diff --git a/.flake8 b/.flake8 index 1f3da2e2bde..2c66c08aedc 100644 --- a/.flake8 +++ b/.flake8 @@ -1,5 +1,5 @@ [flake8] -ignore = +extend-ignore = # H301: one import per line H301, # H306: imports not in alphabetical order (time, os) @@ -15,4 +15,9 @@ ignore = # E221 multiple spaces before operator E221 +extend-exclude = + build, + modules, + .git + max-line-length = 127 diff --git a/.github/workflows/ccache.env b/.github/workflows/ccache.env new file mode 100644 index 00000000000..47455589cb0 --- /dev/null +++ b/.github/workflows/ccache.env @@ -0,0 +1,12 @@ +# common ccache env vars for CI +export CCACHE_SLOPPINESS=file_stat_matches + +git config --global --add safe.directory ${GITHUB_WORKSPACE} + +mkdir -p ~/.ccache +echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf +echo "compression = true" >> ~/.ccache/ccache.conf +echo "compression_level = 6" >> ~/.ccache/ccache.conf +echo "max_size = 400M" >> ~/.ccache/ccache.conf +ccache -s +ccache -z diff --git a/.github/workflows/cygwin_build.yml b/.github/workflows/cygwin_build.yml index d737fa6297d..0b2d83f3da8 100644 --- a/.github/workflows/cygwin_build.yml +++ b/.github/workflows/cygwin_build.yml @@ -13,19 +13,28 @@ jobs: - uses: actions/checkout@v2 with: submodules: 'recursive' - - name: Install cygwin + - uses: cygwin/cygwin-install-action@master + with: + packages: cygwin64 gcc-g++=10.2.0-1 python37 python37-future python37-lxml python37-pip python37-setuptools python37-wheel git procps gettext + - name: Prepare Python environment env: HOME: ${{ runner.workspace }}/ardupilot run: | - choco install cygwin --params "/InstallDir:C:\Cygwin /NoStartMenu /NoAdmin" - choco install cygwin32-gcc-g++ python37 python37-future python37-lxml python37-pip python37-setuptools python37-wheel git libexpat procps gettext --source cygwin - C:\Cygwin\bin\bash --login -c "ln -sf /usr/bin/python3.7 /usr/bin/python && ln -sf /usr/bin/pip3.7 /usr/bin/pip" - C:\Cygwin\bin\bash --login -c "python -m pip install empy pexpect" + bash --login -c "ln -sf /usr/bin/python3.7 /usr/bin/python && ln -sf /usr/bin/pip3.7 /usr/bin/pip" + bash --login -c "python -m pip install empy==3.3.4 pexpect" + bash --login -c "python -m pip install dronecan --upgrade" - name: Build SITL env: HOME: ${{ runner.workspace }}/ardupilot run: | - C:\Cygwin\bin\bash --login -c "Tools/scripts/cygwin_build.sh" + bash --login -c "Tools/scripts/cygwin_build.sh" + + - name: Check build files + id: check_files + uses: andstor/file-existence-action@v1 + with: + files: "artifacts/*" + allow_failure: true - name: Archive build uses: actions/upload-artifact@v2 diff --git a/.github/workflows/macos_build.yml b/.github/workflows/macos_build.yml index 5c5c891fde5..e142a796ace 100644 --- a/.github/workflows/macos_build.yml +++ b/.github/workflows/macos_build.yml @@ -42,13 +42,7 @@ jobs: restore-keys: ${{github.workflow}}-ccache-${{matrix.config}} # restore ccache from either previous build on this branch or on master - name: setup ccache run: | - mkdir -p ~/.ccache - echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf - echo "compression = true" >> ~/.ccache/ccache.conf - echo "compression_level = 6" >> ~/.ccache/ccache.conf - echo "max_size = 400M" >> ~/.ccache/ccache.conf - ccache -s - ccache -z + . .github/workflows/ccache.env - name: test build ${{matrix.config}} env: CI_BUILD_TARGET: ${{matrix.config}} diff --git a/.github/workflows/test_chibios.yml b/.github/workflows/test_chibios.yml index 76db9c91d9a..faf560472ce 100644 --- a/.github/workflows/test_chibios.yml +++ b/.github/workflows/test_chibios.yml @@ -28,7 +28,10 @@ jobs: fmuv3, revo-mini, MatekF405-Wing, - configure-all + CubeOrange-ODID, + configure-all, + build-options-defaults-test, + signing ] toolchain: [ chibios, # GCC-6 @@ -44,6 +47,12 @@ jobs: config: revo-mini - gcc: 6 config: MatekF405-Wing + - gcc: 6 + config: periph-build + - gcc: 6 + config: CubeOrange-ODID + - gcc: 6 + config: signing include: - config: stm32h7 toolchain: chibios-py2 @@ -67,13 +76,7 @@ jobs: restore-keys: ${{github.workflow}}-ccache-${{matrix.config}}-${{ matrix.toolchain }}-${{ matrix.gcc }} # restore ccache from either previous build on this branch or on master - name: setup ccache run: | - mkdir -p ~/.ccache - echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf - echo "compression = true" >> ~/.ccache/ccache.conf - echo "compression_level = 6" >> ~/.ccache/ccache.conf - echo "max_size = 400M" >> ~/.ccache/ccache.conf - ccache -s - ccache -z + . .github/workflows/ccache.env - name: test ${{matrix.config}} ${{ matrix.toolchain }} gcc-${{matrix.gcc}} env: CI_BUILD_TARGET: ${{matrix.config}} diff --git a/.github/workflows/test_coverage.yml b/.github/workflows/test_coverage.yml index e191f6d67e3..b700fa830e3 100644 --- a/.github/workflows/test_coverage.yml +++ b/.github/workflows/test_coverage.yml @@ -46,13 +46,7 @@ jobs: restore-keys: ${{github.workflow}}-ccache-${{ matrix.toolchain }}- # restore ccache from either previous build on this branch or on master - name: setup ccache run: | - mkdir -p ~/.ccache - echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf - echo "compression = true" >> ~/.ccache/ccache.conf - echo "compression_level = 6" >> ~/.ccache/ccache.conf - echo "max_size = 400M" >> ~/.ccache/ccache.conf - ccache -s - ccache -z + . .github/workflows/ccache.env - name: Configure CAN if: ${{ matrix.config == 'sitltest-can'}} run: | @@ -66,6 +60,7 @@ jobs: - name: test ${{matrix.config}} ${{ matrix.toolchain }} env: CI_BUILD_TARGET: ${{matrix.config}} + TERM: xterm shell: 'script -q -e -c "bash {0}"' run: | PATH="/github/home/.local/bin:$PATH" diff --git a/.github/workflows/test_environment.yml b/.github/workflows/test_environment.yml index caeef149b74..ee34b50aafd 100644 --- a/.github/workflows/test_environment.yml +++ b/.github/workflows/test_environment.yml @@ -1,8 +1,8 @@ name: test environment setup on: - workflow_dispatch: schedule: - cron: '0 0 * * 6' # every saturday at midnight + workflow_dispatch: concurrency: @@ -25,8 +25,6 @@ jobs: name: focal - os: ubuntu name: hirsute - - os: ubuntu - name: xenial - os: archlinux name: latest - os: debian @@ -92,6 +90,7 @@ jobs: *"archlinux"*) cp /etc/skel/.bashrc /root cp /etc/skel/.bashrc /github/home + git config --global --add safe.directory /__w/ardupilot/ardupilot Tools/environment_install/install-prereqs-arch.sh -qy ;; esac @@ -104,6 +103,7 @@ jobs: shell: 'script -q -e -c "bash {0}"' run: | source ~/.bashrc + git config --global --add safe.directory /__w/ardupilot/ardupilot ./waf configure ./waf rover @@ -115,5 +115,12 @@ jobs: shell: 'script -q -e -c "bash {0}"' run: | source ~/.bashrc + case ${{matrix.os}} in + *"archlinux"*) + export PATH=/opt/gcc-arm-none-eabi-10-2020-q4-major/bin:$PATH + export PATH=/__w/ardupilot/ardupilot/ardupilot/Tools/autotest:$PATH + ;; + esac + git config --global --add safe.directory /__w/ardupilot/ardupilot ./waf configure --board CubeOrange ./waf plane diff --git a/.github/workflows/test_linux_sbc.yml b/.github/workflows/test_linux_sbc.yml index 7c1ef116888..e36a28fc3db 100644 --- a/.github/workflows/test_linux_sbc.yml +++ b/.github/workflows/test_linux_sbc.yml @@ -60,13 +60,7 @@ jobs: restore-keys: ${{github.workflow}}-ccache- # restore ccache from either previous build on this branch or on master - name: setup ccache run: | - mkdir -p ~/.ccache - echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf - echo "compression = true" >> ~/.ccache/ccache.conf - echo "compression_level = 6" >> ~/.ccache/ccache.conf - echo "max_size = 400M" >> ~/.ccache/ccache.conf - ccache -s - ccache -z + . .github/workflows/ccache.env - name: test ${{matrix.config}} ${{ matrix.toolchain }} env: CI_BUILD_TARGET: ${{matrix.config}} diff --git a/.github/workflows/test_replay.yml b/.github/workflows/test_replay.yml index 69ca68c5875..7ecae879f49 100644 --- a/.github/workflows/test_replay.yml +++ b/.github/workflows/test_replay.yml @@ -41,13 +41,7 @@ jobs: restore-keys: ${{github.workflow}}-ccache-${{ matrix.toolchain }}- # restore ccache from either previous build on this branch or on master - name: setup ccache run: | - mkdir -p ~/.ccache - echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf - echo "compression = true" >> ~/.ccache/ccache.conf - echo "compression_level = 6" >> ~/.ccache/ccache.conf - echo "max_size = 400M" >> ~/.ccache/ccache.conf - ccache -s - ccache -z + . .github/workflows/ccache.env - name: test ${{matrix.config}} ${{ matrix.toolchain }} env: CI_BUILD_TARGET: ${{matrix.config}} diff --git a/.github/workflows/test_sitl_copter.yml b/.github/workflows/test_sitl_copter.yml index bb99604bba6..28c72a64f00 100644 --- a/.github/workflows/test_sitl_copter.yml +++ b/.github/workflows/test_sitl_copter.yml @@ -38,13 +38,7 @@ jobs: restore-keys: ${{github.workflow}}-ccache-${{ matrix.toolchain }}- # restore ccache from either previous build on this branch or on master - name: setup ccache run: | - mkdir -p ~/.ccache - echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf - echo "compression = true" >> ~/.ccache/ccache.conf - echo "compression_level = 6" >> ~/.ccache/ccache.conf - echo "max_size = 400M" >> ~/.ccache/ccache.conf - ccache -s - ccache -z + . .github/workflows/ccache.env - name: build copter ${{ matrix.toolchain }} shell: bash run: | @@ -96,13 +90,7 @@ jobs: restore-keys: ${{github.workflow}}-ccache-base- # restore ccache from either previous build on this branch or on master - name: setup ccache run: | - mkdir -p ~/.ccache - echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf - echo "compression = true" >> ~/.ccache/ccache.conf - echo "compression_level = 6" >> ~/.ccache/ccache.conf - echo "max_size = 400M" >> ~/.ccache/ccache.conf - ccache -s - ccache -z + . .github/workflows/ccache.env - name: test ${{matrix.config}} env: CI_BUILD_TARGET: ${{matrix.config}} @@ -133,7 +121,6 @@ jobs: retention-days: 7 build-gcc-heli: - needs: build # don't try to launch the tests matrix if it doesn't build first, profit from caching for fast build runs-on: ubuntu-20.04 container: image: ardupilot/ardupilot-dev-base:latest @@ -157,13 +144,7 @@ jobs: restore-keys: ${{github.workflow}}-ccache-base- # restore ccache from either previous build on this branch or on master - name: setup ccache run: | - mkdir -p ~/.ccache - echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf - echo "compression = true" >> ~/.ccache/ccache.conf - echo "compression_level = 6" >> ~/.ccache/ccache.conf - echo "max_size = 400M" >> ~/.ccache/ccache.conf - ccache -s - ccache -z + . .github/workflows/ccache.env - name: build heli shell: bash run: | @@ -203,13 +184,7 @@ jobs: restore-keys: ${{github.workflow}}-ccache-base- # restore ccache from either previous build on this branch or on master - name: setup ccache run: | - mkdir -p ~/.ccache - echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf - echo "compression = true" >> ~/.ccache/ccache.conf - echo "compression_level = 6" >> ~/.ccache/ccache.conf - echo "max_size = 400M" >> ~/.ccache/ccache.conf - ccache -s - ccache -z + . .github/workflows/ccache.env - name: test ${{matrix.config}} env: CI_BUILD_TARGET: ${{matrix.config}} diff --git a/.github/workflows/test_sitl_periph.yml b/.github/workflows/test_sitl_periph.yml index 1a81791b70c..8a517adf873 100644 --- a/.github/workflows/test_sitl_periph.yml +++ b/.github/workflows/test_sitl_periph.yml @@ -31,13 +31,7 @@ jobs: restore-keys: ${{github.workflow}}-ccache- # restore ccache from either previous build on this branch or on master - name: setup ccache run: | - mkdir -p ~/.ccache - echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf - echo "compression = true" >> ~/.ccache/ccache.conf - echo "compression_level = 6" >> ~/.ccache/ccache.conf - echo "max_size = 400M" >> ~/.ccache/ccache.conf - ccache -s - ccache -z + . .github/workflows/ccache.env - name: install 32-bit libraries run: | dpkg --add-architecture i386 @@ -90,13 +84,7 @@ jobs: restore-keys: ${{github.workflow}}-ccache- # restore ccache from either previous build on this branch or on master - name: setup ccache run: | - mkdir -p ~/.ccache - echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf - echo "compression = true" >> ~/.ccache/ccache.conf - echo "compression_level = 6" >> ~/.ccache/ccache.conf - echo "max_size = 400M" >> ~/.ccache/ccache.conf - ccache -s - ccache -z + . .github/workflows/ccache.env - name: install 32-bit libraries run: | sudo dpkg --add-architecture i386 diff --git a/.github/workflows/test_sitl_plane.yml b/.github/workflows/test_sitl_plane.yml index 9d4f7df05f0..3640bc4e902 100644 --- a/.github/workflows/test_sitl_plane.yml +++ b/.github/workflows/test_sitl_plane.yml @@ -38,13 +38,7 @@ jobs: restore-keys: ${{github.workflow}}-ccache-${{ matrix.toolchain }}- # restore ccache from either previous build on this branch or on master - name: setup ccache run: | - mkdir -p ~/.ccache - echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf - echo "compression = true" >> ~/.ccache/ccache.conf - echo "compression_level = 6" >> ~/.ccache/ccache.conf - echo "max_size = 400M" >> ~/.ccache/ccache.conf - ccache -s - ccache -z + . .github/workflows/ccache.env - name: build plane ${{ matrix.toolchain }} shell: bash run: | @@ -91,13 +85,7 @@ jobs: restore-keys: ${{github.workflow}}-ccache-base- # restore ccache from either previous build on this branch or on master - name: setup ccache run: | - mkdir -p ~/.ccache - echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf - echo "compression = true" >> ~/.ccache/ccache.conf - echo "compression_level = 6" >> ~/.ccache/ccache.conf - echo "max_size = 400M" >> ~/.ccache/ccache.conf - ccache -s - ccache -z + . .github/workflows/ccache.env - name: test ${{matrix.config}} env: CI_BUILD_TARGET: ${{matrix.config}} diff --git a/.github/workflows/test_sitl_rover.yml b/.github/workflows/test_sitl_rover.yml index 1b0ee631534..f14ffcf919a 100644 --- a/.github/workflows/test_sitl_rover.yml +++ b/.github/workflows/test_sitl_rover.yml @@ -38,13 +38,7 @@ jobs: restore-keys: ${{github.workflow}}-ccache-${{ matrix.toolchain }}- # restore ccache from either previous build on this branch or on master - name: setup ccache run: | - mkdir -p ~/.ccache - echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf - echo "compression = true" >> ~/.ccache/ccache.conf - echo "compression_level = 6" >> ~/.ccache/ccache.conf - echo "max_size = 400M" >> ~/.ccache/ccache.conf - ccache -s - ccache -z + . .github/workflows/ccache.env - name: build rover ${{ matrix.toolchain }} shell: bash run: | @@ -69,6 +63,7 @@ jobs: matrix: config: [ sitltest-rover, + sitltest-sailboat, sitltest-balancebot ] @@ -91,13 +86,7 @@ jobs: restore-keys: ${{github.workflow}}-ccache-base- # restore ccache from either previous build on this branch or on master - name: setup ccache run: | - mkdir -p ~/.ccache - echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf - echo "compression = true" >> ~/.ccache/ccache.conf - echo "compression_level = 6" >> ~/.ccache/ccache.conf - echo "max_size = 400M" >> ~/.ccache/ccache.conf - ccache -s - ccache -z + . .github/workflows/ccache.env - name: test ${{matrix.config}} env: CI_BUILD_TARGET: ${{matrix.config}} diff --git a/.github/workflows/test_sitl_sub.yml b/.github/workflows/test_sitl_sub.yml index 8d43b72d188..39c25c28b59 100644 --- a/.github/workflows/test_sitl_sub.yml +++ b/.github/workflows/test_sitl_sub.yml @@ -38,13 +38,7 @@ jobs: restore-keys: ${{github.workflow}}-ccache-${{ matrix.toolchain }}- # restore ccache from either previous build on this branch or on master - name: setup ccache run: | - mkdir -p ~/.ccache - echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf - echo "compression = true" >> ~/.ccache/ccache.conf - echo "compression_level = 6" >> ~/.ccache/ccache.conf - echo "max_size = 400M" >> ~/.ccache/ccache.conf - ccache -s - ccache -z + . .github/workflows/ccache.env - name: build sub ${{ matrix.toolchain }} shell: bash run: | @@ -90,13 +84,7 @@ jobs: restore-keys: ${{github.workflow}}-ccache-base- # restore ccache from either previous build on this branch or on master - name: setup ccache run: | - mkdir -p ~/.ccache - echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf - echo "compression = true" >> ~/.ccache/ccache.conf - echo "compression_level = 6" >> ~/.ccache/ccache.conf - echo "max_size = 400M" >> ~/.ccache/ccache.conf - ccache -s - ccache -z + . .github/workflows/ccache.env - name: test ${{matrix.config}} env: CI_BUILD_TARGET: ${{matrix.config}} diff --git a/.github/workflows/test_sitl_tracker.yml b/.github/workflows/test_sitl_tracker.yml index db9fc0586ac..8c6abec961c 100644 --- a/.github/workflows/test_sitl_tracker.yml +++ b/.github/workflows/test_sitl_tracker.yml @@ -38,13 +38,7 @@ jobs: restore-keys: ${{github.workflow}}-ccache-${{ matrix.toolchain }}- # restore ccache from either previous build on this branch or on master - name: setup ccache run: | - mkdir -p ~/.ccache - echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf - echo "compression = true" >> ~/.ccache/ccache.conf - echo "compression_level = 6" >> ~/.ccache/ccache.conf - echo "max_size = 400M" >> ~/.ccache/ccache.conf - ccache -s - ccache -z + . .github/workflows/ccache.env - name: build tracker ${{ matrix.toolchain }} shell: bash run: | @@ -90,13 +84,7 @@ jobs: restore-keys: ${{github.workflow}}-ccache-base- # restore ccache from either previous build on this branch or on master - name: setup ccache run: | - mkdir -p ~/.ccache - echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf - echo "compression = true" >> ~/.ccache/ccache.conf - echo "compression_level = 6" >> ~/.ccache/ccache.conf - echo "max_size = 400M" >> ~/.ccache/ccache.conf - ccache -s - ccache -z + . .github/workflows/ccache.env - name: test ${{matrix.config}} env: CI_BUILD_TARGET: ${{matrix.config}} diff --git a/.github/workflows/test_size.yml b/.github/workflows/test_size.yml index 09db01cfd1c..ed38175a1f0 100644 --- a/.github/workflows/test_size.yml +++ b/.github/workflows/test_size.yml @@ -1,6 +1,6 @@ name: test size -on: [push, pull_request, workflow_dispatch] +on: [pull_request] # paths: # - "*" # - "!README.md" <-- don't rebuild on doc change @@ -28,8 +28,8 @@ jobs: steps: - uses: actions/checkout@v2 with: - ref: 'master' - path: 'master' + ref: ${{ github.event.pull_request.base.ref }} + path: base_branch submodules: 'recursive' # Put ccache into github cache for faster build - name: Prepare ccache timestamp @@ -42,24 +42,14 @@ jobs: with: path: ~/.ccache key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}} - restore-keys: ${{github.workflow}}-ccache-${{ matrix.toolchain }}- # restore ccache from either previous build on this branch or on master - - name: setup ccache - run: | - mkdir -p ~/.ccache - echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf - echo "compression = true" >> ~/.ccache/ccache.conf - echo "compression_level = 6" >> ~/.ccache/ccache.conf - echo "max_size = 400M" >> ~/.ccache/ccache.conf - ccache -s - ccache -z - - - name: Build master ${{matrix.config}} ${{ matrix.toolchain }} + restore-keys: ${{github.workflow}}-ccache-${{ matrix.toolchain }}- # restore ccache from either previous build on this branch or on base branch + - name: Build ${{ github.event.pull_request.base.ref }} ${{matrix.config}} ${{ matrix.toolchain }} env: CI_BUILD_TARGET: ${{matrix.config}} shell: bash run: | PATH="/github/home/.local/bin:$PATH" - cd master + cd base_branch ./waf configure --board ${{matrix.config}} if [ "${{matrix.config}}" = "Hitec-Airspeed" ] || [ "${{matrix.config}}" = "f103-GPS" ]; then @@ -67,25 +57,25 @@ jobs: else ./waf fi - mkdir -p $GITHUB_WORKSPACE/master_bin - cp -r build/${{matrix.config}}/bin/* $GITHUB_WORKSPACE/master_bin/ + mkdir -p $GITHUB_WORKSPACE/base_branch_bin + cp -r build/${{matrix.config}}/bin/* $GITHUB_WORKSPACE/base_branch_bin/ # build a set of binaries without symbols so we can check if # the binaries have changed. - echo [`date`] Building master with no versions + echo [`date`] Building ${{ github.event.pull_request.base.ref }} with no versions - NO_VERSIONS_DIR="$GITHUB_WORKSPACE/master_bin_no_versions" + NO_VERSIONS_DIR="$GITHUB_WORKSPACE/base_branch_bin_no_versions" mkdir "$NO_VERSIONS_DIR" if [ "${{matrix.config}}" = "Hitec-Airspeed" ] || [ "${{matrix.config}}" = "f103-GPS" ]; then - CHIBIOS_GIT_VERSION="12345678" GIT_VERSION="abcdef" ./waf AP_Periph + CHIBIOS_GIT_VERSION="12345678" GIT_VERSION="abcdef" GIT_VERSION_INT="15" ./waf AP_Periph else - CHIBIOS_GIT_VERSION="12345678" GIT_VERSION="abcdef" ./waf + CHIBIOS_GIT_VERSION="12345678" GIT_VERSION="abcdef" GIT_VERSION_INT="15" ./waf fi cp -r build/${{matrix.config}}/bin/* "$NO_VERSIONS_DIR" - echo [`date`] Built master with no versions + echo [`date`] Built ${{ github.event.pull_request.base.ref }} with no versions - uses: actions/checkout@v2 with: @@ -102,8 +92,8 @@ jobs: git config user.email "ardupilot-ci@ardupilot.org" git config user.name "ArduPilot CI" git remote add ardupilot https://github.com/ArduPilot/ardupilot.git - git fetch --no-tags --prune --progress ardupilot master - git rebase ardupilot/master + git fetch --no-tags --prune --progress ardupilot ${{ github.event.pull_request.base.ref }} + git rebase ardupilot/${{ github.event.pull_request.base.ref }} git submodule update --init --recursive --depth=1 ./waf configure --board ${{matrix.config}} if [ "${{matrix.config}}" = "Hitec-Airspeed" ] || @@ -124,9 +114,9 @@ jobs: if [ "${{matrix.config}}" = "Hitec-Airspeed" ] || [ "${{matrix.config}}" = "f103-GPS" ]; then - CHIBIOS_GIT_VERSION="12345678" GIT_VERSION="abcdef" ./waf AP_Periph + CHIBIOS_GIT_VERSION="12345678" GIT_VERSION="abcdef" GIT_VERSION_INT="15" ./waf AP_Periph else - CHIBIOS_GIT_VERSION="12345678" GIT_VERSION="abcdef" ./waf + CHIBIOS_GIT_VERSION="12345678" GIT_VERSION="abcdef" GIT_VERSION_INT="15" ./waf fi cp -r build/${{matrix.config}}/bin/* "$NO_VERSIONS_DIR" @@ -146,29 +136,29 @@ jobs: ls -l "$PLANE_BINARY" fi - - name: Full size compare with Master + - name: Full size compare with base branch shell: bash run: | cd pr/ python3 -m pip install -U tabulate - Tools/scripts/pretty_diff_size.py -m $GITHUB_WORKSPACE/master_bin -s $GITHUB_WORKSPACE/pr_bin + Tools/scripts/pretty_diff_size.py -m $GITHUB_WORKSPACE/base_branch_bin -s $GITHUB_WORKSPACE/pr_bin - - name: Checksum compare with Master + - name: Checksum compare with ${{ github.event.pull_request.base.ref }} shell: bash run: | - diff -r $GITHUB_WORKSPACE/master_bin_no_versions $GITHUB_WORKSPACE/pr_bin_no_versions --exclude=*.elf --exclude=*.apj || true + diff -r $GITHUB_WORKSPACE/base_branch_bin_no_versions $GITHUB_WORKSPACE/pr_bin_no_versions --exclude=*.elf --exclude=*.apj || true - - name: elf_diff compare with Master + - name: elf_diff compare with ${{ github.event.pull_request.base.ref }} shell: bash run: | python3 -m pip install -U weasyprint elf_diff anytree mkdir elf_diff if [ "${{matrix.config}}" = "Hitec-Airspeed" ] || [ "${{matrix.config}}" = "f103-GPS" ]; then - python3 -m elf_diff --bin_prefix=arm-none-eabi- --html_dir=elf_diff/AP_Periph $GITHUB_WORKSPACE/master_bin/AP_Periph $GITHUB_WORKSPACE/pr_bin/AP_Periph + python3 -m elf_diff --bin_prefix=arm-none-eabi- --html_dir=elf_diff/AP_Periph $GITHUB_WORKSPACE/base_branch_bin/AP_Periph $GITHUB_WORKSPACE/pr_bin/AP_Periph else - python3 -m elf_diff --bin_prefix=arm-none-eabi- --html_dir=elf_diff/plane $GITHUB_WORKSPACE/master_bin/arduplane $GITHUB_WORKSPACE/pr_bin/arduplane - python3 -m elf_diff --bin_prefix=arm-none-eabi- --html_dir=elf_diff/copter $GITHUB_WORKSPACE/master_bin/arducopter $GITHUB_WORKSPACE/pr_bin/arducopter + python3 -m elf_diff --bin_prefix=arm-none-eabi- --html_dir=elf_diff/plane $GITHUB_WORKSPACE/base_branch_bin/arduplane $GITHUB_WORKSPACE/pr_bin/arduplane + python3 -m elf_diff --bin_prefix=arm-none-eabi- --html_dir=elf_diff/copter $GITHUB_WORKSPACE/base_branch_bin/arducopter $GITHUB_WORKSPACE/pr_bin/arducopter fi zip -r elf_diff.zip elf_diff diff --git a/.github/workflows/test_unit_tests.yml b/.github/workflows/test_unit_tests.yml index db361317e6a..eba8083a9d3 100644 --- a/.github/workflows/test_unit_tests.yml +++ b/.github/workflows/test_unit_tests.yml @@ -23,7 +23,7 @@ jobs: ] config: [ unit-tests, - python-cleanliness, + # python-cleanliness, # DISABLED for 4.3.x sitl # examples, ] @@ -46,13 +46,7 @@ jobs: restore-keys: ${{github.workflow}}-ccache-${{ matrix.toolchain }}- # restore ccache from either previous build on this branch or on master - name: setup ccache run: | - mkdir -p ~/.ccache - echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf - echo "compression = true" >> ~/.ccache/ccache.conf - echo "compression_level = 6" >> ~/.ccache/ccache.conf - echo "max_size = 400M" >> ~/.ccache/ccache.conf - ccache -s - ccache -z + . .github/workflows/ccache.env - name: test ${{matrix.config}} ${{ matrix.toolchain }} env: CI_BUILD_TARGET: ${{matrix.config}} diff --git a/.gitignore b/.gitignore index c618cfe3705..58ef1b120ed 100644 --- a/.gitignore +++ b/.gitignore @@ -36,6 +36,7 @@ *.vbrain *.vrx *.zip +!Tools/autotest/tilecache/**/*.zip *~ .*.swo .*.swp @@ -81,7 +82,6 @@ Thumbs.db autotest.lck build cmake_install.cmake -config.mk cscope.in.out cscope.out cscope.po.out @@ -102,7 +102,6 @@ test.ArduCopter/* GPATH GRTAGS GTAGS -config.mk *.apj .gdbinit /.vscode diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml new file mode 100644 index 00000000000..9c8f9d021c2 --- /dev/null +++ b/.pre-commit-config.yaml @@ -0,0 +1,53 @@ +# See https://pre-commit.com for more information, specially https://pre-commit.com/#pre-commit-run for manual trigger +# Some example useful invocations: +# pre-commit run: this is what pre-commit runs by default when committing. This will run all hooks against currently staged files. +# pre-commit run --all-files: run all the hooks against all the files. This is a useful invocation if you are using pre-commit in CI. +# pre-commit run check-executables-have-shebangs: run the check-executables-have-shebangs hook against all staged files. + +# Files or directory we want to excude from checking +exclude: | + (?x)( + ^modules/ | + ^build/ | + ^cmake-build-debug/ | + \.m | + ^libraries/AP_HAL_ChibiOS/hwdef/scripts/ + ) + +repos: + - repo: https://github.com/pre-commit/pre-commit-hooks + rev: v4.2.0 + hooks: + #- id: trailing-whitespace + #- id: end-of-file-fixer + - id: mixed-line-ending + name: Check line ending character (LF) + args: ["--fix=lf"] + types_or: [python, c, c++, shell] + - id: check-added-large-files + - id: check-executables-have-shebangs + - id: check-shebang-scripts-are-executable + exclude: | + (?x)^( + .*\/wscript | + wscript + )$ + - id: check-merge-conflict + - id: check-xml + - id: check-yaml + +# Use to sort python imports by name and put system import first. + - repo: https://github.com/pycqa/isort + rev: 5.10.1 + hooks: + - id: isort + args: [--check-only] + name: isort (python) + +# Use to check python typing to show errors. + - repo: https://github.com/pre-commit/mirrors-mypy + rev: 'v0.950' + hooks: + - id: mypy + args: [--no-strict-optional, --ignore-missing-imports] + additional_dependencies: [types-PyYAML, types-requests] diff --git a/AntennaTracker/GCS_Mavlink.cpp b/AntennaTracker/GCS_Mavlink.cpp index 62ca06772fe..3a509d9d9f8 100644 --- a/AntennaTracker/GCS_Mavlink.cpp +++ b/AntennaTracker/GCS_Mavlink.cpp @@ -128,8 +128,7 @@ void GCS_MAVLINK_Tracker::send_pid_tuning() // Pitch PID if (g.gcs_pid_mask & 1) { - const AP_Logger::PID_Info *pid_info; - pid_info = &g.pidPitch2Srv.get_pid_info(); + const AP_PIDInfo *pid_info = &g.pidPitch2Srv.get_pid_info(); mavlink_msg_pid_tuning_send(chan, PID_TUNING_PITCH, pid_info->target, pid_info->actual, @@ -146,8 +145,7 @@ void GCS_MAVLINK_Tracker::send_pid_tuning() // Yaw PID if (g.gcs_pid_mask & 2) { - const AP_Logger::PID_Info *pid_info; - pid_info = &g.pidYaw2Srv.get_pid_info(); + const AP_PIDInfo *pid_info = &g.pidYaw2Srv.get_pid_info(); mavlink_msg_pid_tuning_send(chan, PID_TUNING_YAW, pid_info->target, pid_info->actual, @@ -179,6 +177,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK_Parameters, streamRates[0], 1), @@ -188,6 +187,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK_Parameters, streamRates[1], 1), @@ -197,6 +197,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK_Parameters, streamRates[2], 1), @@ -206,6 +207,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("RAW_CTRL", 3, GCS_MAVLINK_Parameters, streamRates[3], 1), @@ -215,6 +217,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("POSITION", 4, GCS_MAVLINK_Parameters, streamRates[4], 1), @@ -224,6 +227,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK_Parameters, streamRates[5], 1), @@ -233,6 +237,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK_Parameters, streamRates[6], 1), @@ -242,6 +247,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK_Parameters, streamRates[7], 1), @@ -251,6 +257,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK_Parameters, streamRates[8], 10), AP_GROUPEND @@ -379,7 +386,7 @@ void GCS_MAVLINK_Tracker::mavlink_check_target(const mavlink_message_t &msg) // set our sysid to the target, this ensures we lock onto a single vehicle if (tracker.g.sysid_target == 0) { - tracker.g.sysid_target = msg.sysid; + tracker.g.sysid_target.set(msg.sysid); } // send data stream request to target on all channels diff --git a/AntennaTracker/GCS_Tracker.cpp b/AntennaTracker/GCS_Tracker.cpp index b4b16de62a8..c89d988cb34 100644 --- a/AntennaTracker/GCS_Tracker.cpp +++ b/AntennaTracker/GCS_Tracker.cpp @@ -58,8 +58,10 @@ void GCS_Tracker::update_vehicle_sensor_status_flags() MAV_SYS_STATUS_SENSOR_YAW_POSITION; } +#if AP_LTM_TELEM_ENABLED // avoid building/linking LTM: void AP_LTM_Telem::init() {}; +#endif #if AP_DEVO_TELEM_ENABLED // avoid building/linking Devo: void AP_DEVO_Telem::init() {}; diff --git a/AntennaTracker/Parameters.cpp b/AntennaTracker/Parameters.cpp index 42be7948916..3ac0378fd0d 100644 --- a/AntennaTracker/Parameters.cpp +++ b/AntennaTracker/Parameters.cpp @@ -281,7 +281,7 @@ const AP_Param::Info Tracker::var_info[] = { // @Path: ../libraries/AP_AHRS/AP_AHRS.cpp GOBJECT(ahrs, "AHRS_", AP_AHRS), -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#if AP_SIM_ENABLED // @Group: SIM_ // @Path: ../libraries/SITL/SITL.cpp GOBJECT(sitl, "SIM_", SITL::SIM), @@ -549,6 +549,7 @@ void Tracker::load_parameters(void) g.format_version.set_and_save(Parameters::k_format_version); hal.console->printf("done.\n"); } + g.format_version.set_default(Parameters::k_format_version); uint32_t before = AP_HAL::micros(); // Load all auto-loaded EEPROM variables diff --git a/AntennaTracker/ReleaseNotes.txt b/AntennaTracker/ReleaseNotes.txt index 15837ec41b3..27269085db3 100644 --- a/AntennaTracker/ReleaseNotes.txt +++ b/AntennaTracker/ReleaseNotes.txt @@ -1,5 +1,18 @@ Antenna Tracker Release Notes: ------------------------------------------------------------------ +AntennaTracker 4.2.0 beta1 25-May-2022 +Changes from 1.1.0 +1) Many new supported boards +2) New sensor support +3) PID improvements +4) Filtering improvements +5) Integrate AP_Stats library +6) Scripting support +7) Logging improvements +8) Improvements to GCS communications +9) Option to scan before vehicle found +10) Innumerable system-level improvements; see Copter and Plane 4.2 release notes +------------------------------------------------------------------ AntennaTracker 1.1.0 3-Aug-2019 Changes from 1.1.0-rc1 1) Instantiate battery monitor instance diff --git a/AntennaTracker/Tracker.cpp b/AntennaTracker/Tracker.cpp index 2cc08b1a9e6..e7e1a384587 100644 --- a/AntennaTracker/Tracker.cpp +++ b/AntennaTracker/Tracker.cpp @@ -66,7 +66,6 @@ const AP_Scheduler::Task Tracker::scheduler_tasks[] = { SCHED_TASK_CLASS(AP_InertialSensor, &tracker.ins, periodic, 50, 50, 70), SCHED_TASK_CLASS(AP_Notify, &tracker.notify, update, 50, 100, 75), SCHED_TASK(one_second_loop, 1, 3900, 80), - SCHED_TASK_CLASS(Compass, &tracker.compass, cal_update, 50, 100, 85), SCHED_TASK(stats_update, 1, 200, 90), }; @@ -81,9 +80,6 @@ void Tracker::get_scheduler_tasks(const AP_Scheduler::Task *&tasks, void Tracker::one_second_loop() { - // make it possible to change orientation at runtime - ahrs.update_orientation(); - // sync MAVLink system ID mavlink_system.sysid = g.sysid_this_mav; diff --git a/AntennaTracker/Tracker.h b/AntennaTracker/Tracker.h index 5371eff85d9..9752f04842f 100644 --- a/AntennaTracker/Tracker.h +++ b/AntennaTracker/Tracker.h @@ -27,7 +27,6 @@ #include #include -#include #include #include // ArduPilot Mega Vector/Matrix math Library #include // ArduPilot Mega DCM Library @@ -38,6 +37,7 @@ #include #include +#include #include #include #include // statistics library diff --git a/AntennaTracker/sensors.cpp b/AntennaTracker/sensors.cpp index 1a63346aa05..55946944d94 100644 --- a/AntennaTracker/sensors.cpp +++ b/AntennaTracker/sensors.cpp @@ -51,9 +51,7 @@ void Tracker::update_GPS(void) // Now have an initial GPS position // use it as the HOME position in future startups current_loc = gps.location(); - if (!set_home(current_loc)) { - // silently ignored - } + IGNORE_RETURN(set_home(current_loc)); ground_start_count = 0; } } diff --git a/AntennaTracker/servos.cpp b/AntennaTracker/servos.cpp index 014dcaee7c7..23e1e0cab5b 100644 --- a/AntennaTracker/servos.cpp +++ b/AntennaTracker/servos.cpp @@ -74,7 +74,7 @@ void Tracker::update_pitch_position_servo() // PITCH2SRV_IMAX 4000.000000 // calculate new servo position - float new_servo_out = SRV_Channels::get_output_scaled(SRV_Channel::k_tracker_pitch) + g.pidPitch2Srv.update_error(nav_status.angle_error_pitch); + float new_servo_out = SRV_Channels::get_output_scaled(SRV_Channel::k_tracker_pitch) + g.pidPitch2Srv.update_error(nav_status.angle_error_pitch, G_Dt); // position limit pitch servo if (new_servo_out <= pitch_min_cd) { @@ -125,7 +125,7 @@ void Tracker::update_pitch_onoff_servo(float pitch) const */ void Tracker::update_pitch_cr_servo(float pitch) { - const float pitch_out = constrain_float(g.pidPitch2Srv.update_error(nav_status.angle_error_pitch), -(-g.pitch_min+g.pitch_max) * 100/2, (-g.pitch_min+g.pitch_max) * 100/2); + const float pitch_out = constrain_float(g.pidPitch2Srv.update_error(nav_status.angle_error_pitch, G_Dt), -(-g.pitch_min+g.pitch_max) * 100/2, (-g.pitch_min+g.pitch_max) * 100/2); SRV_Channels::set_output_scaled(SRV_Channel::k_tracker_pitch, pitch_out); } @@ -187,7 +187,7 @@ void Tracker::update_yaw_position_servo() right direction */ - float servo_change = g.pidYaw2Srv.update_error(nav_status.angle_error_yaw); + float servo_change = g.pidYaw2Srv.update_error(nav_status.angle_error_yaw, G_Dt); servo_change = constrain_float(servo_change, -18000, 18000); float new_servo_out = constrain_float(SRV_Channels::get_output_scaled(SRV_Channel::k_tracker_yaw) + servo_change, -18000, 18000); @@ -238,6 +238,6 @@ void Tracker::update_yaw_onoff_servo(float yaw) const */ void Tracker::update_yaw_cr_servo(float yaw) { - const float yaw_out = constrain_float(-g.pidYaw2Srv.update_error(nav_status.angle_error_yaw), -g.yaw_range * 100/2, g.yaw_range * 100/2); + const float yaw_out = constrain_float(-g.pidYaw2Srv.update_error(nav_status.angle_error_yaw, G_Dt), -g.yaw_range * 100/2, g.yaw_range * 100/2); SRV_Channels::set_output_scaled(SRV_Channel::k_tracker_yaw, yaw_out); } diff --git a/AntennaTracker/system.cpp b/AntennaTracker/system.cpp index e888eef494f..b1b4223cc1a 100644 --- a/AntennaTracker/system.cpp +++ b/AntennaTracker/system.cpp @@ -27,6 +27,10 @@ void Tracker::init_ardupilot() // setup telem slots with serial ports gcs().setup_uarts(); + // update_send so that if the first packet we receive happens to + // be an arm message we don't trigger an internal error when we + // try to initialise stream rates in the main loop. + gcs().update_send(); #if LOGGING_ENABLED == ENABLED log_init(); diff --git a/AntennaTracker/version.h b/AntennaTracker/version.h index 7ca867f5772..1adb76acba8 100644 --- a/AntennaTracker/version.h +++ b/AntennaTracker/version.h @@ -6,14 +6,14 @@ #include "ap_version.h" -#define THISFIRMWARE "AntennaTracker V1.2.0-dev" +#define THISFIRMWARE "AntennaTracker V4.3.0-dev" // the following line is parsed by the autotest scripts -#define FIRMWARE_VERSION 1,2,0,FIRMWARE_VERSION_TYPE_DEV +#define FIRMWARE_VERSION 4,3,0,FIRMWARE_VERSION_TYPE_DEV -#define FW_MAJOR 1 -#define FW_MINOR 2 +#define FW_MAJOR 4 +#define FW_MINOR 3 #define FW_PATCH 0 #define FW_TYPE FIRMWARE_VERSION_TYPE_DEV -#include \ No newline at end of file +#include diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h index f30f0d22eac..326210e22bb 100644 --- a/ArduCopter/APM_Config.h +++ b/ArduCopter/APM_Config.h @@ -1,13 +1,10 @@ // User specific config file. Any items listed in config.h can be overridden here. -// If you used to define your CONFIG_APM_HARDWARE setting here, it is no longer -// valid! You should switch to using a HAL_BOARD flag in your local config.mk. - // uncomment the lines below to disable features (flash sizes listed are for APM2 boards and will underestimate savings on Pixhawk and other boards) //#define LOGGING_ENABLED DISABLED // disable logging to save 11K of flash space //#define MOUNT DISABLED // disable the camera gimbal to save 8K of flash space //#define AUTOTUNE_ENABLED DISABLED // disable the auto tune functionality to save 7k of flash -//#define AC_FENCE DISABLED // disable fence to save 2k of flash +//#define AP_FENCE_ENABLED DISABLED // disable fence to save 2k of flash //#define CAMERA DISABLED // disable camera trigger to save 1k of flash //#define RANGEFINDER_ENABLED DISABLED // disable rangefinder to save 1k of flash //#define AC_RALLY DISABLED // disable rally points library (must also disable terrain which relies on rally) @@ -15,7 +12,6 @@ //#define AC_OAPATHPLANNER_ENABLED DISABLED // disable path planning around obstacles //#define PARACHUTE DISABLED // disable parachute release to save 1k of flash //#define NAV_GUIDED DISABLED // disable external navigation computer ability to control vehicle through MAV_CMD_NAV_GUIDED mission commands -//#define FRSKY_TELEM_ENABLED DISABLED // disable FRSky telemetry //#define PRECISION_LANDING DISABLED // disable precision landing using companion computer or IRLock sensor //#define BEACON_ENABLED DISABLED // disable beacon support //#define SPRAYER_ENABLED DISABLED // disable the crop sprayer feature (two ESC controlled pumps the speed of which depends upon the vehicle's horizontal velocity) diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index 16ed88452af..d31b0175119 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -1,24 +1,5 @@ #include "Copter.h" -#if HAL_MAX_CAN_PROTOCOL_DRIVERS - #include -#endif - -// performs pre-arm checks. expects to be called at 1hz. -void AP_Arming_Copter::update(void) -{ - // perform pre-arm checks & display failures every 30 seconds - static uint8_t pre_arm_display_counter = PREARM_DISPLAY_PERIOD/2; - pre_arm_display_counter++; - bool display_fail = false; - if (pre_arm_display_counter >= PREARM_DISPLAY_PERIOD) { - display_fail = true; - pre_arm_display_counter = 0; - } - - pre_arm_checks(display_fail); -} - bool AP_Arming_Copter::pre_arm_checks(bool display_failure) { const bool passed = run_pre_arm_checks(display_failure); @@ -35,20 +16,38 @@ bool AP_Arming_Copter::run_pre_arm_checks(bool display_failure) return true; } - // check if motor interlock and Emergency Stop aux switches are used + // check if motor interlock and either Emergency Stop aux switches are used // at the same time. This cannot be allowed. if (rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_INTERLOCK) && - rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_ESTOP)){ + (rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_ESTOP) || + rc().find_channel_for_option(RC_Channel::AUX_FUNC::ARM_EMERGENCY_STOP))){ check_failed(display_failure, "Interlock/E-Stop Conflict"); return false; } // check if motor interlock aux switch is in use // if it is, switch needs to be in disabled position to arm - // otherwise exit immediately. This check to be repeated, - // as state can change at any time. + // otherwise exit immediately. if (copter.ap.using_interlock && copter.ap.motor_interlock_switch) { check_failed(display_failure, "Motor Interlock Enabled"); + return false; + } + + // if we are using motor Estop switch, it must not be in Estop position + if (SRV_Channels::get_emergency_stop()){ + check_failed(display_failure, "Motor Emergency Stopped"); + return false; + } + + if (!disarm_switch_checks(display_failure)) { + return false; + } + + // always check motors + char failure_msg[50] {}; + if (!copter.motors->arming_checks(ARRAY_SIZE(failure_msg), failure_msg)) { + check_failed(display_failure, "Motors: %s", failure_msg); + return false; } // if pre arm checks are disabled run only the mandatory checks @@ -57,10 +56,10 @@ bool AP_Arming_Copter::run_pre_arm_checks(bool display_failure) } return parameter_checks(display_failure) - & motor_checks(display_failure) & oa_checks(display_failure) & gcs_failsafe_check(display_failure) & winch_checks(display_failure) + & rc_throttle_failsafe_checks(display_failure) & alt_checks(display_failure) #if AP_AIRSPEED_ENABLED & AP_Arming::airspeed_checks(display_failure) @@ -68,6 +67,40 @@ bool AP_Arming_Copter::run_pre_arm_checks(bool display_failure) & AP_Arming::pre_arm_checks(display_failure); } +bool AP_Arming_Copter::rc_throttle_failsafe_checks(bool display_failure) const +{ + if ((checks_to_perform != ARMING_CHECK_ALL) && + (checks_to_perform & ARMING_CHECK_RC) == 0) { + // this check has been disabled + return true; + } + + // throttle failsafe. In this case the parameter also gates the + // no-pulses RC failure case - the radio-in value can be zero due + // to not having received any RC pulses at all. Note that if we + // have ever seen RC and then we *lose* RC then these checks are + // likely to pass if the user is relying on no-pulses to detect RC + // failure. However, arming is precluded in that case by being in + // RC failsafe. + if (copter.g.failsafe_throttle == FS_THR_DISABLED) { + return true; + } + +#if FRAME_CONFIG == HELI_FRAME + const char *rc_item = "Collective"; +#else + const char *rc_item = "Throttle"; +#endif + + // check throttle is not too low - must be above failsafe throttle + if (copter.channel_throttle->get_radio_in() < copter.g.failsafe_throttle_value) { + check_failed(ARMING_CHECK_RC, display_failure, "%s below failsafe", rc_item); + return false; + } + + return true; +} + bool AP_Arming_Copter::barometer_checks(bool display_failure) { if (!AP_Arming::barometer_checks(display_failure)) { @@ -125,6 +158,23 @@ bool AP_Arming_Copter::board_voltage_checks(bool display_failure) return true; } +// expected to return true if the terrain database is required to have +// all data loaded +bool AP_Arming_Copter::terrain_database_required() const +{ + + if (copter.wp_nav->get_terrain_source() == AC_WPNav::TerrainSource::TERRAIN_FROM_RANGEFINDER) { + // primary terrain source is from rangefinder, allow arming without terrain database + return false; + } + + if (copter.wp_nav->get_terrain_source() == AC_WPNav::TerrainSource::TERRAIN_FROM_TERRAINDATABASE && + copter.mode_rtl.get_alt_type() == ModeRTL::RTLAltType::RTL_ALTTYPE_TERRAIN) { + return true; + } + return AP_Arming::terrain_database_required(); +} + bool AP_Arming_Copter::parameter_checks(bool display_failure) { // check various parameter values @@ -178,7 +228,7 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure) } char fail_msg[50]; - // check input mangager parameters + // check input manager parameters if (!copter.input_manager.parameter_check(fail_msg, ARRAY_SIZE(fail_msg))) { check_failed(ARMING_CHECK_PARAMETERS, display_failure, "%s", fail_msg); return false; @@ -233,22 +283,7 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure) } break; case AC_WPNav::TerrainSource::TERRAIN_FROM_TERRAINDATABASE: -#if AP_TERRAIN_AVAILABLE - if (!copter.terrain.enabled()) { - check_failed(ARMING_CHECK_PARAMETERS, display_failure, failure_template, "terrain disabled"); - return false; - } - // check terrain data is loaded - uint16_t terr_pending, terr_loaded; - copter.terrain.get_statistics(terr_pending, terr_loaded); - if (terr_pending != 0) { - check_failed(ARMING_CHECK_PARAMETERS, display_failure, failure_template, "waiting for terrain data"); - return false; - } -#else - check_failed(ARMING_CHECK_PARAMETERS, display_failure, failure_template, "terrain disabled"); - return false; -#endif + // these checks are done in AP_Arming break; } } @@ -263,7 +298,7 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure) #endif // ensure controllers are OK with us arming: - char failure_msg[50]; + char failure_msg[50] = {}; if (!copter.pos_control->pre_arm_checks("PSC", failure_msg, ARRAY_SIZE(failure_msg))) { check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Bad parameter: %s", failure_msg); return false; @@ -277,79 +312,10 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure) return true; } -// check motor setup was successful -bool AP_Arming_Copter::motor_checks(bool display_failure) -{ - // check motors initialised correctly - if (!copter.motors->initialised_ok()) { - check_failed(display_failure, "Check firmware or FRAME_CLASS"); - return false; - } - - // servo_test check -#if FRAME_CONFIG == HELI_FRAME - if (copter.motors->servo_test_running()) { - check_failed(display_failure, "Servo Test is still running"); - return false; - } -#endif - // further checks enabled with parameters - if (!check_enabled(ARMING_CHECK_PARAMETERS)) { - return true; - } - - // if this is a multicopter using ToshibaCAN ESCs ensure MOT_PMW_MIN = 1000, MOT_PWM_MAX = 2000 -#if HAL_MAX_CAN_PROTOCOL_DRIVERS && (FRAME_CONFIG != HELI_FRAME) - bool tcan_active = false; - uint8_t tcan_index = 0; - const uint8_t num_drivers = AP::can().get_num_drivers(); - for (uint8_t i = 0; i < num_drivers; i++) { - if (AP::can().get_driver_type(i) == AP_CANManager::Driver_Type_ToshibaCAN) { - tcan_active = true; - tcan_index = i; - } - } - if (tcan_active) { - // check motor range parameters - if (copter.motors->get_pwm_output_min() != 1000) { - check_failed(display_failure, "TCAN ESCs require MOT_PWM_MIN=1000"); - return false; - } - if (copter.motors->get_pwm_output_max() != 2000) { - check_failed(display_failure, "TCAN ESCs require MOT_PWM_MAX=2000"); - return false; - } - - // check we have an ESC present for every SERVOx_FUNCTION = motorx - // find and report first missing ESC, extra ESCs are OK - AP_ToshibaCAN *tcan = AP_ToshibaCAN::get_tcan(tcan_index); - const uint16_t motors_mask = copter.motors->get_motor_mask(); - const uint16_t esc_mask = tcan->get_present_mask(); - uint8_t escs_missing = 0; - uint8_t first_missing = 0; - for (uint8_t i = 0; i < 16; i++) { - uint32_t bit = 1UL << i; - if (((motors_mask & bit) > 0) && ((esc_mask & bit) == 0)) { - escs_missing++; - if (first_missing == 0) { - first_missing = i+1; - } - } - } - if (escs_missing > 0) { - check_failed(display_failure, "TCAN missing %d escs, check #%d", (int)escs_missing, (int)first_missing); - return false; - } - } -#endif - - return true; -} - bool AP_Arming_Copter::oa_checks(bool display_failure) { #if AC_OAPATHPLANNER_ENABLED == ENABLED - char failure_msg[50]; + char failure_msg[50] = {}; if (copter.g2.oa.pre_arm_check(failure_msg, ARRAY_SIZE(failure_msg))) { return true; } @@ -385,7 +351,7 @@ bool AP_Arming_Copter::gps_checks(bool display_failure) { // check if fence requires GPS bool fence_requires_gps = false; - #if AC_FENCE == ENABLED + #if AP_FENCE_ENABLED // if circular or polygon fence is enabled we need GPS fence_requires_gps = (copter.fence.get_enabled_fences() & (AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON)) > 0; #endif @@ -420,7 +386,7 @@ bool AP_Arming_Copter::gps_checks(bool display_failure) } // warn about hdop separately - to prevent user confusion with no gps lock - if (copter.gps.get_hdop() > copter.g.gps_hdop_good) { + if ((copter.gps.num_sensors() > 0) && (copter.gps.get_hdop() > copter.g.gps_hdop_good)) { check_failed(ARMING_CHECK_GPS, display_failure, "High GPS HDOP"); AP_Notify::flags.pre_arm_gps_check = false; return false; @@ -487,7 +453,7 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure) // check if fence requires GPS bool fence_requires_gps = false; - #if AC_FENCE == ENABLED + #if AP_FENCE_ENABLED // if circular or polygon fence is enabled we need GPS fence_requires_gps = (copter.fence.get_enabled_fences() & (AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON)) > 0; #endif @@ -520,7 +486,7 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure) } } - // check EKF's compass, position and velocity variances are below failsafe threshold + // check EKF's compass, position, height and velocity variances are below failsafe threshold if (copter.g.fs_ekf_thresh > 0.0f) { float vel_variance, pos_variance, hgt_variance, tas_variance; Vector3f mag_variance; @@ -537,6 +503,10 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure) check_failed(display_failure, "EKF velocity variance"); return false; } + if (hgt_variance >= copter.g.fs_ekf_thresh) { + check_failed(display_failure, "EKF height variance"); + return false; + } } // check if home is too far from EKF origin @@ -626,25 +596,7 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method) // always check if the current mode allows arming if (!copter.flightmode->allows_arming(method)) { - check_failed(true, "Mode not armable"); - return false; - } - - // always check motors - if (!motor_checks(true)) { - return false; - } - - // if we are using motor interlock switch and it's enabled, fail to arm - // skip check in Throw mode which takes control of the motor interlock - if (copter.ap.using_interlock && copter.ap.motor_interlock_switch) { - check_failed(true, "Motor Interlock Enabled"); - return false; - } - - // if we are using motor Estop switch, it must not be in Estop position - if (SRV_Channels::get_emergency_stop()){ - check_failed(true, "Motor Emergency Stopped"); + check_failed(true, "%s mode not armable", copter.flightmode->name()); return false; } @@ -678,12 +630,6 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method) #else const char *rc_item = "Throttle"; #endif - // check throttle is not too low - must be above failsafe throttle - if (copter.g.failsafe_throttle != FS_THR_DISABLED && copter.channel_throttle->get_radio_in() < copter.g.failsafe_throttle_value) { - check_failed(ARMING_CHECK_RC, true, "%s below failsafe", rc_item); - return false; - } - // check throttle is not too high - skips checks if arming from GCS in Guided if (!(method == AP_Arming::Method::MAVLINK && (copter.flightmode->mode_number() == Mode::Number::GUIDED || copter.flightmode->mode_number() == Mode::Number::GUIDED_NOGPS))) { // above top of deadband is too always high diff --git a/ArduCopter/AP_Arming.h b/ArduCopter/AP_Arming.h index ae705b70e41..4d49b05cdcc 100644 --- a/ArduCopter/AP_Arming.h +++ b/ArduCopter/AP_Arming.h @@ -19,8 +19,6 @@ class AP_Arming_Copter : public AP_Arming AP_Arming_Copter(const AP_Arming_Copter &other) = delete; AP_Arming_Copter &operator=(const AP_Arming_Copter&) = delete; - void update(void); - bool rc_calibration_checks(bool display_failure) override; bool disarm(AP_Arming::Method method, bool do_disarm_checks=true) override; @@ -44,15 +42,19 @@ class AP_Arming_Copter : public AP_Arming // NOTE! the following check functions *DO NOT* call into AP_Arming! bool parameter_checks(bool display_failure); - bool motor_checks(bool display_failure); bool oa_checks(bool display_failure); bool mandatory_gps_checks(bool display_failure); bool gcs_failsafe_check(bool display_failure); bool winch_checks(bool display_failure) const; bool alt_checks(bool display_failure); + bool rc_throttle_failsafe_checks(bool display_failure) const; void set_pre_arm_check(bool b); + // expected to return true if the terrain database is required to have + // all data loaded + bool terrain_database_required() const override; + private: // actually contains the pre-arm checks. This is wrapped so that diff --git a/ArduCopter/AP_Rally.cpp b/ArduCopter/AP_Rally.cpp index 574a17d9f70..31027d7909c 100644 --- a/ArduCopter/AP_Rally.cpp +++ b/ArduCopter/AP_Rally.cpp @@ -21,7 +21,7 @@ bool AP_Rally_Copter::is_valid(const Location &rally_point) const { -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED if (!copter.fence.check_destination_within_fence(rally_point)) { return false; } diff --git a/ArduCopter/AP_State.cpp b/ArduCopter/AP_State.cpp index fa9e4629eb8..a3e60e80763 100644 --- a/ArduCopter/AP_State.cpp +++ b/ArduCopter/AP_State.cpp @@ -75,7 +75,7 @@ void Copter::set_failsafe_gcs(bool b) failsafe.gcs = b; // update AP_Notify - AP_Notify::flags.failsafe_gcs = b; + AP_Notify::flags.failsafe_gcs = b; } // --------------------------------------------- diff --git a/ArduCopter/Attitude.cpp b/ArduCopter/Attitude.cpp index c823849d868..deee31f0e39 100644 --- a/ArduCopter/Attitude.cpp +++ b/ArduCopter/Attitude.cpp @@ -1,5 +1,23 @@ #include "Copter.h" +/************************************************************* + * Attitude Rate controllers and timing + ****************************************************************/ + +// update rate controllers and output to roll, pitch and yaw actuators +// called at 400hz by default +void Copter::run_rate_controller() +{ + // set attitude and position controller loop time + const float last_loop_time_s = AP::scheduler().get_last_loop_time_s(); + motors->set_dt(last_loop_time_s); + attitude_control->set_dt(last_loop_time_s); + pos_control->set_dt(last_loop_time_s); + + // run low level rate controllers that only require IMU data + attitude_control->rate_controller_run(); +} + /************************************************************* * throttle control ****************************************************************/ @@ -28,7 +46,7 @@ void Copter::update_throttle_hover() // calc average throttle if we are in a level hover. accounts for heli hover roll trim if (throttle > 0.0f && fabsf(inertial_nav.get_velocity_z_up_cms()) < 60 && - labs(ahrs.roll_sensor-attitude_control->get_roll_trim_cd()) < 500 && labs(ahrs.pitch_sensor) < 500) { + fabsf(ahrs.roll_sensor-attitude_control->get_roll_trim_cd()) < 500 && labs(ahrs.pitch_sensor) < 500) { // Can we set the time constant automatically motors->update_throttle_hover(0.01f); #if HAL_GYROFFT_ENABLED @@ -58,7 +76,7 @@ float Copter::get_pilot_desired_climb_rate(float throttle_control) throttle_control = constrain_float(throttle_control,0.0f,1000.0f); // ensure a reasonable deadzone - g.throttle_deadzone = constrain_int16(g.throttle_deadzone, 0, 400); + g.throttle_deadzone.set(constrain_int16(g.throttle_deadzone, 0, 400)); float desired_rate = 0.0f; const float mid_stick = get_throttle_mid(); diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index 70314c9b565..808c8065ee6 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -83,10 +83,10 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); #define SCHED_TASK(func, _interval_ticks, _max_time_micros, _prio) SCHED_TASK_CLASS(Copter, &copter, func, _interval_ticks, _max_time_micros, _prio) +#define FAST_TASK(func) FAST_TASK_CLASS(Copter, &copter, func) /* - scheduler table - all regular tasks apart from the fast_loop() - should be listed here. + scheduler table - all tasks should be listed here. All entries in this table must be ordered by priority. @@ -110,11 +110,44 @@ SCHED_TASK_CLASS arguments: */ const AP_Scheduler::Task Copter::scheduler_tasks[] = { - SCHED_TASK(rc_loop, 100, 130, 3), + // update INS immediately to get current gyro data populated + FAST_TASK_CLASS(AP_InertialSensor, &copter.ins, update), + // run low level rate controllers that only require IMU data + FAST_TASK(run_rate_controller), +#if AC_CUSTOMCONTROL_MULTI_ENABLED == ENABLED + FAST_TASK(run_custom_controller), +#endif + // send outputs to the motors library immediately + FAST_TASK(motors_output), + // run EKF state estimator (expensive) + FAST_TASK(read_AHRS), +#if FRAME_CONFIG == HELI_FRAME + FAST_TASK(update_heli_control_dynamics), + #if MODE_AUTOROTATE_ENABLED == ENABLED + FAST_TASK(heli_update_autorotation), + #endif +#endif //HELI_FRAME + // Inertial Nav + FAST_TASK(read_inertia), + // check if ekf has reset target heading or position + FAST_TASK(check_ekf_reset), + // run the attitude controllers + FAST_TASK(update_flight_mode), + // update home from EKF if necessary + FAST_TASK(update_home_from_EKF), + // check if we've landed or crashed + FAST_TASK(update_land_and_crash_detectors), +#if HAL_MOUNT_ENABLED + // camera mount's fast update + FAST_TASK_CLASS(AP_Mount, &copter.camera_mount, update_fast), +#endif + FAST_TASK(Log_Video_Stabilisation), + + SCHED_TASK(rc_loop, 250, 130, 3), SCHED_TASK(throttle_loop, 50, 75, 6), SCHED_TASK_CLASS(AP_GPS, &copter.gps, update, 50, 200, 9), #if AP_OPTICALFLOW_ENABLED - SCHED_TASK_CLASS(OpticalFlow, &copter.optflow, update, 200, 160, 12), + SCHED_TASK_CLASS(AP_OpticalFlow, &copter.optflow, update, 200, 160, 12), #endif SCHED_TASK(update_batt_compass, 10, 120, 15), SCHED_TASK_CLASS(RC_Channels, (RC_Channels*)&copter.g2.rc_channels, read_aux_all, 10, 50, 18), @@ -145,9 +178,6 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { SCHED_TASK(three_hz_loop, 3, 75, 57), SCHED_TASK_CLASS(AP_ServoRelayEvents, &copter.ServoRelayEvents, update_events, 50, 75, 60), SCHED_TASK_CLASS(AP_Baro, &copter.barometer, accumulate, 50, 90, 63), -#if AC_FENCE == ENABLED - SCHED_TASK_CLASS(AC_Fence, &copter.fence, update, 10, 100, 66), -#endif #if PRECISION_LANDING == ENABLED SCHED_TASK(update_precland, 400, 50, 69), #endif @@ -155,13 +185,14 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { SCHED_TASK(check_dynamic_flight, 50, 75, 72), #endif #if LOGGING_ENABLED == ENABLED - SCHED_TASK(fourhundred_hz_logging,400, 50, 75), + SCHED_TASK(loop_rate_logging, LOOP_RATE, 50, 75), #endif SCHED_TASK_CLASS(AP_Notify, &copter.notify, update, 50, 90, 78), SCHED_TASK(one_hz_loop, 1, 100, 81), SCHED_TASK(ekf_check, 10, 75, 84), SCHED_TASK(check_vibration, 10, 50, 87), SCHED_TASK(gpsglitch_check, 10, 50, 90), + SCHED_TASK(takeoff_check, 50, 50, 91), #if LANDING_GEAR_ENABLED == ENABLED SCHED_TASK(landinggear_update, 10, 75, 93), #endif @@ -186,7 +217,6 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { #if RPM_ENABLED == ENABLED SCHED_TASK_CLASS(AP_RPM, &copter.rpm_sensor, update, 40, 200, 129), #endif - SCHED_TASK_CLASS(Compass, &copter.compass, cal_update, 100, 100, 132), SCHED_TASK_CLASS(AP_TempCalibration, &copter.g2.temp_calibration, update, 10, 100, 135), #if HAL_ADSB_ENABLED SCHED_TASK(avoidance_adsb_update, 10, 100, 138), @@ -237,62 +267,6 @@ void Copter::get_scheduler_tasks(const AP_Scheduler::Task *&tasks, constexpr int8_t Copter::_failsafe_priorities[7]; -// Main loop - 400hz -void Copter::fast_loop() -{ - // update INS immediately to get current gyro data populated - ins.update(); - - // run low level rate controllers that only require IMU data - attitude_control->rate_controller_run(); - - // send outputs to the motors library immediately - motors_output(); - - // run EKF state estimator (expensive) - // -------------------- - read_AHRS(); - -#if FRAME_CONFIG == HELI_FRAME - update_heli_control_dynamics(); - #if MODE_AUTOROTATE_ENABLED == ENABLED - heli_update_autorotation(); - #endif -#endif //HELI_FRAME - - // Inertial Nav - // -------------------- - read_inertia(); - - // check if ekf has reset target heading or position - check_ekf_reset(); - - // run the attitude controllers - update_flight_mode(); - - // update home from EKF if necessary - update_home_from_EKF(); - - // check if we've landed or crashed - update_land_and_crash_detectors(); - -#if HAL_MOUNT_ENABLED - // camera mount's fast update - camera_mount.update_fast(); -#endif - - // log sensor health - if (should_log(MASK_LOG_ANY)) { - Log_Sensor_Health(); - } - - AP_Vehicle::fast_loop(); - - if (should_log(MASK_LOG_VIDEO_STABILISATION)) { - ahrs.write_video_stabilisation(); - } -} - #if AP_SCRIPTING_ENABLED // start takeoff to given altitude (for use by scripting) bool Copter::start_takeoff(float alt) @@ -418,6 +392,18 @@ bool Copter::set_circle_rate(float rate_dps) return true; } +// set desired speed (m/s). Used for scripting. +bool Copter::set_desired_speed(float speed) +{ + // exit if vehicle is not in auto mode + if (!flightmode->is_autopilot()) { + return false; + } + + wp_nav->set_speed_xy(speed * 100.0f); + return true; +} + // returns true if mode supports NAV_SCRIPT_TIME mission commands bool Copter::nav_scripting_enable(uint8_t mode) { @@ -444,6 +430,12 @@ void Copter::nav_script_time_done(uint16_t id) return mode_auto.nav_script_time_done(id); } +// returns true if the EKF failsafe has triggered. Only used by Lua scripts +bool Copter::has_ekf_failsafed() const +{ + return failsafe.ekf; +} + #endif // AP_SCRIPTING_ENABLED @@ -496,11 +488,18 @@ void Copter::update_batt_compass(void) } // Full rate logging of attitude, rate and pid loops -// should be run at 400hz -void Copter::fourhundred_hz_logging() +// should be run at loop rate +void Copter::loop_rate_logging() { if (should_log(MASK_LOG_ATTITUDE_FAST) && !copter.flightmode->logs_attitude()) { Log_Write_Attitude(); + Log_Write_PIDS(); // only logs if PIDS bitmask is set + } + if (should_log(MASK_LOG_FTN_FAST)) { + AP::ins().write_notch_log_messages(); + } + if (should_log(MASK_LOG_IMU_FAST)) { + AP::ins().Write_IMU(); } } @@ -512,8 +511,12 @@ void Copter::ten_hz_logging_loop() if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_ATTITUDE_FAST) && !copter.flightmode->logs_attitude()) { Log_Write_Attitude(); } - // log EKF attitude data - if (should_log(MASK_LOG_ATTITUDE_MED) || should_log(MASK_LOG_ATTITUDE_FAST)) { + if (!should_log(MASK_LOG_ATTITUDE_FAST)) { + // log at 10Hz if PIDS bitmask is selected, even if no ATT bitmask is selected; logs at looprate if ATT_FAST and PIDS bitmask set + Log_Write_PIDS(); + } + // log EKF attitude data always at 10Hz unless ATTITUDE_FAST, then do it in the 25Hz loop + if (!should_log(MASK_LOG_ATTITUDE_FAST)) { Log_Write_EKF_POS(); } if (should_log(MASK_LOG_MOTBATT)) { @@ -537,10 +540,10 @@ void Copter::ten_hz_logging_loop() if (should_log(MASK_LOG_CTUN)) { attitude_control->control_monitor_log(); #if HAL_PROXIMITY_ENABLED - logger.Write_Proximity(g2.proximity); // Write proximity sensor distances + g2.proximity.log(); // Write proximity sensor distances #endif #if BEACON_ENABLED == ENABLED - logger.Write_Beacon(g2.beacon); + g2.beacon.log(); #endif } #if FRAME_CONFIG == HELI_FRAME @@ -560,7 +563,7 @@ void Copter::twentyfive_hz_logging() Log_Write_EKF_POS(); } - if (should_log(MASK_LOG_IMU)) { + if (should_log(MASK_LOG_IMU) && !(should_log(MASK_LOG_IMU_FAST))) { AP::ins().Write_IMU(); } @@ -581,10 +584,13 @@ void Copter::three_hz_loop() // check if we've lost terrain data failsafe_terrain_check(); -#if AC_FENCE == ENABLED + // check for deadreckoning failsafe + failsafe_deadreckon_check(); + +#if AP_FENCE_ENABLED // check if we have breached a fence fence_check(); -#endif // AC_FENCE_ENABLED +#endif // AP_FENCE_ENABLED // update ch6 in flight tuning @@ -601,12 +607,7 @@ void Copter::one_hz_loop() Log_Write_Data(LogDataID::AP_STATE, ap.value); } - arming.update(); - if (!motors->armed()) { - // make it possible to change ahrs orientation at runtime during initial config - ahrs.update_orientation(); - update_using_interlock(); // check the user hasn't updated the frame class or type @@ -716,7 +717,9 @@ void Copter::update_altitude() if (should_log(MASK_LOG_CTUN)) { Log_Write_Control_Tuning(); - AP::ins().write_notch_log_messages(); + if (!should_log(MASK_LOG_FTN_FAST)) { + AP::ins().write_notch_log_messages(); + } #if HAL_GYROFFT_ENABLED gyro_fft.write_log_messages(); #endif @@ -747,6 +750,18 @@ bool Copter::get_wp_crosstrack_error_m(float &xtrack_error) const return true; } +// get the target earth-frame angular velocities in rad/s (Z-axis component used by some gimbals) +bool Copter::get_rate_ef_targets(Vector3f& rate_ef_targets) const +{ + // always returns zero vector if landed or disarmed + if (copter.ap.land_complete) { + rate_ef_targets.zero(); + } else { + rate_ef_targets = attitude_control->get_rate_ef_targets(); + } + return true; +} + /* constructor for main Copter class */ @@ -761,9 +776,6 @@ Copter::Copter(void) param_loader(var_info), flightmode(&mode_stabilize) { - // init sensor error logging flags - sensor_health.baro = true; - sensor_health.compass = true; } Copter copter; diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 48b1ca783f7..cee5e405c01 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -34,7 +34,6 @@ #include // library for Management for hal.storage to allow for backwards compatible mapping of storage offsets to available storage // Application dependencies -#include // Library for Interface definition for the various Ground Control System #include // ArduPilot Mega Flash Memory Library #include // ArduPilot Mega Vector/Matrix math Library #include // interface and maths for accelerometer calibration @@ -46,6 +45,7 @@ #include // 6DoF Attitude control library #include // Attitude control library for traditional helicopter #include // Position control library +#include // Command model library #include // AP Motors library #include // statistics library #include // Filter library @@ -119,9 +119,6 @@ #if MODE_FOLLOW_ENABLED == ENABLED # include #endif -#if AC_FENCE == ENABLED - # include -#endif #if AP_TERRAIN_AVAILABLE # include #endif @@ -160,6 +157,18 @@ #include #endif +#if AC_CUSTOMCONTROL_MULTI_ENABLED == ENABLED +#include // Custom control library +#endif + +#if AC_AVOID_ENABLED && !AP_FENCE_ENABLED + #error AC_Avoidance relies on AP_FENCE_ENABLED which is disabled +#endif + +#if AC_OAPATHPLANNER_ENABLED && !AP_FENCE_ENABLED + #error AP_OAPathPlanner relies on AP_FENCE_ENABLED which is disabled +#endif + // Local modules #ifdef USER_PARAMS_ENABLED #include "UserParameters.h" @@ -256,10 +265,8 @@ class Copter : public AP_Vehicle { uint32_t glitch_cleared_ms; // system time glitch cleared } rangefinder_state, rangefinder_up_state; - /* - return rangefinder height interpolated using inertial altitude - */ - bool get_rangefinder_height_interpolated_cm(int32_t& ret); + // return rangefinder height interpolated using inertial altitude + bool get_rangefinder_height_interpolated_cm(int32_t& ret) const; class SurfaceTracking { public: @@ -307,7 +314,7 @@ class Copter : public AP_Vehicle { // Optical flow sensor #if AP_OPTICALFLOW_ENABLED - OpticalFlow optflow; + AP_OpticalFlow optflow; #endif // system time in milliseconds of last recorded yaw reset from ekf @@ -321,6 +328,9 @@ class Copter : public AP_Vehicle { uint32_t clear_ms; // system time high vibrations stopped } vibration_check; + // takeoff check + uint32_t takeoff_check_warning_ms; // system time user was last warned of takeoff check failure + // GCS selection GCS_Copter _gcs; // avoid using this; use gcs() GCS_Copter &gcs() { return _gcs; } @@ -392,17 +402,19 @@ class Copter : public AP_Vehicle { uint8_t ekf : 1; // true if ekf failsafe has occurred uint8_t terrain : 1; // true if the missing terrain data failsafe has occurred uint8_t adsb : 1; // true if an adsb related failsafe has occurred + uint8_t deadreckon : 1; // true if a dead reckoning failsafe has triggered } failsafe; bool any_failsafe_triggered() const { - return failsafe.radio || battery.has_failsafed() || failsafe.gcs || failsafe.ekf || failsafe.terrain || failsafe.adsb; + return failsafe.radio || battery.has_failsafed() || failsafe.gcs || failsafe.ekf || failsafe.terrain || failsafe.adsb || failsafe.deadreckon; } - // sensor health for logging + // dead reckoning state struct { - uint8_t baro : 1; // true if baro is healthy - uint8_t compass : 1; // true if compass is healthy - } sensor_health; + bool active; // true if dead reckoning (position estimate using estimated airspeed, no position or velocity source) + bool timeout; // true if dead reckoning has timedout and EKF's position and velocity estimate should no longer be trusted + uint32_t start_ms; // system time that EKF began deadreckoning + } dead_reckoning; // Motor Output MOTOR_CLASS *motors; @@ -459,6 +471,10 @@ class Copter : public AP_Vehicle { AC_WPNav *wp_nav; AC_Loiter *loiter_nav; +#if AC_CUSTOMCONTROL_MULTI_ENABLED == ENABLED + AC_CustomControl custom_control{ahrs_view, attitude_control, motors, scheduler.get_loop_period_s()}; +#endif + #if MODE_CIRCLE_ENABLED == ENABLED AC_Circle *circle_nav; #endif @@ -482,11 +498,6 @@ class Copter : public AP_Vehicle { AP_Mount camera_mount; #endif - // AC_Fence library to reduce fly-aways -#if AC_FENCE == ENABLED - AC_Fence fence; -#endif - #if AC_AVOID_ENABLED == ENABLED AC_Avoid avoid; #endif @@ -641,7 +652,6 @@ class Copter : public AP_Vehicle { void get_scheduler_tasks(const AP_Scheduler::Task *&tasks, uint8_t &task_count, uint32_t &log_bit) override; - void fast_loop() override; #if AP_SCRIPTING_ENABLED bool start_takeoff(float alt) override; bool set_target_location(const Location& target_loc) override; @@ -653,14 +663,18 @@ class Copter : public AP_Vehicle { bool set_target_angle_and_climbrate(float roll_deg, float pitch_deg, float yaw_deg, float climb_rate_ms, bool use_yaw_rate, float yaw_rate_degs) override; bool get_circle_radius(float &radius_m) override; bool set_circle_rate(float rate_dps) override; + bool set_desired_speed(float speed) override; bool nav_scripting_enable(uint8_t mode) override; bool nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2) override; void nav_script_time_done(uint16_t id) override; + // lua scripts use this to retrieve EKF failsafe state + // returns true if the EKF failsafe has triggered + bool has_ekf_failsafed() const override; #endif // AP_SCRIPTING_ENABLED void rc_loop(); void throttle_loop(); void update_batt_compass(void); - void fourhundred_hz_logging(); + void loop_rate_logging(); void ten_hz_logging_loop(); void twentyfive_hz_logging(); void three_hz_loop(); @@ -670,6 +684,10 @@ class Copter : public AP_Vehicle { void update_super_simple_bearing(bool force_update); void read_AHRS(void); void update_altitude(); + bool get_wp_distance_m(float &distance) const override; + bool get_wp_bearing_deg(float &bearing) const override; + bool get_wp_crosstrack_error_m(float &xtrack_error) const override; + bool get_rate_ef_targets(Vector3f& rate_ef_targets) const override; // Attitude.cpp void update_throttle_hover(); @@ -678,6 +696,11 @@ class Copter : public AP_Vehicle { void set_accel_throttle_I_from_pilot_throttle(); void rotate_body_frame_to_NE(float &x, float &y); uint16_t get_pilot_speed_dn() const; + void run_rate_controller(); + +#if AC_CUSTOMCONTROL_MULTI_ENABLED == ENABLED + void run_custom_controller() { custom_control.update(); } +#endif // avoidance.cpp void low_alt_avoidance(); @@ -716,6 +739,7 @@ class Copter : public AP_Vehicle { bool ekf_over_threshold(); void failsafe_ekf_event(); void failsafe_ekf_off_event(void); + void failsafe_ekf_recheck(); void check_ekf_reset(); void check_vibration(); @@ -738,12 +762,14 @@ class Copter : public AP_Vehicle { void failsafe_terrain_set_status(bool data_ok); void failsafe_terrain_on_event(); void gpsglitch_check(); + void failsafe_deadreckon_check(); void set_mode_RTL_or_land_with_pause(ModeReason reason); void set_mode_SmartRTL_or_RTL(ModeReason reason); void set_mode_SmartRTL_or_land_with_pause(ModeReason reason); void set_mode_auto_do_land_start_or_RTL(ModeReason reason); bool should_disarm_on_failsafe(); void do_failsafe_action(FailsafeAction action, ModeReason reason); + void announce_failsafe(const char *type, const char *action_undertaken=nullptr); // failsafe.cpp void failsafe_enable(); @@ -753,7 +779,7 @@ class Copter : public AP_Vehicle { #endif // fence.cpp -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED void fence_check(); #endif @@ -792,13 +818,14 @@ class Copter : public AP_Vehicle { void Log_Write_Control_Tuning(); void Log_Write_Attitude(); void Log_Write_EKF_POS(); + void Log_Write_PIDS(); void Log_Write_Data(LogDataID id, int32_t value); void Log_Write_Data(LogDataID id, uint32_t value); void Log_Write_Data(LogDataID id, int16_t value); void Log_Write_Data(LogDataID id, uint16_t value); void Log_Write_Data(LogDataID id, float value); void Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, float tune_min, float tune_max); - void Log_Sensor_Health(); + void Log_Video_Stabilisation(); #if FRAME_CONFIG == HELI_FRAME void Log_Write_Heli(void); #endif @@ -843,6 +870,9 @@ class Copter : public AP_Vehicle { // Parameters.cpp void load_parameters(void) override; void convert_pid_parameters(void); +#if HAL_PROXIMITY_ENABLED + void convert_prx_parameters(); +#endif void convert_lgr_parameters(void); void convert_tradheli_parameters(void) const; void convert_fs_options_params(void) const; @@ -869,7 +899,9 @@ class Copter : public AP_Vehicle { bool rangefinder_alt_ok() const; bool rangefinder_up_ok() const; void update_optical_flow(void); - void compass_cal_update(void); + + // takeoff_check.cpp + void takeoff_check(); // RC_Channel.cpp void save_trim(); @@ -879,7 +911,6 @@ class Copter : public AP_Vehicle { // system.cpp void init_ardupilot() override; void startup_INS_ground(); - void update_dynamic_notch() override; bool position_ok() const; bool ekf_has_absolute_position() const; bool ekf_has_relative_position() const; @@ -908,11 +939,6 @@ class Copter : public AP_Vehicle { void userhook_auxSwitch2(const RC_Channel::AuxSwitchPos ch_flag); void userhook_auxSwitch3(const RC_Channel::AuxSwitchPos ch_flag); - // vehicle specific waypoint info helpers - bool get_wp_distance_m(float &distance) const override; - bool get_wp_bearing_deg(float &bearing) const override; - bool get_wp_crosstrack_error_m(float &xtrack_error) const override; - #if MODE_ACRO_ENABLED == ENABLED #if FRAME_CONFIG == HELI_FRAME ModeAcro_Heli mode_acro; @@ -978,7 +1004,7 @@ class Copter : public AP_Vehicle { #if MODE_SMARTRTL_ENABLED == ENABLED ModeSmartRTL mode_smartrtl; #endif -#if !HAL_MINIMIZE_FEATURES && AP_OPTICALFLOW_ENABLED +#if MODE_FLOWHOLD_ENABLED == ENABLED ModeFlowHold mode_flowhold; #endif #if MODE_ZIGZAG_ENABLED == ENABLED diff --git a/ArduCopter/GCS_Copter.cpp b/ArduCopter/GCS_Copter.cpp index db0737e89e7..809216e1f00 100644 --- a/ArduCopter/GCS_Copter.cpp +++ b/ArduCopter/GCS_Copter.cpp @@ -115,7 +115,7 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void) #endif #if AP_OPTICALFLOW_ENABLED - const OpticalFlow *optflow = AP::opticalflow(); + const AP_OpticalFlow *optflow = AP::opticalflow(); if (optflow && optflow->enabled()) { control_sensors_present |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW; control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW; diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 12d88004a78..b964672bff8 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -1,6 +1,8 @@ #include "Copter.h" #include "GCS_Mavlink.h" +#include +#include MAV_TYPE GCS_Copter::frame_type() const { @@ -263,7 +265,7 @@ void GCS_MAVLINK_Copter::send_pid_tuning() if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) { return; } - const AP_Logger::PID_Info *pid_info = nullptr; + const AP_PIDInfo *pid_info = nullptr; switch (axes[i]) { case PID_TUNING_ROLL: pid_info = &copter.attitude_control->get_rate_roll_pid().get_pid_info(); @@ -380,6 +382,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK_Parameters, streamRates[0], 0), @@ -389,6 +392,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK_Parameters, streamRates[1], 0), @@ -398,6 +402,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK_Parameters, streamRates[2], 0), @@ -407,6 +412,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("RAW_CTRL", 3, GCS_MAVLINK_Parameters, streamRates[3], 0), @@ -416,15 +422,17 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("POSITION", 4, GCS_MAVLINK_Parameters, streamRates[4], 0), // @Param: EXTRA1 // @DisplayName: Extra data type 1 stream rate to ground station - // @Description: Stream rate of ATTITUDE, SIMSTATE (SITL only), AHRS2 and PID_TUNING to ground station + // @Description: Stream rate of ATTITUDE, SIMSTATE (SIM only), AHRS2 and PID_TUNING to ground station // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK_Parameters, streamRates[5], 0), @@ -434,15 +442,17 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK_Parameters, streamRates[6], 0), // @Param: EXTRA3 // @DisplayName: Extra data type 3 stream rate to ground station - // @Description: Stream rate of AHRS, HWSTATUS, SYSTEM_TIME, RANGEFINDER, DISTANCE_SENSOR, TERRAIN_REQUEST, BATTERY2, MOUNT_STATUS, OPTICAL_FLOW, GIMBAL_REPORT, MAG_CAL_REPORT, MAG_CAL_PROGRESS, EKF_STATUS_REPORT, VIBRATION and RPM to ground station + // @Description: Stream rate of AHRS, HWSTATUS, SYSTEM_TIME, RANGEFINDER, DISTANCE_SENSOR, TERRAIN_REQUEST, BATTERY2, GIMBAL_DEVICE_ATTITUDE_STATUS, OPTICAL_FLOW, MAG_CAL_REPORT, MAG_CAL_PROGRESS, EKF_STATUS_REPORT, VIBRATION and RPM to ground station // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK_Parameters, streamRates[7], 0), @@ -452,6 +462,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK_Parameters, streamRates[8], 0), @@ -461,6 +472,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("ADSB", 9, GCS_MAVLINK_Parameters, streamRates[9], 0), AP_GROUPEND @@ -518,23 +530,28 @@ static const ap_message STREAM_EXTRA3_msgs[] = { #endif MSG_BATTERY2, MSG_BATTERY_STATUS, - MSG_MOUNT_STATUS, + MSG_GIMBAL_DEVICE_ATTITUDE_STATUS, MSG_OPTICAL_FLOW, - MSG_GIMBAL_REPORT, MSG_MAG_CAL_REPORT, MSG_MAG_CAL_PROGRESS, MSG_EKF_STATUS_REPORT, MSG_VIBRATION, +#if AP_RPM_ENABLED MSG_RPM, +#endif MSG_ESC_TELEMETRY, MSG_GENERATOR_STATUS, MSG_WINCH_STATUS, +#if HAL_EFI_ENABLED + MSG_EFI_STATUS, +#endif }; static const ap_message STREAM_PARAMS_msgs[] = { MSG_NEXT_PARAM }; static const ap_message STREAM_ADSB_msgs[] = { - MSG_ADSB_VEHICLE + MSG_ADSB_VEHICLE, + MSG_AIS_VESSEL, }; const struct GCS_MAVLINK::stream_entries GCS_MAVLINK::all_stream_entries[] = { @@ -719,30 +736,29 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_packet(const mavlink_command_i } } +#if HAL_MOUNT_ENABLED MAV_RESULT GCS_MAVLINK_Copter::handle_command_mount(const mavlink_command_long_t &packet) { switch (packet.command) { -#if HAL_MOUNT_ENABLED case MAV_CMD_DO_MOUNT_CONTROL: // if vehicle has a camera mount but it doesn't do pan control then yaw the entire vehicle instead if ((copter.camera_mount.get_mount_type() != copter.camera_mount.MountType::Mount_Type_None) && !copter.camera_mount.has_pan_control()) { - copter.flightmode->auto_yaw.set_yaw_angle_rate( - (float)packet.param3 * 0.01f, - 0.0f); + copter.flightmode->auto_yaw.set_yaw_angle_rate((float)packet.param3, 0.0f); } break; -#endif default: break; } return GCS_MAVLINK::handle_command_mount(packet); } +#endif MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_long_t &packet) { switch(packet.command) { + case MAV_CMD_NAV_VTOL_TAKEOFF: case MAV_CMD_NAV_TAKEOFF: { // param3 : horizontal navigation by pilot acceptable // param4 : yaw angle (not supported) @@ -778,6 +794,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_ } return MAV_RESULT_ACCEPTED; + case MAV_CMD_NAV_VTOL_LAND: case MAV_CMD_NAV_LAND: if (!copter.set_mode(Mode::Number::LAND, ModeReason::GCS_COMMAND)) { return MAV_RESULT_FAILED; @@ -818,13 +835,21 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_ // param4 : unused if (packet.param2 > 0.0f) { if (packet.param1 > 2.9f) { // 3 = speed down - copter.wp_nav->set_speed_down(packet.param2 * 100.0f); + if (copter.flightmode->set_speed_down(packet.param2 * 100.0f)) { + return MAV_RESULT_ACCEPTED; + } + return MAV_RESULT_FAILED; } else if (packet.param1 > 1.9f) { // 2 = speed up - copter.wp_nav->set_speed_up(packet.param2 * 100.0f); + if (copter.flightmode->set_speed_up(packet.param2 * 100.0f)) { + return MAV_RESULT_ACCEPTED; + } + return MAV_RESULT_FAILED; } else { - copter.wp_nav->set_speed_xy(packet.param2 * 100.0f); + if (copter.flightmode->set_speed_xy(packet.param2 * 100.0f)) { + return MAV_RESULT_ACCEPTED; + } + return MAV_RESULT_FAILED; } - return MAV_RESULT_ACCEPTED; } return MAV_RESULT_FAILED; @@ -846,11 +871,9 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_ switch ((uint16_t)packet.param1) { case PARACHUTE_DISABLE: copter.parachute.enabled(false); - AP::logger().Write_Event(LogEvent::PARACHUTE_DISABLED); return MAV_RESULT_ACCEPTED; case PARACHUTE_ENABLE: copter.parachute.enabled(true); - AP::logger().Write_Event(LogEvent::PARACHUTE_ENABLED); return MAV_RESULT_ACCEPTED; case PARACHUTE_RELEASE: // treat as a manual release which performs some additional check of altitude @@ -995,36 +1018,30 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_ MAV_RESULT GCS_MAVLINK_Copter::handle_command_pause_continue(const mavlink_command_int_t &packet) { -#if MODE_AUTO_ENABLED - if (copter.flightmode->mode_number() != Mode::Number::AUTO) { - // only supported in AUTO mode + // requested pause + if ((uint8_t) packet.param1 == 0) { + if (copter.flightmode->pause()) { + return MAV_RESULT_ACCEPTED; + } + send_text(MAV_SEVERITY_INFO, "Failed to pause"); return MAV_RESULT_FAILED; } - // requested pause from GCS - if ((int8_t) packet.param1 == 0) { - copter.mode_auto.mission.stop(); - copter.mode_auto.loiter_start(); - gcs().send_text(MAV_SEVERITY_INFO, "Paused mission"); - return MAV_RESULT_ACCEPTED; - } - - // requested resume from GCS - if ((int8_t) packet.param1 == 1) { - copter.mode_auto.mission.resume(); - gcs().send_text(MAV_SEVERITY_INFO, "Resumed mission"); - return MAV_RESULT_ACCEPTED; + // requested resume + if ((uint8_t) packet.param1 == 1) { + if (copter.flightmode->resume()) { + return MAV_RESULT_ACCEPTED; + } + send_text(MAV_SEVERITY_INFO, "Failed to resume"); + return MAV_RESULT_FAILED; } -#endif - - // fail pause or continue - return MAV_RESULT_FAILED; + return MAV_RESULT_DENIED; } +#if HAL_MOUNT_ENABLED void GCS_MAVLINK_Copter::handle_mount_message(const mavlink_message_t &msg) { switch (msg.msgid) { -#if HAL_MOUNT_ENABLED case MAVLINK_MSG_ID_MOUNT_CONTROL: // if vehicle has a camera mount but it doesn't do pan control then yaw the entire vehicle instead if ((copter.camera_mount.get_mount_type() != copter.camera_mount.MountType::Mount_Type_None) && @@ -1035,10 +1052,10 @@ void GCS_MAVLINK_Copter::handle_mount_message(const mavlink_message_t &msg) break; } -#endif } GCS_MAVLINK::handle_mount_message(msg); } +#endif void GCS_MAVLINK_Copter::handleMessage(const mavlink_message_t &msg) { @@ -1390,28 +1407,6 @@ void GCS_MAVLINK_Copter::handleMessage(const mavlink_message_t &msg) #endif break; - case MAVLINK_MSG_ID_SET_HOME_POSITION: - { - send_received_message_deprecation_warning(STR_VALUE(MAVLINK_MSG_ID_SET_HOME_POSITION)); - - mavlink_set_home_position_t packet; - mavlink_msg_set_home_position_decode(&msg, &packet); - if ((packet.latitude == 0) && (packet.longitude == 0) && (packet.altitude == 0)) { - if (!copter.set_home_to_current_location(true)) { - // silently ignored - } - } else { - Location new_home_loc; - new_home_loc.lat = packet.latitude; - new_home_loc.lng = packet.longitude; - new_home_loc.alt = packet.altitude / 10; - if (!copter.set_home(new_home_loc, true)) { - // silently ignored - } - } - break; - } - #if TOY_MODE_ENABLED == ENABLED case MAVLINK_MSG_ID_NAMED_VALUE_INT: copter.g2.toy_mode.handle_message(msg); diff --git a/ArduCopter/GCS_Mavlink.h b/ArduCopter/GCS_Mavlink.h index 74230150b27..4f9c662fd89 100644 --- a/ArduCopter/GCS_Mavlink.h +++ b/ArduCopter/GCS_Mavlink.h @@ -29,13 +29,17 @@ class GCS_MAVLINK_Copter : public GCS_MAVLINK MAV_RESULT handle_command_do_set_roi(const Location &roi_loc) override; MAV_RESULT handle_preflight_reboot(const mavlink_command_long_t &packet) override; +#if HAL_MOUNT_ENABLED MAV_RESULT handle_command_mount(const mavlink_command_long_t &packet) override; +#endif MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet) override; MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet) override; MAV_RESULT handle_command_int_do_reposition(const mavlink_command_int_t &packet); MAV_RESULT handle_command_pause_continue(const mavlink_command_int_t &packet); +#if HAL_MOUNT_ENABLED void handle_mount_message(const mavlink_message_t &msg) override; +#endif void handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms) override; diff --git a/ArduCopter/Log.cpp b/ArduCopter/Log.cpp index a3a6cdb74f3..027544771d9 100644 --- a/ArduCopter/Log.cpp +++ b/ArduCopter/Log.cpp @@ -35,7 +35,7 @@ void Copter::Log_Write_Control_Tuning() float des_alt_m = 0.0f; int16_t target_climb_rate_cms = 0; if (!flightmode->has_manual_throttle()) { - des_alt_m = pos_control->get_pos_target_z_cm() / 100.0f; + des_alt_m = pos_control->get_pos_target_z_cm() * 0.01f; target_climb_rate_cms = pos_control->get_vel_target_z_cms(); } @@ -71,7 +71,12 @@ void Copter::Log_Write_Attitude() targets.z = wrap_360_cd(targets.z); ahrs.Write_Attitude(targets); ahrs_view->Write_Rate(*motors, *attitude_control, *pos_control); - if (should_log(MASK_LOG_PID)) { + } + +// Write PIDS packets +void Copter::Log_Write_PIDS() +{ + if (should_log(MASK_LOG_PID)) { logger.Write_PID(LOG_PIDR_MSG, attitude_control->get_rate_roll_pid().get_pid_info()); logger.Write_PID(LOG_PIDP_MSG, attitude_control->get_rate_pitch_pid().get_pid_info()); logger.Write_PID(LOG_PIDY_MSG, attitude_control->get_rate_yaw_pid().get_pid_info()); @@ -220,21 +225,12 @@ void Copter::Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, float t logger.WriteBlock(&pkt_tune, sizeof(pkt_tune)); } -// logs when baro or compass becomes unhealthy -void Copter::Log_Sensor_Health() +void Copter::Log_Video_Stabilisation() { - // check baro - if (sensor_health.baro != barometer.healthy()) { - sensor_health.baro = barometer.healthy(); - AP::logger().Write_Error(LogErrorSubsystem::BARO, - (sensor_health.baro ? LogErrorCode::ERROR_RESOLVED : LogErrorCode::UNHEALTHY)); - } - - // check compass - if (sensor_health.compass != compass.healthy()) { - sensor_health.compass = compass.healthy(); - AP::logger().Write_Error(LogErrorSubsystem::COMPASS, (sensor_health.compass ? LogErrorCode::ERROR_RESOLVED : LogErrorCode::UNHEALTHY)); + if (!should_log(MASK_LOG_VIDEO_STABILISATION)) { + return; } + ahrs.write_video_stabilisation(); } struct PACKED log_SysIdD { @@ -591,7 +587,6 @@ void Copter::Log_Write_Data(LogDataID id, int16_t value) {} void Copter::Log_Write_Data(LogDataID id, uint16_t value) {} void Copter::Log_Write_Data(LogDataID id, float value) {} void Copter::Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, float tune_min, float tune_max) {} -void Copter::Log_Sensor_Health() {} void Copter::Log_Write_Guided_Position_Target(ModeGuided::SubMode target_type, const Vector3f& pos_target, bool terrain_alt, const Vector3f& vel_target, const Vector3f& accel_target) {} void Copter::Log_Write_Guided_Attitude_Target(ModeGuided::SubMode target_type, float roll, float pitch, float yaw, const Vector3f &ang_vel, float thrust, float climb_rate) {} void Copter::Log_Write_SysID_Setup(uint8_t systemID_axis, float waveform_magnitude, float frequency_start, float frequency_stop, float time_fade_in, float time_const_freq, float time_record, float time_fade_out) {} diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 1fd0bd11e72..7ada4605d55 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -321,8 +321,8 @@ const AP_Param::Info Copter::var_info[] = { // @Param: LOG_BITMASK // @DisplayName: Log bitmask - // @Description: 4 byte bitmap of log types to enable - // @Bitmask: 0:ATTITUDE_FAST,1:ATTITUDE_MED,2:GPS,3:PM,4:CTUN,5:NTUN,6:RCIN,7:IMU,8:CMD,9:CURRENT,10:RCOUT,11:OPTFLOW,12:PID,13:COMPASS,14:INAV,15:CAMERA,17:MOTBATT,18:IMU_FAST,19:IMU_RAW,20:VideoStabilization + // @Description: Bitmap of what on-board log types to enable. This value is made up of the sum of each of the log types you want to be saved. It is usually best just to enable all basiclog types by setting this to 65535. + // @Bitmask: 0:Fast Attitude,1:Medium Attitude,2:GPS,3:System Performance,4:Control Tuning,5:Navigation Tuning,6:RC input,7:IMU,8:Mission Commands,9:Battery Monitor,10:RC output,11:Optical Flow,12:PID,13:Compass,15:Camera,17:Motors,18:Fast IMU,19:Raw IMU,20:Video Stabilization,21:Fast harmonic notch logging // @User: Standard GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK), @@ -354,7 +354,7 @@ const AP_Param::Info Copter::var_info[] = { // @Param: DISARM_DELAY // @DisplayName: Disarm delay - // @Description: Delay before automatic disarm in seconds. A value of zero disables auto disarm. + // @Description: Delay before automatic disarm in seconds after landing touchdown detection. A value of zero disables auto disarm. If Emergency Motor stop active, delay time is half this value. // @Units: s // @Range: 0 127 // @User: Advanced @@ -404,7 +404,7 @@ const AP_Param::Info Copter::var_info[] = { // @Param: FS_EKF_THRESH // @DisplayName: EKF failsafe variance threshold - // @Description: Allows setting the maximum acceptable compass and velocity variance + // @Description: Allows setting the maximum acceptable compass, velocity, position and height variances. Used in arming check and EKF failsafe. // @Values: 0.6:Strict, 0.8:Default, 1.0:Relaxed // @User: Advanced GSCALAR(fs_ekf_thresh, "FS_EKF_THRESH", FS_EKF_THRESHOLD_DEFAULT), @@ -425,18 +425,6 @@ const AP_Param::Info Copter::var_info[] = { // @User: Advanced GSCALAR(rc_speed, "RC_SPEED", RC_FAST_SPEED), - // @Param: ACRO_RP_P - // @DisplayName: Acro Roll and Pitch P gain - // @Description: Converts pilot roll and pitch into a desired rate of rotation in ACRO and SPORT mode. Higher values mean faster rate of rotation. - // @Range: 1 10 - // @User: Standard - - // @Param: ACRO_YAW_P - // @DisplayName: Acro Yaw P gain - // @Description: Converts pilot yaw input into a desired rate of rotation. Higher values mean faster rate of rotation. - // @Range: 1 10 - // @User: Standard - #if MODE_ACRO_ENABLED == ENABLED || MODE_SPORT_ENABLED == ENABLED // @Param: ACRO_BAL_ROLL // @DisplayName: Acro Balance Roll @@ -455,6 +443,8 @@ const AP_Param::Info Copter::var_info[] = { GSCALAR(acro_balance_pitch, "ACRO_BAL_PITCH", ACRO_BALANCE_PITCH), #endif + // ACRO_RP_EXPO moved to Command Model class + #if MODE_ACRO_ENABLED == ENABLED // @Param: ACRO_TRAINER // @DisplayName: Acro Trainer @@ -462,14 +452,6 @@ const AP_Param::Info Copter::var_info[] = { // @Values: 0:Disabled,1:Leveling,2:Leveling and Limited // @User: Advanced GSCALAR(acro_trainer, "ACRO_TRAINER", (uint8_t)ModeAcro::Trainer::LIMITED), - - // @Param: ACRO_RP_EXPO - // @DisplayName: Acro Roll/Pitch Expo - // @Description: Acro roll/pitch Expo to allow faster rotation when stick at edges - // @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High - // @Range: -0.5 0.95 - // @User: Advanced - GSCALAR(acro_rp_expo, "ACRO_RP_EXPO", ACRO_RP_EXPO_DEFAULT), #endif // variables not in the g class which contain EEPROM saved variables @@ -610,7 +592,7 @@ const AP_Param::Info Copter::var_info[] = { GOBJECT(sprayer, "SPRAY_", AC_Sprayer), #endif -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#if AP_SIM_ENABLED // @Group: SIM_ // @Path: ../libraries/SITL/SITL.cpp GOBJECT(sitl, "SIM_", SITL::SIM), @@ -629,12 +611,6 @@ const AP_Param::Info Copter::var_info[] = { // @Path: ../libraries/AP_Scheduler/AP_Scheduler.cpp GOBJECT(scheduler, "SCHED_", AP_Scheduler), -#if AC_FENCE == ENABLED - // @Group: FENCE_ - // @Path: ../libraries/AC_Fence/AC_Fence.cpp - GOBJECT(fence, "FENCE_", AC_Fence), -#endif - // @Group: AVOID_ // @Path: ../libraries/AC_Avoidance/AC_Avoid.cpp #if AC_AVOID_ENABLED == ENABLED @@ -698,7 +674,7 @@ const AP_Param::Info Copter::var_info[] = { #if AP_OPTICALFLOW_ENABLED // @Group: FLOW // @Path: ../libraries/AP_OpticalFlow/AP_OpticalFlow.cpp - GOBJECT(optflow, "FLOW", OpticalFlow), + GOBJECT(optflow, "FLOW", AP_OpticalFlow), #endif #if PRECISION_LANDING == ENABLED @@ -742,6 +718,12 @@ const AP_Param::Info Copter::var_info[] = { GOBJECT(osd, "OSD", AP_OSD), #endif +#if AC_CUSTOMCONTROL_MULTI_ENABLED == ENABLED + // @Group: CC + // @Path: ../libraries/AC_CustomControl/AC_CustomControl.cpp + GOBJECT(custom_control, "CC", AC_CustomControl), +#endif + // @Group: // @Path: Parameters.cpp GOBJECT(g2, "", ParametersG2), @@ -819,13 +801,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { AP_SUBGROUPINFO(proximity, "PRX", 8, ParametersG2, AP_Proximity), #endif - // @Param: ACRO_Y_EXPO - // @DisplayName: Acro Yaw Expo - // @Description: Acro yaw expo to allow faster rotation when stick at edges - // @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High - // @Range: -1.0 0.95 - // @User: Advanced - AP_GROUPINFO("ACRO_Y_EXPO", 9, ParametersG2, acro_y_expo, ACRO_Y_EXPO_DEFAULT), + // ACRO_Y_EXPO (9) moved to Command Model Class #if MODE_ACRO_ENABLED == ENABLED // @Param: ACRO_THR_MID @@ -915,7 +891,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @User: Advanced AP_GROUPINFO("LAND_ALT_LOW", 25, ParametersG2, land_alt_low, 1000), -#if !HAL_MINIMIZE_FEATURES && AP_OPTICALFLOW_ENABLED +#if MODE_FLOWHOLD_ENABLED == ENABLED // @Group: FHLD // @Path: mode_flowhold.cpp AP_SUBGROUPPTR(mode_flowhold_ptr, "FHLD", 26, ParametersG2, ModeFlowHold), @@ -1068,6 +1044,29 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { AP_GROUPINFO("GUID_TIMEOUT", 46, ParametersG2, guided_timeout, 3.0), #endif + // ACRO_PR_RATE (47), ACRO_Y_RATE (48), PILOT_Y_RATE (49) and PILOT_Y_EXPO (50) moved to command model class + + // @Param: SURFTRAK_MODE + // @DisplayName: Surface Tracking Mode + // @Description: set which surface to track in surface tracking + // @Values: 0:Do not track, 1:Ground, 2:Ceiling + // @User: Advanced + AP_GROUPINFO("SURFTRAK_MODE", 51, ParametersG2, surftrak_mode, (uint8_t)Copter::SurfaceTracking::Surface::GROUND), + + // @Param: FS_DR_ENABLE + // @DisplayName: DeadReckon Failsafe Action + // @Description: Failsafe action taken immediately as deadreckoning starts. Deadreckoning starts when EKF loses position and velocity source and relies only on wind estimates + // @Values: 0:Disabled/NoAction,1:Land, 2:RTL, 3:SmartRTL or RTL, 4:SmartRTL or Land, 6:Auto DO_LAND_START or RTL + // @User: Standard + AP_GROUPINFO("FS_DR_ENABLE", 52, ParametersG2, failsafe_dr_enable, (uint8_t)Copter::FailsafeAction::RTL), + + // @Param: FS_DR_TIMEOUT + // @DisplayName: DeadReckon Failsafe Timeout + // @Description: DeadReckoning is available for this many seconds after losing position and/or velocity source. After this timeout elapses the EKF failsafe will trigger in modes requiring a position estimate + // @Range: 0 120 + // @User: Standard + AP_GROUPINFO("FS_DR_TIMEOUT", 53, ParametersG2, failsafe_dr_timeout, 30), + #if MODE_ACRO_ENABLED == ENABLED || MODE_SPORT_ENABLED == ENABLED // @Param: ACRO_RP_RATE // @DisplayName: Acro Roll and Pitch Rate @@ -1075,7 +1074,23 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Units: deg/s // @Range: 1 1080 // @User: Standard - AP_GROUPINFO("ACRO_RP_RATE", 47, ParametersG2, acro_rp_rate, ACRO_RP_RATE_DEFAULT), + + // @Param: ACRO_RP_EXPO + // @DisplayName: Acro Roll/Pitch Expo + // @Description: Acro roll/pitch Expo to allow faster rotation when stick at edges + // @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High + // @Range: -0.5 0.95 + // @User: Advanced + + // @Param: ACRO_RP_RATE_TC + // @DisplayName: Acro roll/pitch rate control input time constant + // @Description: Acro roll and pitch rate control input time constant. Low numbers lead to sharper response, higher numbers to softer response + // @Units: s + // @Range: 0 1 + // @Increment: 0.01 + // @Values: 0.5:Very Soft, 0.2:Soft, 0.15:Medium, 0.1:Crisp, 0.05:Very Crisp + // @User: Standard + AP_SUBGROUPINFO(command_model_acro_rp, "ACRO_RP_", 54, ParametersG2, AC_CommandModel), #endif #if MODE_ACRO_ENABLED == ENABLED || MODE_DRIFT_ENABLED == ENABLED @@ -1085,7 +1100,23 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Units: deg/s // @Range: 1 360 // @User: Standard - AP_GROUPINFO("ACRO_Y_RATE", 48, ParametersG2, acro_y_rate, ACRO_Y_RATE_DEFAULT), + + // @Param: ACRO_Y_EXPO + // @DisplayName: Acro Yaw Expo + // @Description: Acro yaw expo to allow faster rotation when stick at edges + // @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High + // @Range: -1.0 0.95 + // @User: Advanced + + // @Param: ACRO_Y_RATE_TC + // @DisplayName: Acro yaw rate control input time constant + // @Description: Acro yaw rate control input time constant. Low numbers lead to sharper response, higher numbers to softer response + // @Units: s + // @Range: 0 1 + // @Increment: 0.01 + // @Values: 0.5:Very Soft, 0.2:Soft, 0.15:Medium, 0.1:Crisp, 0.05:Very Crisp + // @User: Standard + AP_SUBGROUPINFO(command_model_acro_y, "ACRO_Y_", 55, ParametersG2, AC_CommandModel), #endif // @Param: PILOT_Y_RATE @@ -1094,7 +1125,6 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Units: deg/s // @Range: 1 360 // @User: Standard - AP_GROUPINFO("PILOT_Y_RATE", 49, ParametersG2, pilot_y_rate, PILOT_Y_RATE_DEFAULT), // @Param: PILOT_Y_EXPO // @DisplayName: Pilot controlled yaw expo @@ -1102,14 +1132,36 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High // @Range: -0.5 1.0 // @User: Advanced - AP_GROUPINFO("PILOT_Y_EXPO", 50, ParametersG2, pilot_y_expo, PILOT_Y_EXPO_DEFAULT), - // @Param: SURFTRAK_MODE - // @DisplayName: Surface Tracking Mode - // @Description: set which surface to track in surface tracking - // @Values: 0:Do not track, 1:Ground, 2:Ceiling - // @User: Advanced - AP_GROUPINFO("SURFTRAK_MODE", 51, ParametersG2, surftrak_mode, (uint8_t)Copter::SurfaceTracking::Surface::GROUND), + // @Param: PILOT_Y_RATE_TC + // @DisplayName: Pilot yaw rate control input time constant + // @Description: Pilot yaw rate control input time constant. Low numbers lead to sharper response, higher numbers to softer response + // @Units: s + // @Range: 0 1 + // @Increment: 0.01 + // @Values: 0.5:Very Soft, 0.2:Soft, 0.15:Medium, 0.1:Crisp, 0.05:Very Crisp + // @User: Standard + AP_SUBGROUPINFO(command_model_pilot, "PILOT_Y_", 56, ParametersG2, AC_CommandModel), + + // @Param: TKOFF_SLEW_TIME + // @DisplayName: Slew time of throttle during take-off + // @Description: Time to slew the throttle from minimum to maximum while checking for a succsessful takeoff. + // @Units: s + // @Range: 0.25 5.0 + // @User: Standard + AP_GROUPINFO("TKOFF_SLEW_TIME", 57, ParametersG2, takeoff_throttle_slew_time, 2.0), + +#if HAL_WITH_ESC_TELEM && FRAME_CONFIG != HELI_FRAME + // @Param: TKOFF_RPM_MIN + // @DisplayName: Takeoff Check RPM minimum + // @Description: Takeoff is not permitted until motors report at least this RPM. Set to zero to disable check + // @Range: 0 10000 + // @User: Standard + AP_GROUPINFO("TKOFF_RPM_MIN", 58, ParametersG2, takeoff_rpm_min, 0), +#endif + + // ID 62 is reserved for the SHOW_... parameters from the Skybrush fork at + // https://github.com/skybrush-io/ardupilot AP_GROUPEND }; @@ -1120,7 +1172,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { ParametersG2::ParametersG2(void) : temp_calibration() // this doesn't actually need constructing, but removing it here is problematic syntax-wise #if BEACON_ENABLED == ENABLED - , beacon(copter.serial_manager) + , beacon() #endif #if HAL_PROXIMITY_ENABLED , proximity() @@ -1131,7 +1183,7 @@ ParametersG2::ParametersG2(void) #if MODE_SMARTRTL_ENABLED == ENABLED ,smart_rtl() #endif -#if !HAL_MINIMIZE_FEATURES && AP_OPTICALFLOW_ENABLED +#if MODE_FLOWHOLD_ENABLED == ENABLED ,mode_flowhold_ptr(&copter.mode_flowhold) #endif #if MODE_FOLLOW_ENABLED == ENABLED @@ -1155,6 +1207,16 @@ ParametersG2::ParametersG2(void) #if MODE_ZIGZAG_ENABLED == ENABLED ,mode_zigzag_ptr(&copter.mode_zigzag) #endif + +#if MODE_ACRO_ENABLED == ENABLED || MODE_SPORT_ENABLED == ENABLED + ,command_model_acro_rp(ACRO_RP_RATE_DEFAULT, ACRO_RP_EXPO_DEFAULT, 0.0f) +#endif + +#if MODE_ACRO_ENABLED == ENABLED || MODE_DRIFT_ENABLED == ENABLED + ,command_model_acro_y(ACRO_Y_RATE_DEFAULT, ACRO_Y_EXPO_DEFAULT, 0.0f) +#endif + + ,command_model_pilot(PILOT_Y_RATE_DEFAULT, PILOT_Y_EXPO_DEFAULT, 0.0f) { AP_Param::setup_object_defaults(this, var_info); } @@ -1173,30 +1235,37 @@ ParametersG2::ParametersG2(void) old object. This should be zero for top level parameters. */ const AP_Param::ConversionInfo conversion_table[] = { + // PARAMETER_CONVERSION - Added: Oct-2014 { Parameters::k_param_log_bitmask_old, 0, AP_PARAM_INT16, "LOG_BITMASK" }, + // PARAMETER_CONVERSION - Added: Jan-2015 { Parameters::k_param_serial0_baud, 0, AP_PARAM_INT16, "SERIAL0_BAUD" }, { Parameters::k_param_serial1_baud, 0, AP_PARAM_INT16, "SERIAL1_BAUD" }, { Parameters::k_param_serial2_baud, 0, AP_PARAM_INT16, "SERIAL2_BAUD" }, + // PARAMETER_CONVERSION - Added: Jan-2017 { Parameters::k_param_arming_check_old, 0, AP_PARAM_INT8, "ARMING_CHECK" }, // battery + // PARAMETER_CONVERSION - Added: Mar-2018 { Parameters::k_param_fs_batt_voltage, 0, AP_PARAM_FLOAT, "BATT_LOW_VOLT" }, { Parameters::k_param_fs_batt_mah, 0, AP_PARAM_FLOAT, "BATT_LOW_MAH" }, { Parameters::k_param_failsafe_battery_enabled,0, AP_PARAM_INT8, "BATT_FS_LOW_ACT" }, + // PARAMETER_CONVERSION - Added: Aug-2018 { Parameters::Parameters::k_param_ch7_option_old, 0, AP_PARAM_INT8, "RC7_OPTION" }, { Parameters::Parameters::k_param_ch8_option_old, 0, AP_PARAM_INT8, "RC8_OPTION" }, { Parameters::Parameters::k_param_ch9_option_old, 0, AP_PARAM_INT8, "RC9_OPTION" }, { Parameters::Parameters::k_param_ch10_option_old, 0, AP_PARAM_INT8, "RC10_OPTION" }, { Parameters::Parameters::k_param_ch11_option_old, 0, AP_PARAM_INT8, "RC11_OPTION" }, { Parameters::Parameters::k_param_ch12_option_old, 0, AP_PARAM_INT8, "RC12_OPTION" }, + // PARAMETER_CONVERSION - Added: Apr-2019 { Parameters::k_param_compass_enabled_deprecated, 0, AP_PARAM_INT8, "COMPASS_ENABLE" }, + // PARAMETER_CONVERSION - Added: Jul-2019 { Parameters::k_param_arming, 2, AP_PARAM_INT16, "ARMING_CHECK" }, }; void Copter::load_parameters(void) { if (!AP_Param::check_var_info()) { - hal.console->printf("Bad var table\n"); + DEV_PRINTF("Bad var table\n"); AP_HAL::panic("Bad var table"); } @@ -1206,14 +1275,15 @@ void Copter::load_parameters(void) g.format_version != Parameters::k_format_version) { // erase all parameters - hal.console->printf("Firmware change: erasing EEPROM...\n"); + DEV_PRINTF("Firmware change: erasing EEPROM...\n"); StorageManager::erase(); AP_Param::erase_all(); // save the current format version g.format_version.set_and_save(Parameters::k_format_version); - hal.console->printf("done.\n"); + DEV_PRINTF("done.\n"); } + g.format_version.set_default(Parameters::k_format_version); uint32_t before = micros(); // Load all auto-loaded EEPROM variables @@ -1222,16 +1292,24 @@ void Copter::load_parameters(void) #if LANDING_GEAR_ENABLED == ENABLED // convert landing gear parameters + // PARAMETER_CONVERSION - Added: Nov-2018 convert_lgr_parameters(); #endif // convert fs_options parameters + // PARAMETER_CONVERSION - Added: Nov-2019 convert_fs_options_params(); #if MODE_RTL_ENABLED == ENABLED + // PARAMETER_CONVERSION - Added: Sep-2021 g.rtl_altitude.convert_parameter_width(AP_PARAM_INT16); #endif + // PARAMETER_CONVERSION - Added: Mar-2022 +#if AP_FENCE_ENABLED + AP_Param::convert_class(g.k_param_fence_old, &fence, fence.var_info, 0, 0, true); +#endif + hal.console->printf("load_all took %uus\n", (unsigned)(micros() - before)); // setup AP_Param frame type flags @@ -1244,6 +1322,7 @@ void Copter::convert_pid_parameters(void) { // conversion info const AP_Param::ConversionInfo pid_conversion_info[] = { + // PARAMETER_CONVERSION - Added: Apr-2016 { Parameters::k_param_pid_rate_roll, 0, AP_PARAM_FLOAT, "ATC_RAT_RLL_P" }, { Parameters::k_param_pid_rate_roll, 1, AP_PARAM_FLOAT, "ATC_RAT_RLL_I" }, { Parameters::k_param_pid_rate_roll, 2, AP_PARAM_FLOAT, "ATC_RAT_RLL_D" }, @@ -1254,16 +1333,19 @@ void Copter::convert_pid_parameters(void) { Parameters::k_param_pid_rate_yaw, 1, AP_PARAM_FLOAT, "ATC_RAT_YAW_I" }, { Parameters::k_param_pid_rate_yaw, 2, AP_PARAM_FLOAT, "ATC_RAT_YAW_D" }, #if FRAME_CONFIG == HELI_FRAME + // PARAMETER_CONVERSION - Added: May-2016 { Parameters::k_param_pid_rate_roll, 4, AP_PARAM_FLOAT, "ATC_RAT_RLL_VFF" }, { Parameters::k_param_pid_rate_pitch, 4, AP_PARAM_FLOAT, "ATC_RAT_PIT_VFF" }, { Parameters::k_param_pid_rate_yaw , 4, AP_PARAM_FLOAT, "ATC_RAT_YAW_VFF" }, #endif }; const AP_Param::ConversionInfo imax_conversion_info[] = { + // PARAMETER_CONVERSION - Added: Apr-2016 { Parameters::k_param_pid_rate_roll, 5, AP_PARAM_FLOAT, "ATC_RAT_RLL_IMAX" }, { Parameters::k_param_pid_rate_pitch, 5, AP_PARAM_FLOAT, "ATC_RAT_PIT_IMAX" }, { Parameters::k_param_pid_rate_yaw, 5, AP_PARAM_FLOAT, "ATC_RAT_YAW_IMAX" }, #if FRAME_CONFIG == HELI_FRAME + // PARAMETER_CONVERSION - Added: May-2016 { Parameters::k_param_pid_rate_roll, 7, AP_PARAM_FLOAT, "ATC_RAT_RLL_ILMI" }, { Parameters::k_param_pid_rate_pitch, 7, AP_PARAM_FLOAT, "ATC_RAT_PIT_ILMI" }, { Parameters::k_param_pid_rate_yaw, 7, AP_PARAM_FLOAT, "ATC_RAT_YAW_ILMI" }, @@ -1271,36 +1353,46 @@ void Copter::convert_pid_parameters(void) }; // conversion from Copter-3.3 to Copter-3.4 const AP_Param::ConversionInfo angle_and_filt_conversion_info[] = { + // PARAMETER_CONVERSION - Added: May-2016 { Parameters::k_param_p_stabilize_roll, 0, AP_PARAM_FLOAT, "ATC_ANG_RLL_P" }, { Parameters::k_param_p_stabilize_pitch, 0, AP_PARAM_FLOAT, "ATC_ANG_PIT_P" }, { Parameters::k_param_p_stabilize_yaw, 0, AP_PARAM_FLOAT, "ATC_ANG_YAW_P" }, + // PARAMETER_CONVERSION - Added: Apr-2016 { Parameters::k_param_pid_rate_roll, 6, AP_PARAM_FLOAT, "ATC_RAT_RLL_FILT" }, { Parameters::k_param_pid_rate_pitch, 6, AP_PARAM_FLOAT, "ATC_RAT_PIT_FILT" }, + // PARAMETER_CONVERSION - Added: Jan-2018 { Parameters::k_param_pid_rate_yaw, 6, AP_PARAM_FLOAT, "ATC_RAT_YAW_FILT" }, { Parameters::k_param_pi_vel_xy, 0, AP_PARAM_FLOAT, "PSC_VELXY_P" }, { Parameters::k_param_pi_vel_xy, 1, AP_PARAM_FLOAT, "PSC_VELXY_I" }, { Parameters::k_param_pi_vel_xy, 2, AP_PARAM_FLOAT, "PSC_VELXY_IMAX" }, + // PARAMETER_CONVERSION - Added: Aug-2021 { Parameters::k_param_pi_vel_xy, 3, AP_PARAM_FLOAT, "PSC_VELXY_FLTE" }, + // PARAMETER_CONVERSION - Added: Jan-2018 { Parameters::k_param_p_vel_z, 0, AP_PARAM_FLOAT, "PSC_VELZ_P" }, { Parameters::k_param_pid_accel_z, 0, AP_PARAM_FLOAT, "PSC_ACCZ_P" }, { Parameters::k_param_pid_accel_z, 1, AP_PARAM_FLOAT, "PSC_ACCZ_I" }, { Parameters::k_param_pid_accel_z, 2, AP_PARAM_FLOAT, "PSC_ACCZ_D" }, { Parameters::k_param_pid_accel_z, 5, AP_PARAM_FLOAT, "PSC_ACCZ_IMAX" }, + // PARAMETER_CONVERSION - Added: Oct-2019 { Parameters::k_param_pid_accel_z, 6, AP_PARAM_FLOAT, "PSC_ACCZ_FLTE" }, + // PARAMETER_CONVERSION - Added: Jan-2018 { Parameters::k_param_p_alt_hold, 0, AP_PARAM_FLOAT, "PSC_POSZ_P" }, { Parameters::k_param_p_pos_xy, 0, AP_PARAM_FLOAT, "PSC_POSXY_P" }, }; const AP_Param::ConversionInfo throttle_conversion_info[] = { + // PARAMETER_CONVERSION - Added: Jun-2016 { Parameters::k_param_throttle_min, 0, AP_PARAM_FLOAT, "MOT_SPIN_MIN" }, { Parameters::k_param_throttle_mid, 0, AP_PARAM_FLOAT, "MOT_THST_HOVER" } }; const AP_Param::ConversionInfo loiter_conversion_info[] = { + // PARAMETER_CONVERSION - Added: Apr-2018 { Parameters::k_param_wp_nav, 4, AP_PARAM_FLOAT, "LOIT_SPEED" }, { Parameters::k_param_wp_nav, 7, AP_PARAM_FLOAT, "LOIT_BRK_JERK" }, { Parameters::k_param_wp_nav, 8, AP_PARAM_FLOAT, "LOIT_ACC_MAX" }, { Parameters::k_param_wp_nav, 9, AP_PARAM_FLOAT, "LOIT_BRK_ACCEL" } }; + // PARAMETER_CONVERSION - Added: Apr-2016 // gains increase by 27% due to attitude controller's switch to use radians instead of centi-degrees // and motor libraries switch to accept inputs in -1 to +1 range instead of -4500 ~ +4500 float pid_scaler = 1.27f; @@ -1329,6 +1421,7 @@ void Copter::convert_pid_parameters(void) AP_Param::convert_old_parameter(&info, 0.001f); } // convert RC_FEEL_RP to ATC_INPUT_TC + // PARAMETER_CONVERSION - Added: Mar-2018 const AP_Param::ConversionInfo rc_feel_rp_conversion_info = { Parameters::k_param_rc_feel_rp, 0, AP_PARAM_INT8, "ATC_INPUT_TC" }; AP_Int8 rc_feel_rp_old; if (AP_Param::find_old_parameter(&rc_feel_rp_conversion_info, &rc_feel_rp_old)) { @@ -1342,6 +1435,7 @@ void Copter::convert_pid_parameters(void) // TradHeli default parameters #if FRAME_CONFIG == HELI_FRAME static const struct AP_Param::defaults_table_struct heli_defaults_table[] = { + // PARAMETER_CONVERSION - Added: Nov-2018 { "LOIT_ACC_MAX", 500.0f }, { "LOIT_BRK_ACCEL", 125.0f }, { "LOIT_BRK_DELAY", 1.0f }, @@ -1353,8 +1447,11 @@ void Copter::convert_pid_parameters(void) { "PSC_VELXY_D", 0.0f }, { "PSC_VELXY_I", 0.5f }, { "PSC_VELXY_P", 1.0f }, + // PARAMETER_CONVERSION - Added: Jan-2019 { "RC8_OPTION", 32 }, + // PARAMETER_CONVERSION - Added: Aug-2018 { "RC_OPTIONS", 0 }, + // PARAMETER_CONVERSION - Added: Feb-2022 { "ATC_RAT_RLL_ILMI", 0.05}, { "ATC_RAT_PIT_ILMI", 0.05}, }; @@ -1366,20 +1463,26 @@ void Copter::convert_pid_parameters(void) const AP_Param::ConversionInfo ff_and_filt_conversion_info[] = { #if FRAME_CONFIG == HELI_FRAME // tradheli moves ATC_RAT_RLL/PIT_FILT to FLTE, ATC_RAT_YAW_FILT to FLTE + // PARAMETER_CONVERSION - Added: Jul-2019 { Parameters::k_param_attitude_control, 386, AP_PARAM_FLOAT, "ATC_RAT_RLL_FLTE" }, { Parameters::k_param_attitude_control, 387, AP_PARAM_FLOAT, "ATC_RAT_PIT_FLTE" }, { Parameters::k_param_attitude_control, 388, AP_PARAM_FLOAT, "ATC_RAT_YAW_FLTE" }, #else // multicopters move ATC_RAT_RLL/PIT_FILT to FLTD & FLTT, ATC_RAT_YAW_FILT to FLTE { Parameters::k_param_attitude_control, 385, AP_PARAM_FLOAT, "ATC_RAT_RLL_FLTD" }, + // PARAMETER_CONVERSION - Added: Oct-2019 { Parameters::k_param_attitude_control, 385, AP_PARAM_FLOAT, "ATC_RAT_RLL_FLTT" }, + // PARAMETER_CONVERSION - Added: Jul-2019 { Parameters::k_param_attitude_control, 386, AP_PARAM_FLOAT, "ATC_RAT_PIT_FLTD" }, + // PARAMETER_CONVERSION - Added: Oct-2019 { Parameters::k_param_attitude_control, 386, AP_PARAM_FLOAT, "ATC_RAT_PIT_FLTT" }, + // PARAMETER_CONVERSION - Added: Jul-2019 { Parameters::k_param_attitude_control, 387, AP_PARAM_FLOAT, "ATC_RAT_YAW_FLTE" }, { Parameters::k_param_attitude_control, 449, AP_PARAM_FLOAT, "ATC_RAT_RLL_FF" }, { Parameters::k_param_attitude_control, 450, AP_PARAM_FLOAT, "ATC_RAT_PIT_FF" }, { Parameters::k_param_attitude_control, 451, AP_PARAM_FLOAT, "ATC_RAT_YAW_FF" }, #endif + // PARAMETER_CONVERSION - Added: Oct-2019 { Parameters::k_param_pos_control, 388, AP_PARAM_FLOAT, "PSC_ACCZ_FLTE" }, }; uint8_t filt_table_size = ARRAY_SIZE(ff_and_filt_conversion_info); @@ -1387,17 +1490,27 @@ void Copter::convert_pid_parameters(void) AP_Param::convert_old_parameters(&ff_and_filt_conversion_info[i], 1.0f); } - // notch filter parameter conversions (changed position and type) for Copter-3.7 - const AP_Param::ConversionInfo notchfilt_conversion_info[] = { - { Parameters::k_param_ins, 165, AP_PARAM_INT16, "INS_NOTCH_FREQ" }, - { Parameters::k_param_ins, 229, AP_PARAM_INT16, "INS_NOTCH_BW" }, - }; - uint8_t notchfilt_table_size = ARRAY_SIZE(notchfilt_conversion_info); - for (uint8_t i=0; i 1 + if (!ins.harmonic_notches[1].params.enabled()) { + // notch filter parameter conversions (moved to INS_HNTC2) for 4.2.x, converted from fixed notch + const AP_Param::ConversionInfo notchfilt_conversion_info[] { + // PARAMETER_CONVERSION - Added: Apr 2022 + { Parameters::k_param_ins, 101, AP_PARAM_INT8, "INS_HNTC2_ENABLE" }, + { Parameters::k_param_ins, 293, AP_PARAM_FLOAT, "INS_HNTC2_ATT" }, + { Parameters::k_param_ins, 357, AP_PARAM_FLOAT, "INS_HNTC2_FREQ" }, + { Parameters::k_param_ins, 421, AP_PARAM_FLOAT, "INS_HNTC2_BW" }, + }; + uint8_t notchfilt_table_size = ARRAY_SIZE(notchfilt_conversion_info); + for (uint8_t i=0; iconfigured_in_storage() || - servo_max->configured_in_storage() || - servo_trim->configured_in_storage() || - servo_reversed->configured_in_storage()) { + if (servo_min->configured() || + servo_max->configured() || + servo_trim->configured() || + servo_reversed->configured()) { // has been previously saved, don't upgrade return; } @@ -1498,6 +1653,7 @@ void Copter::convert_lgr_parameters(void) // handle conversion of tradheli parameters from Copter-3.6 to Copter-3.7 void Copter::convert_tradheli_parameters(void) const { + // PARAMETER_CONVERSION - Added: Mar-2019 if (g2.frame_class.get() == AP_Motors::MOTOR_FRAME_HELI) { // single heli conversion info const AP_Param::ConversionInfo singleheli_conversion_info[] = { @@ -1515,6 +1671,7 @@ void Copter::convert_tradheli_parameters(void) const } // convert to known swash type for setups that match + // PARAMETER_CONVERSION - Added: Sep-2019 AP_Int16 swash_pos_1, swash_pos_2, swash_pos_3, swash_phang; AP_Int8 swash_type; bool swash_pos1_exist = AP_Param::find_old_parameter(&singleheli_conversion_info[0], &swash_pos_1); @@ -1538,7 +1695,7 @@ void Copter::convert_tradheli_parameters(void) const // make sure the pointer is valid if (ap2 != nullptr) { // see if we can load it from EEPROM - if (!ap2->configured_in_storage()) { + if (!ap2->configured()) { // the new parameter is not in storage so set generic swash AP_Param::set_and_save_by_name("H_SW_TYPE", SwashPlateType::SWASHPLATE_TYPE_H3); } @@ -1551,12 +1708,17 @@ void Copter::convert_tradheli_parameters(void) const { Parameters::k_param_motors, 1, AP_PARAM_INT16, "H_SW_H3_SV1_POS" }, { Parameters::k_param_motors, 2, AP_PARAM_INT16, "H_SW_H3_SV2_POS" }, { Parameters::k_param_motors, 3, AP_PARAM_INT16, "H_SW_H3_SV3_POS" }, + // PARAMETER_CONVERSION - Added: Mar-2019 { Parameters::k_param_motors, 4, AP_PARAM_INT16, "H_SW2_H3_SV1_POS" }, { Parameters::k_param_motors, 5, AP_PARAM_INT16, "H_SW2_H3_SV2_POS" }, { Parameters::k_param_motors, 6, AP_PARAM_INT16, "H_SW2_H3_SV3_POS" }, + // PARAMETER_CONVERSION - Added: Sep-2019 { Parameters::k_param_motors, 7, AP_PARAM_INT16, "H_SW_H3_PHANG" }, + // PARAMETER_CONVERSION - Added: Mar-2019 { Parameters::k_param_motors, 8, AP_PARAM_INT16, "H_SW2_H3_PHANG" }, + // PARAMETER_CONVERSION - Added: Sep-2019 { Parameters::k_param_motors, 19, AP_PARAM_INT8, "H_SW_COL_DIR" }, + // PARAMETER_CONVERSION - Added: Mar-2019 { Parameters::k_param_motors, 19, AP_PARAM_INT8, "H_SW2_COL_DIR" }, }; @@ -1567,6 +1729,8 @@ void Copter::convert_tradheli_parameters(void) const } + // PARAMETER_CONVERSION - Added: Sep-2019 + // convert to known swash type for setups that match AP_Int16 swash1_pos_1, swash1_pos_2, swash1_pos_3, swash1_phang, swash2_pos_1, swash2_pos_2, swash2_pos_3, swash2_phang; bool swash1_pos1_exist = AP_Param::find_old_parameter(&dualheli_conversion_info[0], &swash1_pos_1); @@ -1589,7 +1753,7 @@ void Copter::convert_tradheli_parameters(void) const // make sure the pointer is valid if (ap2 != nullptr) { // see if we can load it from EEPROM - if (!ap2->configured_in_storage()) { + if (!ap2->configured()) { // the new parameter is not in storage so set generic swash AP_Param::set_and_save_by_name("H_SW_TYPE", SwashPlateType::SWASHPLATE_TYPE_H3); } @@ -1606,7 +1770,7 @@ void Copter::convert_tradheli_parameters(void) const // make sure the pointer is valid if (ap2 != nullptr) { // see if we can load it from EEPROM - if (!ap2->configured_in_storage()) { + if (!ap2->configured()) { // the new parameter is not in storage so set generic swash AP_Param::set_and_save_by_name("H_SW2_TYPE", SwashPlateType::SWASHPLATE_TYPE_H3); } @@ -1653,6 +1817,7 @@ void Copter::convert_tradheli_parameters(void) const AP_Param::set_and_save_by_name("H_TAIL_SPEED", tailspeed_pct ); } + // PARAMETER_CONVERSION - Added: Dec-2019 // table of stabilize collective parameters to be converted with scaling const AP_Param::ConversionInfo collhelipct_conversion_info[] = { { Parameters::k_param_input_manager, 1, AP_PARAM_INT16, "IM_STB_COL_1" }, @@ -1672,11 +1837,13 @@ void Copter::convert_tradheli_parameters(void) const void Copter::convert_fs_options_params(void) const { + // PARAMETER_CONVERSION - Added: Nov-2019 + // If FS_OPTIONS has already been configured and we don't change it. enum ap_var_type ptype; AP_Int32 *fs_opt = (AP_Int32 *)AP_Param::find("FS_OPTIONS", &ptype); - if (fs_opt == nullptr || fs_opt->configured_in_storage() || ptype != AP_PARAM_INT32) { + if (fs_opt == nullptr || fs_opt->configured() || ptype != AP_PARAM_INT32) { return; } diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index a8813e5dbe0..2f7221cec5b 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -128,7 +128,7 @@ class Parameters { k_param_rangefinder, // rangefinder object k_param_fs_ekf_thresh, k_param_terrain, - k_param_acro_rp_expo, + k_param_acro_rp_expo, // deprecated - remove k_param_throttle_deadzone, k_param_optflow, k_param_dcmcheck_thresh, // deprecated - remove @@ -143,7 +143,7 @@ class Parameters { k_param_gpslock_limit, // deprecated - remove k_param_geofence_limit, // deprecated - remove k_param_altitude_limit, // deprecated - remove - k_param_fence, + k_param_fence_old, // only used for conversion k_param_gps_glitch, // deprecated k_param_baro_glitch, // 71 - deprecated @@ -199,6 +199,7 @@ class Parameters { k_param_pos_control, k_param_circle_nav, k_param_loiter_nav, // 105 + k_param_custom_control, // 110: Telemetry control // @@ -362,7 +363,7 @@ class Parameters { k_param_pid_accel_z, // remove k_param_acro_balance_roll, k_param_acro_balance_pitch, - k_param_acro_yaw_p, + k_param_acro_yaw_p, // remove k_param_autotune_axis_bitmask, // remove k_param_autotune_aggressiveness, // remove k_param_pi_vel_xy, // remove @@ -469,7 +470,6 @@ class Parameters { #if MODE_ACRO_ENABLED == ENABLED // Acro parameters AP_Int8 acro_trainer; - AP_Float acro_rp_expo; #endif // Note: keep initializers here in the same order as they are declared @@ -539,8 +539,6 @@ class ParametersG2 { // developer options AP_Int32 dev_options; - // acro exponent parameters - AP_Float acro_y_expo; #if MODE_ACRO_ENABLED == ENABLED AP_Float acro_thr_mid; #endif @@ -627,6 +625,17 @@ class ParametersG2 { void *mode_zigzag_ptr; #endif + // command model parameters +#if MODE_ACRO_ENABLED == ENABLED || MODE_SPORT_ENABLED == ENABLED + AC_CommandModel command_model_acro_rp; +#endif + +#if MODE_ACRO_ENABLED == ENABLED || MODE_DRIFT_ENABLED == ENABLED + AC_CommandModel command_model_acro_y; +#endif + + AC_CommandModel command_model_pilot; + #if MODE_ACRO_ENABLED == ENABLED AP_Int8 acro_options; #endif @@ -655,18 +664,15 @@ class ParametersG2 { AP_Float guided_timeout; #endif -#if MODE_ACRO_ENABLED == ENABLED || MODE_SPORT_ENABLED == ENABLED - // Acro parameters - AP_Float acro_rp_rate; -#endif + AP_Int8 surftrak_mode; + AP_Int8 failsafe_dr_enable; + AP_Int16 failsafe_dr_timeout; -#if MODE_ACRO_ENABLED == ENABLED || MODE_DRIFT_ENABLED == ENABLED - AP_Float acro_y_rate; + // ramp time of throttle during take-off + AP_Float takeoff_throttle_slew_time; +#if HAL_WITH_ESC_TELEM && FRAME_CONFIG != HELI_FRAME + AP_Int16 takeoff_rpm_min; #endif - - AP_Float pilot_y_rate; - AP_Float pilot_y_expo; - AP_Int8 surftrak_mode; }; extern const AP_Param::Info var_info[]; diff --git a/ArduCopter/RC_Channel.cpp b/ArduCopter/RC_Channel.cpp index 5230f617376..dfad573d6ec 100644 --- a/ArduCopter/RC_Channel.cpp +++ b/ArduCopter/RC_Channel.cpp @@ -120,6 +120,7 @@ void RC_Channel_Copter::init_aux_function(const aux_func_t ch_option, const AuxS case AUX_FUNC::WINCH_ENABLE: case AUX_FUNC::AIRMODE: case AUX_FUNC::FORCEFLYING: + case AUX_FUNC::CUSTOM_CONTROLLER: run_aux_function(ch_option, ch_flag, AuxFuncTriggerSource::INIT); break; default: @@ -268,15 +269,15 @@ bool RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const AuxSwi #if MODE_ACRO_ENABLED == ENABLED switch(ch_flag) { case AuxSwitchPos::LOW: - copter.g.acro_trainer = (uint8_t)ModeAcro::Trainer::OFF; + copter.g.acro_trainer.set((uint8_t)ModeAcro::Trainer::OFF); AP::logger().Write_Event(LogEvent::ACRO_TRAINER_OFF); break; case AuxSwitchPos::MIDDLE: - copter.g.acro_trainer = (uint8_t)ModeAcro::Trainer::LEVELING; + copter.g.acro_trainer.set((uint8_t)ModeAcro::Trainer::LEVELING); AP::logger().Write_Event(LogEvent::ACRO_TRAINER_LEVELING); break; case AuxSwitchPos::HIGH: - copter.g.acro_trainer = (uint8_t)ModeAcro::Trainer::LIMITED; + copter.g.acro_trainer.set((uint8_t)ModeAcro::Trainer::LIMITED); AP::logger().Write_Event(LogEvent::ACRO_TRAINER_LIMITED); break; } @@ -326,11 +327,9 @@ bool RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const AuxSwi switch (ch_flag) { case AuxSwitchPos::LOW: copter.parachute.enabled(false); - AP::logger().Write_Event(LogEvent::PARACHUTE_DISABLED); break; case AuxSwitchPos::MIDDLE: copter.parachute.enabled(true); - AP::logger().Write_Event(LogEvent::PARACHUTE_ENABLED); break; case AuxSwitchPos::HIGH: copter.parachute.enabled(true); @@ -613,6 +612,12 @@ bool RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const AuxSwi } break; +#if AC_CUSTOMCONTROL_MULTI_ENABLED == ENABLED + case AUX_FUNC::CUSTOM_CONTROLLER: + copter.custom_control.set_custom_controller(ch_flag == AuxSwitchPos::HIGH); + break; +#endif + default: return RC_Channel::do_aux_function(ch_option, ch_flag); } diff --git a/ArduCopter/ReleaseNotes.txt b/ArduCopter/ReleaseNotes.txt index b8e04a380e3..aa935999b31 100644 --- a/ArduCopter/ReleaseNotes.txt +++ b/ArduCopter/ReleaseNotes.txt @@ -1,6 +1,465 @@ ArduPilot Copter Release Notes: ------------------------------------------------------------------ -Copter 4.2.0-rc1 28-Feb-2022 +Copter 4.3.8-beta1 12-Aug-2023 +Changes from 4.3.7 +1) Bug fixes + - DroneCAN GPS RTK injection fix + - INAxxx battery monitors allow for battery reset remaining + - Notch filter gyro glitch caused by race condition fixed + - Scripting restart memory corruption bug fixed +------------------------------------------------------------------ +Copter 4.3.7 31-May-2023 / 4.3.7-beta1 24-May-2023 +Changes from 4.3.6 +1) Bug fixes + a) EKF3 accel bias calculations bug fix + b) EKF3 accel bias process noise adjusted for greater robustness + c) GSF yaw numerical stability fix caused by compassmot + d) INS batch sampler fix to avoid watchdog if INS_LOG_BAT_CNT changed without rebooting + e) Memory corruption bug in the STM32H757 (very rare) + f) RC input on IOMCU bug fix (RC might not be regained if lost) +------------------------------------------------------------------ +Copter 4.3.6 05-Apr-2023 / 4.3.6-beta1, 4.3.6--beta2 27-Mar-2023 +Changes from 4.3.5 +1) Bi-directional DShot fix for possible motor stop approx 72min after startup +------------------------------------------------------------------ +Copter Copter 4.3.5 14-Mar-2023 / 4.3.5-rc1 01-Mar-2023 +Changes from 4.3.4 +1) Bug fixes + a) GPS unconfigured error fix for non-M10 uBlox GPS + b) Gremsy gimbal fix when attached to autopilot's serial3 (or higher) + c) Landing detector fix with large AHRS_TRIM values (>0.1) + d) MambaF405 2022 gets VTX power on support + e) MCU voltage enabled on H757 CPUs (including CubeOrangePlus) + f) PiccoloCAN fix for ESC voltage and current scaling + g) Servo gimbal mount yaw handling fix (only affects 3-axis servo gimbals) +------------------------------------------------------------------ +Copter 4.3.4 01-Mar-2023 +Changes from 4.3.4-rc1 +1) Lua script PWMSource feature disabled (will be back in 4.4.x) +------------------------------------------------------------------ +Copter 4.3.4-rc1 14-Feb-2023 +Changes from 4.3.3 +1) AutoPilot specific enhancements + a) CubeOrangePlusBG support + b) Foxeer ReaperF745 supports external compass + c) MambaH743v4 supports VTX power +2) Precision landing option to resume tracking target after pilot repositioning +3) Bug fixes + a) Arming check fix for terrain following with rangefinder (failed if terrain db was disabled) + b) Arming check fix if BARO_FIELD_ELEV set + c) Compass calibration diagonals set to 1,1,1 if incorrectly set to 0,0,0 + d) FFT notch tune feature disabled (will be re-released in 4.4) + e) Gimbal's yaw feed-forward set to zero when landed (affects Gremsy gimbals) + f) IOMCU double reset and safety disable fix + g) Logging fix for duplicate format messages + h) OpenDroneId sets emergency status on crash or chute deploy + i) Peripheral firmware updates using MAVCAN fixed + j) RC protocol cannot be changed once detected on boards with IOMCU + k) Surface tracking uses filtered and corrected rangefinder values +------------------------------------------------------------------ +Copter 4.3.3 20-Jan-2023 +Changes from 4.3.3-rc1 +1) Bug fixes + a) MAVFTP fix to terminate session error (could cause FTP failures) + b) IMU fast fifo reset log message max frequency reduced +------------------------------------------------------------------ +Copter 4.3.3-rc1 09-Jan-2023 +Changes from 4.3.2 +1) Autopilot related changes + a) AIRLink LTE module enable pin and HEAT_ params added + b) CUAV Nora/Nora+ bdshot firmware (allows Bi-directional DShot) + c) CubeOrange, CubeYellow gets fast reset of ICM20602 + d) MambaH743v2 with dual ICM42688 supported + e) PixPilot-V6 +2) Attitude and Navigation controllers use real-time dt (better handles variable or slow main loop) +3) MAVFTP speed improvement including faster param download +4) Bug fixes + a) Analog rangefinder GPIO pin arming check fixed + b) Arming check of AHRS/EKF vs GPS location disabled if GPS disabled + c) CRSF gets RC_OPTIONS for ELRS baudrate to avoid RC failsafes + d) Null pointer checks avoid watchdog when out of memory + e) Position Controller limit handling improved to avoid overshooting and hard landings + f) Position Controller internal error after 70min of flight fixed + g) PSC_ANGLE_MAX param reduction causing WPNAV_ACCEL to be set too low fixed + h) Servo gimbal yaw jump to opposite side fixed + i) Siyi A8 gimbal driver's record video feature fixed + j) SToRM32 serial gimbal driver actual angle reporting fixed (pitch and yaw angle signs were reversed) + k) Takeoff in Auto, Guided fixed when target altitude is current altitude + l) Takeoff in Auto handles baro drift before takeoff + m) Takeoff twitch due to velocity integrator init bug fixed +------------------------------------------------------------------ +Copter 4.3.2 23-Dec-2022 +Changes from 4.3.2-rc1 +1) Reverted arming check that main loop is running at configured speed (e.g. SCHED_LOOP_RATE) +------------------------------------------------------------------ +Copter 4.3.2-rc1 10-Dec-2022 +Changes from 4.3.1 +1) Arming check that main loop is running at configured speed (e.g. SCHED_LOOP_RATE) +2) uBlox M10 support +3) Autopilot specific changes + a) CubeOrange defaults to using 2nd IMU as primary + b) SIRF and SBP GPS disabled on BeastF7v2, MatekF405-STD, MAtekF405-Wing, omnibusf4pro +4) Bug fixes + a) AutoTune gains loaded correctly during pilot testing + b) Camera driver's CAM_MIN_INTERVAL fixed if pilot manually triggers extra picture + c) EKF3 fix when using EK3_RNG_USE_HGT/SPD params and rangefinder provides bad readings + d) Main loop slowdown after arming fixed (parameter logging was causing delays) + e) Main loop's fast tasks always run (caused twitches in Loiter on heavily loaded CPUs) + f) MAVLink commands received on private channels checked for valid target sysid + g) ModalAI cameras support fixed (ODOMETRY message frame was consumed incorrectly) + h) Param reset after firmware load fixed on these boards + - BeastF7v2 + - CubeYellow-bdshot + - f405-MatekAirspeed + - FlywooF745Nano + - KakuteF4Mini + - KakuteF7-bdshot + - MatekF405-bdshot + - MatekF405-STD + - MatekF405-Wing-bdshot + - MatekF765-SE + - MatekF765-Wing-bdshot + i) Siyi A8 gimbal support fixed + j) Windows builds move to compiling only 64-bit executables +------------------------------------------------------------------ +Copter 4.3.1 05-Dec-2022 / 4.3.1-rc1 17-Nov-2022 +Changes from 4.3.0 +1) Autopilot specific enhancements + a) ARKV6X support + b) MatekH743 supports 8 bi-directional dshot channels + c) Pixhawk boards support MS5607 baros + d) SpeedbyBee F405v3 support +2) DroneCAN Airspeed sensor support including hygrometer (aka water vapour) readings +3) EFI support (electronic fuel injection engines) +4) Pre-arm warning if multiple UARTs with SERIALx_PROTOCOL = RCIN +5) Siyi gimbal support +6) Bug fixes + a) Arm check warning loses duplicate "AHRS" prefix + b) AtomRCF405NAVI bootloader file name fixed + c) BRD_SAFETY_MASK fixed on boards with both FMU safety switch and IOMCU + d) Compass calibration continues even if a single compass's cal fails + e) Gremsy gimbal driver sends autopilot info at lower rate to save bandwidth + f) Invensense 42605 and 42609 IMUs use anti-aliasing filter and notch filter + g) Mode change to AUTOTUNE message shortened + h) OSD stats screen fix + i) RC input on serial port uses first UART with SERIALx_PROTOCOL = 23 (was using last) + j) RunCam caching fix with enablement and setup on 3-pos switch + k) RTK CAN GPS fix when GPSs conneted to separate CAN ports on autopilot + l) SkyViper GPS fix + m) Turtle mode safety fixes (e.g. can only enter Tutle mode with at zero throttle) +------------------------------------------------------------------ +Copter 4.3.0 31-Oct-2022 / 4.3.0-beta4 24-Oct-2022 +Changes from 4.3.0-beta3 +1) Scripting supports implementing AUX functions +2) Bug fixes + a) BMI085 accel scaling fixed + b) Build with gcc 11.3 fixed (developer only) + c) EKF3 alt discrepancy if GPS or baro alt changed soon after startup fixed + d) Harmonic Notch and ESC telem fix when motor outputs are non-contiguous + e) NMEA GPS's KSXT message parsing fixed (affected position accuracy) + f) Scripting random number generator fix +------------------------------------------------------------------ +Copter 4.3.0-beta3 14-Oct-2022 +Changes from 4.3.0-beta2 +1) Pixhawk1-1M, fmuv2, fmuv3 display warning if firmware mismatches board's flash size (1M and 2M) +2) Scripting support for multi-byte i2c reads +3) Bug fixes + a) Airspeed CAN sensor ordering fixed (ordering could change if using multiple airspeed sensors) + b) BRD_SAFETY_MASK fix for enabling outputs when safety is on + c) Defaults.parm file processing fixed when a line has >100 characters and/or no new line (developer only) + d) NMEA serial output precision fixed (was only accurate to 1m, now accurate to 1cm) +------------------------------------------------------------------ +Copter 4.3.0-beta2 4-Oct-2022 +Changes from 4.3.0-beta1 +1) Autopilot specific fixes and enhancements + a) AIRLink autopilot supports UART2 + b) CUAV V6X supports CAN battery monitor by default + c) MatekF405-CAN board uses less memory to fix compass calibration issues + d) Pixhawk1-1M only supports uBlox and NMEA GPSs to save flash space + e) SkystarsH7HD-bdshot (allows Bi-directional DShot) + f) SkystarsH7HD supports VTX power by default +2) EFI support + a) Currawong ECU support (added as Electronic Fuel Injection driver) + b) Scripting support for EFI drivers (allows writing EFI drivers in Lua) + c) SkyPower and HFE CAN EFI drivers (via scripting) +3) Safety features + a) Arming check that SPIN_MIN less than 0.3 and greater than SPIN_ARM +4) Minor enhancements + a) Autopilot board names max length increased to 23 characters (was 13) + b) CAN actuators can report PWM equivalent values (eases debugging) + c) Log download speed improved for boards with "block" backends + d) Notch filter slew limit reduces chance of notch freq moving incorrectly + e) SLCAN disabled when vehicle is armed to reduce CPU load +5) Bug fixes + a) DO_JUMP mission command fixed if active command changed before changing to Auto mode + b) EKF3 altitude error fix when using dual GPSs and affinity enabled + c) FFT indexing bug fixed + d) Gimbal mount fix to default mode (see MNTx_DEFLT_MODE parameter) + e) MSP fix to report arm status to DJI FPV goggles + f) Notch fix for non-throttle notch (was being incorrectly disabled) + g) OSD fixes for params, font and resolution + h) RPM reporting from harmonic notch fixed + i) "Sending unknown message (50)" warning removed + j) SBF/GSOF/NOVA GPS auto detction of baud rate fixed + k) VideoTX fixes for buffer overruns and Tramp video transmitter support +------------------------------------------------------------------ +Copter 4.3.0-beta1 14-Sep-2022 +Changes from 4.2.3 +1) New autopilot support + a) AtomRCF405 + b) CubeOrange-SimOnHardWare + c) DevEBoxH7v2 + d) KakuteH7Mini-Nand + e) KakuteH7v2 + f) Mamba F405 Mk4 + g) SkystarsH7HD + h) bi-directional dshot (aka "bdshot") versions for CubeOrange, CubeYellow, KakuteF7, KakuteH7, MatekF405-Wing, Matek F765, PH4-mini, Pixhawk-1M +2) EKF enhancements and fixes + a) EK3_GPS_VACC_MAX threshold to control when GPS altitude is used as alt source + b) EKF ring buffer fix for very slow sensor updates (those that update once every few seconds) + c) EKF3 source set change captured in Replay logs +3) Gimbal enhancements + a) Angle limit params renamed and scaled to degrees (e.g. MNT1_ROLL_MIN, MNT1_PITCH_MIN, etc) + b) BrushlessPWM driver (set MNT1_TYPE = 7) is unstabilized Servo driver + c) Dual mount support (see MNT1_, MNT2 params) + d) Gremsy driver added (set MNT1_TYPE = 6) + e) MAVLink gimbalv2 support including sending GIMBAL_DEVICE_STATUS_UPDATE (replaces MOUNT_STATUS message) + f) "Mount Lock" auxiliary switch supports follow and lock modes in RC targetting (aka earth-frame and body-frame) + g) RC channels to control gimbal set using RCx_OPTION = 212 (Roll), 213 (Pitch) or 214 (Yaw) + h) RC targetting rotation rate in deg/sec (see MNT1_RC_RATE which replaces MNT_JSTICK_SPD) + i) Yaw can be disabled on 3-axis gimbals (set MNTx_YAW_MIN = MNTx_YAW_MAX) +4) Navigation and Flight mode enhancements + a) Auto mode ATTITUDE_TIME command allows specifying lean angle for specified number of seconds (GPS not required) + b) Auto mode support of DO_GIMBAL_MANAGER_PITCHYAW command + c) Auto mode LOITER_TURNS command max radius increased to 2.5km + d) AutoTune allows higher ANGLE_P gains + e) Guided mode support DO_CHANGE_SPEED commands + f) Manual modes throttle mix reduced (improves landing) + g) Payload touchdown detection reliability improved + h) Takeoff detection improved to reduce chance of flip before takeoff if GPS moves + i) TKOFF_SLEW_TIME allows slower takeoffs in Auto, Guided, etc +5) Notch filter enhancements + a) Attitude and filter logging at main loop rate + b) Batch sampler logging both pre and post-filter + c) FFT frame averaging + d) In-flight throttle notch parameter learning using averaged FFTs + e) Triple harmonic notch +5) RemoteId and SecureBoot enhancements + a) Remote update of secure boot's public keys (also allows remote unlocking of bootloader) +6) Safety enhancements + a) Arming checks of FRAME_CLASS/TYPE made mandatory (even if ARMING_CHECK=0) + b) crash_dump.bin file saved to SD Card on startup (includes details re cause of software failures) + c) Dead-reckoning for 30sec on loss of GPS (requires wind estimation be enabled) + d) Dead-reckoning Lua script (On loss of GPS flies towards home for specified number of seconds) + e) Disabling Fence clears any active breaches (e.g. FENCE_TYPE = 0 will clear breaches) + f) "GPS Glitch" message clarified to "GPS Glitch or Compass error" + g) Pre-arm check that configured AHRS is being used (e.g. checks AHRS_EKF_TYPE not changed since boot) + h) Pre-arm check that gimbals are healthy (currently only for Gremsy gimbals, others in future release) + i) Pre-arm check that all motors are setup + j) Pre-arm check that scripts are running + k) Pre-arm check that terrain data loaded if RTL_ALT_TYPE set to Terrain + l) Pre-arm messages are correctly prefixed with "PreArm:" (instead of "Arm:") + m) RC auxiliary switch option for Arm / Emergency Stop + n) RC failsafe made pre-arm check (previously only triggered at arming) + o) RC failsafe option (see FS_OPTIONS) to continue in Guided obeyed even if GCS failsafe disabled + p) TKOFF_RPM_MIN checks all motors spinning before takeoff + q) Vibration compensation disabled in manual modes +7) Scripting enhancements + a) CAN2 port bindings to allow scripts to communicate on 2nd CAN bus + b) ESC RPM bindings to allow scripts to report engine RPM + c) Gimbal bingings to allow scripts to control gimbal + d) Pre-arm check bindings (allows scripts to check if pre-arm checks have passed) + e) Semicolon (:) and period (.) supported (e.g both Logger:write() and Logger.write will work) +8) Sensor driver enhancements + a) Benewake H30 radar support + b) BMI270 IMU performance improvements + c) IRC Tramp VTX suppor + d) Logging pause-able with auxiliary switch. see RCx_OPTION = 165 (Pause Stream Logging) + e) Proximity sensor support for up to 3 sensors + f) Precision Landing consumes LANDING_TARGET MAVLink message's PositionX,Y,Z fields + g) RichenPower generator maintenance-required messages can be suppressed using GEN_OPTIONS param + h) TeraRanger Neo rangefinder support + i) GPS support to provide ellipsoid altitude instead of AMSL (see GPS_DRV_OPTIONS) + j) W25N01GV 1Gb flash support +9) Bug fixes + a) Accel calibration throws away queued commands from GCS (avoids commands being run long after they were sent) + b) Airmode throttle mix at zero throttle fix + c) Cygbot proximity sensor fix to support different orientations (see PRXx_ORIENT) + d) Loiter fix to avoid potential wobble on 2nd takeoff (was not clearing non-zero attitude target from previous landing) + e) Lutan EFI message flood reduced + f) Missions download to GCS corruption avoided by checking serial buffer has space + g) Payload place fix so vehicle flies to specified Lat,Lon (if provided). Previously it could get stuck + h) Safety switch disabled if IOMCU is disabled (see BRD_IO_ENABLE=0) + i) Script restart memory leak fixed + j) Takeoff vertical velocity limits enforced correctly even if PILOT_TKOFF_ALT set to a significant height +10) Developer items + a) Custom controller support + b) Fast loop task list available in real-time using @SYS/tasks.txt + c) Parameter defaults sent to GCS with param FTP and recorded in onboard logs + d) ROS+ArduPilot environment installation script + e) Sim on Hardware allows simulator to run on autopilot (good for exhibitions) + f) Timer info available in real-time using @SYS/timers.txt +------------------------------------------------------------------ +Copter 4.2.3 30-Aug-2022 +Changes from 4.2.3-rc3 +1) OpenDroneId bug fix to consume open-drone-id-system-update message +------------------------------------------------------------------ +Copter 4.2.3-rc3 20-Aug-2022 +Changes from 4.2.3-rc2 +1) OpenDroneId improvements including reporting if operator location is lost +2) Firmware ID and CRC check (disabled by default) +3) Bug Fixes + a) Auto takeoff with terrain altitude frame fix (could cause climb away if rangefinder became out of range) + b) Revert Notch filter ordering on loss of RPM source (see 4.2.3-rc1's 3g below) because fix is incomplete +------------------------------------------------------------------ +Copter 4.2.3-rc2 13-Aug-2022 +Changes from 4.2.3-rc1 +1) BlueRobotics Navigator autopilot filesystem fix +------------------------------------------------------------------ +Copter 4.2.3-rc1 12-Aug-2022 +Changes from 4.2.2 +1) OpenDroneId support (aka RemoteID) +2) New autopilot support + a) CubeOrange+ + b) Foxeer Reaper F745 + c) MFE PixSurveyA1 + d) Pixhawk6C and Pixhawk6X +3) Bug Fixes and minor enhancements + a) Battery monitor health check fixed to check all enabled monitors + b) ICE Lutan EFI update serial flood fixed + c) ICM42xxx IMU filter settings improved and allow for faster sample rates + d) INA2xx batteries may init after startup + e) KakuteH7 OSD parameter menu enabled + f) Lua script support to set desired speed in Auto mode + g) Notch filter ordering bug on loss of RPM source fixed + h) Payload Place mission command obeys specified altitude type (was always terrain alt) + i) PreArm check that MOT_PWM_MIN/MAX are non-zero + j) PreArm check of Rangefinder pin conflict and servo outputs + k) SCurve logs debug if internal error occurs + l) WSL2 upload fixed (developer issue only) +------------------------------------------------------------------ +Copter 4.2.2 18-Jul-2022 / 4.2.2-rc2 04-Jul-2022 +No changes from 4.2.2 +------------------------------------------------------------------ +Copter 4.2.2-rc1 21-Jun-2022 +Changes from 4.2.1 +1) MambaH743v4 and MambaF405 MK4 autopilot support +2) Second full harmonic notches available (see INS_HNTC2_ parameters) +3) UAVCAN memory usage reduced (see CAN_Dn_UC_POOL parameter to control DroneCAN pool size) +4) VTOL QuikTune lua script added +5) Watchdog (caused by hardfault) saves crash dump logs to SD card +6) Bug fixes + a) Circle mode stops below altitude fence + b) CRSF protection against watchdog on bad frames + c) CRSF reset in flight handled + d) FFT init watchdog fix when ARMING_REQUIRE=0 (not actually possible on Copter) + e) OSD flight modes menu includes newer flight modes + f) Param download (via MAVFTP) fixed for params with overlapping names + g) PWM rangefinder bug fix and added SCALING parameter support + h) Replay bug fix when EK3_SRCs changed + i) SERIALx_OPTION fix when "Don't forward mavlink to/from" selected (resolves MAVLink gimbal detection) + j) TradHeli Autotune fix which could cause incorrect gains to be loaded + k) VL53L1X rangefinder preserves addresses +------------------------------------------------------------------ +Copter 4.2.1 07-Jun-2022 / 4.2.1-rc1 28-May-2022 +Changes from 4.2.0 +1) CAN ESCs bus bandwidth efficiency improvements (see CAN_Dx_UC_ESC_OF parameter) +2) DShot timing improvements to support for ESC variants +3) LOITER_TURNS command radius max increased from 255m to 2550m (but only 10m accuracy when over 255) +4) Luftan EFI measures fuel consumption (see EFI_COEF1, EFI_COEF2) +5) Bug fixes + a) CAN ESCs work on boards with no safety switch (e.g. MatekH743) + b) Inflight Compass calibration checks GSF yaw estimate is good + c) LOITER_TURNS command's Turns field limited to 255 (previously would wrap to lower number) + d) NeoPixel colour fix + e) Precision Landing maintains yaw during retries +------------------------------------------------------------------ +Copter 4.2.0 23-May-2022 / 4.2.0-rc4 14-May-2022 +Changes from 4.2.0-rc3 +1) FlyingMoon F407 and F427 autopilots supported +2) Vibration failsafe disabled in manual modes +3) Bug fixes + a) Log file list with over 500 logs fixed + b) Loiter mode ignores ATC_SLEW_YAW parameter + c) RSSI when using IOMCU pin 103 fixed + d) TradHeli internal error during takeoff fixed +------------------------------------------------------------------ +Copter 4.2.0-rc3 07-May-2022 +Changes from 4.2.0-rc2 +1) Bug fixes + a) Blended Z axis accel calculation fix when not using first IMU + b) Custom compass orientation for DroneCAN compasses +------------------------------------------------------------------ +Copter 4.2.0-rc2 29-Apr-2022 +Changes from 4.2.0-rc1 +1) Minor Enhancements + a) Button, Relay and RPM GPIO pin conflict pre-arm check improved + b) DShot uses narrower bitwidths for more accurate timing (allows BLHeli BlueJay to work) + c) iFlight Chimera default parameters file added + d) INS_NOTCH parameters renamed to INS_HNTC2 + e) Matek F765-Wing-bdshot firmware added + f) Matek H743 supports ICM42688 + g) QiotekZealot H743 supports ICM4xxxx + h) Scripting heap size increased to 100k on F7/H7 + i) SPRacingH7 improvements including external flash performance improvements +2) Bug fixes + a) BMI088 IMU FIFO overruns fixed + b) DO_SET_SERVO with SERVOn_FUNCTION=0 fixed, added pre-arm check of servo functions configured on disabled channels + c) Log file descriptor init fixed (issues only seen on Linux autopilots) + d) Log list cope with gaps, performance improvement to reduce impact on EKF and some ESCs + e) Proximity sensor fix when using MAVLink lidars in non-forward orientations + f) RPM sensor fix to avoid "failed to attach pin" spam to GCS + g) STM32 DMA fatal exceptions disabled (caused watch dogs reboots with zero information) + h) SysID mode bug fix (was not restoring body-frame feedforward setting upon exit) + i) Tradheli autotune fix when max frequency is exceeded +------------------------------------------------------------------ +Copter 4.2.0-rc1 10-Apr-2022 +Changes from 4.2.0-beta3 +1) Minor Enhancements + a) Log and monitor threads stack size increased + b) SPro H7 Extreme QSPI support improved +2) Bug fixes + a) EKF3 accel bias fixed when an IMU is disabled + b) MatekH743 buzzer fixed by reverting to 16 bit timer + c) STM32 H7 flash storage bug fixed that caused re-init on overflow + d) @SYS file logging fixed + e) Timer bug fixed that could cause a watchdog on boards using flash storage + f) UART driver incorrect lock class fixed +------------------------------------------------------------------ +Copter 4.2.0-beta3 30-Mar-2022 +Changes from 4.2.0-beta2 +1) Minor Enhancements + a) BATT_OPTIONS supports sending resting voltage (corrected for internal resistance) to the ground station + b) KakuteH7-bdshot support + c) MatekH743 uses a 32 bit timer to resolve occasional 68ms timing glitch + d) RC input protocol text message sent to GCS (helps pilot awareness during RC handover) + e) Autotune code changes to reduce flash size (no functional impact) +2) Bug fixes + a) Battery remaining percentage fixed when using Sum battery + b) DShot reversal bug with IOMCU based boards (see SERVO_BLH_RVMASK) + c) GPS blending fix that could have resulted in the wrong GPS being used for a short time + d) Param conversion bug (impacted airspeed enable) + e) RC handover between IOMCU RC input and a secondary RC input on a serial port fixed + f) Terrain reference adjustment ensures alt-above-terrain is zero at takeoff (see TERRAIN_OFS_MAX) + g) QioTek Zealot H743 SLCAN port and relays fixed +------------------------------------------------------------------ +Copter 4.2.0-beta2 10-Mar-2022 +Changes from 4.2.0-beta1 +1) Auto and Guided mode changes + a) Delay removed when waypoints are very close together + b) Pause and continue support (GCS changes are still pending) + c) Takeoff and landing use position controller with slower reposition speed (also affects RTL, Land modes) + d) Waypoint navigation will make use of maximum waypoint radius to maximize speed through corners +2) Follow mode supports FOLLOW_TARGET message (sent by QGC ground station) +3) Bug fixes + a) Arming checks ignore SERVOx_MIN, MAX if setup as GPIO pin + b) BeastH7v2 BMI270 baro support + c) DShot prescaler fix (ESCs were not initialising correctly) + d) EKF3 variance constraint fix used to prevent "ill-conditioning" + e) POWR log message MCU voltage fix (min and max voltage were swapped) + f) SPRacingH7 firmware install fix +------------------------------------------------------------------ +Copter 4.2.0-beta1 28-Feb-2022 Changes from 4.1.5 1) AHRS/EKF improvements a) EKF startup messages reduced @@ -276,7 +735,7 @@ Changes from 4.1.0-beta6 e) Guided mode terrain following init fix (might fly at incorrect alt on second use) f) Guided mode yaw rate target timeout fix (vehicle could keep spinning even after targets stopped arriving) g) OSD overwrite and nullptr check fix - h) Proximity Avoidance auxilary switch also disables avoidance using upward facing lidar + h) Proximity Avoidance auxiliary switch also disables avoidance using upward facing lidar i) Proximity sensor pre-arm check disabled if avoidance using proximity sensors is disabled j) RCOut banner displayed at very end of startup procedure to avoid invalid output k) Tricopter tail servo alway uses regular PWM (fixes use with BLHeli motors) diff --git a/ArduCopter/afs_copter.cpp b/ArduCopter/afs_copter.cpp index 2eb2c1db147..9f669eee8cd 100644 --- a/ArduCopter/afs_copter.cpp +++ b/ArduCopter/afs_copter.cpp @@ -45,7 +45,7 @@ void AP_AdvancedFailsafe_Copter::setup_IO_failsafe(void) #if FRAME_CONFIG != HELI_FRAME // setup AP_Motors outputs for failsafe - uint16_t mask = copter.motors->get_motor_mask(); + uint32_t mask = copter.motors->get_motor_mask(); hal.rcout->set_failsafe_pwm(mask, copter.motors->get_pwm_output_min()); #endif } diff --git a/ArduCopter/compassmot.cpp b/ArduCopter/compassmot.cpp index 81a24c3d810..5e24bd2b407 100644 --- a/ArduCopter/compassmot.cpp +++ b/ArduCopter/compassmot.cpp @@ -102,7 +102,7 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan) } // disable throttle failsafe - g.failsafe_throttle = FS_THR_DISABLED; + g.failsafe_throttle.set(FS_THR_DISABLED); // disable motor compensation compass.motor_compensation_type(AP_COMPASS_MOT_COMP_DISABLED); @@ -147,7 +147,7 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan) // pass through throttle to motors SRV_Channels::cork(); - motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() / 1000.0f); + motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() * 0.001f); SRV_Channels::push(); // read some compass values @@ -157,7 +157,7 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan) battery.read(); // calculate scaling for throttle - throttle_pct = (float)channel_throttle->get_control_in() / 1000.0f; + throttle_pct = (float)channel_throttle->get_control_in() * 0.001f; throttle_pct = constrain_float(throttle_pct,0.0f,1.0f); // record maximum throttle diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 9a971cc66d2..50250d9bec8 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -145,10 +145,6 @@ #define FS_TERRAIN_TIMEOUT_MS 5000 // 5 seconds of missing terrain data will trigger failsafe (RTL) #endif -#ifndef PREARM_DISPLAY_PERIOD -# define PREARM_DISPLAY_PERIOD 30 -#endif - // pre-arm baro vs inertial nav max alt disparity #ifndef PREARM_MAX_ALT_DISPARITY_CM # define PREARM_MAX_ALT_DISPARITY_CM 100 // barometer and inertial nav altitude must be within this many centimeters @@ -323,6 +319,12 @@ # define MODE_TURTLE_ENABLED !HAL_MINIMIZE_FEATURES && !defined(DISABLE_DSHOT) && FRAME_CONFIG != HELI_FRAME #endif +////////////////////////////////////////////////////////////////////////////// +// Flowhold - use optical flow to hover in place +#ifndef MODE_FLOWHOLD_ENABLED +# define MODE_FLOWHOLD_ENABLED !HAL_MINIMIZE_FEATURES && AP_OPTICALFLOW_ENABLED +#endif + ////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////// @@ -421,6 +423,9 @@ #ifndef LAND_DETECTOR_TRIGGER_SEC # define LAND_DETECTOR_TRIGGER_SEC 1.0f // number of seconds to detect a landing #endif +#ifndef LAND_AIRMODE_DETECTOR_TRIGGER_SEC + # define LAND_AIRMODE_DETECTOR_TRIGGER_SEC 3.0f // number of seconds to detect a landing in air mode +#endif #ifndef LAND_DETECTOR_MAYBE_TRIGGER_SEC # define LAND_DETECTOR_MAYBE_TRIGGER_SEC 0.2f // number of seconds that means we might be landed (used to reset horizontal position targets to prevent tipping over) #endif @@ -623,11 +628,6 @@ // Fence, Rally and Terrain and AC_Avoidance defaults // -// Enable/disable Fence -#ifndef AC_FENCE - #define AC_FENCE ENABLED -#endif - #ifndef AC_RALLY #define AC_RALLY ENABLED #endif @@ -644,10 +644,6 @@ #define AC_OAPATHPLANNER_ENABLED !HAL_MINIMIZE_FEATURES #endif -#if AC_AVOID_ENABLED && !AC_FENCE - #error AC_Avoidance relies on AC_FENCE which is disabled -#endif - #if MODE_FOLLOW_ENABLED && !AC_AVOID_ENABLED #error Follow Mode relies on AC_AVOID which is disabled #endif @@ -688,11 +684,6 @@ // Developer Items // -//use this to completely disable FRSKY TELEM -#ifndef FRSKY_TELEM_ENABLED - # define FRSKY_TELEM_ENABLED ENABLED -#endif - #ifndef ADVANCED_FAILSAFE # define ADVANCED_FAILSAFE DISABLED #endif @@ -720,3 +711,7 @@ #ifndef HAL_FRAME_TYPE_DEFAULT #define HAL_FRAME_TYPE_DEFAULT AP_Motors::MOTOR_FRAME_TYPE_X #endif + +#ifndef AC_CUSTOMCONTROL_MULTI_ENABLED +#define AC_CUSTOMCONTROL_MULTI_ENABLED FRAME_CONFIG == MULTICOPTER_FRAME && AP_CUSTOMCONTROL_ENABLED +#endif diff --git a/ArduCopter/crash_check.cpp b/ArduCopter/crash_check.cpp index 253d359a05d..b57114ae7c8 100644 --- a/ArduCopter/crash_check.cpp +++ b/ArduCopter/crash_check.cpp @@ -191,7 +191,7 @@ void Copter::yaw_imbalance_check() return; } - // thrust loss is trigerred, yaw issues are expected + // thrust loss is triggered, yaw issues are expected if (motors->get_thrust_boost()) { yaw_I_filt.reset(0.0f); return; @@ -219,8 +219,8 @@ void Copter::yaw_imbalance_check() const float I_max = attitude_control->get_rate_yaw_pid().imax(); if ((is_positive(I_max) && ((I > YAW_IMBALANCE_IMAX_THRESHOLD * I_max) || (is_equal(I_term,I_max))))) { - // filtered using over precentage of I max or unfiltered = I max - // I makes up more than precentage of total available control power + // filtered using over percentage of I max or unfiltered = I max + // I makes up more than percentage of total available control power const uint32_t now = millis(); if (now - last_yaw_warn_ms > YAW_IMBALANCE_WARN_MS) { last_yaw_warn_ms = now; diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index 27296c21b59..37684bc398f 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -144,6 +144,7 @@ enum LoggingParameters { #define MASK_LOG_IMU_FAST (1UL<<18) #define MASK_LOG_IMU_RAW (1UL<<19) #define MASK_LOG_VIDEO_STABILISATION (1UL<<20) +#define MASK_LOG_FTN_FAST (1UL<<21) #define MASK_LOG_ANY 0xFFFF // Radio failsafe definitions (FS_THR parameter) diff --git a/ArduCopter/ekf_check.cpp b/ArduCopter/ekf_check.cpp index 3a516b25209..0b5fde50af8 100644 --- a/ArduCopter/ekf_check.cpp +++ b/ArduCopter/ekf_check.cpp @@ -61,7 +61,7 @@ void Copter::ekf_check() // increment or decrement counters and take action if (!checks_passed) { - // if compass is not yet flagged as bad + // if variances are not yet flagged as bad if (!ekf_check_state.bad_variance) { // increase counter ekf_check_state.fail_count++; @@ -94,7 +94,7 @@ void Copter::ekf_check() if (ekf_check_state.fail_count > 0) { ekf_check_state.fail_count--; - // if compass is flagged as bad and the counter reaches zero then clear flag + // if variances are flagged as bad and the counter reaches zero then clear flag if (ekf_check_state.bad_variance && ekf_check_state.fail_count == 0) { ekf_check_state.bad_variance = false; AP::logger().Write_Error(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_VARIANCE_CLEARED); @@ -152,11 +152,6 @@ bool Copter::ekf_over_threshold() // failsafe_ekf_event - perform ekf failsafe void Copter::failsafe_ekf_event() { - // return immediately if ekf failsafe already triggered - if (failsafe.ekf) { - return; - } - // EKF failsafe event has occurred failsafe.ekf = true; AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_OCCURRED); @@ -213,6 +208,19 @@ void Copter::failsafe_ekf_off_event(void) AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_RESOLVED); } +// re-check if the flight mode requires GPS but EKF failsafe is active +// this should be called by flight modes that are changing their submode from one that does NOT require a position estimate to one that does +void Copter::failsafe_ekf_recheck() +{ + // return immediately if not in ekf failsafe + if (!failsafe.ekf) { + return; + } + + // trigger EKF failsafe action + failsafe_ekf_event(); +} + // check for ekf yaw reset and adjust target heading, also log position reset void Copter::check_ekf_reset() { @@ -262,7 +270,7 @@ void Copter::check_vibration() const bool is_vibration_affected = ahrs.is_vibration_affected(); const bool bad_vibe_detected = (innovation_checks_valid && innov_velD_posD_positive && (vel_variance > 1.0f)) || is_vibration_affected; - const bool do_bad_vibe_actions = (g2.fs_vibe_enabled == 1) && bad_vibe_detected && motors->armed(); + const bool do_bad_vibe_actions = (g2.fs_vibe_enabled == 1) && bad_vibe_detected && motors->armed() && !flightmode->has_manual_throttle(); if (!vibration_check.high_vibes) { // initialise timers @@ -271,7 +279,7 @@ void Copter::check_vibration() } // check if failure has persisted for at least 1 second if (now - vibration_check.start_ms > 1000) { - // switch ekf to use resistant gains + // switch position controller to use resistant gains vibration_check.clear_ms = 0; vibration_check.high_vibes = true; pos_control->set_vibe_comp(true); @@ -285,7 +293,7 @@ void Copter::check_vibration() } // turn off vibration compensation after 15 seconds if (now - vibration_check.clear_ms > 15000) { - // restore ekf gains, reset timers and update user + // restore position controller gains, reset timers and update user vibration_check.start_ms = 0; vibration_check.high_vibes = false; pos_control->set_vibe_comp(false); diff --git a/ArduCopter/esc_calibration.cpp b/ArduCopter/esc_calibration.cpp index 1457502252b..b4c5c119063 100644 --- a/ArduCopter/esc_calibration.cpp +++ b/ArduCopter/esc_calibration.cpp @@ -96,7 +96,7 @@ void Copter::esc_calibration_passthrough() // pass through to motors SRV_Channels::cork(); - motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() / 1000.0f); + motors->set_throttle_passthrough_for_esc_calibration(channel_throttle->get_control_in() * 0.001f); SRV_Channels::push(); } #endif // FRAME_CONFIG != HELI_FRAME diff --git a/ArduCopter/events.cpp b/ArduCopter/events.cpp index 3cab93e1aee..6d9a6f72df2 100644 --- a/ArduCopter/events.cpp +++ b/ArduCopter/events.cpp @@ -43,33 +43,32 @@ void Copter::failsafe_radio_on_event() // Conditions to deviate from FS_THR_ENABLE selection and send specific GCS warning if (should_disarm_on_failsafe()) { // should immediately disarm when we're on the ground - gcs().send_text(MAV_SEVERITY_WARNING, "Radio Failsafe - Disarming"); + announce_failsafe("Radio", "Disarming"); arming.disarm(AP_Arming::Method::RADIOFAILSAFE); desired_action = FailsafeAction::NONE; } else if (flightmode->is_landing() && ((battery.has_failsafed() && battery.get_highest_failsafe_priority() <= FAILSAFE_LAND_PRIORITY))) { // Allow landing to continue when battery failsafe requires it (not a user option) - gcs().send_text(MAV_SEVERITY_WARNING, "Radio + Battery Failsafe - Continuing Landing"); + announce_failsafe("Radio + Battery", "Continuing Landing"); desired_action = FailsafeAction::LAND; } else if (flightmode->is_landing() && failsafe_option(FailsafeOption::CONTINUE_IF_LANDING)) { // Allow landing to continue when FS_OPTIONS is set to continue landing - gcs().send_text(MAV_SEVERITY_WARNING, "Radio Failsafe - Continuing Landing"); + announce_failsafe("Radio", "Continuing Landing"); desired_action = FailsafeAction::LAND; } else if (flightmode->mode_number() == Mode::Number::AUTO && failsafe_option(FailsafeOption::RC_CONTINUE_IF_AUTO)) { // Allow mission to continue when FS_OPTIONS is set to continue mission - gcs().send_text(MAV_SEVERITY_WARNING, "Radio Failsafe - Continuing Auto Mode"); + announce_failsafe("Radio", "Continuing Auto"); desired_action = FailsafeAction::NONE; - } else if ((flightmode->in_guided_mode()) && - (failsafe_option(FailsafeOption::RC_CONTINUE_IF_GUIDED)) && (g.failsafe_gcs != FS_GCS_DISABLED)) { - // Allow guided mode to continue when FS_OPTIONS is set to continue in guided mode. Only if the GCS failsafe is enabled. - gcs().send_text(MAV_SEVERITY_WARNING, "Radio Failsafe - Continuing Guided Mode"); + } else if ((flightmode->in_guided_mode()) && failsafe_option(FailsafeOption::RC_CONTINUE_IF_GUIDED)) { + // Allow guided mode to continue when FS_OPTIONS is set to continue in guided mode + announce_failsafe("Radio", "Continuing Guided Mode"); desired_action = FailsafeAction::NONE; } else { - gcs().send_text(MAV_SEVERITY_WARNING, "Radio Failsafe"); + announce_failsafe("Radio"); } // Call the failsafe action handler @@ -85,6 +84,15 @@ void Copter::failsafe_radio_off_event() gcs().send_text(MAV_SEVERITY_WARNING, "Radio Failsafe Cleared"); } +void Copter::announce_failsafe(const char *type, const char *action_undertaken) +{ + if (action_undertaken != nullptr) { + gcs().send_text(MAV_SEVERITY_WARNING, "%s Failsafe - %s", type, action_undertaken); + } else { + gcs().send_text(MAV_SEVERITY_WARNING, "%s Failsafe", type); + } +} + void Copter::handle_battery_failsafe(const char *type_str, const int8_t action) { AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_BATT, LogErrorCode::FAILSAFE_OCCURRED); @@ -96,14 +104,14 @@ void Copter::handle_battery_failsafe(const char *type_str, const int8_t action) // should immediately disarm when we're on the ground arming.disarm(AP_Arming::Method::BATTERYFAILSAFE); desired_action = FailsafeAction::NONE; - gcs().send_text(MAV_SEVERITY_WARNING, "Battery Failsafe - Disarming"); + announce_failsafe("Battery", "Disarming"); } else if (flightmode->is_landing() && failsafe_option(FailsafeOption::CONTINUE_IF_LANDING) && desired_action != FailsafeAction::NONE) { // Allow landing to continue when FS_OPTIONS is set to continue when landing desired_action = FailsafeAction::LAND; - gcs().send_text(MAV_SEVERITY_WARNING, "Battery Failsafe - Continuing Landing"); + announce_failsafe("Battery", "Continuing Landing"); } else { - gcs().send_text(MAV_SEVERITY_WARNING, "Battery Failsafe"); + announce_failsafe("Battery"); } // Battery FS options already use the Failsafe_Options enum. So use them directly. @@ -183,35 +191,35 @@ void Copter::failsafe_gcs_on_event(void) // Conditions to deviate from FS_GCS_ENABLE parameter setting if (!motors->armed()) { desired_action = FailsafeAction::NONE; - gcs().send_text(MAV_SEVERITY_WARNING, "GCS Failsafe"); + announce_failsafe("GCS"); } else if (should_disarm_on_failsafe()) { // should immediately disarm when we're on the ground arming.disarm(AP_Arming::Method::GCSFAILSAFE); desired_action = FailsafeAction::NONE; - gcs().send_text(MAV_SEVERITY_WARNING, "GCS Failsafe - Disarming"); + announce_failsafe("GCS", "Disarming"); } else if (flightmode->is_landing() && ((battery.has_failsafed() && battery.get_highest_failsafe_priority() <= FAILSAFE_LAND_PRIORITY))) { // Allow landing to continue when battery failsafe requires it (not a user option) - gcs().send_text(MAV_SEVERITY_WARNING, "GCS + Battery Failsafe - Continuing Landing"); + announce_failsafe("GCS + Battery", "Continuing Landing"); desired_action = FailsafeAction::LAND; } else if (flightmode->is_landing() && failsafe_option(FailsafeOption::CONTINUE_IF_LANDING)) { // Allow landing to continue when FS_OPTIONS is set to continue landing - gcs().send_text(MAV_SEVERITY_WARNING, "GCS Failsafe - Continuing Landing"); + announce_failsafe("GCS", "Continuing Landing"); desired_action = FailsafeAction::LAND; } else if (flightmode->mode_number() == Mode::Number::AUTO && failsafe_option(FailsafeOption::GCS_CONTINUE_IF_AUTO)) { // Allow mission to continue when FS_OPTIONS is set to continue mission - gcs().send_text(MAV_SEVERITY_WARNING, "GCS Failsafe - Continuing Auto Mode"); + announce_failsafe("GCS", "Continuing Auto Mode"); desired_action = FailsafeAction::NONE; } else if (failsafe_option(FailsafeOption::GCS_CONTINUE_IF_PILOT_CONTROL) && !flightmode->is_autopilot()) { // should continue when in a pilot controlled mode because FS_OPTIONS is set to continue in pilot controlled modes - gcs().send_text(MAV_SEVERITY_WARNING, "GCS Failsafe - Continuing Pilot Control"); + announce_failsafe("GCS", "Continuing Pilot Control"); desired_action = FailsafeAction::NONE; } else { - gcs().send_text(MAV_SEVERITY_WARNING, "GCS Failsafe"); + announce_failsafe("GCS"); } // Call the failsafe action handler @@ -293,10 +301,70 @@ void Copter::gpsglitch_check() ap.gps_glitching = gps_glitching; if (gps_glitching) { AP::logger().Write_Error(LogErrorSubsystem::GPS, LogErrorCode::GPS_GLITCH); - gcs().send_text(MAV_SEVERITY_CRITICAL,"GPS Glitch"); + gcs().send_text(MAV_SEVERITY_CRITICAL,"GPS Glitch or Compass error"); } else { AP::logger().Write_Error(LogErrorSubsystem::GPS, LogErrorCode::ERROR_RESOLVED); - gcs().send_text(MAV_SEVERITY_CRITICAL,"GPS Glitch cleared"); + gcs().send_text(MAV_SEVERITY_CRITICAL,"Glitch cleared"); + } + } +} + +// dead reckoning alert and failsafe +void Copter::failsafe_deadreckon_check() +{ + // update dead reckoning state + const char* dr_prefix_str = "Dead Reckoning"; + + // get EKF filter status + bool ekf_dead_reckoning = inertial_nav.get_filter_status().flags.dead_reckoning; + + // alert user to start or stop of dead reckoning + const uint32_t now_ms = AP_HAL::millis(); + if (dead_reckoning.active != ekf_dead_reckoning) { + dead_reckoning.active = ekf_dead_reckoning; + if (dead_reckoning.active) { + dead_reckoning.start_ms = now_ms; + gcs().send_text(MAV_SEVERITY_CRITICAL,"%s started", dr_prefix_str); + } else { + dead_reckoning.start_ms = 0; + dead_reckoning.timeout = false; + gcs().send_text(MAV_SEVERITY_CRITICAL,"%s stopped", dr_prefix_str); + } + } + + // check for timeout + if (dead_reckoning.active && !dead_reckoning.timeout) { + const uint32_t dr_timeout_ms = uint32_t(constrain_float(g2.failsafe_dr_timeout * 1000.0f, 0.0f, UINT32_MAX)); + if (now_ms - dead_reckoning.start_ms > dr_timeout_ms) { + dead_reckoning.timeout = true; + gcs().send_text(MAV_SEVERITY_CRITICAL,"%s timeout", dr_prefix_str); + } + } + + // exit immediately if deadreckon failsafe is disabled + if (g2.failsafe_dr_enable <= 0) { + failsafe.deadreckon = false; + return; + } + + // check for failsafe action + if (failsafe.deadreckon != ekf_dead_reckoning) { + failsafe.deadreckon = ekf_dead_reckoning; + + // only take action in modes requiring position estimate + if (failsafe.deadreckon && copter.flightmode->requires_GPS()) { + + // log error + AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_DEADRECKON, LogErrorCode::FAILSAFE_OCCURRED); + + // immediately disarm while landed + if (should_disarm_on_failsafe()) { + arming.disarm(AP_Arming::Method::DEADRECKON_FAILSAFE); + return; + } + + // take user specified action + do_failsafe_action((FailsafeAction)g2.failsafe_dr_enable.get(), ModeReason::DEADRECKON_FAILSAFE); } } } diff --git a/ArduCopter/failsafe.cpp b/ArduCopter/failsafe.cpp index 75e44f36ec8..d2d54a3afef 100644 --- a/ArduCopter/failsafe.cpp +++ b/ArduCopter/failsafe.cpp @@ -79,7 +79,7 @@ void Copter::failsafe_check() void Copter::afs_fs_check(void) { // perform AFS failsafe checks -#if AC_FENCE +#if AP_FENCE_ENABLED const bool fence_breached = fence.get_breaches() != 0; #else const bool fence_breached = false; diff --git a/ArduCopter/fence.cpp b/ArduCopter/fence.cpp index ab9164ed72c..122d49a9654 100644 --- a/ArduCopter/fence.cpp +++ b/ArduCopter/fence.cpp @@ -2,7 +2,7 @@ // Code to integrate AC_Fence library with main ArduCopter code -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // fence_check - ask fence library to check for breaches and initiate the response // called at 1hz diff --git a/ArduCopter/land_detector.cpp b/ArduCopter/land_detector.cpp index e8690b6c706..94f1df5541a 100644 --- a/ArduCopter/land_detector.cpp +++ b/ArduCopter/land_detector.cpp @@ -14,7 +14,7 @@ static uint32_t land_detector_count = 0; void Copter::update_land_and_crash_detectors() { // update 1hz filtered acceleration - Vector3f accel_ef = ahrs.get_accel_ef_blended(); + Vector3f accel_ef = ahrs.get_accel_ef(); accel_ef.z += GRAVITY_MSS; land_accel_ef_filter.apply(accel_ef, scheduler.get_loop_period_s()); @@ -48,10 +48,13 @@ void Copter::update_land_detector() } else if (ap.land_complete) { #if FRAME_CONFIG == HELI_FRAME // if rotor speed and collective pitch are high then clear landing flag - if (motors->get_takeoff_collective() && motors->get_spool_state() == AP_Motors::SpoolState::THROTTLE_UNLIMITED) { + if (!flightmode->is_taking_off() && motors->get_takeoff_collective() && motors->get_spool_state() == AP_Motors::SpoolState::THROTTLE_UNLIMITED) { #else // if throttle output is high then clear landing flag - if (motors->get_throttle() > get_non_takeoff_throttle()) { + if (!flightmode->is_taking_off() && motors->get_throttle_out() > get_non_takeoff_throttle() && motors->get_spool_state() == AP_Motors::SpoolState::THROTTLE_UNLIMITED) { + // this should never happen because take-off should be detected at the flight mode level + // this here to highlight there is a bug or missing take-off detection + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); #endif set_land_complete(false); } @@ -60,6 +63,7 @@ void Copter::update_land_detector() land_detector_count = 0; } else { + float land_trigger_sec = LAND_DETECTOR_TRIGGER_SEC; #if FRAME_CONFIG == HELI_FRAME // check for both manual collective modes and modes that use altitude hold. For manual collective (called throttle // because multi's use throttle), check that collective pitch is below land min collective position or throttle stick is zero. @@ -70,9 +74,17 @@ void Copter::update_land_detector() const bool landing = flightmode->is_landing(); bool motor_at_lower_limit = (flightmode->has_manual_throttle() && (motors->get_below_land_min_coll() || heli_flags.coll_stk_low) && fabsf(ahrs.get_roll()) < M_PI/2.0f) || ((!force_flying || landing) && motors->limit.throttle_lower && pos_control->get_vel_desired_cms().z < 0.0f); + bool throttle_mix_at_min = true; #else // check that the average throttle output is near minimum (less than 12.5% hover throttle) - bool motor_at_lower_limit = motors->limit.throttle_lower && attitude_control->is_throttle_mix_min(); + bool motor_at_lower_limit = motors->limit.throttle_lower; + bool throttle_mix_at_min = attitude_control->is_throttle_mix_min(); + // set throttle_mix_at_min to true because throttle is never at mix min in airmode + // increase land_trigger_sec when using airmode + if (flightmode->has_manual_throttle() && air_mode == AirMode::AIRMODE_ENABLED) { + land_trigger_sec = LAND_AIRMODE_DETECTOR_TRIGGER_SEC; + throttle_mix_at_min = true; + } #endif uint8_t land_detector_scalar = 1; @@ -99,9 +111,9 @@ void Copter::update_land_detector() const bool WoW_check = true; #endif - if (motor_at_lower_limit && accel_stationary && descent_rate_low && rangefinder_check && WoW_check) { + if (motor_at_lower_limit && throttle_mix_at_min && accel_stationary && descent_rate_low && rangefinder_check && WoW_check) { // landed criteria met - increment the counter and check if we've triggered - if( land_detector_count < ((float)LAND_DETECTOR_TRIGGER_SEC)*scheduler.get_loop_rate_hz()) { + if( land_detector_count < land_trigger_sec*scheduler.get_loop_rate_hz()) { land_detector_count++; } else { set_land_complete(true); @@ -174,7 +186,7 @@ void Copter::update_throttle_mix() if (flightmode->has_manual_throttle()) { // manual throttle - if (channel_throttle->get_control_in() <= 0 || air_mode == AirMode::AIRMODE_DISABLED) { + if (channel_throttle->get_control_in() <= 0 && air_mode != AirMode::AIRMODE_ENABLED) { attitude_control->set_throttle_mix_min(); } else { attitude_control->set_throttle_mix_man(); diff --git a/ArduCopter/leds.cpp b/ArduCopter/leds.cpp deleted file mode 100644 index d452858e518..00000000000 --- a/ArduCopter/leds.cpp +++ /dev/null @@ -1 +0,0 @@ -#include "Copter.h" diff --git a/ArduCopter/mode.cpp b/ArduCopter/mode.cpp index 7eda3f3c93a..4462afad315 100644 --- a/ArduCopter/mode.cpp +++ b/ArduCopter/mode.cpp @@ -139,7 +139,7 @@ Mode *Copter::mode_from_mode_num(const Mode::Number mode) break; #endif -#if AP_OPTICALFLOW_ENABLED +#if MODE_FLOWHOLD_ENABLED == ENABLED case Mode::Number::FLOWHOLD: ret = (Mode *)g2.mode_flowhold_ptr; break; @@ -207,6 +207,10 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason) // return immediately if we are already in the desired mode if (mode == flightmode->mode_number()) { control_mode_reason = reason; + // set yaw rate time constant during autopilot startup + if (reason == ModeReason::INITIALISED && mode == Mode::Number::STABILIZE) { + attitude_control->set_yaw_rate_tc(g2.command_model_pilot.get_rate_tc()); + } // make happy noise if (copter.ap.initialised && (reason != last_reason)) { AP_Notify::events.user_mode_change = 1; @@ -288,7 +292,7 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason) } if (!new_flightmode->init(ignore_checks)) { - mode_change_failed(new_flightmode, "initialisation failed"); + mode_change_failed(new_flightmode, "init failed"); return false; } @@ -308,7 +312,7 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason) adsb.set_is_auto_mode((mode == Mode::Number::AUTO) || (mode == Mode::Number::RTL) || (mode == Mode::Number::GUIDED)); #endif -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // pilot requested flight mode change during a fence breach indicates pilot is attempting to manually recover // this flight mode change could be automatic (i.e. fence, battery, GPS or GCS failsafe) // but it should be harmless to disable the fence temporarily in these situations as well @@ -319,6 +323,17 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason) camera.set_is_auto_mode(flightmode->mode_number() == Mode::Number::AUTO); #endif + // set rate shaping time constants +#if MODE_ACRO_ENABLED == ENABLED || MODE_SPORT_ENABLED == ENABLED + attitude_control->set_roll_pitch_rate_tc(g2.command_model_acro_rp.get_rate_tc()); +#endif + attitude_control->set_yaw_rate_tc(g2.command_model_pilot.get_rate_tc()); +#if MODE_ACRO_ENABLED == ENABLED || MODE_DRIFT_ENABLED == ENABLED + if (mode== Mode::Number::ACRO || mode== Mode::Number::DRIFT) { + attitude_control->set_yaw_rate_tc(g2.command_model_acro_y.get_rate_tc()); + } +#endif + // update notify object notify_flight_mode(); @@ -397,38 +412,56 @@ void Copter::notify_flight_mode() { // get_pilot_desired_angle - transform pilot's roll or pitch input into a desired lean angle // returns desired angle in centi-degrees -void Mode::get_pilot_desired_lean_angles(float &roll_out, float &pitch_out, float angle_max, float angle_limit) const +void Mode::get_pilot_desired_lean_angles(float &roll_out_cd, float &pitch_out_cd, float angle_max_cd, float angle_limit_cd) const { // throttle failsafe check if (copter.failsafe.radio || !copter.ap.rc_receiver_present) { - roll_out = 0; - pitch_out = 0; + roll_out_cd = 0.0; + pitch_out_cd = 0.0; return; } - // fetch roll and pitch inputs - roll_out = channel_roll->get_control_in(); - pitch_out = channel_pitch->get_control_in(); - // limit max lean angle - angle_limit = constrain_float(angle_limit, 1000.0f, angle_max); + //transform pilot's normalised roll or pitch stick input into a roll and pitch euler angle command + float roll_out_deg; + float pitch_out_deg; + rc_input_to_roll_pitch(channel_roll->get_control_in()*(1.0/ROLL_PITCH_YAW_INPUT_MAX), channel_pitch->get_control_in()*(1.0/ROLL_PITCH_YAW_INPUT_MAX), angle_max_cd * 0.01, angle_limit_cd * 0.01, roll_out_deg, pitch_out_deg); - // scale roll and pitch inputs to ANGLE_MAX parameter range - float scaler = angle_max/(float)ROLL_PITCH_YAW_INPUT_MAX; - roll_out *= scaler; - pitch_out *= scaler; + // Convert to centi-degrees + roll_out_cd = roll_out_deg * 100.0; + pitch_out_cd = pitch_out_deg * 100.0; +} - // do circular limit - float total_in = norm(pitch_out, roll_out); - if (total_in > angle_limit) { - float ratio = angle_limit / total_in; - roll_out *= ratio; - pitch_out *= ratio; +// transform pilot's roll or pitch input into a desired velocity +Vector2f Mode::get_pilot_desired_velocity(float vel_max) const +{ + Vector2f vel; + + // throttle failsafe check + if (copter.failsafe.radio || !copter.ap.rc_receiver_present) { + return vel; } + // fetch roll and pitch inputs + float roll_out = channel_roll->get_control_in(); + float pitch_out = channel_pitch->get_control_in(); - // do lateral tilt to euler roll conversion - roll_out = (18000/M_PI) * atanf(cosf(pitch_out*(M_PI/18000))*tanf(roll_out*(M_PI/18000))); + // convert roll and pitch inputs to -1 to +1 range + float scaler = 1.0 / (float)ROLL_PITCH_YAW_INPUT_MAX; + roll_out *= scaler; + pitch_out *= scaler; - // roll_out and pitch_out are returned + // convert roll and pitch inputs into velocity in NE frame + vel = Vector2f(-pitch_out, roll_out); + if (vel.is_zero()) { + return vel; + } + copter.rotate_body_frame_to_NE(vel.x, vel.y); + + // Transform square input range to circular output + // vel_scaler is the vector to the edge of the +- 1.0 square in the direction of the current input + Vector2f vel_scaler = vel / MAX(fabsf(vel.x), fabsf(vel.y)); + // We scale the output by the ratio of the distance to the square to the unit circle and multiply by vel_max + vel *= vel_max / vel_scaler.length(); + return vel; } bool Mode::_TakeOff::triggered(const float target_climb_rate) const @@ -508,6 +541,8 @@ void Mode::make_safe_ground_handling(bool force_throttle_unlimited) break; } + pos_control->relax_velocity_controller_xy(); + pos_control->update_xy_controller(); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero pos_control->update_z_controller(); // we may need to move this out @@ -598,13 +633,12 @@ void Mode::land_run_vertical_control(bool pause_descent) void Mode::land_run_horizontal_control() { - float target_roll = 0.0f; - float target_pitch = 0.0f; + Vector2f vel_correction; float target_yaw_rate = 0; // relax loiter target if we might be landed if (copter.ap.land_complete_maybe) { - loiter_nav->soften_for_landing(); + pos_control->soften_for_landing_xy(); } // process pilot inputs @@ -621,15 +655,25 @@ void Mode::land_run_horizontal_control() // apply SIMPLE mode transform to pilot inputs update_simple_mode(); - // convert pilot input to lean angles - get_pilot_desired_lean_angles(target_roll, target_pitch, loiter_nav->get_angle_max_cd(), attitude_control->get_althold_lean_angle_max_cd()); + // convert pilot input to reposition velocity + // use half maximum acceleration as the maximum velocity to ensure aircraft will + // stop from full reposition speed in less than 1 second. + const float max_pilot_vel = wp_nav->get_wp_acceleration() * 0.5; + vel_correction = get_pilot_desired_velocity(max_pilot_vel); // record if pilot has overridden roll or pitch - if (!is_zero(target_roll) || !is_zero(target_pitch)) { + if (!vel_correction.is_zero()) { if (!copter.ap.land_repo_active) { AP::logger().Write_Event(LogEvent::LAND_REPO_ACTIVE); } copter.ap.land_repo_active = true; +#if PRECISION_LANDING == ENABLED + } else { + // no override right now, check if we should allow precland + if (copter.precland.allow_precland_after_reposition()) { + copter.ap.land_repo_active = false; + } +#endif } } @@ -641,11 +685,11 @@ void Mode::land_run_horizontal_control() } // this variable will be updated if prec land target is in sight and pilot isn't trying to reposition the vehicle - bool doing_precision_landing = false; + copter.ap.prec_land_active = false; #if PRECISION_LANDING == ENABLED - doing_precision_landing = !copter.ap.land_repo_active && copter.precland.target_acquired(); + copter.ap.prec_land_active = !copter.ap.land_repo_active && copter.precland.target_acquired(); // run precision landing - if (doing_precision_landing) { + if (copter.ap.prec_land_active) { Vector2f target_pos, target_vel; if (!copter.precland.get_target_position_cm(target_pos)) { target_pos = inertial_nav.get_position_xy_cm(); @@ -657,29 +701,16 @@ void Mode::land_run_horizontal_control() Vector2p landing_pos = target_pos.topostype(); // target vel will remain zero if landing target is stationary pos_control->input_pos_vel_accel_xy(landing_pos, target_vel, zero); - // run pos controller - pos_control->update_xy_controller(); } #endif - if (!doing_precision_landing) { - if (copter.ap.prec_land_active) { - // precland isn't active anymore but was active a while back - // lets run an init again - // set target to stopping point - Vector2f stopping_point; - loiter_nav->get_stopping_point_xy(stopping_point); - loiter_nav->init_target(stopping_point); - } - // process roll, pitch inputs - loiter_nav->set_pilot_desired_acceleration(target_roll, target_pitch); - - // run loiter controller - loiter_nav->update(); + if (!copter.ap.prec_land_active) { + Vector2f accel; + pos_control->input_vel_accel_xy(vel_correction, accel); } - copter.ap.prec_land_active = doing_precision_landing; - + // run pos controller + pos_control->update_xy_controller(); Vector3f thrust_vector = pos_control->get_thrust_vector(); if (g2.wp_navalt_min > 0) { @@ -691,7 +722,7 @@ void Mode::land_run_horizontal_control() // interpolate for 1m above that const float attitude_limit_cd = linear_interpolate(700, copter.aparm.angle_max, get_alt_above_ground_cm(), g2.wp_navalt_min*100U, (g2.wp_navalt_min+1)*100U); - const float thrust_vector_max = sinf(radians(attitude_limit_cd / 100.0f)) * GRAVITY_MSS * 100.0f; + const float thrust_vector_max = sinf(radians(attitude_limit_cd * 0.01f)) * GRAVITY_MSS * 100.0f; const float thrust_vector_mag = thrust_vector.xy().length(); if (thrust_vector_mag > thrust_vector_max) { float ratio = thrust_vector_max / thrust_vector_mag; @@ -737,6 +768,7 @@ void Mode::land_run_normal_or_precland(bool pause_descent) // The passed in location is expected to be NED and in m void Mode::precland_retry_position(const Vector3f &retry_pos) { + float target_yaw_rate = 0; if (!copter.failsafe.radio) { if ((g.throttle_behavior & THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND) != 0 && copter.rc_throttle_control_in_filter.get() > LAND_CANCEL_TRIGGER_THR){ AP::logger().Write_Event(LogEvent::LAND_CANCELLED_BY_PILOT); @@ -747,7 +779,7 @@ void Mode::precland_retry_position(const Vector3f &retry_pos) } // allow user to take control during repositioning. Note: copied from land_run_horizontal_control() - // To-Do: this code exists at several different places in slightly diffrent forms and that should be fixed + // To-Do: this code exists at several different places in slightly different forms and that should be fixed if (g.land_repositioning) { float target_roll = 0.0f; float target_pitch = 0.0f; @@ -763,10 +795,15 @@ void Mode::precland_retry_position(const Vector3f &retry_pos) copter.ap.land_repo_active = true; } } + + target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz()); + if (!is_zero(target_yaw_rate)) { + auto_yaw.set_mode(AUTO_YAW_HOLD); + } } Vector3p retry_pos_NEU{retry_pos.x, retry_pos.y, retry_pos.z * -1.0f}; - //pos contoller expects input in NEU cm's + // pos controller expects input in NEU cm's retry_pos_NEU = retry_pos_NEU * 100.0f; pos_control->input_pos_xyz(retry_pos_NEU, 0.0f, 1000.0f); @@ -776,8 +813,14 @@ void Mode::precland_retry_position(const Vector3f &retry_pos) const Vector3f thrust_vector{pos_control->get_thrust_vector()}; - // roll, pitch from position controller, yaw heading from auto_heading() - attitude_control->input_thrust_vector_heading(thrust_vector, auto_yaw.yaw()); + // call attitude controller + if (auto_yaw.mode() == AUTO_YAW_HOLD) { + // roll & pitch from waypoint controller, yaw rate from pilot + attitude_control->input_thrust_vector_rate_heading(thrust_vector, target_yaw_rate); + } else { + // roll, pitch from waypoint controller, yaw heading from auto_heading() + attitude_control->input_thrust_vector_heading(thrust_vector, auto_yaw.yaw()); + } } // Run precland statemachine. This function should be called from any mode that wants to do precision landing. @@ -941,7 +984,7 @@ float Mode::get_pilot_desired_yaw_rate(float yaw_in) } // convert pilot input to the desired yaw rate - return g2.pilot_y_rate * 100.0 * input_expo(yaw_in, g2.pilot_y_expo); + return g2.command_model_pilot.get_rate() * 100.0 * input_expo(yaw_in, g2.command_model_pilot.get_expo()); } // pass-through functions to reduce code churn on conversion; @@ -976,14 +1019,6 @@ GCS_Copter &Mode::gcs() return copter.gcs(); } -// set_throttle_takeoff - allows modes to tell throttle controller we -// are taking off so I terms can be cleared -void Mode::set_throttle_takeoff() -{ - // initialise the vertical position controller - pos_control->init_z_controller(); -} - uint16_t Mode::get_pilot_speed_dn() { return copter.get_pilot_speed_dn(); diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index cc27ab62474..1031c7a9598 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -1,6 +1,7 @@ #pragma once #include "Copter.h" +#include class Parameters; class ParametersG2; @@ -38,6 +39,9 @@ class Mode { AUTOROTATE = 26, // Autonomous autorotation AUTO_RTL = 27, // Auto RTL, this is not a true mode, AUTO will report as this mode if entered to perform a DO_LAND_START Landing sequence TURTLE = 28, // Flip over after crash + + // Mode number 127 reserved for the "drone show mode" in the Skybrush + // fork at https://github.com/skybrush-io/ardupilot }; // constructor @@ -86,10 +90,16 @@ class Mode { virtual uint32_t wp_distance() const { return 0; } virtual float crosstrack_error() const { return 0.0f;} + // functions to support MAV_CMD_DO_CHANGE_SPEED + virtual bool set_speed_xy(float speed_xy_cms) {return false;} + virtual bool set_speed_up(float speed_xy_cms) {return false;} + virtual bool set_speed_down(float speed_xy_cms) {return false;} + int32_t get_alt_above_ground_cm(void); // pilot input processing - void get_pilot_desired_lean_angles(float &roll_out, float &pitch_out, float angle_max, float angle_limit) const; + void get_pilot_desired_lean_angles(float &roll_out_cd, float &pitch_out_cd, float angle_max_cd, float angle_limit_cd) const; + Vector2f get_pilot_desired_velocity(float vel_max) const; float get_pilot_desired_yaw_rate(float yaw_in); float get_pilot_desired_throttle() const; @@ -109,6 +119,10 @@ class Mode { // returns true if pilot's yaw input should be used to adjust vehicle's heading virtual bool use_pilot_yaw() const {return true; } + // pause and resume a mode + virtual bool pause() { return false; }; + virtual bool resume() { return false; }; + protected: // helper functions @@ -189,22 +203,29 @@ class Mode { private: bool _running; float take_off_start_alt; - float take_off_complete_alt ; + float take_off_complete_alt; }; static _TakeOff takeoff; virtual bool do_user_takeoff_start(float takeoff_alt_cm); - // method shared by both Guided and Auto for takeoff. This is - // waypoint navigation but the user can control the yaw. + // method shared by both Guided and Auto for takeoff. + // position controller controls vehicle but the user can control the yaw. void auto_takeoff_run(); - void auto_takeoff_set_start_alt(void); + void auto_takeoff_start(float complete_alt_cm, bool terrain_alt); + bool auto_takeoff_get_position(Vector3p& completion_pos); // altitude above-ekf-origin below which auto takeoff does not control horizontal position static bool auto_takeoff_no_nav_active; static float auto_takeoff_no_nav_alt_cm; + // auto takeoff variables + static float auto_takeoff_complete_alt_cm; // completion altitude expressed in cm above ekf origin or above terrain (depending upon auto_takeoff_terrain_alt) + static bool auto_takeoff_terrain_alt; // true if altitudes are above terrain + static bool auto_takeoff_complete; // true when takeoff is complete + static Vector3p auto_takeoff_complete_pos; // target takeoff position as offset from ekf origin in cm + public: // Navigation Yaw control class AutoYaw { @@ -274,7 +295,6 @@ class Mode { bool set_mode(Mode::Number mode, ModeReason reason); void set_land_complete(bool b); GCS_Copter &gcs(); - void set_throttle_takeoff(void); uint16_t get_pilot_speed_dn(void); // end pass-through functions }; @@ -386,11 +406,11 @@ class ModeAuto : public Mode { void exit() override; void run() override; - bool requires_GPS() const override { return true; } + bool requires_GPS() const override; bool has_manual_throttle() const override { return false; } bool allows_arming(AP_Arming::Method method) const override; bool is_autopilot() const override { return true; } - bool in_guided_mode() const override { return mode() == SubMode::NAVGUIDED || mode() == SubMode::NAV_SCRIPT_TIME; } + bool in_guided_mode() const override { return _mode == SubMode::NAVGUIDED || _mode == SubMode::NAV_SCRIPT_TIME; } // Auto modes enum class SubMode : uint8_t { @@ -405,17 +425,21 @@ class ModeAuto : public Mode { LOITER_TO_ALT, NAV_PAYLOAD_PLACE, NAV_SCRIPT_TIME, + NAV_ATTITUDE_TIME, }; - // Auto - SubMode mode() const { return _mode; } + // set submode. returns true on success, false on failure + void set_submode(SubMode new_submode); + + // pause continue in auto mode + bool pause() override; + bool resume() override; bool loiter_start(); void rtl_start(); void takeoff_start(const Location& dest_loc); void wp_start(const Location& dest_loc); void land_start(); - void land_start(const Vector2f& destination); void circle_movetoedge_start(const Location &circle_center, float radius_m); void circle_start(); void nav_guided_start(); @@ -425,6 +449,10 @@ class ModeAuto : public Mode { bool is_taking_off() const override; bool use_pilot_yaw() const override; + bool set_speed_xy(float speed_xy_cms) override; + bool set_speed_up(float speed_up_cms) override; + bool set_speed_down(float speed_down_cms) override; + bool requires_terrain_failsafe() const override { return true; } // return true if this flight mode supports user takeoff @@ -483,19 +511,19 @@ class ModeAuto : public Mode { void nav_guided_run(); void loiter_run(); void loiter_to_alt_run(); + void nav_attitude_time_run(); Location loc_from_cmd(const AP_Mission::Mission_Command& cmd, const Location& default_loc) const; - void payload_place_start(const Vector2f& destination); void payload_place_run(); bool payload_place_run_should_run(); - void payload_place_run_loiter(); + void payload_place_run_hover(); void payload_place_run_descend(); void payload_place_run_release(); SubMode _mode = SubMode::TAKEOFF; // controls which auto controller is run - Location terrain_adjusted_location(const AP_Mission::Mission_Command& cmd) const; + bool shift_alt_to_current_alt(Location& target_loc) const; void do_takeoff(const AP_Mission::Mission_Command& cmd); void do_nav_wp(const AP_Mission::Mission_Command& cmd); @@ -530,6 +558,7 @@ class ModeAuto : public Mode { #if AP_SCRIPTING_ENABLED void do_nav_script_time(const AP_Mission::Mission_Command& cmd); #endif + void do_nav_attitude_time(const AP_Mission::Mission_Command& cmd); bool verify_takeoff(); bool verify_land(); @@ -551,6 +580,7 @@ class ModeAuto : public Mode { #if AP_SCRIPTING_ENABLED bool verify_nav_script_time(); #endif + bool verify_nav_attitude_time(const AP_Mission::Mission_Command& cmd); // Loiter control uint16_t loiter_time_max; // How long we should stay in Loiter Mode for mission scripting (time in seconds) @@ -606,6 +636,15 @@ class ModeAuto : public Mode { float arg2; // 2nd argument provided by mission command } nav_scripting; #endif + + // nav attitude time command variables + struct { + int16_t roll_deg; // target roll angle in degrees. provided by mission command + int8_t pitch_deg; // target pitch angle in degrees. provided by mission command + int16_t yaw_deg; // target yaw angle in degrees. provided by mission command + float climb_rate; // climb rate in m/s. provided by mission command + uint32_t start_ms; // system time that nav attitude time command was received (used for timeout) + } nav_attitude_time; }; #if AUTOTUNE_ENABLED == ENABLED @@ -795,7 +834,7 @@ class ModeFlip : public Mode { }; -#if !HAL_MINIMIZE_FEATURES && AP_OPTICALFLOW_ENABLED +#if MODE_FLOWHOLD_ENABLED == ENABLED /* class to support FLOWHOLD mode, which is a position hold mode using optical flow directly, avoiding the need for a rangefinder @@ -881,7 +920,7 @@ class ModeFlowHold : public Mode { // last time there was significant stick input uint32_t last_stick_input_ms; }; -#endif // AP_OPTICALFLOW_ENABLED +#endif // MODE_FLOWHOLD_ENABLED class ModeGuided : public Mode { @@ -938,7 +977,13 @@ class ModeGuided : public Mode { bool limit_check(); bool is_taking_off() const override; + + bool set_speed_xy(float speed_xy_cms) override; + bool set_speed_up(float speed_up_cms) override; + bool set_speed_down(float speed_down_cms) override; + // initialises position controller to implement take-off + // takeoff_alt_cm is interpreted as alt-above-home (in cm) or alt-above-terrain if a rangefinder is available bool do_user_takeoff_start(float takeoff_alt_cm) override; enum class SubMode { @@ -961,6 +1006,10 @@ class ModeGuided : public Mode { bool use_pilot_yaw() const override; + // pause continue in guided mode + bool pause() override; + bool resume() override; + protected: const char *name() const override { return "GUIDED"; } @@ -996,6 +1045,7 @@ class ModeGuided : public Mode { void pos_control_run(); void accel_control_run(); void velaccel_control_run(); + void pause_control_run(); void posvelaccel_control_run(); void set_yaw_state(bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_angle); @@ -1003,6 +1053,9 @@ class ModeGuided : public Mode { SubMode guided_mode = SubMode::TakeOff; bool send_notification; // used to send one time notification to ground station bool takeoff_complete; // true once takeoff has completed (used to trigger retracting of landing gear) + + // guided mode is paused or not + bool _paused; }; @@ -1445,6 +1498,7 @@ class ModeSystemId : public Mode { bool init(bool ignore_checks) override; void run() override; + void exit() override; bool requires_GPS() const override { return false; } bool has_manual_throttle() const override { return true; } @@ -1452,10 +1506,12 @@ class ModeSystemId : public Mode { bool is_autopilot() const override { return false; } bool logs_attitude() const override { return true; } - void set_magnitude(float input) { waveform_magnitude = input; } + void set_magnitude(float input) { waveform_magnitude.set(input); } static const struct AP_Param::GroupInfo var_info[]; + Chirp chirp_input; + protected: const char *name() const override { return "SYSTEMID"; } @@ -1464,7 +1520,6 @@ class ModeSystemId : public Mode { private: void log_data() const; - float waveform(float time); enum class AxisType { NONE = 0, // none @@ -1585,6 +1640,9 @@ class ModeTurtle : public Mode { const char *name4() const override { return "TRTL"; } private: + void arm_motors(); + void disarm_motors(); + float motors_output; Vector2f motors_input; }; diff --git a/ArduCopter/mode_acro.cpp b/ArduCopter/mode_acro.cpp index 9aa04397ae8..03160ab2a05 100644 --- a/ArduCopter/mode_acro.cpp +++ b/ArduCopter/mode_acro.cpp @@ -7,7 +7,6 @@ /* * Init and run calls for acro flight mode */ - void ModeAcro::run() { // convert the input to the desired body frame rate @@ -17,24 +16,33 @@ void ModeAcro::run() if (!motors->armed()) { // Motors should be Stopped motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN); - } else if (copter.ap.throttle_zero && copter.air_mode != AirMode::AIRMODE_ENABLED) { - // Attempting to Land, if airmode is enabled only an actual landing will spool down the motors + } else if (copter.ap.throttle_zero + || (copter.air_mode == AirMode::AIRMODE_ENABLED && motors->get_spool_state() == AP_Motors::SpoolState::SHUT_DOWN)) { + // throttle_zero is never true in air mode, but the motors should be allowed to go through ground idle + // in order to facilitate the spoolup block + + // Attempting to Land or motors not yet spinning + // if airmode is enabled only an actual landing will spool down the motors motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE); } else { motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); } + float pilot_desired_throttle = get_pilot_desired_throttle(); + switch (motors->get_spool_state()) { case AP_Motors::SpoolState::SHUT_DOWN: // Motors Stopped attitude_control->reset_target_and_rate(true); attitude_control->reset_rate_controller_I_terms(); + pilot_desired_throttle = 0.0f; break; case AP_Motors::SpoolState::GROUND_IDLE: // Landed attitude_control->reset_target_and_rate(); attitude_control->reset_rate_controller_I_terms_smoothly(); + pilot_desired_throttle = 0.0f; break; case AP_Motors::SpoolState::THROTTLE_UNLIMITED: @@ -58,9 +66,7 @@ void ModeAcro::run() } // output pilot's throttle without angle boost - attitude_control->set_throttle_out(get_pilot_desired_throttle(), - false, - copter.g.throttle_filt); + attitude_control->set_throttle_out(pilot_desired_throttle, false, copter.g.throttle_filt); } bool ModeAcro::init(bool ignore_checks) @@ -113,13 +119,13 @@ void ModeAcro::get_pilot_desired_angle_rates(float roll_in, float pitch_in, floa // calculate roll, pitch rate requests // roll expo - rate_bf_request_cd.x = g2.acro_rp_rate * 100.0 * input_expo(roll_in, g.acro_rp_expo); + rate_bf_request_cd.x = g2.command_model_acro_rp.get_rate() * 100.0 * input_expo(roll_in, g2.command_model_acro_rp.get_expo()); // pitch expo - rate_bf_request_cd.y = g2.acro_rp_rate * 100.0 * input_expo(pitch_in, g.acro_rp_expo); + rate_bf_request_cd.y = g2.command_model_acro_rp.get_rate() * 100.0 * input_expo(pitch_in, g2.command_model_acro_rp.get_expo()); // yaw expo - rate_bf_request_cd.z = g2.acro_y_rate * 100.0 * input_expo(yaw_in, g2.acro_y_expo); + rate_bf_request_cd.z = g2.command_model_acro_y.get_rate() * 100.0 * input_expo(yaw_in, g2.command_model_acro_y.get_expo()); // calculate earth frame rate corrections to pull the copter back to level while in ACRO mode @@ -143,15 +149,15 @@ void ModeAcro::get_pilot_desired_angle_rates(float roll_in, float pitch_in, floa if (g.acro_trainer == (uint8_t)Trainer::LIMITED) { const float angle_max = copter.aparm.angle_max; if (roll_angle > angle_max){ - rate_ef_level_cd.x += sqrt_controller(angle_max - roll_angle, g2.acro_rp_rate * 100.0 / ACRO_LEVEL_MAX_OVERSHOOT, attitude_control->get_accel_roll_max_cdss(), G_Dt); + rate_ef_level_cd.x += sqrt_controller(angle_max - roll_angle, g2.command_model_acro_rp.get_rate() * 100.0 / ACRO_LEVEL_MAX_OVERSHOOT, attitude_control->get_accel_roll_max_cdss(), G_Dt); }else if (roll_angle < -angle_max) { - rate_ef_level_cd.x += sqrt_controller(-angle_max - roll_angle, g2.acro_rp_rate * 100.0 / ACRO_LEVEL_MAX_OVERSHOOT, attitude_control->get_accel_roll_max_cdss(), G_Dt); + rate_ef_level_cd.x += sqrt_controller(-angle_max - roll_angle, g2.command_model_acro_rp.get_rate() * 100.0 / ACRO_LEVEL_MAX_OVERSHOOT, attitude_control->get_accel_roll_max_cdss(), G_Dt); } if (pitch_angle > angle_max){ - rate_ef_level_cd.y += sqrt_controller(angle_max - pitch_angle, g2.acro_rp_rate * 100.0 / ACRO_LEVEL_MAX_OVERSHOOT, attitude_control->get_accel_pitch_max_cdss(), G_Dt); + rate_ef_level_cd.y += sqrt_controller(angle_max - pitch_angle, g2.command_model_acro_rp.get_rate() * 100.0 / ACRO_LEVEL_MAX_OVERSHOOT, attitude_control->get_accel_pitch_max_cdss(), G_Dt); }else if (pitch_angle < -angle_max) { - rate_ef_level_cd.y += sqrt_controller(-angle_max - pitch_angle, g2.acro_rp_rate * 100.0 / ACRO_LEVEL_MAX_OVERSHOOT, attitude_control->get_accel_pitch_max_cdss(), G_Dt); + rate_ef_level_cd.y += sqrt_controller(-angle_max - pitch_angle, g2.command_model_acro_rp.get_rate() * 100.0 / ACRO_LEVEL_MAX_OVERSHOOT, attitude_control->get_accel_pitch_max_cdss(), G_Dt); } } diff --git a/ArduCopter/mode_althold.cpp b/ArduCopter/mode_althold.cpp index 858ce86d25c..36a344f87e3 100644 --- a/ArduCopter/mode_althold.cpp +++ b/ArduCopter/mode_althold.cpp @@ -100,4 +100,4 @@ void ModeAltHold::run() // run the vertical position controller and set output throttle pos_control->update_z_controller(); -} +} \ No newline at end of file diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index 9d449ef7700..1ff806139fe 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -24,14 +24,14 @@ bool ModeAuto::init(bool ignore_checks) { auto_RTL = false; if (mission.num_commands() > 1 || ignore_checks) { - _mode = SubMode::LOITER; - // reject switching to auto mode if landed with motors armed but first command is not a takeoff (reduce chance of flips) if (motors->armed() && copter.ap.land_complete && !mission.starts_with_takeoff_cmd()) { gcs().send_text(MAV_SEVERITY_CRITICAL, "Auto: Missing Takeoff Cmd"); return false; } + _mode = SubMode::LOITER; + // stop ROI from carrying over from previous runs of the mission // To-Do: reset the yaw as part of auto_wp_start when the previous command was not a wp command to remove the need for this special ROI check if (auto_yaw.mode() == AUTO_YAW_ROI) { @@ -152,6 +152,10 @@ void ModeAuto::run() case SubMode::NAV_PAYLOAD_PLACE: payload_place_run(); break; + + case SubMode::NAV_ATTITUDE_TIME: + nav_attitude_time_run(); + break; } // only pretend to be in auto RTL so long as mission still thinks its in a landing sequence or the mission has completed @@ -162,6 +166,34 @@ void ModeAuto::run() } } +// return true if a position estimate is required +bool ModeAuto::requires_GPS() const +{ + // position estimate is required in all sub modes except attitude control + return _mode != SubMode::NAV_ATTITUDE_TIME; +} + +// set submode. This may re-trigger the vehicle's EKF failsafe if the new submode requires a position estimate +void ModeAuto::set_submode(SubMode new_submode) +{ + // return immediately if the submode has not been changed + if (new_submode == _mode) { + return; + } + + // backup old mode + SubMode old_submode = _mode; + + // set mode + _mode = new_submode; + + // if changing out of the nav-attitude-time submode, recheck the EKF failsafe + // this may trigger a flight mode change if the EKF failsafe is active + if (old_submode == SubMode::NAV_ATTITUDE_TIME) { + copter.failsafe_ekf_recheck(); + } +} + bool ModeAuto::allows_arming(AP_Arming::Method method) const { return ((copter.g2.auto_options & (uint32_t)Options::AllowArming) != 0) && !auto_RTL; @@ -251,64 +283,85 @@ bool ModeAuto::loiter_start() // auto_rtl_start - initialises RTL in AUTO flight mode void ModeAuto::rtl_start() { - _mode = SubMode::RTL; - // call regular rtl flight mode initialisation and ask it to ignore checks - copter.mode_rtl.init(true); + if (copter.mode_rtl.init(true)) { + set_submode(SubMode::RTL); + } else { + // this should never happen because RTL never fails init if argument is true + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + } } -// auto_takeoff_start - initialises waypoint controller to implement take-off +// initialise waypoint controller to implement take-off void ModeAuto::takeoff_start(const Location& dest_loc) { - _mode = SubMode::TAKEOFF; - - Location dest(dest_loc); - if (!copter.current_loc.initialised()) { - // vehicle doesn't know where it is ATM. We should not - // initialise our takeoff destination without knowing this! + // this should never happen because mission commands are not executed until + // the AHRS/EKF origin is set by which time current_loc should also have been set + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); return; } - // set horizontal target - dest.lat = copter.current_loc.lat; - dest.lng = copter.current_loc.lng; + // calculate current and target altitudes + // by default current_alt_cm and alt_target_cm are alt-above-EKF-origin + int32_t alt_target_cm; + bool alt_target_terrain = false; + float current_alt_cm = inertial_nav.get_position_z_up_cm(); + float terrain_offset; // terrain's altitude in cm above the ekf origin + if ((dest_loc.get_alt_frame() == Location::AltFrame::ABOVE_TERRAIN) && wp_nav->get_terrain_offset(terrain_offset)) { + // subtract terrain offset to convert vehicle's alt-above-ekf-origin to alt-above-terrain + current_alt_cm -= terrain_offset; - // get altitude target - int32_t alt_target; - if (!dest.get_alt_cm(Location::AltFrame::ABOVE_HOME, alt_target)) { - // this failure could only happen if take-off alt was specified as an alt-above terrain and we have no terrain data - AP::logger().Write_Error(LogErrorSubsystem::TERRAIN, LogErrorCode::MISSING_TERRAIN_DATA); - // fall back to altitude above current altitude - alt_target = copter.current_loc.alt + dest.alt; + // specify alt_target_cm as alt-above-terrain + alt_target_cm = dest_loc.alt; + alt_target_terrain = true; + } else { + // set horizontal target + Location dest(dest_loc); + dest.lat = copter.current_loc.lat; + dest.lng = copter.current_loc.lng; + + // get altitude target above EKF origin + if (!dest.get_alt_cm(Location::AltFrame::ABOVE_ORIGIN, alt_target_cm)) { + // this failure could only happen if take-off alt was specified as an alt-above terrain and we have no terrain data + AP::logger().Write_Error(LogErrorSubsystem::TERRAIN, LogErrorCode::MISSING_TERRAIN_DATA); + // fall back to altitude above current altitude + alt_target_cm = current_alt_cm + dest.alt; + } } // sanity check target - int32_t alt_target_min_cm = copter.current_loc.alt + (copter.ap.land_complete ? 100 : 0); - if (alt_target < alt_target_min_cm ) { - dest.set_alt_cm(alt_target_min_cm , Location::AltFrame::ABOVE_HOME); - } - - // set waypoint controller target - if (!wp_nav->set_wp_destination_loc(dest)) { - // failure to set destination can only be because of missing terrain data - copter.failsafe_terrain_on_event(); - return; - } + int32_t alt_target_min_cm = current_alt_cm + (copter.ap.land_complete ? 100 : 0); + alt_target_cm = MAX(alt_target_cm, alt_target_min_cm); // initialise yaw auto_yaw.set_mode(AUTO_YAW_HOLD); // clear i term when we're taking off - set_throttle_takeoff(); + pos_control->init_z_controller(); + + // initialise alt for WP_NAVALT_MIN and set completion alt + auto_takeoff_start(alt_target_cm, alt_target_terrain); - // get initial alt for WP_NAVALT_MIN - auto_takeoff_set_start_alt(); + // set submode + set_submode(SubMode::TAKEOFF); } // auto_wp_start - initialises waypoint controller to implement flying to a particular destination void ModeAuto::wp_start(const Location& dest_loc) { + // init wpnav and set origin if transitioning from takeoff + if (!wp_nav->is_active()) { + Vector3f stopping_point; + if (_mode == SubMode::TAKEOFF) { + Vector3p takeoff_complete_pos; + if (auto_takeoff_get_position(takeoff_complete_pos)) { + stopping_point = takeoff_complete_pos.tofloat(); + } + } + wp_nav->wp_and_spline_init(0, stopping_point); + } + // send target to waypoint controller if (!wp_nav->set_wp_destination_loc(dest_loc)) { // failure to set destination can only be because of missing terrain data @@ -316,33 +369,31 @@ void ModeAuto::wp_start(const Location& dest_loc) return; } - _mode = SubMode::WP; - // initialise yaw // To-Do: reset the yaw only when the previous navigation command is not a WP. this would allow removing the special check for ROI if (auto_yaw.mode() != AUTO_YAW_ROI) { auto_yaw.set_mode_to_default(false); } + + // set submode + set_submode(SubMode::WP); } // auto_land_start - initialises controller to implement a landing void ModeAuto::land_start() { - // set target to stopping point - Vector2f stopping_point; - loiter_nav->get_stopping_point_xy(stopping_point); - - // call location specific land start function - land_start(stopping_point); -} + // set horizontal speed and acceleration limits + pos_control->set_max_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration()); + pos_control->set_correction_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration()); -// auto_land_start - initialises controller to implement a landing -void ModeAuto::land_start(const Vector2f& destination) -{ - _mode = SubMode::LAND; + // initialise the vertical position controller + if (!pos_control->is_active_xy()) { + pos_control->init_xy_controller(); + } - // initialise loiter target destination - loiter_nav->init_target(destination); + // set vertical speed and acceleration limits + pos_control->set_max_speed_accel_z(wp_nav->get_default_speed_down(), wp_nav->get_default_speed_up(), wp_nav->get_accel_z()); + pos_control->set_correction_speed_accel_z(wp_nav->get_default_speed_down(), wp_nav->get_default_speed_up(), wp_nav->get_accel_z()); // initialise the vertical position controller if (!pos_control->is_active_z()) { @@ -357,7 +408,7 @@ void ModeAuto::land_start(const Vector2f& destination) copter.landinggear.deploy_for_landing(); #endif -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // disable the fence on landing copter.fence.auto_disable_fence_for_landing(); #endif @@ -367,6 +418,9 @@ void ModeAuto::land_start(const Vector2f& destination) // this will be set true if prec land is later active copter.ap.prec_land_active = false; + + // set submode + set_submode(SubMode::LAND); } // auto_circle_movetoedge_start - initialise waypoint controller to move to edge of a circle with it's center at the specified location @@ -378,7 +432,7 @@ void ModeAuto::circle_movetoedge_start(const Location &circle_center, float radi // set circle radius if (!is_zero(radius_m)) { - copter.circle_nav->set_radius(radius_m * 100.0f); + copter.circle_nav->set_radius_cm(radius_m * 100.0f); } // check our distance from edge of circle @@ -388,9 +442,6 @@ void ModeAuto::circle_movetoedge_start(const Location &circle_center, float radi // if more than 3m then fly to edge if (dist_to_edge > 300.0f) { - // set the state to move to the edge of the circle - _mode = SubMode::CIRCLE_MOVE_TO_EDGE; - // convert circle_edge_neu to Location Location circle_edge(circle_edge_neu, Location::AltFrame::ABOVE_ORIGIN); @@ -415,6 +466,9 @@ void ModeAuto::circle_movetoedge_start(const Location &circle_center, float radi auto_yaw.set_mode(AUTO_YAW_HOLD); } } + + // set the submode to move to the edge of the circle + set_submode(SubMode::CIRCLE_MOVE_TO_EDGE); } else { circle_start(); } @@ -424,27 +478,33 @@ void ModeAuto::circle_movetoedge_start(const Location &circle_center, float radi // assumes that circle_nav object has already been initialised with circle center and radius void ModeAuto::circle_start() { - _mode = SubMode::CIRCLE; - // initialise circle controller copter.circle_nav->init(copter.circle_nav->get_center(), copter.circle_nav->center_is_terrain_alt()); if (auto_yaw.mode() != AUTO_YAW_ROI) { auto_yaw.set_mode(AUTO_YAW_CIRCLE); } + + // set submode to circle + set_submode(SubMode::CIRCLE); } #if NAV_GUIDED == ENABLED // auto_nav_guided_start - hand over control to external navigation controller in AUTO mode void ModeAuto::nav_guided_start() { - _mode = SubMode::NAVGUIDED; - // call regular guided flight mode initialisation - copter.mode_guided.init(true); + if (!copter.mode_guided.init(true)) { + // this should never happen because guided mode never fails to init + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + return; + } // initialise guided start time and position as reference for limit checking copter.mode_guided.limit_init_time_and_pos(); + + // set submode + set_submode(SubMode::NAVGUIDED); } #endif //NAV_GUIDED @@ -463,18 +523,37 @@ bool ModeAuto::is_landing() const bool ModeAuto::is_taking_off() const { - return ((_mode == SubMode::TAKEOFF) && !wp_nav->reached_wp_destination()); + return ((_mode == SubMode::TAKEOFF) && !auto_takeoff_complete); } // auto_payload_place_start - initialises controller to implement a placing void ModeAuto::payload_place_start() { - // set target to stopping point - Vector2f stopping_point; - loiter_nav->get_stopping_point_xy(stopping_point); + nav_payload_place.state = PayloadPlaceStateType_Calibrating_Hover_Start; - // call location specific place start function - payload_place_start(stopping_point); + // set horizontal speed and acceleration limits + pos_control->set_max_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration()); + pos_control->set_correction_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration()); + + // initialise the vertical position controller + if (!pos_control->is_active_xy()) { + pos_control->init_xy_controller(); + } + + // set vertical speed and acceleration limits + pos_control->set_max_speed_accel_z(wp_nav->get_default_speed_down(), wp_nav->get_default_speed_up(), wp_nav->get_accel_z()); + pos_control->set_correction_speed_accel_z(wp_nav->get_default_speed_down(), wp_nav->get_default_speed_up(), wp_nav->get_accel_z()); + + // initialise the vertical position controller + if (!pos_control->is_active_z()) { + pos_control->init_z_controller(); + } + + // initialise yaw + auto_yaw.set_mode(AUTO_YAW_HOLD); + + // set submode + set_submode(SubMode::NAV_PAYLOAD_PLACE); } // returns true if pilot's yaw input should be used to adjust vehicle's heading @@ -483,6 +562,24 @@ bool ModeAuto::use_pilot_yaw(void) const return (copter.g2.auto_options.get() & uint32_t(Options::IgnorePilotYaw)) == 0; } +bool ModeAuto::set_speed_xy(float speed_xy_cms) +{ + copter.wp_nav->set_speed_xy(speed_xy_cms); + return true; +} + +bool ModeAuto::set_speed_up(float speed_up_cms) +{ + copter.wp_nav->set_speed_up(speed_up_cms); + return true; +} + +bool ModeAuto::set_speed_down(float speed_down_cms) +{ + copter.wp_nav->set_speed_down(speed_down_cms); + return true; +} + // start_command - this function will be called when the ap_mission lib wishes to start a new command bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd) { @@ -496,6 +593,7 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd) /// /// navigation commands /// + case MAV_CMD_NAV_VTOL_TAKEOFF: case MAV_CMD_NAV_TAKEOFF: // 22 do_takeoff(cmd); break; @@ -504,6 +602,7 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd) do_nav_wp(cmd); break; + case MAV_CMD_NAV_VTOL_LAND: case MAV_CMD_NAV_LAND: // 21 LAND to Waypoint do_land(cmd); break; @@ -552,6 +651,10 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd) break; #endif + case MAV_CMD_NAV_ATTITUDE_TIME: + do_nav_attitude_time(cmd); + break; + // // conditional commands // @@ -589,7 +692,7 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd) break; case MAV_CMD_DO_FENCE_ENABLE: -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED if (cmd.p1 == 0) { //disable copter.fence.enable(false); gcs().send_text(MAV_SEVERITY_INFO, "Fence Disabled"); @@ -597,7 +700,7 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd) copter.fence.enable(true); gcs().send_text(MAV_SEVERITY_INFO, "Fence Enabled"); } -#endif //AC_FENCE == ENABLED +#endif //AP_FENCE_ENABLED break; #if NAV_GUIDED == ENABLED @@ -645,7 +748,7 @@ void ModeAuto::exit_mission() bool ModeAuto::do_guided(const AP_Mission::Mission_Command& cmd) { // only process guided waypoint if we are in guided mode - if (copter.flightmode->mode_number() != Mode::Number::GUIDED && !(copter.flightmode->mode_number() == Mode::Number::AUTO && mode() == SubMode::NAVGUIDED)) { + if (copter.flightmode->mode_number() != Mode::Number::GUIDED && !(copter.flightmode->mode_number() == Mode::Number::AUTO && _mode == SubMode::NAVGUIDED)) { return false; } @@ -732,6 +835,7 @@ bool ModeAuto::verify_command(const AP_Mission::Mission_Command& cmd) // // navigation commands // + case MAV_CMD_NAV_VTOL_TAKEOFF: case MAV_CMD_NAV_TAKEOFF: cmd_complete = verify_takeoff(); break; @@ -740,6 +844,7 @@ bool ModeAuto::verify_command(const AP_Mission::Mission_Command& cmd) cmd_complete = verify_nav_wp(cmd); break; + case MAV_CMD_NAV_VTOL_LAND: case MAV_CMD_NAV_LAND: cmd_complete = verify_land(); break; @@ -787,6 +892,10 @@ bool ModeAuto::verify_command(const AP_Mission::Mission_Command& cmd) break; #endif + case MAV_CMD_NAV_ATTITUDE_TIME: + cmd_complete = verify_nav_attitude_time(cmd); + break; + /// /// conditional commands /// @@ -860,7 +969,6 @@ void ModeAuto::wp_run() // if not armed set throttle to zero and exit immediately if (is_disarmed_or_landed()) { make_safe_ground_handling(); - wp_nav->wp_and_spline_init(); return; } @@ -892,8 +1000,6 @@ void ModeAuto::land_run() // if not armed set throttle to zero and exit immediately if (is_disarmed_or_landed()) { make_safe_ground_handling(); - loiter_nav->clear_pilot_desired_acceleration(); - loiter_nav->init_target(); return; } @@ -959,7 +1065,6 @@ void ModeAuto::loiter_run() // if not armed set throttle to zero and exit immediately if (is_disarmed_or_landed()) { make_safe_ground_handling(); - wp_nav->wp_and_spline_init(); return; } @@ -985,7 +1090,7 @@ void ModeAuto::loiter_to_alt_run() { // if not auto armed or motor interlock not enabled set throttle to zero and exit immediately if (is_disarmed_or_landed() || !motors->get_interlock()) { - zero_throttle_and_relax_ac(); + make_safe_ground_handling(); return; } @@ -999,9 +1104,14 @@ void ModeAuto::loiter_to_alt_run() } if (!loiter_to_alt.loiter_start_done) { - loiter_nav->clear_pilot_desired_acceleration(); - loiter_nav->init_target(); - _mode = SubMode::LOITER_TO_ALT; + // set horizontal speed and acceleration limits + pos_control->set_max_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration()); + pos_control->set_correction_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration()); + + if (!pos_control->is_active_xy()) { + pos_control->init_xy_controller(); + } + loiter_to_alt.loiter_start_done = true; } const float alt_error_cm = copter.current_loc.alt - loiter_to_alt.alt; @@ -1038,20 +1148,33 @@ void ModeAuto::loiter_to_alt_run() pos_control->update_z_controller(); } -// auto_payload_place_start - initialises controller to implement placement of a load -void ModeAuto::payload_place_start(const Vector2f& destination) +// maintain an attitude for a specified time +void ModeAuto::nav_attitude_time_run() { - _mode = SubMode::NAV_PAYLOAD_PLACE; - nav_payload_place.state = PayloadPlaceStateType_Calibrating_Hover_Start; + // if not auto armed or motor interlock not enabled set throttle to zero and exit immediately + if (is_disarmed_or_landed() || !motors->get_interlock()) { + make_safe_ground_handling(); + return; + } - // initialise loiter target destination - loiter_nav->init_target(destination); + // constrain climb rate + float target_climb_rate_cms = constrain_float(nav_attitude_time.climb_rate * 100.0, pos_control->get_max_speed_down_cms(), pos_control->get_max_speed_up_cms()); - // initialise the vertical position controller - pos_control->init_z_controller(); + // get avoidance adjusted climb rate + target_climb_rate_cms = get_avoidance_adjusted_climbrate(target_climb_rate_cms); - // initialise yaw - auto_yaw.set_mode(AUTO_YAW_HOLD); + // limit and scale lean angles + const float angle_limit_cd = MAX(1000.0f, MIN(copter.aparm.angle_max, attitude_control->get_althold_lean_angle_max_cd())); + Vector2f target_rp_cd(nav_attitude_time.roll_deg * 100, nav_attitude_time.pitch_deg * 100); + target_rp_cd.limit_length(angle_limit_cd); + + // send targets to attitude controller + attitude_control->input_euler_angle_roll_pitch_yaw(target_rp_cd.x, target_rp_cd.y, nav_attitude_time.yaw_deg * 100, true); + + // Send the commanded climb rate to the position controller + pos_control->set_pos_target_z_from_climb_rate_cm(target_climb_rate_cms); + + pos_control->update_z_controller(); } // auto_payload_place_run - places an object in auto mode @@ -1060,9 +1183,6 @@ void ModeAuto::payload_place_run() { if (!payload_place_run_should_run()) { zero_throttle_and_relax_ac(); - // set target to current position - loiter_nav->clear_pilot_desired_acceleration(); - loiter_nav->init_target(); return; } @@ -1074,7 +1194,7 @@ void ModeAuto::payload_place_run() return wp_run(); case PayloadPlaceStateType_Calibrating_Hover_Start: case PayloadPlaceStateType_Calibrating_Hover: - return payload_place_run_loiter(); + return payload_place_run_hover(); case PayloadPlaceStateType_Descending_Start: case PayloadPlaceStateType_Descending: return payload_place_run_descend(); @@ -1082,10 +1202,10 @@ void ModeAuto::payload_place_run() case PayloadPlaceStateType_Releasing: case PayloadPlaceStateType_Released: case PayloadPlaceStateType_Ascending_Start: - return payload_place_run_loiter(); + return payload_place_run_hover(); case PayloadPlaceStateType_Ascending: case PayloadPlaceStateType_Done: - return wp_run(); + return takeoff_run(); } } @@ -1100,7 +1220,7 @@ bool ModeAuto::payload_place_run_should_run() return false; } // must not be landed - if (copter.ap.land_complete) { + if (copter.ap.land_complete && (nav_payload_place.state == PayloadPlaceStateType_FlyToLocation || nav_payload_place.state == PayloadPlaceStateType_Calibrating_Hover_Start)) { return false; } // interlock must be enabled (i.e. unsafe) @@ -1111,13 +1231,10 @@ bool ModeAuto::payload_place_run_should_run() return true; } -void ModeAuto::payload_place_run_loiter() +void ModeAuto::payload_place_run_hover() { - // loiter... land_run_horizontal_control(); - - // call position controller - pos_control->update_z_controller(); + land_run_vertical_control(true); } void ModeAuto::payload_place_run_descend() @@ -1126,25 +1243,33 @@ void ModeAuto::payload_place_run_descend() land_run_vertical_control(); } -// terrain_adjusted_location: returns a Location with lat/lon from cmd -// and altitude from our current altitude adjusted for location -Location ModeAuto::terrain_adjusted_location(const AP_Mission::Mission_Command& cmd) const +// sets the target_loc's alt to the vehicle's current alt but does not change target_loc's frame +// in the case of terrain altitudes either the terrain database or the rangefinder may be used +// returns true on success, false on failure +bool ModeAuto::shift_alt_to_current_alt(Location& target_loc) const { - // convert to location class - Location target_loc(cmd.content.location); + // if terrain alt using rangefinder is being used then set alt to current rangefinder altitude + if ((target_loc.get_alt_frame() == Location::AltFrame::ABOVE_TERRAIN) && + (wp_nav->get_terrain_source() == AC_WPNav::TerrainSource::TERRAIN_FROM_RANGEFINDER)) { + int32_t curr_rngfnd_alt_cm; + if (copter.get_rangefinder_height_interpolated_cm(curr_rngfnd_alt_cm)) { + // wp_nav is using rangefinder so use current rangefinder alt + target_loc.set_alt_cm(MAX(curr_rngfnd_alt_cm, 200), Location::AltFrame::ABOVE_TERRAIN); + return true; + } + return false; + } - // decide if we will use terrain following - int32_t curr_terr_alt_cm, target_terr_alt_cm; - if (copter.current_loc.get_alt_cm(Location::AltFrame::ABOVE_TERRAIN, curr_terr_alt_cm) && - target_loc.get_alt_cm(Location::AltFrame::ABOVE_TERRAIN, target_terr_alt_cm)) { - curr_terr_alt_cm = MAX(curr_terr_alt_cm,200); - // if using terrain, set target altitude to current altitude above terrain - target_loc.set_alt_cm(curr_terr_alt_cm, Location::AltFrame::ABOVE_TERRAIN); - } else { - // set target altitude to current altitude above home - target_loc.set_alt_cm(copter.current_loc.alt, Location::AltFrame::ABOVE_HOME); + // take copy of current location and change frame to match target + Location currloc = copter.current_loc; + if (!currloc.change_alt_frame(target_loc.get_alt_frame())) { + // this could fail due missing terrain database alt + return false; } - return target_loc; + + // set target_loc's alt + target_loc.set_alt_cm(currloc.alt, currloc.get_alt_frame()); + return true; } /********************************************************************************/ @@ -1194,6 +1319,18 @@ void ModeAuto::do_nav_wp(const AP_Mission::Mission_Command& cmd) } } + // init wpnav and set origin if transitioning from takeoff + if (!wp_nav->is_active()) { + Vector3f stopping_point; + if (_mode == SubMode::TAKEOFF) { + Vector3p takeoff_complete_pos; + if (auto_takeoff_get_position(takeoff_complete_pos)) { + stopping_point = takeoff_complete_pos.tofloat(); + } + } + wp_nav->wp_and_spline_init(0, stopping_point); + } + // get waypoint's location from command and send to wp_nav const Location dest_loc = loc_from_cmd(cmd, default_loc); if (!wp_nav->set_wp_destination_loc(dest_loc)) { @@ -1202,8 +1339,6 @@ void ModeAuto::do_nav_wp(const AP_Mission::Mission_Command& cmd) return; } - _mode = SubMode::WP; - // this will be used to remember the time in millis after we reach or pass the WP. loiter_time = 0; // this is the delay, stored in seconds @@ -1221,6 +1356,9 @@ void ModeAuto::do_nav_wp(const AP_Mission::Mission_Command& cmd) if (auto_yaw.mode() != AUTO_YAW_ROI) { auto_yaw.set_mode_to_default(false); } + + // set submode + set_submode(SubMode::WP); } // checks the next mission command and adds it as a destination if necessary @@ -1257,10 +1395,12 @@ bool ModeAuto::set_next_wp(const AP_Mission::Mission_Command& current_cmd, const get_spline_from_cmd(next_cmd, default_loc, next_dest_loc, next_next_dest_loc, next_next_dest_loc_is_spline); return wp_nav->set_spline_destination_next_loc(next_dest_loc, next_next_dest_loc, next_next_dest_loc_is_spline); } + case MAV_CMD_NAV_VTOL_LAND: case MAV_CMD_NAV_LAND: // stop because we may change between rel,abs and terrain alt types case MAV_CMD_NAV_LOITER_TURNS: case MAV_CMD_NAV_RETURN_TO_LAUNCH: + case MAV_CMD_NAV_VTOL_TAKEOFF: case MAV_CMD_NAV_TAKEOFF: // always stop for RTL and takeoff commands default: @@ -1281,7 +1421,15 @@ void ModeAuto::do_land(const AP_Mission::Mission_Command& cmd) // set state to fly to location state = State::FlyToLocation; - const Location target_loc = terrain_adjusted_location(cmd); + // convert cmd to location class + Location target_loc(cmd.content.location); + if (!shift_alt_to_current_alt(target_loc)) { + // this can only fail due to missing terrain database alt or rangefinder alt + // use current alt-above-home and report error + target_loc.set_alt_cm(copter.current_loc.alt, Location::AltFrame::ABOVE_HOME); + AP::logger().Write_Error(LogErrorSubsystem::TERRAIN, LogErrorCode::MISSING_TERRAIN_DATA); + gcs().send_text(MAV_SEVERITY_CRITICAL, "Land: no terrain data, using alt-above-home"); + } wp_start(target_loc); } else { @@ -1334,7 +1482,12 @@ void ModeAuto::do_circle(const AP_Mission::Mission_Command& cmd) const Location circle_center = loc_from_cmd(cmd, copter.current_loc); // calculate radius - uint8_t circle_radius_m = HIGHBYTE(cmd.p1); // circle radius held in high byte of p1 + uint16_t circle_radius_m = HIGHBYTE(cmd.p1); // circle radius held in high byte of p1 + if (cmd.id == MAV_CMD_NAV_LOITER_TURNS && + cmd.type_specific_bits & (1U << 0)) { + // special storage handling allows for larger radii + circle_radius_m *= 10; + } // move to edge of circle (verify_circle) will ensure we begin circling once we reach the edge circle_movetoedge_start(circle_center, circle_radius_m); @@ -1358,7 +1511,6 @@ void ModeAuto::do_loiter_to_alt(const AP_Mission::Mission_Command& cmd) { // re-use loiter unlimited do_loiter_unlimited(cmd); - _mode = SubMode::LOITER_TO_ALT; // if we aren't navigating to a location then we have to adjust // altitude for current location @@ -1381,6 +1533,10 @@ void ModeAuto::do_loiter_to_alt(const AP_Mission::Mission_Command& cmd) // set vertical speed and acceleration limits pos_control->set_max_speed_accel_z(wp_nav->get_default_speed_down(), wp_nav->get_default_speed_up(), wp_nav->get_accel_z()); + pos_control->set_correction_speed_accel_z(wp_nav->get_default_speed_down(), wp_nav->get_default_speed_up(), wp_nav->get_accel_z()); + + // set submode + set_submode(SubMode::LOITER_TO_ALT); } // do_spline_wp - initiate move to next waypoint @@ -1405,8 +1561,6 @@ void ModeAuto::do_spline_wp(const AP_Mission::Mission_Command& cmd) return; } - _mode = SubMode::WP; - // this will be used to remember the time in millis after we reach or pass the WP. loiter_time = 0; // this is the delay, stored in seconds @@ -1424,6 +1578,9 @@ void ModeAuto::do_spline_wp(const AP_Mission::Mission_Command& cmd) if (auto_yaw.mode() != AUTO_YAW_ROI) { auto_yaw.set_mode_to_default(false); } + + // set submode + set_submode(SubMode::WP); } // calculate locations required to build a spline curve from a mission command @@ -1486,7 +1643,6 @@ void ModeAuto::do_nav_script_time(const AP_Mission::Mission_Command& cmd) { // call regular guided flight mode initialisation if (copter.mode_guided.init(true)) { - _mode = SubMode::NAV_SCRIPT_TIME; nav_scripting.done = false; nav_scripting.id++; nav_scripting.start_ms = millis(); @@ -1494,6 +1650,7 @@ void ModeAuto::do_nav_script_time(const AP_Mission::Mission_Command& cmd) nav_scripting.timeout_s = cmd.content.nav_script_time.timeout_s; nav_scripting.arg1 = cmd.content.nav_script_time.arg1; nav_scripting.arg2 = cmd.content.nav_script_time.arg2; + set_submode(SubMode::NAV_SCRIPT_TIME); } else { // for safety we set nav_scripting to done to protect against the mission getting stuck nav_scripting.done = true; @@ -1501,6 +1658,17 @@ void ModeAuto::do_nav_script_time(const AP_Mission::Mission_Command& cmd) } #endif +// start maintaining an attitude for a specified time +void ModeAuto::do_nav_attitude_time(const AP_Mission::Mission_Command& cmd) +{ + // copy command arguments into local structure + nav_attitude_time.roll_deg = cmd.content.nav_attitude_time.roll_deg; + nav_attitude_time.pitch_deg = cmd.content.nav_attitude_time.pitch_deg; + nav_attitude_time.yaw_deg = cmd.content.nav_attitude_time.yaw_deg; + nav_attitude_time.climb_rate = cmd.content.nav_attitude_time.climb_rate; + nav_attitude_time.start_ms = AP_HAL::millis(); + set_submode(SubMode::NAV_ATTITUDE_TIME); +} /********************************************************************************/ // Condition (May) commands @@ -1577,7 +1745,7 @@ void ModeAuto::do_mount_control(const AP_Mission::Mission_Command& cmd) auto_yaw.set_yaw_angle_rate(cmd.content.mount_control.yaw,0.0f); } // pass the target angles to the camera mount - copter.camera_mount.set_angle_targets(cmd.content.mount_control.roll, cmd.content.mount_control.pitch, cmd.content.mount_control.yaw); + copter.camera_mount.set_angle_target(cmd.content.mount_control.roll, cmd.content.mount_control.pitch, cmd.content.mount_control.yaw, false); #endif } @@ -1611,7 +1779,15 @@ void ModeAuto::do_payload_place(const AP_Mission::Mission_Command& cmd) // set state to fly to location nav_payload_place.state = PayloadPlaceStateType_FlyToLocation; - const Location target_loc = terrain_adjusted_location(cmd); + // convert cmd to location class + Location target_loc(cmd.content.location); + if (!shift_alt_to_current_alt(target_loc)) { + // this can only fail due to missing terrain database alt or rangefinder alt + // use current alt-above-home and report error + target_loc.set_alt_cm(copter.current_loc.alt, Location::AltFrame::ABOVE_HOME); + AP::logger().Write_Error(LogErrorSubsystem::TERRAIN, LogErrorCode::MISSING_TERRAIN_DATA); + gcs().send_text(MAV_SEVERITY_CRITICAL, "PayloadPlace: no terrain data, using alt-above-home"); + } wp_start(target_loc); } else { @@ -1637,18 +1813,15 @@ void ModeAuto::do_RTL(void) // verify_takeoff - check if we have completed the takeoff bool ModeAuto::verify_takeoff() { - // have we reached our target altitude? - const bool reached_wp_dest = copter.wp_nav->reached_wp_destination(); - #if LANDING_GEAR_ENABLED == ENABLED // if we have reached our destination - if (reached_wp_dest) { + if (auto_takeoff_complete) { // retract the landing gear copter.landinggear.retract_after_takeoff(); } #endif - return reached_wp_dest; + return auto_takeoff_complete; } // verify_land - returns true if landing has been completed @@ -1660,11 +1833,8 @@ bool ModeAuto::verify_land() case State::FlyToLocation: // check if we've reached the location if (copter.wp_nav->reached_wp_destination()) { - // get destination so we can use it for loiter target - const Vector2f& dest = copter.wp_nav->get_wp_destination().xy(); - // initialise landing controller - land_start(dest); + land_start(); // advance to next state state = State::Descending; @@ -1711,6 +1881,7 @@ bool ModeAuto::verify_payload_place() { const uint16_t hover_throttle_calibrate_time = 2000; // milliseconds const uint16_t descend_throttle_calibrate_time = 2000; // milliseconds + const uint16_t measure_time = 1000; // milliseconds const float hover_throttle_placed_fraction = 0.7; // i.e. if throttle is less than 70% of hover we have placed const float descent_throttle_placed_fraction = 0.9; // i.e. if throttle is less than 90% of descent throttle we have placed const uint16_t placed_time = 500; // how long we have to be below a throttle threshold before considering placed @@ -1719,7 +1890,7 @@ bool ModeAuto::verify_payload_place() const uint32_t now = AP_HAL::millis(); // if we discover we've landed then immediately release the load: - if (copter.ap.land_complete) { + if (copter.ap.land_complete || copter.ap.land_complete_maybe) { switch (nav_payload_place.state) { case PayloadPlaceStateType_FlyToLocation: case PayloadPlaceStateType_Calibrating_Hover_Start: @@ -1747,77 +1918,79 @@ bool ModeAuto::verify_payload_place() payload_place_start(); return false; case PayloadPlaceStateType_Calibrating_Hover_Start: - // hover for 1 second to get an idea of what our hover - // throttle looks like + // hover for 2 seconds to measure hover thrust debug("Calibrate start"); nav_payload_place.hover_start_timestamp = now; + nav_payload_place.hover_throttle_level = 1.0; nav_payload_place.state = PayloadPlaceStateType_Calibrating_Hover; FALLTHROUGH; case PayloadPlaceStateType_Calibrating_Hover: { + if (now - nav_payload_place.hover_start_timestamp < hover_throttle_calibrate_time - measure_time) { + // waiting for aircraft to settle + return false; + } if (now - nav_payload_place.hover_start_timestamp < hover_throttle_calibrate_time) { - // still calibrating... - debug("Calibrate Timer: %d", now - nav_payload_place.hover_start_timestamp); + // measure hover thrust + nav_payload_place.hover_throttle_level = MIN(nav_payload_place.hover_throttle_level, current_throttle_level); return false; } - // we have a valid calibration. Hopefully. - nav_payload_place.hover_throttle_level = current_throttle_level; - const float hover_throttle_delta = fabsf(nav_payload_place.hover_throttle_level - motors->get_throttle_hover()); - gcs().send_text(MAV_SEVERITY_INFO, "hover throttle delta: %f", static_cast(hover_throttle_delta)); + // hover thrust has been measured + gcs().send_text(MAV_SEVERITY_INFO, "PayloadPlace: payload hover throttle: %f", static_cast(nav_payload_place.hover_throttle_level)); nav_payload_place.state = PayloadPlaceStateType_Descending_Start; } FALLTHROUGH; case PayloadPlaceStateType_Descending_Start: nav_payload_place.descend_start_timestamp = now; nav_payload_place.descend_start_altitude = inertial_nav.get_position_z_up_cm(); - nav_payload_place.descend_throttle_level = 0; + nav_payload_place.descend_throttle_level = 1.0; nav_payload_place.state = PayloadPlaceStateType_Descending; FALLTHROUGH; case PayloadPlaceStateType_Descending: - // make sure we don't descend too far: + // make sure we don't descend too far debug("descended: %f cm (%f cm max)", (nav_payload_place.descend_start_altitude - inertial_nav.get_position_z_up_cm()), nav_payload_place.descend_max); if (!is_zero(nav_payload_place.descend_max) && nav_payload_place.descend_start_altitude - inertial_nav.get_position_z_up_cm() > nav_payload_place.descend_max) { - nav_payload_place.state = PayloadPlaceStateType_Ascending; - gcs().send_text(MAV_SEVERITY_WARNING, "Reached maximum descent"); + nav_payload_place.state = PayloadPlaceStateType_Ascending_Start; + gcs().send_text(MAV_SEVERITY_WARNING, "PayloadPlace: Reached maximum descent"); return false; // we'll do any cleanups required next time through the loop } - // see if we've been descending long enough to calibrate a descend-throttle-level: - if (is_zero(nav_payload_place.descend_throttle_level) && - now - nav_payload_place.descend_start_timestamp > descend_throttle_calibrate_time) { - nav_payload_place.descend_throttle_level = current_throttle_level; + // if the aircraft has been descending long enough, calibrate the decent thrust + if ((now - nav_payload_place.descend_start_timestamp > descend_throttle_calibrate_time - measure_time) && + (now - nav_payload_place.descend_start_timestamp < descend_throttle_calibrate_time)) { + // measure decent thrust + nav_payload_place.descend_throttle_level = MIN(nav_payload_place.descend_throttle_level, current_throttle_level); } - // watch the throttle to determine whether the load has been placed - // debug("hover ratio: %f descend ratio: %f\n", current_throttle_level/nav_payload_place.hover_throttle_level, ((nav_payload_place.descend_throttle_level == 0) ? -1.0f : current_throttle_level/nav_payload_place.descend_throttle_level)); - if (current_throttle_level/nav_payload_place.hover_throttle_level > hover_throttle_placed_fraction && - (is_zero(nav_payload_place.descend_throttle_level) || - current_throttle_level/nav_payload_place.descend_throttle_level > descent_throttle_placed_fraction)) { + // check for reduced thrust requirement indicating possible payload touch down + if (current_throttle_level > hover_throttle_placed_fraction * nav_payload_place.hover_throttle_level && + (now - nav_payload_place.descend_start_timestamp < descend_throttle_calibrate_time || + current_throttle_level > descent_throttle_placed_fraction * nav_payload_place.descend_throttle_level)) { // throttle is above both threshold ratios (or above hover threshold ration and descent threshold ratio not yet valid) - nav_payload_place.place_start_timestamp = 0; - return false; - } - if (nav_payload_place.place_start_timestamp == 0) { - // we've only just now hit the correct throttle level nav_payload_place.place_start_timestamp = now; return false; - } else if (now - nav_payload_place.place_start_timestamp < placed_time) { - // keep going down.... + } + if (now - nav_payload_place.place_start_timestamp < placed_time) { + // continue decent debug("Place Timer: %d", now - nav_payload_place.place_start_timestamp); return false; } nav_payload_place.state = PayloadPlaceStateType_Releasing_Start; FALLTHROUGH; case PayloadPlaceStateType_Releasing_Start: + // Reinitialise vertical position controller to remove discontinuity due to touch down of payload + pos_control->init_z_controller_no_descent(); #if GRIPPER_ENABLED == ENABLED if (g2.gripper.valid()) { - gcs().send_text(MAV_SEVERITY_INFO, "Releasing the gripper"); + gcs().send_text(MAV_SEVERITY_INFO, "PayloadPlace: Releasing the gripper"); g2.gripper.release(); } else { - gcs().send_text(MAV_SEVERITY_INFO, "Gripper not valid"); + gcs().send_text(MAV_SEVERITY_INFO, "PayloadPlace: Gripper not valid"); nav_payload_place.state = PayloadPlaceStateType_Ascending_Start; - break; + return false; } #else gcs().send_text(MAV_SEVERITY_INFO, "Gripper code disabled"); + nav_payload_place.state = PayloadPlaceStateType_Ascending_Start; + return false; #endif nav_payload_place.state = PayloadPlaceStateType_Releasing; FALLTHROUGH; @@ -1834,14 +2007,12 @@ bool ModeAuto::verify_payload_place() } FALLTHROUGH; case PayloadPlaceStateType_Ascending_Start: { - Location target_loc(inertial_nav.get_position_neu_cm(), Location::AltFrame::ABOVE_ORIGIN); - target_loc.alt = nav_payload_place.descend_start_altitude; - wp_start(target_loc); + auto_takeoff_start(nav_payload_place.descend_start_altitude, false); nav_payload_place.state = PayloadPlaceStateType_Ascending; } FALLTHROUGH; case PayloadPlaceStateType_Ascending: - if (!copter.wp_nav->reached_wp_destination()) { + if (!auto_takeoff_complete) { return false; } nav_payload_place.state = PayloadPlaceStateType_Done; @@ -1971,7 +2142,7 @@ bool ModeAuto::verify_nav_wp(const AP_Mission::Mission_Command& cmd) bool ModeAuto::verify_circle(const AP_Mission::Mission_Command& cmd) { // check if we've reached the edge - if (mode() == SubMode::CIRCLE_MOVE_TO_EDGE) { + if (_mode == SubMode::CIRCLE_MOVE_TO_EDGE) { if (copter.wp_nav->reached_wp_destination()) { // start circling circle_start(); @@ -1980,7 +2151,7 @@ bool ModeAuto::verify_circle(const AP_Mission::Mission_Command& cmd) } // check if we have completed circling - return fabsf(copter.circle_nav->get_angle_total()/M_2PI) >= LOWBYTE(cmd.p1); + return fabsf(copter.circle_nav->get_angle_total()/float(M_2PI)) >= LOWBYTE(cmd.p1); } // verify_spline_wp - check if we have reached the next way point using spline @@ -2042,4 +2213,34 @@ bool ModeAuto::verify_nav_script_time() } #endif +// check if nav_attitude_time command has completed +bool ModeAuto::verify_nav_attitude_time(const AP_Mission::Mission_Command& cmd) +{ + return ((AP_HAL::millis() - nav_attitude_time.start_ms) > (cmd.content.nav_attitude_time.time_sec * 1000)); +} + +// pause - Prevent aircraft from progressing along the track +bool ModeAuto::pause() +{ + // do not pause if already paused or not in the WP sub mode or already reached to the destination + if(wp_nav->paused() || _mode != SubMode::WP || wp_nav->reached_wp_destination()) { + return false; + } + + wp_nav->set_pause(); + return true; +} + +// resume - Allow aircraft to progress along the track +bool ModeAuto::resume() +{ + // do not resume if not paused before + if(!wp_nav->paused()) { + return false; + } + + wp_nav->set_resume(); + return true; +} + #endif diff --git a/ArduCopter/mode_autorotate.cpp b/ArduCopter/mode_autorotate.cpp index dc8873c14c1..fb009a1d342 100644 --- a/ArduCopter/mode_autorotate.cpp +++ b/ArduCopter/mode_autorotate.cpp @@ -41,7 +41,7 @@ bool ModeAutorotate::init(bool ignore_checks) g2.arot.init_hs_controller(); g2.arot.init_fwd_spd_controller(); - // Retrive rpm and start rpm sensor health checks + // Retrieve rpm and start rpm sensor health checks _initial_rpm = g2.arot.get_rpm(true); // Display message @@ -173,7 +173,7 @@ void ModeAutorotate::run() g2.arot.set_desired_fwd_speed(); // Set target head speed in head speed controller - _target_head_speed = HEAD_SPEED_TARGET_RATIO; //Ensure target hs is set to glide incase hs hasent reached target for glide + _target_head_speed = HEAD_SPEED_TARGET_RATIO; //Ensure target hs is set to glide in case hs hasent reached target for glide g2.arot.set_target_head_speed(_target_head_speed); // Prevent running the initial glide functions again @@ -209,7 +209,7 @@ void ModeAutorotate::run() gcs().send_text(MAV_SEVERITY_INFO, "Bailing Out of Autorotation"); #endif - // Set bail out timer remaining equal to the paramter value, bailout time + // Set bail out timer remaining equal to the parameter value, bailout time // cannot be less than the motor spool-up time: BAILOUT_MOTOR_RAMP_TIME. _bail_time = MAX(g2.arot.get_bail_time(),BAILOUT_MOTOR_RAMP_TIME+0.1f); diff --git a/ArduCopter/mode_brake.cpp b/ArduCopter/mode_brake.cpp index 29fe7803d0f..55d71f1c63f 100644 --- a/ArduCopter/mode_brake.cpp +++ b/ArduCopter/mode_brake.cpp @@ -37,7 +37,6 @@ void ModeBrake::run() // if not armed set throttle to zero and exit immediately if (is_disarmed_or_landed()) { make_safe_ground_handling(); - pos_control->relax_velocity_controller_xy(); pos_control->relax_z_controller(0.0f); return; } @@ -47,7 +46,7 @@ void ModeBrake::run() // relax stop target if we might be landed if (copter.ap.land_complete_maybe) { - loiter_nav->soften_for_landing(); + pos_control->soften_for_landing_xy(); } // use position controller to stop diff --git a/ArduCopter/mode_circle.cpp b/ArduCopter/mode_circle.cpp index 6b31b95c768..7ec53c2674f 100644 --- a/ArduCopter/mode_circle.cpp +++ b/ArduCopter/mode_circle.cpp @@ -52,7 +52,7 @@ void ModeCircle::run() const float radius_new = MAX(radius_current + radius_pilot_change,0); // new radius target if (!is_equal(radius_current, radius_new)) { - copter.circle_nav->set_radius(radius_new); + copter.circle_nav->set_radius_cm(radius_new); } // update the orbicular rate target based on pilot roll stick inputs @@ -90,6 +90,9 @@ void ModeCircle::run() // get pilot desired climb rate (or zero if in radio failsafe) float target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->get_control_in()); + // get avoidance adjusted climb rate + target_climb_rate = get_avoidance_adjusted_climbrate(target_climb_rate); + // if not armed set throttle to zero and exit immediately if (is_disarmed_or_landed()) { make_safe_ground_handling(); diff --git a/ArduCopter/mode_drift.cpp b/ArduCopter/mode_drift.cpp index b02bff21acb..9b48478c5a5 100644 --- a/ArduCopter/mode_drift.cpp +++ b/ArduCopter/mode_drift.cpp @@ -54,7 +54,7 @@ void ModeDrift::run() // gain scheduling for yaw float pitch_vel2 = MIN(fabsf(pitch_vel), 2000); - float target_yaw_rate = target_roll * (1.0f - (pitch_vel2 / 5000.0f)) * g2.acro_y_rate / 45.0; + float target_yaw_rate = target_roll * (1.0f - (pitch_vel2 / 5000.0f)) * g2.command_model_acro_y.get_rate() / 45.0; roll_vel = constrain_float(roll_vel, -DRIFT_SPEEDLIMIT, DRIFT_SPEEDLIMIT); pitch_vel = constrain_float(pitch_vel, -DRIFT_SPEEDLIMIT, DRIFT_SPEEDLIMIT); diff --git a/ArduCopter/mode_flowhold.cpp b/ArduCopter/mode_flowhold.cpp index 8551a7d5edc..91814ab45f3 100644 --- a/ArduCopter/mode_flowhold.cpp +++ b/ArduCopter/mode_flowhold.cpp @@ -1,7 +1,7 @@ #include "Copter.h" #include -#if !HAL_MINIMIZE_FEATURES && AP_OPTICALFLOW_ENABLED +#if MODE_FLOWHOLD_ENABLED == ENABLED /* implement FLOWHOLD mode, for position hold using optical flow @@ -179,7 +179,7 @@ void ModeFlowHold::flowhold_flow_to_angle(Vector2f &bf_angles, bool stick_input) for (uint8_t i=0; i<2; i++) { float &velocity = sensor_flow[i]; float abs_vel_cms = fabsf(velocity)*100; - const float brake_gain = (15.0f * brake_rate_dps.get() + 95.0f) / 100.0f; + const float brake_gain = (15.0f * brake_rate_dps.get() + 95.0f) * 0.01f; float lean_angle_cd = brake_gain * abs_vel_cms * (1.0f+500.0f/(abs_vel_cms+60.0f)); if (velocity < 0) { lean_angle_cd = -lean_angle_cd; @@ -509,4 +509,4 @@ void ModeFlowHold::update_height_estimate(void) last_ins_height = ins_height; } -#endif // AP_OPTICALFLOW_ENABLED +#endif // MODE_FLOWHOLD_ENABLED diff --git a/ArduCopter/mode_guided.cpp b/ArduCopter/mode_guided.cpp index 0a26f0aa14b..e30e5dafcbe 100644 --- a/ArduCopter/mode_guided.cpp +++ b/ArduCopter/mode_guided.cpp @@ -40,6 +40,10 @@ bool ModeGuided::init(bool ignore_checks) guided_vel_target_cms.zero(); guided_accel_target_cmss.zero(); send_notification = false; + + // clear pause state when entering guided mode + _paused = false; + return true; } @@ -47,6 +51,12 @@ bool ModeGuided::init(bool ignore_checks) // should be called at 100hz or more void ModeGuided::run() { + // run pause control if the vehicle is paused + if (_paused) { + pause_control_run(); + return; + } + // call the correct auto controller switch (guided_mode) { @@ -98,14 +108,13 @@ bool ModeGuided::allows_arming(AP_Arming::Method method) const return (copter.g2.guided_options & (uint32_t)Options::AllowArmingFromTX) != 0; }; -// do_user_takeoff_start - initialises waypoint controller to implement take-off +// initialises position controller to implement take-off +// takeoff_alt_cm is interpreted as alt-above-home (in cm) or alt-above-terrain if a rangefinder is available bool ModeGuided::do_user_takeoff_start(float takeoff_alt_cm) { - guided_mode = SubMode::TakeOff; - - // initialise wpnav destination - Location target_loc = copter.current_loc; - Location::AltFrame frame = Location::AltFrame::ABOVE_HOME; + // calculate target altitude and frame (either alt-above-ekf-origin or alt-above-terrain) + int32_t alt_target_cm; + bool alt_target_terrain = false; if (wp_nav->rangefinder_used_and_healthy() && wp_nav->get_terrain_source() == AC_WPNav::TerrainSource::TERRAIN_FROM_RANGEFINDER && takeoff_alt_cm < copter.rangefinder.max_distance_cm_orient(ROTATION_PITCH_270)) { @@ -113,25 +122,31 @@ bool ModeGuided::do_user_takeoff_start(float takeoff_alt_cm) if (takeoff_alt_cm <= copter.rangefinder_state.alt_cm) { return false; } - frame = Location::AltFrame::ABOVE_TERRAIN; - } - target_loc.set_alt_cm(takeoff_alt_cm, frame); + // provide target altitude as alt-above-terrain + alt_target_cm = takeoff_alt_cm; + alt_target_terrain = true; + } else { + // interpret altitude as alt-above-home + Location target_loc = copter.current_loc; + target_loc.set_alt_cm(takeoff_alt_cm, Location::AltFrame::ABOVE_HOME); - if (!wp_nav->set_wp_destination_loc(target_loc)) { - // failure to set destination can only be because of missing terrain data - AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::FAILED_TO_SET_DESTINATION); - // failure is propagated to GCS with NAK - return false; + // provide target altitude as alt-above-ekf-origin + if (!target_loc.get_alt_cm(Location::AltFrame::ABOVE_ORIGIN, alt_target_cm)) { + // this should never happen but we reject the command just in case + return false; + } } + guided_mode = SubMode::TakeOff; + // initialise yaw auto_yaw.set_mode(AUTO_YAW_HOLD); // clear i term when we're taking off - set_throttle_takeoff(); + pos_control->init_z_controller(); - // get initial alt for WP_NAVALT_MIN - auto_takeoff_set_start_alt(); + // initialise alt for WP_NAVALT_MIN and set completion alt + auto_takeoff_start(alt_target_cm, alt_target_terrain); // record takeoff has not completed takeoff_complete = false; @@ -151,9 +166,10 @@ void ModeGuided::wp_control_start() // initialise wpnav to stopping point Vector3f stopping_point; wp_nav->get_wp_stopping_point(stopping_point); - - // no need to check return status because terrain data is not used - wp_nav->set_wp_destination(stopping_point, false); + if (!wp_nav->set_wp_destination(stopping_point, false)) { + // this should never happen because terrain data is not used + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + } // initialise yaw auto_yaw.set_mode_to_default(false); @@ -268,6 +284,30 @@ bool ModeGuided::is_taking_off() const return guided_mode == SubMode::TakeOff && !takeoff_complete; } +bool ModeGuided::set_speed_xy(float speed_xy_cms) +{ + // initialise horizontal speed, acceleration + pos_control->set_max_speed_accel_xy(speed_xy_cms, wp_nav->get_wp_acceleration()); + pos_control->set_correction_speed_accel_xy(speed_xy_cms, wp_nav->get_wp_acceleration()); + return true; +} + +bool ModeGuided::set_speed_up(float speed_up_cms) +{ + // initialize vertical speeds and acceleration + pos_control->set_max_speed_accel_z(wp_nav->get_default_speed_down(), speed_up_cms, wp_nav->get_accel_z()); + pos_control->set_correction_speed_accel_z(wp_nav->get_default_speed_down(), speed_up_cms, wp_nav->get_accel_z()); + return true; +} + +bool ModeGuided::set_speed_down(float speed_down_cms) +{ + // initialize vertical speeds and acceleration + pos_control->set_max_speed_accel_z(speed_down_cms, wp_nav->get_default_speed_up(), wp_nav->get_accel_z()); + pos_control->set_correction_speed_accel_z(speed_down_cms, wp_nav->get_default_speed_up(), wp_nav->get_accel_z()); + return true; +} + // initialise guided mode's angle controller void ModeGuided::angle_control_start() { @@ -300,7 +340,7 @@ void ModeGuided::angle_control_start() // else return false if the waypoint is outside the fence bool ModeGuided::set_destination(const Vector3f& destination, bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_yaw, bool terrain_alt) { -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // reject destination if outside the fence const Location dest_loc(destination, terrain_alt ? Location::AltFrame::ABOVE_TERRAIN : Location::AltFrame::ABOVE_ORIGIN); if (!copter.fence.check_destination_within_fence(dest_loc)) { @@ -392,7 +432,7 @@ bool ModeGuided::get_wp(Location& destination) const // or if the fence is enabled and guided waypoint is outside the fence bool ModeGuided::set_destination(const Location& dest_loc, bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_yaw) { -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // reject destination outside the fence. // Note: there is a danger that a target specified as a terrain altitude might not be checked if the conversion to alt-above-home fails if (!copter.fence.check_destination_within_fence(dest_loc)) { @@ -535,7 +575,7 @@ bool ModeGuided::set_destination_posvel(const Vector3f& destination, const Vecto // set_destination_posvelaccel - set guided mode position, velocity and acceleration target bool ModeGuided::set_destination_posvelaccel(const Vector3f& destination, const Vector3f& velocity, const Vector3f& acceleration, bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_yaw) { -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // reject destination if outside the fence const Location dest_loc(destination, Location::AltFrame::ABOVE_ORIGIN); if (!copter.fence.check_destination_within_fence(dest_loc)) { @@ -629,7 +669,7 @@ void ModeGuided::set_angle(const Quaternion &attitude_quat, const Vector3f &ang_ void ModeGuided::takeoff_run() { auto_takeoff_run(); - if (!takeoff_complete && wp_nav->reached_wp_destination()) { + if (auto_takeoff_complete && !takeoff_complete) { takeoff_complete = true; #if LANDING_GEAR_ENABLED == ENABLED // optionally retract landing gear @@ -684,7 +724,7 @@ void ModeGuided::pos_control_run() float pos_offset_z_buffer = 0.0; // Vertical buffer size in m if (guided_pos_terrain_alt) { - pos_offset_z_buffer = MIN(copter.wp_nav->get_terrain_margin() * 100.0, 0.5 * fabsf(guided_pos_target_cm.z)); + pos_offset_z_buffer = MIN(copter.wp_nav->get_terrain_margin() * 100.0, 0.5 * fabsF(guided_pos_target_cm.z)); } pos_control->input_pos_xyz(guided_pos_target_cm, terr_offset, pos_offset_z_buffer); @@ -738,7 +778,7 @@ void ModeGuided::accel_control_run() auto_yaw.set_rate(0.0f); } pos_control->input_vel_accel_xy(guided_vel_target_cms.xy(), guided_accel_target_cmss.xy(), false); - pos_control->input_vel_accel_z(guided_vel_target_cms.z, guided_accel_target_cmss.z, false, false); + pos_control->input_vel_accel_z(guided_vel_target_cms.z, guided_accel_target_cmss.z, false); } else { // update position controller with new target pos_control->input_accel_xy(guided_accel_target_cmss); @@ -825,7 +865,7 @@ void ModeGuided::velaccel_control_run() // set position errors to zero pos_control->stop_pos_xy_stabilisation(); } - pos_control->input_vel_accel_z(guided_vel_target_cms.z, guided_accel_target_cmss.z, false, false); + pos_control->input_vel_accel_z(guided_vel_target_cms.z, guided_accel_target_cmss.z, false); // call velocity controller which includes z axis controller pos_control->update_xy_controller(); @@ -844,6 +884,36 @@ void ModeGuided::velaccel_control_run() } } +// pause_control_run - runs the guided mode pause controller +// called from guided_run +void ModeGuided::pause_control_run() +{ + // if not armed set throttle to zero and exit immediately + if (is_disarmed_or_landed()) { + // do not spool down tradheli when on the ground with motor interlock enabled + make_safe_ground_handling(copter.is_tradheli() && motors->get_interlock()); + return; + } + + // set motors to full range + motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); + + // set the horizontal velocity and acceleration targets to zero + Vector2f vel_xy, accel_xy; + pos_control->input_vel_accel_xy(vel_xy, accel_xy, false); + + // set the vertical velocity and acceleration targets to zero + float vel_z = 0.0; + pos_control->input_vel_accel_z(vel_z, 0.0, false); + + // call velocity controller which includes z axis controller + pos_control->update_xy_controller(); + pos_control->update_z_controller(); + + // call attitude controller + attitude_control->input_thrust_vector_rate_heading(pos_control->get_thrust_vector(), 0.0); +} + // posvelaccel_control_run - runs the guided position, velocity and acceleration controller // called from guided_run void ModeGuided::posvelaccel_control_run() @@ -972,7 +1042,7 @@ void ModeGuided::angle_control_run() motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); if (motors->get_spool_state() == AP_Motors::SpoolState::THROTTLE_UNLIMITED) { set_land_complete(false); - set_throttle_takeoff(); + pos_control->init_z_controller(); } return; } @@ -1159,4 +1229,18 @@ uint32_t ModeGuided::get_timeout_ms() const return MAX(copter.g2.guided_timeout, 0.1) * 1000; } +// pause guide mode +bool ModeGuided::pause() +{ + _paused = true; + return true; +} + +// resume guided mode +bool ModeGuided::resume() +{ + _paused = false; + return true; +} + #endif diff --git a/ArduCopter/mode_land.cpp b/ArduCopter/mode_land.cpp index e06f00d3fc9..8c518e5cec1 100644 --- a/ArduCopter/mode_land.cpp +++ b/ArduCopter/mode_land.cpp @@ -5,17 +5,19 @@ bool ModeLand::init(bool ignore_checks) { // check if we have GPS and decide which LAND we're going to do control_position = copter.position_ok(); - if (control_position) { - // set target to stopping point - Vector2f stopping_point; - loiter_nav->get_stopping_point_xy(stopping_point); - loiter_nav->init_target(stopping_point); + + // set horizontal speed and acceleration limits + pos_control->set_max_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration()); + pos_control->set_correction_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration()); + + // initialise the horizontal position controller + if (control_position && !pos_control->is_active_xy()) { + pos_control->init_xy_controller(); } // set vertical speed and acceleration limits pos_control->set_max_speed_accel_z(wp_nav->get_default_speed_down(), wp_nav->get_default_speed_up(), wp_nav->get_accel_z()); pos_control->set_correction_speed_accel_z(wp_nav->get_default_speed_down(), wp_nav->get_default_speed_up(), wp_nav->get_accel_z()); - pos_control->set_max_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration()); // initialise the vertical position controller if (!pos_control->is_active_z()) { @@ -39,7 +41,7 @@ bool ModeLand::init(bool ignore_checks) copter.landinggear.deploy_for_landing(); #endif -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // disable the fence on landing copter.fence.auto_disable_fence_for_landing(); #endif @@ -76,8 +78,6 @@ void ModeLand::gps_run() // Land State Machine Determination if (is_disarmed_or_landed()) { make_safe_ground_handling(); - loiter_nav->clear_pilot_desired_acceleration(); - loiter_nav->init_target(); } else { // set motors to full range motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); diff --git a/ArduCopter/mode_loiter.cpp b/ArduCopter/mode_loiter.cpp index 938ea249b67..366228cbacb 100644 --- a/ArduCopter/mode_loiter.cpp +++ b/ArduCopter/mode_loiter.cpp @@ -128,7 +128,7 @@ void ModeLoiter::run() attitude_control->reset_yaw_target_and_rate(); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero loiter_nav->init_target(); - attitude_control->input_thrust_vector_rate_heading(loiter_nav->get_thrust_vector(), target_yaw_rate); + attitude_control->input_thrust_vector_rate_heading(loiter_nav->get_thrust_vector(), target_yaw_rate, false); break; case AltHold_Takeoff: @@ -147,7 +147,7 @@ void ModeLoiter::run() loiter_nav->update(); // call attitude controller - attitude_control->input_thrust_vector_rate_heading(loiter_nav->get_thrust_vector(), target_yaw_rate); + attitude_control->input_thrust_vector_rate_heading(loiter_nav->get_thrust_vector(), target_yaw_rate, false); break; case AltHold_Landed_Ground_Idle: @@ -157,7 +157,7 @@ void ModeLoiter::run() case AltHold_Landed_Pre_Takeoff: attitude_control->reset_rate_controller_I_terms_smoothly(); loiter_nav->init_target(); - attitude_control->input_thrust_vector_rate_heading(loiter_nav->get_thrust_vector(), target_yaw_rate); + attitude_control->input_thrust_vector_rate_heading(loiter_nav->get_thrust_vector(), target_yaw_rate, false); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero break; @@ -186,7 +186,7 @@ void ModeLoiter::run() #endif // call attitude controller - attitude_control->input_thrust_vector_rate_heading(loiter_nav->get_thrust_vector(), target_yaw_rate); + attitude_control->input_thrust_vector_rate_heading(loiter_nav->get_thrust_vector(), target_yaw_rate, false); // get avoidance adjusted climb rate target_climb_rate = get_avoidance_adjusted_climbrate(target_climb_rate); diff --git a/ArduCopter/mode_poshold.cpp b/ArduCopter/mode_poshold.cpp index 4862c12295f..9ad5133836d 100644 --- a/ArduCopter/mode_poshold.cpp +++ b/ArduCopter/mode_poshold.cpp @@ -41,7 +41,7 @@ bool ModePosHold::init(bool ignore_checks) pilot_pitch = 0.0f; // compute brake_gain - brake.gain = (15.0f * (float)g.poshold_brake_rate + 95.0f) / 100.0f; + brake.gain = (15.0f * (float)g.poshold_brake_rate + 95.0f) * 0.01f; if (copter.ap.land_complete) { // if landed begin in loiter mode @@ -106,7 +106,6 @@ void ModePosHold::run() pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero loiter_nav->clear_pilot_desired_acceleration(); loiter_nav->init_target(); - loiter_nav->update(false); // set poshold state to pilot override roll_mode = RPMode::PILOT_OVERRIDE; @@ -131,7 +130,6 @@ void ModePosHold::run() // init and update loiter although pilot is controlling lean angles loiter_nav->clear_pilot_desired_acceleration(); loiter_nav->init_target(); - loiter_nav->update(false); // set poshold state to pilot override roll_mode = RPMode::PILOT_OVERRIDE; @@ -141,7 +139,6 @@ void ModePosHold::run() case AltHold_Landed_Ground_Idle: loiter_nav->clear_pilot_desired_acceleration(); loiter_nav->init_target(); - loiter_nav->update(false); attitude_control->reset_yaw_target_and_rate(); init_wind_comp_estimate(); FALLTHROUGH; diff --git a/ArduCopter/mode_rtl.cpp b/ArduCopter/mode_rtl.cpp index 9515334c3fd..519b9759fb4 100644 --- a/ArduCopter/mode_rtl.cpp +++ b/ArduCopter/mode_rtl.cpp @@ -79,7 +79,7 @@ void ModeRTL::run(bool disarm_on_land) case SubMode::LOITER_AT_HOME: if (rtl_path.land || copter.failsafe.radio) { land_start(); - }else{ + } else { descent_start(); } break; @@ -190,7 +190,7 @@ void ModeRTL::climb_return_run() if (auto_yaw.mode() == AUTO_YAW_HOLD) { // roll & pitch from waypoint controller, yaw rate from pilot attitude_control->input_thrust_vector_rate_heading(wp_nav->get_thrust_vector(), target_yaw_rate); - }else{ + } else { // roll, pitch from waypoint controller, yaw heading from auto_heading() attitude_control->input_thrust_vector_heading(wp_nav->get_thrust_vector(), auto_yaw.yaw()); } @@ -248,7 +248,7 @@ void ModeRTL::loiterathome_run() if (auto_yaw.mode() == AUTO_YAW_HOLD) { // roll & pitch from waypoint controller, yaw rate from pilot attitude_control->input_thrust_vector_rate_heading(wp_nav->get_thrust_vector(), target_yaw_rate); - }else{ + } else { // roll, pitch from waypoint controller, yaw heading from auto_heading() attitude_control->input_thrust_vector_heading(wp_nav->get_thrust_vector(), auto_yaw.yaw()); } @@ -273,9 +273,6 @@ void ModeRTL::descent_start() _state = SubMode::FINAL_DESCENT; _state_complete = false; - // Set wp navigation target to above home - loiter_nav->init_target(wp_nav->get_wp_destination().xy()); - // initialise altitude target to stopping point pos_control->init_z_controller_stopping_point(); @@ -287,7 +284,7 @@ void ModeRTL::descent_start() copter.landinggear.deploy_for_landing(); #endif -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // disable the fence on landing copter.fence.auto_disable_fence_for_landing(); #endif @@ -297,8 +294,7 @@ void ModeRTL::descent_start() // called by rtl_run at 100hz or more void ModeRTL::descent_run() { - float target_roll = 0.0f; - float target_pitch = 0.0f; + Vector2f vel_correction; float target_yaw_rate = 0.0f; // if not armed set throttle to zero and exit immediately @@ -321,11 +317,11 @@ void ModeRTL::descent_run() // apply SIMPLE mode transform to pilot inputs update_simple_mode(); - // convert pilot input to lean angles - get_pilot_desired_lean_angles(target_roll, target_pitch, loiter_nav->get_angle_max_cd(), attitude_control->get_althold_lean_angle_max_cd()); + // convert pilot input to reposition velocity + vel_correction = get_pilot_desired_velocity(wp_nav->get_wp_acceleration() * 0.5); // record if pilot has overridden roll or pitch - if (!is_zero(target_roll) || !is_zero(target_pitch)) { + if (!vel_correction.is_zero()) { if (!copter.ap.land_repo_active) { AP::logger().Write_Event(LogEvent::LAND_REPO_ACTIVE); } @@ -342,11 +338,9 @@ void ModeRTL::descent_run() // set motors to full range motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); - // process roll, pitch inputs - loiter_nav->set_pilot_desired_acceleration(target_roll, target_pitch); - - // run loiter controller - loiter_nav->update(); + Vector2f accel; + pos_control->input_vel_accel_xy(vel_correction, accel); + pos_control->update_xy_controller(); // WP_Nav has set the vertical position control targets // run the vertical position controller and set output throttle @@ -354,7 +348,7 @@ void ModeRTL::descent_run() pos_control->update_z_controller(); // roll & pitch from waypoint controller, yaw rate from pilot - attitude_control->input_thrust_vector_rate_heading(loiter_nav->get_thrust_vector(), target_yaw_rate); + attitude_control->input_thrust_vector_rate_heading(pos_control->get_thrust_vector(), target_yaw_rate); // check if we've reached within 20cm of final altitude _state_complete = labs(rtl_path.descent_target.alt - copter.current_loc.alt) < 20; @@ -366,8 +360,14 @@ void ModeRTL::land_start() _state = SubMode::LAND; _state_complete = false; - // Set wp navigation target to above home - loiter_nav->init_target(wp_nav->get_wp_destination().xy()); + // set horizontal speed and acceleration limits + pos_control->set_max_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration()); + pos_control->set_correction_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration()); + + // initialise loiter target destination + if (!pos_control->is_active_xy()) { + pos_control->init_xy_controller(); + } // initialise the vertical position controller if (!pos_control->is_active_z()) { @@ -382,7 +382,7 @@ void ModeRTL::land_start() copter.landinggear.deploy_for_landing(); #endif -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // disable the fence on landing copter.fence.auto_disable_fence_for_landing(); #endif @@ -408,8 +408,6 @@ void ModeRTL::land_run(bool disarm_on_land) // if not armed set throttle to zero and exit immediately if (is_disarmed_or_landed()) { make_safe_ground_handling(); - loiter_nav->clear_pilot_desired_acceleration(); - loiter_nav->init_target(); return; } @@ -533,7 +531,7 @@ void ModeRTL::compute_return_target() // set returned target alt to new target_alt (don't change altitude type) rtl_path.return_target.set_alt_cm(target_alt, (alt_type == ReturnTargetAltType::RELATIVE) ? Location::AltFrame::ABOVE_HOME : Location::AltFrame::ABOVE_TERRAIN); -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // ensure not above fence altitude if alt fence is enabled // Note: because the rtl_path.climb_target's altitude is simply copied from the return_target's altitude, // if terrain altitudes are being used, the code below which reduces the return_target's altitude can lead to diff --git a/ArduCopter/mode_sport.cpp b/ArduCopter/mode_sport.cpp index 9cd8d4016fc..0c2cbb4d6fa 100644 --- a/ArduCopter/mode_sport.cpp +++ b/ArduCopter/mode_sport.cpp @@ -34,8 +34,8 @@ void ModeSport::run() // get pilot's desired roll and pitch rates // calculate rate requests - float target_roll_rate = channel_roll->get_control_in() * g2.acro_rp_rate * 100.0 / ROLL_PITCH_YAW_INPUT_MAX; - float target_pitch_rate = channel_pitch->get_control_in() * g2.acro_rp_rate * 100.0 / ROLL_PITCH_YAW_INPUT_MAX; + float target_roll_rate = channel_roll->get_control_in() * g2.command_model_acro_rp.get_rate() * 100.0 / ROLL_PITCH_YAW_INPUT_MAX; + float target_pitch_rate = channel_pitch->get_control_in() * g2.command_model_acro_rp.get_rate() * 100.0 / ROLL_PITCH_YAW_INPUT_MAX; // get attitude targets const Vector3f att_target = attitude_control->get_att_target_euler_cd(); @@ -50,15 +50,15 @@ void ModeSport::run() const float angle_max = copter.aparm.angle_max; if (roll_angle > angle_max){ - target_roll_rate += sqrt_controller(angle_max - roll_angle, g2.acro_rp_rate * 100.0 / ACRO_LEVEL_MAX_OVERSHOOT, attitude_control->get_accel_roll_max_cdss(), G_Dt); + target_roll_rate += sqrt_controller(angle_max - roll_angle, g2.command_model_acro_rp.get_rate() * 100.0 / ACRO_LEVEL_MAX_OVERSHOOT, attitude_control->get_accel_roll_max_cdss(), G_Dt); }else if (roll_angle < -angle_max) { - target_roll_rate += sqrt_controller(-angle_max - roll_angle, g2.acro_rp_rate * 100.0 / ACRO_LEVEL_MAX_OVERSHOOT, attitude_control->get_accel_roll_max_cdss(), G_Dt); + target_roll_rate += sqrt_controller(-angle_max - roll_angle, g2.command_model_acro_rp.get_rate() * 100.0 / ACRO_LEVEL_MAX_OVERSHOOT, attitude_control->get_accel_roll_max_cdss(), G_Dt); } if (pitch_angle > angle_max){ - target_pitch_rate += sqrt_controller(angle_max - pitch_angle, g2.acro_rp_rate * 100.0 / ACRO_LEVEL_MAX_OVERSHOOT, attitude_control->get_accel_pitch_max_cdss(), G_Dt); + target_pitch_rate += sqrt_controller(angle_max - pitch_angle, g2.command_model_acro_rp.get_rate() * 100.0 / ACRO_LEVEL_MAX_OVERSHOOT, attitude_control->get_accel_pitch_max_cdss(), G_Dt); }else if (pitch_angle < -angle_max) { - target_pitch_rate += sqrt_controller(-angle_max - pitch_angle, g2.acro_rp_rate * 100.0 / ACRO_LEVEL_MAX_OVERSHOOT, attitude_control->get_accel_pitch_max_cdss(), G_Dt); + target_pitch_rate += sqrt_controller(-angle_max - pitch_angle, g2.command_model_acro_rp.get_rate() * 100.0 / ACRO_LEVEL_MAX_OVERSHOOT, attitude_control->get_accel_pitch_max_cdss(), G_Dt); } // get pilot's desired yaw rate diff --git a/ArduCopter/mode_stabilize.cpp b/ArduCopter/mode_stabilize.cpp index 135cdea51cd..5dbf2d4bdc4 100644 --- a/ArduCopter/mode_stabilize.cpp +++ b/ArduCopter/mode_stabilize.cpp @@ -21,24 +21,32 @@ void ModeStabilize::run() if (!motors->armed()) { // Motors should be Stopped motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN); - } else if (copter.ap.throttle_zero) { + } else if (copter.ap.throttle_zero + || (copter.air_mode == AirMode::AIRMODE_ENABLED && motors->get_spool_state() == AP_Motors::SpoolState::SHUT_DOWN)) { + // throttle_zero is never true in air mode, but the motors should be allowed to go through ground idle + // in order to facilitate the spoolup block + // Attempting to Land motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE); } else { motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); } + float pilot_desired_throttle = get_pilot_desired_throttle(); + switch (motors->get_spool_state()) { case AP_Motors::SpoolState::SHUT_DOWN: // Motors Stopped attitude_control->reset_yaw_target_and_rate(); attitude_control->reset_rate_controller_I_terms(); + pilot_desired_throttle = 0.0f; break; case AP_Motors::SpoolState::GROUND_IDLE: // Landed attitude_control->reset_yaw_target_and_rate(); attitude_control->reset_rate_controller_I_terms_smoothly(); + pilot_desired_throttle = 0.0f; break; case AP_Motors::SpoolState::THROTTLE_UNLIMITED: @@ -58,7 +66,5 @@ void ModeStabilize::run() attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate); // output pilot's throttle - attitude_control->set_throttle_out(get_pilot_desired_throttle(), - true, - g.throttle_filt); + attitude_control->set_throttle_out(pilot_desired_throttle, true, g.throttle_filt); } diff --git a/ArduCopter/mode_stabilize_heli.cpp b/ArduCopter/mode_stabilize_heli.cpp index 2a7056cd1f6..e9caa4212b4 100644 --- a/ArduCopter/mode_stabilize_heli.cpp +++ b/ArduCopter/mode_stabilize_heli.cpp @@ -22,7 +22,6 @@ bool ModeStabilize_Heli::init(bool ignore_checks) void ModeStabilize_Heli::run() { float target_roll, target_pitch; - float target_yaw_rate; float pilot_throttle_scaled; // apply SIMPLE mode transform to pilot inputs @@ -32,7 +31,7 @@ void ModeStabilize_Heli::run() get_pilot_desired_lean_angles(target_roll, target_pitch, copter.aparm.angle_max, copter.aparm.angle_max); // get pilot's desired yaw rate - target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz()); + float target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz()); // get pilot's desired throttle pilot_throttle_scaled = copter.input_manager.get_pilot_desired_collective(channel_throttle->get_control_in()); diff --git a/ArduCopter/mode_systemid.cpp b/ArduCopter/mode_systemid.cpp index 63ac09a1e1f..60cb56718b1 100644 --- a/ArduCopter/mode_systemid.cpp +++ b/ArduCopter/mode_systemid.cpp @@ -95,6 +95,8 @@ bool ModeSystemId::init(bool ignore_checks) systemid_state = SystemIDModeState::SYSTEMID_STATE_TESTING; log_subsample = 0; + chirp_input.init(time_record, frequency_start, frequency_stop, time_fade_in, time_fade_out, time_const_freq); + gcs().send_text(MAV_SEVERITY_INFO, "SystemID Starting: axis=%d", (unsigned)axis); copter.Log_Write_SysID_Setup(axis, waveform_magnitude, frequency_start, frequency_stop, time_fade_in, time_const_freq, time_record, time_fade_out); @@ -102,6 +104,13 @@ bool ModeSystemId::init(bool ignore_checks) return true; } +// systemId_exit - clean up systemId controller before exiting +void ModeSystemId::exit() +{ + // reset the feedfoward enabled parameter to the initialized state + attitude_control->bf_feedforward(att_bf_feedforward); +} + // systemId_run - runs the systemId controller // should be called at 100hz or more void ModeSystemId::run() @@ -172,13 +181,14 @@ void ModeSystemId::run() } waveform_time += G_Dt; - waveform_sample = waveform(waveform_time - SYSTEM_ID_DELAY); + waveform_sample = chirp_input.update(waveform_time - SYSTEM_ID_DELAY, waveform_magnitude); + waveform_freq_rads = chirp_input.get_frequency_rads(); switch (systemid_state) { case SystemIDModeState::SYSTEMID_STATE_STOPPED: + attitude_control->bf_feedforward(att_bf_feedforward); break; case SystemIDModeState::SYSTEMID_STATE_TESTING: - attitude_control->bf_feedforward(att_bf_feedforward); if (copter.ap.land_complete) { systemid_state = SystemIDModeState::SYSTEMID_STATE_STOPPED; @@ -291,43 +301,4 @@ void ModeSystemId::log_data() const copter.Log_Write_Attitude(); } -// init_test - initialises the test -float ModeSystemId::waveform(float time) -{ - float wMin = 2 * M_PI * frequency_start; - float wMax = 2 * M_PI * frequency_stop; - - float window; - float output; - - float B = logf(wMax / wMin); - - if (time <= 0.0f) { - window = 0.0f; - } else if (time <= time_fade_in) { - window = 0.5 - 0.5 * cosf(M_PI * time / time_fade_in); - } else if (time <= time_record - time_fade_out) { - window = 1.0; - } else if (time <= time_record) { - window = 0.5 - 0.5 * cosf(M_PI * (time - (time_record - time_fade_out)) / time_fade_out + M_PI); - } else { - window = 0.0; - } - - if (time <= 0.0f) { - waveform_freq_rads = wMin; - output = 0.0f; - } else if (time <= time_const_freq) { - waveform_freq_rads = wMin; - output = window * waveform_magnitude * sinf(wMin * time - wMin * time_const_freq); - } else if (time <= time_record) { - waveform_freq_rads = wMin * expf(B * (time - time_const_freq) / (time_record - time_const_freq)); - output = window * waveform_magnitude * sinf((wMin * (time_record - time_const_freq) / B) * (expf(B * (time - time_const_freq) / (time_record - time_const_freq)) - 1)); - } else { - waveform_freq_rads = wMax; - output = 0.0f; - } - return output; -} - #endif diff --git a/ArduCopter/mode_throw.cpp b/ArduCopter/mode_throw.cpp index df73c4db42e..c9ff702e3fd 100644 --- a/ArduCopter/mode_throw.cpp +++ b/ArduCopter/mode_throw.cpp @@ -52,6 +52,7 @@ void ModeThrow::run() } else if (stage == Throw_Detecting && throw_detected()){ gcs().send_text(MAV_SEVERITY_INFO,"throw detected - spooling motors"); + copter.set_land_complete(false); stage = Throw_Wait_Throttle_Unlimited; // Cancel the waiting for throw tone sequence diff --git a/ArduCopter/mode_turtle.cpp b/ArduCopter/mode_turtle.cpp index 552bcad266e..2e0aef1c67a 100644 --- a/ArduCopter/mode_turtle.cpp +++ b/ArduCopter/mode_turtle.cpp @@ -18,26 +18,41 @@ bool ModeTurtle::init(bool ignore_checks) return false; } - // do not enter the mode if sticks are not centered + // do not enter the mode if sticks are not centered or throttle is not at zero if (!is_zero(channel_pitch->norm_input_dz()) || !is_zero(channel_roll->norm_input_dz()) - || !is_zero(channel_yaw->norm_input_dz())) { + || !is_zero(channel_yaw->norm_input_dz()) + || !is_zero(channel_throttle->norm_input_dz())) { return false; } + + // turn on notify leds + AP_Notify::flags.esc_calibration = true; + + return true; +} + +void ModeTurtle::arm_motors() +{ + if (hal.util->get_soft_armed()) { + return; + } + + // stop the spoolup block activating + motors->set_spoolup_block(false); + // reverse the motors hal.rcout->disable_channel_mask_updates(); change_motor_direction(true); // disable throttle and gps failsafe - g.failsafe_throttle = FS_THR_DISABLED; - g.failsafe_gcs = FS_GCS_DISABLED; - g.fs_ekf_action = 0; + g.failsafe_throttle.set(FS_THR_DISABLED); + g.failsafe_gcs.set(FS_GCS_DISABLED); + g.fs_ekf_action.set(0); // arm motors->armed(true); hal.util->set_soft_armed(true); - - return true; } bool ModeTurtle::allows_arming(AP_Arming::Method method) const @@ -47,6 +62,18 @@ bool ModeTurtle::allows_arming(AP_Arming::Method method) const void ModeTurtle::exit() { + disarm_motors(); + + // turn off notify leds + AP_Notify::flags.esc_calibration = false; +} + +void ModeTurtle::disarm_motors() +{ + if (!hal.util->get_soft_armed()) { + return; + } + // disarm motors->armed(false); hal.util->set_soft_armed(false); @@ -85,7 +112,7 @@ void ModeTurtle::change_motor_direction(bool reverse) void ModeTurtle::run() { - const float flip_power_factor = 1.0f - CRASH_FLIP_EXPO / 100.0f; + const float flip_power_factor = 1.0f - CRASH_FLIP_EXPO * 0.01f; const bool norc = copter.failsafe.radio || !copter.ap.rc_receiver_present; const float stick_deflection_pitch = norc ? 0.0f : channel_pitch->norm_input_dz(); const float stick_deflection_roll = norc ? 0.0f : channel_roll->norm_input_dz(); @@ -142,6 +169,14 @@ void ModeTurtle::run() // actually write values to the motors void ModeTurtle::output_to_motors() { + // throttle needs to be raised + if (is_zero(channel_throttle->norm_input_dz())) { + disarm_motors(); + return; + } + + arm_motors(); + // check if motor are allowed to spin const bool allow_output = motors->armed() && motors->get_interlock(); diff --git a/ArduCopter/motor_test.cpp b/ArduCopter/motor_test.cpp index 2248aa3e169..13114e1744d 100644 --- a/ArduCopter/motor_test.cpp +++ b/ArduCopter/motor_test.cpp @@ -6,8 +6,6 @@ */ // motor test definitions -#define MOTOR_TEST_PWM_MIN 800 // min pwm value accepted by the test -#define MOTOR_TEST_PWM_MAX 2200 // max pwm value accepted by the test #define MOTOR_TEST_TIMEOUT_SEC 600 // max timeout is 10 minutes (600 seconds) static uint32_t motor_test_start_ms; // system time the motor test began @@ -84,7 +82,7 @@ void Copter::motor_test_output() } // sanity check throttle values - if (pwm >= MOTOR_TEST_PWM_MIN && pwm <= MOTOR_TEST_PWM_MAX ) { + if (pwm >= RC_Channel::RC_MIN_LIMIT_PWM && pwm <= RC_Channel::RC_MAX_LIMIT_PWM) { // turn on motor to specified pwm value motors->output_test_seq(motor_test_seq, pwm); } else { @@ -161,9 +159,9 @@ MAV_RESULT Copter::mavlink_motor_test_start(const GCS_MAVLINK &gcs_chan, uint8_t } // disable throttle and gps failsafe - g.failsafe_throttle = FS_THR_DISABLED; - g.failsafe_gcs = FS_GCS_DISABLED; - g.fs_ekf_action = 0; + g.failsafe_throttle.set(FS_THR_DISABLED); + g.failsafe_gcs.set(FS_GCS_DISABLED); + g.fs_ekf_action.set(0); // turn on notify leds AP_Notify::flags.esc_calibration = true; diff --git a/ArduCopter/radio.cpp b/ArduCopter/radio.cpp index ba3c74b3bcf..e7360c08907 100644 --- a/ArduCopter/radio.cpp +++ b/ArduCopter/radio.cpp @@ -41,7 +41,6 @@ void Copter::init_rc_in() // init_rc_out -- initialise motors void Copter::init_rc_out() { - motors->set_loop_rate(scheduler.get_loop_rate_hz()); motors->init((AP_Motors::motor_frame_class)g2.frame_class.get(), (AP_Motors::motor_frame_type)g.frame_type.get()); // enable aux servos to cope with multiple output channels per motor @@ -51,7 +50,7 @@ void Copter::init_rc_out() motors->set_update_rate(g.rc_speed); #if FRAME_CONFIG != HELI_FRAME - if (channel_throttle->configured_in_storage()) { + if (channel_throttle->configured()) { // throttle inputs setup, use those to set motor PWM min and max if not already configured motors->convert_pwm_min_max_param(channel_throttle->get_radio_min(), channel_throttle->get_radio_max()); } else { diff --git a/ArduCopter/sensors.cpp b/ArduCopter/sensors.cpp index 54968f092fa..afa8c7e3332 100644 --- a/ArduCopter/sensors.cpp +++ b/ArduCopter/sensors.cpp @@ -135,7 +135,7 @@ bool Copter::rangefinder_up_ok() const difference between the inertial height at that time and the current inertial height to give us interpolation of height from rangefinder */ -bool Copter::get_rangefinder_height_interpolated_cm(int32_t& ret) +bool Copter::get_rangefinder_height_interpolated_cm(int32_t& ret) const { if (!rangefinder_alt_ok()) { return false; diff --git a/ArduCopter/surface_tracking.cpp b/ArduCopter/surface_tracking.cpp index 63f48902add..669e7c646a7 100644 --- a/ArduCopter/surface_tracking.cpp +++ b/ArduCopter/surface_tracking.cpp @@ -17,7 +17,7 @@ void Copter::SurfaceTracking::update_surface_offset() // e.g. if vehicle is 10m above the EKF origin and rangefinder reports alt of 3m. curr_surface_alt_above_origin_cm is 7m (or 700cm) RangeFinderState &rf_state = (surface == Surface::GROUND) ? copter.rangefinder_state : copter.rangefinder_up_state; const float dir = (surface == Surface::GROUND) ? 1.0f : -1.0f; - const float curr_surface_alt_above_origin_cm = copter.inertial_nav.get_position_z_up_cm() - dir * rf_state.alt_cm; + const float curr_surface_alt_above_origin_cm = rf_state.inertial_alt_cm - dir * rf_state.alt_cm_filt.get(); // update position controller target offset to the surface's alt above the EKF origin copter.pos_control->set_pos_offset_target_z_cm(curr_surface_alt_above_origin_cm); diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index dd5213b88b3..27ff27a2126 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -31,10 +31,6 @@ void Copter::init_ardupilot() g2.gripper.init(); #endif -#if AC_FENCE == ENABLED - fence.init(); -#endif - // init winch #if WINCH_ENABLED == ENABLED g2.winch.init(); @@ -77,7 +73,7 @@ void Copter::init_ardupilot() init_rc_in(); // sets up rc channels from radio // initialise surface to be tracked in SurfaceTracking - // must be before rc init to not override inital switch position + // must be before rc init to not override initial switch position surface_tracking.init((SurfaceTracking::Surface)copter.g2.surftrak_mode.get()); // allocate the motors class @@ -187,6 +183,10 @@ void Copter::init_ardupilot() g2.scripting.init(); #endif // AP_SCRIPTING_ENABLED +#if AC_CUSTOMCONTROL_MULTI_ENABLED == ENABLED + custom_control.init(); +#endif + // set landed flags set_land_complete(true); set_land_complete_maybe(true); @@ -233,78 +233,6 @@ void Copter::startup_INS_ground() ahrs.reset(); } -// update the harmonic notch filter center frequency dynamically -void Copter::update_dynamic_notch() -{ - if (!ins.gyro_harmonic_notch_enabled()) { - return; - } - const float ref_freq = ins.get_gyro_harmonic_notch_center_freq_hz(); - const float ref = ins.get_gyro_harmonic_notch_reference(); - if (is_zero(ref)) { - ins.update_harmonic_notch_freq_hz(ref_freq); - return; - } - - const float throttle_freq = ref_freq * MAX(1.0f, sqrtf(motors->get_throttle_out() / ref)); - - switch (ins.get_gyro_harmonic_notch_tracking_mode()) { - case HarmonicNotchDynamicMode::UpdateThrottle: // throttle based tracking - // set the harmonic notch filter frequency approximately scaled on motor rpm implied by throttle - ins.update_harmonic_notch_freq_hz(throttle_freq); - break; - -#if RPM_ENABLED == ENABLED - case HarmonicNotchDynamicMode::UpdateRPM: // rpm sensor based tracking - float rpm; - if (rpm_sensor.get_rpm(0, rpm)) { - // set the harmonic notch filter frequency from the main rotor rpm - ins.update_harmonic_notch_freq_hz(MAX(ref_freq, rpm * ref / 60.0f)); - } else { - ins.update_harmonic_notch_freq_hz(ref_freq); - } - break; -#endif -#if HAL_WITH_ESC_TELEM - case HarmonicNotchDynamicMode::UpdateBLHeli: // BLHeli based tracking - // set the harmonic notch filter frequency scaled on measured frequency - if (ins.has_harmonic_option(HarmonicNotchFilterParams::Options::DynamicHarmonic)) { - float notches[INS_MAX_NOTCHES]; - const uint8_t num_notches = AP::esc_telem().get_motor_frequencies_hz(ins.get_num_gyro_dynamic_notches(), notches); - - for (uint8_t i = 0; i < num_notches; i++) { - notches[i] = MAX(ref_freq, notches[i]); - } - if (num_notches > 0) { - ins.update_harmonic_notch_frequencies_hz(num_notches, notches); - } else { // throttle fallback - ins.update_harmonic_notch_freq_hz(throttle_freq); - } - } else { - ins.update_harmonic_notch_freq_hz(MAX(ref_freq, AP::esc_telem().get_average_motor_frequency_hz() * ref)); - } - break; -#endif -#if HAL_GYROFFT_ENABLED - case HarmonicNotchDynamicMode::UpdateGyroFFT: // FFT based tracking - // set the harmonic notch filter frequency scaled on measured frequency - if (ins.has_harmonic_option(HarmonicNotchFilterParams::Options::DynamicHarmonic)) { - float notches[INS_MAX_NOTCHES]; - const uint8_t peaks = gyro_fft.get_weighted_noise_center_frequencies_hz(ins.get_num_gyro_dynamic_notches(), notches); - - ins.update_harmonic_notch_frequencies_hz(peaks, notches); - } else { - ins.update_harmonic_notch_freq_hz(gyro_fft.get_weighted_noise_center_freq_hz()); - } - break; -#endif - case HarmonicNotchDynamicMode::Fixed: // static - default: - ins.update_harmonic_notch_freq_hz(ref_freq); - break; - } -} - // position_ok - returns true if the horizontal absolute position is ok and home position is set bool Copter::position_ok() const { @@ -345,7 +273,7 @@ bool Copter::ekf_has_relative_position() const return false; } - // return immediately if neither optflow nor visual odometry is enabled + // return immediately if neither optflow nor visual odometry is enabled and dead reckoning is inactive bool enabled = false; #if AP_OPTICALFLOW_ENABLED if (optflow.enabled()) { @@ -357,6 +285,9 @@ bool Copter::ekf_has_relative_position() const enabled = true; } #endif + if (dead_reckoning.active && !dead_reckoning.timeout) { + enabled = true; + } if (!enabled) { return false; } @@ -475,7 +406,7 @@ void Copter::allocate_motors(void) motors_var_info = AP_MotorsMatrix_6DoF_Scripting::var_info; #endif // AP_SCRIPTING_ENABLED break; -case AP_Motors::MOTOR_FRAME_DYNAMIC_SCRIPTING_MATRIX: + case AP_Motors::MOTOR_FRAME_DYNAMIC_SCRIPTING_MATRIX: #if AP_SCRIPTING_ENABLED motors = new AP_MotorsMatrix_Scripting_Dynamic(copter.scheduler.get_loop_rate_hz()); motors_var_info = AP_MotorsMatrix_Scripting_Dynamic::var_info; @@ -517,15 +448,15 @@ case AP_Motors::MOTOR_FRAME_DYNAMIC_SCRIPTING_MATRIX: #if FRAME_CONFIG != HELI_FRAME if ((AP_Motors::motor_frame_class)g2.frame_class.get() == AP_Motors::MOTOR_FRAME_6DOF_SCRIPTING) { #if AP_SCRIPTING_ENABLED - attitude_control = new AC_AttitudeControl_Multi_6DoF(*ahrs_view, aparm, *motors, scheduler.get_loop_period_s()); + attitude_control = new AC_AttitudeControl_Multi_6DoF(*ahrs_view, aparm, *motors); ac_var_info = AC_AttitudeControl_Multi_6DoF::var_info; #endif // AP_SCRIPTING_ENABLED } else { - attitude_control = new AC_AttitudeControl_Multi(*ahrs_view, aparm, *motors, scheduler.get_loop_period_s()); + attitude_control = new AC_AttitudeControl_Multi(*ahrs_view, aparm, *motors); ac_var_info = AC_AttitudeControl_Multi::var_info; } #else - attitude_control = new AC_AttitudeControl_Heli(*ahrs_view, aparm, *motors, scheduler.get_loop_period_s()); + attitude_control = new AC_AttitudeControl_Heli(*ahrs_view, aparm, *motors); ac_var_info = AC_AttitudeControl_Heli::var_info; #endif if (attitude_control == nullptr) { @@ -533,7 +464,7 @@ case AP_Motors::MOTOR_FRAME_DYNAMIC_SCRIPTING_MATRIX: } AP_Param::load_object_from_eeprom(attitude_control, ac_var_info); - pos_control = new AC_PosControl(*ahrs_view, inertial_nav, *motors, *attitude_control, scheduler.get_loop_period_s()); + pos_control = new AC_PosControl(*ahrs_view, inertial_nav, *motors, *attitude_control); if (pos_control == nullptr) { AP_BoardConfig::allocation_error("PosControl"); } @@ -594,6 +525,11 @@ case AP_Motors::MOTOR_FRAME_DYNAMIC_SCRIPTING_MATRIX: convert_tradheli_parameters(); #endif +#if HAL_PROXIMITY_ENABLED + // convert PRX to PRX1_ parameters + convert_prx_parameters(); +#endif + // param count could have changed AP_Param::invalidate_count(); } diff --git a/ArduCopter/takeoff.cpp b/ArduCopter/takeoff.cpp index 687287336b0..3aa39f3b7b9 100644 --- a/ArduCopter/takeoff.cpp +++ b/ArduCopter/takeoff.cpp @@ -4,6 +4,10 @@ Mode::_TakeOff Mode::takeoff; bool Mode::auto_takeoff_no_nav_active = false; float Mode::auto_takeoff_no_nav_alt_cm = 0; +float Mode::auto_takeoff_complete_alt_cm = 0; +bool Mode::auto_takeoff_terrain_alt = false; +bool Mode::auto_takeoff_complete = false; +Vector3p Mode::auto_takeoff_complete_pos; // This file contains the high-level takeoff logic for Loiter, PosHold, AltHold, Sport modes. // The take-off can be initiated from a GCS NAV_TAKEOFF command which includes a takeoff altitude @@ -52,11 +56,6 @@ bool Mode::do_user_takeoff(float takeoff_alt_cm, bool must_navigate) // start takeoff to specified altitude above home in centimeters void Mode::_TakeOff::start(float alt_cm) { - // indicate we are taking off - copter.set_land_complete(false); - // tell position controller to reset alt target and reset I terms - copter.flightmode->set_throttle_takeoff(); - // initialise takeoff state _running = true; take_off_start_alt = copter.pos_control->get_pos_target_z_cm(); @@ -67,6 +66,11 @@ void Mode::_TakeOff::start(float alt_cm) void Mode::_TakeOff::stop() { _running = false; + // Check if we have progressed far enough through the takeoff process that the + // aircraft may have left the ground but not yet detected the climb. + if (copter.attitude_control->get_throttle_in() > copter.get_non_takeoff_throttle()) { + copter.set_land_complete(false); + } } // do_pilot_takeoff - controls the vertical position controller during the process of taking off @@ -80,26 +84,56 @@ void Mode::_TakeOff::do_pilot_takeoff(float& pilot_climb_rate_cm) return; } - float pos_z = take_off_complete_alt; - float vel_z = pilot_climb_rate_cm; + if (copter.ap.land_complete) { + // send throttle to attitude controller with angle boost + float throttle = constrain_float(copter.attitude_control->get_throttle_in() + copter.G_Dt / copter.g2.takeoff_throttle_slew_time, 0.0, 1.0); + copter.attitude_control->set_throttle_out(throttle, true, 0.0); + // tell position controller to reset alt target and reset I terms + copter.pos_control->init_z_controller(); + if (throttle >= 0.9 || + (copter.pos_control->get_z_accel_cmss() >= 0.5 * copter.pos_control->get_max_accel_z_cmss()) || + (copter.pos_control->get_vel_desired_cms().z >= constrain_float(pilot_climb_rate_cm, copter.pos_control->get_max_speed_up_cms() * 0.1, copter.pos_control->get_max_speed_up_cms() * 0.5)) || + (is_positive(take_off_complete_alt - take_off_start_alt) && copter.pos_control->get_pos_target_z_cm() - take_off_start_alt > 0.5 * (take_off_complete_alt - take_off_start_alt))) { + // throttle > 90% + // acceleration > 50% maximum acceleration + // velocity > 10% maximum velocity && commanded climb rate + // velocity > 50% maximum velocity + // altitude change greater than half complete alt from start off alt + copter.set_land_complete(false); + } + } else { + float pos_z = take_off_complete_alt; + float vel_z = pilot_climb_rate_cm; - // command the aircraft to the take off altitude and current pilot climb rate - copter.pos_control->input_pos_vel_accel_z(pos_z, vel_z, 0); + // command the aircraft to the take off altitude and current pilot climb rate + copter.pos_control->input_pos_vel_accel_z(pos_z, vel_z, 0); - // stop take off early and return if negative climb rate is commanded or we are within 0.1% of our take off altitude - if (is_negative(pilot_climb_rate_cm) || - (take_off_complete_alt - take_off_start_alt) * 0.999f < copter.pos_control->get_pos_target_z_cm() - take_off_start_alt) { - stop(); + // stop take off early and return if negative climb rate is commanded or we are within 0.1% of our take off altitude + if (is_negative(pilot_climb_rate_cm) || + (take_off_complete_alt - take_off_start_alt) * 0.999f < copter.pos_control->get_pos_target_z_cm() - take_off_start_alt) { + stop(); + } } } +// auto_takeoff_run - controls the vertical position controller during the process of taking off in auto modes +// auto_takeoff_complete set to true when target altitude is within 10% of the take off altitude and less than 50% max climb rate void Mode::auto_takeoff_run() { // if not armed set throttle to zero and exit immediately if (!motors->armed() || !copter.ap.auto_armed) { // do not spool down tradheli when on the ground with motor interlock enabled make_safe_ground_handling(copter.is_tradheli() && motors->get_interlock()); - wp_nav->shift_wp_origin_and_destination_to_current_pos_xy(); + // update auto_takeoff_no_nav_alt_cm + auto_takeoff_no_nav_alt_cm = inertial_nav.get_position_z_up_cm() + g2.wp_navalt_min * 100; + return; + } + + // get terrain offset + float terr_offset = 0.0f; + if (auto_takeoff_terrain_alt && !wp_nav->get_terrain_offset(terr_offset)) { + // trigger terrain failsafe + copter.failsafe_terrain_on_event(); return; } @@ -116,17 +150,42 @@ void Mode::auto_takeoff_run() } } - // aircraft stays in landed state until rotor speed runup has finished - if (motors->get_spool_state() == AP_Motors::SpoolState::THROTTLE_UNLIMITED) { - set_land_complete(false); - } else { + // aircraft stays in landed state until rotor speed run up has finished + if (motors->get_spool_state() != AP_Motors::SpoolState::THROTTLE_UNLIMITED) { // motors have not completed spool up yet so relax navigation and position controllers - wp_nav->shift_wp_origin_and_destination_to_current_pos_xy(); + pos_control->relax_velocity_controller_xy(); + pos_control->update_xy_controller(); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero pos_control->update_z_controller(); attitude_control->reset_yaw_target_and_rate(); attitude_control->reset_rate_controller_I_terms(); - attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(0.0f, 0.0f, 0.0f); + attitude_control->input_thrust_vector_rate_heading(pos_control->get_thrust_vector(), 0.0); + // update auto_takeoff_no_nav_alt_cm + auto_takeoff_no_nav_alt_cm = inertial_nav.get_position_z_up_cm() + g2.wp_navalt_min * 100; + return; + } + + // aircraft stays in landed state until vertical movement is detected or 90% throttle is reached + if (copter.ap.land_complete) { + // send throttle to attitude controller with angle boost + float throttle = constrain_float(copter.attitude_control->get_throttle_in() + copter.G_Dt / copter.g2.takeoff_throttle_slew_time, 0.0, 1.0); + copter.attitude_control->set_throttle_out(throttle, true, 0.0); + // tell position controller to reset alt target and reset I terms + copter.pos_control->init_z_controller(); + pos_control->relax_velocity_controller_xy(); + pos_control->update_xy_controller(); + attitude_control->reset_rate_controller_I_terms(); + attitude_control->input_thrust_vector_rate_heading(pos_control->get_thrust_vector(), 0.0); + if (throttle >= 0.9 || + (copter.pos_control->get_z_accel_cmss() >= 0.5 * copter.pos_control->get_max_accel_z_cmss()) || + (copter.pos_control->get_vel_desired_cms().z >= 0.1 * copter.pos_control->get_max_speed_up_cms()) || + ( auto_takeoff_no_nav_active && (inertial_nav.get_position_z_up_cm() >= auto_takeoff_no_nav_alt_cm))) { + // throttle > 90% + // acceleration > 50% maximum acceleration + // velocity > 10% maximum velocity + // altitude change greater than half auto_takeoff_no_nav_alt_cm + copter.set_land_complete(false); + } return; } @@ -135,57 +194,82 @@ void Mode::auto_takeoff_run() // check if vehicle has reached no_nav_alt threshold if (inertial_nav.get_position_z_up_cm() >= auto_takeoff_no_nav_alt_cm) { auto_takeoff_no_nav_active = false; - wp_nav->shift_wp_origin_and_destination_to_stopping_point_xy(); - } else { - // shift the navigation target horizontally to our current position - wp_nav->shift_wp_origin_and_destination_to_current_pos_xy(); } - // tell the position controller that we have limited roll/pitch demand to prevent integrator buildup - pos_control->set_externally_limited_xy(); - } - - // run waypoint controller - copter.failsafe_terrain_set_status(wp_nav->update_wpnav()); - - Vector3f thrustvector{0, 0, -GRAVITY_MSS * 100.0f}; - if (!auto_takeoff_no_nav_active) { - thrustvector = wp_nav->get_thrust_vector(); + pos_control->relax_velocity_controller_xy(); + } else { + Vector2f vel; + Vector2f accel; + pos_control->input_vel_accel_xy(vel, accel); } + pos_control->update_xy_controller(); - // WP_Nav has set the vertical position control targets + // command the aircraft to the take off altitude + float pos_z = auto_takeoff_complete_alt_cm + terr_offset; + float vel_z = 0.0; + copter.pos_control->input_pos_vel_accel_z(pos_z, vel_z, 0.0); + // run the vertical position controller and set output throttle - copter.pos_control->update_z_controller(); + pos_control->update_z_controller(); // call attitude controller if (auto_yaw.mode() == AUTO_YAW_HOLD) { // roll & pitch from position controller, yaw rate from pilot - attitude_control->input_thrust_vector_rate_heading(thrustvector, target_yaw_rate); + attitude_control->input_thrust_vector_rate_heading(pos_control->get_thrust_vector(), target_yaw_rate); } else if (auto_yaw.mode() == AUTO_YAW_RATE) { // roll & pitch from position controller, yaw rate from mavlink command or mission item - attitude_control->input_thrust_vector_rate_heading(thrustvector, auto_yaw.rate_cds()); + attitude_control->input_thrust_vector_rate_heading(pos_control->get_thrust_vector(), auto_yaw.rate_cds()); } else { // roll & pitch from position controller, yaw heading from GCS or auto_heading() - attitude_control->input_thrust_vector_heading(thrustvector, auto_yaw.yaw(), auto_yaw.rate_cds()); + attitude_control->input_thrust_vector_heading(pos_control->get_thrust_vector(), auto_yaw.yaw(), auto_yaw.rate_cds()); + } + + // takeoff complete when we are less than 1% of the stopping distance from the target altitude + // and 10% our maximum climb rate + const float vel_threshold_fraction = 0.1; + // stopping distance from vel_threshold_fraction * max velocity + const float stop_distance = 0.5 * sq(vel_threshold_fraction * copter.pos_control->get_max_speed_up_cms()) / copter.pos_control->get_max_accel_z_cmss(); + bool reached_altitude = copter.pos_control->get_pos_target_z_cm() >= pos_z - stop_distance; + bool reached_climb_rate = copter.pos_control->get_vel_desired_cms().z < copter.pos_control->get_max_speed_up_cms() * vel_threshold_fraction; + auto_takeoff_complete = reached_altitude && reached_climb_rate; + + // calculate completion for location in case it is needed for a smooth transition to wp_nav + if (auto_takeoff_complete) { + const Vector3p& complete_pos = copter.pos_control->get_pos_target_cm(); + auto_takeoff_complete_pos = Vector3p{complete_pos.x, complete_pos.y, pos_z}; } } -void Mode::auto_takeoff_set_start_alt(void) +void Mode::auto_takeoff_start(float complete_alt_cm, bool terrain_alt) { + // auto_takeoff_complete_alt_cm is a problem if equal to auto_takeoff_start_alt_cm + auto_takeoff_complete_alt_cm = complete_alt_cm; + auto_takeoff_terrain_alt = terrain_alt; + auto_takeoff_complete = false; + // initialise auto_takeoff_no_nav_alt_cm + auto_takeoff_no_nav_alt_cm = inertial_nav.get_position_z_up_cm() + g2.wp_navalt_min * 100; if ((g2.wp_navalt_min > 0) && (is_disarmed_or_landed() || !motors->get_interlock())) { // we are not flying, climb with no navigation to current alt-above-ekf-origin + wp_navalt_min - auto_takeoff_no_nav_alt_cm = inertial_nav.get_position_z_up_cm() + g2.wp_navalt_min * 100; auto_takeoff_no_nav_active = true; } else { auto_takeoff_no_nav_active = false; } } -bool Mode::is_taking_off() const +// return takeoff final position if takeoff has completed successfully +bool Mode::auto_takeoff_get_position(Vector3p& complete_pos) { - if (!has_user_takeoff(false)) { + // only provide location if takeoff has completed + if (!auto_takeoff_complete) { return false; } - if (copter.ap.land_complete) { + + complete_pos = auto_takeoff_complete_pos; + return true; +} + +bool Mode::is_taking_off() const +{ + if (!has_user_takeoff(false)) { return false; } return takeoff.running(); diff --git a/ArduCopter/takeoff_check.cpp b/ArduCopter/takeoff_check.cpp new file mode 100644 index 00000000000..f3b55ec45fb --- /dev/null +++ b/ArduCopter/takeoff_check.cpp @@ -0,0 +1,56 @@ +#include "Copter.h" + +// +// pre-takeoff checks +// + +// detects if the vehicle should be allowed to takeoff or not and sets the motors.blocked flag +void Copter::takeoff_check() +{ +#if HAL_WITH_ESC_TELEM && FRAME_CONFIG != HELI_FRAME + // If takeoff check is disabled or vehicle is armed and flying then clear block and return + if ((g2.takeoff_rpm_min <= 0) || (motors->armed() && !ap.land_complete)) { + motors->set_spoolup_block(false); + return; + } + + // block takeoff when disarmed but do not display warnings + if (!motors->armed()) { + motors->set_spoolup_block(true); + takeoff_check_warning_ms = 0; + return; + } + + // if motors have become unblocked return immediately + // this ensures the motors can only be blocked immediate after arming + if (!motors->get_spoolup_block()) { + return; + } + + // check ESCs are sending RPM at expected level + uint32_t motor_mask = motors->get_motor_mask(); + const bool telem_active = AP::esc_telem().is_telemetry_active(motor_mask); + const bool rpm_adequate = AP::esc_telem().are_motors_running(motor_mask, g2.takeoff_rpm_min); + + // if RPM is at the expected level clear block + if (telem_active && rpm_adequate) { + motors->set_spoolup_block(false); + return; + } + + // warn user telem inactive or rpm is inadequate every 5 seconds + uint32_t now_ms = AP_HAL::millis(); + if (takeoff_check_warning_ms == 0) { + takeoff_check_warning_ms = now_ms; + } + if (now_ms - takeoff_check_warning_ms > 5000) { + takeoff_check_warning_ms = now_ms; + const char* prefix_str = "Takeoff blocked:"; + if (!telem_active) { + gcs().send_text(MAV_SEVERITY_CRITICAL, "%s waiting for ESC RPM", prefix_str); + } else if (!rpm_adequate) { + gcs().send_text(MAV_SEVERITY_CRITICAL, "%s ESC RPM too low", prefix_str); + } + } +#endif +} diff --git a/ArduCopter/toy_mode.cpp b/ArduCopter/toy_mode.cpp index b80539f62e1..922a51727ba 100644 --- a/ArduCopter/toy_mode.cpp +++ b/ArduCopter/toy_mode.cpp @@ -430,7 +430,7 @@ void ToyMode::update() */ if (set_and_remember_mode(Mode::Number::ALT_HOLD, ModeReason::TOY_MODE)) { gcs().send_text(MAV_SEVERITY_INFO, "Tmode: ALT_HOLD update arm"); -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED copter.fence.enable(false); #endif if (!copter.arming.arm(AP_Arming::Method::MAVLINK)) { @@ -459,7 +459,7 @@ void ToyMode::update() AP_Notify::flags.hybrid_loiter = false; #endif } else if (copter.position_ok() && set_and_remember_mode(Mode::Number::LOITER, ModeReason::TOY_MODE)) { -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED copter.fence.enable(true); #endif gcs().send_text(MAV_SEVERITY_INFO, "Tmode: LOITER update"); @@ -622,7 +622,7 @@ void ToyMode::update() copter.set_mode(Mode::Number::ALT_HOLD, ModeReason::TOY_MODE); } else { copter.set_mode(Mode::Number::ALT_HOLD, ModeReason::TOY_MODE); -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED copter.fence.enable(false); #endif if (copter.arming.arm(AP_Arming::Method::MAVLINK)) { @@ -643,13 +643,13 @@ void ToyMode::update() if (new_mode != copter.flightmode->mode_number()) { load_test.running = false; -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED copter.fence.enable(false); #endif if (set_and_remember_mode(new_mode, ModeReason::TOY_MODE)) { gcs().send_text(MAV_SEVERITY_INFO, "Tmode: mode %s", copter.flightmode->name4()); // force fence on in all GPS flight modes -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED if (copter.flightmode->requires_GPS()) { copter.fence.enable(true); } @@ -660,7 +660,7 @@ void ToyMode::update() // if we can't RTL then land gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: LANDING"); set_and_remember_mode(Mode::Number::LAND, ModeReason::TOY_MODE); -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED if (copter.landing_with_GPS()) { copter.fence.enable(true); } @@ -799,7 +799,7 @@ void ToyMode::action_arm(void) arm_check_compass(); if (needs_gps && copter.arming.gps_checks(false)) { -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // we want GPS and checks are passing, arm and enable fence copter.fence.enable(true); #endif @@ -815,7 +815,7 @@ void ToyMode::action_arm(void) AP_Notify::events.arming_failed = true; gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: GPS arming failed"); } else { -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // non-GPS mode copter.fence.enable(false); #endif diff --git a/ArduCopter/tuning.cpp b/ArduCopter/tuning.cpp index d9e1612966a..0cd125782e9 100644 --- a/ArduCopter/tuning.cpp +++ b/ArduCopter/tuning.cpp @@ -107,14 +107,14 @@ void Copter::tuning() #if MODE_ACRO_ENABLED == ENABLED || MODE_SPORT_ENABLED == ENABLED // Acro roll pitch rates case TUNING_ACRO_RP_RATE: - g2.acro_rp_rate = tuning_value; + g2.command_model_acro_rp.set_rate(tuning_value); break; #endif #if MODE_ACRO_ENABLED == ENABLED || MODE_DRIFT_ENABLED == ENABLED // Acro yaw rate case TUNING_ACRO_YAW_RATE: - g2.acro_y_rate = tuning_value; + g2.command_model_acro_y.set_rate(tuning_value); break; #endif @@ -180,14 +180,14 @@ void Copter::tuning() break; #endif - case TUNING_RATE_YAW_FILT: - attitude_control->get_rate_yaw_pid().filt_E_hz(tuning_value); - break; + case TUNING_RATE_YAW_FILT: + attitude_control->get_rate_yaw_pid().filt_E_hz(tuning_value); + break; - case TUNING_SYSTEM_ID_MAGNITUDE: + case TUNING_SYSTEM_ID_MAGNITUDE: #if MODE_SYSTEMID_ENABLED == ENABLED - copter.mode_systemid.set_magnitude(tuning_value); + copter.mode_systemid.set_magnitude(tuning_value); #endif - break; + break; } } diff --git a/ArduCopter/version.h b/ArduCopter/version.h index 34092026aa5..bb6248b3935 100644 --- a/ArduCopter/version.h +++ b/ArduCopter/version.h @@ -6,14 +6,14 @@ #include "ap_version.h" -#define THISFIRMWARE "ArduCopter V4.2.0-dev" +#define THISFIRMWARE "ArduCopter V4.3.8-beta1" // the following line is parsed by the autotest scripts -#define FIRMWARE_VERSION 4,2,0,FIRMWARE_VERSION_TYPE_DEV +#define FIRMWARE_VERSION 4,3,8,FIRMWARE_VERSION_TYPE_BETA+1 #define FW_MAJOR 4 -#define FW_MINOR 2 -#define FW_PATCH 0 -#define FW_TYPE FIRMWARE_VERSION_TYPE_DEV +#define FW_MINOR 3 +#define FW_PATCH 8 +#define FW_TYPE FIRMWARE_VERSION_TYPE_BETA #include diff --git a/ArduPlane/AP_Arming.cpp b/ArduPlane/AP_Arming.cpp index 1abe179c28c..d527469f591 100644 --- a/ArduPlane/AP_Arming.cpp +++ b/ArduPlane/AP_Arming.cpp @@ -17,6 +17,18 @@ const AP_Param::GroupInfo AP_Arming_Plane::var_info[] = { AP_GROUPEND }; +// expected to return true if the terrain database is required to have +// all data loaded +bool AP_Arming_Plane::terrain_database_required() const +{ +#if AP_TERRAIN_AVAILABLE + if (plane.g.terrain_follow) { + return true; + } +#endif + return AP_Arming::terrain_database_required(); +} + /* additional arming checks for plane @@ -66,6 +78,11 @@ bool AP_Arming_Plane::pre_arm_checks(bool display_failure) ret = false; } + if (plane.aparm.airspeed_min < MIN_AIRSPEED_MIN) { + check_failed(display_failure, "ARSPD_FBW_MIN too low (%i < %i)", plane.aparm.airspeed_min.get(), MIN_AIRSPEED_MIN); + ret = false; + } + if (plane.channel_throttle->get_reverse() && Plane::ThrFailsafe(plane.g.throttle_fs_enabled.get()) != Plane::ThrFailsafe::Disabled && plane.g.throttle_fs_value < @@ -102,6 +119,12 @@ bool AP_Arming_Plane::pre_arm_checks(bool display_failure) } } + if (plane.mission.get_in_landing_sequence_flag() && + !plane.mission.starts_with_takeoff_cmd()) { + check_failed(display_failure,"In landing sequence"); + ret = false; + } + return ret; } @@ -124,8 +147,9 @@ bool AP_Arming_Plane::quadplane_checks(bool display_failure) ret = false; } - if (!plane.quadplane.motors->initialised_ok()) { - check_failed(display_failure, "Quadplane: check motor setup"); + char failure_msg[50] {}; + if (!plane.quadplane.motors->arming_checks(ARRAY_SIZE(failure_msg), failure_msg)) { + check_failed(display_failure, "Motors: %s", failure_msg); ret = false; } @@ -153,7 +177,6 @@ bool AP_Arming_Plane::quadplane_checks(bool display_failure) } // ensure controllers are OK with us arming: - char failure_msg[50]; if (!plane.quadplane.pos_control->pre_arm_checks("PSC", failure_msg, ARRAY_SIZE(failure_msg))) { check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Bad parameter: %s", failure_msg); ret = false; @@ -162,8 +185,12 @@ bool AP_Arming_Plane::quadplane_checks(bool display_failure) check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Bad parameter: %s", failure_msg); ret = false; } + if (!plane.quadplane.motors->check_mot_pwm_params()) { + check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Check Q_M_PWM_MIN/MAX"); + ret = false; + } - if ((plane.quadplane.options & QuadPlane::OPTION_ONLY_ARM_IN_QMODE_OR_AUTO) != 0) { + if (plane.quadplane.option_is_set(QuadPlane::OPTION::ONLY_ARM_IN_QMODE_OR_AUTO)) { if (!plane.control_mode->is_vtol_mode() && (plane.control_mode != &plane.mode_auto) && (plane.control_mode != &plane.mode_guided)) { check_failed(display_failure,"not in Q mode"); ret = false; @@ -174,6 +201,26 @@ bool AP_Arming_Plane::quadplane_checks(bool display_failure) } } + if ((plane.control_mode == &plane.mode_auto) && !plane.mission.starts_with_takeoff_cmd()) { + check_failed(display_failure,"missing takeoff waypoint"); + ret = false; + } + + if (plane.control_mode == &plane.mode_rtl) { + check_failed(display_failure,"in RTL mode"); + ret = false; + } + + /* + Q_ASSIST_SPEED really should be enabled for all quadplanes except tailsitters + */ + if (check_enabled(ARMING_CHECK_PARAMETERS) && + is_zero(plane.quadplane.assist_speed) && + !plane.quadplane.tailsitter.enabled()) { + check_failed(display_failure,"Q_ASSIST_SPEED is not set"); + ret = false; + } + return ret; } #endif // HAL_QUADPLANE_ENABLED @@ -259,6 +306,18 @@ bool AP_Arming_Plane::arm(const AP_Arming::Method method, const bool do_arming_c return false; } + if (plane.update_home()) { + // after update_home the home position could still be + // different from the current_loc if the EKF refused the + // resetHeightDatum call. If we are updating home then we want + // to force the home to be the current_loc so relative alt + // takeoffs work correctly + if (plane.ahrs.set_home(plane.current_loc)) { + // update current_loc + plane.update_current_loc(); + } + } + change_arm_state(); // rising edge of delay_arming oneshot @@ -275,12 +334,15 @@ bool AP_Arming_Plane::arm(const AP_Arming::Method method, const bool do_arming_c bool AP_Arming_Plane::disarm(const AP_Arming::Method method, bool do_disarm_checks) { if (do_disarm_checks && - method == AP_Arming::Method::RUDDER) { - // don't allow rudder-disarming in flight: + (method == AP_Arming::Method::MAVLINK || + method == AP_Arming::Method::RUDDER)) { if (plane.is_flying()) { - // obviously this could happen in-flight so we can't warn about it + // don't allow mavlink or rudder disarm while flying return false; } + } + + if (do_disarm_checks && method == AP_Arming::Method::RUDDER) { // option must be enabled: if (get_rudder_arming_type() != AP_Arming::RudderArming::ARMDISARM) { gcs().send_text(MAV_SEVERITY_INFO, "Rudder disarm: disabled"); @@ -348,3 +410,40 @@ void AP_Arming_Plane::update_soft_armed() } } +/* + extra plane mission checks + */ +bool AP_Arming_Plane::mission_checks(bool report) +{ + // base checks + bool ret = AP_Arming::mission_checks(report); + if (plane.mission.get_landing_sequence_start() > 0 && plane.g.rtl_autoland == RtlAutoland::RTL_DISABLE) { + ret = false; + check_failed(ARMING_CHECK_MISSION, report, "DO_LAND_START set and RTL_AUTOLAND disabled"); + } +#if HAL_QUADPLANE_ENABLED + if (plane.quadplane.available()) { + const uint16_t num_commands = plane.mission.num_commands(); + AP_Mission::Mission_Command prev_cmd {}; + for (uint16_t i=1; i 0 || (plane.g2.flight_options & FlightOptions::CLIMB_BEFORE_TURN))) { // ensure we do the initial climb in RTL. We add an extra // 10m in the demanded height to push TECS to climb // quickly - target_alt = MAX(target_alt, prev_WP_loc.alt - home.alt) + (g2.rtl_climb_min+10)*100; + tecs_target_alt_cm = MAX(tecs_target_alt_cm, prev_WP_loc.alt - home.alt) + (g2.rtl_climb_min+10)*100; } - TECS_controller.update_pitch_throttle(target_alt, + TECS_controller.update_pitch_throttle(tecs_target_alt_cm, target_airspeed_cm, flight_stage, distance_beyond_land_wp, @@ -713,19 +721,20 @@ bool Plane::get_wp_crosstrack_error_m(float &xtrack_error) const #if AP_SCRIPTING_ENABLED // set target location (for use by scripting) -bool Plane::set_target_location(const Location& target_loc) +bool Plane::set_target_location(const Location &target_loc) { + Location loc{target_loc}; + if (plane.control_mode != &plane.mode_guided) { // only accept position updates when in GUIDED mode return false; } - plane.guided_WP_loc = target_loc; // add home alt if needed - if (plane.guided_WP_loc.relative_alt) { - plane.guided_WP_loc.alt += plane.home.alt; - plane.guided_WP_loc.relative_alt = 0; + if (loc.relative_alt) { + loc.alt += plane.home.alt; + loc.relative_alt = 0; } - plane.set_guided_WP(); + plane.set_guided_WP(loc); return true; } @@ -738,6 +747,7 @@ bool Plane::get_target_location(Location& target_loc) case Mode::Number::GUIDED: case Mode::Number::AUTO: case Mode::Number::LOITER: + case Mode::Number::TAKEOFF: #if HAL_QUADPLANE_ENABLED case Mode::Number::QLOITER: case Mode::Number::QLAND: @@ -751,28 +761,68 @@ bool Plane::get_target_location(Location& target_loc) } return false; } + +/* + update_target_location() works in all auto navigation modes + */ +bool Plane::update_target_location(const Location &old_loc, const Location &new_loc) +{ + if (!old_loc.same_latlon_as(next_WP_loc)) { + return false; + } + ftype alt_diff; + if (!old_loc.get_alt_distance(next_WP_loc, alt_diff) || + !is_zero(alt_diff)) { + return false; + } + next_WP_loc = new_loc; + next_WP_loc.change_alt_frame(old_loc.get_alt_frame()); + + return true; +} + +// allow for velocity matching in VTOL +bool Plane::set_velocity_match(const Vector2f &velocity) +{ +#if HAL_QUADPLANE_ENABLED + if (quadplane.in_vtol_mode() || quadplane.in_vtol_land_sequence()) { + quadplane.poscontrol.velocity_match = velocity; + quadplane.poscontrol.last_velocity_match_ms = AP_HAL::millis(); + return true; + } +#endif + return false; +} + #endif // AP_SCRIPTING_ENABLED -#if OSD_ENABLED // correct AHRS pitch for TRIM_PITCH_CD in non-VTOL modes, and return VTOL view in VTOL void Plane::get_osd_roll_pitch_rad(float &roll, float &pitch) const { - pitch = ahrs.pitch; - roll = ahrs.roll; -#if HAL_QUADPLANE_ENABLED - if (quadplane.show_vtol_view()) { - return; - } -#endif - if (!(g2.flight_options & FlightOptions::OSD_REMOVE_TRIM_PITCH_CD)) { // correct for TRIM_PITCH_CD - pitch -= g.pitch_trim_cd * 0.01 * DEG_TO_RAD; - return; - } #if HAL_QUADPLANE_ENABLED - pitch = quadplane.ahrs_view->pitch; - roll = quadplane.ahrs_view->roll; + if (quadplane.show_vtol_view()) { + pitch = quadplane.ahrs_view->pitch; + roll = quadplane.ahrs_view->roll; + return; + } #endif + pitch = ahrs.pitch; + roll = ahrs.roll; + if (!(g2.flight_options & FlightOptions::OSD_REMOVE_TRIM_PITCH_CD)) { // correct for TRIM_PITCH_CD + pitch -= g.pitch_trim_cd * 0.01 * DEG_TO_RAD; + } +} + +/* + update current_loc Location + */ +void Plane::update_current_loc(void) +{ + have_position = plane.ahrs.get_location(plane.current_loc); + + // re-calculate relative altitude + ahrs.get_relative_position_D_home(plane.relative_altitude); + relative_altitude *= -1.0f; } -#endif AP_HAL_MAIN_CALLBACKS(&plane); diff --git a/ArduPlane/Attitude.cpp b/ArduPlane/Attitude.cpp index 52d455af6d2..765d022efe6 100644 --- a/ArduPlane/Attitude.cpp +++ b/ArduPlane/Attitude.cpp @@ -9,23 +9,24 @@ float Plane::calc_speed_scaler(void) { float aspeed, speed_scaler; if (ahrs.airspeed_estimate(aspeed)) { - if (aspeed > auto_state.highest_airspeed) { + if (aspeed > auto_state.highest_airspeed && hal.util->get_soft_armed()) { auto_state.highest_airspeed = aspeed; } + // ensure we have scaling over the full configured airspeed + const float airspeed_min = MAX(aparm.airspeed_min, MIN_AIRSPEED_MIN); + const float scale_min = MIN(0.5, g.scaling_speed / (2.0 * aparm.airspeed_max)); + const float scale_max = MAX(2.0, g.scaling_speed / (0.7 * airspeed_min)); if (aspeed > 0.0001f) { speed_scaler = g.scaling_speed / aspeed; } else { - speed_scaler = 2.0; + speed_scaler = scale_max; } - // ensure we have scaling over the full configured airspeed - float scale_min = MIN(0.5, (0.5 * aparm.airspeed_min) / g.scaling_speed); - float scale_max = MAX(2.0, (1.5 * aparm.airspeed_max) / g.scaling_speed); speed_scaler = constrain_float(speed_scaler, scale_min, scale_max); #if HAL_QUADPLANE_ENABLED if (quadplane.in_vtol_mode() && hal.util->get_soft_armed()) { // when in VTOL modes limit surface movement at low speed to prevent instability - float threshold = aparm.airspeed_min * 0.5; + float threshold = airspeed_min * 0.5; if (aspeed < threshold) { float new_scaler = linear_interpolate(0.001, g.scaling_speed / threshold, aspeed, 0, threshold); speed_scaler = MIN(speed_scaler, new_scaler); @@ -61,7 +62,11 @@ float Plane::calc_speed_scaler(void) */ bool Plane::stick_mixing_enabled(void) { -#if AC_FENCE == ENABLED + if (!rc().has_valid_input()) { + // never stick mix without valid RC + return false; + } +#if AP_FENCE_ENABLED const bool stickmixing = fence_stickmixing(); #else const bool stickmixing = true; @@ -81,10 +86,7 @@ bool Plane::stick_mixing_enabled(void) // we're in an auto mode. Check the stick mixing flag if (g.stick_mixing != StickMixing::NONE && g.stick_mixing != StickMixing::VTOL_YAW && - stickmixing && - failsafe.state == FAILSAFE_NONE && - !rc_failsafe_active()) { - // we're in an auto mode, and haven't triggered failsafe + stickmixing) { return true; } else { return false; @@ -236,6 +238,11 @@ void Plane::stabilize_stick_mixing_direct() aileron = channel_roll->stick_mixing(aileron); SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, aileron); + if ((control_mode == &mode_loiter) && (plane.g2.flight_options & FlightOptions::ENABLE_LOITER_ALT_CONTROL)) { + // loiter is using altitude control based on the pitch stick, don't use it again here + return; + } + float elevator = SRV_Channels::get_output_scaled(SRV_Channel::k_elevator); elevator = channel_pitch->stick_mixing(elevator); SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, elevator); @@ -280,7 +287,12 @@ void Plane::stabilize_stick_mixing_fbw() } nav_roll_cd += roll_input * roll_limit_cd; nav_roll_cd = constrain_int32(nav_roll_cd, -roll_limit_cd, roll_limit_cd); - + + if ((control_mode == &mode_loiter) && (plane.g2.flight_options & FlightOptions::ENABLE_LOITER_ALT_CONTROL)) { + // loiter is using altitude control based on the pitch stick, don't use it again here + return; + } + float pitch_input = channel_pitch->norm_input(); if (pitch_input > 0.5f) { pitch_input = (3*pitch_input - 1); @@ -595,6 +607,7 @@ void Plane::calc_nav_yaw_coordinated(float speed_scaler) int16_t rudder_in = rudder_input(); int16_t commanded_rudder; + bool using_rate_controller = false; // Received an external msg that guides yaw in the last 3 seconds? if (control_mode->is_guided_mode() && @@ -605,7 +618,10 @@ void Plane::calc_nav_yaw_coordinated(float speed_scaler) // user is doing an AUTOTUNE with yaw rate control const float rudd_expo = rudder_in_expo(true); const float yaw_rate = (rudd_expo/SERVO_MAX) * g.acro_yaw_rate; - commanded_rudder = yawController.get_rate_out(yaw_rate, speed_scaler, false); + // add in the corrdinated turn yaw rate to make it easier to fly while tuning the yaw rate controller + const float coordination_yaw_rate = degrees(GRAVITY_MSS * tanf(radians(nav_roll_cd*0.01f))/MAX(aparm.airspeed_min,smoothed_airspeed)); + commanded_rudder = yawController.get_rate_out(yaw_rate+coordination_yaw_rate, speed_scaler, false); + using_rate_controller = true; } else { if (control_mode == &mode_stabilize && rudder_in != 0) { disable_integrator = true; @@ -619,6 +635,13 @@ void Plane::calc_nav_yaw_coordinated(float speed_scaler) } steering_control.rudder = constrain_int16(commanded_rudder, -4500, 4500); + + if (!using_rate_controller) { + /* + When not running the yaw rate controller, we need to reset the rate + */ + yawController.reset_rate_PID(); + } } /* @@ -737,8 +760,7 @@ void Plane::calc_nav_roll() float bank_limit = degrees(atanf(guided_state.target_heading_accel_limit/GRAVITY_MSS)) * 1e2f; - g2.guidedHeading.update_error(error); // push error into AC_PID , possible improvement is to use update_all instead.? - g2.guidedHeading.set_dt(delta); + g2.guidedHeading.update_error(error, delta); // push error into AC_PID , possible improvement is to use update_all instead.? float i = g2.guidedHeading.get_i(); // get integrator TODO if (((is_negative(error) && !guided_state.target_heading_limit_low) || (is_positive(error) && !guided_state.target_heading_limit_high))) { diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 591ec224de5..eed957f52c5 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -1,6 +1,9 @@ #include "GCS_Mavlink.h" #include "Plane.h" +#include +#include +#include MAV_TYPE GCS_Plane::frame_type() const { @@ -172,20 +175,23 @@ void GCS_MAVLINK_Plane::send_nav_controller_output() const } #if HAL_QUADPLANE_ENABLED const QuadPlane &quadplane = plane.quadplane; - if (quadplane.show_vtol_view()) { + if (quadplane.show_vtol_view() && quadplane.using_wp_nav()) { const Vector3f &targets = quadplane.attitude_control->get_att_target_euler_cd(); - bool wp_nav_valid = quadplane.using_wp_nav(); + + const Vector2f& curr_pos = quadplane.inertial_nav.get_position_xy_cm(); + const Vector2f& target_pos = quadplane.pos_control->get_pos_target_cm().xy().tofloat(); + const Vector2f error = (target_pos - curr_pos) * 0.01; mavlink_msg_nav_controller_output_send( chan, targets.x * 0.01, targets.y * 0.01, targets.z * 0.01, - wp_nav_valid ? quadplane.wp_nav->get_wp_bearing_to_destination() : 0, - wp_nav_valid ? MIN(quadplane.wp_nav->get_wp_distance_to_destination() * 0.01, UINT16_MAX) : 0, + degrees(error.angle()), + MIN(error.length(), UINT16_MAX), (plane.control_mode != &plane.mode_qstabilize) ? quadplane.pos_control->get_pos_error_z_cm() * 0.01 : 0, plane.airspeed_error * 100, // incorrect units; see PR#7933 - wp_nav_valid ? quadplane.wp_nav->crosstrack_error() : 0); + quadplane.wp_nav->crosstrack_error()); return; } #endif @@ -244,9 +250,11 @@ float GCS_MAVLINK_Plane::vfr_hud_airspeed() const // will use an airspeed sensor, that value is constrained by the // ground speed. When reporting we should send the true airspeed // value if possible: +#if AP_AIRSPEED_ENABLED if (plane.airspeed.enabled() && plane.airspeed.healthy()) { return plane.airspeed.get_airspeed(); } +#endif // airspeed estimates are OK: float aspeed; @@ -285,7 +293,7 @@ void GCS_MAVLINK_Plane::send_wind() const } // sends a single pid info over the provided channel -void GCS_MAVLINK_Plane::send_pid_info(const AP_Logger::PID_Info *pid_info, +void GCS_MAVLINK_Plane::send_pid_info(const AP_PIDInfo *pid_info, const uint8_t axis, const float achieved) { if (pid_info == nullptr) { @@ -317,7 +325,7 @@ void GCS_MAVLINK_Plane::send_pid_tuning() const Parameters &g = plane.g; - const AP_Logger::PID_Info *pid_info; + const AP_PIDInfo *pid_info; if (g.gcs_pid_mask & TUNING_BITS_ROLL) { pid_info = &plane.rollController.get_pid_info(); #if HAL_QUADPLANE_ENABLED @@ -411,12 +419,58 @@ bool GCS_MAVLINK_Plane::try_send_message(enum ap_message id) case MSG_LANDING: plane.landing.send_landing_message(chan); break; + + case MSG_HYGROMETER: +#if AP_AIRSPEED_HYGROMETER_ENABLE + CHECK_PAYLOAD_SIZE(HYGROMETER_SENSOR); + send_hygrometer(); +#endif + break; + default: return GCS_MAVLINK::try_send_message(id); } return true; } +#if AP_AIRSPEED_HYGROMETER_ENABLE +void GCS_MAVLINK_Plane::send_hygrometer() +{ + if (!HAVE_PAYLOAD_SPACE(chan, HYGROMETER_SENSOR)) { + return; + } + + const auto *airspeed = AP::airspeed(); + if (airspeed == nullptr) { + return; + } + const uint32_t now = AP_HAL::millis(); + + for (uint8_t i=0; iget_hygrometer(idx, last_sample_ms, temperature, humidity)) { + continue; + } + if (now - last_sample_ms > 2000) { + // not updating, stop sending + continue; + } + if (!HAVE_PAYLOAD_SPACE(chan, HYGROMETER_SENSOR)) { + return; + } + + mavlink_msg_hygrometer_sensor_send( + chan, + idx, + int16_t(temperature*100), + uint16_t(humidity*100)); + last_hygrometer_send_idx = idx; + } +} +#endif // AP_AIRSPEED_HYGROMETER_ENABLE + /* default stream rates to 1Hz @@ -428,6 +482,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK_Parameters, streamRates[0], 1), @@ -437,6 +492,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK_Parameters, streamRates[1], 1), @@ -446,6 +502,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK_Parameters, streamRates[2], 1), @@ -455,6 +512,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("RAW_CTRL", 3, GCS_MAVLINK_Parameters, streamRates[3], 1), @@ -464,6 +522,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("POSITION", 4, GCS_MAVLINK_Parameters, streamRates[4], 1), @@ -473,6 +532,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK_Parameters, streamRates[5], 1), @@ -482,6 +542,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK_Parameters, streamRates[6], 1), @@ -491,6 +552,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK_Parameters, streamRates[7], 1), @@ -500,6 +562,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK_Parameters, streamRates[8], 10), @@ -509,6 +572,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("ADSB", 9, GCS_MAVLINK_Parameters, streamRates[9], 5), AP_GROUPEND @@ -552,12 +616,19 @@ static const ap_message STREAM_EXTRA1_msgs[] = { MSG_ATTITUDE, MSG_SIMSTATE, MSG_AHRS2, +#if AP_RPM_ENABLED MSG_RPM, +#endif MSG_AOA_SSA, MSG_PID_TUNING, MSG_LANDING, MSG_ESC_TELEMETRY, +#if HAL_EFI_ENABLED MSG_EFI_STATUS, +#endif +#if AP_AIRSPEED_HYGROMETER_ENABLE + MSG_HYGROMETER, +#endif }; static const ap_message STREAM_EXTRA2_msgs[] = { MSG_VFR_HUD @@ -574,9 +645,8 @@ static const ap_message STREAM_EXTRA3_msgs[] = { #endif MSG_BATTERY2, MSG_BATTERY_STATUS, - MSG_MOUNT_STATUS, + MSG_GIMBAL_DEVICE_ATTITUDE_STATUS, MSG_OPTICAL_FLOW, - MSG_GIMBAL_REPORT, MSG_MAG_CAL_REPORT, MSG_MAG_CAL_PROGRESS, MSG_EKF_STATUS_REPORT, @@ -586,7 +656,8 @@ static const ap_message STREAM_PARAMS_msgs[] = { MSG_NEXT_PARAM }; static const ap_message STREAM_ADSB_msgs[] = { - MSG_ADSB_VEHICLE + MSG_ADSB_VEHICLE, + MSG_AIS_VESSEL, }; const struct GCS_MAVLINK::stream_entries GCS_MAVLINK::all_stream_entries[] = { @@ -642,6 +713,10 @@ void GCS_MAVLINK_Plane::packetReceived(const mavlink_status_t &status, { #if HAL_ADSB_ENABLED plane.avoidance_adsb.handle_msg(msg); +#endif +#if AP_SCRIPTING_ENABLED + // pass message to follow library + plane.g2.follow.handle_msg(msg); #endif GCS_MAVLINK::packetReceived(status, msg); } @@ -695,15 +770,14 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_do_reposition(const mavlink_com if (((int32_t)packet.param2 & MAV_DO_REPOSITION_FLAGS_CHANGE_MODE) || (plane.control_mode == &plane.mode_guided)) { plane.set_mode(plane.mode_guided, ModeReason::GCS_COMMAND); - plane.guided_WP_loc = requested_position; // add home alt if needed - if (plane.guided_WP_loc.relative_alt) { - plane.guided_WP_loc.alt += plane.home.alt; - plane.guided_WP_loc.relative_alt = 0; + if (requested_position.relative_alt) { + requested_position.alt += plane.home.alt; + requested_position.relative_alt = 0; } - plane.set_guided_WP(); + plane.set_guided_WP(requested_position); return MAV_RESULT_ACCEPTED; } @@ -874,6 +948,16 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in case MAV_CMD_GUIDED_CHANGE_HEADING: return handle_command_int_guided_slew_commands(packet); + case MAV_CMD_DO_FOLLOW: +#if AP_SCRIPTING_ENABLED + // param1: sysid of target to follow + if ((packet.param1 > 0) && (packet.param1 <= 255)) { + plane.g2.follow.set_target_sysid((uint8_t)packet.param1); + return MAV_RESULT_ACCEPTED; + } +#endif + return MAV_RESULT_FAILED; + default: return GCS_MAVLINK::handle_command_int_packet(packet); } @@ -954,7 +1038,7 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_l const bool attempt_go_around = (!plane.quadplane.available()) || ((!plane.quadplane.in_vtol_auto()) && - (!(plane.quadplane.options & QuadPlane::OPTION_MISSION_LAND_FW_APPROACH))); + (!plane.quadplane.landing_with_fixed_wing_spiral_approach())); #else const bool attempt_go_around = true; #endif @@ -1069,12 +1153,24 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_l return MAV_RESULT_ACCEPTED; #endif +#if AP_ICENGINE_ENABLED case MAV_CMD_DO_ENGINE_CONTROL: if (!plane.g2.ice_control.engine_control(packet.param1, packet.param2, packet.param3)) { return MAV_RESULT_FAILED; } return MAV_RESULT_ACCEPTED; +#endif +#if AP_SCRIPTING_ENABLED + case MAV_CMD_DO_FOLLOW: + // param1: sysid of target to follow + if ((packet.param1 > 0) && (packet.param1 <= 255)) { + plane.g2.follow.set_target_sysid((uint8_t)packet.param1); + return MAV_RESULT_ACCEPTED; + } + return MAV_RESULT_FAILED; +#endif + default: return GCS_MAVLINK::handle_command_long_packet(packet); } @@ -1194,23 +1290,6 @@ void GCS_MAVLINK_Plane::handleMessage(const mavlink_message_t &msg) break; } - case MAVLINK_MSG_ID_SET_HOME_POSITION: - { - send_received_message_deprecation_warning(STR_VALUE(MAVLINK_MSG_ID_SET_HOME_POSITION)); - - mavlink_set_home_position_t packet; - mavlink_msg_set_home_position_decode(&msg, &packet); - Location new_home_loc {}; - new_home_loc.lat = packet.latitude; - new_home_loc.lng = packet.longitude; - new_home_loc.alt = packet.altitude / 10; - if (!set_home(new_home_loc, false)) { - // silently fails... - break; - } - break; - } - case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED: { // decode packet diff --git a/ArduPlane/GCS_Mavlink.h b/ArduPlane/GCS_Mavlink.h index 95fa3bca64c..4b7304bb927 100644 --- a/ArduPlane/GCS_Mavlink.h +++ b/ArduPlane/GCS_Mavlink.h @@ -2,6 +2,7 @@ #include #include +#include class GCS_MAVLINK_Plane : public GCS_MAVLINK { @@ -41,7 +42,7 @@ class GCS_MAVLINK_Plane : public GCS_MAVLINK private: - void send_pid_info(const AP_Logger::PID_Info *pid_info, const uint8_t axis, const float achieved); + void send_pid_info(const AP_PIDInfo *pid_info, const uint8_t axis, const float achieved); void handleMessage(const mavlink_message_t &msg) override; bool handle_guided_request(AP_Mission::Mission_Command &cmd) override; @@ -71,6 +72,11 @@ class GCS_MAVLINK_Plane : public GCS_MAVLINK uint8_t high_latency_wind_direction() const override; #endif // HAL_HIGH_LATENCY2_ENABLED +#if AP_AIRSPEED_HYGROMETER_ENABLE + void send_hygrometer(); + uint8_t last_hygrometer_send_idx; +#endif + MAV_VTOL_STATE vtol_state() const override; MAV_LANDED_STATE landed_state() const override; diff --git a/ArduPlane/GCS_Plane.cpp b/ArduPlane/GCS_Plane.cpp index c0b094fb808..ec51ad8aa87 100644 --- a/ArduPlane/GCS_Plane.cpp +++ b/ArduPlane/GCS_Plane.cpp @@ -99,7 +99,7 @@ void GCS_Plane::update_vehicle_sensor_status_flags(void) } #if AP_OPTICALFLOW_ENABLED - const OpticalFlow *optflow = AP::opticalflow(); + const AP_OpticalFlow *optflow = AP::opticalflow(); if (optflow && optflow->enabled()) { control_sensors_present |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW; control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW; diff --git a/ArduPlane/Log.cpp b/ArduPlane/Log.cpp index ad3ba064f66..8ed1f0d5755 100644 --- a/ArduPlane/Log.cpp +++ b/ArduPlane/Log.cpp @@ -20,10 +20,14 @@ void Plane::Log_Write_Attitude(void) quadplane.attitude_control->get_attitude_target_quat().to_euler(targets.x, targets.y, targets.z); targets *= degrees(100.0f); quadplane.ahrs_view->Write_AttitudeView(targets); - } else { + } else +#endif + { ahrs.Write_Attitude(targets); } - if (quadplane.in_vtol_mode() || quadplane.in_assisted_flight()) { + +#if HAL_QUADPLANE_ENABLED + if (AP_HAL::millis() - quadplane.last_att_control_ms < 100) { // log quadplane PIDs separately from fixed wing PIDs logger.Write_PID(LOG_PIQR_MSG, quadplane.attitude_control->get_rate_roll_pid().get_pid_info()); logger.Write_PID(LOG_PIQP_MSG, quadplane.attitude_control->get_rate_pitch_pid().get_pid_info()); @@ -45,17 +49,11 @@ void Plane::Log_Write_Attitude(void) } // do fast logging for plane -void Plane::Log_Write_Fast(void) +void Plane::Log_Write_FullRate(void) { - if (!should_log(MASK_LOG_ATTITUDE_FULLRATE)) { - uint32_t now = AP_HAL::millis(); - if (now - last_log_fast_ms < 40) { - // default to 25Hz - return; - } - last_log_fast_ms = now; - } - if (should_log(MASK_LOG_ATTITUDE_FAST | MASK_LOG_ATTITUDE_FULLRATE)) { + // MASK_LOG_ATTITUDE_FULLRATE logs at 400Hz, MASK_LOG_ATTITUDE_FAST at 25Hz, MASK_LOG_ATTIUDE_MED logs at 10Hz + // highest rate selected wins + if (should_log(MASK_LOG_ATTITUDE_FULLRATE)) { Log_Write_Attitude(); } } @@ -149,7 +147,8 @@ struct PACKED log_Nav_Tuning { float airspeed_error; int32_t target_lat; int32_t target_lng; - int32_t target_alt; + int32_t target_alt_wp; + int32_t target_alt_tecs; int32_t target_airspeed; }; @@ -168,7 +167,8 @@ void Plane::Log_Write_Nav_Tuning() airspeed_error : airspeed_error, target_lat : next_WP_loc.lat, target_lng : next_WP_loc.lng, - target_alt : next_WP_loc.alt, + target_alt_wp : next_WP_loc.alt, + target_alt_tecs : tecs_target_alt_cm, target_airspeed : target_airspeed_cm, }; logger.WriteBlock(&pkt, sizeof(pkt)); @@ -308,16 +308,17 @@ const struct LogStructure Plane::log_structure[] = { // @Field: Dist: distance to the current navigation waypoint // @Field: TBrg: bearing to the current navigation waypoint // @Field: NavBrg: the vehicle's desired heading -// @Field: AltErr: difference between current vehicle height and target height +// @Field: AltE: difference between current vehicle height and target height // @Field: XT: the vehicle's current distance from the current travel segment // @Field: XTi: integration of the vehicle's crosstrack error -// @Field: AspdE: difference between vehicle's airspeed and desired airspeed +// @Field: AsE: difference between vehicle's airspeed and desired airspeed // @Field: TLat: target latitude // @Field: TLng: target longitude -// @Field: TAlt: target altitude -// @Field: TAspd: target airspeed +// @Field: TAW: target altitude WP +// @Field: TAT: target altitude TECS +// @Field: TAsp: target airspeed { LOG_NTUN_MSG, sizeof(log_Nav_Tuning), - "NTUN", "QfcccfffLLii", "TimeUS,Dist,TBrg,NavBrg,AltErr,XT,XTi,AspdE,TLat,TLng,TAlt,TAspd", "smddmmmnDUmn", "F0BBB0B0GGBB" , true }, + "NTUN", "QfcccfffLLeee", "TimeUS,Dist,TBrg,NavBrg,AltE,XT,XTi,AsE,TLat,TLng,TAW,TAT,TAsp", "smddmmmnDUmmn", "F0BBB0B0GG000" , true }, // @LoggerMessage: ATRP // @Description: Plane AutoTune diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index 1b0c5139404..bee825802bc 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -617,8 +617,8 @@ const AP_Param::Info Plane::var_info[] = { // @Param: LOG_BITMASK // @DisplayName: Log bitmask - // @Description: Bitmap of what on-board log types to enable. This value is made up of the sum of each of the log types you want to be saved. It is usually best just to enable all log types by setting this to 65535. The individual bits are ATTITUDE_FAST=1, ATTITUDE_MEDIUM=2, GPS=4, PerformanceMonitoring=8, ControlTuning=16, NavigationTuning=32, Mode=64, IMU=128, Commands=256, Battery=512, Compass=1024, TECS=2048, Camera=4096, RCandServo=8192, Sonar=16384, Arming=32768, FullLogs=65535 - // @Bitmask: 0:ATTITUDE_FAST,1:ATTITUDE_MED,2:GPS,3:PM,4:CTUN,5:NTUN,6:MODE,7:IMU,8:CMD,9:CURRENT,10:COMPASS,11:TECS,12:CAMERA,13:RC,14:SONAR,15:ARM/DISARM,19:IMU_RAW,20:ATTITUDE_FULLRATE,21:VideoStabilization + // @Description: Bitmap of what on-board log types to enable. This value is made up of the sum of each of the log types you want to be saved. It is usually best just to enable all basic log types by setting this to 65535. + // @Bitmask: 0:Fast Attitude,1:Medium Attitude,2:GPS,3:Performance,4:Control Tuning,5:Navigation Tuning,7:IMU,8:Mission Commands,9:Battery Monitor,10:Compass,11:TECS,12:Camera,13:RC Input-Output,14:Rangefinder,19:Raw IMU,20:Fullrate Attitude,21:Video Stabilization // @User: Advanced GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK), @@ -716,10 +716,10 @@ const AP_Param::Info Plane::var_info[] = { // @Param: RTL_AUTOLAND // @DisplayName: RTL auto land - // @Description: Automatically begin landing sequence after arriving at RTL location. This requires the addition of a DO_LAND_START mission item, which acts as a marker for the start of a landing sequence. The closest landing sequence will be chosen to the current location. - // @Values: 0:Disable,1:Enable - go HOME then land,2:Enable - go directly to landing sequence + // @Description: Automatically begin landing sequence after arriving at RTL location. This requires the addition of a DO_LAND_START mission item, which acts as a marker for the start of a landing sequence. The closest landing sequence will be chosen to the current location. If this is set to 0 and there is a DO_LAND_START mission item then you will get an arming check failure. You can set to a value of 3 to avoid the arming check failure and use the DO_LAND_START for go-around without it changing RTL behaviour. For a value of 1 a rally point will be used instead of HOME if in range (see rally point documentation). + // @Values: 0:Disable,1:Fly HOME then land,2:Go directly to landing sequence, 3:OnlyForGoAround // @User: Standard - GSCALAR(rtl_autoland, "RTL_AUTOLAND", 0), + GSCALAR(rtl_autoland, "RTL_AUTOLAND", float(RtlAutoland::RTL_DISABLE)), // @Param: CRASH_ACC_THRESH // @DisplayName: Crash Deceleration Threshold @@ -924,7 +924,7 @@ const AP_Param::Info Plane::var_info[] = { GOBJECT(can_mgr, "CAN_", AP_CANManager), #endif -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#if AP_SIM_ENABLED // @Group: SIM_ // @Path: ../libraries/SITL/SITL.cpp GOBJECT(sitl, "SIM_", SITL::SIM), @@ -939,7 +939,7 @@ const AP_Param::Info Plane::var_info[] = { #if AP_OPTICALFLOW_ENABLED // @Group: FLOW // @Path: ../libraries/AP_OpticalFlow/AP_OpticalFlow.cpp - GOBJECT(optflow, "FLOW", OpticalFlow), + GOBJECT(optflow, "FLOW", AP_OpticalFlow), #endif // @Group: MIS_ @@ -950,12 +950,6 @@ const AP_Param::Info Plane::var_info[] = { // @Path: ../libraries/AP_Rally/AP_Rally.cpp GOBJECT(rally, "RALLY_", AP_Rally), -#if AC_FENCE == ENABLED - // @Group: FENCE_ - // @Path: ../libraries/AC_Fence/AC_Fence.cpp - GOBJECT(fence, "FENCE_", AC_Fence), -#endif - #if HAL_NAVEKF2_AVAILABLE // @Group: EK2_ // @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp @@ -1016,9 +1010,11 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { AP_SUBGROUPPTR(button_ptr, "BTN_", 1, ParametersG2, AP_Button), #endif +#if AP_ICENGINE_ENABLED // @Group: ICE_ // @Path: ../libraries/AP_ICEngine/AP_ICEngine.cpp AP_SUBGROUPINFO(ice_control, "ICE_", 2, ParametersG2, AP_ICEngine), +#endif // 3 was used by prototype for servo_channels @@ -1082,7 +1078,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Param: FLIGHT_OPTIONS // @DisplayName: Flight mode options // @Description: Flight mode specific options - // @Bitmask: 0:Rudder mixing in direct flight modes only (Manual / Stabilize / Acro),1:Use centered throttle in Cruise or FBWB to indicate trim airspeed, 2:Disable attitude check for takeoff arming, 3:Force target airspeed to trim airspeed in Cruise or FBWB, 4: Climb to ALT_HOLD_RTL before turning for RTL, 5: Enable yaw damper in acro mode, 6: Surpress speed scaling during auto takeoffs to be 1 or less to prevent oscillations without airpseed sensor., 7:EnableDefaultAirspeed for takeoff, 8: Remove the TRIM_PITCH_CD on the GCS horizon, 9: Remove the TRIM_PITCH_CD on the OSD horizon, 10: Adjust mid-throttle to be TRIM_THROTTLE in non-auto throttle modes except MANUAL, 11:Disable suppression of fixed wing rate gains in ground mode + // @Bitmask: 0:Rudder mixing in direct flight modes only (Manual / Stabilize / Acro),1:Use centered throttle in Cruise or FBWB to indicate trim airspeed, 2:Disable attitude check for takeoff arming, 3:Force target airspeed to trim airspeed in Cruise or FBWB, 4: Climb to ALT_HOLD_RTL before turning for RTL, 5: Enable yaw damper in acro mode, 6: Surpress speed scaling during auto takeoffs to be 1 or less to prevent oscillations without airpseed sensor., 7:EnableDefaultAirspeed for takeoff, 8: Remove the TRIM_PITCH_CD on the GCS horizon, 9: Remove the TRIM_PITCH_CD on the OSD horizon, 10: Adjust mid-throttle to be TRIM_THROTTLE in non-auto throttle modes except MANUAL, 11:Disable suppression of fixed wing rate gains in ground mode, 12: Enable FBWB style loiter altitude control // @User: Advanced AP_GROUPINFO("FLIGHT_OPTIONS", 13, ParametersG2, flight_options, 0), @@ -1229,12 +1225,21 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @User: Advanced // @Bitmask: 0: Servo 1, 1: Servo 2, 2: Servo 3, 3: Servo 4, 4: Servo 5, 5: Servo 6, 6: Servo 7, 7: Servo 8, 8: Servo 9, 9: Servo 10, 10: Servo 11, 11: Servo 12, 12: Servo 13, 13: Servo 14, 14: Servo 15 AP_GROUPINFO("ONESHOT_MASK", 32, ParametersG2, oneshot_mask, 0), + +#if AP_SCRIPTING_ENABLED + // @Group: FOLL + // @Path: ../libraries/AP_Follow/AP_Follow.cpp + AP_SUBGROUPINFO(follow, "FOLL", 33, ParametersG2, AP_Follow), +#endif AP_GROUPEND }; ParametersG2::ParametersG2(void) : - ice_control(plane.rpm_sensor) + unused_integer{1} +#if AP_ICENGINE_ENABLED + ,ice_control(plane.rpm_sensor) +#endif #if HAL_SOARING_ENABLED ,soaring_controller(plane.TECS_controller, plane.aparm) #endif @@ -1344,6 +1349,7 @@ void Plane::load_parameters(void) g.format_version.set_and_save(Parameters::k_format_version); hal.console->printf("done.\n"); } + g.format_version.set_default(Parameters::k_format_version); uint32_t before = micros(); // Load all auto-loaded EEPROM variables @@ -1379,6 +1385,7 @@ void Plane::load_parameters(void) } } +#if AP_FENCE_ENABLED enum ap_var_type ptype_fence_type; AP_Int8 *fence_type_new = (AP_Int8*)AP_Param::find("FENCE_TYPE", &ptype_fence_type); if (fence_type_new && !fence_type_new->configured()) { @@ -1463,6 +1470,7 @@ void Plane::load_parameters(void) } } } +#endif // AP_FENCE_ENABLED #if AP_TERRAIN_AVAILABLE g.terrain_follow.convert_parameter_width(AP_PARAM_INT8); @@ -1486,6 +1494,7 @@ void Plane::load_parameters(void) } #endif +#if AP_AIRSPEED_ENABLED // PARAMETER_CONVERSION - Added: Jan-2022 { const uint16_t old_key = g.k_param_airspeed; @@ -1493,6 +1502,30 @@ void Plane::load_parameters(void) const uint16_t old_top_element = 0; // Old group element in the tree for the first subgroup element (see AP_PARAM_KEY_DUMP) AP_Param::convert_class(old_key, &airspeed, airspeed.var_info, old_index, old_top_element, true); } +#endif + +#if HAL_INS_NUM_HARMONIC_NOTCH_FILTERS > 1 + if (!ins.harmonic_notches[1].params.enabled()) { + // notch filter parameter conversions (moved to INS_HNTC2) for 4.2.x, converted from fixed notch + const AP_Param::ConversionInfo notchfilt_conversion_info[] { + { Parameters::k_param_ins, 101, AP_PARAM_INT8, "INS_HNTC2_ENABLE" }, + { Parameters::k_param_ins, 293, AP_PARAM_FLOAT, "INS_HNTC2_ATT" }, + { Parameters::k_param_ins, 357, AP_PARAM_FLOAT, "INS_HNTC2_FREQ" }, + { Parameters::k_param_ins, 421, AP_PARAM_FLOAT, "INS_HNTC2_BW" }, + }; + uint8_t notchfilt_table_size = ARRAY_SIZE(notchfilt_conversion_info); + for (uint8_t i=0; iprintf("load_all took %uus\n", (unsigned)(micros() - before)); } diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index d22e435a47b..ab94503a9d7 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -350,7 +350,7 @@ class Parameters { k_param_gcs4, // stream rates k_param_gcs5, // stream rates k_param_gcs6, // stream rates - k_param_fence, // vehicle fence + k_param_fence, // vehicle fence - unused k_param_acro_yaw_rate, }; @@ -362,7 +362,7 @@ class Parameters { AP_Int16 sysid_my_gcs; AP_Int8 telem_delay; - AP_Int8 rtl_autoland; + AP_Enum rtl_autoland; AP_Int8 crash_accel_threshold; @@ -485,8 +485,10 @@ class ParametersG2 { AP_Stats stats; #endif +#if AP_ICENGINE_ENABLED // internal combustion engine control AP_ICEngine ice_control; +#endif // RC input channels RC_Channels_Plane rc_channels; @@ -545,6 +547,9 @@ class ParametersG2 { AC_PID guidedHeading{5000.0, 0.0, 0.0, 0 , 10.0, 5.0, 5.0 , 5.0 , 0.2}; #endif +#if AP_SCRIPTING_ENABLED + AP_Follow follow; +#endif AP_Float fs_ekf_thresh; @@ -556,6 +561,9 @@ class ParametersG2 { AP_Int8 man_expo_rudder; AP_Int32 oneshot_mask; + + // just to make compilation easier when all things are compiled out... + uint8_t unused_integer; }; extern const AP_Param::Info var_info[]; diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index cdf85eb5a91..028e04d999f 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -31,6 +31,7 @@ #include #include +#include #include #include #include // ArduPilot Mega Vector/Matrix math Library @@ -82,6 +83,7 @@ #include #include #include // Landing Gear library +#include #include "GCS_Mavlink.h" #include "GCS_Plane.h" @@ -95,10 +97,6 @@ #include "afs_plane.h" #endif -#if AC_FENCE == ENABLED -#include -#endif - // Local modules #include "defines.h" #include "mode.h" @@ -198,7 +196,7 @@ class Plane : public AP_Vehicle { AP_RPM rpm_sensor; - AP_TECS TECS_controller{ahrs, aparm, landing}; + AP_TECS TECS_controller{ahrs, aparm, landing, MASK_LOG_TECS}; AP_L1_Control L1_controller{ahrs, &TECS_controller}; // Attitude to servo controllers @@ -242,7 +240,7 @@ class Plane : public AP_Vehicle { #if AP_OPTICALFLOW_ENABLED // Optical flow sensor - OpticalFlow optflow; + AP_OpticalFlow optflow; #endif // Rally Ponints @@ -252,10 +250,6 @@ class Plane : public AP_Vehicle { AP_OSD osd; #endif -#if AC_FENCE == ENABLED - AC_Fence fence; -#endif - ModeCircle mode_circle; ModeStabilize mode_stabilize; ModeTraining mode_training; @@ -719,9 +713,6 @@ class Plane : public AP_Vehicle { // The location of the current/active waypoint. Used for altitude ramp, track following and loiter calculations. Location next_WP_loc {}; - // The location of the active waypoint in Guided mode. - struct Location guided_WP_loc {}; - // Altitude control struct { // target altitude above sea level in cm. Used for barometric @@ -877,7 +868,7 @@ class Plane : public AP_Vehicle { // Log.cpp uint32_t last_log_fast_ms; - void Log_Write_Fast(void); + void Log_Write_FullRate(void); void Log_Write_Attitude(void); void Log_Write_Control_Tuning(); void Log_Write_OFG_Guided(); @@ -938,6 +929,15 @@ class Plane : public AP_Vehicle { bool verify_command_callback(const AP_Mission::Mission_Command& cmd); float get_wp_radius() const; + void do_nav_delay(const AP_Mission::Mission_Command& cmd); + bool verify_nav_delay(const AP_Mission::Mission_Command& cmd); + + // Delay the next navigation command + struct { + uint32_t time_max_ms; + uint32_t time_start_ms; + } nav_delay; + #if AP_SCRIPTING_ENABLED // nav scripting support void do_nav_script_time(const AP_Mission::Mission_Command& cmd); @@ -945,8 +945,14 @@ class Plane : public AP_Vehicle { #endif // commands.cpp - void set_guided_WP(void); - void update_home(); + void set_guided_WP(const Location &loc); + + // update home position. Return true if update done + bool update_home(); + + // update current_loc + void update_current_loc(void); + // set home location and store it persistently: bool set_home_persistently(const Location &loc) WARN_IF_UNUSED; @@ -975,17 +981,16 @@ class Plane : public AP_Vehicle { void handle_battery_failsafe(const char* type_str, const int8_t action); bool failsafe_in_landing_sequence() const; // returns true if the vehicle is in landing sequence. Intended only for use in failsafe code. -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // fence.cpp void fence_check(); bool fence_stickmixing() const; + bool in_fence_recovery() const; #endif // ArduPlane.cpp void disarm_if_autoland_complete(); -# if OSD_ENABLED void get_osd_roll_pitch_rad(float &roll, float &pitch) const override; -#endif float tecs_hgt_afe(void); void efi_update(void); void get_scheduler_tasks(const AP_Scheduler::Task *&tasks, @@ -1006,8 +1011,8 @@ class Plane : public AP_Vehicle { void airspeed_ratio_update(void); #endif void compass_save(void); - void update_logging1(void); - void update_logging2(void); + void update_logging10(void); + void update_logging25(void); void update_control_mode(void); void update_fly_forward(void); void update_flight_stage(); @@ -1049,13 +1054,11 @@ class Plane : public AP_Vehicle { bool set_mode(Mode& new_mode, const ModeReason reason); bool set_mode(const uint8_t mode, const ModeReason reason) override; bool set_mode_by_number(const Mode::Number new_mode_number, const ModeReason reason); - ModeReason _last_reason; void check_long_failsafe(); void check_short_failsafe(); void startup_INS_ground(void); bool should_log(uint32_t mask); int8_t throttle_percentage(void); - void update_dynamic_notch() override; void notify_mode(const Mode& mode); // takeoff.cpp @@ -1204,11 +1207,19 @@ class Plane : public AP_Vehicle { float pitch_in_expo(bool use_dz) const; float rudder_in_expo(bool use_dz) const; + // mode reason for entering previous mode + ModeReason previous_mode_reason = ModeReason::UNKNOWN; + + // last target alt we passed to tecs + int32_t tecs_target_alt_cm; + public: void failsafe_check(void); #if AP_SCRIPTING_ENABLED bool set_target_location(const Location& target_loc) override; bool get_target_location(Location& target_loc) override; + bool update_target_location(const Location &old_loc, const Location &new_loc) override; + bool set_velocity_match(const Vector2f &velocity) override; #endif // AP_SCRIPTING_ENABLED }; diff --git a/ArduPlane/RC_Channel.cpp b/ArduPlane/RC_Channel.cpp index dcf71e5085b..2fbb0feede1 100644 --- a/ArduPlane/RC_Channel.cpp +++ b/ArduPlane/RC_Channel.cpp @@ -203,7 +203,7 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::aux_func_t ch_option, } } -// do_aux_function - implement the function invoked by auxillary switches +// do_aux_function - implement the function invoked by auxiliary switches bool RC_Channel_Plane::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos ch_flag) { switch(ch_option) { @@ -268,6 +268,7 @@ bool RC_Channel_Plane::do_aux_function(const aux_func_t ch_option, const AuxSwit case AUX_FUNC::FLAP: case AUX_FUNC::FBWA_TAILDRAGGER: + case AUX_FUNC::AIRBRAKE: break; // input labels, nothing to do #if HAL_QUADPLANE_ENABLED @@ -308,6 +309,7 @@ bool RC_Channel_Plane::do_aux_function(const aux_func_t ch_option, const AuxSwit switch (ch_flag) { case AuxSwitchPos::HIGH: plane.quadplane.air_mode = AirMode::ON; + plane.quadplane.throttle_wait = false; break; case AuxSwitchPos::MIDDLE: break; @@ -318,9 +320,9 @@ bool RC_Channel_Plane::do_aux_function(const aux_func_t ch_option, const AuxSwit break; #endif -case AUX_FUNC::ARSPD_CALIBRATE: + case AUX_FUNC::ARSPD_CALIBRATE: #if AP_AIRSPEED_AUTOCAL_ENABLE - switch (ch_flag) { + switch (ch_flag) { case AuxSwitchPos::HIGH: plane.airspeed.set_calibration_enabled(true); break; @@ -333,9 +335,9 @@ case AUX_FUNC::ARSPD_CALIBRATE: #endif break; - case AUX_FUNC::LANDING_FLARE: - do_aux_function_flare(ch_flag); - break; + case AUX_FUNC::LANDING_FLARE: + do_aux_function_flare(ch_flag); + break; case AUX_FUNC::PARACHUTE_RELEASE: #if PARACHUTE == ENABLED @@ -358,6 +360,7 @@ case AUX_FUNC::ARSPD_CALIBRATE: RC_Channel::do_aux_function_armdisarm(ch_flag); if (plane.arming.is_armed()) { plane.quadplane.air_mode = AirMode::ON; + plane.quadplane.throttle_wait = false; } break; diff --git a/ArduPlane/ReleaseNotes.txt b/ArduPlane/ReleaseNotes.txt index e45c3c3247b..c1d07487b5b 100644 --- a/ArduPlane/ReleaseNotes.txt +++ b/ArduPlane/ReleaseNotes.txt @@ -1,3 +1,797 @@ +Release 4.3.8-beta1 12th August 2023 +------------------------------------ + +Changes since 4.3.7: + + - fixed scripting restart bug which could cause a crash on a math error + - fixed RTK injection when first module is a moving baseline BASE + - fixed auto-enable of fence on forced arm + - fixed race condition that can cause gyro glitches with notch filtering + - fixed INAxxx battery monitors to allow for battery reset remaining + +Release 4.3.7 31st May 2023 +--------------------------- + +This stable release is for the 4.3.x stable series and is being done +because of a serious bug that has been found with RC input on boards +that use an IOMCU for RC input (boards with a separate set of 8 "main" +outputs from "aux" outputs). + +The bug was that when RC input is lost and the receiver is one that +uses "no pulses" for loss of RC input then there is a chance that when +the RC link is regained that ArduPilot will not regain RC control and +will continue in RC failsafe. + +The bug is an old one, first introduced in the 4.0.6 release in +September 2020. The bug does not occur often which is why it has been +such a long time before it was noticed. We would like to thank CUAV +for noticing and reporting the bug! + +This release also has some other changes, some of which are to sync +with the Copter 4.3.6 release (which will go to 4.3.7 with this RC +input bug fix) and some are other bugs found since the 4.3.5 plane +release. + +This release skips the 4.3.6 number to sync with copter. + +The full list of changes is: + + - fixed a fault in the INS batch sampler code if you change the INS_LOG_BAT_CNT parameter without rebooting + - fixed the RC input on IOMCU bug explained above + - fixed a bug in ICE engine control if you do a "delay engine start" mission command while flying + - added MCU voltage monitoring for the H757 microcontroller (eg. CubeOrangePlus) + - servo gimbal mount yaw handling fix (only affects 3-axis servo gimbals) + - PiccoloCAN fix for ESC voltage and current scaling + - Gremsy gimbal fix when attached to autopilot's serial3 (or higher) + - added CubeOrangePlus-bdshot build + - fixed a bug in handling bad UART data in the megasquirt serial EFI driver + - added -g option for configuring with debug symbols without full debug (helped with RCIN bug diagnosis) + - fixed airmode switch for QACRO and QSTABILIZE modes + - fixed a rare memory corruption bug in the STM32H757 + - fixed an EKF3 bug in accel bias calculations + - adjust EKF3 accel bias process noise for greater robustness + - cope with compassmot impacting GSF yaw numerical stability + + +Please test and report any issues! + +Release 4.3.5 26th March 2023 +------------------------------ + +- fixed 32 bit microsecond wrap in BDShot code + +This release has a single bug fix for a critical bug for anyone using +bi-directional DShot on their vehicle. If using bi-directional DShot +and the vehicle is running its motors when 32 bit microsecond time +wraps at 71 minutes (or multiples of 71 minutes) then the bug that is +fixed in this release has an approximately 1 in 3 chance of causing +the motor to stop. + +Note that the time is the time since boot, not the time since arming, +so even vehicles flying for a short time could be vulnerable if they +sit for a long time on the ground before takeoff. + +Release 4.3.4 1st March 2023 +----------------------------- + +- support CubeOrangePlus BG edition +- enable VTX power on MambaH743v4 +- probe external compasses on Foxeer Reaper F745 +- fixed home update on bad GPS quality +- fixed GPS unconfigured error for non-M10 uBlox GPS +- don't allow RC protocol change on IOMCU once detected +- fixed FBWA pitch limits when in VTOL qassist +- fixed handling of zero compass diagonals +- added an output buffer to MAVCAN +- set emergency status in OpenDroneID on crash or chute deploy +- avoid logging duplicate format messages +- fixed bug in alt error arming check with BARO_FIELD_ELEV set +- fixed handling of double IOMCU reset and safety disable +- enable VTX power on MambaF405 2022 +- disable PWMSource feature in lua scripts (will be back in 4.4.x) +- fixed throttle wait on rudder arming in quadplanes +- fixed earth frame accel compensation for AHRS_TRIM + +Happy flying! + +Release 4.3.3 Jan 19th 2023 +--------------------------- + + - AIRLink LTE module enable pin added + - CUAV Nora/Nora+ bdshot firmware (allows Bi-directional DShot) + - CubeOrange, CubeYellow gets fast reset of ICM20602 + - PixPilot-V6 support + - Attitude and Navigation controllers use real-time dt (better handles variable or slow main loop) + - Analog rangefinder GPIO pin arming check fixed + - Arming check of AHRS/EKF vs GPS location disabled if GPS disabled + - Position Controller limit handling improved to avoid overshooting and hard landings + - PSC_ANGLE_MAX param reduction causing WPNAV_ACCEL to be set too low fixed + - Servo gimbal yaw jump to opposite side fixed + - Siyi A8 gimbal driver's record video feature fixed + - SToRM32 serial gimbal driver actual angle reporting fixed (pitch and yaw angle signs were reversed) + - Takeoff in Auto, Guided fixed when target altitude is current altitude + - Takeoff in Auto handles baro drift before takeoff + - Takeoff twitch due to velocity integrator init bug fixed + - moved FTP MAVLink transfers to FTP thread and better control bandwidth + - switch to QRTL if indide RTL radius when using Q_RTL_MODE=3 (approach) + - check for 3 good frames for CRSF + - allow for ELRS at 420kbaud + - support MambaH743-v2 + - support MambaF405-2022B + - fixed nullptr checks on new + - fixed a bug in terrain handling for ship landing lua script checks on new + +Happy flying! + +Release 4.3.2 Dec 23rd 2022 +--------------------------- + +This is a minor release with bug fixes for the 4.3.x release series. + +Changes from 4.3.1: + + - improved uBlox M10 support + - CubeOrange defaults to using 2nd IMU as primary + - SIRF and SBP GPS disabled on BeastF7v2, MatekF405-STD, MAtekF405-Wing, omnibusf4pro + - fixed loading of autotune gains during pilot testing + - Fixed CAM_MIN_INTERVAL to cope with mission and pilot triggering + - EKF3 fix when using EK3_RNG_USE_HGT/SPD params and rangefinder provides bad readings + - Main loop slowdown after arming fixed (parameter logging was causing delays) + - changed to 'fast task' scheme for critical loop updates + - MAVLink commands received on private channels checked for valid target sysid + - ModalAI camera support fixed (ODOMETRY message frame was consumed incorrectly) + - Param reset after firmware load fixed on several boards + - Siyi A8 gimbal support fixed + - Windows builds move to compiling only 64-bit executables + - ARKV6X support + - MatekH743 supports 8 bi-directional dshot channels + - Pixhawk1 boards support MS5607 baros + - SpeedbyBee F405v3 support + - DroneCAN Airspeed sensor support including hygrometer readings + - Pre-arm warning if multiple UARTs with SERIALx_PROTOCOL = RCIN + - Siyi gimbal support + - Arm check warning loses duplicate "AHRS" prefix + - AtomRCF405NAVI bootloader file name fixed + - BRD_SAFETY_MASK fixed on boards with both FMU safety switch and IOMCU + - Compass calibration continues even if a single compass's cal fails + - Gremsy gimbal driver sends autopilot info at lower rate to save bandwidth + - Invensense 42605 and 42609 IMUs use anti-aliasing filter and notch filter + - OSD stats screen fix + - RC input on serial port uses first UART with SERIALx_PROTOCOL = 23 (was using last) + - RunCam caching fix with enablement and setup on 3-pos switch + - RTK CAN GPS fix when GPSs conneted to separate CAN ports on autopilot + - fixed yaw rate for fixed wing autotune + +Release 4.3.1 24th Oct 2022 +--------------------------- + +This is a minor release with some important fixes: + + - fixed build with gcc 11.3 + - fixed random number generator in lua core + - scale VTOL angle P with airspeed in quadplane back-transiton + - added support for implementing AUX functions in lua scripts + - fixed BMI085 accel scaling + - fixed KSXT NMEA parsing affecting position resolution + - fixed race condition in TECS control leading to 'nod' in forward transiton + - allow for expansion of notch filters to fix notch of fwd motors in quadplanes + - added logging of TECS target alt + - fixed EKF3 altitude discrepancy with GPS or baro alt change on startup + - allow auto mode sequencing to land in a fence breach + +Happy flying! + +Release 4.3.0 9th Oct 2022 +-------------------------- + +The is the first 4.3.x stable release for plane. It is a major release +with a lot of changes since 4.2.3. + +Changes since 4.3.0beta3: + + - added 1M and 2M flash warning checks for for fmuv2, fmuv3 and Pixhawk1-1M firmwares + - added support for multi-byte i2c reads in scripting + +The change list from 4.2.3 stable is very long. Here are the main changes: + + - fixed BRD_SAFETY_MASK for enabling outputs when safety on + - fixed persistence of mapping of CAN airspeed sensors to instances + - fixed precision of NMEA serial output function + - added report of "Engine Running" when using ICE + - fixed handling of defaults.parm files with lines over 100 chars + - fixed handling of defaults.parm files with no newline on last line + - fixed possible divide by zero when changing to GUIDED on quadplanes + - fixes for VideoTX, fixing buffer overrun and tramp handling + - fixed spurious error about sending RPM when RPM disabled + - fixed an EKF3 lane switch issue that can cause incorrect height with dual GPS + - fixed mission cmd to mission int initialisation error + - fixed mission jump tracking init on startup + - fixed OSD view roll/pitch error for tailsitters + - added SkystarsH7HD-bdshot + - fixed SkystarsH7HD VTX control + - reduced memory usage on MatekF405-CAN board + - disable SLCAN when armed to reduce CPU load + - enable CAN battery mon on CUAV V6X by default + - added arming check for Q_M_SPIN_MIN value too high + - fixed reporting of RPM from harmonic notch + - improved handling of airspeed errors and airspeed auto disable + - fixed SERVO_AUTO_TRIM for multiple outputs of same type + - fixed auto baud rate detection on SBF/GSOF/NOVA GPS + - increased max board name length for mavlink statustext to 23 + - fixed incorrect disable of notches for non-throttle notch + - added notch filter slew limit to reduce notch errors + - added ARMING_OPTIONS to control display of pre-arm errors + - several OSD fixes for params, font and resolution + - support PWM type transmission for CAN PWM output + - support Currawong ECU as EFI backend + - support lua scripts for EFI backends + - implement SkyPower and HFE CAN EFI lua scripts + - improved speed of log download with dataflash block backends + - disabled all GPS drivers except uBlox and NMEA on Pixhawk1-1M to save flash + - disabled all GPS drivers except uBlox on MatekF405-bdshot and omnibusf4pro-bdshot + - fixed FFT indexing bug + - added USART2 for AIRLink + - allow reset to default airspeed using mission item DO_CHANGE_SPEED + - added new boards AtomRCF405, KakuteH7Mini-Nand, SkystarsH7HD + - added bi-directional dshot for several new boards + - EK3_GPS_VACC_MAX threshold to control when GPS altitude is used as alt source + - EKF ring buffer fix for slow sensor updates + - EKF3 source set change captured in replay logs + - numerous gimbal support improvements + - improved RemoteId support + - SecureBoot support with remote update of secure boot public keys + - crash_dump.bin file saved to SD Card on startup (includes details re cause of software failures) + - several new pre-arm checks (AHRS type, scripts, terrain) + - numerous scripting improvements + - fixed scripting restart leaking memory + - Benewake H30 radar support + - BMI270 IMU performance improvements + - Logging pause with auxiliary switch + - TeraRanger Neo rangefinder support + - support for both AMSL and ellipsoid height in most GPS drivers + - Custom controller support + - parameter defaults sent with param FTP and onboard logs + - Sim on Hardware allows simulator to run on autopilot + - added Q_LAND_ALTCHG parameter + - added climb before QRTL for safer QRTL from low altitudes + - added support for logging pre and post filtered FFT data + - support triple-notch harmonic notch filter + - support up to 32 actuators (with SERVO_32_ENABLE parameter) + - support EFI input over DroneCAN + - by default only run notch filter on first IMU + - added ESC_TLM_MAV_OFS parameter for mapping ESCs to MAVLink ESC telemetry + - added Q_NAVALT_MIN for quadplane takeoff + - added ICE redline governor + - added in-flight FFT notch tuning option + - added Sagetech ADSB support + - added INS_HNTCH_FM_RAT parameter for handling under-hover throttle + - improvements to filtering on ICM42xxx IMUs + - added option parameters to NAV_VTOL_LAND mission item for fixed wing approach + +Many thanks to the huge number of developers, testers and documenters +who contributed to the 4.3.0 release! + +Special thanks to all the ArduPilot Parters who have worked closely +with us on the 4.3.x development and testing, with many partners +contributing suggestions or supporting particular features. + +Release 4.3.0beta3 7th Oct 2022 +------------------------------- + +This is the third beta of the 4.3.0 stable release. Changes since +beta1 are: + + - fixed BRD_SAFETY_MASK for enabling outputs when safety on + - fixed persistence of mapping of CAN airspeed sensors to instances + - fixed precision of NMEA serial output function + - added report of "Engine Running" when using ICE + - fixed handling of defaults.parm files with lines over 100 chars + - fixed handling of defaults.parm files with no newline on last line + - fixed possible divide by zero when changing to GUIDED on quadplanes + +Happy flying! + +Release 4.3.0beta2 3rd Oct 2022 +------------------------------- + +This is the second beta of the 4.3.0 stable release. Changes since +beta1 are: + + - fixes for VideoTX, fixing buffer overrun and tramp handling + - fixed spurious error about sending RPM when RPM disabled + - fixed an EKF3 lane switch issue that can cause incorrect height with dual GPS + - fixed mission cmd to mission int initialisation error + - fixed mission jump tracking init on startup + - fixed OSD view roll/pitch error for tailsitters + - added SkystarsH7HD-bdshot + - fixed SkystarsH7HD VTX control + - reduced memory usage on MatekF405-CAN board + - disable SLCAN when armed to reduce CPU load + - enable CAN battery mon on CUAV V6X by default + - added arming check for Q_M_SPIN_MIN value too high + - fixed reporting of RPM from harmonic notch + - improved handling of airspeed errors and airspeed auto disable + - fixed SERVO_AUTO_TRIM for multiple outputs of same type + - fixed auto baud rate detection on SBF/GSOF/NOVA GPS + - increased max board name length for mavlink statustext to 23 + - fixed incorrect disable of notches for non-throttle notch + - added notch filter slew limit to reduce notch errors + - added ARMING_OPTIONS to control display of pre-arm errors + - several OSD fixes for params, font and resolution + - support PWM type transmission for CAN PWM output + - support Currawong ECU as EFI backend + - support lua scripts for EFI backends + - implement SkyPower and HFE CAN EFI lua scripts + - improved speed of log download with dataflash block backends + - disabled all GPS drivers except uBlox and NMEA on Pixhawk1-1M to save flash + - disabled all GPS drivers except uBlox on MatekF405-bdshot and omnibusf4pro-bdshot + - fixed FFT indexing bug + - added USART2 for AIRLink + - allow reset to default airspeed using mission item DO_CHANGE_SPEED + +Happy flying! + + +Release 4.3.0beta1 13th Sep 2022 +-------------------------------- + +This is the first beta of the 4.3.0 stable release. There are a lot of +changes since the 4.2.3 stable release. Key changes are: + +- added new boards AtomRCF405, KakuteH7Mini-Nand, SkystarsH7HD +- added bi-directional dshot for several new boards +- EK3_GPS_VACC_MAX threshold to control when GPS altitude is used as alt source +- EKF ring buffer fix for slow sensor updates +- EKF3 source set change captured in replay logs +- numerous gimbal support improvements +- improved RemoteId support +- SecureBoot support with remote update of secure boot public keys +- crash_dump.bin file saved to SD Card on startup (includes details re cause of software failures) +- several new pre-arm checks (AHRS type, scripts, terrain) +- numerous scripting improvements +- fixed scripting restart leaking memory +- Benewake H30 radar support +- BMI270 IMU performance improvements +- Logging pause with auxiliary switch +- TeraRanger Neo rangefinder support +- support for both AMSL and ellipsoid height in most GPS drivers +- Custom controller support +- parameter defaults sent with param FTP and onboard logs +- Sim on Hardware allows simulator to run on autopilot +- added Q_LAND_ALTCHG parameter +- added climb before QRTL for safer QRTL from low altitudes +- added support for logging pre and post filtered FFT data +- support triple-notch harmonic notch filter +- support up to 32 actuators (with SERVO_32_ENABLE parameter) +- support EFI input over DroneCAN +- by default only run notch filter on first IMU +- added ESC_TLM_MAV_OFS parameter for mapping ESCs to MAVLink ESC telemetry +- added Q_NAVALT_MIN for quadplane takeoff +- added ICE redline governor +- added in-flight FFT notch tuning option +- added Sagetech ADSB support +- added INS_HNTCH_FM_RAT parameter for handling under-hover throttle +- improvements to filtering on ICM42xxx IMUs +- added option parameters to NAV_VTOL_LAND mission item for fixed wing approach + +Please report flight tests of the 4.3.0beta series on discuss.ardupilot.org + +Happy flying! + +Release 4.2.3 21st August 2022 +------------------------------ + +This is a minor stable release with a few new features and bug +fixes. The changes from 4.2.0 are: + +- OpenDroneID improvements +- added --enable-opendroneid configure option +- added --enable-check-firmware configure option +- enable OSD menus on KakuteH7 +- added prearm checks for rangefinder pin conflicts +- added diagnostics for scurve internal error +- allow absolute paths for linux boards in param defaults +- fixed AIRBRAKE rc option warning +- fixed notch filtering ordering issue on loss of RPM source +- fixed Lutan EFI update serial flood +- fixed --upload to work on WSL2 +- allow INA2xx battery to init after startup +- fixed healthy check on battery monitors to check all enabled monitors +- added Pixhawk6C and Pixhawk6X support +- fixed alighment of QRTL start in fixed wing circle landing approach +- added Foxeer Reaper F745 support +- added MFE PixSurveyA1 support +- fixed combination of waypoint passby with acceptance distance +- cut throttle on ICE stop when armed +- added ICE option for starting when disarmed +- zero VFWD integrator on ICE override in quadplanes +- don't failsafe when in fixed wing landing sequence with RTL_AUTOLAND +- improved handling of overshoot in VTOL landing +- improved choice of target airspeed in VTOL landing approach +- improved ICM42xxx filter settings +- allow for faster sample rates on ICM42xxx + +Release 4.2.3beta3 19th August 2022 +----------------------------------- + +This is a minor stable release with a few new features and bug +fixes. The changes from beta1 are: + +- OpenDroneID improvements +- added --enable-opendroneid configure option +- added --enable-check-firmware configure option +- reverted notch filter changes from beta3 due to issue on some aircraft +- enable OSD menus on KakuteH7 +- added prearm checks for rangefinder pin conflicts +- added diagnostics for scurve internal error +- allow absolute paths for linux boards in param defaults +- fixed AIRBRAKE rc option warning + + +Release 4.2.3beta2 10th August 2022 +----------------------------------- + +This is a minor stable release with a few new features and bug +fixes. The changes from beta1 are: + +- OpenDroneID support +- fixed notch filtering ordering issue on loss of RPM source +- fixed Lutan EFI update serial flood +- fixed --upload to work on WSL2 + +Release 4.2.3beta1 2nd August 2022 +---------------------------------- + +This is a minor stable release with a few new features and bug +fixes. The changes are: + +- allow INA2xx battery to init after startup +- fixed healthy check on battery monitors to check all enabled monitors +- added Pixhawk6C and Pixhawk6X support +- fixed alighment of QRTL start in fixed wing circle landing approach +- added Foxeer Reaper F745 support +- added MFE PixSurveyA1 support +- fixed combination of waypoint passby with acceptance distance +- cut throttle on ICE stop when armed +- added ICE option for starting when disarmed +- zero VFWD integrator on ICE override in quadplanes +- don't failsafe when in fixed wing landing sequence with RTL_AUTOLAND +- improved handling of overshoot in VTOL landing +- improved choice of target airspeed in VTOL landing approach +- improved ICM42xxx filter settings +- allow for faster sample rates on ICM42xxx + + + +Release 4.2.2 24th June 2022 +---------------------------- + +This is a minor stable release with a few new features and bug +fixes. Just one change since beta1. The changes are: + + - support two full harmonic notches using the INS_HNTC2_ parameters + - adjust neopixel bitwidths for better reliability + - fixed EKF3 replay bugs that caused poor replay fidelity + - added BLHeli_S ESC type in SERVO_DSHOT_ESC + - reduced min lean angle for alt-hold in quadplanes to 5 degrees + - fixed param ftp run length encoding bug + - reduced default quadplane rate accelerations and XY position gains + - improved parameter checks of Q_M_PWM parameters for bad conversions + - added Q_NAVALT_MIN parameter for min alt to start attitude control in takeoff + - added CAN_Dn_UC_POOL parameter to control DroneCAN pool size, to allow memory saving on F4 boards + - saved hardfault crash dumps to microSD if detected + - fixed PWM rangefinder bug and support SCALING parameter + - updated OSD flight modes menu for newer modes + - preserve new rangefinder addresses on VL53L1X + - protect against hardfault on bad CRSF frames + - handle reset of CRSF receiver in flight + - added MambaH743v4 and MambaF405 MK4 + - fixed fault on FFT init with ARMING_REQUIRE=0 + - synced quicktune lua script with latest version + - learn MAVLink routes on private channels + - fixed throttle compensation with FWD_BAT_VOLT_MAX at low voltages + +Happy flying! + +Release 4.2.2beta1 16th June 2022 +--------------------------------- + +This is a minor stable release with a few new features and bug +fixes. The changes are: + + - support two full harmonic notches using the INS_HNTC2_ parameters + - adjust neopixel bitwidths for better reliability + - fixed EKF3 replay bugs that caused poor replay fidelity + - added BLHeli_S ESC type in SERVO_DSHOT_ESC + - reduced min lean angle for alt-hold in quadplanes to 5 degrees + - fixed param ftp run length encoding bug + - reduced default quadplane rate accelerations and XY position gains + - improved parameter checks of Q_M_PWM parameters for bad conversions + - added Q_NAVALT_MIN parameter for min alt to start attitude control in takeoff + - added CAN_Dn_UC_POOL parameter to control DroneCAN pool size, to allow memory saving on F4 boards + - saved hardfault crash dumps to microSD if detected + - fixed PWM rangefinder bug and support SCALING parameter + - updated OSD flight modes menu for newer modes + - preserve new rangefinder addresses on VL53L1X + - protect against hardfault on bad CRSF frames + - handle reset of CRSF receiver in flight + - added MambaH743v4 and MambaF405 MK4 + - fixed fault on FFT init with ARMING_REQUIRE=0 + - synced quicktune lua script with latest version + - learn MAVLink routes on private channels + +Happy flying! + +Release 4.2.1 23rd May 2022 +--------------------------- + +This is a minor release on top of the 4.2 firmware. It has a number of +bug fixes and safety improvements. The changes are: + +- fixed a bug in handling wrap in log download when 500 logs are on the microSD card +- added FlyingMoonF407 and FlyingMoonF427 support +- fixed RSSI input on the RCIN pin on CubeBlack and CubeOrange +- fixed update of gyro FFT throttle tracking +- removed unhealthy reporting on airspeed sensors with negative pressure as this commonly happens on VTOL takeoff +- improved handling of large LOITER_TURNS mission items, expanding maximum to 2.5km +- added fuel usage integration on Lutan EFI +- refuse arming in AUTO when in a landing sequence due to a failsafe +- account for sprung throttle (from RC_OPTIONS) in throttle suppression code +- improved safety of in-flight compass learning +- fixed automatic airspeed ratio calibration for 2nd airspeed sensor +- increase safety of GUIDED -> AUTO takeoff sequence used by QGC +- added CAN_Dx_UC_ESC_OF parameter for ESC offset for bandwidth efficiency +- fixed handling of safety state on boards with no safety switch +- fixed bug where a false positive could trigger landing disarm while land repositioning is active + +The most important fixes are related to how QGC (which is often used +on modern GCS style transmitters) does automatic takeoff with the +"swipe right for takeoff" system. QGC does a sequence of a change to +GUIDED mode, then arming, then change to AUTO mode. That sequence is +dangerous if the current waypoint is not properly reset to a VTOL +takeoff. To fix this a number of changes were made to ensure that +takeoff is done with a valid VTOL takeoff. The changes include +handling of failsafe events (such as GCS or RC failsafe) part way +through this takeoff sequence. If QRTL or RTL is engaged during this +sequence then the vehicle will switch to QLAND. + +Happy flying! + + +Release 4.2.1beta1 19th May 2022 +-------------------------------- + +This is a minor release on top of the 4.2 firmware. It has a number of +bug fixes and safety improvements. The changes are: + +- fixed a bug in handling wrap in log download when 500 logs are on the microSD card +- added FlyingMoonF407 and FlyingMoonF427 support +- fixed RSSI input on the RCIN pin on CubeBlack and CubeOrange +- fixed update of gyro FFT throttle tracking +- removed unhealthy reporting on airspeed sensors with negative pressure as this commonly happens on VTOL takeoff +- improved handling of large LOITER_TURNS mission items, expanding maximum to 2.5km +- added fuel usage integration on Lutan EFI +- refuse arming in AUTO when in a landing sequence due to a failsafe +- account for sprung throttle (from RC_OPTIONS) in throttle suppression code +- improved safety of in-flight compass learning +- fixed automatic airspeed ratio calibration for 2nd airspeed sensor +- increase safety of GUIDED -> AUTO takeoff sequence used by QGC +- added CAN_Dx_UC_ESC_OF parameter for ESC offset for bandwidth efficiency + +The most important fixes are related to how QGC (which is often used +on modern GCS style transmitters) does automatic takeoff with the +"swipe right for takeoff" system. QGC does a sequence of a change to +GUIDED mode, then arming, then change to AUTO mode. That sequence is +dangerous if the current waypoint is not properly reset to a VTOL +takeoff. To fix this a number of changes were made to ensure that +takeoff is done with a valid VTOL takeoff. The changes include +handling of failsafe events (such as GCS or RC failsafe) part way +through this takeoff sequence. If QRTL or RTL is engaged during this +sequence then the vehicle will switch to QLAND. + +Happy flying! + +Release 4.2.0 4th May 2022 +-------------------------- + +This is the first 4.2 stable release of plane. Since 4.2.0beta6 there +have only been 3 changes: + + - added VTOL-quicktune lua script + - fixed custom compass orientation for DroneCAN compasses + - fixed a bug in blended Z accel calculation when not using first IMU + +Since the last stable 4.1.7 release there have been over 4k changes, +so it is not practical to list them all here. Highlights for plane +users include: + + - smoother quadplane transitions + - ship landing support + - CAN over mavlink support + - major tailsitter improvements + - much better error reporting and diagnostics + - numerous lua scripting improvements + - improved weathervaning support and options + - support for fixed wing aerobatics + - many new flight controllers added + - DroneCAN dual-GPS for yaw support + +Happy flying! + + +Release 4.2.0beta6 28th April 2022 +---------------------------------- + +This is the 6th beta of the 4.2.0 major release + + - fix FIFO overruns on the BMI088 IMU + - fix plane avoidance behaviour when in AvoidADSB mode + - disable fatal exceptions on DMA errors on STM32 + - changed quadplane weathervaning to make pitch input optional for nose-in and tail-in + - increased default scripting heap size on F7/H7 to 100k + - added ICM42688 option on MatekH743 + - added ICM4xxxx option on QiotekZealotH743 + - rename INS_NOTCH parameters to INS_HNTC2 + - added Q_OPTION for RTL on failsafe in Q modes, for ship operation + - disabled setting of highest airspeed when disarmed + - fixed init of file descriptor in logging + - cope with gaps in log listing, and reduce impact of log listing on EKF and ESCs + - avoided repeated message on "failed to detach from pin" for RPM + - improved error messages on GPIO pin configuration conflict + - use narrower bitwidths for dshot, giving more accurate timing + - added MatekF765-Wing-bdshot target + - fixed use of DO_SET_SERVO with SERVOn_FUNCTION=0 + - several improvements to SPRacingH7 support + +Happy flying! + +Release 4.2.0beta5 5th April 2022 +--------------------------------- + +This is the 5th beta of the 4.2.0 major release + + - fixed a timer bug that could cause boards using flash storage to watchdog + - added OTG2 USB on QioTekZealotH743 + - increased stack size on log and monitor threads + - fixed rudder control when ARMING_RUDDER != 2 on quadplanes + - fixed accel bias when an IMU is disabled in EKF3 + - improved QSPI support for SPro H7 Extreme + - fixed @SYS file logging + - fixed buzzer on MatekH743, going back to 16 bit timer + - fixed H7 flash storage bug that caused re-init on overflow + - fixed incorrect lock class in UART driver + +Happy flying! + +Release 4.2.0beta4 28th March 2022 +---------------------------------- + +This is the 4th beta of the 4.2.0 major release. + + - added BATT_OPTIONS option to send resting voltage (corrected for internal resistance) to the ground station + - fixed a bug when a blended GPS is lost, where the wrong GPS could be used for a short time + - prevent rapid RTL/AUTO switching with DO_LAND_START and fence breach + - added RTL_AUTOLAND=3 to prevent arming check about DO_LAND_START with no RTL_AUTOLAND + - fixed yaw in AUTO mode on the ground on quadplanes when using rudder to disarm + - fixed failover between IOMCU RC input and a secondary RC input on a uart + - display source of RC input with protocol + - fixed DShot reversal bugs with IOMCU based boards + - fixed battery remaining percentage with sum battery backend + - added KakuteH7-bdshot + - added terrain reference adjustment and TERRAIN_OFS_MAX parameter + - fixed param conversion bug (impacts airspeed enable) + - changed MatekH743 to use a 32 bit timer + +Happy flying! + +Release 4.2.0beta3 18th March 2022 +---------------------------------- + +This is the 3rd beta of the 4.2.0 major release. This beta should be +close to the final 4.2.0 release. + + - fixed pitch envelope constraint after AIRBRAKE + - improvements to POSITION1 quadplane landing controller + - added arming check for Q_ASSIST_SPEED + - added warning if arming with ARMING_CHECK=0 + - added arming check for DO_LAND_START with RTL_AUTOLAND=0 + - improved throttle mix for quadplane autoland + - added fence breach message on GCS + - constrain indexing on declination tables + +Happy flying! + +Release 4.2.0beta2 10th March 2022 +---------------------------------- + +This is the 2nd beta of the 4.2.0 major release. This beta should be +close to the final 4.2.0 release. + + - fixed EKF3 constrain bug + - added quadplane ship landing support + - added Q_LAND_ALTCHG to adjust landing detection sensitivity + - fixed a bug in terrain home compensation + - changed quaplane POSITION1 landing controller to use jerk and accel limiting + - fixed default gain for weathervaning on quadplanes + - fixed health check of airspeed sensor for dual sensors + - fixed arming check on servos for GPIO outputs + - disable stick mixing when RC input is unavailable + - fixed stick mixing during GCS failsafe + - disallow mavlink disarm while flying + - adjust frequency selection for DShot + - fixed logging bug for MCU voltage + - added BeastH7v2 support + - improvement to AC_WPNav for quadplane waypoint control + - simplify RC failsafe messages sent to GCS + +Happy flying! + +Release 4.2.0beta1 2nd March 2022 +--------------------------------- + +This is a major release with a lot of changes. We expect at least 4 +weeks of beta testing and several beta updates before 4.2.0 final is +released. + +Changes include: + + - EKF startup messages reduced + - LORD Microstrain CX5/GX5 external AHRS support + - Auto mode supports up to 100 DO_JUMP commands on high memory boards + - Auto support for NAV_SCRIPT_TIME commands (Lua within Auto) + - aerobatic scripting from any mode via RC switches + - new boards AirLink, BeastF7v2, BeastH7v2, JHEMCU GSF405A, KakuteH7, KakuteH7Mini, MambaF405US-I2C, MatekF405-TE, ModalAI fc-v1, PixC4-Jetson, Pixhawk5X, QioTekZealotH743, RPI-Zero2W, SPRacingH7 Extreme, Swan-K1 + - Parachute option to leave servo in open position (see CHUTE_OPTIONS parameter) + - Parachute released arming check added + - Pre-arm check of IMU heater temp + - Pre-arm check of rangefinder health + - Pre-arm check of throttle position skipped if PILOT_THR_BHV is "Feedback from mid stick" + - ADIS16470, ADIS16507 and BMI270 IMU support + - AK09918 compass support + - Battery monitor supports voltage offset (see BATTx_VLT_OFFSET) + - Benewake TFMiniPlus I2C address defaults correctly + - Buzzer can be connected to any PWM on any board + - Compass calibration (in-flight) uses GSF for better accuracy + - CRSFv3 support, CSRF telemetry link reports link quality in RSSI + - Cybot D1 Lidar support + - DroneCan (aka UAVCAN) battery monitors support scaling (see BATTx_CURR_MULT) + - DroneCan (aka UAVCAN) GPS-for-yaw support + - Electronic Fuel Injection support incl Lutan EFI + - FETtecOneWire resyncs if EMI causes lost bytes + - IMU heater params renamed to BRD_HEAT_xxx + - Landing gear enable parameter added (see LGR_ENABLE) + - Lightware SF40C ver 0.9 support removed (ver 1.0 and higher still supported) + - Maxbotix serial sonar driver support RNGFNDx_SCALING parameter to support for varieties of sensor + - MPPT solar charge controller support + - MTK GPS driver removed + - Optical flow in-flight calibration + - Ping200x ADSB support + - Proximity sensor min and max range (see PRX_MIN, PRX_MAX) + - QSPI external flash support + - uLanding (aka USD1) radar provides average of last few samples + - Unicore NMEA GPS support for yaw and 3D velocity + - Board ID sent in AUTOPILOT_VERSION mavlink message + - DO_SET_CAM_TRIG_DIST supports instantly triggering camera + - DJI FPV OSD multi screen and stats support + - GPIO pins configured by setting SERVOx_FUNCTION to -1 (also see SERVO_GPIO_MASK. BRD_PWM_COUNT removed) + - GPIO pin support on main outputs on boards with IOMCU + - GyroFlow logging (see LOG_BITMASK's "VideoStabilization" option) + - Firmware version logged in VER message + - SD card format via MAVLink + - Serial port option to disable changes to stream rate (see SERIALx_OPTIONS) + - VIBE logging units to m/s/s + - BLHeli passthrough reliability improvements + - Compass learning (inflight) fixed to ignore unused compasses (e.g. those with COMPASS_USE = 0) + - EKF optical flow terrain alt reset fixed (large changes in rangefinder alt might never be fused) + - EKF resets due to bad IMU data occur at most once per second + - GPIO pin fix on CubeOrange, F4BY, mRoControlZeroF7, R9Pilot + - MAVlink2 serial ports always send MAVLink2 messages (previously waited until other side sent MAVLink2) + - Omnibusf4pro bi-directional dshot fix + - Real-Time-Clock (RTC) oldest possible date updated to Jan-2022 + +Happy flying! + + Release 4.1.7 12th February 2022 -------------------------------- diff --git a/ArduPlane/afs_plane.cpp b/ArduPlane/afs_plane.cpp index 893d1208b32..f01297470b4 100644 --- a/ArduPlane/afs_plane.cpp +++ b/ArduPlane/afs_plane.cpp @@ -84,7 +84,7 @@ void AP_AdvancedFailsafe_Plane::setup_IO_failsafe(void) #if HAL_QUADPLANE_ENABLED if (plane.quadplane.available()) { // setup AP_Motors outputs for failsafe - uint16_t mask = plane.quadplane.motors->get_motor_mask(); + uint32_t mask = plane.quadplane.motors->get_motor_mask(); hal.rcout->set_failsafe_pwm(mask, plane.quadplane.motors->get_pwm_output_min()); } #endif diff --git a/ArduPlane/altitude.cpp b/ArduPlane/altitude.cpp index ce717a12b67..ad7c3fafc7d 100644 --- a/ArduPlane/altitude.cpp +++ b/ArduPlane/altitude.cpp @@ -31,6 +31,9 @@ void Plane::adjust_altitude_target() control_mode == &mode_cruise) { return; } + if ((control_mode == &mode_loiter) && plane.stick_mixing_enabled() && (plane.g2.flight_options & FlightOptions::ENABLE_LOITER_ALT_CONTROL)) { + return; + } #if OFFBOARD_GUIDED == ENABLED if (control_mode == &mode_guided && ((guided_state.target_alt_time_ms != 0) || guided_state.target_alt > -0.001 )) { // target_alt now defaults to -1, and _time_ms defaults to zero. // offboard altitude demanded @@ -177,7 +180,7 @@ float Plane::relative_ground_altitude(bool use_rangefinder_if_available) #if HAL_QUADPLANE_ENABLED if (quadplane.in_vtol_land_descent() && - !(quadplane.options & QuadPlane::OPTION_MISSION_LAND_FW_APPROACH)) { + !quadplane.landing_with_fixed_wing_spiral_approach()) { // when doing a VTOL landing we can use the waypoint height as // ground height. We can't do this if using the // LAND_FW_APPROACH as that uses the wp height as the approach @@ -628,8 +631,8 @@ void Plane::rangefinder_terrain_correction(float &height) return; } float terrain_amsl1, terrain_amsl2; - if (!terrain.height_amsl(current_loc, terrain_amsl1, false) || - !terrain.height_amsl(next_WP_loc, terrain_amsl2, false)) { + if (!terrain.height_amsl(current_loc, terrain_amsl1) || + !terrain.height_amsl(next_WP_loc, terrain_amsl2)) { return; } float correction = (terrain_amsl1 - terrain_amsl2); diff --git a/ArduPlane/avoidance_adsb.cpp b/ArduPlane/avoidance_adsb.cpp index b44ff75b962..0bdbaa6fde8 100644 --- a/ArduPlane/avoidance_adsb.cpp +++ b/ArduPlane/avoidance_adsb.cpp @@ -61,31 +61,34 @@ MAV_COLLISION_ACTION AP_Avoidance_Plane::handle_avoidance(const AP_Avoidance::Ob } break; - case MAV_COLLISION_ACTION_ASCEND_OR_DESCEND: + case MAV_COLLISION_ACTION_ASCEND_OR_DESCEND: { // climb or descend to avoid obstacle - if (handle_avoidance_vertical(obstacle, failsafe_state_change)) { - plane.set_guided_WP(); + Location loc = plane.next_WP_loc; + if (handle_avoidance_vertical(obstacle, failsafe_state_change, loc)) { + plane.set_guided_WP(loc); } else { actual_action = MAV_COLLISION_ACTION_NONE; } break; - - case MAV_COLLISION_ACTION_MOVE_HORIZONTALLY: + } + case MAV_COLLISION_ACTION_MOVE_HORIZONTALLY: { // move horizontally to avoid obstacle - if (handle_avoidance_horizontal(obstacle, failsafe_state_change)) { - plane.set_guided_WP(); + Location loc = plane.next_WP_loc; + if (handle_avoidance_horizontal(obstacle, failsafe_state_change, loc)) { + plane.set_guided_WP(loc); } else { actual_action = MAV_COLLISION_ACTION_NONE; } break; - + } case MAV_COLLISION_ACTION_MOVE_PERPENDICULAR: { // move horizontally and vertically to avoid obstacle - const bool success_vert = handle_avoidance_vertical(obstacle, failsafe_state_change); - const bool success_hor = handle_avoidance_horizontal(obstacle, failsafe_state_change); + Location loc = plane.next_WP_loc; + const bool success_vert = handle_avoidance_vertical(obstacle, failsafe_state_change, loc); + const bool success_hor = handle_avoidance_horizontal(obstacle, failsafe_state_change, loc); if (success_vert || success_hor) { - plane.set_guided_WP(); + plane.set_guided_WP(loc); } else { actual_action = MAV_COLLISION_ACTION_NONE; } @@ -134,11 +137,18 @@ void AP_Avoidance_Plane::handle_recovery(RecoveryAction recovery_action) case RecoveryAction::RESUME_IF_AUTO_ELSE_LOITER: if (prev_control_mode_number == Mode::Number::AUTO) { plane.set_mode(plane.mode_auto, ModeReason::AVOIDANCE_RECOVERY); + } else { + // let ModeAvoidADSB continue in its guided + // behaviour, but reset the loiter location, + // rather than where the avoidance location was + plane.set_guided_WP(plane.current_loc); } - // else do nothing, same as RecoveryAction::LOITER break; default: + // user has specified an invalid recovery action; + // loiter where we are + plane.set_guided_WP(plane.current_loc); break; } // switch } @@ -157,7 +167,7 @@ bool AP_Avoidance_Plane::check_flightmode(bool allow_mode_change) return (plane.control_mode == &plane.mode_avoidADSB); } -bool AP_Avoidance_Plane::handle_avoidance_vertical(const AP_Avoidance::Obstacle *obstacle, bool allow_mode_change) +bool AP_Avoidance_Plane::handle_avoidance_vertical(const AP_Avoidance::Obstacle *obstacle, bool allow_mode_change, Location &new_loc) { // ensure copter is in avoid_adsb mode if (!check_flightmode(allow_mode_change)) { @@ -167,20 +177,20 @@ bool AP_Avoidance_Plane::handle_avoidance_vertical(const AP_Avoidance::Obstacle // get best vector away from obstacle if (plane.current_loc.alt > obstacle->_location.alt) { // should climb - plane.guided_WP_loc.alt = plane.current_loc.alt + 1000; // set alt demand to be 10m above us, climb rate will be TECS_CLMB_MAX + new_loc.alt = plane.current_loc.alt + 1000; // set alt demand to be 10m above us, climb rate will be TECS_CLMB_MAX return true; } else if (plane.current_loc.alt > plane.g.RTL_altitude_cm) { // should descend while above RTL alt // TODO: consider using a lower altitude than RTL_altitude_cm since it's default (100m) is quite high - plane.guided_WP_loc.alt = plane.current_loc.alt - 1000; // set alt demand to be 10m below us, sink rate will be TECS_SINK_MAX + new_loc.alt = plane.current_loc.alt - 1000; // set alt demand to be 10m below us, sink rate will be TECS_SINK_MAX return true; } return false; } -bool AP_Avoidance_Plane::handle_avoidance_horizontal(const AP_Avoidance::Obstacle *obstacle, bool allow_mode_change) +bool AP_Avoidance_Plane::handle_avoidance_horizontal(const AP_Avoidance::Obstacle *obstacle, bool allow_mode_change, Location &new_loc) { // ensure plane is in avoid_adsb mode if (!check_flightmode(allow_mode_change)) { @@ -205,7 +215,7 @@ bool AP_Avoidance_Plane::handle_avoidance_horizontal(const AP_Avoidance::Obstacl velocity_neu *= 10000; // set target - plane.guided_WP_loc.offset(velocity_neu.x, velocity_neu.y); + new_loc.offset(velocity_neu.x, velocity_neu.y); return true; } diff --git a/ArduPlane/avoidance_adsb.h b/ArduPlane/avoidance_adsb.h index 23cf57ba196..508fe658770 100644 --- a/ArduPlane/avoidance_adsb.h +++ b/ArduPlane/avoidance_adsb.h @@ -26,10 +26,10 @@ class AP_Avoidance_Plane : public AP_Avoidance { bool check_flightmode(bool allow_mode_change); // vertical avoidance handler - bool handle_avoidance_vertical(const AP_Avoidance::Obstacle *obstacle, bool allow_mode_change); + bool handle_avoidance_vertical(const AP_Avoidance::Obstacle *obstacle, bool allow_mode_change, Location &new_loc); // horizontal avoidance handler - bool handle_avoidance_horizontal(const AP_Avoidance::Obstacle *obstacle, bool allow_mode_change); + bool handle_avoidance_horizontal(const AP_Avoidance::Obstacle *obstacle, bool allow_mode_change, Location &new_loc); // control mode before avoidance began enum Mode::Number prev_control_mode_number = Mode::Number::RTL; diff --git a/ArduPlane/commands.cpp b/ArduPlane/commands.cpp index c5bcee335bd..027708e443e 100644 --- a/ArduPlane/commands.cpp +++ b/ArduPlane/commands.cpp @@ -61,9 +61,9 @@ void Plane::set_next_WP(const struct Location &loc) setup_turn_angle(); } -void Plane::set_guided_WP(void) +void Plane::set_guided_WP(const Location &loc) { - if (aparm.loiter_radius < 0 || guided_WP_loc.loiter_ccw) { + if (aparm.loiter_radius < 0 || loc.loiter_ccw) { loiter.direction = -1; } else { loiter.direction = 1; @@ -75,7 +75,7 @@ void Plane::set_guided_WP(void) // Load the next_WP slot // --------------------- - next_WP_loc = guided_WP_loc; + next_WP_loc = loc; // used to control FBW and limit the rate of climb // ----------------------------------------------- @@ -105,11 +105,13 @@ void Plane::set_guided_WP(void) update home location from GPS this is called as long as we have 3D lock and the arming switch is not pushed + + returns true if home is changed */ -void Plane::update_home() +bool Plane::update_home() { if (hal.util->was_watchdog_armed()) { - return; + return false; } if ((g2.home_reset_threshold == -1) || ((g2.home_reset_threshold > 0) && @@ -118,24 +120,30 @@ void Plane::update_home() // significantly. This allows us to cope with slow baro drift // but not re-do home and the baro if we have changed height // significantly - return; + return false; } - if (ahrs.home_is_set() && !ahrs.home_is_locked()) { + bool ret = false; + if (ahrs.home_is_set() && !ahrs.home_is_locked() && gps.status() >= AP_GPS::GPS_OK_FIX_3D) { Location loc; - if(ahrs.get_location(loc) && gps.status() >= AP_GPS::GPS_OK_FIX_3D) { + if (ahrs.get_location(loc)) { // we take the altitude directly from the GPS as we are // about to reset the baro calibration. We can't use AHRS // altitude or we can end up perpetuating a bias in // altitude, as AHRS alt depends on home alt, which means // we would have a circular dependency loc.alt = gps.location().alt; - if (!AP::ahrs().set_home(loc)) { - // silently fail - } + ret = AP::ahrs().set_home(loc); } } + + // even if home is not updated we do a baro reset to stop baro + // drift errors while disarmed barometer.update_calibration(); ahrs.resetHeightDatum(); + + update_current_loc(); + + return ret; } bool Plane::set_home_persistently(const Location &loc) diff --git a/ArduPlane/commands_logic.cpp b/ArduPlane/commands_logic.cpp index b5c621fae9e..6d2763d4942 100644 --- a/ArduPlane/commands_logic.cpp +++ b/ArduPlane/commands_logic.cpp @@ -98,7 +98,7 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd) return quadplane.do_vtol_takeoff(cmd); case MAV_CMD_NAV_VTOL_LAND: - if (quadplane.options & QuadPlane::OPTION_MISSION_LAND_FW_APPROACH) { + if (quadplane.landing_with_fixed_wing_spiral_approach()) { // the user wants to approach the landing in a fixed wing flight mode // the waypoint will be used as a loiter_to_alt // after which point the plane will compute the optimal into the wind direction @@ -142,7 +142,7 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd) break; case MAV_CMD_DO_FENCE_ENABLE: -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED if (cmd.p1 == 0) { // disable fence plane.fence.enable(false); gcs().send_text(MAV_SEVERITY_INFO, "Fence disabled"); @@ -180,9 +180,7 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd) case MAV_CMD_DO_MOUNT_CONTROL: // 205 // point the camera to a specified angle - camera_mount.set_angle_targets(cmd.content.mount_control.roll, - cmd.content.mount_control.pitch, - cmd.content.mount_control.yaw); + camera_mount.set_angle_target(cmd.content.mount_control.roll, cmd.content.mount_control.pitch, cmd.content.mount_control.yaw, false); break; #endif @@ -192,17 +190,23 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd) break; #endif +#if AP_ICENGINE_ENABLED case MAV_CMD_DO_ENGINE_CONTROL: plane.g2.ice_control.engine_control(cmd.content.do_engine_control.start_control, cmd.content.do_engine_control.cold_start, cmd.content.do_engine_control.height_delay_cm*0.01f); break; +#endif #if AP_SCRIPTING_ENABLED case MAV_CMD_NAV_SCRIPT_TIME: do_nav_script_time(cmd); break; #endif + + case MAV_CMD_NAV_DELAY: + do_nav_delay(cmd); + break; default: // unable to use the command, allow the vehicle to try the next command @@ -282,7 +286,7 @@ bool Plane::verify_command(const AP_Mission::Mission_Command& cmd) // Ret case MAV_CMD_NAV_VTOL_TAKEOFF: return quadplane.verify_vtol_takeoff(cmd); case MAV_CMD_NAV_VTOL_LAND: - if ((quadplane.options & QuadPlane::OPTION_MISSION_LAND_FW_APPROACH) && !verify_landing_vtol_approach(cmd)) { + if (quadplane.landing_with_fixed_wing_spiral_approach() && !verify_landing_vtol_approach(cmd)) { // verify_landing_vtol_approach will return true once we have completed the approach, // in which case we fall over to normal vtol landing code return false; @@ -303,7 +307,10 @@ bool Plane::verify_command(const AP_Mission::Mission_Command& cmd) // Ret case MAV_CMD_NAV_SCRIPT_TIME: return verify_nav_script_time(cmd); #endif - + + case MAV_CMD_NAV_DELAY: + return verify_nav_delay(cmd); + // do commands (always return true) case MAV_CMD_DO_CHANGE_SPEED: case MAV_CMD_DO_SET_HOME: @@ -411,7 +418,7 @@ void Plane::do_land(const AP_Mission::Mission_Command& cmd) set_flight_stage(AP_Vehicle::FixedWing::FLIGHT_LAND); } -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED plane.fence.auto_disable_fence_for_landing(); #endif } @@ -424,15 +431,6 @@ void Plane::do_landing_vtol_approach(const AP_Mission::Mission_Command& cmd) loc.sanitize(current_loc); set_next_WP(loc); - // only set the direction if the quadplane landing radius override is not 0 - // if it's 0 update_loiter will manage the direction for us when we hand it - // 0 later in the controller - if (is_negative(quadplane.fw_land_approach_radius)) { - loiter.direction = -1; - } else if (is_positive(quadplane.fw_land_approach_radius)) { - loiter.direction = 1; - } - vtol_approach_s.approach_stage = LOITER_TO_ALT; } #endif @@ -522,6 +520,21 @@ void Plane::do_loiter_to_alt(const AP_Mission::Mission_Command& cmd) condition_value = 0; } +// do_nav_delay - Delay the next navigation command +void Plane::do_nav_delay(const AP_Mission::Mission_Command& cmd) +{ + nav_delay.time_start_ms = millis(); + + if (cmd.content.nav_delay.seconds > 0) { + // relative delay + nav_delay.time_max_ms = cmd.content.nav_delay.seconds * 1000; // convert seconds to milliseconds + } else { + // absolute delay to utc time + nav_delay.time_max_ms = AP::rtc().get_time_utc(cmd.content.nav_delay.hour_utc, cmd.content.nav_delay.min_utc, cmd.content.nav_delay.sec_utc, 0); + } + gcs().send_text(MAV_SEVERITY_INFO, "Delaying %u sec", (unsigned)(nav_delay.time_max_ms/1000)); +} + /********************************************************************************/ // Verify Nav (Must) commands /********************************************************************************/ @@ -588,7 +601,7 @@ bool Plane::verify_takeoff() auto_state.takeoff_complete = true; next_WP_loc = prev_WP_loc = current_loc; -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED plane.fence.auto_enable_fence_after_takeoff(); #endif @@ -617,13 +630,11 @@ bool Plane::verify_nav_wp(const AP_Mission::Mission_Command& cmd) uint8_t cmd_acceptance_distance = LOWBYTE(cmd.p1); // radius in meters to accept reaching the wp if (cmd_passby > 0) { - float dist = prev_WP_loc.get_distance(flex_next_WP_loc); - - if (!is_zero(dist)) { - float factor = (dist + cmd_passby) / dist; + const float dist = prev_WP_loc.get_distance(flex_next_WP_loc); + const float bearing_deg = degrees(prev_WP_loc.get_bearing(flex_next_WP_loc)); - flex_next_WP_loc.lat = flex_next_WP_loc.lat + (flex_next_WP_loc.lat - prev_WP_loc.lat) * (factor - 1.0f); - flex_next_WP_loc.lng = flex_next_WP_loc.lng + Location::diff_longitude(flex_next_WP_loc.lng,prev_WP_loc.lng) * (factor - 1.0f); + if (is_positive(dist)) { + flex_next_WP_loc.offset_bearing(bearing_deg, cmd_passby); } } @@ -653,8 +664,8 @@ bool Plane::verify_nav_wp(const AP_Mission::Mission_Command& cmd) } else if (cmd_passby == 0) { acceptance_distance_m = nav_controller->turn_distance(get_wp_radius(), auto_state.next_turn_angle); } - - if (auto_state.wp_distance <= acceptance_distance_m) { + const float wp_dist = current_loc.get_distance(flex_next_WP_loc); + if (wp_dist <= acceptance_distance_m) { gcs().send_text(MAV_SEVERITY_INFO, "Reached waypoint #%i dist %um", (unsigned)mission.get_current_nav_cmd().index, (unsigned)current_loc.get_distance(flex_next_WP_loc)); @@ -713,6 +724,10 @@ bool Plane::verify_loiter_turns(const AP_Mission::Mission_Command &cmd) { bool result = false; uint16_t radius = HIGHBYTE(cmd.p1); + if (cmd.type_specific_bits & (1U<<0)) { + // special storage handling allows for larger radii + radius *= 10; + } update_loiter(radius); // LOITER_TURNS makes no sense as VTOL @@ -852,6 +867,20 @@ bool Plane::verify_altitude_wait(const AP_Mission::Mission_Command &cmd) return false; } +// verify_nav_delay - check if we have waited long enough +bool Plane::verify_nav_delay(const AP_Mission::Mission_Command& cmd) +{ + if (hal.util->get_soft_armed()) { + // don't delay while armed, we need a nav controller running + return true; + } + if (millis() - nav_delay.time_start_ms > nav_delay.time_max_ms) { + nav_delay.time_max_ms = 0; + return true; + } + return false; +} + /********************************************************************************/ // Condition (May) commands /********************************************************************************/ @@ -908,8 +937,12 @@ bool Plane::do_change_speed(const AP_Mission::Mission_Command& cmd) switch (cmd.content.speed.speed_type) { case 0: // Airspeed - if ((cmd.content.speed.target_ms >= aparm.airspeed_min.get()) && (cmd.content.speed.target_ms <= aparm.airspeed_max.get())) { - new_airspeed_cm = cmd.content.speed.target_ms * 100; //new airspeed target for AUTO or GUIDED modes + if (is_equal(cmd.content.speed.target_ms, -2.0f)) { + new_airspeed_cm = -1; // return to default airspeed + return true; + } else if ((cmd.content.speed.target_ms >= aparm.airspeed_min.get()) && + (cmd.content.speed.target_ms <= aparm.airspeed_max.get())) { + new_airspeed_cm = cmd.content.speed.target_ms * 100; //new airspeed target for AUTO or GUIDED modes gcs().send_text(MAV_SEVERITY_INFO, "Set airspeed %u m/s", (unsigned)cmd.content.speed.target_ms); return true; } @@ -982,11 +1015,17 @@ void Plane::exit_mission_callback() #if HAL_QUADPLANE_ENABLED bool Plane::verify_landing_vtol_approach(const AP_Mission::Mission_Command &cmd) { + const float radius = is_zero(quadplane.fw_land_approach_radius)? aparm.loiter_radius : quadplane.fw_land_approach_radius; + const int8_t direction = is_negative(radius) ? -1 : 1; + const float abs_radius = fabsf(radius); + + loiter.direction = direction; + switch (vtol_approach_s.approach_stage) { case RTL: { // fly home and loiter at RTL alt - update_loiter(fabsf(quadplane.fw_land_approach_radius)); + nav_controller->update_loiter(cmd.content.location, abs_radius, direction); if (plane.reached_loiter_target()) { // decend to Q RTL alt plane.do_RTL(plane.home.alt + plane.quadplane.qrtl_alt*100UL); @@ -997,7 +1036,7 @@ bool Plane::verify_landing_vtol_approach(const AP_Mission::Mission_Command &cmd) } case LOITER_TO_ALT: { - update_loiter(fabsf(quadplane.fw_land_approach_radius)); + nav_controller->update_loiter(cmd.content.location, abs_radius, direction); if (labs(loiter.sum_cd) > 1 && (loiter.reached_target_alt || loiter.unable_to_acheive_target_alt)) { Vector3f wind = ahrs.wind_estimate(); @@ -1009,21 +1048,12 @@ bool Plane::verify_landing_vtol_approach(const AP_Mission::Mission_Command &cmd) } case ENSURE_RADIUS: { - float radius; - if (is_zero(quadplane.fw_land_approach_radius)) { - radius = aparm.loiter_radius; - } else { - radius = quadplane.fw_land_approach_radius; - } - const int8_t direction = is_negative(radius) ? -1 : 1; - radius = fabsf(radius); - // validate that the vehicle is at least the expected distance away from the loiter point // require an angle total of at least 2 centidegrees, due to special casing of 1 centidegree - if (((fabsf(cmd.content.location.get_distance(current_loc) - radius) > 5.0f) && - (cmd.content.location.get_distance(current_loc) < radius)) || - (loiter.sum_cd < 2)) { - nav_controller->update_loiter(cmd.content.location, radius, direction); + if (((fabsf(cmd.content.location.get_distance(current_loc) - abs_radius) > 5.0f) && + (cmd.content.location.get_distance(current_loc) < abs_radius)) || + (labs(loiter.sum_cd) < 2)) { + nav_controller->update_loiter(cmd.content.location, abs_radius, direction); break; } vtol_approach_s.approach_stage = WAIT_FOR_BREAKOUT; @@ -1031,18 +1061,12 @@ bool Plane::verify_landing_vtol_approach(const AP_Mission::Mission_Command &cmd) } case WAIT_FOR_BREAKOUT: { - float radius = quadplane.fw_land_approach_radius; - if (is_zero(radius)) { - radius = aparm.loiter_radius; - } - const int8_t direction = is_negative(radius) ? -1 : 1; - nav_controller->update_loiter(cmd.content.location, radius, direction); - const float breakout_direction_rad = radians(wrap_180(vtol_approach_s.approach_direction_deg + (direction > 0 ? 270 : 90))); + const float breakout_direction_rad = radians(vtol_approach_s.approach_direction_deg + (direction > 0 ? 270 : 90)); // breakout when within 5 degrees of the opposite direction - if (fabsf(ahrs.yaw - breakout_direction_rad) < radians(5.0f)) { + if (fabsf(wrap_PI(ahrs.yaw - breakout_direction_rad)) < radians(5.0f)) { gcs().send_text(MAV_SEVERITY_INFO, "Starting VTOL land approach path"); vtol_approach_s.approach_stage = APPROACH_LINE; set_next_WP(cmd.content.location); @@ -1065,9 +1089,22 @@ bool Plane::verify_landing_vtol_approach(const AP_Mission::Mission_Command &cmd) nav_controller->update_waypoint(start, end); // check if we should move on to the next waypoint + Location breakout_stopping_loc = cmd.content.location; + breakout_stopping_loc.offset_bearing(vtol_approach_s.approach_direction_deg + 180, quadplane.stopping_distance()); + const bool past_finish_line = current_loc.past_interval_finish_line(start, breakout_stopping_loc); + Location breakout_loc = cmd.content.location; - breakout_loc.offset_bearing(vtol_approach_s.approach_direction_deg + 180, quadplane.stopping_distance()); - if(current_loc.past_interval_finish_line(start, breakout_loc)) { + breakout_loc.offset_bearing(vtol_approach_s.approach_direction_deg + 180, abs_radius); + const bool half_radius = current_loc.line_path_proportion(breakout_loc, cmd.content.location) > 0.5; + bool lined_up = true; + Vector3f vel_NED; + if (ahrs.get_velocity_NED(vel_NED)) { + const Vector2f target_vec = current_loc.get_distance_NE(cmd.content.location); + const float angle_err = fabsf(wrap_180(degrees(vel_NED.xy().angle(target_vec)))); + lined_up = (angle_err < 30); + } + + if (past_finish_line && (lined_up || half_radius)) { vtol_approach_s.approach_stage = VTOL_LANDING; quadplane.do_vtol_land(cmd); // fallthrough diff --git a/ArduPlane/config.h b/ArduPlane/config.h index f27263f074e..e0c1283a1f3 100644 --- a/ArduPlane/config.h +++ b/ArduPlane/config.h @@ -233,11 +233,6 @@ # define SCALING_SPEED 15.0 #endif -// use this to disable geo-fencing -#ifndef AC_FENCE - # define AC_FENCE ENABLED -#endif - // a digital pin to set high when the geo-fence triggers. Defaults // to -1, which means don't activate a pin #ifndef FENCE_TRIGGERED_PIN diff --git a/ArduPlane/control_modes.cpp b/ArduPlane/control_modes.cpp index d97ce4212a5..62689c78a28 100644 --- a/ArduPlane/control_modes.cpp +++ b/ArduPlane/control_modes.cpp @@ -107,9 +107,8 @@ void Plane::read_control_switch() // If we get this value we do not want to change modes. if(switchPosition == 255) return; - if (failsafe.rc_failsafe || failsafe.throttle_counter > 0) { - // when we are in rc_failsafe mode then RC input is not - // working, and we need to ignore the mode switch channel + if (!rc().has_valid_input()) { + // ignore the mode switch channel if there is no valid RC input return; } diff --git a/ArduPlane/defines.h b/ArduPlane/defines.h index 3bcfd2e8c74..fdb9c656923 100644 --- a/ArduPlane/defines.h +++ b/ArduPlane/defines.h @@ -6,6 +6,8 @@ #define SERVO_MAX 4500.0 // This value represents 45 degrees and is just an // arbitrary representation of servo max travel. +#define MIN_AIRSPEED_MIN 5 // m/s, used for arming check and speed scaling + // failsafe // ---------------------- enum failsafe_state { @@ -50,6 +52,15 @@ enum class StickMixing { VTOL_YAW = 3, }; +// values for RTL_AUTOLAND +enum class RtlAutoland { + RTL_DISABLE = 0, + RTL_THEN_DO_LAND_START = 1, + RTL_IMMEDIATE_DO_LAND_START = 2, + NO_RTL_GO_AROUND = 3, +}; + + enum ChannelMixing { MIXING_DISABLED = 0, MIXING_UPUP = 1, @@ -153,6 +164,8 @@ enum FlightOptions { OSD_REMOVE_TRIM_PITCH_CD = (1 << 9), CENTER_THROTTLE_TRIM = (1<<10), DISABLE_GROUND_PID_SUPPRESSION = (1<<11), + ENABLE_LOITER_ALT_CONTROL = (1<<12), + }; enum CrowFlapOptions { diff --git a/ArduPlane/events.cpp b/ArduPlane/events.cpp index e0a420a4857..479b0670d3b 100644 --- a/ArduPlane/events.cpp +++ b/ArduPlane/events.cpp @@ -12,6 +12,9 @@ bool Plane::failsafe_in_landing_sequence() const return true; } #endif + if (mission.get_in_landing_sequence_flag()) { + return true; + } return false; } @@ -21,7 +24,7 @@ void Plane::failsafe_short_on_event(enum failsafe_state fstype, ModeReason reaso failsafe.state = fstype; failsafe.short_timer_ms = millis(); failsafe.saved_mode_number = control_mode->mode_number(); - gcs().send_text(MAV_SEVERITY_WARNING, "Failsafe. Short event on: type=%u/reason=%u", fstype, static_cast(reason)); + gcs().send_text(MAV_SEVERITY_WARNING, "RC Short Failsafe On"); switch (control_mode->mode_number()) { case Mode::Number::MANUAL: @@ -54,7 +57,9 @@ void Plane::failsafe_short_on_event(enum failsafe_state fstype, ModeReason reaso case Mode::Number::QAUTOTUNE: #endif case Mode::Number::QACRO: - if (quadplane.options & QuadPlane::OPTION_FS_QRTL) { + if (quadplane.option_is_set(QuadPlane::OPTION::FS_RTL)) { + set_mode(mode_rtl, reason); + } else if (quadplane.option_is_set(QuadPlane::OPTION::FS_QRTL)) { set_mode(mode_qrtl, reason); } else { set_mode(mode_qland, reason); @@ -102,7 +107,12 @@ void Plane::failsafe_short_on_event(enum failsafe_state fstype, ModeReason reaso void Plane::failsafe_long_on_event(enum failsafe_state fstype, ModeReason reason) { // This is how to handle a long loss of control signal failsafe. - gcs().send_text(MAV_SEVERITY_WARNING, "Failsafe. Long event on: type=%u/reason=%u", fstype, static_cast(reason)); + if (reason == ModeReason:: GCS_FAILSAFE) { + gcs().send_text(MAV_SEVERITY_WARNING, "GCS Failsafe On"); + } + else { + gcs().send_text(MAV_SEVERITY_WARNING, "RC Long Failsafe On"); + } // If the GCS is locked up we allow control to revert to RC RC_Channels::clear_overrides(); failsafe.state = fstype; @@ -142,7 +152,9 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype, ModeReason reason #if QAUTOTUNE_ENABLED case Mode::Number::QAUTOTUNE: #endif - if (quadplane.options & QuadPlane::OPTION_FS_QRTL) { + if (quadplane.option_is_set(QuadPlane::OPTION::FS_RTL)) { + set_mode(mode_rtl, reason); + } else if (quadplane.option_is_set(QuadPlane::OPTION::FS_QRTL)) { set_mode(mode_qrtl, reason); } else { set_mode(mode_qland, reason); @@ -186,19 +198,24 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype, ModeReason reason void Plane::failsafe_short_off_event(ModeReason reason) { // We're back in radio contact - gcs().send_text(MAV_SEVERITY_WARNING, "Failsafe. Short event off: reason=%u", static_cast(reason)); + gcs().send_text(MAV_SEVERITY_WARNING, "Short Failsafe Cleared"); failsafe.state = FAILSAFE_NONE; - //restore entry mode if desired but check that our current mode is still due to failsafe - if ( _last_reason == ModeReason::RADIO_FAILSAFE) { + // restore entry mode if desired but check that our current mode is still due to failsafe + if (control_mode_reason == ModeReason::RADIO_FAILSAFE) { set_mode_by_number(failsafe.saved_mode_number, ModeReason::RADIO_FAILSAFE_RECOVERY); gcs().send_text(MAV_SEVERITY_INFO,"Flight mode %s restored",control_mode->name()); - } + } } void Plane::failsafe_long_off_event(ModeReason reason) { - // We're back in radio contact - gcs().send_text(MAV_SEVERITY_WARNING, "Failsafe. Long event off: reason=%u", static_cast(reason)); + // We're back in radio contact with RC or GCS + if (reason == ModeReason:: GCS_FAILSAFE) { + gcs().send_text(MAV_SEVERITY_WARNING, "GCS Failsafe Off"); + } + else { + gcs().send_text(MAV_SEVERITY_WARNING, "RC Long Failsafe Cleared"); + } failsafe.state = FAILSAFE_NONE; } @@ -251,7 +268,7 @@ void Plane::handle_battery_failsafe(const char *type_str, const int8_t action) #endif if (!already_landing) { // never stop a landing if we were already committed - if (g.rtl_autoland == 2 && plane.mission.is_best_land_sequence()) { + if (g.rtl_autoland == RtlAutoland::RTL_IMMEDIATE_DO_LAND_START && plane.mission.is_best_land_sequence()) { // continue mission as it will reach a landing in less distance plane.mission.set_in_landing_sequence_flag(true); break; diff --git a/ArduPlane/fence.cpp b/ArduPlane/fence.cpp index df2b69c09c4..28f4abdca67 100644 --- a/ArduPlane/fence.cpp +++ b/ArduPlane/fence.cpp @@ -2,7 +2,7 @@ // Code to integrate AC_Fence library with main ArduPlane code -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // fence_check - ask fence library to check for breaches and initiate the response void Plane::fence_check() @@ -43,15 +43,15 @@ void Plane::fence_check() return; } - if (orig_breaches && - (control_mode->is_guided_mode() - || control_mode == &mode_rtl || fence.get_action() == AC_FENCE_ACTION_REPORT_ONLY)) { + if (in_fence_recovery()) { // we have already triggered, don't trigger again until the // user disables/re-enables using the fence channel switch return; } - if (new_breaches || orig_breaches) { + if (new_breaches) { + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Fence Breached"); + // if the user wants some kind of response and motors are armed const uint8_t fence_act = fence.get_action(); switch (fence_act) { @@ -61,44 +61,51 @@ void Plane::fence_check() case AC_FENCE_ACTION_GUIDED_THROTTLE_PASS: case AC_FENCE_ACTION_RTL_AND_LAND: if (fence_act == AC_FENCE_ACTION_RTL_AND_LAND) { + if (control_mode == &mode_auto && + mission.get_in_landing_sequence_flag() && + (g.rtl_autoland == RtlAutoland::RTL_THEN_DO_LAND_START || + g.rtl_autoland == RtlAutoland::RTL_IMMEDIATE_DO_LAND_START)) { + // already landing + return; + } set_mode(mode_rtl, ModeReason::FENCE_BREACHED); } else { set_mode(mode_guided, ModeReason::FENCE_BREACHED); } + Location loc; if (fence.get_return_rally() != 0 || fence_act == AC_FENCE_ACTION_RTL_AND_LAND) { - guided_WP_loc = rally.calc_best_rally_or_home_location(current_loc, get_RTL_altitude_cm()); + loc = rally.calc_best_rally_or_home_location(current_loc, get_RTL_altitude_cm()); } else { //return to fence return point, not a rally point - guided_WP_loc = {}; if (fence.get_return_altitude() > 0) { // fly to the return point using _retalt - guided_WP_loc.alt = home.alt + 100.0f * fence.get_return_altitude(); + loc.alt = home.alt + 100.0f * fence.get_return_altitude(); } else if (fence.get_safe_alt_min() >= fence.get_safe_alt_max()) { // invalid min/max, use RTL_altitude - guided_WP_loc.alt = home.alt + g.RTL_altitude_cm; + loc.alt = home.alt + g.RTL_altitude_cm; } else { // fly to the return point, with an altitude half way between // min and max - guided_WP_loc.alt = home.alt + 100.0f * (fence.get_safe_alt_min() + fence.get_safe_alt_max()) / 2; + loc.alt = home.alt + 100.0f * (fence.get_safe_alt_min() + fence.get_safe_alt_max()) / 2; } Vector2l return_point; if(fence.polyfence().get_return_point(return_point)) { - guided_WP_loc.lat = return_point[0]; - guided_WP_loc.lng = return_point[1]; + loc.lat = return_point[0]; + loc.lng = return_point[1]; } else { // When no fence return point is found (ie. no inclusion fence uploaded, but exclusion is) // we fail to obtain a valid fence return point. In this case, home is considered a safe // return point. - guided_WP_loc.lat = home.lat; - guided_WP_loc.lng = home.lng; + loc.lat = home.lat; + loc.lng = home.lng; } } if (fence.get_action() != AC_FENCE_ACTION_RTL_AND_LAND) { - setup_terrain_target_alt(guided_WP_loc); - set_guided_WP(); + setup_terrain_target_alt(loc); + set_guided_WP(loc); } if (fence.get_action() == AC_FENCE_ACTION_GUIDED_THROTTLE_PASS) { @@ -118,7 +125,7 @@ bool Plane::fence_stickmixing(void) const { if (fence.enabled() && fence.get_breaches() && - control_mode->is_guided_mode()) + in_fence_recovery()) { // don't mix in user input return false; @@ -127,4 +134,16 @@ bool Plane::fence_stickmixing(void) const return true; } +bool Plane::in_fence_recovery() const +{ + const bool current_mode_breach = plane.control_mode_reason == ModeReason::FENCE_BREACHED; + const bool previous_mode_breach = plane.previous_mode_reason == ModeReason::FENCE_BREACHED; + const bool previous_mode_complete = (plane.control_mode_reason == ModeReason::RTL_COMPLETE_SWITCHING_TO_VTOL_LAND_RTL) || + (plane.control_mode_reason == ModeReason::RTL_COMPLETE_SWITCHING_TO_FIXEDWING_AUTOLAND) || + (plane.control_mode_reason == ModeReason::QRTL_INSTEAD_OF_RTL) || + (plane.control_mode_reason == ModeReason::QLAND_INSTEAD_OF_RTL); + + return current_mode_breach || (previous_mode_breach && previous_mode_complete); +} + #endif diff --git a/ArduPlane/is_flying.cpp b/ArduPlane/is_flying.cpp index 38fa07c6a43..81733a15879 100644 --- a/ArduPlane/is_flying.cpp +++ b/ArduPlane/is_flying.cpp @@ -291,8 +291,14 @@ void Plane::crash_detection_update(void) // if we have no GPS lock and we don't have a functional airspeed // sensor then don't do crash detection - if (gps.status() < AP_GPS::GPS_OK_FIX_3D && (!airspeed.use() || !airspeed.healthy())) { + if (gps.status() < AP_GPS::GPS_OK_FIX_3D) { +#if AP_AIRSPEED_ENABLED + if (!airspeed.use() || !airspeed.healthy()) { + crashed = false; + } +#else crashed = false; +#endif } if (!crashed) { diff --git a/ArduPlane/mode.cpp b/ArduPlane/mode.cpp index f4ca11a06c6..365be2981ff 100644 --- a/ArduPlane/mode.cpp +++ b/ArduPlane/mode.cpp @@ -50,6 +50,7 @@ bool Mode::enter() plane.guided_state.target_heading_type = GUIDED_HEADING_NONE; plane.guided_state.target_airspeed_cm = -1; // same as above, although an airspeed of -1 is rare on plane. plane.guided_state.target_alt = -1; // same as above, although a target alt of -1 is rare on plane. + plane.guided_state.target_alt_time_ms = 0; plane.guided_state.last_target_alt = 0; #endif @@ -80,6 +81,10 @@ bool Mode::enter() // initialize speed variable used in AUTO and GUIDED for DO_CHANGE_SPEED commands plane.new_airspeed_cm = -1; +#if HAL_QUADPLANE_ENABLED + quadplane.mode_enter(); +#endif + bool enter_result = _enter(); if (enter_result) { @@ -97,6 +102,13 @@ bool Mode::enter() // update RC failsafe, as mode change may have necessitated changing the failsafe throttle plane.control_failsafe(); + +#if AP_FENCE_ENABLED + // pilot requested flight mode change during a fence breach indicates pilot is attempting to manually recover + // this flight mode change could be automatic (i.e. fence, battery, GPS or GCS failsafe) + // but it should be harmless to disable the fence temporarily in these situations as well + plane.fence.manual_recovery_start(); +#endif } return enter_result; diff --git a/ArduPlane/mode.h b/ArduPlane/mode.h index 0dafd9a0eb7..8744beb5b4b 100644 --- a/ArduPlane/mode.h +++ b/ArduPlane/mode.h @@ -271,6 +271,8 @@ class ModeLoiter : public Mode bool does_auto_navigation() const override { return true; } bool does_auto_throttle() const override { return true; } + + bool allows_terrain_disable() const override { return true; } protected: @@ -339,7 +341,7 @@ class ModeRTL : public Mode private: // Switch to QRTL if enabled and within radius - bool switch_QRTL(bool check_loiter_target = true); + bool switch_QRTL(); }; class ModeStabilize : public Mode @@ -597,6 +599,13 @@ class ModeQRTL : public Mode protected: bool _enter() override; + +private: + + enum class SubMode { + climb, + RTL, + } submode; }; class ModeQAcro : public Mode diff --git a/ArduPlane/mode_LoiterAltQLand.cpp b/ArduPlane/mode_LoiterAltQLand.cpp index 586820e3848..0cc8b9457c1 100644 --- a/ArduPlane/mode_LoiterAltQLand.cpp +++ b/ArduPlane/mode_LoiterAltQLand.cpp @@ -44,20 +44,18 @@ void ModeLoiterAltQLand::switch_qland() bool ModeLoiterAltQLand::handle_guided_request(Location target_loc) { - plane.guided_WP_loc = target_loc; - // setup altitude #if AP_TERRAIN_AVAILABLE if (plane.terrain_enabled_in_mode(Mode::Number::QLAND)) { - plane.guided_WP_loc.set_alt_cm(quadplane.qrtl_alt*100UL, Location::AltFrame::ABOVE_TERRAIN); + target_loc.set_alt_cm(quadplane.qrtl_alt*100UL, Location::AltFrame::ABOVE_TERRAIN); } else { - plane.guided_WP_loc.set_alt_cm(quadplane.qrtl_alt*100UL, Location::AltFrame::ABOVE_HOME); + target_loc.set_alt_cm(quadplane.qrtl_alt*100UL, Location::AltFrame::ABOVE_HOME); } #else - plane.guided_WP_loc.set_alt_cm(quadplane.qrtl_alt*100UL, Location::AltFrame::ABOVE_HOME); + target_loc.set_alt_cm(quadplane.qrtl_alt*100UL, Location::AltFrame::ABOVE_HOME); #endif - plane.set_guided_WP(); + plane.set_guided_WP(target_loc); return true; } diff --git a/ArduPlane/mode_auto.cpp b/ArduPlane/mode_auto.cpp index 9b6332b059c..17affcf0a2c 100644 --- a/ArduPlane/mode_auto.cpp +++ b/ArduPlane/mode_auto.cpp @@ -4,6 +4,17 @@ bool ModeAuto::_enter() { #if HAL_QUADPLANE_ENABLED + // check if we should refuse auto mode due to a missing takeoff in + // guided_wait_takeoff state + if (plane.previous_mode == &plane.mode_guided && + quadplane.guided_wait_takeoff_on_mode_enter) { + if (!plane.mission.starts_with_takeoff_cmd()) { + gcs().send_text(MAV_SEVERITY_ERROR,"Takeoff waypoint required"); + quadplane.guided_wait_takeoff = true; + return false; + } + } + if (plane.quadplane.available() && plane.quadplane.enable == 2) { plane.auto_state.vtol_mode = true; } else { diff --git a/ArduPlane/mode_guided.cpp b/ArduPlane/mode_guided.cpp index aeac4819895..b80e72dd021 100644 --- a/ArduPlane/mode_guided.cpp +++ b/ArduPlane/mode_guided.cpp @@ -8,19 +8,19 @@ bool ModeGuided::_enter() when entering guided mode we set the target as the current location. This matches the behaviour of the copter code */ - plane.guided_WP_loc = plane.current_loc; + Location loc{plane.current_loc}; #if HAL_QUADPLANE_ENABLED if (plane.quadplane.guided_mode_enabled()) { /* if using Q_GUIDED_MODE then project forward by the stopping distance */ - plane.guided_WP_loc.offset_bearing(degrees(plane.ahrs.groundspeed_vector().angle()), - plane.quadplane.stopping_distance()); + loc.offset_bearing(degrees(plane.ahrs.groundspeed_vector().angle()), + plane.quadplane.stopping_distance()); } #endif - plane.set_guided_WP(); + plane.set_guided_WP(loc); return true; } @@ -45,15 +45,13 @@ void ModeGuided::navigate() bool ModeGuided::handle_guided_request(Location target_loc) { - plane.guided_WP_loc = target_loc; - // add home alt if needed - if (plane.guided_WP_loc.relative_alt) { - plane.guided_WP_loc.alt += plane.home.alt; - plane.guided_WP_loc.relative_alt = 0; + if (target_loc.relative_alt) { + target_loc.alt += plane.home.alt; + target_loc.relative_alt = 0; } - plane.set_guided_WP(); + plane.set_guided_WP(target_loc); return true; } diff --git a/ArduPlane/mode_loiter.cpp b/ArduPlane/mode_loiter.cpp index 45600af3424..1e9b7b6175b 100644 --- a/ArduPlane/mode_loiter.cpp +++ b/ArduPlane/mode_loiter.cpp @@ -5,6 +5,14 @@ bool ModeLoiter::_enter() { plane.do_loiter_at_location(); plane.setup_terrain_target_alt(plane.next_WP_loc); + + // make sure the local target altitude is the same as the nav target used for loiter nav + // this allows us to do FBWB style stick control + /*IGNORE_RETURN(plane.next_WP_loc.get_alt_cm(Location::AltFrame::ABSOLUTE, plane.target_altitude.amsl_cm));*/ + if (plane.stick_mixing_enabled() && (plane.g2.flight_options & FlightOptions::ENABLE_LOITER_ALT_CONTROL)) { + plane.set_target_altitude_current(); + } + plane.loiter_angle_reset(); return true; @@ -13,8 +21,12 @@ bool ModeLoiter::_enter() void ModeLoiter::update() { plane.calc_nav_roll(); - plane.calc_nav_pitch(); - plane.calc_throttle(); + if (plane.stick_mixing_enabled() && (plane.g2.flight_options & FlightOptions::ENABLE_LOITER_ALT_CONTROL)) { + plane.update_fbwb_speed_height(); + } else { + plane.calc_nav_pitch(); + plane.calc_throttle(); + } } bool ModeLoiter::isHeadingLinedUp(const Location loiterCenterLoc, const Location targetLoc) @@ -74,6 +86,11 @@ bool ModeLoiter::isHeadingLinedUp_cd(const int32_t bearing_cd) void ModeLoiter::navigate() { + if (plane.g2.flight_options & FlightOptions::ENABLE_LOITER_ALT_CONTROL) { + // update the WP alt from the global target adjusted by update_fbwb_speed_height + plane.next_WP_loc.set_alt_cm(plane.target_altitude.amsl_cm, Location::AltFrame::ABSOLUTE); + } + // Zero indicates to use WP_LOITER_RAD plane.update_loiter(0); } diff --git a/ArduPlane/mode_qacro.cpp b/ArduPlane/mode_qacro.cpp index f329ec35544..79d8ed69ebc 100644 --- a/ArduPlane/mode_qacro.cpp +++ b/ArduPlane/mode_qacro.cpp @@ -6,8 +6,12 @@ bool ModeQAcro::_enter() { quadplane.throttle_wait = false; - quadplane.transition->force_transistion_complete(); + quadplane.transition->force_transition_complete(); attitude_control->relax_attitude_controllers(); + + // disable yaw rate time contant to mantain old behaviour + quadplane.disable_yaw_rate_time_constant(); + return true; } diff --git a/ArduPlane/mode_qhover.cpp b/ArduPlane/mode_qhover.cpp index fe616292a73..13c1a4c4e65 100644 --- a/ArduPlane/mode_qhover.cpp +++ b/ArduPlane/mode_qhover.cpp @@ -8,7 +8,7 @@ bool ModeQHover::_enter() // set vertical speed and acceleration limits pos_control->set_max_speed_accel_z(-quadplane.get_pilot_velocity_z_max_dn(), quadplane.pilot_velocity_z_max_up, quadplane.pilot_accel_z); pos_control->set_correction_speed_accel_z(-quadplane.get_pilot_velocity_z_max_dn(), quadplane.pilot_velocity_z_max_up, quadplane.pilot_accel_z); - quadplane.set_climb_rate_cms(0, false); + quadplane.set_climb_rate_cms(0); quadplane.init_throttle_wait(); return true; diff --git a/ArduPlane/mode_qland.cpp b/ArduPlane/mode_qland.cpp index dfc89ebfd99..204d90f0368 100644 --- a/ArduPlane/mode_qland.cpp +++ b/ArduPlane/mode_qland.cpp @@ -16,7 +16,7 @@ bool ModeQLand::_enter() #if LANDING_GEAR_ENABLED == ENABLED plane.g2.landing_gear.deploy_for_landing(); #endif -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED plane.fence.auto_disable_fence_for_landing(); #endif return true; diff --git a/ArduPlane/mode_qloiter.cpp b/ArduPlane/mode_qloiter.cpp index 836143192ee..0b3aa6dfa6f 100644 --- a/ArduPlane/mode_qloiter.cpp +++ b/ArduPlane/mode_qloiter.cpp @@ -77,6 +77,9 @@ void ModeQLoiter::run() pos_control->set_externally_limited_xy(); } + // Pilot input, use yaw rate time constant + quadplane.set_pilot_yaw_rate_time_constant(); + // call attitude controller with conservative smoothing gain of 4.0f attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(plane.nav_roll_cd, plane.nav_pitch_cd, @@ -86,25 +89,27 @@ void ModeQLoiter::run() if (poscontrol.get_state() < QuadPlane::QPOS_LAND_FINAL && quadplane.check_land_final()) { poscontrol.set_state(QuadPlane::QPOS_LAND_FINAL); quadplane.setup_target_position(); +#if AP_ICENGINE_ENABLED // cut IC engine if enabled if (quadplane.land_icengine_cut != 0) { plane.g2.ice_control.engine_control(0, 0, 0); } +#endif // AP_ICENGINE_ENABLED } float height_above_ground = plane.relative_ground_altitude(plane.g.rangefinder_landing); float descent_rate_cms = quadplane.landing_descent_rate_cms(height_above_ground); - if (poscontrol.get_state() == QuadPlane::QPOS_LAND_FINAL && (quadplane.options & QuadPlane::OPTION_DISABLE_GROUND_EFFECT_COMP) == 0) { + if (poscontrol.get_state() == QuadPlane::QPOS_LAND_FINAL && !quadplane.option_is_set(QuadPlane::OPTION::DISABLE_GROUND_EFFECT_COMP)) { quadplane.ahrs.set_touchdown_expected(true); } - quadplane.set_climb_rate_cms(-descent_rate_cms, descent_rate_cms>0); + pos_control->land_at_climb_rate_cm(-descent_rate_cms, descent_rate_cms>0); quadplane.check_land_complete(); } else if (plane.control_mode == &plane.mode_guided && quadplane.guided_takeoff) { - quadplane.set_climb_rate_cms(0, false); + quadplane.set_climb_rate_cms(0); } else { // update altitude target and call position controller - quadplane.set_climb_rate_cms(quadplane.get_pilot_desired_climb_rate_cms(), false); + quadplane.set_climb_rate_cms(quadplane.get_pilot_desired_climb_rate_cms()); } quadplane.run_z_controller(); } diff --git a/ArduPlane/mode_qrtl.cpp b/ArduPlane/mode_qrtl.cpp index 9ddbd458516..22654b84cee 100644 --- a/ArduPlane/mode_qrtl.cpp +++ b/ArduPlane/mode_qrtl.cpp @@ -5,27 +5,55 @@ bool ModeQRTL::_enter() { - // use do_RTL() to setup next_WP_loc - plane.do_RTL(plane.home.alt + quadplane.qrtl_alt*100UL); + // treat QRTL as QLAND if we are in guided wait takeoff state, to cope + // with failsafes during GUIDED->AUTO takeoff sequence + if (plane.quadplane.guided_wait_takeoff_on_mode_enter) { + plane.set_mode(plane.mode_qland, ModeReason::QLAND_INSTEAD_OF_RTL); + return true; + } + submode = SubMode::RTL; plane.prev_WP_loc = plane.current_loc; - pos_control->set_accel_desired_xy_cmss(Vector2f()); - pos_control->init_xy_controller(); - quadplane.poscontrol_init_approach(); - float dist = plane.next_WP_loc.get_distance(plane.current_loc); - const float radius = MAX(fabsf(plane.aparm.loiter_radius), fabsf(plane.g.rtl_radius)); - if (dist < 1.5*radius && - quadplane.motors->get_desired_spool_state() == AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED) { - // we're close to destination and already running VTOL motors, don't transition - gcs().send_text(MAV_SEVERITY_INFO,"VTOL position1 d=%.1f r=%.1f", dist, radius); - poscontrol.set_state(QuadPlane::QPOS_POSITION1); + + const int32_t RTL_alt_abs_cm = plane.home.alt + quadplane.qrtl_alt*100UL; + if (quadplane.motors->get_desired_spool_state() == AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED) { + // VTOL motors are active, either in VTOL flight or assisted flight + Location destination = plane.rally.calc_best_rally_or_home_location(plane.current_loc, RTL_alt_abs_cm); + + const float dist = plane.current_loc.get_distance(destination); + const float radius = MAX(fabsf(plane.aparm.loiter_radius), fabsf(plane.g.rtl_radius)); + + const float dist_to_climb = quadplane.qrtl_alt - plane.relative_ground_altitude(plane.g.rangefinder_landing); + if (dist < 1.5*radius) { + // we're close to destination and already running VTOL motors, don't transition and don't climb + gcs().send_text(MAV_SEVERITY_INFO,"VTOL position1 d=%.1f r=%.1f", dist, radius); + poscontrol.set_state(QuadPlane::QPOS_POSITION1); + + } else if (is_positive(dist_to_climb)) { + // climb before returning, only next waypoint altitude is used + submode = SubMode::climb; + plane.next_WP_loc = plane.current_loc; +#if AP_TERRAIN_AVAILABLE + if (plane.terrain_enabled_in_mode(mode_number())) { + plane.next_WP_loc.set_alt_cm(quadplane.qrtl_alt * 100UL, Location::AltFrame::ABOVE_TERRAIN); + return true; + } +#endif + plane.next_WP_loc.set_alt_cm(plane.current_loc.alt + dist_to_climb * 100UL, plane.current_loc.get_alt_frame()); + return true; + } } + + // use do_RTL() to setup next_WP_loc + plane.do_RTL(RTL_alt_abs_cm); + quadplane.poscontrol_init_approach(); + int32_t from_alt; int32_t to_alt; if (plane.current_loc.get_alt_cm(Location::AltFrame::ABSOLUTE,from_alt) && plane.next_WP_loc.get_alt_cm(Location::AltFrame::ABSOLUTE,to_alt)) { poscontrol.slow_descent = from_alt > to_alt; return true; } - // defualt back to old method + // default back to old method poscontrol.slow_descent = (plane.current_loc.alt > plane.next_WP_loc.alt); return true; } @@ -40,20 +68,64 @@ void ModeQRTL::update() */ void ModeQRTL::run() { - quadplane.vtol_position_controller(); - if (poscontrol.get_state() > QuadPlane::QPOS_POSITION2) { - // change target altitude to home alt - plane.next_WP_loc.alt = plane.home.alt; - } - if (poscontrol.get_state() >= QuadPlane::QPOS_POSITION2) { - // start landing logic - quadplane.verify_vtol_land(); - } + switch (submode) { + case SubMode::climb: { + // request zero velocity + Vector2f vel, accel; + pos_control->input_vel_accel_xy(vel, accel); + quadplane.run_xy_controller(); + + // nav roll and pitch are controller by position controller + plane.nav_roll_cd = pos_control->get_roll_cd(); + plane.nav_pitch_cd = pos_control->get_pitch_cd(); + if (quadplane.transition->set_VTOL_roll_pitch_limit(plane.nav_roll_cd, plane.nav_pitch_cd)) { + pos_control->set_externally_limited_xy(); + } + // weathervane with no pilot input + quadplane.disable_yaw_rate_time_constant(); + attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(plane.nav_roll_cd, + plane.nav_pitch_cd, + quadplane.get_weathervane_yaw_rate_cds()); + + // climb at full WP nav speed + quadplane.set_climb_rate_cms(quadplane.wp_nav->get_default_speed_up()); + quadplane.run_z_controller(); + + ftype alt_diff; + if (!plane.current_loc.get_alt_distance(plane.next_WP_loc, alt_diff) || is_positive(alt_diff)) { + // climb finshed or cant get alt diff, head home + submode = SubMode::RTL; + plane.prev_WP_loc = plane.current_loc; + plane.do_RTL(plane.home.alt + quadplane.qrtl_alt*100UL); + quadplane.poscontrol_init_approach(); + if (plane.current_loc.get_alt_distance(plane.next_WP_loc, alt_diff)) { + poscontrol.slow_descent = is_positive(alt_diff); + } else { + // default back to old method + poscontrol.slow_descent = (plane.current_loc.alt > plane.next_WP_loc.alt); + } + } + break; + } + + case SubMode::RTL: { + quadplane.vtol_position_controller(); + if (poscontrol.get_state() > QuadPlane::QPOS_POSITION2) { + // change target altitude to home alt + plane.next_WP_loc.alt = plane.home.alt; + } + if (poscontrol.get_state() >= QuadPlane::QPOS_POSITION2) { + // start landing logic + quadplane.verify_vtol_land(); + } - // when in approach allow stick mixing - if (quadplane.poscontrol.get_state() == QuadPlane::QPOS_AIRBRAKE || - quadplane.poscontrol.get_state() == QuadPlane::QPOS_APPROACH) { - plane.stabilize_stick_mixing_fbw(); + // when in approach allow stick mixing + if (quadplane.poscontrol.get_state() == QuadPlane::QPOS_AIRBRAKE || + quadplane.poscontrol.get_state() == QuadPlane::QPOS_APPROACH) { + plane.stabilize_stick_mixing_fbw(); + } + break; + } } } @@ -65,7 +137,7 @@ bool ModeQRTL::update_target_altitude() /* update height target in approach */ - if (plane.quadplane.poscontrol.get_state() != QuadPlane::QPOS_APPROACH) { + if ((submode != SubMode::RTL) || (plane.quadplane.poscontrol.get_state() != QuadPlane::QPOS_APPROACH)) { return false; } @@ -92,7 +164,7 @@ bool ModeQRTL::update_target_altitude() // only nudge during approach bool ModeQRTL::allows_throttle_nudging() const { - return plane.quadplane.poscontrol.get_state() == QuadPlane::QPOS_APPROACH; + return (submode == SubMode::RTL) && (plane.quadplane.poscontrol.get_state() == QuadPlane::QPOS_APPROACH); } #endif diff --git a/ArduPlane/mode_qstabilize.cpp b/ArduPlane/mode_qstabilize.cpp index 8a5f9fef65b..2c8da2d9688 100644 --- a/ArduPlane/mode_qstabilize.cpp +++ b/ArduPlane/mode_qstabilize.cpp @@ -27,7 +27,7 @@ void ModeQStabilize::update() return; } - if ((plane.quadplane.options & QuadPlane::OPTION_INGORE_FW_ANGLE_LIMITS_IN_Q_MODES) == 0) { + if (!plane.quadplane.option_is_set(QuadPlane::OPTION::INGORE_FW_ANGLE_LIMITS_IN_Q_MODES)) { // by default angles are also constrained by forward flight limits set_limited_roll_pitch(roll_input, pitch_input); } else { diff --git a/ArduPlane/mode_rtl.cpp b/ArduPlane/mode_rtl.cpp index 42f38d560ea..902749f0fcb 100644 --- a/ArduPlane/mode_rtl.cpp +++ b/ArduPlane/mode_rtl.cpp @@ -8,11 +8,37 @@ bool ModeRTL::_enter() plane.rtl.done_climb = false; #if HAL_QUADPLANE_ENABLED plane.vtol_approach_s.approach_stage = Plane::Landing_ApproachStage::RTL; -#endif - // do not check if we have reached the loiter target if switching from loiter this will trigger as the nav controller has not yet proceeded the new destination -#if HAL_QUADPLANE_ENABLED - switch_QRTL(false); + // Quadplane specific checks + if (plane.quadplane.available()) { + // treat RTL as QLAND if we are in guided wait takeoff state, to cope + // with failsafes during GUIDED->AUTO takeoff sequence + if (plane.quadplane.guided_wait_takeoff_on_mode_enter) { + plane.set_mode(plane.mode_qland, ModeReason::QLAND_INSTEAD_OF_RTL); + return true; + } + + // if Q_RTL_MODE is QRTL always, immediately switch to QRTL mode + if (plane.quadplane.rtl_mode == QuadPlane::RTL_MODE::QRTL_ALWAYS) { + plane.set_mode(plane.mode_qrtl, ModeReason::QRTL_INSTEAD_OF_RTL); + return true; + } + + // if VTOL landing is expected and quadplane motors are active and within QRTL radius and under QRTL altitude then switch to QRTL + const bool vtol_landing = (plane.quadplane.rtl_mode == QuadPlane::RTL_MODE::SWITCH_QRTL) || (plane.quadplane.rtl_mode == QuadPlane::RTL_MODE::VTOL_APPROACH_QRTL); + if (vtol_landing && (quadplane.motors->get_desired_spool_state() == AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED)) { + uint16_t qrtl_radius = abs(plane.g.rtl_radius); + if (qrtl_radius == 0) { + qrtl_radius = abs(plane.aparm.loiter_radius); + } + int32_t alt_cm; + if ((plane.current_loc.get_distance(plane.next_WP_loc) < qrtl_radius) && + plane.current_loc.get_alt_cm(Location::AltFrame::ABOVE_HOME, alt_cm) && (alt_cm < plane.quadplane.qrtl_alt*100)) { + plane.set_mode(plane.mode_qrtl, ModeReason::QRTL_INSTEAD_OF_RTL); + return true; + } + } + } #endif return true; @@ -55,10 +81,10 @@ void ModeRTL::update() void ModeRTL::navigate() { #if HAL_QUADPLANE_ENABLED - if (plane.control_mode->mode_number() != QRTL) { + if ((plane.control_mode->mode_number() != QRTL) && plane.quadplane.available()) { // QRTL shares this navigate function with RTL - if (plane.quadplane.available() && (plane.quadplane.rtl_mode == QuadPlane::RTL_MODE::VTOL_APPROACH_QRTL)) { + if (plane.quadplane.rtl_mode == QuadPlane::RTL_MODE::VTOL_APPROACH_QRTL) { // VTOL approach landing AP_Mission::Mission_Command cmd; cmd.content.location = plane.next_WP_loc; @@ -75,7 +101,7 @@ void ModeRTL::navigate() } #endif - if (plane.g.rtl_autoland == 1 && + if (plane.g.rtl_autoland == RtlAutoland::RTL_THEN_DO_LAND_START && !plane.auto_state.checked_for_autoland && plane.reached_loiter_target() && labs(plane.altitude_error_cm) < 1000) { @@ -90,7 +116,7 @@ void ModeRTL::navigate() // on every loop plane.auto_state.checked_for_autoland = true; } - else if (plane.g.rtl_autoland == 2 && + else if (plane.g.rtl_autoland == RtlAutoland::RTL_IMMEDIATE_DO_LAND_START && !plane.auto_state.checked_for_autoland) { // Go directly to the landing sequence if (plane.mission.jump_to_landing_sequence()) { @@ -113,24 +139,18 @@ void ModeRTL::navigate() #if HAL_QUADPLANE_ENABLED // Switch to QRTL if enabled and within radius -bool ModeRTL::switch_QRTL(bool check_loiter_target) +bool ModeRTL::switch_QRTL() { - if (!plane.quadplane.available() || ((plane.quadplane.rtl_mode != QuadPlane::RTL_MODE::SWITCH_QRTL) && (plane.quadplane.rtl_mode != QuadPlane::RTL_MODE::QRTL_ALWAYS))) { + if (plane.quadplane.rtl_mode != QuadPlane::RTL_MODE::SWITCH_QRTL) { return false; } - // if Q_RTL_MODE is QRTL always, then immediately switch to QRTL mode - if (plane.quadplane.rtl_mode == QuadPlane::RTL_MODE::QRTL_ALWAYS) { - plane.set_mode(plane.mode_qrtl, ModeReason::QRTL_INSTEAD_OF_RTL); - return true; - } - uint16_t qrtl_radius = abs(plane.g.rtl_radius); if (qrtl_radius == 0) { qrtl_radius = abs(plane.aparm.loiter_radius); } - if ( (check_loiter_target && plane.nav_controller->reached_loiter_target()) || + if (plane.nav_controller->reached_loiter_target() || plane.current_loc.past_interval_finish_line(plane.prev_WP_loc, plane.next_WP_loc) || plane.auto_state.wp_distance < MAX(qrtl_radius, plane.quadplane.stopping_distance())) { /* diff --git a/ArduPlane/mode_takeoff.cpp b/ArduPlane/mode_takeoff.cpp index d1eb42a4bc6..3eb8604c373 100644 --- a/ArduPlane/mode_takeoff.cpp +++ b/ArduPlane/mode_takeoff.cpp @@ -114,7 +114,7 @@ void ModeTakeoff::update() plane.set_flight_stage(AP_Vehicle::FixedWing::FLIGHT_NORMAL); -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED plane.fence.auto_enable_fence_after_takeoff(); #endif } diff --git a/ArduPlane/motor_test.cpp b/ArduPlane/motor_test.cpp index 8774aa18336..cfc640cab98 100644 --- a/ArduPlane/motor_test.cpp +++ b/ArduPlane/motor_test.cpp @@ -7,8 +7,6 @@ */ // motor test definitions -#define MOTOR_TEST_PWM_MIN 800 // min pwm value accepted by the test -#define MOTOR_TEST_PWM_MAX 2200 // max pwm value accepted by the test #define MOTOR_TEST_TIMEOUT_MS_MAX 30000 // max timeout is 30 seconds // motor_test_output - checks for timeout and sends updates to motors objects @@ -68,7 +66,7 @@ void QuadPlane::motor_test_output() } // sanity check throttle values - if (pwm >= MOTOR_TEST_PWM_MIN && pwm <= MOTOR_TEST_PWM_MAX ) { + if (pwm >= RC_Channel::RC_MIN_LIMIT_PWM && pwm <= RC_Channel::RC_MAX_LIMIT_PWM) { // turn on motor to specified pwm vlaue motors->output_test_seq(motor_test.seq, pwm); } else { diff --git a/ArduPlane/navigation.cpp b/ArduPlane/navigation.cpp index 1f2c8b744e3..1cf0f7d5222 100644 --- a/ArduPlane/navigation.cpp +++ b/ArduPlane/navigation.cpp @@ -113,7 +113,7 @@ void Plane::navigate() float Plane::mode_auto_target_airspeed_cm() { #if HAL_QUADPLANE_ENABLED - if ((quadplane.options & QuadPlane::OPTION_MISSION_LAND_FW_APPROACH) && + if (quadplane.landing_with_fixed_wing_spiral_approach() && ((vtol_approach_s.approach_stage == Landing_ApproachStage::APPROACH_LINE) || (vtol_approach_s.approach_stage == Landing_ApproachStage::VTOL_LANDING))) { const float land_airspeed = TECS_controller.get_land_airspeed(); @@ -143,9 +143,9 @@ void Plane::calc_airspeed_errors() // Get the airspeed_estimate, update smoothed airspeed estimate // NOTE: we use the airspeed estimate function not direct sensor // as TECS may be using synthetic airspeed - float airspeed_measured = 0; + float airspeed_measured = 0.1; if (ahrs.airspeed_estimate(airspeed_measured)) { - smoothed_airspeed = smoothed_airspeed * 0.8f + airspeed_measured * 0.2f; + smoothed_airspeed = MAX(0.1, smoothed_airspeed * 0.8f + airspeed_measured * 0.2f); } // low pass filter speed scaler, with 1Hz cutoff, at 10Hz @@ -365,7 +365,7 @@ void Plane::update_loiter(uint16_t radius) } /* - handle speed and height control in FBWB or CRUISE mode. + handle speed and height control in FBWB, CRUISE, and optionally, LOITER mode. In this mode the elevator is used to change target altitude. The throttle is used to change target airspeed or throttle */ @@ -380,7 +380,7 @@ void Plane::update_fbwb_speed_height(void) target_altitude.last_elev_check_us = now; - float elevator_input = channel_pitch->get_control_in() / 4500.0f; + float elevator_input = channel_pitch->get_control_in() * (1/4500.0); if (g.flybywire_elev_reverse) { elevator_input = -elevator_input; diff --git a/ArduPlane/qautotune.h b/ArduPlane/qautotune.h index d82555c0f9b..587ba85b15a 100644 --- a/ArduPlane/qautotune.h +++ b/ArduPlane/qautotune.h @@ -4,7 +4,7 @@ #pragma once -#include +#include #include "quadplane.h" diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 491d89d79f2..ebecaaff3d3 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -103,7 +103,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { // @Param: ASSIST_SPEED // @DisplayName: Quadplane assistance speed - // @Description: This is the speed below which the quad motors will provide stability and lift assistance in fixed wing modes. Zero means no assistance except during transition + // @Description: This is the speed below which the quad motors will provide stability and lift assistance in fixed wing modes. Zero means no assistance except during transition. Note that if this is set to zero then other Q_ASSIST features are also disabled. A higher value will lead to more false positives which can waste battery. A lower value will result in less false positive, but will result in assistance taking longer to trigger. If unsure then set to 3 m/s below the minimum airspeed you will fly at. If you don't have an airspeed sensor then use 5 m/s below the minimum airspeed you fly at. If you want to disable the arming check Q_ASSIST_SPEED then set to -1. // @Units: m/s // @Range: 0 100 // @Increment: 0.1 @@ -117,7 +117,8 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { // @Range: 50 500 // @Increment: 1 // @User: Standard - AP_GROUPINFO("YAW_RATE_MAX", 25, QuadPlane, yaw_rate_max, 100), + + // YAW_RATE_MAX index 25 // @Param: LAND_SPEED // @DisplayName: Land speed @@ -187,7 +188,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { // @Param: RTL_MODE // @DisplayName: VTOL RTL mode - // @Description: If this is set to 1 then an RTL will change to QRTL when within RTL_RADIUS meters of the RTL destination, VTOL approach: vehicle will RTL at RTL alt and circle with a radius of Q_FW_LND_APR_RAD down to Q_RLT_ALT and then transission into the wind and QRTL, see 'AUTO VTOL Landing', QRTL Always: do a QRTL instead of RTL + // @Description: If this is set to 1 then an RTL will change to QRTL when within RTL_RADIUS meters of the RTL destination, VTOL approach: vehicle will RTL at RTL alt and circle with a radius of Q_FW_LND_APR_RAD down to Q_RTL_ALT and then transition into the wind and QRTL, see 'AUTO VTOL Landing', QRTL Always: do a QRTL instead of RTL // @Values: 0:Disabled,1:Enabled,2:VTOL approach,3:QRTL Always // @User: Standard AP_GROUPINFO("RTL_MODE", 36, QuadPlane, rtl_mode, 0), @@ -256,8 +257,8 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { // @Param: OPTIONS // @DisplayName: quadplane options - // @Description: Level Transition:Keep wings within LEVEL_ROLL_LIMIT and only use forward motor(s) for climb during transition, Allow FW Takeoff: If bit is not set then NAV_TAKEOFF command on quadplanes will instead perform a NAV_VTOL takeoff, Allow FW Land:If bit is not set then NAV_LAND command on quadplanes will instead perform a NAV_VTOL_LAND, Vtol Takeoff Frame: command NAV_VTOL_TAKEOFF altitude is as set by the command's reference frame rather than a delta above current location, Use FW Approach:Use a fixed wing approach for VTOL landings, USE QRTL:instead of QLAND for rc failsafe when in VTOL modes, Use Governor:Use ICE Idle Governor in MANUAL for forward motor, Force Qassist: on always,Mtrs_Only_Qassist: in tailsitters only, uses VTOL motors and not flying surfaces for QASSIST, Airmode_On_Arm:Airmode enabled when arming by aux switch, Disarmed Yaw Tilt:Enable motor tilt for yaw when disarmed, Delay Spoolup:Delay VTOL spoolup for 2 seconds after arming, ThrLandControl: enable throttle stick control of landing rate, DisableApproach: Disable use of approach and airbrake stages in VTOL landing, EnableLandResposition: enable pilot controlled repositioning in AUTO land. Descent will pause while repositioning. ARMVTOL: Arm only in VTOL or AUTO modes. CompleteTransition: to fixed wing if Q_TRANS_FAIL timer times out instead of QLAND. - // @Bitmask: 0:Level Transition,1:Allow FW Takeoff,2:Allow FW Land,3:Vtol Takeoff Frame,4:Use FW Approach,5:Use QRTL,6:Use Governor,7:Force Qassist,8:Mtrs_Only_Qassist,10:Disarmed Yaw Tilt,11:Delay Spoolup,12:disable Qassist based on synthetic airspeed,13:Disable Ground Effect Compensation,14:Ignore forward flight angle limits in Qmodes,15:ThrLandControl,16:DisableApproach,17:EnableLandResponsition,18:ARMVtol, 19: CompleteTransition if Q_TRANS_FAIL + // @Description: Level Transition:Keep wings within LEVEL_ROLL_LIMIT and only use forward motor(s) for climb during transition, Allow FW Takeoff: If bit is not set then NAV_TAKEOFF command on quadplanes will instead perform a NAV_VTOL takeoff, Allow FW Land:If bit is not set then NAV_LAND command on quadplanes will instead perform a NAV_VTOL_LAND, Vtol Takeoff Frame: command NAV_VTOL_TAKEOFF altitude is as set by the command's reference frame rather than a delta above current location, Always use FW spiral approach:Always use Use a fixed wing spiral approach for VTOL landings, USE QRTL:instead of QLAND for rc failsafe when in VTOL modes, Use Governor:Use ICE Idle Governor in MANUAL for forward motor, Force Qassist: on always,Mtrs_Only_Qassist: in tailsitters only, uses VTOL motors and not flying surfaces for QASSIST, Airmode_On_Arm:Airmode enabled when arming by aux switch, Disarmed Yaw Tilt:Enable motor tilt for yaw when disarmed, Delay Spoolup:Delay VTOL spoolup for 2 seconds after arming, ThrLandControl: enable throttle stick control of landing rate, DisableApproach: Disable use of approach and airbrake stages in VTOL landing, EnableLandResposition: enable pilot controlled repositioning in AUTO land. Descent will pause while repositioning. ARMVTOL: Arm only in VTOL or AUTO modes. CompleteTransition: to fixed wing if Q_TRANS_FAIL timer times out instead of QLAND. Force RTL mode: forces RTL mode on rc failsafe in VTOL modes overriding bit 5(USE_QRTL). + // @Bitmask: 0:Level Transition,1:Allow FW Takeoff,2:Allow FW Land,3:Vtol Takeoff Frame,4:Always use FW spiral approach,5:Use QRTL,6:Use Governor,7:Force Qassist,8:Mtrs_Only_Qassist,10:Disarmed Yaw Tilt,11:Delay Spoolup,12:disable Qassist based on synthetic airspeed,13:Disable Ground Effect Compensation,14:Ignore forward flight angle limits in Qmodes,15:ThrLandControl,16:DisableApproach,17:EnableLandReposition,18:ARMVtol, 19: CompleteTransition if Q_TRANS_FAIL, 20: Force RTL mode on VTOL failsafes overriding bit 5(USE QRTL), 21:Tilt rotor tilt motors up when disarmed in FW modes (except manual) to prevent ground strikes AP_GROUPINFO("OPTIONS", 58, QuadPlane, options, 0), AP_SUBGROUPEXTENSION("",59, QuadPlane, var_info2), @@ -434,6 +435,46 @@ const AP_Param::GroupInfo QuadPlane::var_info2[] = { // @Path: ../libraries/AC_AttitudeControl/AC_WeatherVane.cpp AP_SUBGROUPPTR(weathervane, "WVANE_", 30, QuadPlane, AC_WeatherVane), + // @Param: LAND_ALTCHG + // @DisplayName: Land detection altitude change threshold + // @Description: The maximum altitude change allowed during land detection. You can raise this value if you find that landing detection takes a long time to complete. It is the maximum change in altitude over a period of 4 seconds for landing to be detected + // @Units: m + // @Range: 0.1 0.6 + // @Increment: 0.05 + // @User: Standard + AP_GROUPINFO("LAND_ALTCHG", 31, QuadPlane, landing_detect.detect_alt_change, 0.2), + + // @Param: NAVALT_MIN + // @DisplayName: Minimum navigation altitude + // @Description: This is the altitude in meters above which navigation begins in auto takeoff. Below this altitude the target roll and pitch will be zero. A value of zero disables the feature + // @Range: 0 5 + // @User: Advanced + AP_GROUPINFO("NAVALT_MIN", 32, QuadPlane, takeoff_navalt_min, 0), + + // @Param: PLT_Y_RATE + // @DisplayName: Pilot controlled yaw rate + // @Description: Pilot controlled yaw rate max. Used in all pilot controlled modes except QAcro + // @Units: deg/s + // @Range: 1 360 + // @User: Standard + + // @Param: PLT_Y_EXPO + // @DisplayName: Pilot controlled yaw expo + // @Description: Pilot controlled yaw expo to allow faster rotation when stick at edges + // @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High + // @Range: -0.5 1.0 + // @User: Advanced + + // @Param: PLT_Y_RATE_TC + // @DisplayName: Pilot yaw rate control input time constant + // @Description: Pilot yaw rate control input time constant. Low numbers lead to sharper response, higher numbers to softer response. + // @Units: s + // @Range: 0 1 + // @Increment: 0.01 + // @Values: 0.5:Very Soft, 0.2:Soft, 0.15:Medium, 0.1:Crisp, 0.05:Very Crisp + // @User: Standard + AP_SUBGROUPINFO(command_model_pilot, "PLT_Y_", 33, QuadPlane, AC_CommandModel), + AP_GROUPEND }; @@ -461,6 +502,11 @@ static const struct AP_Param::defaults_table_struct defaults_table[] = { { "Q_LOIT_SPEED", 500 }, { "Q_WP_SPEED", 500 }, { "Q_WP_ACCEL", 100 }, + { "Q_P_JERK_XY", 2 }, + // lower rotational accel limits + { "Q_A_ACCEL_R_MAX", 40000 }, + { "Q_A_ACCEL_P_MAX", 40000 }, + { "Q_A_ACCEL_Y_MAX", 10000 }, }; /* @@ -517,14 +563,19 @@ const AP_Param::ConversionInfo q_conversion_table[] = { { Parameters::k_param_quadplane, 1467, AP_PARAM_FLOAT, "Q_TILT_FIX_ANGLE" }, { Parameters::k_param_quadplane, 1531, AP_PARAM_FLOAT, "Q_TILT_FIX_GAIN" }, - { Parameters::k_param_quadplane, 22, AP_PARAM_INT16, "Q_M_PWM_MIN" }, - { Parameters::k_param_quadplane, 23, AP_PARAM_INT16, "Q_M_PWM_MAX" }, - // PARAMETER_CONVERSION - Added: Jan-2022 { Parameters::k_param_quadplane, 33, AP_PARAM_FLOAT, "Q_WVANE_GAIN" }, // Moved from quadplane to weathervane library { Parameters::k_param_quadplane, 34, AP_PARAM_FLOAT, "Q_WVANE_ANG_MIN" }, // Q_WVANE_MINROLL moved from quadplane to weathervane library + + // PARAMETER_CONVERSION - Added: July-2022 + { Parameters::k_param_quadplane, 25, AP_PARAM_FLOAT, "Q_PLT_Y_RATE" }, // Moved from quadplane to command model library }; +// PARAMETER_CONVERSION - Added: Oct-2021 +const AP_Param::ConversionInfo mot_pwm_conversion_table[] = { + { Parameters::k_param_quadplane, 22, AP_PARAM_INT16, "Q_M_PWM_MIN" }, + { Parameters::k_param_quadplane, 23, AP_PARAM_INT16, "Q_M_PWM_MAX" }, +}; QuadPlane::QuadPlane(AP_AHRS &_ahrs) : ahrs(_ahrs) @@ -556,7 +607,6 @@ bool QuadPlane::setup(void) if (!enable || hal.util->get_soft_armed()) { return false; } - float loop_delta_t = 1.0 / plane.scheduler.get_loop_rate_hz(); /* cope with upgrade from old AP_Motors values for frame_class @@ -632,12 +682,12 @@ bool QuadPlane::setup(void) switch ((AP_Motors::motor_frame_class)frame_class) { case AP_Motors::MOTOR_FRAME_TRI: - motors = new AP_MotorsTri(plane.scheduler.get_loop_rate_hz(), rc_speed); + motors = new AP_MotorsTri(rc_speed); motors_var_info = AP_MotorsTri::var_info; break; case AP_Motors::MOTOR_FRAME_TAILSITTER: // this is a duo-motor tailsitter - tailsitter.tailsitter_motors = new AP_MotorsTailsitter(plane.scheduler.get_loop_rate_hz(), rc_speed); + tailsitter.tailsitter_motors = new AP_MotorsTailsitter(rc_speed); motors = tailsitter.tailsitter_motors; motors_var_info = AP_MotorsTailsitter::var_info; break; @@ -648,7 +698,7 @@ bool QuadPlane::setup(void) #endif // AP_SCRIPTING_ENABLED break; default: - motors = new AP_MotorsMatrix(plane.scheduler.get_loop_rate_hz(), rc_speed); + motors = new AP_MotorsMatrix(rc_speed); motors_var_info = AP_MotorsMatrix::var_info; break; } @@ -665,13 +715,13 @@ bool QuadPlane::setup(void) AP_BoardConfig::allocation_error("ahrs_view"); } - attitude_control = new AC_AttitudeControl_TS(*ahrs_view, aparm, *motors, loop_delta_t); + attitude_control = new AC_AttitudeControl_TS(*ahrs_view, aparm, *motors); if (!attitude_control) { AP_BoardConfig::allocation_error("attitude_control"); } AP_Param::load_object_from_eeprom(attitude_control, attitude_control->var_info); - pos_control = new AC_PosControl(*ahrs_view, inertial_nav, *motors, *attitude_control, loop_delta_t); + pos_control = new AC_PosControl(*ahrs_view, inertial_nav, *motors, *attitude_control); if (!pos_control) { AP_BoardConfig::allocation_error("pos_control"); } @@ -699,13 +749,19 @@ bool QuadPlane::setup(void) motors->set_update_rate(rc_speed); attitude_control->parameter_sanity_check(); + // Try to convert mot PWM params, if still invalid force conversion + AP_Param::convert_old_parameters(&mot_pwm_conversion_table[0], ARRAY_SIZE(mot_pwm_conversion_table)); + if (!motors->check_mot_pwm_params()) { + AP_Param::convert_old_parameters(&mot_pwm_conversion_table[0], ARRAY_SIZE(mot_pwm_conversion_table), AP_Param::CONVERT_FLAG_FORCE); + } + // setup the trim of any motors used by AP_Motors so I/O board // failsafe will disable motors - uint16_t mask = plane.quadplane.motors->get_motor_mask(); + uint32_t mask = plane.quadplane.motors->get_motor_mask(); hal.rcout->set_failsafe_pwm(mask, plane.quadplane.motors->get_pwm_output_min()); // default QAssist state as set with Q_OPTIONS - if ((options & OPTION_Q_ASSIST_FORCE_ENABLE) != 0) { + if (option_is_set(QuadPlane::OPTION::Q_ASSIST_FORCE_ENABLE)) { q_assist_state = Q_ASSIST_STATE_ENUM::Q_ASSIST_FORCE; } @@ -727,7 +783,7 @@ bool QuadPlane::setup(void) // init wp_nav variables after detaults are setup wp_nav->wp_and_spline_init(); - transition->force_transistion_complete(); + transition->force_transition_complete(); // param count will have changed AP_Param::invalidate_count(); @@ -799,6 +855,9 @@ void QuadPlane::multicopter_attitude_rate_update(float yaw_rate_cds) // tailsitter in transition to VTOL flight is not really in a VTOL mode yet if (use_multicopter_control) { + // Pilot input, use yaw rate time constant + set_pilot_yaw_rate_time_constant(); + // tailsitter-only body-frame roll control options // Angle mode attitude control for pitch and body-frame roll, rate control for euler yaw. if (tailsitter.enabled() && @@ -824,6 +883,7 @@ void QuadPlane::multicopter_attitude_rate_update(float yaw_rate_cds) roll_limit = tailsitter.max_roll_angle * 100.0f; } // Prevent a divide by zero + const float yaw_rate_max = command_model_pilot.get_rate(); float yaw_rate_limit = ((yaw_rate_max < 1.0f) ? 1 : yaw_rate_max) * 100.0f; float yaw2roll_scale = roll_limit / yaw_rate_limit; @@ -856,14 +916,17 @@ void QuadPlane::multicopter_attitude_rate_update(float yaw_rate_cds) } } else { // use the fixed wing desired rates - float roll_rate = plane.rollController.get_pid_info().target; - float pitch_rate = plane.pitchController.get_pid_info().target; - if (tailsitter.enabled()) { - // tailsitter roll and yaw swapped due to change in reference frame - attitude_control->input_rate_bf_roll_pitch_yaw_2(yaw_rate_cds,pitch_rate*100.0f, -roll_rate*100.0f); - } else { - attitude_control->input_rate_bf_roll_pitch_yaw_2(roll_rate*100.0f, pitch_rate*100.0f, yaw_rate_cds); - } + Vector3f bf_input_cd { plane.rollController.get_pid_info().target * 100.0f, + plane.pitchController.get_pid_info().target * 100.0f, + yaw_rate_cds }; + + // rotate into multicopter attitude refence frame + ahrs_view->rotate(bf_input_cd); + + // disable yaw time constant for 1:1 match of desired rates + disable_yaw_rate_time_constant(); + + attitude_control->input_rate_bf_roll_pitch_yaw_2(bf_input_cd.x, bf_input_cd.y, bf_input_cd.z); } } @@ -899,7 +962,7 @@ void QuadPlane::run_z_controller(void) // never run Z controller in tailsitter transtion return; } - if ((now - last_pidz_active_ms) > 20) { + if ((now - last_pidz_active_ms) > 20 || !pos_control->is_active_z()) { // set vertical speed and acceleration limits pos_control->set_max_speed_accel_z(-get_pilot_velocity_z_max_dn(), pilot_velocity_z_max_up, pilot_accel_z); @@ -940,9 +1003,9 @@ void QuadPlane::check_yaw_reset(void) } } -void QuadPlane::set_climb_rate_cms(float target_climb_rate_cms, bool force_descend) +void QuadPlane::set_climb_rate_cms(float target_climb_rate_cms) { - pos_control->input_vel_accel_z(target_climb_rate_cms, 0, force_descend); + pos_control->input_vel_accel_z(target_climb_rate_cms, 0, false); } /* @@ -960,7 +1023,7 @@ void QuadPlane::hold_hover(float target_climb_rate_cms) multicopter_attitude_rate_update(get_desired_yaw_rate_cds(false)); // call position controller - set_climb_rate_cms(target_climb_rate_cms, false); + set_climb_rate_cms(target_climb_rate_cms); run_z_controller(); } @@ -1126,7 +1189,7 @@ float QuadPlane::landing_descent_rate_cms(float height_above_ground) height_above_ground, land_final_alt, land_final_alt+6); - if ((options & OPTION_THR_LANDING_CONTROL) != 0) { + if (option_is_set(QuadPlane::OPTION::THR_LANDING_CONTROL)) { // allow throttle control for landing speed const float thr_in = get_pilot_land_throttle(); if (thr_in > THR_CTRL_LAND_THRESH) { @@ -1162,11 +1225,15 @@ float QuadPlane::landing_descent_rate_cms(float height_above_ground) */ float QuadPlane::get_pilot_input_yaw_rate_cds(void) const { + const auto rudder_in = plane.channel_rudder->get_control_in(); bool manual_air_mode = plane.control_mode->is_vtol_man_throttle() && air_mode_active(); if (!manual_air_mode && - !is_positive(plane.get_throttle_input()) && !plane.control_mode->does_auto_throttle() && - plane.arming.get_rudder_arming_type() != AP_Arming::RudderArming::IS_DISABLED && !(inertial_nav.get_velocity_z_up_cms() < -0.5 * get_pilot_velocity_z_max_dn())) { - // the user may be trying to disarm + !is_positive(plane.get_throttle_input()) && + (!plane.control_mode->does_auto_throttle() || motors->limit.throttle_lower) && + plane.arming.get_rudder_arming_type() == AP_Arming::RudderArming::ARMDISARM && + rudder_in < 0 && + fabsf(inertial_nav.get_velocity_z_up_cms()) < 0.5 * get_pilot_velocity_z_max_dn()) { + // the user may be trying to disarm, disable pilot yaw control return 0; } @@ -1178,6 +1245,7 @@ float QuadPlane::get_pilot_input_yaw_rate_cds(void) const } // add in rudder input + const float yaw_rate_max = command_model_pilot.get_rate(); float max_rate = yaw_rate_max; if (!in_vtol_mode() && tailsitter.enabled()) { // scale by RUDD_DT_GAIN when not in a VTOL mode for @@ -1192,7 +1260,7 @@ float QuadPlane::get_pilot_input_yaw_rate_cds(void) const // must have a non-zero max yaw rate for scaling to work max_rate = (yaw_rate_max < 1.0f) ? 1 : yaw_rate_max; } - return plane.channel_rudder->get_control_in() * max_rate / 45; + return input_expo(rudder_in * (1/4500.0), command_model_pilot.get_expo()) * max_rate * 100.0; } /* @@ -1205,11 +1273,7 @@ float QuadPlane::get_desired_yaw_rate_cds(bool should_weathervane) // use bank angle to get desired yaw rate yaw_cds += desired_auto_yaw_rate_cds(); } - bool manual_air_mode = plane.control_mode->is_vtol_man_throttle() && air_mode_active(); - if (!is_positive(plane.get_throttle_input()) && !plane.control_mode->does_auto_throttle() && !manual_air_mode && !(inertial_nav.get_velocity_z_up_cms() < -0.5 * get_pilot_velocity_z_max_dn())) { - // the user may be trying to disarm - return 0; - } + // add in pilot input yaw_cds += get_pilot_input_yaw_rate_cds(); @@ -1224,7 +1288,8 @@ float QuadPlane::get_desired_yaw_rate_cds(bool should_weathervane) // get pilot desired climb rate in cm/s float QuadPlane::get_pilot_desired_climb_rate_cms(void) const { - if (plane.failsafe.rc_failsafe || plane.failsafe.throttle_counter > 0) { + if (!rc().has_valid_input()) { + // no valid input means no sensible pilot desired climb rate. // descend at 0.5m/s for now return -50; } @@ -1255,6 +1320,16 @@ void QuadPlane::set_armed(bool armed) return; } motors->armed(armed); + + if (plane.control_mode == &plane.mode_guided) { + guided_wait_takeoff = armed; + } + + // re-init throttle wait on arm and disarm, to prevent rudder + // arming on 2nd flight causing yaw + if (!air_mode_active()) { + init_throttle_wait(); + } } @@ -1339,7 +1414,7 @@ bool QuadPlane::should_assist(float aspeed, bool have_airspeed) // assistance due to Q_ASSIST_SPEED // if option bit is enabled only allow assist with real airspeed sensor if ((have_airspeed && aspeed < assist_speed) && - (((options & OPTION_DISABLE_SYNTHETIC_AIRSPEED_ASSIST) == 0) || ahrs.airspeed_sensor_enabled())) { + (!option_is_set(QuadPlane::OPTION::DISABLE_SYNTHETIC_AIRSPEED_ASSIST) || ahrs.airspeed_sensor_enabled())) { in_angle_assist = false; angle_error_start_ms = 0; return true; @@ -1459,18 +1534,7 @@ void SLT_Transition::update() transition_start_ms = 0; transition_low_airspeed_ms = 0; } - - if (transition_state < TRANSITION_TIMER) { - // set a single loop pitch limit in TECS - if (plane.ahrs.groundspeed() < 3) { - // until we have some ground speed limit to zero pitch - plane.TECS_controller.set_pitch_max_limit(0); - } else { - plane.TECS_controller.set_pitch_max_limit(quadplane.transition_pitch_max); - } - } else if (transition_state < TRANSITION_DONE) { - plane.TECS_controller.set_pitch_max_limit((quadplane.transition_pitch_max+1)*2); - } + if (transition_state < TRANSITION_DONE) { // during transition we ask TECS to use a synthetic // airspeed. Otherwise the pitch limits will throw off the @@ -1498,7 +1562,7 @@ void SLT_Transition::update() // if option is set and ground speed> 1/2 arspd_fbw_min for non-tiltrotors, then complete transition, otherwise QLAND. // tiltrotors will immediately transition const bool tiltrotor_with_ground_speed = quadplane.tiltrotor.enabled() && (plane.ahrs.groundspeed() > plane.aparm.airspeed_min * 0.5); - if ((quadplane.options & QuadPlane::OPTION_TRANS_FAIL_TO_FW) && tiltrotor_with_ground_speed) { + if (quadplane.option_is_set(QuadPlane::OPTION::TRANS_FAIL_TO_FW) && tiltrotor_with_ground_speed) { transition_state = TRANSITION_TIMER; in_forced_transition = true; } else { @@ -1534,7 +1598,7 @@ void SLT_Transition::update() // otherwise the plane can end up in high-alpha flight with // low VTOL thrust and may not complete a transition float climb_rate_cms = quadplane.assist_climb_rate_cms(); - if ((quadplane.options & QuadPlane::OPTION_LEVEL_TRANSITION) && !quadplane.tiltrotor.enabled()) { + if (quadplane.option_is_set(QuadPlane::OPTION::LEVEL_TRANSITION) && !quadplane.tiltrotor.enabled()) { climb_rate_cms = MIN(climb_rate_cms, 0.0f); } quadplane.hold_hover(climb_rate_cms); @@ -1623,16 +1687,14 @@ void SLT_Transition::update() quadplane.set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN); motors->output(); } - last_fw_mode_ms = now; - last_fw_nav_pitch_cd = plane.nav_pitch_cd; + set_last_fw_pitch(); in_forced_transition = false; return; } quadplane.motors_output(); - last_fw_mode_ms = now; - last_fw_nav_pitch_cd = plane.nav_pitch_cd; + set_last_fw_pitch(); } void SLT_Transition::VTOL_update() @@ -1704,7 +1766,7 @@ void QuadPlane::update(void) } const uint32_t now = AP_HAL::millis(); - if (!in_vtol_mode()) { + if (!in_vtol_mode() && !in_vtol_airbrake()) { // we're in a fixed wing mode, cope with transitions and check // for assistance needed if (plane.control_mode == &plane.mode_manual || @@ -1715,7 +1777,7 @@ void QuadPlane::update(void) set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN); motors->output(); } - transition->force_transistion_complete(); + transition->force_transition_complete(); assisted_flight = false; } else { transition->update(); @@ -1723,7 +1785,7 @@ void QuadPlane::update(void) } else { - assisted_flight = false; + assisted_flight = in_vtol_airbrake(); // output to motors motors_output(); @@ -1735,8 +1797,7 @@ void QuadPlane::update(void) // disable throttle_wait when throttle rises above 10% if (throttle_wait && (plane.get_throttle_input() > 10 || - plane.failsafe.rc_failsafe || - plane.failsafe.throttle_counter>0)) { + !rc().has_valid_input())) { throttle_wait = false; } @@ -1785,8 +1846,21 @@ void QuadPlane::update_throttle_suppression(void) return; } - // if the users throttle is above zero then allow motors to run - if (!is_zero(plane.get_throttle_input())) { + if (guided_wait_takeoff) { + goto idle_state; + } + + /* if the users throttle is above zero then allow motors to run + + if the user has unset the "check throttle zero when arming" + then the RC controller has a sprung throttle and we should not + consider non-zero throttle to mean that pilot is commanding + takeoff unless in a manual thottle mode + */ + if (!is_zero(plane.get_throttle_input()) && + (rc().arming_check_throttle() || + plane.control_mode->is_vtol_man_throttle() || + plane.channel_throttle->norm_input_dz() > 0)) { return; } @@ -1815,7 +1889,8 @@ void QuadPlane::update_throttle_suppression(void) if (plane.control_mode == &plane.mode_auto && is_vtol_takeoff(plane.mission.get_current_nav_cmd().id)) { return; } - + +idle_state: // motors should be in the spin when armed state to warn user they could become active set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE); motors->set_throttle(0); @@ -1862,6 +1937,9 @@ void QuadPlane::update_throttle_hover() ahrs.airspeed_estimate(aspeed) && aspeed < plane.aparm.airspeed_min*0.3) { // Can we set the time constant automatically motors->update_throttle_hover(0.01f); +#if HAL_GYROFFT_ENABLED + plane.gyro_fft.update_freq_hover(0.01f, motors->get_throttle_out()); +#endif } } /* @@ -1873,7 +1951,7 @@ void QuadPlane::motors_output(bool run_rate_controller) 1) for safety (OPTION_DELAY_ARMING) 2) to allow motors to return to vertical (OPTION_DISARMED_TILT) */ - if ((options & OPTION_DISARMED_TILT) || (options & OPTION_DELAY_ARMING)) { + if (option_is_set(QuadPlane::OPTION::DISARMED_TILT) || option_is_set(QuadPlane::OPTION::DELAY_ARMING)) { if (plane.arming.get_delay_arming()) { // delay motor start after arming set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN); @@ -1913,6 +1991,11 @@ void QuadPlane::motors_output(bool run_rate_controller) // relax if have been inactive relax_attitude_control(); } + // run low level rate controllers that only require IMU data and set loop time + const float last_loop_time_s = AP::scheduler().get_last_loop_time_s(); + motors->set_dt(last_loop_time_s); + attitude_control->set_dt(last_loop_time_s); + pos_control->set_dt(last_loop_time_s); attitude_control->rate_controller_run(); last_att_control_ms = now; } @@ -2002,6 +2085,9 @@ bool QuadPlane::in_vtol_auto(void) const /* are we in a VTOL mode? This is used to decide if we run the transition handling code or not + + note that AIRBRAKE is not considered in_vtol_mode even though the + VTOL motors are running */ bool QuadPlane::in_vtol_mode(void) const { @@ -2009,7 +2095,7 @@ bool QuadPlane::in_vtol_mode(void) const return false; } if (in_vtol_land_sequence()) { - return poscontrol.get_state() != QPOS_APPROACH; + return poscontrol.get_state() != QPOS_APPROACH && poscontrol.get_state() != QPOS_AIRBRAKE; } if (plane.control_mode->is_vtol_mode()) { return true; @@ -2024,7 +2110,7 @@ bool QuadPlane::in_vtol_mode(void) const return true; } if (in_vtol_auto()) { - if (!plane.auto_state.vtol_loiter || poscontrol.get_state() > QPOS_APPROACH) { + if (!plane.auto_state.vtol_loiter || poscontrol.get_state() > QPOS_AIRBRAKE) { return true; } } @@ -2056,7 +2142,7 @@ bool QuadPlane::in_vtol_posvel_mode(void) const */ void QuadPlane::update_land_positioning(void) { - if ((options & OPTION_REPOSITION_LANDING) == 0) { + if (!option_is_set(QuadPlane::OPTION::REPOSITION_LANDING)) { // not enabled poscontrol.pilot_correction_active = false; poscontrol.target_vel_cms.zero(); @@ -2073,7 +2159,8 @@ void QuadPlane::update_land_positioning(void) poscontrol.target_vel_cms = Vector3f(-pitch_in, roll_in, 0) * speed_max_cms; poscontrol.target_vel_cms.rotate_xy(ahrs_view->yaw); - poscontrol.target_cm += (poscontrol.target_vel_cms * dt).topostype(); + // integrate our corrected position + poscontrol.xy_correction += poscontrol.target_vel_cms.xy() * dt * 0.01; poscontrol.pilot_correction_active = (!is_zero(roll_in) || !is_zero(pitch_in)); if (poscontrol.pilot_correction_active) { @@ -2084,13 +2171,20 @@ void QuadPlane::update_land_positioning(void) /* run (and possibly init) xy controller */ -void QuadPlane::run_xy_controller(void) +void QuadPlane::run_xy_controller(float accel_limit) { + float accel_cmss = wp_nav->get_wp_acceleration(); + if (is_positive(accel_limit)) { + // allow for accel limit override + accel_cmss = MAX(accel_cmss, accel_limit*100); + } + const float speed_cms = wp_nav->get_default_speed_xy(); + pos_control->set_max_speed_accel_xy(speed_cms, accel_cmss); + pos_control->set_correction_speed_accel_xy(speed_cms, accel_cmss); if (!pos_control->is_active_xy()) { - pos_control->set_max_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration()); - pos_control->set_correction_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration()); pos_control->init_xy_controller(); } + pos_control->set_lean_angle_max_cd(MIN(4500, MAX(accel_to_angle(accel_limit)*100, aparm.angle_max))); pos_control->update_xy_controller(); } @@ -2100,7 +2194,7 @@ void QuadPlane::run_xy_controller(void) void QuadPlane::poscontrol_init_approach(void) { const float dist = plane.current_loc.get_distance(plane.next_WP_loc); - if ((options & OPTION_DISABLE_APPROACH) != 0) { + if (option_is_set(QuadPlane::OPTION::DISABLE_APPROACH)) { // go straight to QPOS_POSITION1 poscontrol.set_state(QPOS_POSITION1); gcs().send_text(MAV_SEVERITY_INFO,"VTOL Position1 d=%.1f", dist); @@ -2111,8 +2205,13 @@ void QuadPlane::poscontrol_init_approach(void) if (tailsitter.enabled() || motors->get_desired_spool_state() == AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED) { gcs().send_text(MAV_SEVERITY_INFO,"VTOL Position1 d=%.1f", dist); poscontrol.set_state(QPOS_POSITION1); + transition->set_last_fw_pitch(); } else { - gcs().send_text(MAV_SEVERITY_INFO,"VTOL short d=%.1f", dist); + gcs().send_text(MAV_SEVERITY_INFO,"VTOL airbrake v=%.1f d=%.0f sd=%.0f h=%.1f", + plane.ahrs.groundspeed(), + dist, + stopping_distance(), + plane.relative_ground_altitude(plane.g.rangefinder_landing)); poscontrol.set_state(QPOS_AIRBRAKE); } } else { @@ -2121,6 +2220,9 @@ void QuadPlane::poscontrol_init_approach(void) } poscontrol.thrust_loss_start_ms = 0; } + poscontrol.pilot_correction_done = false; + poscontrol.xy_correction.zero(); + poscontrol.slow_descent = false; } /* @@ -2128,10 +2230,13 @@ void QuadPlane::poscontrol_init_approach(void) */ void QuadPlane::log_QPOS(void) { - AP::logger().WriteStreaming("QPOS", "TimeUS,State,Dist", "QBf", + AP::logger().WriteStreaming("QPOS", "TimeUS,State,Dist,TSpd,TAcc,OShoot", "QBfffB", AP_HAL::micros64(), poscontrol.get_state(), - plane.auto_state.wp_distance); + plane.auto_state.wp_distance, + poscontrol.target_speed, + poscontrol.target_accel, + poscontrol.overshoot); } /* @@ -2139,6 +2244,7 @@ void QuadPlane::log_QPOS(void) */ void QuadPlane::PosControlState::set_state(enum position_control_state s) { + const uint32_t now = AP_HAL::millis(); if (state != s) { auto &qp = plane.quadplane; pilot_correction_done = false; @@ -2148,29 +2254,33 @@ void QuadPlane::PosControlState::set_state(enum position_control_state s) // never do a rate reset, if attitude control is not active it will be automaticaly reset before running, see: last_att_control_ms // if it is active then the rate control should not be reset at all qp.attitude_control->reset_yaw_target_and_rate(false); - pos1_start_speed = plane.ahrs.groundspeed_vector().length(); - } else if (s == QPOS_POSITION2) { - // POSITION2 changes target speed, so we need to change it - // back to normal - qp.pos_control->set_max_speed_accel_xy(qp.wp_nav->get_default_speed_xy(), - qp.wp_nav->get_wp_acceleration()); - qp.pos_control->set_correction_speed_accel_xy(qp.wp_nav->get_default_speed_xy(), - qp.wp_nav->get_wp_acceleration()); + pos1_speed_limit = plane.ahrs.groundspeed_vector().length(); + done_accel_init = false; } else if (s == QPOS_AIRBRAKE) { // start with zero integrator on vertical throttle qp.pos_control->get_accel_z_pid().set_integrator(0); } else if (s == QPOS_LAND_DESCEND) { // reset throttle descent control qp.thr_ctrl_land = false; + } else if (s == QPOS_LAND_FINAL) { + // remember last pos reset to handle GPS glitch in LAND_FINAL + Vector2f rpos; + last_pos_reset_ms = plane.ahrs.getLastPosNorthEastReset(rpos); + qp.landing_detect.land_start_ms = 0; + qp.landing_detect.lower_limit_start_ms = 0; } + // double log to capture the state change + qp.log_QPOS(); + state = s; qp.log_QPOS(); + last_log_ms = now; + overshoot = false; } - state = s; - last_state_change_ms = AP_HAL::millis(); + last_state_change_ms = now; // we consider setting the state to be equivalent to running to // prevent code from overriding the state as stale - last_run_ms = last_state_change_ms; + last_run_ms = now; } /* @@ -2186,10 +2296,10 @@ void QuadPlane::vtol_position_controller(void) uint32_t now_ms = AP_HAL::millis(); // distance that we switch to QPOS_POSITION2 - const float position2_dist_threshold = 5.0; + const float position2_dist_threshold = 10.0; // target speed when we reach position2 threshold - const float position2_target_speed = 2.0; + const float position2_target_speed = 3.0; if (hal.util->get_soft_armed()) { poscontrol.last_run_ms = now_ms; @@ -2199,6 +2309,11 @@ void QuadPlane::vtol_position_controller(void) // and tilt is more than tilt max bool suppress_z_controller = false; + Vector2f landing_velocity; + if (now_ms - poscontrol.last_velocity_match_ms < 1000) { + landing_velocity = poscontrol.velocity_match; + } + // horizontal position control switch (poscontrol.get_state()) { @@ -2265,7 +2380,11 @@ void QuadPlane::vtol_position_controller(void) // use nav controller roll plane.calc_nav_roll(); - const float stop_distance = stopping_distance(); + // work out the point to enter airbrake mode. We want enough + // distance to stop, plus some margin for the time it takes to + // change the accel (jerk limit) plus the min time in airbrake + // mode. For simplicity we assume 2 seconds margin + const float stop_distance = stopping_distance() + 2*closing_speed; if (!suppress_z_controller && poscontrol.get_state() == QPOS_AIRBRAKE) { hold_hover(0); @@ -2288,6 +2407,7 @@ void QuadPlane::vtol_position_controller(void) stop_distance, plane.relative_ground_altitude(plane.g.rangefinder_landing)); poscontrol.set_state(QPOS_POSITION1); + transition->set_last_fw_pitch(); } else { gcs().send_text(MAV_SEVERITY_INFO,"VTOL airbrake v=%.1f d=%.0f sd=%.0f h=%.1f", groundspeed, @@ -2312,6 +2432,7 @@ void QuadPlane::vtol_position_controller(void) if (poscontrol.get_state() == QPOS_AIRBRAKE && poscontrol.time_since_state_start_ms() > min_airbrake_ms && (aspeed < aspeed_threshold || + fabsf(degrees(closing_vel.angle(desired_closing_vel))) > 60 || closing_speed > MAX(desired_closing_speed*1.2, desired_closing_speed+2) || labs(plane.ahrs.roll_sensor - plane.nav_roll_cd) > attitude_error_threshold_cd || labs(plane.ahrs.pitch_sensor - plane.nav_pitch_cd) > attitude_error_threshold_cd)) { @@ -2321,6 +2442,7 @@ void QuadPlane::vtol_position_controller(void) plane.relative_ground_altitude(plane.g.rangefinder_landing), desired_closing_speed); poscontrol.set_state(QPOS_POSITION1); + transition->set_last_fw_pitch(); // switch to vfwd for throttle control vel_forward.integrator = SRV_Channels::get_output_scaled(SRV_Channel::k_throttle); @@ -2344,6 +2466,7 @@ void QuadPlane::vtol_position_controller(void) gcs().send_text(MAV_SEVERITY_INFO,"VTOL pos1 thrust loss as=%.1f at=%.1f", aspeed, aspeed_threshold); poscontrol.set_state(QPOS_POSITION1); + transition->set_last_fw_pitch(); } } else { poscontrol.thrust_loss_start_ms = 0; @@ -2355,6 +2478,7 @@ void QuadPlane::vtol_position_controller(void) gcs().send_text(MAV_SEVERITY_INFO,"VTOL pos1 low speed as=%.1f at=%.1f", aspeed, aspeed_threshold); poscontrol.set_state(QPOS_POSITION1); + transition->set_last_fw_pitch(); } } @@ -2374,6 +2498,13 @@ void QuadPlane::vtol_position_controller(void) const Vector2f diff_wp = plane.current_loc.get_distance_NE(loc); const float distance = diff_wp.length(); + const Vector2f rel_groundspeed_vector = landing_closing_velocity(); + const float rel_groundspeed_sq = rel_groundspeed_vector.length_squared(); + float closing_groundspeed = 0; + + if (distance > 0.1) { + closing_groundspeed = rel_groundspeed_vector * diff_wp.normalized(); + } // calculate speed we should be at to reach the position2 // target speed at the position2 distance threshold, assuming @@ -2383,15 +2514,16 @@ void QuadPlane::vtol_position_controller(void) float target_speed = stopping_speed; // maximum configured VTOL speed - const float wp_speed = wp_nav->get_default_speed_xy() * 0.01; - const float current_speed_sq = plane.ahrs.groundspeed_vector().length_squared(); + const float wp_speed = MAX(1.0, wp_nav->get_default_speed_xy() * 0.01); const float scaled_wp_speed = get_scaled_wp_speed(degrees(diff_wp.angle())); - // limit target speed to initial pos1 speed, but at least twice the Q_WP_SPEED - target_speed = MIN(MAX(poscontrol.pos1_start_speed, 2*wp_speed), target_speed); + // limit target speed to a the pos1 speed limit, which starts out at the initial speed + // but is adjusted if we start putting our nose down. We always allow at least twice + // the WP speed + target_speed = MIN(MAX(poscontrol.pos1_speed_limit, 2*wp_speed), target_speed); if (poscontrol.reached_wp_speed || - current_speed_sq < sq(wp_speed) || + rel_groundspeed_sq < sq(wp_speed) || wp_speed > 1.35*scaled_wp_speed) { // once we get below the Q_WP_SPEED then we don't want to // speed up again. At that point we should fly within the @@ -2407,26 +2539,82 @@ void QuadPlane::vtol_position_controller(void) plane.nav_controller->update_waypoint(plane.current_loc, loc); Vector2f target_speed_xy_cms; + Vector2f target_accel_cms; + bool have_target_yaw = false; + float target_yaw_deg; + const float target_accel = MIN(accel_needed(distance, sq(closing_groundspeed)), transition_decel*2); if (distance > 0.1) { - target_speed_xy_cms = diff_wp.normalized() * target_speed * 100; + Vector2f diff_wp_norm = diff_wp.normalized(); + target_speed_xy_cms = diff_wp_norm * target_speed * 100; + target_accel_cms = diff_wp_norm * (-target_accel*100); + target_yaw_deg = degrees(diff_wp_norm.angle()); + const float yaw_err_deg = wrap_180(target_yaw_deg - degrees(plane.ahrs.yaw)); + bool overshoot = (closing_groundspeed < 0 || fabsf(yaw_err_deg) > 60); + if (overshoot && !poscontrol.overshoot) { + gcs().send_text(MAV_SEVERITY_INFO,"VTOL Overshoot d=%.1f cs=%.1f yerr=%.1f", + distance, closing_groundspeed, yaw_err_deg); + poscontrol.overshoot = true; + pos_control->set_accel_desired_xy_cmss(Vector2f()); + } + if (poscontrol.overshoot) { + /* we have overshot the landing point or our nose is + off by more than 60 degrees. Zero target accel and + point nose at the landing point. Set target speed + to our position2 threshold speed + */ + target_accel_cms.zero(); + + // allow up to the WP speed when we are further away, slowing to the pos2 target speed + // when we are close + target_speed = linear_interpolate(position2_target_speed, wp_speed, + distance, + position2_dist_threshold*1.5, + 2*position2_dist_threshold + stopping_distance(rel_groundspeed_sq)); + + target_speed_xy_cms = diff_wp_norm * target_speed * 100; + have_target_yaw = true; + + // adjust target yaw angle for wind. We calculate yaw based on the target speed + // we want assuming no speed scaling due to direction + const Vector2f wind = plane.ahrs.wind_estimate().xy(); + const float gnd_speed = plane.ahrs.groundspeed(); + Vector2f target_speed_xy = landing_velocity + diff_wp_norm * gnd_speed - wind; + target_yaw_deg = degrees(target_speed_xy.angle()); + } } - if (!tailsitter.enabled()) { - // this method ignores pos-control velocity/accel limtis - pos_control->set_vel_desired_xy_cms(target_speed_xy_cms); - - // reset position controller xy target to current position - // because we only want velocity control (no position control) - const Vector2f& curr_pos = inertial_nav.get_position_xy_cm(); - pos_control->set_pos_target_xy_cm(curr_pos.x, curr_pos.y); - pos_control->set_accel_desired_xy_cmss(Vector2f()); - } else { - // tailsitters use input shaping and abide by velocity limits - pos_control->input_vel_accel_xy(target_speed_xy_cms, Vector2f()); + const float target_speed_ms = target_speed_xy_cms.length() * 0.01; + + target_speed_xy_cms += landing_velocity * 100; + poscontrol.target_speed = target_speed_ms; + poscontrol.target_accel = target_accel; + + if (!poscontrol.reached_wp_speed && + rel_groundspeed_sq < sq(target_speed_ms) && + rel_groundspeed_sq > sq(2*wp_speed) && + plane.nav_pitch_cd < 0) { + // we have slowed down more than expected, likely due to + // drag from the props and we're starting to put our nose + // down as a result. We want to accept the slowdown and + // re-calculate the target speed profile + poscontrol.pos1_speed_limit = sqrtf(rel_groundspeed_sq); } + // use input shaping and abide by accel and jerk limits + pos_control->input_vel_accel_xy(target_speed_xy_cms, target_accel_cms); + // run horizontal velocity controller - run_xy_controller(); + run_xy_controller(MAX(target_accel, transition_decel)*1.5); + if (!poscontrol.done_accel_init) { + /* + the pos controller init assumes zero accel, we need to + override that so that we can start decelerating more + quickly at the start of POSITION1 + */ + poscontrol.done_accel_init = true; + pos_control->set_accel_desired_xy_cmss(target_accel_cms); + } + // nav roll and pitch are controller by position controller plane.nav_roll_cd = pos_control->get_roll_cd(); plane.nav_pitch_cd = pos_control->get_pitch_cd(); @@ -2436,10 +2624,22 @@ void QuadPlane::vtol_position_controller(void) } // call attitude controller - attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(plane.nav_roll_cd, - plane.nav_pitch_cd, - desired_auto_yaw_rate_cds() + get_weathervane_yaw_rate_cds()); - if ((plane.auto_state.wp_distance < position2_dist_threshold) && tiltrotor.tilt_angle_achieved()) { + disable_yaw_rate_time_constant(); + + // setup scaling of roll and pitch angle P gains to match fixed wing gains + setup_rp_fw_angle_gains(); + + if (have_target_yaw) { + attitude_control->input_euler_angle_roll_pitch_yaw(plane.nav_roll_cd, + plane.nav_pitch_cd, + target_yaw_deg*100, true); + } else { + attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(plane.nav_roll_cd, + plane.nav_pitch_cd, + desired_auto_yaw_rate_cds() + get_weathervane_yaw_rate_cds()); + } + if ((plane.auto_state.wp_distance < position2_dist_threshold) && tiltrotor.tilt_angle_achieved() && + fabsf(rel_groundspeed_sq) < sq(3*position2_target_speed)) { // if continuous tiltrotor only advance to position 2 once tilts have finished moving poscontrol.set_state(QPOS_POSITION2); poscontrol.pilot_correction_done = false; @@ -2452,36 +2652,20 @@ void QuadPlane::vtol_position_controller(void) case QPOS_POSITION2: case QPOS_LAND_DESCEND: { + setup_target_position(); /* for final land repositioning and descent we run the position controller */ - if (poscontrol.pilot_correction_done) { - // if the pilot has repositioned the vehicle then we switch to velocity control. This prevents the vehicle - // shifting position in the event of GPS glitches. - Vector2f zero; - pos_control->input_vel_accel_xy(poscontrol.target_vel_cms.xy(), zero); - } else { - Vector2f zero; - pos_control->input_pos_vel_accel_xy(poscontrol.target_cm.xy(), zero, zero); - } + Vector2f zero; + Vector2f vel_cms = poscontrol.target_vel_cms.xy() + landing_velocity*100; + pos_control->input_pos_vel_accel_xy(poscontrol.target_cm.xy(), vel_cms, zero); // also run fixed wing navigation plane.nav_controller->update_waypoint(plane.current_loc, loc); update_land_positioning(); - /* - apply the same asymmetric speed limits from POSITION1, so we - don't suddenly speed up when we change to POSITION2 and - LAND_DESCEND - */ - const Vector2f diff_wp = plane.current_loc.get_distance_NE(loc); - const float scaled_wp_speed = get_scaled_wp_speed(degrees(diff_wp.angle())); - - pos_control->set_max_speed_accel_xy(scaled_wp_speed*100, wp_nav->get_wp_acceleration()); - pos_control->set_correction_speed_accel_xy(scaled_wp_speed*100, wp_nav->get_wp_acceleration()); - - run_xy_controller(); + run_xy_controller(transition_decel*1.5); // nav roll and pitch are controlled by position controller plane.nav_roll_cd = pos_control->get_roll_cd(); @@ -2492,6 +2676,7 @@ void QuadPlane::vtol_position_controller(void) } // call attitude controller + set_pilot_yaw_rate_time_constant(); attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(plane.nav_roll_cd, plane.nav_pitch_cd, get_pilot_input_yaw_rate_cds() + get_weathervane_yaw_rate_cds()); @@ -2505,9 +2690,23 @@ void QuadPlane::vtol_position_controller(void) if (should_relax()) { pos_control->relax_velocity_controller_xy(); } else { - // we use velocity control in QPOS_LAND_FINAL to allow for GPS glitch handling Vector2f zero; - pos_control->input_vel_accel_xy(poscontrol.target_vel_cms.xy(), zero); + Vector2f vel_cms = poscontrol.target_vel_cms.xy() + landing_velocity*100; + Vector2f rpos; + const uint32_t last_reset_ms = plane.ahrs.getLastPosNorthEastReset(rpos); + /* we use velocity control when we may be touching the + ground or if we've had a position reset from AHRS. This + helps us handle a GPS glitch in the final land phase, + and also prevents trying to reposition after touchdown + */ + if (motors->limit.throttle_lower || + motors->get_throttle() < 0.5*motors->get_throttle_hover() || + last_reset_ms != poscontrol.last_pos_reset_ms) { + pos_control->input_vel_accel_xy(vel_cms, zero); + } else { + // otherwise use full pos control + pos_control->input_pos_vel_accel_xy(poscontrol.target_cm.xy(), vel_cms, zero); + } } run_xy_controller(); @@ -2517,6 +2716,7 @@ void QuadPlane::vtol_position_controller(void) plane.nav_pitch_cd = pos_control->get_pitch_cd(); // call attitude controller + set_pilot_yaw_rate_time_constant(); attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(plane.nav_roll_cd, plane.nav_pitch_cd, get_pilot_input_yaw_rate_cds() + get_weathervane_yaw_rate_cds()); @@ -2596,7 +2796,7 @@ void QuadPlane::vtol_position_controller(void) float zero = 0; pos_control->input_pos_vel_accel_z(target_z, zero, 0); } else { - set_climb_rate_cms(0, false); + set_climb_rate_cms(0); } break; } @@ -2605,12 +2805,12 @@ void QuadPlane::vtol_position_controller(void) case QPOS_LAND_FINAL: { float height_above_ground = plane.relative_ground_altitude(plane.g.rangefinder_landing); if (poscontrol.get_state() == QPOS_LAND_FINAL) { - if ((options & OPTION_DISABLE_GROUND_EFFECT_COMP) == 0) { + if (!option_is_set(QuadPlane::OPTION::DISABLE_GROUND_EFFECT_COMP)) { ahrs.set_touchdown_expected(true); } } const float descent_rate_cms = landing_descent_rate_cms(height_above_ground); - set_climb_rate_cms(-descent_rate_cms, descent_rate_cms>0); + pos_control->land_at_climb_rate_cm(-descent_rate_cms, descent_rate_cms>0); break; } @@ -2668,20 +2868,12 @@ void QuadPlane::setup_target_position(void) set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); } - const Vector2f diff2d = origin.get_distance_NE(loc); + Vector2f diff2d = origin.get_distance_NE(loc); + diff2d += poscontrol.xy_correction; poscontrol.target_cm.x = diff2d.x * 100; poscontrol.target_cm.y = diff2d.y * 100; poscontrol.target_cm.z = plane.next_WP_loc.alt - origin.alt; - const uint32_t now = AP_HAL::millis(); - if (!loc.same_latlon_as(last_auto_target) || - plane.next_WP_loc.alt != last_auto_target.alt || - now - last_loiter_ms > 500) { - wp_nav->set_wp_destination(poscontrol.target_cm.tofloat()); - last_auto_target = loc; - } - last_loiter_ms = now; - // set vertical speed and acceleration limits pos_control->set_max_speed_accel_z(-get_pilot_velocity_z_max_dn(), pilot_velocity_z_max_up, pilot_accel_z); pos_control->set_correction_speed_accel_z(-get_pilot_velocity_z_max_dn(), pilot_velocity_z_max_up, pilot_accel_z); @@ -2692,31 +2884,69 @@ void QuadPlane::setup_target_position(void) */ void QuadPlane::takeoff_controller(void) { + if (!hal.util->get_soft_armed()) { + return; + } + + if (plane.control_mode == &plane.mode_guided && guided_takeoff + && tiltrotor.enabled() && !tiltrotor.fully_up()) { + // waiting for motors to tilt up + return; + } + /* for takeoff we use the position controller */ setup_target_position(); - // set position controller desired velocity and acceleration to zero - pos_control->set_vel_desired_xy_cms(Vector2f()); - pos_control->set_accel_desired_xy_cmss(Vector2f()); - // set position control target and update - Vector2f zero; - pos_control->input_vel_accel_xy(zero, zero); - run_xy_controller(); + Vector2f vel, zero; + if (AP_HAL::millis() - poscontrol.last_velocity_match_ms < 1000) { + vel = poscontrol.velocity_match * 100; + } + + /* + support zeroing roll/pitch during early part of takeoff. This + can help particularly with poor GPS velocity data + */ + bool no_navigation = false; + if (takeoff_navalt_min > 0) { + uint32_t now = AP_HAL::millis(); + const float alt = plane.current_loc.alt*0.01; + if (takeoff_last_run_ms == 0 || + now - takeoff_last_run_ms > 1000) { + takeoff_start_alt = alt; + } + takeoff_last_run_ms = now; + if (alt - takeoff_start_alt < takeoff_navalt_min) { + no_navigation = true; + } + } + + if (no_navigation) { + plane.nav_roll_cd = 0; + plane.nav_pitch_cd = 0; + pos_control->relax_velocity_controller_xy(); + } else { + pos_control->set_accel_desired_xy_cmss(zero); + pos_control->set_vel_desired_xy_cms(vel); + pos_control->input_vel_accel_xy(vel, zero); + + // nav roll and pitch are controller by position controller + plane.nav_roll_cd = pos_control->get_roll_cd(); + plane.nav_pitch_cd = pos_control->get_pitch_cd(); + } - // nav roll and pitch are controller by position controller - plane.nav_roll_cd = pos_control->get_roll_cd(); - plane.nav_pitch_cd = pos_control->get_pitch_cd(); + run_xy_controller(); + set_pilot_yaw_rate_time_constant(); attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(plane.nav_roll_cd, plane.nav_pitch_cd, get_pilot_input_yaw_rate_cds() + get_weathervane_yaw_rate_cds()); float vel_z = wp_nav->get_default_speed_up(); - if (guided_takeoff) { + if (plane.control_mode == &plane.mode_guided && guided_takeoff) { // for guided takeoff we aim for a specific height with zero // velocity at that height Location origin; @@ -2728,10 +2958,10 @@ void QuadPlane::takeoff_controller(void) vel_z = 0; pos_control->input_pos_vel_accel_z(pos_z, vel_z, 0); } else { - set_climb_rate_cms(vel_z, false); + set_climb_rate_cms(vel_z); } } else { - set_climb_rate_cms(vel_z, false); + set_climb_rate_cms(vel_z); } run_z_controller(); @@ -2744,6 +2974,16 @@ void QuadPlane::waypoint_controller(void) { setup_target_position(); + const Location &loc = plane.next_WP_loc; + const uint32_t now = AP_HAL::millis(); + if (!loc.same_latlon_as(last_auto_target) || + plane.next_WP_loc.alt != last_auto_target.alt || + now - last_loiter_ms > 500) { + wp_nav->set_wp_destination(poscontrol.target_cm.tofloat()); + last_auto_target = loc; + } + last_loiter_ms = now; + /* this is full copter control of auto flight */ @@ -2759,13 +2999,14 @@ void QuadPlane::waypoint_controller(void) } // call attitude controller + disable_yaw_rate_time_constant(); attitude_control->input_euler_angle_roll_pitch_yaw(plane.nav_roll_cd, plane.nav_pitch_cd, wp_nav->get_yaw(), true); // climb based on altitude error - set_climb_rate_cms(assist_climb_rate_cms(), false); + set_climb_rate_cms(assist_climb_rate_cms()); run_z_controller(); } @@ -2833,7 +3074,7 @@ bool QuadPlane::do_vtol_takeoff(const AP_Mission::Mission_Command& cmd) loc.lat = 0; loc.lng = 0; plane.set_next_WP(loc); - if (options & OPTION_RESPECT_TAKEOFF_FRAME) { + if (option_is_set(QuadPlane::OPTION::RESPECT_TAKEOFF_FRAME)) { if (plane.current_loc.alt >= plane.next_WP_loc.alt) { // we are above the takeoff already, no need to do anything return false; @@ -2927,7 +3168,7 @@ bool QuadPlane::verify_vtol_takeoff(const AP_Mission::Mission_Command &cmd) } if (now - takeoff_start_time_ms < 3000 && - (options & OPTION_DISABLE_GROUND_EFFECT_COMP) == 0) { + !option_is_set(QuadPlane::OPTION::DISABLE_GROUND_EFFECT_COMP)) { ahrs.set_takeoff_expected(true); } @@ -2938,11 +3179,13 @@ bool QuadPlane::verify_vtol_takeoff(const AP_Mission::Mission_Command &cmd) return false; } +#if AP_AIRSPEED_ENABLED if (is_positive(maximum_takeoff_airspeed) && (plane.airspeed.get_airspeed() > maximum_takeoff_airspeed)) { gcs().send_text(MAV_SEVERITY_CRITICAL, "Failed to complete takeoff, excessive wind"); plane.set_mode(plane.mode_qland, ModeReason::VTOL_FAILED_TAKEOFF); return false; } +#endif if (plane.current_loc.alt < plane.next_WP_loc.alt) { return false; @@ -2953,7 +3196,7 @@ bool QuadPlane::verify_vtol_takeoff(const AP_Mission::Mission_Command &cmd) // todo: why are you doing this, I want to delete it. set_alt_target_current(); -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED plane.fence.auto_enable_fence_after_takeoff(); #endif @@ -2975,13 +3218,12 @@ bool QuadPlane::verify_vtol_takeoff(const AP_Mission::Mission_Command &cmd) */ bool QuadPlane::land_detector(uint32_t timeout_ms) { - const uint32_t now = AP_HAL::millis(); - bool might_be_landed = (landing_detect.lower_limit_start_ms != 0 && - now - landing_detect.lower_limit_start_ms > 1000); + bool might_be_landed = should_relax() && !poscontrol.pilot_correction_active; if (!might_be_landed) { landing_detect.land_start_ms = 0; return false; } + const uint32_t now = AP_HAL::millis(); float height = inertial_nav.get_position_z_up_cm() * 0.01; if (landing_detect.land_start_ms == 0) { landing_detect.land_start_ms = now; @@ -2991,7 +3233,7 @@ bool QuadPlane::land_detector(uint32_t timeout_ms) // we only consider the vehicle landed when the motors have been // at minimum for timeout_ms+1000 and the vertical position estimate has not // changed by more than 20cm for timeout_ms - if (fabsf(height - landing_detect.vpos_start_m) > 0.2) { + if (fabsf(height - landing_detect.vpos_start_m) > landing_detect.detect_alt_change) { // height has changed, call off landing detection landing_detect.land_start_ms = 0; return false; @@ -3073,11 +3315,20 @@ bool QuadPlane::verify_vtol_land(void) const float dist = (inertial_nav.get_position_neu_cm().topostype() - poscontrol.target_cm).xy().length() * 0.01; reached_position = dist < descend_dist_threshold; } + Vector2f target_vel; + if (AP_HAL::millis() - poscontrol.last_velocity_match_ms < 1000) { + target_vel = poscontrol.velocity_match; + } + Vector3f vel_ned; + UNUSED_RESULT(plane.ahrs.get_velocity_NED(vel_ned)); + if (reached_position && - plane.ahrs.groundspeed() < descend_speed_threshold) { + (vel_ned.xy() - target_vel).length() < descend_speed_threshold) { poscontrol.set_state(QPOS_LAND_DESCEND); poscontrol.pilot_correction_done = false; -#if AC_FENCE == ENABLED + pos_control->set_lean_angle_max_cd(0); + poscontrol.xy_correction.zero(); +#if AP_FENCE_ENABLED plane.fence.auto_disable_fence_for_landing(); #endif #if LANDING_GEAR_ENABLED == ENABLED @@ -3101,10 +3352,12 @@ bool QuadPlane::verify_vtol_land(void) if (poscontrol.get_state() == QPOS_LAND_DESCEND && check_land_final()) { poscontrol.set_state(QPOS_LAND_FINAL); +#if AP_ICENGINE_ENABLED // cut IC engine if enabled if (land_icengine_cut != 0) { plane.g2.ice_control.engine_control(0, 0, 0); } +#endif // AP_ICENGINE_ENABLED gcs().send_text(MAV_SEVERITY_INFO,"Land final started"); } @@ -3121,7 +3374,7 @@ void QuadPlane::Log_Write_QControl_Tuning() float des_alt_m = 0.0f; int16_t target_climb_rate_cms = 0; if (plane.control_mode != &plane.mode_qstabilize) { - des_alt_m = pos_control->get_pos_target_z_cm() / 100.0f; + des_alt_m = pos_control->get_pos_target_z_cm() * 0.01f; target_climb_rate_cms = pos_control->get_vel_target_z_cms(); } @@ -3139,7 +3392,7 @@ void QuadPlane::Log_Write_QControl_Tuning() climb_rate : int16_t(inertial_nav.get_velocity_z_up_cms()), throttle_mix : attitude_control->get_throttle_mix(), speed_scaler : tailsitter.log_spd_scaler, - transition_state : transition->get_log_transision_state(), + transition_state : transition->get_log_transition_state(), assist : assisted_flight, }; plane.logger.WriteBlock(&pkt, sizeof(pkt)); @@ -3302,11 +3555,11 @@ float QuadPlane::get_weathervane_yaw_rate_cds(void) if (weathervane->get_yaw_out(wv_output, plane.channel_rudder->get_control_in(), plane.relative_ground_altitude(plane.g.rangefinder_landing), - wp_nav->get_roll(), - wp_nav->get_pitch(), + pos_control->get_roll_cd(), + pos_control->get_pitch_cd(), is_takeoff, in_vtol_land_sequence())) { - return constrain_float(wv_output / 45, -100.0, 100.0) * yaw_rate_max * 0.5; + return constrain_float(wv_output * (1/45.0), -100.0, 100.0) * command_model_pilot.get_rate() * 0.5; } return 0.0; @@ -3321,13 +3574,13 @@ void QuadPlane::guided_start(void) setup_target_position(); int32_t from_alt; int32_t to_alt; + poscontrol_init_approach(); if (plane.current_loc.get_alt_cm(Location::AltFrame::ABSOLUTE,from_alt) && plane.next_WP_loc.get_alt_cm(Location::AltFrame::ABSOLUTE,to_alt)) { poscontrol.slow_descent = from_alt > to_alt; } else { // default back to old method poscontrol.slow_descent = (plane.current_loc.alt > plane.next_WP_loc.alt); } - poscontrol_init_approach(); } /* @@ -3407,7 +3660,8 @@ bool QuadPlane::do_user_takeoff(float takeoff_altitude) set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); guided_start(); guided_takeoff = true; - if ((options & OPTION_DISABLE_GROUND_EFFECT_COMP) == 0) { + guided_wait_takeoff = false; + if (!option_is_set(QuadPlane::OPTION::DISABLE_GROUND_EFFECT_COMP)) { ahrs.set_takeoff_expected(true); } return true; @@ -3419,12 +3673,6 @@ bool QuadPlane::using_wp_nav(void) const if (plane.control_mode == &plane.mode_qloiter || plane.control_mode == &plane.mode_qland) { return true; } - if (plane.control_mode == &plane.mode_qrtl && poscontrol.get_state() >= QPOS_POSITION2) { - return true; - } - if (plane.control_mode == &plane.mode_auto && poscontrol.get_state() > QPOS_APPROACH) { - return true; - } return false; } @@ -3447,7 +3695,7 @@ bool QuadPlane::is_vtol_takeoff(uint16_t id) const if (id == MAV_CMD_NAV_VTOL_TAKEOFF) { return true; } - if (id == MAV_CMD_NAV_TAKEOFF && available() && (options & OPTION_ALLOW_FW_TAKEOFF) == 0) { + if (id == MAV_CMD_NAV_TAKEOFF && available() && !option_is_set(QuadPlane::OPTION::ALLOW_FW_TAKEOFF)) { // treat fixed wing takeoff as VTOL takeoff return true; } @@ -3460,13 +3708,13 @@ bool QuadPlane::is_vtol_takeoff(uint16_t id) const bool QuadPlane::is_vtol_land(uint16_t id) const { if (id == MAV_CMD_NAV_VTOL_LAND) { - if (options & QuadPlane::OPTION_MISSION_LAND_FW_APPROACH) { + if (landing_with_fixed_wing_spiral_approach()) { return plane.vtol_approach_s.approach_stage == Plane::Landing_ApproachStage::VTOL_LANDING; } else { return true; } } - if (id == MAV_CMD_NAV_LAND && available() && (options & OPTION_ALLOW_FW_LAND) == 0) { + if (id == MAV_CMD_NAV_LAND && available() && !option_is_set(QuadPlane::OPTION::ALLOW_FW_LAND)) { // treat fixed wing land as VTOL land return true; } @@ -3484,7 +3732,7 @@ bool QuadPlane::in_transition(void) const /* calculate current stopping distance for a quadplane in fixed wing flight */ -float QuadPlane::stopping_distance(float ground_speed_squared) +float QuadPlane::stopping_distance(float ground_speed_squared) const { // use v^2/(2*accel). This is only quite approximate as the drag // varies with pitch, but it gives something for the user to @@ -3492,6 +3740,14 @@ float QuadPlane::stopping_distance(float ground_speed_squared) return ground_speed_squared / (2 * transition_decel); } +/* + calculate acceleration needed to stop in the given distance given current speed + */ +float QuadPlane::accel_needed(float stop_distance, float ground_speed_squared) const +{ + return ground_speed_squared / (2 * MAX(1,stop_distance)); +} + /* calculate current stopping distance for a quadplane in fixed wing flight */ @@ -3517,7 +3773,7 @@ float QuadPlane::transition_threshold(void) void QuadPlane::update_throttle_mix(void) { // update filtered acceleration - Vector3f accel_ef = ahrs.get_accel_ef_blended(); + Vector3f accel_ef = ahrs.get_accel_ef(); accel_ef.z += GRAVITY_MSS; throttle_mix_accel_ef_filter.apply(accel_ef, plane.scheduler.get_loop_period_s()); @@ -3556,7 +3812,17 @@ void QuadPlane::update_throttle_mix(void) // check for requested descent bool descent_not_demanded = pos_control->get_vel_desired_cms().z >= 0.0f; - if (large_angle_request || large_angle_error || accel_moving || descent_not_demanded) { + bool use_mix_max = large_angle_request || large_angle_error || accel_moving || descent_not_demanded; + + /* + special case for auto landing, we want a high degree of + attitude control until LAND_FINAL + */ + if (in_vtol_land_sequence()) { + use_mix_max = !in_vtol_land_final(); + } + + if (use_mix_max) { attitude_control->set_throttle_mix_max(1.0); } else { attitude_control->set_throttle_mix_min(); @@ -3629,6 +3895,23 @@ bool QuadPlane::in_vtol_land_poscontrol(void) const return false; } +/* + see if we are in the airbrake phase of a VTOL landing + */ +bool QuadPlane::in_vtol_airbrake(void) const +{ + if (plane.control_mode == &plane.mode_qrtl && + poscontrol.get_state() == QPOS_AIRBRAKE) { + return true; + } + if (plane.control_mode == &plane.mode_auto && + is_vtol_land(plane.mission.get_current_nav_cmd().id) && + poscontrol.get_state() == QPOS_AIRBRAKE) { + return true; + } + return false; +} + // return true if we should show VTOL view bool QuadPlane::show_vtol_view() const { @@ -3670,14 +3953,16 @@ bool QuadPlane::use_fw_attitude_controllers(void) const } /* - calculate our closing velocity vector on the landing point. In the - future this will take account of the landing point having a - velocity + calculate our closing velocity vector on the landing point, taking + into account target velocity */ Vector2f QuadPlane::landing_closing_velocity() { - Vector2f vel = ahrs.groundspeed_vector(); - return vel; + Vector2f landing_velocity; + if (AP_HAL::millis() - poscontrol.last_velocity_match_ms < 1000) { + landing_velocity = poscontrol.velocity_match; + } + return ahrs.groundspeed_vector() - landing_velocity; } /* @@ -3696,6 +3981,16 @@ Vector2f QuadPlane::landing_desired_closing_velocity() // base target speed based on sqrt of distance float target_speed = safe_sqrt(2*transition_decel*dist); + + // don't let the target speed go above landing approach speed + const float eas2tas = plane.ahrs.get_EAS2TAS(); + float land_speed = plane.aparm.airspeed_cruise_cm * 0.01; + float tecs_land_airspeed = plane.TECS_controller.get_land_airspeed(); + if (is_positive(tecs_land_airspeed)) { + land_speed = tecs_land_airspeed; + } + target_speed = MIN(target_speed, eas2tas * land_speed); + Vector2f target_speed_xy = diff_wp.normalized() * target_speed; return target_speed_xy; @@ -3706,26 +4001,38 @@ Vector2f QuadPlane::landing_desired_closing_velocity() */ float QuadPlane::get_land_airspeed(void) { - if (poscontrol.get_state() == QPOS_APPROACH || + const auto qstate = poscontrol.get_state(); + if (qstate == QPOS_APPROACH || plane.control_mode == &plane.mode_rtl) { - float land_airspeed = plane.TECS_controller.get_land_airspeed(); - if (!is_positive(land_airspeed)) { - land_airspeed = plane.aparm.airspeed_cruise_cm * 0.01; + const float cruise_speed = plane.aparm.airspeed_cruise_cm * 0.01; + float approach_speed = cruise_speed; + float tecs_land_airspeed = plane.TECS_controller.get_land_airspeed(); + if (is_positive(tecs_land_airspeed)) { + approach_speed = tecs_land_airspeed; + } else { + if (qstate == QPOS_APPROACH) { + // default to half way between min airspeed and cruise + // airspeed when on the approach + approach_speed = 0.5*(cruise_speed+plane.aparm.airspeed_min); + } else { + // otherwise cruise + approach_speed = cruise_speed; + } } - float cruise_airspeed = plane.aparm.airspeed_cruise_cm * 0.01; - float time_to_landing = plane.auto_state.wp_distance / MAX(land_airspeed, 5); + const float time_to_pos1 = (plane.auto_state.wp_distance - stopping_distance(sq(approach_speed))) / MAX(approach_speed, 5); /* slow down to landing approach speed as we get closer to landing - */ - land_airspeed = linear_interpolate(land_airspeed, cruise_airspeed, - time_to_landing, - 20, 60); - return land_airspeed; + */ + approach_speed = linear_interpolate(approach_speed, cruise_speed, + time_to_pos1, + 20, 60); + return approach_speed; } - Vector2f vel = landing_desired_closing_velocity(); - const float eas2tas = plane.ahrs.get_EAS2TAS(); + // calculate speed based on landing desired velocity + Vector2f vel = landing_desired_closing_velocity(); const Vector3f wind = plane.ahrs.wind_estimate(); + const float eas2tas = plane.ahrs.get_EAS2TAS(); vel.x -= wind.x; vel.y -= wind.y; vel /= eas2tas; @@ -3735,6 +4042,13 @@ float QuadPlane::get_land_airspeed(void) void QuadPlane::set_desired_spool_state(AP_Motors::DesiredSpoolState state) { if (motors->get_desired_spool_state() != state) { + if (state == AP_Motors::DesiredSpoolState::SHUT_DOWN) { + // also request zero throttle, so we avoid the slow ramp down + motors->set_roll(0); + motors->set_pitch(0); + motors->set_yaw(0); + motors->set_throttle(0); + } motors->set_desired_spool_state(state); } } @@ -3765,7 +4079,7 @@ QuadPlane *QuadPlane::_singleton = nullptr; bool SLT_Transition::set_FW_roll_limit(int32_t& roll_limit_cd) { if (quadplane.assisted_flight && (transition_state == TRANSITION_AIRSPEED_WAIT || transition_state == TRANSITION_TIMER) && - (quadplane.options & QuadPlane::OPTION_LEVEL_TRANSITION)) { + quadplane.option_is_set(QuadPlane::OPTION::LEVEL_TRANSITION)) { // the user wants transitions to be kept level to within LEVEL_ROLL_LIMIT roll_limit_cd = MIN(roll_limit_cd, plane.g.level_roll_limit*100); return true; @@ -3784,24 +4098,77 @@ bool SLT_Transition::active() const return quadplane.assisted_flight && ((transition_state == TRANSITION_AIRSPEED_WAIT) || (transition_state == TRANSITION_TIMER)); } +/* + limit VTOL roll/pitch in POSITION1, POSITION2 and waypoint controller. This serves three roles: + 1) an expanding envelope limit on pitch to prevent sudden pitch at the start of a back transition + + 2) limiting roll and pitch down to the Q_ANGLE_MAX, as the accel limits may push us beyond that for pitch up. + This is needed as the position controller doesn't have separate limits for pitch and roll + + 3) preventing us pitching up a lot when our airspeed may be low + enough that the real airspeed may be negative, which would result + in reversed control surfaces + */ bool SLT_Transition::set_VTOL_roll_pitch_limit(int32_t& roll_cd, int32_t& pitch_cd) { + bool ret = false; + const int16_t angle_max = quadplane.aparm.angle_max; + + /* + we always limit roll to Q_ANGLE_MAX + */ + int32_t new_roll_cd = constrain_int32(roll_cd, -angle_max, angle_max); + if (new_roll_cd != roll_cd) { + roll_cd = new_roll_cd; + ret = true; + } + + /* + always limit pitch down to Q_ANGLE_MAX. We need to do this as + the position controller accel limits may exceed this limit + */ + if (pitch_cd < -angle_max) { + pitch_cd = -angle_max; + ret = true; + } + + /* + prevent trying to fly backwards (negative airspeed) at high + pitch angles, which can result in a high degree of instability + in SLT aircraft. This can happen with a tailwind in a back + transition, where the position controller (which is unaware of + airspeed) demands high pitch to hit the desired landing point + */ + float airspeed; + if (pitch_cd > angle_max && + plane.ahrs.airspeed_estimate(airspeed) && airspeed < 0.5 * plane.aparm.airspeed_min) { + const float max_limit_cd = linear_interpolate(angle_max, 4500, + airspeed, + 0, 0.5 * plane.aparm.airspeed_min); + if (pitch_cd > max_limit_cd) { + pitch_cd = max_limit_cd; + ret = true; + } + } + if (quadplane.back_trans_pitch_limit_ms <= 0) { - // disabled - return false; + // time based pitch envelope disabled + return ret; } - uint32_t limit_time_ms = quadplane.back_trans_pitch_limit_ms; - const uint32_t now = AP_HAL::millis(); - if (now - last_fw_mode_ms > limit_time_ms) { - // past transition period, nothing to do - return false; + const uint32_t limit_time_ms = quadplane.back_trans_pitch_limit_ms; + + const uint32_t dt = AP_HAL::millis() - last_fw_mode_ms; + if (last_fw_mode_ms == 0 || dt > limit_time_ms) { + // we are beyond the time limit, don't apply envelope + last_fw_mode_ms = 0; + return ret; } // we limit pitch during initial transition - float max_limit_cd = linear_interpolate(MAX(last_fw_nav_pitch_cd,0), MIN(quadplane.aparm.angle_max,plane.aparm.pitch_limit_max_cd), - now, - last_fw_mode_ms, last_fw_mode_ms+limit_time_ms); + const float max_limit_cd = linear_interpolate(MAX(last_fw_nav_pitch_cd,0), MIN(angle_max,plane.aparm.pitch_limit_max_cd), + dt, + 0, limit_time_ms); if (pitch_cd > max_limit_cd) { pitch_cd = max_limit_cd; @@ -3819,26 +4186,34 @@ bool SLT_Transition::set_VTOL_roll_pitch_limit(int32_t& roll_cd, int32_t& pitch_ to prevent inability to progress to position if moving from a loiter to landing */ - float min_limit_cd = linear_interpolate(MIN(last_fw_nav_pitch_cd,0), MAX(-quadplane.aparm.angle_max,plane.aparm.pitch_limit_min_cd), - now, - last_fw_mode_ms, last_fw_mode_ms+limit_time_ms); + const float min_limit_cd = linear_interpolate(MIN(last_fw_nav_pitch_cd,0), MAX(-angle_max,plane.aparm.pitch_limit_min_cd), + dt, + 0, limit_time_ms); if (plane.nav_pitch_cd < min_limit_cd) { plane.nav_pitch_cd = min_limit_cd; return true; } - return false; + return ret; } -void SLT_Transition::force_transistion_complete() { +/* + remember last fixed wing pitch for pitch envelope in back transition + */ +void SLT_Transition::set_last_fw_pitch() +{ + last_fw_mode_ms = AP_HAL::millis(); + last_fw_nav_pitch_cd = plane.nav_pitch_cd; +} + +void SLT_Transition::force_transition_complete() { transition_state = TRANSITION_DONE; in_forced_transition = false; transition_start_ms = 0; transition_low_airspeed_ms = 0; - last_fw_mode_ms = AP_HAL::millis(); - last_fw_nav_pitch_cd = plane.nav_pitch_cd; -}; + set_last_fw_pitch(); +} MAV_VTOL_STATE SLT_Transition::get_mav_vtol_state() const { @@ -3864,4 +4239,155 @@ MAV_VTOL_STATE SLT_Transition::get_mav_vtol_state() const return MAV_VTOL_STATE_UNDEFINED; } +// Set FW roll and pitch limits and keep TECS informed +void SLT_Transition::set_FW_roll_pitch(int32_t& nav_pitch_cd, int32_t& nav_roll_cd, bool& allow_stick_mixing) +{ + if (quadplane.in_vtol_mode() || quadplane.in_vtol_airbrake()) { + // not in FW flight + return; + } + + if (transition_state == TRANSITION_DONE) { + // transition complete, nothing to do + return; + } + + if (!plane.control_mode->does_auto_throttle()) { + // don't limit pitch when in manually controlled modes like FBWA, ACRO + return; + } + + float max_pitch; + if (transition_state < TRANSITION_TIMER) { + if (plane.ahrs.groundspeed() < 3.0) { + // until we have some ground speed limit to zero pitch + max_pitch = 0.0; + } else { + max_pitch = quadplane.transition_pitch_max; + } + } else { + max_pitch = (quadplane.transition_pitch_max+1.0)*2.0; + } + + // set a single loop pitch limit in TECS + plane.TECS_controller.set_pitch_max_limit(max_pitch); + + // ensure pitch is constrained to limit + nav_pitch_cd = constrain_int32(nav_pitch_cd, -max_pitch*100.0, max_pitch*100.0); +} + +/* + see if we are in a VTOL takeoff + */ +bool QuadPlane::in_vtol_takeoff(void) const +{ + if (in_vtol_auto() && is_vtol_takeoff(plane.mission.get_current_nav_cmd().id)) { + return true; + } + return false; +} + +// called when we change mode (for any mode, not just Q modes) +void QuadPlane::mode_enter(void) +{ + if (available()) { + pos_control->set_lean_angle_max_cd(0); + } + poscontrol.xy_correction.zero(); + poscontrol.velocity_match.zero(); + poscontrol.last_velocity_match_ms = 0; + poscontrol.set_state(QuadPlane::QPOS_NONE); + + // clear guided takeoff wait on any mode change, but remember the + // state for special behaviour + guided_wait_takeoff_on_mode_enter = guided_wait_takeoff; + guided_wait_takeoff = false; +} + +// Set attitude control yaw rate time constant to pilot input command model value +void QuadPlane::set_pilot_yaw_rate_time_constant() +{ + attitude_control->set_yaw_rate_tc(command_model_pilot.get_rate_tc()); +} + +// Disable attitude control yaw rate time constant +void QuadPlane::disable_yaw_rate_time_constant() +{ + attitude_control->set_yaw_rate_tc(0.0); +} + +// Check if servo auto trim is allowed, only if countrol surfaces are fully in use +bool QuadPlane::allow_servo_auto_trim() +{ + if (!available()) { + // Quadplane disabled, auto trim always allowed + return true; + } + if (in_vtol_mode()) { + // VTOL motors active in VTOL modes + return false; + } + if (!in_assisted_flight()) { + // In forward flight and VTOL motors not active + return true; + } + if (tailsitter.enabled() && option_is_set(QuadPlane::OPTION::TAILSIT_Q_ASSIST_MOTORS_ONLY)) { + // Tailsitter in forward flight, motors providing active stabalisation with motors only option + // Control surfaces are running as normal with I term active, motor I term is zeroed + return true; + } + // In forward flight with active VTOL motors + return false; +} + +bool QuadPlane::landing_with_fixed_wing_spiral_approach(void) const +{ + const AP_Mission::Mission_Command cmd = plane.mission.get_current_nav_cmd(); + + return ((cmd.id == MAV_CMD_NAV_VTOL_LAND) && + (option_is_set(QuadPlane::OPTION::MISSION_LAND_FW_APPROACH) || + cmd.p1 == NAV_VTOL_LAND_OPTIONS_FW_SPIRAL_APPROACH)); +} + +/* + setup scaling of roll and pitch angle P gains to match fixed wing gains + + we setup the angle P gain to match fixed wing at high speed (above + ARSPD_FBW_MIN) where fixed wing surfaces are presumed to + dominate. At lower speeds we use the multicopter angle P gains. +*/ +void QuadPlane::setup_rp_fw_angle_gains(void) +{ + const float mc_angR = attitude_control->get_angle_roll_p().kP(); + const float mc_angP = attitude_control->get_angle_pitch_p().kP(); + const float fw_angR = 1.0/plane.rollController.tau(); + const float fw_angP = 1.0/plane.pitchController.tau(); + + if (!is_positive(mc_angR) || !is_positive(mc_angP)) { + // bad configuration, don't scale + return; + } + + float aspeed; + if (!ahrs.airspeed_estimate(aspeed)) { + // can't get airspeed, no scaling of VTOL angle gains + return; + } + + const float low_airspeed = 3.0; + if (aspeed <= low_airspeed || plane.aparm.airspeed_min <= low_airspeed) { + // no scaling + return; + } + + const float angR_scale = linear_interpolate(mc_angR, fw_angR, + aspeed, + low_airspeed, plane.aparm.airspeed_min) / mc_angR; + const float angP_scale = linear_interpolate(mc_angP, fw_angP, + aspeed, + low_airspeed, plane.aparm.airspeed_min) / mc_angP; + const Vector3f gain_scale{angR_scale, angP_scale, 1.0}; + attitude_control->set_angle_P_scale(gain_scale); +} + #endif // HAL_QUADPLANE_ENABLED diff --git a/ArduPlane/quadplane.h b/ArduPlane/quadplane.h index d20404d1ff1..e0e936c93d4 100644 --- a/ArduPlane/quadplane.h +++ b/ArduPlane/quadplane.h @@ -11,13 +11,14 @@ #include #include #include // Attitude control library +#include #include #include #include #include #include -#include #include +#include #include #include "qautotune.h" #include "defines.h" @@ -108,6 +109,7 @@ class QuadPlane bool verify_vtol_land(void); bool in_vtol_auto(void) const; bool in_vtol_mode(void) const; + bool in_vtol_takeoff(void) const; bool in_vtol_posvel_mode(void) const; void update_throttle_hover(); bool show_vtol_view() const; @@ -163,6 +165,12 @@ class QuadPlane }; void set_q_assist_state(Q_ASSIST_STATE_ENUM state) {q_assist_state = state;}; + // called when we change mode (for any mode, not just Q modes) + void mode_enter(void); + + // Check if servo auto trim is allowed + bool allow_servo_auto_trim(); + private: AP_AHRS &ahrs; AP_Vehicle::MultiCopter aparm; @@ -191,6 +199,13 @@ class QuadPlane // air mode state: OFF, ON, ASSISTED_FLIGHT_ONLY AirMode air_mode; + // Command model parameter class + // Default max rate, default expo, default time constant + AC_CommandModel command_model_pilot{100.0, 0.25, 0.25}; + // helper functions to set and disable time constant from command model + void set_pilot_yaw_rate_time_constant(); + void disable_yaw_rate_time_constant(); + // return true if airmode should be active bool air_mode_active() const; @@ -210,7 +225,7 @@ class QuadPlane void hold_stabilize(float throttle_in); // set climb rate in position controller - void set_climb_rate_cms(float target_climb_rate_cms, bool force_descend); + void set_climb_rate_cms(float target_climb_rate_cms); // get pilot desired yaw rate in cd/s float get_pilot_input_yaw_rate_cds(void) const; @@ -261,12 +276,13 @@ class QuadPlane void update_throttle_suppression(void); void run_z_controller(void); - void run_xy_controller(void); + void run_xy_controller(float accel_limit=0.0); void setup_defaults(void); // calculate a stopping distance for fixed-wing to vtol transitions - float stopping_distance(float ground_speed_squared); + float stopping_distance(float ground_speed_squared) const; + float accel_needed(float stop_distance, float ground_speed_squared) const; float stopping_distance(void); // distance below which we don't do approach, based on stopping @@ -313,9 +329,6 @@ class QuadPlane uint32_t alt_error_start_ms; bool in_alt_assist; - // maximum yaw rate in degrees/second - AP_Float yaw_rate_max; - // landing speed in cm/s AP_Int16 land_speed_cms; @@ -397,11 +410,38 @@ class QuadPlane // are we in a guided takeoff? bool guided_takeoff:1; + /* if we arm in guided mode when we arm then go into a "waiting + for takeoff command" state. In this state we are waiting for + one of the following: + + 1) disarm + 2) guided takeoff command + 3) change to AUTO with a takeoff waypoint as first nav waypoint + 4) change to another mode + + while in this state we don't go to throttle unlimited, and will + refuse a change to AUTO mode if the first waypoint is not a + takeoff. If we try to switch to RTL then we will instead use + QLAND + + This state is needed to cope with the takeoff sequence used + by QGC on common controllers such as the MX16, which do this on a "takeoff" swipe: + + - changes mode to GUIDED + - arms + - changes mode to AUTO + */ + bool guided_wait_takeoff; + bool guided_wait_takeoff_on_mode_enter; + struct { // time when motors reached lower limit uint32_t lower_limit_start_ms; uint32_t land_start_ms; float vpos_start_m; + + // landing detection threshold in meters + AP_Float detect_alt_change; } landing_detect; // throttle mix acceleration filter @@ -430,6 +470,7 @@ class QuadPlane return AP_HAL::millis() - last_state_change_ms; } Vector3p target_cm; + Vector2f xy_correction; Vector3f target_vel_cms; bool slow_descent:1; bool pilot_correction_active; @@ -438,7 +479,14 @@ class QuadPlane uint32_t last_log_ms; bool reached_wp_speed; uint32_t last_run_ms; - float pos1_start_speed; + float pos1_speed_limit; + bool done_accel_init; + Vector2f velocity_match; + uint32_t last_velocity_match_ms; + float target_speed; + float target_accel; + uint32_t last_pos_reset_ms; + bool overshoot; private: uint32_t last_state_change_ms; enum position_control_state state; @@ -487,28 +535,33 @@ class QuadPlane // additional options AP_Int32 options; - enum { - OPTION_LEVEL_TRANSITION=(1<<0), - OPTION_ALLOW_FW_TAKEOFF=(1<<1), - OPTION_ALLOW_FW_LAND=(1<<2), - OPTION_RESPECT_TAKEOFF_FRAME=(1<<3), - OPTION_MISSION_LAND_FW_APPROACH=(1<<4), - OPTION_FS_QRTL=(1<<5), - OPTION_IDLE_GOV_MANUAL=(1<<6), - OPTION_Q_ASSIST_FORCE_ENABLE=(1<<7), - OPTION_TAILSIT_Q_ASSIST_MOTORS_ONLY=(1<<8), - OPTION_AIRMODE_UNUSED=(1<<9), - OPTION_DISARMED_TILT=(1<<10), - OPTION_DELAY_ARMING=(1<<11), - OPTION_DISABLE_SYNTHETIC_AIRSPEED_ASSIST=(1<<12), - OPTION_DISABLE_GROUND_EFFECT_COMP=(1<<13), - OPTION_INGORE_FW_ANGLE_LIMITS_IN_Q_MODES=(1<<14), - OPTION_THR_LANDING_CONTROL=(1<<15), - OPTION_DISABLE_APPROACH=(1<<16), - OPTION_REPOSITION_LANDING=(1<<17), - OPTION_ONLY_ARM_IN_QMODE_OR_AUTO=(1<<18), - OPTION_TRANS_FAIL_TO_FW=(1<<19), + enum class OPTION { + LEVEL_TRANSITION=(1<<0), + ALLOW_FW_TAKEOFF=(1<<1), + ALLOW_FW_LAND=(1<<2), + RESPECT_TAKEOFF_FRAME=(1<<3), + MISSION_LAND_FW_APPROACH=(1<<4), + FS_QRTL=(1<<5), + IDLE_GOV_MANUAL=(1<<6), + Q_ASSIST_FORCE_ENABLE=(1<<7), + TAILSIT_Q_ASSIST_MOTORS_ONLY=(1<<8), + AIRMODE_UNUSED=(1<<9), + DISARMED_TILT=(1<<10), + DELAY_ARMING=(1<<11), + DISABLE_SYNTHETIC_AIRSPEED_ASSIST=(1<<12), + DISABLE_GROUND_EFFECT_COMP=(1<<13), + INGORE_FW_ANGLE_LIMITS_IN_Q_MODES=(1<<14), + THR_LANDING_CONTROL=(1<<15), + DISABLE_APPROACH=(1<<16), + REPOSITION_LANDING=(1<<17), + ONLY_ARM_IN_QMODE_OR_AUTO=(1<<18), + TRANS_FAIL_TO_FW=(1<<19), + FS_RTL=(1<<20), + DISARMED_TILT_UP=(1<<21), }; + bool option_is_set(OPTION option) const { + return (options.get() & int32_t(option)) != 0; + } AP_Float takeoff_failure_scalar; AP_Float maximum_takeoff_airspeed; @@ -517,6 +570,10 @@ class QuadPlane float last_land_final_agl; + // min alt for navigation in takeoff + AP_Float takeoff_navalt_min; + uint32_t takeoff_last_run_ms; + float takeoff_start_alt; // oneshot with duration ARMING_DELAY_MS used by quadplane to delay spoolup after arming: // ignored unless OPTION_DELAY_ARMING or OPTION_TILT_DISARMED is set @@ -561,7 +618,15 @@ class QuadPlane see if we are in the VTOL position control phase of a landing */ bool in_vtol_land_poscontrol(void) const; - + + /* + are we in the airbrake phase of a VTOL landing? + */ + bool in_vtol_airbrake(void) const; + + // returns true if the vehicle should currently be doing a spiral landing + bool landing_with_fixed_wing_spiral_approach(void) const; + // Q assist state, can be enabled, disabled or force. Default to enabled Q_ASSIST_STATE_ENUM q_assist_state = Q_ASSIST_STATE_ENUM::Q_ASSIST_ENABLED; @@ -601,6 +666,11 @@ class QuadPlane */ float get_scaled_wp_speed(float target_bearing_deg) const; + /* + setup scaling of roll and pitch angle P gains to match fixed wing gains + */ + void setup_rp_fw_angle_gains(void); + public: void motor_test_output(); MAV_RESULT mavlink_motor_test_start(mavlink_channel_t chan, uint8_t motor_seq, uint8_t throttle_type, diff --git a/ArduPlane/radio.cpp b/ArduPlane/radio.cpp index 5e534f66539..7cc32fb0eef 100644 --- a/ArduPlane/radio.cpp +++ b/ArduPlane/radio.cpp @@ -178,7 +178,7 @@ void Plane::read_radio() control_failsafe(); -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED const bool stickmixing = fence_stickmixing(); #else const bool stickmixing = true; @@ -280,7 +280,7 @@ void Plane::control_failsafe() // throttle has dropped below the mark failsafe.throttle_counter++; if (failsafe.throttle_counter == 10) { - gcs().send_text(MAV_SEVERITY_WARNING, "Throttle failsafe on"); + gcs().send_text(MAV_SEVERITY_WARNING, "Throttle failsafe %s", "on"); failsafe.rc_failsafe = true; AP_Notify::flags.failsafe_radio = true; } @@ -295,7 +295,7 @@ void Plane::control_failsafe() failsafe.throttle_counter = 3; } if (failsafe.throttle_counter == 1) { - gcs().send_text(MAV_SEVERITY_WARNING, "Throttle failsafe off"); + gcs().send_text(MAV_SEVERITY_WARNING, "Throttle failsafe %s", "off"); } else if(failsafe.throttle_counter == 0) { failsafe.rc_failsafe = false; AP_Notify::flags.failsafe_radio = false; @@ -430,7 +430,7 @@ bool Plane::throttle_at_zero(void) const to center stick area in conjunction with sprung throttle, cannot use in_trim, must use rc_min */ if (((!(g2.flight_options & FlightOptions::CENTER_THROTTLE_TRIM) && channel_throttle->in_trim_dz()) || - (g2.flight_options & FlightOptions::CENTER_THROTTLE_TRIM && channel_throttle->within_min_dz()))) { + (g2.flight_options & FlightOptions::CENTER_THROTTLE_TRIM && channel_throttle->in_min_dz()))) { return true; } return false; diff --git a/ArduPlane/reverse_thrust.cpp b/ArduPlane/reverse_thrust.cpp index b44c36feed0..04033d00f66 100644 --- a/ArduPlane/reverse_thrust.cpp +++ b/ArduPlane/reverse_thrust.cpp @@ -90,16 +90,16 @@ bool Plane::allow_reverse_thrust(void) const case Mode::Number::TAKEOFF: allow = false; break; -case Mode::Number::FLY_BY_WIRE_A: + case Mode::Number::FLY_BY_WIRE_A: allow |= (g.use_reverse_thrust & USE_REVERSE_THRUST_FBWA); break; -case Mode::Number::ACRO: + case Mode::Number::ACRO: allow |= (g.use_reverse_thrust & USE_REVERSE_THRUST_ACRO); break; -case Mode::Number::STABILIZE: + case Mode::Number::STABILIZE: allow |= (g.use_reverse_thrust & USE_REVERSE_THRUST_STABILIZE); break; -case Mode::Number::THERMAL: + case Mode::Number::THERMAL: allow |= (g.use_reverse_thrust & USE_REVERSE_THRUST_THERMAL); break; default: diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index 41b6f8ff45c..03fc39115c4 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -133,11 +133,17 @@ bool Plane::suppress_throttle(void) // if we have an airspeed sensor, then check it too, and // require 5m/s. This prevents throttle up due to spiky GPS // groundspeed with bad GPS reception +#if AP_AIRSPEED_ENABLED if ((!ahrs.airspeed_sensor_enabled()) || airspeed.get_airspeed() >= 5) { // we're moving at more than 5 m/s throttle_suppressed = false; return false; } +#else + // no airspeed sensor, so we trust that the GPS's movement is truthful + throttle_suppressed = false; + return false; +#endif } #if HAL_QUADPLANE_ENABLED @@ -382,13 +388,15 @@ void Plane::set_servos_manual_passthrough(void) SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, throttle); #if HAL_QUADPLANE_ENABLED - if (quadplane.available() && (quadplane.options & QuadPlane::OPTION_IDLE_GOV_MANUAL)) { + if (quadplane.available() && quadplane.option_is_set(QuadPlane::OPTION::IDLE_GOV_MANUAL)) { // for quadplanes it can be useful to run the idle governor in MANUAL mode // as it prevents the VTOL motors from running int8_t min_throttle = aparm.throttle_min.get(); // apply idle governor +#if AP_ICENGINE_ENABLED g2.ice_control.update_idle_governor(min_throttle); +#endif throttle = MAX(throttle, min_throttle); SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, throttle); } @@ -424,8 +432,8 @@ void Plane::throttle_voltage_comp(int8_t &min_throttle, int8_t &max_throttle) co const float ratio = g2.fwd_thr_batt_voltage_max / batt_voltage_resting_estimate; // Scale the throttle limits to prevent subsequent clipping - min_throttle = MAX((int8_t)(ratio * (float)min_throttle), -100); - max_throttle = MIN((int8_t)(ratio * (float)max_throttle), 100); + min_throttle = int8_t(MAX((ratio * (float)min_throttle), -100)); + max_throttle = int8_t(MIN((ratio * (float)max_throttle), 100)); SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, constrain_float(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) * ratio, -100, 100)); @@ -493,9 +501,11 @@ void Plane::set_servos_controlled(void) int8_t min_throttle = aparm.throttle_min.get(); int8_t max_throttle = aparm.throttle_max.get(); +#if AP_ICENGINE_ENABLED // apply idle governor g2.ice_control.update_idle_governor(min_throttle); - +#endif + if (min_throttle < 0 && !allow_reverse_thrust()) { // reverse thrust is available but inhibited. min_throttle = 0; @@ -561,7 +571,7 @@ void Plane::set_servos_controlled(void) control_mode == &mode_fbwa || control_mode == &mode_autotune) { // a manual throttle mode - if (failsafe.throttle_counter) { + if (!rc().has_valid_input()) { SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0.0); } else if (g.throttle_passthru_stabilize) { // manual pass through of throttle while in FBWA or @@ -615,7 +625,7 @@ void Plane::set_servos_flaps(void) int8_t manual_flap_percent = 0; // work out any manual flap input - if (channel_flap != nullptr && !failsafe.rc_failsafe && failsafe.throttle_counter == 0) { + if (channel_flap != nullptr && rc().has_valid_input()) { manual_flap_percent = channel_flap->percent_input(); } @@ -710,7 +720,7 @@ void Plane::set_landing_gear(void) void Plane::servos_twin_engine_mix(void) { float throttle = SRV_Channels::get_output_scaled(SRV_Channel::k_throttle); - float rud_gain = float(plane.g2.rudd_dt_gain) / 100; + float rud_gain = float(plane.g2.rudd_dt_gain) * 0.01f; rudder_dt = rud_gain * SRV_Channels::get_output_scaled(SRV_Channel::k_rudder) / SERVO_MAX; #if ADVANCED_FAILSAFE == ENABLED @@ -880,6 +890,10 @@ void Plane::set_servos(void) // slew rate limit throttle throttle_slew_limit(SRV_Channel::k_throttle); +#if AP_ICENGINE_ENABLED + const float base_throttle = SRV_Channels::get_output_scaled(SRV_Channel::k_throttle); +#endif + if (!arming.is_armed()) { //Some ESCs get noisy (beep error msgs) if PWM == 0. //This little segment aims to avoid this. @@ -905,11 +919,16 @@ void Plane::set_servos(void) } } - uint8_t override_pct; - if (g2.ice_control.throttle_override(override_pct)) { - // the ICE controller wants to override the throttle for starting +#if AP_ICENGINE_ENABLED + float override_pct = SRV_Channels::get_output_scaled(SRV_Channel::k_throttle); + if (g2.ice_control.throttle_override(override_pct, base_throttle)) { + // the ICE controller wants to override the throttle for starting, idle, or redline SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, override_pct); +#if HAL_QUADPLANE_ENABLED + quadplane.vel_forward.integrator = 0; +#endif } +#endif // AP_ICENGINE_ENABLED // run output mixer and send values to the hal for output servos_output(); @@ -979,7 +998,7 @@ void Plane::servos_output(void) // support MANUAL_RCMASK if (g2.manual_rc_mask.get() != 0 && control_mode == &mode_manual) { - SRV_Channels::copy_radio_in_out_mask(uint16_t(g2.manual_rc_mask.get())); + SRV_Channels::copy_radio_in_out_mask(uint32_t(g2.manual_rc_mask.get())); } SRV_Channels::calc_pwm(); @@ -1018,7 +1037,7 @@ void Plane::servos_auto_trim(void) return; } #if HAL_QUADPLANE_ENABLED - if (quadplane.in_assisted_flight() || quadplane.in_vtol_mode()) { + if (!quadplane.allow_servo_auto_trim()) { // can't auto-trim with quadplane motors running return; } diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index 205dda44459..c29f7bfd14f 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -36,7 +36,7 @@ void Plane::init_ardupilot() // initialise rc channels including setting mode #if HAL_QUADPLANE_ENABLED - rc().convert_options(RC_Channel::AUX_FUNC::ARMDISARM_UNUSED, (quadplane.enabled() && (quadplane.options & QuadPlane::OPTION_AIRMODE_UNUSED) && (rc().find_channel_for_option(RC_Channel::AUX_FUNC::AIRMODE) == nullptr)) ? RC_Channel::AUX_FUNC::ARMDISARM_AIRMODE : RC_Channel::AUX_FUNC::ARMDISARM); + rc().convert_options(RC_Channel::AUX_FUNC::ARMDISARM_UNUSED, (quadplane.enabled() && quadplane.option_is_set(QuadPlane::OPTION::AIRMODE_UNUSED) && (rc().find_channel_for_option(RC_Channel::AUX_FUNC::AIRMODE) == nullptr)) ? RC_Channel::AUX_FUNC::ARMDISARM_AIRMODE : RC_Channel::AUX_FUNC::ARMDISARM); #else rc().convert_options(RC_Channel::AUX_FUNC::ARMDISARM_UNUSED, RC_Channel::AUX_FUNC::ARMDISARM); #endif @@ -147,11 +147,6 @@ void Plane::init_ardupilot() #if GRIPPER_ENABLED == ENABLED g2.gripper.init(); #endif - - // init fence -#if AC_FENCE == ENABLED - fence.init(); -#endif } //******************************************************************************** @@ -202,16 +197,33 @@ void Plane::startup_ground(void) } +#if AP_FENCE_ENABLED +/* + return true if a mode reason is an automatic mode change due to + landing sequencing. + */ +static bool mode_reason_is_landing_sequence(const ModeReason reason) +{ + switch (reason) { + case ModeReason::RTL_COMPLETE_SWITCHING_TO_FIXEDWING_AUTOLAND: + case ModeReason::RTL_COMPLETE_SWITCHING_TO_VTOL_LAND_RTL: + case ModeReason::QRTL_INSTEAD_OF_RTL: + case ModeReason::QLAND_INSTEAD_OF_RTL: + return true; + default: + break; + } + return false; +} +#endif // AP_FENCE_ENABLED + bool Plane::set_mode(Mode &new_mode, const ModeReason reason) { - // update last reason - const ModeReason last_reason = _last_reason; - _last_reason = reason; if (control_mode == &new_mode) { // don't switch modes if we are already in the correct mode. // only make happy noise if using a difent method to switch, this stops beeping for repeated change mode requests from GCS - if ((reason != last_reason) && (reason != ModeReason::INITIALISED)) { + if ((reason != control_mode_reason) && (reason != ModeReason::INITIALISED)) { AP_Notify::events.user_mode_change = 1; } return true; @@ -252,6 +264,20 @@ bool Plane::set_mode(Mode &new_mode, const ModeReason reason) } #endif // HAL_QUADPLANE_ENABLED +#if AP_FENCE_ENABLED + // may not be allowed to change mode if recovering from fence breach + if (hal.util->get_soft_armed() && + fence.enabled() && + fence.option_enabled(AC_Fence::OPTIONS::DISABLE_MODE_CHANGE) && + fence.get_breaches() && + in_fence_recovery() && + !mode_reason_is_landing_sequence(reason)) { + gcs().send_text(MAV_SEVERITY_NOTICE,"Mode change to %s denied, in fence recovery", new_mode.name()); + AP_Notify::events.user_mode_change_failed = 1; + return false; + } +#endif + // backup current control_mode and previous_mode Mode &old_previous_mode = *previous_mode; Mode &old_mode = *control_mode; @@ -260,7 +286,8 @@ bool Plane::set_mode(Mode &new_mode, const ModeReason reason) // TODO: move these to be after enter() once start_command_callback() no longer checks control_mode previous_mode = control_mode; control_mode = &new_mode; - const ModeReason previous_mode_reason = control_mode_reason; + const ModeReason old_previous_mode_reason = previous_mode_reason; + previous_mode_reason = control_mode_reason; control_mode_reason = reason; // attempt to enter new mode @@ -272,6 +299,7 @@ bool Plane::set_mode(Mode &new_mode, const ModeReason reason) previous_mode = &old_previous_mode; control_mode = &old_mode; control_mode_reason = previous_mode_reason; + previous_mode_reason = old_previous_mode_reason; // make sad noise if (reason != ModeReason::INITIALISED) { @@ -288,9 +316,6 @@ bool Plane::set_mode(Mode &new_mode, const ModeReason reason) // exit previous mode old_mode.exit(); - // record reasons - control_mode_reason = reason; - // log and notify mode change logger.Write_Mode(control_mode->mode_number(), control_mode_reason); notify_mode(*control_mode); @@ -445,80 +470,3 @@ int8_t Plane::throttle_percentage(void) } return constrain_int16(throttle, -100, 100); } - -// update the harmonic notch filter center frequency dynamically -void Plane::update_dynamic_notch() -{ - if (!ins.gyro_harmonic_notch_enabled()) { - return; - } - const float ref_freq = ins.get_gyro_harmonic_notch_center_freq_hz(); - const float ref = ins.get_gyro_harmonic_notch_reference(); - - if (is_zero(ref)) { - ins.update_harmonic_notch_freq_hz(ref_freq); - return; - } - - switch (ins.get_gyro_harmonic_notch_tracking_mode()) { - case HarmonicNotchDynamicMode::UpdateThrottle: // throttle based tracking - // set the harmonic notch filter frequency approximately scaled on motor rpm implied by throttle -#if HAL_QUADPLANE_ENABLED - if (quadplane.available()) { - ins.update_harmonic_notch_freq_hz(ref_freq * MAX(1.0f, sqrtf(quadplane.motors->get_throttle_out() / ref))); - } -#endif - break; - - case HarmonicNotchDynamicMode::UpdateRPM: // rpm sensor based tracking - float rpm; - if (rpm_sensor.get_rpm(0, rpm)) { - // set the harmonic notch filter frequency from the main rotor rpm - ins.update_harmonic_notch_freq_hz(MAX(ref_freq, rpm * ref / 60.0f)); - } else { - ins.update_harmonic_notch_freq_hz(ref_freq); - } - break; -#if HAL_WITH_ESC_TELEM - case HarmonicNotchDynamicMode::UpdateBLHeli: // BLHeli based tracking - // set the harmonic notch filter frequency scaled on measured frequency - if (ins.has_harmonic_option(HarmonicNotchFilterParams::Options::DynamicHarmonic)) { - float notches[INS_MAX_NOTCHES]; - const uint8_t num_notches = AP::esc_telem().get_motor_frequencies_hz(ins.get_num_gyro_dynamic_notches(), notches); - - for (uint8_t i = 0; i < num_notches; i++) { - notches[i] = MAX(ref_freq, notches[i]); - } - if (num_notches > 0) { - ins.update_harmonic_notch_frequencies_hz(num_notches, notches); -#if HAL_QUADPLANE_ENABLED - } else if (quadplane.available()) { // throttle fallback - ins.update_harmonic_notch_freq_hz(ref_freq * MAX(1.0f, sqrtf(quadplane.motors->get_throttle_out() / ref))); -#endif - } else { - ins.update_harmonic_notch_freq_hz(ref_freq); - } - } else { - ins.update_harmonic_notch_freq_hz(MAX(ref_freq, AP::esc_telem().get_average_motor_frequency_hz() * ref)); - } - break; -#endif -#if HAL_GYROFFT_ENABLED - case HarmonicNotchDynamicMode::UpdateGyroFFT: // FFT based tracking - // set the harmonic notch filter frequency scaled on measured frequency - if (ins.has_harmonic_option(HarmonicNotchFilterParams::Options::DynamicHarmonic)) { - float notches[INS_MAX_NOTCHES]; - const uint8_t peaks = gyro_fft.get_weighted_noise_center_frequencies_hz(ins.get_num_gyro_dynamic_notches(), notches); - - ins.update_harmonic_notch_frequencies_hz(peaks, notches); - } else { - ins.update_harmonic_notch_freq_hz(gyro_fft.get_weighted_noise_center_freq_hz()); - } - break; -#endif - case HarmonicNotchDynamicMode::Fixed: // static - default: - ins.update_harmonic_notch_freq_hz(ref_freq); - break; - } -} diff --git a/ArduPlane/tailsitter.cpp b/ArduPlane/tailsitter.cpp index 7ee5b999201..2a099c4f682 100644 --- a/ArduPlane/tailsitter.cpp +++ b/ArduPlane/tailsitter.cpp @@ -236,7 +236,7 @@ void Tailsitter::setup() // Do not allow arming in forward flight modes // motors will become active due to assisted flight airmode, the vehicle will try very hard to get level - quadplane.options.set(quadplane.options.get() | QuadPlane::OPTION_ONLY_ARM_IN_QMODE_OR_AUTO); + quadplane.options.set(quadplane.options.get() | int32_t(QuadPlane::OPTION::ONLY_ARM_IN_QMODE_OR_AUTO)); } transition = new Tailsitter_Transition(quadplane, motors, *this); @@ -294,7 +294,7 @@ void Tailsitter::output(void) // handle forward flight modes and transition to VTOL modes if (!active() || in_vtol_transition()) { // get FW controller throttle demand and mask of motors enabled during forward flight - if (hal.util->get_soft_armed() && in_vtol_transition() && !quadplane.throttle_wait && quadplane.is_flying()) { + if (hal.util->get_soft_armed() && in_vtol_transition() && !quadplane.throttle_wait) { /* during transitions to vtol mode set the throttle to hover thrust, center the rudder */ @@ -312,6 +312,11 @@ void Tailsitter::output(void) // in assisted flight this is done in the normal motor output path if (!quadplane.assisted_flight) { + + // keep attitude control throttle level upto date, this value should never be output to motors + // it is used to re-set the accel Z integrator term allowing for a smooth transfer of control + quadplane.attitude_control->set_throttle_out(throttle, false, 0); + // convert the hover throttle to the same output that would result if used via AP_Motors // apply expo, battery scaling and SPIN min/max. throttle = motors->thrust_to_actuator(throttle); @@ -356,7 +361,7 @@ void Tailsitter::output(void) quadplane.hold_stabilize(throttle); quadplane.motors_output(true); - if ((quadplane.options & QuadPlane::OPTION_TAILSIT_Q_ASSIST_MOTORS_ONLY) != 0) { + if (quadplane.option_is_set(QuadPlane::OPTION::TAILSIT_Q_ASSIST_MOTORS_ONLY)) { // only use motors for Q assist, control surfaces remain under plane control // zero copter I terms and use plane quadplane.attitude_control->reset_rate_controller_I_terms(); @@ -791,6 +796,7 @@ void Tailsitter_Transition::update() // multiply by 0.1 to convert (degrees/second * milliseconds) to centi degrees plane.nav_pitch_cd = constrain_float(fw_transition_initial_pitch - (quadplane.tailsitter.transition_rate_fw * dt) * 0.1f * (plane.fly_inverted()?-1.0f:1.0f), -8500, 8500); plane.nav_roll_cd = 0; + quadplane.disable_yaw_rate_time_constant(); quadplane.attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(plane.nav_roll_cd, plane.nav_pitch_cd, 0); @@ -827,7 +833,7 @@ void Tailsitter_Transition::VTOL_update() if (transition_state == TRANSITION_ANGLE_WAIT_VTOL) { float aspeed; bool have_airspeed = quadplane.ahrs.airspeed_estimate(aspeed); - // provide assistance in forward flight portion of tailsitter transistion + // provide assistance in forward flight portion of tailsitter transition quadplane.assisted_flight = quadplane.should_assist(aspeed, have_airspeed); if (!quadplane.tailsitter.transition_vtol_complete()) { return; @@ -932,7 +938,7 @@ void Tailsitter_Transition::restart() } // force state to FW and setup for the transition back to VTOL -void Tailsitter_Transition::force_transistion_complete() +void Tailsitter_Transition::force_transition_complete() { transition_state = TRANSITION_DONE; vtol_transition_start_ms = AP_HAL::millis(); diff --git a/ArduPlane/tailsitter.h b/ArduPlane/tailsitter.h index 30dc780d963..b8e0a0380c4 100644 --- a/ArduPlane/tailsitter.h +++ b/ArduPlane/tailsitter.h @@ -54,7 +54,7 @@ friend class Plane; // check if we have completed transition to vtol bool transition_vtol_complete(void) const; - // return true if transistion to VTOL flight + // return true if transition to VTOL flight bool in_vtol_transition(uint32_t now = 0) const; // account for control surface speed scaling in VTOL modes @@ -144,14 +144,14 @@ friend class Tailsitter; void VTOL_update() override; - void force_transistion_complete() override; + void force_transition_complete() override; bool complete() const override { return transition_state == TRANSITION_DONE; } // setup for the transition back to fixed wing void restart() override; - uint8_t get_log_transision_state() const override { return static_cast(transition_state); } + uint8_t get_log_transition_state() const override { return static_cast(transition_state); } bool active() const override { return transition_state != TRANSITION_DONE; } diff --git a/ArduPlane/tiltrotor.cpp b/ArduPlane/tiltrotor.cpp index 5a48b3b4da0..da27d7aee73 100644 --- a/ArduPlane/tiltrotor.cpp +++ b/ArduPlane/tiltrotor.cpp @@ -74,7 +74,7 @@ const AP_Param::GroupInfo Tiltrotor::var_info[] = { // @Param: WING_FLAP // @DisplayName: Tiltrotor tilt angle that will be used as flap - // @Description: For use on tilt wings, the wing will tilt up to this angle for flap, transistion will be complete when the wing reaches this angle from the forward fight position, 0 disables + // @Description: For use on tilt wings, the wing will tilt up to this angle for flap, transition will be complete when the wing reaches this angle from the forward fight position, 0 disables // @Units: deg // @Increment: 1 // @Range: 0 15 @@ -175,7 +175,7 @@ float Tiltrotor::tilt_max_change(bool up, bool in_flap_range) const rate = MAX(rate, 90); } } - return rate * plane.G_Dt / 90.0f; + return rate * plane.G_Dt * (1/90.0); } /* @@ -196,13 +196,13 @@ void Tiltrotor::slew(float newtilt) // tilt wings can sustain forward flight with some amount of wing tilt float Tiltrotor::get_fully_forward_tilt() const { - return 1.0 - (flap_angle_deg / 90.0); + return 1.0 - (flap_angle_deg * (1/90.0)); } // return the target tilt value for forward flight float Tiltrotor::get_forward_flight_tilt() const { - return 1.0 - ((flap_angle_deg / 90.0) * SRV_Channels::get_slew_limited_output_scaled(SRV_Channel::k_flap_auto) * 0.01); + return 1.0 - ((flap_angle_deg * (1/90.0)) * SRV_Channels::get_slew_limited_output_scaled(SRV_Channel::k_flap_auto) * 0.01); } /* @@ -219,7 +219,10 @@ void Tiltrotor::continuous_update(void) if (!quadplane.in_vtol_mode() && (!hal.util->get_soft_armed() || !quadplane.assisted_flight)) { // we are in pure fixed wing mode. Move the tiltable motors all the way forward and run them as // a forward motor - slew(get_forward_flight_tilt()); + + // option set then if disarmed move to VTOL position to prevent ground strikes, allow tilt forward in manual mode for testing + const bool disarmed_tilt_up = !hal.util->get_soft_armed() && (plane.control_mode != &plane.mode_manual) && quadplane.option_is_set(QuadPlane::OPTION::DISARMED_TILT_UP); + slew(disarmed_tilt_up ? 0.0 : get_forward_flight_tilt()); max_change = tilt_max_change(false); @@ -305,8 +308,8 @@ void Tiltrotor::continuous_update(void) // Q_TILT_MAX. Anything above 50% throttle gets // Q_TILT_MAX. Below 50% throttle we decrease linearly. This // relies heavily on Q_VFWD_GAIN being set appropriately. - float settilt = constrain_float((SRV_Channels::get_output_scaled(SRV_Channel::k_throttle)-MAX(plane.aparm.throttle_min.get(),0)) / 50.0f, 0, 1); - slew(MIN(settilt * max_angle_deg / 90.0f, get_forward_flight_tilt())); + float settilt = constrain_float((SRV_Channels::get_output_scaled(SRV_Channel::k_throttle)-MAX(plane.aparm.throttle_min.get(),0)) * 0.02, 0, 1); + slew(MIN(settilt * max_angle_deg * (1/90.0), get_forward_flight_tilt())); } } @@ -479,6 +482,17 @@ bool Tiltrotor::fully_fwd(void) const return (current_tilt >= get_fully_forward_tilt()); } +/* + return true if the rotors are fully tilted up + */ +bool Tiltrotor::fully_up(void) const +{ + if (!enabled() || (tilt_mask == 0)) { + return false; + } + return (current_tilt <= 0); +} + /* control vectoring for tilt multicopters */ @@ -497,7 +511,7 @@ void Tiltrotor::vectoring(void) // Wait TILT_DELAY_MS after disarming to allow props to spin down first. constexpr uint32_t TILT_DELAY_MS = 3000; uint32_t now = AP_HAL::millis(); - if (!hal.util->get_soft_armed() && (plane.quadplane.options & QuadPlane::OPTION_DISARMED_TILT)) { + if (!hal.util->get_soft_armed() && plane.quadplane.option_is_set(QuadPlane::OPTION::DISARMED_TILT)) { // this test is subject to wrapping at ~49 days, but the consequences are insignificant if ((now - hal.util->get_last_armed_change()) > TILT_DELAY_MS) { if (quadplane.in_vtol_mode()) { @@ -516,9 +530,9 @@ void Tiltrotor::vectoring(void) // base the tilt on elevon mixing, which means it // takes account of the MIXING_GAIN. The rear tilt is // based on elevator - const float right = gain * SRV_Channels::get_output_scaled(SRV_Channel::k_elevon_right) / 4500.0; - const float left = gain * SRV_Channels::get_output_scaled(SRV_Channel::k_elevon_left) / 4500.0; - const float mid = gain * SRV_Channels::get_output_scaled(SRV_Channel::k_elevator) / 4500.0; + const float right = gain * SRV_Channels::get_output_scaled(SRV_Channel::k_elevon_right) * (1/4500.0); + const float left = gain * SRV_Channels::get_output_scaled(SRV_Channel::k_elevon_left) * (1/4500.0); + const float mid = gain * SRV_Channels::get_output_scaled(SRV_Channel::k_elevator) * (1/4500.0); // front tilt is effective canards, so need to swap and use negative. Rear motors are treated live elevons. SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorLeft,1000 * constrain_float(base_output - right,0,1)); SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorRight,1000 * constrain_float(base_output - left,0,1)); @@ -536,9 +550,9 @@ void Tiltrotor::vectoring(void) // we don't want tilt impacted by airspeed const float scaler = plane.control_mode == &plane.mode_manual?1:(quadplane.FW_vector_throttle_scaling() / plane.get_speed_scaler()); const float gain = fixed_gain * fixed_tilt_limit * scaler; - const float right = gain * SRV_Channels::get_output_scaled(SRV_Channel::k_elevon_right) / 4500.0; - const float left = gain * SRV_Channels::get_output_scaled(SRV_Channel::k_elevon_left) / 4500.0; - const float mid = gain * SRV_Channels::get_output_scaled(SRV_Channel::k_elevator) / 4500.0; + const float right = gain * SRV_Channels::get_output_scaled(SRV_Channel::k_elevon_right) * (1/4500.0); + const float left = gain * SRV_Channels::get_output_scaled(SRV_Channel::k_elevon_left) * (1/4500.0); + const float mid = gain * SRV_Channels::get_output_scaled(SRV_Channel::k_elevator) * (1/4500.0); SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorLeft,1000 * constrain_float(base_output - right,0,1)); SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorRight,1000 * constrain_float(base_output - left,0,1)); SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorRearLeft,1000 * constrain_float(base_output + left,0,1)); @@ -596,10 +610,10 @@ void Tiltrotor::bicopter_output(void) float tilt_right = SRV_Channels::get_output_scaled(SRV_Channel::k_tiltMotorRight); if (is_negative(tilt_left)) { - tilt_left *= tilt_yaw_angle / 90.0f; + tilt_left *= tilt_yaw_angle * (1/90.0); } if (is_negative(tilt_right)) { - tilt_right *= tilt_yaw_angle / 90.0f; + tilt_right *= tilt_yaw_angle * (1/90.0); } // reduce authority of bicopter as motors are tilted forwards diff --git a/ArduPlane/tiltrotor.h b/ArduPlane/tiltrotor.h index e6953ebf469..2467fc28cca 100644 --- a/ArduPlane/tiltrotor.h +++ b/ArduPlane/tiltrotor.h @@ -49,6 +49,7 @@ friend class Tiltrotor_Transition; } bool fully_fwd() const; + bool fully_up() const; float tilt_max_change(bool up, bool in_flap_range = false) const; float get_fully_forward_tilt() const; float get_forward_flight_tilt() const; diff --git a/ArduPlane/transition.h b/ArduPlane/transition.h index 00167800779..9ddc1d5b5f5 100644 --- a/ArduPlane/transition.h +++ b/ArduPlane/transition.h @@ -13,7 +13,7 @@ along with this program. If not, see . */ #pragma once -#include +#include class QuadPlane; class AP_MotorsMulticopter; @@ -28,13 +28,13 @@ class Transition virtual void VTOL_update() = 0; - virtual void force_transistion_complete() = 0; + virtual void force_transition_complete() = 0; virtual bool complete() const = 0; virtual void restart() = 0; - virtual uint8_t get_log_transision_state() const = 0; + virtual uint8_t get_log_transition_state() const = 0; virtual bool active() const = 0; @@ -54,6 +54,8 @@ class Transition virtual bool allow_weathervane() { return true; } + virtual void set_last_fw_pitch(void) {} + protected: // refences for convenience @@ -73,18 +75,20 @@ class SLT_Transition : public Transition void VTOL_update() override; - void force_transistion_complete() override; + void force_transition_complete() override; bool complete() const override { return transition_state == TRANSITION_DONE; } void restart() override { transition_state = TRANSITION_AIRSPEED_WAIT; } - uint8_t get_log_transision_state() const override { return static_cast(transition_state); } + uint8_t get_log_transition_state() const override { return static_cast(transition_state); } bool active() const override; bool show_vtol_view() const override; + void set_FW_roll_pitch(int32_t& nav_pitch_cd, int32_t& nav_roll_cd, bool& allow_stick_mixing) override; + bool set_FW_roll_limit(int32_t& roll_limit_cd) override; bool allow_update_throttle_mix() const override; @@ -93,6 +97,8 @@ class SLT_Transition : public Transition bool set_VTOL_roll_pitch_limit(int32_t& nav_roll_cd, int32_t& nav_pitch_cd) override; + void set_last_fw_pitch(void) override; + protected: enum { diff --git a/ArduPlane/tuning.cpp b/ArduPlane/tuning.cpp index de966e4bd08..2218a11ab0a 100644 --- a/ArduPlane/tuning.cpp +++ b/ArduPlane/tuning.cpp @@ -8,7 +8,7 @@ const AP_Param::GroupInfo AP_Tuning_Plane::var_info[] = { // @Param: PARAM // @DisplayName: Transmitter tuning parameter or set of parameters // @Description: This sets which parameter or set of parameters will be tuned. Values greater than 100 indicate a set of parameters rather than a single parameter. Parameters less than 50 are for QuadPlane vertical lift motors only. - // @Values: 0:None,1:RateRollPI,2:RateRollP,3:RateRollI,4:RateRollD,5:RatePitchPI,6:RatePitchP,7:RatePitchI,8:RatePitchD,9:RateYawPI,10:RateYawP,11:RateYawI,12:RateYawD,13:AngleRollP,14:AnglePitchP,15:AngleYawP,16:PosXYP,17:PosZP,18:VelXYP,19:VelXYI,20:VelZP,21:AccelZP,22:AccelZI,23:AccelZD,24:RatePitchFF,25:RateRollFF,26:RateYawFF,50:FixedWingRollP,51:FixedWingRollI,52:FixedWingRollD,53:FixedWingRollFF,54:FixedWingPitchP,55:FixedWingPitchI,56:FixedWingPitchD,57:FixedWingPitchFF,101:Set_RateRollPitch,102:Set_RateRoll,103:Set_RatePitch,104:Set_RateYaw,105:Set_AngleRollPitch,106:Set_VelXY,107:Set_AccelZ + // @Values: 0:None,1:RateRollPI,2:RateRollP,3:RateRollI,4:RateRollD,5:RatePitchPI,6:RatePitchP,7:RatePitchI,8:RatePitchD,9:RateYawPI,10:RateYawP,11:RateYawI,12:RateYawD,13:AngleRollP,14:AnglePitchP,15:AngleYawP,16:PosXYP,17:PosZP,18:VelXYP,19:VelXYI,20:VelZP,21:AccelZP,22:AccelZI,23:AccelZD,24:RatePitchFF,25:RateRollFF,26:RateYawFF,50:FixedWingRollP,51:FixedWingRollI,52:FixedWingRollD,53:FixedWingRollFF,54:FixedWingPitchP,55:FixedWingPitchI,56:FixedWingPitchD,57:FixedWingPitchFF,101:Set_RateRollPitch,102:Set_RateRoll,103:Set_RatePitch,104:Set_RateYaw,105:Set_AngleRollPitch,106:Set_VelXY,107:Set_AccelZ,108:Set_RatePitchDP,109:Set_RateRollDP,110:Set_RateYawDP // @User: Standard AP_GROUPINFO("PARAM", 1, AP_Tuning_Plane, parmset, 0), @@ -22,27 +22,33 @@ const AP_Param::GroupInfo AP_Tuning_Plane::var_info[] = { /* tables of tuning sets */ -const uint8_t AP_Tuning_Plane::tuning_set_rate_roll_pitch[] = { TUNING_RATE_ROLL_D, TUNING_RATE_ROLL_PI, - TUNING_RATE_PITCH_D, TUNING_RATE_PITCH_PI}; -const uint8_t AP_Tuning_Plane::tuning_set_rate_roll[] = { TUNING_RATE_ROLL_D, TUNING_RATE_ROLL_PI }; -const uint8_t AP_Tuning_Plane::tuning_set_rate_pitch[] = { TUNING_RATE_PITCH_D, TUNING_RATE_PITCH_PI }; -const uint8_t AP_Tuning_Plane::tuning_set_rate_yaw[] = { TUNING_RATE_YAW_P, TUNING_RATE_YAW_I, TUNING_RATE_YAW_D }; -const uint8_t AP_Tuning_Plane::tuning_set_ang_roll_pitch[] = { TUNING_ANG_ROLL_P, TUNING_ANG_PITCH_P }; -const uint8_t AP_Tuning_Plane::tuning_set_vxy[] = { TUNING_VXY_P, TUNING_VXY_I }; -const uint8_t AP_Tuning_Plane::tuning_set_az[] = { TUNING_AZ_P, TUNING_AZ_I, TUNING_AZ_D }; +const uint8_t AP_Tuning_Plane::tuning_set_rate_roll_pitch[] = { TUNING_RATE_ROLL_D, TUNING_RATE_ROLL_PI, + TUNING_RATE_PITCH_D, TUNING_RATE_PITCH_PI}; +const uint8_t AP_Tuning_Plane::tuning_set_rate_roll[] = { TUNING_RATE_ROLL_D, TUNING_RATE_ROLL_PI }; +const uint8_t AP_Tuning_Plane::tuning_set_rate_pitch[] = { TUNING_RATE_PITCH_D, TUNING_RATE_PITCH_PI }; +const uint8_t AP_Tuning_Plane::tuning_set_rate_yaw[] = { TUNING_RATE_YAW_P, TUNING_RATE_YAW_I, TUNING_RATE_YAW_D }; +const uint8_t AP_Tuning_Plane::tuning_set_ang_roll_pitch[] = { TUNING_ANG_ROLL_P, TUNING_ANG_PITCH_P }; +const uint8_t AP_Tuning_Plane::tuning_set_vxy[] = { TUNING_VXY_P, TUNING_VXY_I }; +const uint8_t AP_Tuning_Plane::tuning_set_az[] = { TUNING_AZ_P, TUNING_AZ_I, TUNING_AZ_D }; +const uint8_t AP_Tuning_Plane::tuning_set_rate_pitchDP[]= { TUNING_RATE_PITCH_D, TUNING_RATE_PITCH_P }; +const uint8_t AP_Tuning_Plane::tuning_set_rate_rollDP[]= { TUNING_RATE_ROLL_D, TUNING_RATE_ROLL_P }; +const uint8_t AP_Tuning_Plane::tuning_set_rate_yawDP[]= { TUNING_RATE_YAW_D, TUNING_RATE_YAW_P }; // macro to prevent getting the array length wrong #define TUNING_ARRAY(v) ARRAY_SIZE(v), v // list of tuning sets const AP_Tuning_Plane::tuning_set AP_Tuning_Plane::tuning_sets[] = { - { TUNING_SET_RATE_ROLL_PITCH, TUNING_ARRAY(tuning_set_rate_roll_pitch) }, - { TUNING_SET_RATE_ROLL, TUNING_ARRAY(tuning_set_rate_roll) }, - { TUNING_SET_RATE_PITCH, TUNING_ARRAY(tuning_set_rate_pitch) }, - { TUNING_SET_RATE_YAW, TUNING_ARRAY(tuning_set_rate_yaw) }, - { TUNING_SET_ANG_ROLL_PITCH, TUNING_ARRAY(tuning_set_ang_roll_pitch) }, - { TUNING_SET_VXY, TUNING_ARRAY(tuning_set_vxy) }, - { TUNING_SET_AZ, TUNING_ARRAY(tuning_set_az) }, + { TUNING_SET_RATE_ROLL_PITCH, TUNING_ARRAY(tuning_set_rate_roll_pitch) }, + { TUNING_SET_RATE_ROLL, TUNING_ARRAY(tuning_set_rate_roll) }, + { TUNING_SET_RATE_PITCH, TUNING_ARRAY(tuning_set_rate_pitch) }, + { TUNING_SET_RATE_YAW, TUNING_ARRAY(tuning_set_rate_yaw) }, + { TUNING_SET_ANG_ROLL_PITCH, TUNING_ARRAY(tuning_set_ang_roll_pitch) }, + { TUNING_SET_VXY, TUNING_ARRAY(tuning_set_vxy) }, + { TUNING_SET_AZ, TUNING_ARRAY(tuning_set_az) }, + { TUNING_SET_RATE_PITCHDP, TUNING_ARRAY(tuning_set_rate_pitchDP) }, + { TUNING_SET_RATE_ROLLDP, TUNING_ARRAY(tuning_set_rate_rollDP) }, + { TUNING_SET_RATE_YAWDP, TUNING_ARRAY(tuning_set_rate_yawDP) }, { 0, 0, nullptr } }; diff --git a/ArduPlane/tuning.h b/ArduPlane/tuning.h index e178ea35547..0a005f7dafd 100644 --- a/ArduPlane/tuning.h +++ b/ArduPlane/tuning.h @@ -83,6 +83,9 @@ class AP_Tuning_Plane : public AP_Tuning TUNING_SET_ANG_ROLL_PITCH = 5, TUNING_SET_VXY = 6, TUNING_SET_AZ = 7, + TUNING_SET_RATE_PITCHDP = 8, + TUNING_SET_RATE_ROLLDP = 9, + TUNING_SET_RATE_YAWDP = 10, }; AP_Float *get_param_pointer(uint8_t parm) override; @@ -98,6 +101,9 @@ class AP_Tuning_Plane : public AP_Tuning static const uint8_t tuning_set_ang_roll_pitch[]; static const uint8_t tuning_set_vxy[]; static const uint8_t tuning_set_az[]; + static const uint8_t tuning_set_rate_pitchDP[]; + static const uint8_t tuning_set_rate_rollDP[]; + static const uint8_t tuning_set_rate_yawDP[]; // mask of what params have been set uint64_t have_set; diff --git a/ArduPlane/version.h b/ArduPlane/version.h index ead1f4b9a5e..64aceae908f 100644 --- a/ArduPlane/version.h +++ b/ArduPlane/version.h @@ -6,14 +6,14 @@ #include "ap_version.h" -#define THISFIRMWARE "ArduPlane V4.2.0dev" +#define THISFIRMWARE "ArduPlane V4.3.8-beta1" // the following line is parsed by the autotest scripts -#define FIRMWARE_VERSION 4,2,0,FIRMWARE_VERSION_TYPE_DEV +#define FIRMWARE_VERSION 4,3,7,FIRMWARE_VERSION_TYPE_BETA #define FW_MAJOR 4 -#define FW_MINOR 2 -#define FW_PATCH 0 -#define FW_TYPE FIRMWARE_VERSION_TYPE_DEV +#define FW_MINOR 3 +#define FW_PATCH 7 +#define FW_TYPE FIRMWARE_VERSION_TYPE_BETA #include diff --git a/ArduPlane/wscript b/ArduPlane/wscript index 4ce4e0f02c8..1386bd7b7c1 100644 --- a/ArduPlane/wscript +++ b/ArduPlane/wscript @@ -29,6 +29,7 @@ def build(bld): 'AP_OSD', 'AC_AutoTune', 'AP_KDECAN', + 'AP_Follow', ], ) diff --git a/ArduSub/ArduSub.cpp b/ArduSub/ArduSub.cpp index 81d772dada3..bc76d7af82e 100644 --- a/ArduSub/ArduSub.cpp +++ b/ArduSub/ArduSub.cpp @@ -18,10 +18,10 @@ #include "Sub.h" #define SCHED_TASK(func, rate_hz, max_time_micros, priority) SCHED_TASK_CLASS(Sub, &sub, func, rate_hz, max_time_micros, priority) +#define FAST_TASK(func) FAST_TASK_CLASS(Sub, &sub, func) /* - scheduler table - all regular tasks apart from the fast_loop() - should be listed here. + scheduler table - all tasks should be listed here. All entries in this table must be ordered by priority. @@ -46,10 +46,33 @@ SCHED_TASK_CLASS arguments: */ const AP_Scheduler::Task Sub::scheduler_tasks[] = { + // update INS immediately to get current gyro data populated + FAST_TASK_CLASS(AP_InertialSensor, &sub.ins, update), + // run low level rate controllers that only require IMU data + FAST_TASK(run_rate_controller), + // send outputs to the motors library immediately + FAST_TASK(motors_output), + // run EKF state estimator (expensive) + FAST_TASK(read_AHRS), + // Inertial Nav + FAST_TASK(read_inertia), + // check if ekf has reset target heading + FAST_TASK(check_ekf_yaw_reset), + // run the attitude controllers + FAST_TASK(update_flight_mode), + // update home from EKF if necessary + FAST_TASK(update_home_from_EKF), + // check if we've reached the surface or bottom + FAST_TASK(update_surface_and_bottom_detector), +#if HAL_MOUNT_ENABLED + // camera mount's fast update + FAST_TASK_CLASS(AP_Mount, &sub.camera_mount, update_fast), +#endif + SCHED_TASK(fifty_hz_loop, 50, 75, 3), SCHED_TASK_CLASS(AP_GPS, &sub.gps, update, 50, 200, 6), #if AP_OPTICALFLOW_ENABLED - SCHED_TASK_CLASS(OpticalFlow, &sub.optflow, update, 200, 160, 9), + SCHED_TASK_CLASS(AP_OpticalFlow, &sub.optflow, update, 200, 160, 9), #endif SCHED_TASK(update_batt_compass, 10, 120, 12), SCHED_TASK(read_rangefinder, 20, 100, 15), @@ -61,9 +84,6 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = { SCHED_TASK(one_hz_loop, 1, 100, 33), SCHED_TASK_CLASS(GCS, (GCS*)&sub._gcs, update_receive, 400, 180, 36), SCHED_TASK_CLASS(GCS, (GCS*)&sub._gcs, update_send, 400, 550, 39), -#if AC_FENCE == ENABLED - SCHED_TASK_CLASS(AC_Fence, &sub.fence, update, 10, 100, 42), -#endif #if HAL_MOUNT_ENABLED SCHED_TASK_CLASS(AP_Mount, &sub.camera_mount, update, 50, 75, 45), #endif @@ -78,7 +98,6 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = { #if RPM_ENABLED == ENABLED SCHED_TASK_CLASS(AP_RPM, &sub.rpm_sensor, update, 10, 200, 66), #endif - SCHED_TASK_CLASS(Compass, &sub.compass, cal_update, 100, 100, 69), SCHED_TASK(terrain_update, 10, 100, 72), #if GRIPPER_ENABLED == ENABLED SCHED_TASK_CLASS(AP_Gripper, &sub.g2.gripper, update, 10, 75, 75), @@ -111,52 +130,18 @@ void Sub::get_scheduler_tasks(const AP_Scheduler::Task *&tasks, constexpr int8_t Sub::_failsafe_priorities[5]; -// Main loop - 400hz -void Sub::fast_loop() +void Sub::run_rate_controller() { - // update INS immediately to get current gyro data populated - ins.update(); + const float last_loop_time_s = AP::scheduler().get_last_loop_time_s(); + motors.set_dt(last_loop_time_s); + attitude_control.set_dt(last_loop_time_s); + pos_control.set_dt(last_loop_time_s); //don't run rate controller in manual or motordetection modes if (control_mode != MANUAL && control_mode != MOTOR_DETECT) { - // run low level rate controllers that only require IMU data + // run low level rate controllers that only require IMU data and set loop time attitude_control.rate_controller_run(); } - - // send outputs to the motors library - motors_output(); - - // run EKF state estimator (expensive) - // -------------------- - read_AHRS(); - - // Inertial Nav - // -------------------- - read_inertia(); - - // check if ekf has reset target heading - check_ekf_yaw_reset(); - - // run the attitude controllers - update_flight_mode(); - - // update home from EKF if necessary - update_home_from_EKF(); - - // check if we've reached the surface or bottom - update_surface_and_bottom_detector(); - -#if HAL_MOUNT_ENABLED - // camera mount's fast update - camera_mount.update_fast(); -#endif - - // log sensor health - if (should_log(MASK_LOG_ANY)) { - Log_Sensor_Health(); - } - - AP_Vehicle::fast_loop(); } // 50 Hz tasks @@ -263,10 +248,10 @@ void Sub::three_hz_loop() // check if we've lost terrain data failsafe_terrain_check(); -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // check if we have breached a fence fence_check(); -#endif // AC_FENCE_ENABLED +#endif // AP_FENCE_ENABLED ServoRelayEvents.update_events(); } @@ -285,18 +270,12 @@ void Sub::one_hz_loop() } if (!motors.armed()) { - // make it possible to change ahrs orientation at runtime during initial config - ahrs.update_orientation(); - motors.update_throttle_range(); } // update assigned functions and enable auxiliary servos SRV_Channels::enable_aux_servos(); - // update position controller alt limits - update_poscon_alt_max(); - // log terrain data terrain_logging(); diff --git a/ArduSub/Attitude.cpp b/ArduSub/Attitude.cpp index c5dbc67e737..424f853939a 100644 --- a/ArduSub/Attitude.cpp +++ b/ArduSub/Attitude.cpp @@ -5,7 +5,7 @@ void Sub::get_pilot_desired_lean_angles(float roll_in, float pitch_in, float &roll_out, float &pitch_out, float angle_max) { // sanity check angle max parameter - aparm.angle_max = constrain_int16(aparm.angle_max,1000,8000); + aparm.angle_max.set(constrain_int16(aparm.angle_max,1000,8000)); // limit max lean angle angle_max = constrain_float(angle_max, 1000, aparm.angle_max); @@ -103,7 +103,7 @@ float Sub::get_pilot_desired_climb_rate(float throttle_control) throttle_control = constrain_float(throttle_control,0.0f,1000.0f); // ensure a reasonable deadzone - g.throttle_deadzone = constrain_int16(g.throttle_deadzone, 0, 400); + g.throttle_deadzone.set(constrain_int16(g.throttle_deadzone, 0, 400)); // check throttle is above, below or in the deadband if (throttle_control < deadband_bottom) { @@ -163,29 +163,6 @@ float Sub::get_surface_tracking_climb_rate(int16_t target_rate, float current_al #endif } -// updates position controller's maximum altitude using fence and EKF limits -void Sub::update_poscon_alt_max() -{ - // minimum altitude, ie. maximum depth - // interpreted as no limit if left as zero - float min_alt_cm = 0.0; - - // no limit if greater than 100, a limit is necessary, - // or the vehicle will try to fly out of the water - float max_alt_cm = g.surface_depth; // minimum depth - -#if AC_FENCE == ENABLED - // set fence altitude limit in position controller - if ((fence.get_enabled_fences() & AC_FENCE_TYPE_ALT_MAX) != 0) { - min_alt_cm = fence.get_safe_alt_min()*100.0f; - max_alt_cm = fence.get_safe_alt_max()*100.0f; - } -#endif - // pass limit to pos controller - pos_control.set_alt_min(min_alt_cm); - pos_control.set_alt_max(max_alt_cm); -} - // rotate vector from vehicle's perspective to North-East frame void Sub::rotate_body_frame_to_NE(float &x, float &y) { diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index d3976fb84f3..3c6ce9d2901 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -1,6 +1,7 @@ #include "Sub.h" #include "GCS_Mavlink.h" +#include MAV_TYPE GCS_Sub::frame_type() const { @@ -154,7 +155,7 @@ void GCS_MAVLINK_Sub::send_pid_tuning() const Vector3f &gyro = ahrs.get_gyro(); if (g.gcs_pid_mask & 1) { - const AP_Logger::PID_Info &pid_info = attitude_control.get_rate_roll_pid().get_pid_info(); + const AP_PIDInfo &pid_info = attitude_control.get_rate_roll_pid().get_pid_info(); mavlink_msg_pid_tuning_send(chan, PID_TUNING_ROLL, pid_info.target*0.01f, degrees(gyro.x), @@ -169,7 +170,7 @@ void GCS_MAVLINK_Sub::send_pid_tuning() } } if (g.gcs_pid_mask & 2) { - const AP_Logger::PID_Info &pid_info = attitude_control.get_rate_pitch_pid().get_pid_info(); + const AP_PIDInfo &pid_info = attitude_control.get_rate_pitch_pid().get_pid_info(); mavlink_msg_pid_tuning_send(chan, PID_TUNING_PITCH, pid_info.target*0.01f, degrees(gyro.y), @@ -184,7 +185,7 @@ void GCS_MAVLINK_Sub::send_pid_tuning() } } if (g.gcs_pid_mask & 4) { - const AP_Logger::PID_Info &pid_info = attitude_control.get_rate_yaw_pid().get_pid_info(); + const AP_PIDInfo &pid_info = attitude_control.get_rate_yaw_pid().get_pid_info(); mavlink_msg_pid_tuning_send(chan, PID_TUNING_YAW, pid_info.target*0.01f, degrees(gyro.z), @@ -199,10 +200,10 @@ void GCS_MAVLINK_Sub::send_pid_tuning() } } if (g.gcs_pid_mask & 8) { - const AP_Logger::PID_Info &pid_info = sub.pos_control.get_accel_z_pid().get_pid_info(); + const AP_PIDInfo &pid_info = sub.pos_control.get_accel_z_pid().get_pid_info(); mavlink_msg_pid_tuning_send(chan, PID_TUNING_ACCZ, pid_info.target*0.01f, - -(ahrs.get_accel_ef_blended().z + GRAVITY_MSS), + -(ahrs.get_accel_ef().z + GRAVITY_MSS), pid_info.FF*0.01f, pid_info.P*0.01f, pid_info.I*0.01f, @@ -255,6 +256,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_RAW_SENSORS], 0), @@ -264,6 +266,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_EXTENDED_STATUS], 0), @@ -273,6 +276,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_RC_CHANNELS], 0), @@ -282,6 +286,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("POSITION", 4, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_POSITION], 0), @@ -291,6 +296,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_EXTRA1], 0), @@ -300,6 +306,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_EXTRA2], 0), @@ -309,6 +316,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_EXTRA3], 0), @@ -318,6 +326,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK_Parameters, streamRates[GCS_MAVLINK::STREAM_PARAMS], 0), AP_GROUPEND @@ -374,9 +383,8 @@ static const ap_message STREAM_EXTRA3_msgs[] = { #endif MSG_BATTERY2, MSG_BATTERY_STATUS, - MSG_MOUNT_STATUS, + MSG_GIMBAL_DEVICE_ATTITUDE_STATUS, MSG_OPTICAL_FLOW, - MSG_GIMBAL_REPORT, MSG_MAG_CAL_REPORT, MSG_MAG_CAL_PROGRESS, MSG_EKF_STATUS_REPORT, @@ -652,6 +660,7 @@ void GCS_MAVLINK_Sub::handleMessage(const mavlink_message_t &msg) break; } + bool z_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_Z_IGNORE; bool pos_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE; bool vel_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE; bool acc_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE; @@ -663,7 +672,7 @@ void GCS_MAVLINK_Sub::handleMessage(const mavlink_message_t &msg) * bool yaw_rate_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE; */ - if (!pos_ignore && sub.control_mode == ALT_HOLD) { // Control only target depth when in ALT_HOLD + if (!z_ignore && sub.control_mode == ALT_HOLD) { // Control only target depth when in ALT_HOLD sub.pos_control.set_pos_target_z_cm(packet.alt*100); break; } @@ -709,30 +718,6 @@ void GCS_MAVLINK_Sub::handleMessage(const mavlink_message_t &msg) #endif break; - case MAVLINK_MSG_ID_SET_HOME_POSITION: { - send_received_message_deprecation_warning(STR_VALUE(MAVLINK_MSG_ID_SET_HOME_POSITION)); - - mavlink_set_home_position_t packet; - mavlink_msg_set_home_position_decode(&msg, &packet); - if ((packet.latitude == 0) && (packet.longitude == 0) && (packet.altitude == 0)) { - if (!sub.set_home_to_current_location(true)) { - // ignore this failure - } - } else { - Location new_home_loc; - new_home_loc.lat = packet.latitude; - new_home_loc.lng = packet.longitude; - new_home_loc.alt = packet.altitude / 10; - if (sub.far_from_EKF_origin(new_home_loc)) { - break; - } - if (!sub.set_home(new_home_loc, true)) { - // silently ignored - } - } - break; - } - // This adds support for leak detectors in a separate enclosure // connected to a mavlink enabled subsystem case MAVLINK_MSG_ID_SYS_STATUS: { diff --git a/ArduSub/GCS_Sub.cpp b/ArduSub/GCS_Sub.cpp index 0946c397ad3..ede014dcdc6 100644 --- a/ArduSub/GCS_Sub.cpp +++ b/ArduSub/GCS_Sub.cpp @@ -57,7 +57,7 @@ void GCS_Sub::update_vehicle_sensor_status_flags() } #if AP_OPTICALFLOW_ENABLED - const OpticalFlow *optflow = AP::opticalflow(); + const AP_OpticalFlow *optflow = AP::opticalflow(); if (optflow && optflow->enabled()) { control_sensors_present |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW; control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW; @@ -96,8 +96,10 @@ void GCS_Sub::update_vehicle_sensor_status_flags() #endif } +#if AP_LTM_TELEM_ENABLED // avoid building/linking LTM: void AP_LTM_Telem::init() {}; +#endif #if AP_DEVO_TELEM_ENABLED // avoid building/linking Devo: void AP_DEVO_Telem::init() {}; diff --git a/ArduSub/Log.cpp b/ArduSub/Log.cpp index 482bf404d23..c070163e473 100644 --- a/ArduSub/Log.cpp +++ b/ArduSub/Log.cpp @@ -168,22 +168,6 @@ void Sub::Log_Write_Data(LogDataID id, float value) } } -// logs when baro or compass becomes unhealthy -void Sub::Log_Sensor_Health() -{ - // check baro - if (sensor_health.baro != barometer.healthy()) { - sensor_health.baro = barometer.healthy(); - AP::logger().Write_Error(LogErrorSubsystem::BARO, (sensor_health.baro ? LogErrorCode::ERROR_RESOLVED : LogErrorCode::UNHEALTHY)); - } - - // check compass - if (sensor_health.compass != compass.healthy()) { - sensor_health.compass = compass.healthy(); - AP::logger().Write_Error(LogErrorSubsystem::COMPASS, (sensor_health.compass ? LogErrorCode::ERROR_RESOLVED : LogErrorCode::UNHEALTHY)); - } -} - struct PACKED log_GuidedTarget { LOG_PACKET_HEADER; uint64_t time_us; @@ -322,7 +306,6 @@ void Sub::Log_Write_Data(LogDataID id, uint32_t value) {} void Sub::Log_Write_Data(LogDataID id, int16_t value) {} void Sub::Log_Write_Data(LogDataID id, uint16_t value) {} void Sub::Log_Write_Data(LogDataID id, float value) {} -void Sub::Log_Sensor_Health() {} void Sub::Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target) {} void Sub::Log_Write_Vehicle_Startup_Messages() {} diff --git a/ArduSub/Parameters.cpp b/ArduSub/Parameters.cpp index 549c7af0686..27cf80d5821 100644 --- a/ArduSub/Parameters.cpp +++ b/ArduSub/Parameters.cpp @@ -521,7 +521,7 @@ const AP_Param::Info Sub::var_info[] = { GOBJECT(can_mgr, "CAN_", AP_CANManager), #endif -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#if AP_SIM_ENABLED GOBJECT(sitl, "SIM_", SITL::SIM), #endif @@ -543,12 +543,6 @@ const AP_Param::Info Sub::var_info[] = { // @Path: ../libraries/AP_Scheduler/AP_Scheduler.cpp GOBJECT(scheduler, "SCHED_", AP_Scheduler), -#if AC_FENCE == ENABLED - // @Group: FENCE_ - // @Path: ../libraries/AC_Fence/AC_Fence.cpp - GOBJECT(fence, "FENCE_", AC_Fence), -#endif - #if AVOIDANCE_ENABLED == ENABLED // @Group: AVOID_ // @Path: ../libraries/AC_Avoidance/AC_Avoid.cpp @@ -602,7 +596,7 @@ const AP_Param::Info Sub::var_info[] = { #if AP_OPTICALFLOW_ENABLED // @Group: FLOW // @Path: ../libraries/AP_OpticalFlow/AP_OpticalFlow.cpp - GOBJECT(optflow, "FLOW", OpticalFlow), + GOBJECT(optflow, "FLOW", AP_OpticalFlow), #endif #if RPM_ENABLED == ENABLED @@ -699,6 +693,7 @@ void Sub::load_parameters() g.format_version.set_and_save(Parameters::k_format_version); hal.console->println("done."); } + g.format_version.set_default(Parameters::k_format_version); uint32_t before = AP_HAL::micros(); // Load all auto-loaded EEPROM variables @@ -720,11 +715,11 @@ void Sub::load_parameters() AP_Param::set_default_by_name("RC3_TRIM", 1100); AP_Param::set_default_by_name("COMPASS_OFFS_MAX", 1000); AP_Param::set_default_by_name("INS_GYR_CAL", 0); - AP_Param::set_default_by_name("MNT_TYPE", 1); - AP_Param::set_default_by_name("MNT_DEFLT_MODE", MAV_MOUNT_MODE_RC_TARGETING); - AP_Param::set_default_by_name("MNT_JSTICK_SPD", 100); - AP_Param::set_by_name("MNT_RC_IN_PAN", 7); - AP_Param::set_by_name("MNT_RC_IN_TILT", 8); + AP_Param::set_default_by_name("MNT1_TYPE", 1); + AP_Param::set_default_by_name("MNT1_DEFLT_MODE", MAV_MOUNT_MODE_RC_TARGETING); + AP_Param::set_default_by_name("MNT1_RC_RATE", 30); + AP_Param::set_default_by_name("RC7_OPTION", 214); // MOUNT1_YAW + AP_Param::set_default_by_name("RC8_OPTION", 213); // MOUNT1_PITCH // We should ignore this parameter since ROVs are neutral buoyancy AP_Param::set_by_name("MOT_THST_HOVER", 0.5); @@ -741,6 +736,11 @@ void Sub::load_parameters() AP_Param::convert_class(info.old_key, &airspeed, airspeed.var_info, old_index, old_top_element, false); #endif + + // PARAMETER_CONVERSION - Added: Mar-2022 +#if AP_FENCE_ENABLED + AP_Param::convert_class(g.k_param_fence_old, &fence, fence.var_info, 0, 0, true); +#endif } void Sub::convert_old_parameters() diff --git a/ArduSub/Parameters.h b/ArduSub/Parameters.h index 2a90c07b3ac..ff2cba528f0 100644 --- a/ArduSub/Parameters.h +++ b/ArduSub/Parameters.h @@ -87,7 +87,7 @@ class Parameters { k_param_pos_control, // Position Control k_param_wp_nav, // Waypoint navigation k_param_mission, // Mission library - k_param_fence, // Fence Library + k_param_fence_old, // only used for conversion k_param_terrain, // Terrain database k_param_rally, // Disabled k_param_circle_nav, // Disabled diff --git a/ArduSub/Sub.cpp b/ArduSub/Sub.cpp index c55a6cd1a37..bd73ce41a6b 100644 --- a/ArduSub/Sub.cpp +++ b/ArduSub/Sub.cpp @@ -32,17 +32,13 @@ Sub::Sub() auto_yaw_mode(AUTO_YAW_LOOK_AT_NEXT_WP), inertial_nav(ahrs), ahrs_view(ahrs, ROTATION_NONE), - attitude_control(ahrs_view, aparm, motors, scheduler.get_loop_period_s()), - pos_control(ahrs_view, inertial_nav, motors, attitude_control, scheduler.get_loop_period_s()), + attitude_control(ahrs_view, aparm, motors), + pos_control(ahrs_view, inertial_nav, motors, attitude_control), wp_nav(inertial_nav, ahrs_view, pos_control, attitude_control), loiter_nav(inertial_nav, ahrs_view, pos_control, attitude_control), circle_nav(inertial_nav, ahrs_view, pos_control), param_loader(var_info) { - // init sensor error logging flags - sensor_health.baro = true; - sensor_health.compass = true; - #if CONFIG_HAL_BOARD != HAL_BOARD_SITL failsafe.pilot_input = true; #endif diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index 36b1819bcd2..e3d0240457a 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -32,7 +32,6 @@ #include #include #include -#include #include // interface and maths for accelerometer calibration #include // ArduPilot Mega Vector/Matrix math Library #include // ArduPilot Mega Declination Helper Library @@ -47,7 +46,7 @@ #include #include // Mission command library #include // Attitude control library -#include // Position control library +#include // Position control library #include // AP Motors library #include // Filter library #include // APM relay @@ -57,10 +56,8 @@ #include // Waypoint navigation library #include #include // circle navigation library -#include // Fence library #include // main loop scheduler #include // loop perf monitoring -#include // Notify library #include // Battery monitor library #include #include // Joystick/gamepad button function assignment @@ -166,7 +163,7 @@ class Sub : public AP_Vehicle { // Optical flow sensor #if AP_OPTICALFLOW_ENABLED - OpticalFlow optflow; + AP_OpticalFlow optflow; #endif // system time in milliseconds of last recorded yaw reset from ekf @@ -235,7 +232,6 @@ class Sub : public AP_Vehicle { // sensor health for logging struct { - uint8_t baro : 1; // true if any single baro is healthy uint8_t depth : 1; // true if depth sensor is healthy uint8_t compass : 1; // true if compass is healthy } sensor_health; @@ -331,7 +327,7 @@ class Sub : public AP_Vehicle { // To-Do: move inertial nav up or other navigation variables down here AC_AttitudeControl_Sub attitude_control; - AC_PosControl_Sub pos_control; + AC_PosControl pos_control; AC_WPNav wp_nav; AC_Loiter loiter_nav; @@ -347,11 +343,6 @@ class Sub : public AP_Vehicle { AP_Mount camera_mount; #endif - // AC_Fence library to reduce fly-aways -#if AC_FENCE == ENABLED - AC_Fence fence; -#endif - #if AVOIDANCE_ENABLED == ENABLED AC_Avoid avoid; #endif @@ -386,7 +377,7 @@ class Sub : public AP_Vehicle { static const AP_Param::Info var_info[]; static const struct LogStructure log_structure[]; - void fast_loop() override; + void run_rate_controller(); void fifty_hz_loop(); void update_batt_compass(void); void ten_hz_logging_loop(); @@ -404,7 +395,6 @@ class Sub : public AP_Vehicle { float get_look_ahead_yaw(); float get_pilot_desired_climb_rate(float throttle_control); float get_surface_tracking_climb_rate(int16_t target_rate, float current_alt_target, float dt); - void update_poscon_alt_max(); void rotate_body_frame_to_NE(float &x, float &y); void Log_Write_Control_Tuning(); void Log_Write_Attitude(); @@ -413,7 +403,6 @@ class Sub : public AP_Vehicle { void Log_Write_Data(LogDataID id, int16_t value); void Log_Write_Data(LogDataID id, uint16_t value); void Log_Write_Data(LogDataID id, float value); - void Log_Sensor_Health(); void Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target); void Log_Write_Vehicle_Startup_Messages(); void load_parameters(void) override; diff --git a/ArduSub/commands_logic.cpp b/ArduSub/commands_logic.cpp index 70a006cdc03..bfeb57bc5fd 100644 --- a/ArduSub/commands_logic.cpp +++ b/ArduSub/commands_logic.cpp @@ -353,7 +353,10 @@ void Sub::do_circle(const AP_Mission::Mission_Command& cmd) } // calculate radius - uint8_t circle_radius_m = HIGHBYTE(cmd.p1); // circle radius held in high byte of p1 + uint16_t circle_radius_m = HIGHBYTE(cmd.p1); // circle radius held in high byte of p1 + if (cmd.type_specific_bits & (1U << 0)) { + circle_radius_m *= 10; + } // move to edge of circle (verify_circle) will ensure we begin circling once we reach the edge auto_circle_movetoedge_start(circle_center, circle_radius_m); @@ -682,6 +685,6 @@ void Sub::do_roi(const AP_Mission::Mission_Command& cmd) void Sub::do_mount_control(const AP_Mission::Mission_Command& cmd) { #if HAL_MOUNT_ENABLED - camera_mount.set_angle_targets(cmd.content.mount_control.roll, cmd.content.mount_control.pitch, cmd.content.mount_control.yaw); + camera_mount.set_angle_target(cmd.content.mount_control.roll, cmd.content.mount_control.pitch, cmd.content.mount_control.yaw, false); #endif } diff --git a/ArduSub/config.h b/ArduSub/config.h index 1b8828eafdc..a7bb740cce9 100644 --- a/ArduSub/config.h +++ b/ArduSub/config.h @@ -230,11 +230,6 @@ MASK_LOG_MOTBATT #endif -// Enable/disable Fence -#ifndef AC_FENCE -#define AC_FENCE ENABLED -#endif - #ifndef AC_RALLY #define AC_RALLY DISABLED #endif diff --git a/ArduSub/control_acro.cpp b/ArduSub/control_acro.cpp index 0ea73b30b26..959ad69f8e8 100644 --- a/ArduSub/control_acro.cpp +++ b/ArduSub/control_acro.cpp @@ -76,7 +76,7 @@ void Sub::get_pilot_desired_angle_rates(int16_t roll_in, int16_t pitch_in, int16 // range check expo if (g.acro_expo > 1.0f) { - g.acro_expo = 1.0f; + g.acro_expo.set(1.0f); } // roll expo diff --git a/ArduSub/control_althold.cpp b/ArduSub/control_althold.cpp index 2e49e3c046d..a420cfe3149 100644 --- a/ArduSub/control_althold.cpp +++ b/ArduSub/control_althold.cpp @@ -37,7 +37,7 @@ void Sub::althold_run() if (!motors.armed()) { motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE); // Sub vehicles do not stabilize roll/pitch/yaw when not auto-armed (i.e. on the ground, pilot has never raised throttle) - attitude_control.set_throttle_out(0,true,g.throttle_filt); + attitude_control.set_throttle_out(0.5,true,g.throttle_filt); attitude_control.relax_attitude_controllers(); pos_control.relax_z_controller(motors.get_throttle_hover()); last_pilot_heading = ahrs.yaw_sensor; @@ -101,33 +101,20 @@ void Sub::althold_run() } void Sub::control_depth() { - // Hold actual position until zero derivative is detected - static bool engageStopZ = true; - // Get last user velocity direction to check for zero derivative points - static bool lastVelocityZWasNegative = false; - if (fabsf(channel_throttle->norm_input()-0.5f) > 0.05f) { // Throttle input above 5% - // output pilot's throttle - attitude_control.set_throttle_out(channel_throttle->norm_input(), false, g.throttle_filt); - // reset z targets to current values - pos_control.relax_z_controller(channel_throttle->norm_input()); - engageStopZ = true; - lastVelocityZWasNegative = is_negative(inertial_nav.get_velocity_z_up_cms()); - } else { // hold z - - if (ap.at_bottom) { - pos_control.init_z_controller(); - pos_control.set_pos_target_z_cm(inertial_nav.get_position_z_up_cm() + 10.0); // set target to 10 cm above bottom + float target_climb_rate_cm_s = get_pilot_desired_climb_rate(channel_throttle->get_control_in()); + target_climb_rate_cm_s = constrain_float(target_climb_rate_cm_s, -get_pilot_speed_dn(), g.pilot_speed_up); + + // desired_climb_rate returns 0 when within the deadzone. + //we allow full control to the pilot, but as soon as there's no input, we handle being at surface/bottom + if (fabsf(target_climb_rate_cm_s) < 0.05f) { + if (ap.at_surface) { + pos_control.set_pos_target_z_cm(MIN(pos_control.get_pos_target_z_cm(), g.surface_depth - 5.0f)); // set target to 5 cm below surface level + } else if (ap.at_bottom) { + pos_control.set_pos_target_z_cm(MAX(inertial_nav.get_position_z_up_cm() + 10.0f, pos_control.get_pos_target_z_cm())); // set target to 10 cm above bottom } + } - // Detects a zero derivative - // When detected, move the altitude set point to the actual position - // This will avoid any problem related to joystick delays - // or smaller input signals - if(engageStopZ && (lastVelocityZWasNegative ^ is_negative(inertial_nav.get_velocity_z_up_cms()))) { - engageStopZ = false; - pos_control.init_z_controller(); - } + pos_control.set_pos_target_z_from_climb_rate_cm(target_climb_rate_cm_s); + pos_control.update_z_controller(); - pos_control.update_z_controller(); - } } diff --git a/ArduSub/control_auto.cpp b/ArduSub/control_auto.cpp index 8114a220fd3..4860cbc15c4 100644 --- a/ArduSub/control_auto.cpp +++ b/ArduSub/control_auto.cpp @@ -162,10 +162,10 @@ void Sub::auto_wp_run() // call attitude controller if (auto_yaw_mode == AUTO_YAW_HOLD) { - // roll & pitch from waypoint controller, yaw rate from pilot + // roll & pitch & yaw rate from pilot attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate); } else { - // roll, pitch from waypoint controller, yaw heading from auto_heading() + // roll, pitch from pilot, yaw heading from auto_heading() attitude_control.input_euler_angle_roll_pitch_yaw(target_roll, target_pitch, get_auto_heading(), true); } } @@ -180,7 +180,7 @@ void Sub::auto_circle_movetoedge_start(const Location &circle_center, float radi // set circle radius if (!is_zero(radius_m)) { - circle_nav.set_radius(radius_m * 100.0f); + circle_nav.set_radius_cm(radius_m * 100.0f); } // check our distance from edge of circle @@ -339,7 +339,7 @@ void Sub::auto_loiter_run() float target_roll, target_pitch; get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, aparm.angle_max); - // roll & pitch from waypoint controller, yaw rate from pilot + // roll & pitch & yaw rate from pilot attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate); } diff --git a/ArduSub/control_guided.cpp b/ArduSub/control_guided.cpp index bcab8732d9d..851ff8fa909 100644 --- a/ArduSub/control_guided.cpp +++ b/ArduSub/control_guided.cpp @@ -129,7 +129,7 @@ bool Sub::guided_set_destination(const Vector3f& destination) guided_pos_control_start(); } -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // reject destination if outside the fence const Location dest_loc(destination, Location::AltFrame::ABOVE_ORIGIN); if (!fence.check_destination_within_fence(dest_loc)) { @@ -157,7 +157,7 @@ bool Sub::guided_set_destination(const Location& dest_loc) guided_pos_control_start(); } -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // reject destination outside the fence. // Note: there is a danger that a target specified as a terrain altitude might not be checked if the conversion to alt-above-home fails if (!fence.check_destination_within_fence(dest_loc)) { @@ -201,7 +201,7 @@ bool Sub::guided_set_destination_posvel(const Vector3f& destination, const Vecto guided_posvel_control_start(); } -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // reject destination if outside the fence const Location dest_loc(destination, Location::AltFrame::ABOVE_ORIGIN); if (!fence.check_destination_within_fence(dest_loc)) { @@ -315,10 +315,10 @@ void Sub::guided_pos_control_run() // call attitude controller if (auto_yaw_mode == AUTO_YAW_HOLD) { - // roll & pitch from waypoint controller, yaw rate from pilot + // roll & pitch & yaw rate from pilot attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate); } else { - // roll, pitch from waypoint controller, yaw heading from auto_heading() + // roll, pitch from pilot, yaw heading from auto_heading() attitude_control.input_euler_angle_roll_pitch_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), get_auto_heading(), true); } } @@ -371,10 +371,10 @@ void Sub::guided_vel_control_run() // call attitude controller if (auto_yaw_mode == AUTO_YAW_HOLD) { - // roll & pitch from waypoint controller, yaw rate from pilot + // roll & pitch & yaw rate from pilot attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate); } else { - // roll, pitch from waypoint controller, yaw heading from auto_heading() + // roll, pitch from pilot, yaw heading from auto_heading() attitude_control.input_euler_angle_roll_pitch_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), get_auto_heading(), true); } } @@ -437,10 +437,10 @@ void Sub::guided_posvel_control_run() // call attitude controller if (auto_yaw_mode == AUTO_YAW_HOLD) { - // roll & pitch from waypoint controller, yaw rate from pilot + // roll & pitch & yaw rate from pilot attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate); } else { - // roll, pitch from waypoint controller, yaw heading from auto_heading() + // roll, pitch from pilot, yaw heading from auto_heading() attitude_control.input_euler_angle_roll_pitch_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), get_auto_heading(), true); } } diff --git a/ArduSub/control_stabilize.cpp b/ArduSub/control_stabilize.cpp index 8d135fa82a0..356ce2479be 100644 --- a/ArduSub/control_stabilize.cpp +++ b/ArduSub/control_stabilize.cpp @@ -16,7 +16,6 @@ void Sub::stabilize_run() { uint32_t tnow = AP_HAL::millis(); float target_roll, target_pitch; - float target_yaw_rate; // if not armed set throttle to zero and exit immediately if (!motors.armed()) { @@ -34,7 +33,7 @@ void Sub::stabilize_run() get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, aparm.angle_max); // get pilot's desired yaw rate - target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); + float target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); // call attitude controller // update attitude controller targets diff --git a/ArduSub/control_surface.cpp b/ArduSub/control_surface.cpp index cd9e20bc515..407b04ab5a8 100644 --- a/ArduSub/control_surface.cpp +++ b/ArduSub/control_surface.cpp @@ -21,7 +21,6 @@ bool Sub::surface_init() void Sub::surface_run() { float target_roll, target_pitch; - float target_yaw_rate; // if not armed set throttle to zero and exit immediately if (!motors.armed()) { @@ -43,7 +42,7 @@ void Sub::surface_run() get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, aparm.angle_max); // get pilot's desired yaw rate - target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); + float target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); // call attitude controller attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate); diff --git a/ArduSub/defines.h b/ArduSub/defines.h index 6abaece5b1e..b3c7109f10f 100644 --- a/ArduSub/defines.h +++ b/ArduSub/defines.h @@ -186,6 +186,7 @@ enum LoggingParameters { #define FS_TERRAIN_RECOVER_TIMEOUT_MS 10000 // for mavlink SET_POSITION_TARGET messages +#define MAVLINK_SET_POS_TYPE_MASK_Z_IGNORE (1<<2) #define MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE ((1<<0) | (1<<1) | (1<<2)) #define MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE ((1<<3) | (1<<4) | (1<<5)) #define MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE ((1<<6) | (1<<7) | (1<<8)) diff --git a/ArduSub/fence.cpp b/ArduSub/fence.cpp index 56954855c4f..7d89c89cae1 100644 --- a/ArduSub/fence.cpp +++ b/ArduSub/fence.cpp @@ -2,7 +2,7 @@ // Code to integrate AC_Fence library with main ArduSub code -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // fence_check - ask fence library to check for breaches and initiate the response // called at 1hz diff --git a/ArduSub/flight_mode.cpp b/ArduSub/flight_mode.cpp index 2801d2cad84..cfd9c5943b5 100644 --- a/ArduSub/flight_mode.cpp +++ b/ArduSub/flight_mode.cpp @@ -82,7 +82,7 @@ bool Sub::set_mode(control_mode_t mode, ModeReason reason) camera.set_is_auto_mode(control_mode == AUTO); #endif -#if AC_FENCE == ENABLED +#if AP_FENCE_ENABLED // pilot requested flight mode change during a fence breach indicates pilot is attempting to manually recover // this flight mode change could be automatic (i.e. fence, battery, GPS or GCS failsafe) // but it should be harmless to disable the fence temporarily in these situations as well diff --git a/ArduSub/joystick.cpp b/ArduSub/joystick.cpp index d77268e7d47..bbbd19c3464 100644 --- a/ArduSub/joystick.cpp +++ b/ArduSub/joystick.cpp @@ -183,7 +183,7 @@ void Sub::handle_jsbutton_press(uint8_t _button, bool shift, bool held) case JSButton::button_function_t::k_mount_center: #if HAL_MOUNT_ENABLED - camera_mount.set_angle_targets(0, 0, 0); + camera_mount.set_angle_target(0, 0, 0, false); // for some reason the call to set_angle_targets changes the mode to mavlink targeting! camera_mount.set_mode(MAV_MOUNT_MODE_RC_TARGETING); #endif diff --git a/ArduSub/radio.cpp b/ArduSub/radio.cpp index e79d4c7ac61..a5c21047082 100644 --- a/ArduSub/radio.cpp +++ b/ArduSub/radio.cpp @@ -50,7 +50,6 @@ void Sub::init_rc_in() void Sub::init_rc_out() { motors.set_update_rate(g.rc_speed); - motors.set_loop_rate(scheduler.get_loop_rate_hz()); motors.init((AP_Motors::motor_frame_class)g.frame_configuration.get(), AP_Motors::motor_frame_type::MOTOR_FRAME_TYPE_PLUS); motors.convert_pwm_min_max_param(channel_throttle->get_radio_min(), channel_throttle->get_radio_max()); motors.update_throttle_range(); diff --git a/ArduSub/system.cpp b/ArduSub/system.cpp index c0503d4e387..e3d398f053d 100644 --- a/ArduSub/system.cpp +++ b/ArduSub/system.cpp @@ -24,10 +24,6 @@ void Sub::init_ardupilot() g2.gripper.init(); #endif -#if AC_FENCE == ENABLED - fence.init(); -#endif - // initialise notify system notify.init(); @@ -98,7 +94,7 @@ void Sub::init_ardupilot() // initialise camera mount camera_mount.init(); // This step ncessary so the servo is properly initialized - camera_mount.set_angle_targets(0, 0, 0); + camera_mount.set_angle_target(0, 0, 0, false); // for some reason the call to set_angle_targets changes the mode to mavlink targeting! camera_mount.set_mode(MAV_MOUNT_MODE_RC_TARGETING); #endif diff --git a/ArduSub/wscript b/ArduSub/wscript index 04b1f4fa52f..de8dc48a7b9 100644 --- a/ArduSub/wscript +++ b/ArduSub/wscript @@ -19,7 +19,6 @@ def build(bld): 'AP_TemperatureSensor', 'AP_Arming', 'AP_KDECAN', - 'AP_RCMapper', 'AP_OSD', ], ) diff --git a/Blimp/AP_Arming.cpp b/Blimp/AP_Arming.cpp index e02d1f4fe58..17b12078a3d 100644 --- a/Blimp/AP_Arming.cpp +++ b/Blimp/AP_Arming.cpp @@ -1,21 +1,5 @@ #include "Blimp.h" - -// performs pre-arm checks. expects to be called at 1hz. -void AP_Arming_Blimp::update(void) -{ - // perform pre-arm checks & display failures every 30 seconds - static uint8_t pre_arm_display_counter = PREARM_DISPLAY_PERIOD/2; - pre_arm_display_counter++; - bool display_fail = false; - if (pre_arm_display_counter >= PREARM_DISPLAY_PERIOD) { - display_fail = true; - pre_arm_display_counter = 0; - } - - pre_arm_checks(display_fail); -} - bool AP_Arming_Blimp::pre_arm_checks(bool display_failure) { const bool passed = run_pre_arm_checks(display_failure); diff --git a/Blimp/AP_Arming.h b/Blimp/AP_Arming.h index 8955e093627..b092fa9ee48 100644 --- a/Blimp/AP_Arming.h +++ b/Blimp/AP_Arming.h @@ -19,8 +19,6 @@ class AP_Arming_Blimp : public AP_Arming AP_Arming_Blimp(const AP_Arming_Blimp &other) = delete; AP_Arming_Blimp &operator=(const AP_Arming_Blimp&) = delete; - void update(void); - bool rc_calibration_checks(bool display_failure) override; bool disarm(AP_Arming::Method method, bool do_disarm_checks=true) override; diff --git a/Blimp/Blimp.cpp b/Blimp/Blimp.cpp index 861217e0fde..9c9f457b137 100644 --- a/Blimp/Blimp.cpp +++ b/Blimp/Blimp.cpp @@ -22,10 +22,10 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); #define SCHED_TASK(func, rate_hz, max_time_micros, priority) SCHED_TASK_CLASS(Blimp, &blimp, func, rate_hz, max_time_micros, priority) +#define FAST_TASK(func) FAST_TASK_CLASS(Blimp, &blimp, func) /* - scheduler table - all regular tasks apart from the fast_loop() - should be listed here. + scheduler table - all tasks should be listed here. All entries in this table must be ordered by priority. @@ -49,6 +49,21 @@ SCHED_TASK_CLASS arguments: */ const AP_Scheduler::Task Blimp::scheduler_tasks[] = { + // update INS immediately to get current gyro data populated + FAST_TASK_CLASS(AP_InertialSensor, &blimp.ins, update), + // send outputs to the motors library immediately + FAST_TASK(motors_output), + // run EKF state estimator (expensive) + FAST_TASK(read_AHRS), + // Inertial Nav + FAST_TASK(read_inertia), + // check if ekf has reset target heading or position + FAST_TASK(check_ekf_reset), + // run the attitude controllers + FAST_TASK(update_flight_mode), + // update home from EKF if necessary + FAST_TASK(update_home_from_EKF), + SCHED_TASK(rc_loop, 100, 130, 3), SCHED_TASK(throttle_loop, 50, 75, 6), SCHED_TASK_CLASS(AP_GPS, &blimp.gps, update, 50, 200, 9), @@ -76,7 +91,6 @@ const AP_Scheduler::Task Blimp::scheduler_tasks[] = { #endif SCHED_TASK_CLASS(AP_InertialSensor, &blimp.ins, periodic, 400, 50, 66), SCHED_TASK_CLASS(AP_Scheduler, &blimp.scheduler, update_logging, 0.1, 75, 69), - SCHED_TASK_CLASS(Compass, &blimp.compass, cal_update, 100, 100, 72), #if STATS_ENABLED == ENABLED SCHED_TASK_CLASS(AP_Stats, &blimp.g2.stats, update, 1, 100, 75), #endif @@ -93,40 +107,6 @@ void Blimp::get_scheduler_tasks(const AP_Scheduler::Task *&tasks, constexpr int8_t Blimp::_failsafe_priorities[4]; -// Main loop -void Blimp::fast_loop() -{ - // update INS immediately to get current gyro data populated - ins.update(); - - // send outputs to the motors library immediately - motors_output(); - - // run EKF state estimator (expensive) - // -------------------- - read_AHRS(); - - // Inertial Nav - // -------------------- - read_inertia(); - - // check if ekf has reset target heading or position - check_ekf_reset(); - - // run the attitude controllers - update_flight_mode(); - - // update home from EKF if necessary - update_home_from_EKF(); - - // log sensor health - if (should_log(MASK_LOG_ANY)) { - Log_Sensor_Health(); - } - - AP_Vehicle::fast_loop(); //just does gyro fft -} - // rc_loops - reads user input from transmitter/receiver // called at 100hz void Blimp::rc_loop() @@ -223,13 +203,6 @@ void Blimp::one_hz_loop() Log_Write_Data(LogDataID::AP_STATE, ap.value); } - arming.update(); - - if (!motors->armed()) { - // make it possible to change ahrs orientation at runtime during initial config - ahrs.update_orientation(); - } - // update assigned functions and enable auxiliary servos SRV_Channels::enable_aux_servos(); @@ -289,15 +262,11 @@ Blimp::Blimp(void) : logger(g.log_bitmask), flight_modes(&g.flight_mode1), control_mode(Mode::Number::MANUAL), - land_accel_ef_filter(LAND_DETECTOR_ACCEL_LPF_CUTOFF), rc_throttle_control_in_filter(1.0f), inertial_nav(ahrs), param_loader(var_info), flightmode(&mode_manual) { - // init sensor error logging flags - sensor_health.baro = true; - sensor_health.compass = true; } Blimp blimp; diff --git a/Blimp/Blimp.h b/Blimp/Blimp.h index 5aece1b6747..fff397191d7 100644 --- a/Blimp/Blimp.h +++ b/Blimp/Blimp.h @@ -34,7 +34,6 @@ #include // Application dependencies -#include #include // ArduPilot Mega Flash Memory Library #include // ArduPilot Mega Vector/Matrix math Library // #include // interface and maths for accelerometer calibration @@ -188,12 +187,6 @@ class Blimp : public AP_Vehicle return failsafe.radio || battery.has_failsafed() || failsafe.gcs || failsafe.ekf; } - // sensor health for logging - struct { - uint8_t baro : 1; // true if baro is healthy - uint8_t compass : 1; // true if compass is healthy - } sensor_health; - // Motor Output Fins *motors; @@ -210,7 +203,6 @@ class Blimp : public AP_Vehicle // Altitude int32_t baro_alt; // barometer altitude in cm above home - LowPassFilterVector3f land_accel_ef_filter; // accelerations for land and crash detector tests // filtered pilot's throttle input used to cancel landing if throttle held high LowPassFilterFloat rc_throttle_control_in_filter; @@ -232,13 +224,13 @@ class Blimp : public AP_Vehicle AP_InertialNav inertial_nav; // Vel & pos PIDs - AC_PID_2D pid_vel_xy{3, 0.2, 0, 0, 0.2, 3, 3, 0.02}; //These are the defaults - P I D FF IMAX FiltHz FiltDHz DT - AC_PID_Basic pid_vel_z{7, 1.5, 0, 0, 1, 3, 3, 0.02}; - AC_PID_Basic pid_vel_yaw{3, 0.4, 0, 0, 0.2, 3, 3, 0.02}; + AC_PID_2D pid_vel_xy{3, 0.2, 0, 0, 0.2, 3, 3}; //These are the defaults - P I D FF IMAX FiltHz FiltDHz DT + AC_PID_Basic pid_vel_z{7, 1.5, 0, 0, 1, 3, 3}; + AC_PID_Basic pid_vel_yaw{3, 0.4, 0, 0, 0.2, 3, 3}; - AC_PID_2D pid_pos_xy{1, 0.05, 0, 0, 0.1, 3, 3, 0.02}; - AC_PID_Basic pid_pos_z{0.7, 0, 0, 0, 0, 3, 3, 0.02}; - AC_PID pid_pos_yaw{1.2, 0.5, 0, 0, 2, 3, 3, 3, 0.02}; //p, i, d, ff, imax, filt_t, filt_e, filt_d, dt, opt srmax, opt srtau + AC_PID_2D pid_pos_xy{1, 0.05, 0, 0, 0.1, 3, 3}; + AC_PID_Basic pid_pos_z{0.7, 0, 0, 0, 0, 3, 3}; + AC_PID pid_pos_yaw{1.2, 0.5, 0, 0, 2, 3, 3, 3}; //p, i, d, ff, imax, filt_t, filt_e, filt_d, dt, opt srmax, opt srtau // System Timers // -------------- @@ -299,7 +291,6 @@ class Blimp : public AP_Vehicle void get_scheduler_tasks(const AP_Scheduler::Task *&tasks, uint8_t &task_count, uint32_t &log_bit) override; - void fast_loop() override; void rc_loop(); void throttle_loop(); void update_batt_compass(void); @@ -366,7 +357,6 @@ class Blimp : public AP_Vehicle void Log_Write_Data(LogDataID id, uint16_t value); void Log_Write_Data(LogDataID id, float value); void Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, float tune_min, float tune_max); - void Log_Sensor_Health(); void Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target); void Log_Write_SysID_Setup(uint8_t systemID_axis, float waveform_magnitude, float frequency_start, float frequency_stop, float time_fade_in, float time_const_freq, float time_record, float time_fade_out); void Log_Write_SysID_Data(float waveform_time, float waveform_sample, float waveform_freq, float angle_x, float angle_y, float angle_z, float accel_x, float accel_y, float accel_z); diff --git a/Blimp/GCS_Mavlink.cpp b/Blimp/GCS_Mavlink.cpp index 30ae53ed830..c51054eb4cc 100644 --- a/Blimp/GCS_Mavlink.cpp +++ b/Blimp/GCS_Mavlink.cpp @@ -1,6 +1,7 @@ #include "Blimp.h" #include "GCS_Mavlink.h" +#include MAV_TYPE GCS_Blimp::frame_type() const { @@ -123,7 +124,7 @@ void GCS_MAVLINK_Blimp::send_pid_tuning() if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) { return; } - const AP_Logger::PID_Info *pid_info = nullptr; + const AP_PIDInfo *pid_info = nullptr; switch (axes[i]) { case PID_SEND::VELX: pid_info = &blimp.pid_vel_xy.get_pid_info_x(); @@ -217,6 +218,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 10 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK_Parameters, streamRates[0], 0), @@ -226,6 +228,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 10 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK_Parameters, streamRates[1], 0), @@ -235,6 +238,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 10 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK_Parameters, streamRates[2], 0), @@ -244,6 +248,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 10 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("RAW_CTRL", 3, GCS_MAVLINK_Parameters, streamRates[3], 0), @@ -253,6 +258,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 10 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("POSITION", 4, GCS_MAVLINK_Parameters, streamRates[4], 0), @@ -262,6 +268,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 10 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK_Parameters, streamRates[5], 0), @@ -271,15 +278,17 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 10 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK_Parameters, streamRates[6], 0), // @Param: EXTRA3 // @DisplayName: Extra data type 3 stream rate to ground station - // @Description: Stream rate of AHRS, HWSTATUS, SYSTEM_TIME, RANGEFINDER, DISTANCE_SENSOR, TERRAIN_REQUEST, BATTERY2, MOUNT_STATUS, OPTICAL_FLOW, GIMBAL_REPORT, MAG_CAL_REPORT, MAG_CAL_PROGRESS, EKF_STATUS_REPORT, VIBRATION and RPM to ground station + // @Description: Stream rate of AHRS, HWSTATUS, SYSTEM_TIME, RANGEFINDER, DISTANCE_SENSOR, TERRAIN_REQUEST, BATTERY2, GIMBAL_DEVICE_ATTITUDE_STATUS, OPTICAL_FLOW, MAG_CAL_REPORT, MAG_CAL_PROGRESS, EKF_STATUS_REPORT, VIBRATION and RPM to ground station // @Units: Hz // @Range: 0 10 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK_Parameters, streamRates[7], 0), @@ -289,6 +298,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 10 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK_Parameters, streamRates[8], 0), AP_GROUPEND @@ -343,14 +353,15 @@ static const ap_message STREAM_EXTRA3_msgs[] = { MSG_DISTANCE_SENSOR, MSG_BATTERY2, MSG_BATTERY_STATUS, - MSG_MOUNT_STATUS, + MSG_GIMBAL_DEVICE_ATTITUDE_STATUS, MSG_OPTICAL_FLOW, - MSG_GIMBAL_REPORT, MSG_MAG_CAL_REPORT, MSG_MAG_CAL_PROGRESS, MSG_EKF_STATUS_REPORT, MSG_VIBRATION, +#if AP_RPM_ENABLED MSG_RPM, +#endif MSG_ESC_TELEMETRY, MSG_GENERATOR_STATUS, }; @@ -358,7 +369,8 @@ static const ap_message STREAM_PARAMS_msgs[] = { MSG_NEXT_PARAM }; static const ap_message STREAM_ADSB_msgs[] = { - MSG_ADSB_VEHICLE + MSG_ADSB_VEHICLE, + MSG_AIS_VESSEL, }; const struct GCS_MAVLINK::stream_entries GCS_MAVLINK::all_stream_entries[] = { @@ -529,25 +541,6 @@ void GCS_MAVLINK_Blimp::handleMessage(const mavlink_message_t &msg) case MAVLINK_MSG_ID_TERRAIN_CHECK: break; - case MAVLINK_MSG_ID_SET_HOME_POSITION: { - mavlink_set_home_position_t packet; - mavlink_msg_set_home_position_decode(&msg, &packet); - if ((packet.latitude == 0) && (packet.longitude == 0) && (packet.altitude == 0)) { - if (!blimp.set_home_to_current_location(true)) { - // silently ignored - } - } else { - Location new_home_loc; - new_home_loc.lat = packet.latitude; - new_home_loc.lng = packet.longitude; - new_home_loc.alt = packet.altitude / 10; - if (!blimp.set_home(new_home_loc, true)) { - // silently ignored - } - } - break; - } - default: handle_common_message(msg); break; diff --git a/Blimp/Log.cpp b/Blimp/Log.cpp index a4593304e12..dab16518e39 100644 --- a/Blimp/Log.cpp +++ b/Blimp/Log.cpp @@ -232,23 +232,6 @@ tuning_max : tune_max logger.WriteBlock(&pkt_tune, sizeof(pkt_tune)); } -// logs when baro or compass becomes unhealthy -void Blimp::Log_Sensor_Health() -{ - // check baro - if (sensor_health.baro != barometer.healthy()) { - sensor_health.baro = barometer.healthy(); - AP::logger().Write_Error(LogErrorSubsystem::BARO, - (sensor_health.baro ? LogErrorCode::ERROR_RESOLVED : LogErrorCode::UNHEALTHY)); - } - - // check compass - if (sensor_health.compass != compass.healthy()) { - sensor_health.compass = compass.healthy(); - AP::logger().Write_Error(LogErrorSubsystem::COMPASS, (sensor_health.compass ? LogErrorCode::ERROR_RESOLVED : LogErrorCode::UNHEALTHY)); - } -} - struct PACKED log_SysIdD { LOG_PACKET_HEADER; uint64_t time_us; @@ -521,7 +504,6 @@ void Blimp::Log_Write_Data(LogDataID id, int16_t value) {} void Blimp::Log_Write_Data(LogDataID id, uint16_t value) {} void Blimp::Log_Write_Data(LogDataID id, float value) {} void Blimp::Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, float tune_min, float tune_max) {} -void Blimp::Log_Sensor_Health() {} void Blimp::Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target) {} void Blimp::Log_Write_SysID_Setup(uint8_t systemID_axis, float waveform_magnitude, float frequency_start, float frequency_stop, float time_fade_in, float time_const_freq, float time_record, float time_fade_out) {} void Blimp::Log_Write_SysID_Data(float waveform_time, float waveform_sample, float waveform_freq, float angle_x, float angle_y, float angle_z, float accel_x, float accel_y, float accel_z) {} diff --git a/Blimp/Parameters.cpp b/Blimp/Parameters.cpp index 9ac54e3658b..542e35ef351 100644 --- a/Blimp/Parameters.cpp +++ b/Blimp/Parameters.cpp @@ -102,7 +102,7 @@ const AP_Param::Info Blimp::var_info[] = { // @Param: FS_GCS_ENABLE // @DisplayName: Ground Station Failsafe Enable // @Description: Controls whether failsafe will be invoked (and what action to take) when connection with Ground station is lost for at least 5 seconds. See FS_OPTIONS param for additional actions, or for cases allowing Mission continuation, when GCS failsafe is enabled. - // @Values: 0:Disabled/NoAction,1:RTL,2:RTL or Continue with Mission in Auto Mode (Removed in 4.0+-see FS_OPTIONS),3:SmartRTL or RTL,4:SmartRTL or Land,5:Land (4.0+ Only) + // @Values: 0:Disabled/NoAction,5:Land // @User: Standard GSCALAR(failsafe_gcs, "FS_GCS_ENABLE", FS_GCS_DISABLED), @@ -116,7 +116,7 @@ const AP_Param::Info Blimp::var_info[] = { // @Param: FS_THR_ENABLE // @DisplayName: Throttle Failsafe Enable // @Description: The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel - // @Values: 0:Disabled,1:Enabled always RTL,2:Enabled Continue with Mission in Auto Mode (Removed in 4.0+),3:Enabled always Land,4:Enabled always SmartRTL or RTL,5:Enabled always SmartRTL or Land + // @Values: 0:Disabled,3:Enabled always Land // @User: Standard GSCALAR(failsafe_throttle, "FS_THR_ENABLE", FS_THR_ENABLED_ALWAYS_RTL), @@ -141,7 +141,7 @@ const AP_Param::Info Blimp::var_info[] = { // @Param: FLTMODE1 // @DisplayName: Flight Mode 1 // @Description: Flight mode when Channel 5 pwm is <= 1230 - // @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL,22:FlowHold,23:Follow,24:ZigZag,25:SystemID,26:Heli_Autorotate + // @Values: 0:LAND,1:MANUAL,2:VELOCITY,3:LOITER // @User: Standard GSCALAR(flight_mode1, "FLTMODE1", (uint8_t)FLIGHT_MODE_1), @@ -189,33 +189,18 @@ const AP_Param::Info Blimp::var_info[] = { // @Param: INITIAL_MODE // @DisplayName: Initial flight mode - // @Description: This selects the mode to start in on boot. This is useful for when you want to start in AUTO mode on boot without a receiver. + // @Description: This selects the mode to start in on boot. // @CopyValuesFrom: FLTMODE1 // @User: Advanced GSCALAR(initial_mode, "INITIAL_MODE", (uint8_t)Mode::Number::MANUAL), // @Param: LOG_BITMASK // @DisplayName: Log bitmask - // @Description: 4 byte bitmap of log types to enable - // @Bitmask: 0:ATTITUDE_FAST,1:ATTITUDE_MED,2:GPS,3:PM,4:CTUN,5:NTUN,6:RCIN,7:IMU,8:CMD,9:CURRENT,10:RCOUT,11:OPTFLOW,12:PID,13:COMPASS,14:INAV,15:CAMERA,17:MOTBATT,18:IMU_FAST,19:IMU_RAW + // @Description: Bitmap of what log types to enable in on-board logger. This value is made up of the sum of each of the log types you want to be saved. On boards supporting microSD cards or other large block-storage devices it is usually best just to enable all basic log types by setting this to 65535. + // @Bitmask: 0:Fast Attitude,1:Medium Attitude,2:GPS,3:System Performance,4:Control Tuning,6:RC Input,7:IMU,9:Battery Monitor,10:RC Output,11:Optical Flow,12:PID,13:Compass // @User: Standard GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK), - // @Param: TUNE - // @DisplayName: Channel 6 Tuning - // @Description: Controls which parameters (normally PID gains) are being tuned with transmitter's channel 6 knob - // @User: Standard - // @Values: 0:None,1:Stab Roll/Pitch kP,4:Rate Roll/Pitch kP,5:Rate Roll/Pitch kI,21:Rate Roll/Pitch kD,3:Stab Yaw kP,6:Rate Yaw kP,26:Rate Yaw kD,56:Rate Yaw Filter,55:Motor Yaw Headroom,14:AltHold kP,7:Throttle Rate kP,34:Throttle Accel kP,35:Throttle Accel kI,36:Throttle Accel kD,12:Loiter Pos kP,22:Velocity XY kP,28:Velocity XY kI,10:WP Speed,25:Acro RollPitch kP,40:Acro Yaw kP,45:RC Feel,13:Heli Ext Gyro,38:Declination,39:Circle Rate,41:RangeFinder Gain,46:Rate Pitch kP,47:Rate Pitch kI,48:Rate Pitch kD,49:Rate Roll kP,50:Rate Roll kI,51:Rate Roll kD,52:Rate Pitch FF,53:Rate Roll FF,54:Rate Yaw FF,58:SysID Magnitude - GSCALAR(radio_tuning, "TUNE", 0), - - // @Param: FRAME_TYPE - // @DisplayName: Frame Type (+, X, V, etc) - // @Description: Controls motor mixing for multiblimps. Not used for Tri or Traditional Heliblimps. - // @Values: 0:Plus, 1:X, 2:V, 3:H, 4:V-Tail, 5:A-Tail, 10:Y6B, 11:Y6F, 12:BetaFlightX, 13:DJIX, 14:ClockwiseX, 15: I, 18: BetaFlightXReversed - // @User: Standard - // @RebootRequired: True - GSCALAR(frame_type, "FRAME_TYPE", HAL_FRAME_TYPE_DEFAULT), - // @Group: ARMING_ // @Path: ../libraries/AP_Arming/AP_Arming.cpp GOBJECT(arming, "ARMING_", AP_Arming_Blimp), @@ -231,7 +216,7 @@ const AP_Param::Info Blimp::var_info[] = { // @Param: FS_EKF_ACTION // @DisplayName: EKF Failsafe Action // @Description: Controls the action that will be taken when an EKF failsafe is invoked - // @Values: 1:Land, 2:AltHold, 3:Land even in Stabilize + // @Values: 1:Land, 3:Land even in MANUAL // @User: Advanced GSCALAR(fs_ekf_action, "FS_EKF_ACTION", FS_EKF_ACTION_DEFAULT), @@ -387,7 +372,7 @@ const AP_Param::Info Blimp::var_info[] = { GOBJECT(can_mgr, "CAN_", AP_CANManager), #endif -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#if AP_SIM_ENABLED GOBJECT(sitl, "SIM_", SITL::SIM), #endif @@ -574,13 +559,6 @@ const AP_Param::Info Blimp::var_info[] = { // @Units: Hz // @User: Advanced - // @Param: VELYAW_FLTE - // @DisplayName: Velocity (yaw) input filter - // @Description: Velocity (yaw) input filter. This filter (in Hz) is applied to the input for D term - // @Range: 0 100 - // @Units: Hz - // @User: Advanced - // @Param: VELYAW_FF // @DisplayName: Velocity (yaw) feed forward gain // @Description: Velocity (yaw) feed forward gain. Converts the difference between desired velocity to a target acceleration @@ -822,18 +800,6 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { AP_SUBGROUPINFO(scripting, "SCR_", 30, ParametersG2, AP_Scripting), #endif - // @Param: TUNE_MIN - // @DisplayName: Tuning minimum - // @Description: Minimum value that the parameter currently being tuned with the transmitter's channel 6 knob will be set to - // @User: Standard - AP_GROUPINFO("TUNE_MIN", 31, ParametersG2, tuning_min, 0), - - // @Param: TUNE_MAX - // @DisplayName: Tuning maximum - // @Description: Maximum value that the parameter currently being tuned with the transmitter's channel 6 knob will be set to - // @User: Standard - AP_GROUPINFO("TUNE_MAX", 32, ParametersG2, tuning_max, 0), - // @Param: FS_VIBE_ENABLE // @DisplayName: Vibration Failsafe enable // @Description: This enables the vibration failsafe which will use modified altitude estimation and control during high vibrations @@ -844,8 +810,8 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Param: FS_OPTIONS // @DisplayName: Failsafe options bitmask // @Description: Bitmask of additional options for battery, radio, & GCS failsafes. 0 (default) disables all options. - // @Values: 0:Disabled, 1:Continue if in Auto on RC failsafe only, 2:Continue if in Auto on GCS failsafe only, 3:Continue if in Auto on RC and/or GCS failsafe, 4:Continue if in Guided on RC failsafe only, 8:Continue if landing on any failsafe, 16:Continue if in pilot controlled modes on GCS failsafe, 19:Continue if in Auto on RC and/or GCS failsafe and continue if in pilot controlled modes on GCS failsafe - // @Bitmask: 0:Continue if in Auto on RC failsafe, 1:Continue if in Auto on GCS failsafe, 2:Continue if in Guided on RC failsafe, 3:Continue if landing on any failsafe, 4:Continue if in pilot controlled modes on GCS failsafe, 5:Release Gripper + // @Values: 0:Disabled, 16:Continue if in pilot controlled modes on GCS failsafe + // @Bitmask: 4:Continue if in pilot controlled modes on GCS failsafe // @User: Advanced AP_GROUPINFO("FS_OPTIONS", 36, ParametersG2, fs_options, (float)Blimp::FailsafeOption::GCS_CONTINUE_IF_PILOT_CONTROL), @@ -890,6 +856,7 @@ void Blimp::load_parameters(void) g.format_version.set_and_save(Parameters::k_format_version); hal.console->printf("done.\n"); } + g.format_version.set_default(Parameters::k_format_version); uint32_t before = micros(); // Load all auto-loaded EEPROM variables diff --git a/Blimp/Parameters.h b/Blimp/Parameters.h index 70718b39e58..7db8cae8dbd 100644 --- a/Blimp/Parameters.h +++ b/Blimp/Parameters.h @@ -148,7 +148,7 @@ class Parameters // 140: Sensor parameters // k_param_compass, - k_param_frame_type, + k_param_frame_type, //unused k_param_ahrs, // AHRS group // 159 // @@ -170,7 +170,7 @@ class Parameters // k_param_failsafe_throttle = 170, k_param_failsafe_throttle_value, - k_param_radio_tuning, + k_param_radio_tuning, // unused k_param_rc_speed = 192, k_param_failsafe_gcs, k_param_rcmap, // 199 @@ -235,8 +235,6 @@ class Parameters // Misc // AP_Int32 log_bitmask; - AP_Int8 radio_tuning; - AP_Int8 frame_type; AP_Int8 disarm_delay; AP_Int8 fs_ekf_action; @@ -313,9 +311,6 @@ class ParametersG2 AP_Scripting scripting; #endif // AP_SCRIPTING_ENABLED - AP_Float tuning_min; - AP_Float tuning_max; - // vibration failsafe enable/disable AP_Int8 fs_vibe_enabled; diff --git a/Blimp/config.h b/Blimp/config.h index fd386ad5f40..776dcb4f8c8 100644 --- a/Blimp/config.h +++ b/Blimp/config.h @@ -132,10 +132,6 @@ #define FS_TERRAIN_TIMEOUT_MS 5000 // 5 seconds of missing terrain data will trigger failsafe (RTL) #endif -#ifndef PREARM_DISPLAY_PERIOD -# define PREARM_DISPLAY_PERIOD 30 -#endif - // pre-arm baro vs inertial nav max alt disparity #ifndef PREARM_MAX_ALT_DISPARITY_CM # define PREARM_MAX_ALT_DISPARITY_CM 100 // barometer and inertial nav altitude must be within this many centimeters diff --git a/Blimp/events.cpp b/Blimp/events.cpp index 7c3c5577a65..b3856bc9605 100644 --- a/Blimp/events.cpp +++ b/Blimp/events.cpp @@ -120,7 +120,7 @@ void Blimp::failsafe_gcs_check() } else if (last_gcs_update_ms > gcs_timeout_ms && !failsafe.gcs) { // New GCS failsafe event, trigger events set_failsafe_gcs(true); - // failsafe_gcs_on_event(); + arming.disarm(AP_Arming::Method::GCSFAILSAFE); // failsafe_gcs_on_event() should replace this when written } } @@ -174,4 +174,4 @@ void Blimp::gpsglitch_check() gcs().send_text(MAV_SEVERITY_CRITICAL,"GPS Glitch cleared"); } } -} \ No newline at end of file +} diff --git a/Blimp/mode_loiter.cpp b/Blimp/mode_loiter.cpp index bec0629d809..71e2794c2bb 100644 --- a/Blimp/mode_loiter.cpp +++ b/Blimp/mode_loiter.cpp @@ -14,11 +14,13 @@ //Runs the main loiter controller void ModeLoiter::run() { + const float dt = blimp.scheduler.get_last_loop_time_s(); + Vector3f pilot; - pilot.x = channel_front->get_control_in() / float(RC_SCALE) * g.max_pos_xy * blimp.scheduler.get_loop_period_s(); - pilot.y = channel_right->get_control_in() / float(RC_SCALE) * g.max_pos_xy * blimp.scheduler.get_loop_period_s(); - pilot.z = channel_down->get_control_in() / float(RC_SCALE) * g.max_pos_z * blimp.scheduler.get_loop_period_s(); - float pilot_yaw = channel_yaw->get_control_in() / float(RC_SCALE) * g.max_pos_yaw * blimp.scheduler.get_loop_period_s(); + pilot.x = channel_front->get_control_in() / float(RC_SCALE) * g.max_pos_xy * dt; + pilot.y = channel_right->get_control_in() / float(RC_SCALE) * g.max_pos_xy * dt; + pilot.z = channel_down->get_control_in() / float(RC_SCALE) * g.max_pos_z * dt; + float pilot_yaw = channel_yaw->get_control_in() / float(RC_SCALE) * g.max_pos_yaw * dt; if (g.simple_mode == 0){ //If simple mode is disabled, input is in body-frame, thus needs to be rotated. @@ -30,10 +32,10 @@ void ModeLoiter::run() target_yaw = wrap_PI(target_yaw + pilot_yaw); //Pos controller's output becomes target for velocity controller - Vector3f target_vel_ef{blimp.pid_pos_xy.update_all(target_pos, blimp.pos_ned, {0,0,0}), 0}; - target_vel_ef.z = blimp.pid_pos_z.update_all(target_pos.z, blimp.pos_ned.z); + Vector3f target_vel_ef{blimp.pid_pos_xy.update_all(target_pos, blimp.pos_ned, dt, {0,0,0}), 0}; + target_vel_ef.z = blimp.pid_pos_z.update_all(target_pos.z, blimp.pos_ned.z, dt); float yaw_ef = blimp.ahrs.get_yaw(); - float target_vel_yaw = blimp.pid_pos_yaw.update_error(wrap_PI(target_yaw - yaw_ef)); + float target_vel_yaw = blimp.pid_pos_yaw.update_error(wrap_PI(target_yaw - yaw_ef), dt); blimp.pid_pos_yaw.set_target_rate(target_yaw); blimp.pid_pos_yaw.set_actual_rate(yaw_ef); @@ -42,10 +44,10 @@ void ModeLoiter::run() constrain_float(target_vel_ef.z, -g.max_vel_z, g.max_vel_z)}; float target_vel_yaw_c = constrain_float(target_vel_yaw, -g.max_vel_yaw, g.max_vel_yaw); - Vector2f actuator = blimp.pid_vel_xy.update_all(target_vel_ef_c, blimp.vel_ned_filtd, {0,0,0}); - float act_down = blimp.pid_vel_z.update_all(target_vel_ef_c.z, blimp.vel_ned_filtd.z); + Vector2f actuator = blimp.pid_vel_xy.update_all(target_vel_ef_c, blimp.vel_ned_filtd, dt, {0,0,0}); + float act_down = blimp.pid_vel_z.update_all(target_vel_ef_c.z, blimp.vel_ned_filtd.z, dt); blimp.rotate_NE_to_BF(actuator); - float act_yaw = blimp.pid_vel_yaw.update_all(target_vel_yaw_c, blimp.vel_yaw_filtd); + float act_yaw = blimp.pid_vel_yaw.update_all(target_vel_yaw_c, blimp.vel_yaw_filtd, dt); if(!(blimp.g.dis_mask & (1<<(2-1)))){ motors->front_out = actuator.x; diff --git a/Blimp/mode_velocity.cpp b/Blimp/mode_velocity.cpp index b0990897568..bd3db6b9223 100644 --- a/Blimp/mode_velocity.cpp +++ b/Blimp/mode_velocity.cpp @@ -6,6 +6,8 @@ // Runs the main velocity controller void ModeVelocity::run() { + const float dt = blimp.scheduler.get_last_loop_time_s(); + Vector3f target_vel; target_vel.x = channel_front->get_control_in() / float(RC_SCALE) * g.max_vel_xy; target_vel.y = channel_right->get_control_in() / float(RC_SCALE) * g.max_vel_xy; @@ -13,10 +15,10 @@ void ModeVelocity::run() target_vel.z = channel_down->get_control_in() / float(RC_SCALE) * g.max_vel_z; float target_vel_yaw = channel_yaw->get_control_in() / float(RC_SCALE) * g.max_vel_yaw; - Vector2f actuator = blimp.pid_vel_xy.update_all(target_vel, blimp.vel_ned_filtd, {0,0,0}); + Vector2f actuator = blimp.pid_vel_xy.update_all(target_vel, blimp.vel_ned_filtd, dt, {0,0,0}); blimp.rotate_NE_to_BF(actuator); - float act_down = blimp.pid_vel_z.update_all(target_vel.z, blimp.vel_ned_filtd.z); - float act_yaw = blimp.pid_vel_yaw.update_all(target_vel_yaw, blimp.vel_yaw_filtd); + float act_down = blimp.pid_vel_z.update_all(target_vel.z, blimp.vel_ned_filtd.z, dt); + float act_yaw = blimp.pid_vel_yaw.update_all(target_vel_yaw, blimp.vel_yaw_filtd, dt); if(!(blimp.g.dis_mask & (1<<(2-1)))){ motors->front_out = actuator.x; diff --git a/Blimp/version.h b/Blimp/version.h index aa97bacfe22..a922ff5c4c1 100644 --- a/Blimp/version.h +++ b/Blimp/version.h @@ -6,13 +6,13 @@ #include "ap_version.h" -#define THISFIRMWARE "Blimp V4.1.0-dev" +#define THISFIRMWARE "Blimp V4.3.0-dev" // the following line is parsed by the autotest scripts -#define FIRMWARE_VERSION 4,1,0,FIRMWARE_VERSION_TYPE_DEV +#define FIRMWARE_VERSION 4,3,0,FIRMWARE_VERSION_TYPE_DEV #define FW_MAJOR 4 -#define FW_MINOR 1 +#define FW_MINOR 3 #define FW_PATCH 0 #define FW_TYPE FIRMWARE_VERSION_TYPE_DEV diff --git a/Dockerfile b/Dockerfile index 8d0f97a77eb..808271fefc6 100644 --- a/Dockerfile +++ b/Dockerfile @@ -2,36 +2,48 @@ FROM ubuntu:20.04 WORKDIR /ardupilot ARG DEBIAN_FRONTEND=noninteractive -RUN useradd -U -m ardupilot && \ - usermod -G users ardupilot +ARG USER_NAME=ardupilot +ARG USER_UID=1000 +ARG USER_GID=1000 +RUN groupadd ${USER_NAME} --gid ${USER_GID}\ + && useradd -l -m ${USER_NAME} -u ${USER_UID} -g ${USER_GID} -s /bin/bash RUN apt-get update && apt-get install --no-install-recommends -y \ lsb-release \ sudo \ - bash-completion \ - software-properties-common + tzdata \ + bash-completion COPY Tools/environment_install/install-prereqs-ubuntu.sh /ardupilot/Tools/environment_install/ COPY Tools/completion /ardupilot/Tools/completion/ # Create non root user for pip -ENV USER=ardupilot +ENV USER=${USER_NAME} -RUN echo "ardupilot ALL=(ALL) NOPASSWD:ALL" > /etc/sudoers.d/ardupilot -RUN chmod 0440 /etc/sudoers.d/ardupilot +RUN echo "ardupilot ALL=(ALL) NOPASSWD:ALL" > /etc/sudoers.d/${USER_NAME} +RUN chmod 0440 /etc/sudoers.d/${USER_NAME} -RUN chown -R ardupilot:ardupilot /ardupilot +RUN chown -R ${USER_NAME}:${USER_NAME} /${USER_NAME} -USER ardupilot +USER ${USER_NAME} ENV SKIP_AP_EXT_ENV=1 SKIP_AP_GRAPHIC_ENV=1 SKIP_AP_COV_ENV=1 SKIP_AP_GIT_CHECK=1 RUN Tools/environment_install/install-prereqs-ubuntu.sh -y # add waf alias to ardupilot waf to .bashrc -RUN echo "alias waf=\"/ardupilot/waf\"" >> ~/.bashrc +RUN echo "alias waf=\"/${USER_NAME}/waf\"" >> ~/ardupilot_entrypoint.sh # Check that local/bin are in PATH for pip --user installed package -RUN echo "if [ -d \"\$HOME/.local/bin\" ] ; then\nPATH=\"\$HOME/.local/bin:\$PATH\"\nfi" >> ~/.bashrc +RUN echo "if [ -d \"\$HOME/.local/bin\" ] ; then\nPATH=\"\$HOME/.local/bin:\$PATH\"\nfi" >> ~/ardupilot_entrypoint.sh + +# Create entrypoint as docker cannot do shell substitution correctly +RUN export ARDUPILOT_ENTRYPOINT="/home/${USER_NAME}/ardupilot_entrypoint.sh" \ + && echo "#!/bin/bash" > $ARDUPILOT_ENTRYPOINT \ + && echo "set -e" >> $ARDUPILOT_ENTRYPOINT \ + && echo "source /home/${USER_NAME}/.ardupilot_env" >> $ARDUPILOT_ENTRYPOINT \ + && echo 'exec "$@"' >> $ARDUPILOT_ENTRYPOINT \ + && chmod +x $ARDUPILOT_ENTRYPOINT \ + && sudo mv $ARDUPILOT_ENTRYPOINT /ardupilot_entrypoint.sh # Set the buildlogs directory into /tmp as other directory aren't accessible ENV BUILDLOGS=/tmp/buildlogs @@ -41,3 +53,5 @@ RUN sudo apt-get clean \ && sudo rm -rf /var/lib/apt/lists/* /tmp/* /var/tmp/* ENV CCACHE_MAXSIZE=1G +ENTRYPOINT ["/ardupilot_entrypoint.sh"] +CMD ["bash"] diff --git a/README.md b/README.md index 10db35f4269..36994430d4f 100644 --- a/README.md +++ b/README.md @@ -2,11 +2,11 @@ Discord -[![Test Copter](https://github.com/ArduPilot/ardupilot/workflows/test%20copter/badge.svg?branch=master)](https://github.com/ArduPilot/ardupilot/ardupilot/actions/workflows/test_sitl_copter.yml) [![Test Plane](https://github.com/ArduPilot/ardupilot/workflows/test%20plane/badge.svg?branch=master)](https://github.com/ArduPilot/ardupilot/ardupilot/actions/workflows/test_sitl_plane.yml) [![Test Rover](https://github.com/ArduPilot/ardupilot/workflows/test%20rover/badge.svg?branch=master)](https://github.com/ArduPilot/ardupilot/ardupilot/actions/workflows/test_sitl_rover.yml) [![Test Sub](https://github.com/ArduPilot/ardupilot/workflows/test%20sub/badge.svg?branch=master)](https://github.com/ArduPilot/ardupilot/ardupilot/actions/workflows/test_sitl_sub.yml) [![Test Tracker](https://github.com/ArduPilot/ardupilot/workflows/test%20tracker/badge.svg?branch=master)](https://github.com/ArduPilot/ardupilot/ardupilot/actions/workflows/test_sitl_tracker.yml) +[![Test Copter](https://github.com/ArduPilot/ardupilot/workflows/test%20copter/badge.svg?branch=master)](https://github.com/ArduPilot/ardupilot/actions/workflows/test_sitl_copter.yml) [![Test Plane](https://github.com/ArduPilot/ardupilot/workflows/test%20plane/badge.svg?branch=master)](https://github.com/ArduPilot/ardupilot/actions/workflows/test_sitl_plane.yml) [![Test Rover](https://github.com/ArduPilot/ardupilot/workflows/test%20rover/badge.svg?branch=master)](https://github.com/ArduPilot/ardupilot/actions/workflows/test_sitl_rover.yml) [![Test Sub](https://github.com/ArduPilot/ardupilot/workflows/test%20sub/badge.svg?branch=master)](https://github.com/ArduPilot/ardupilot/actions/workflows/test_sitl_sub.yml) [![Test Tracker](https://github.com/ArduPilot/ardupilot/workflows/test%20tracker/badge.svg?branch=master)](https://github.com/ArduPilot/ardupilot/actions/workflows/test_sitl_tracker.yml) -[![Test AP_Periph](https://github.com/ArduPilot/ardupilot/workflows/test%20ap_periph/badge.svg?branch=master)](https://github.com/ArduPilot/ardupilot/ardupilot/actions/workflows/test_sitl_periph.yml) [![Test Chibios](https://github.com/ArduPilot/ardupilot/workflows/test%20chibios/badge.svg?branch=master)](https://github.com/ArduPilot/ardupilot/ardupilot/actions/workflows/test_chibios.yml) [![Test Linux SBC](https://github.com/ArduPilot/ardupilot/workflows/test%20Linux%20SBC/badge.svg?branch=master)](https://github.com/ArduPilot/ardupilot/ardupilot/actions/workflows/test_linux_sbc.yml) [![Test Replay](https://github.com/ArduPilot/ardupilot/workflows/test%20replay/badge.svg?branch=master)](https://github.com/ArduPilot/ardupilot/ardupilot/actions/workflows/test_replay.yml) +[![Test AP_Periph](https://github.com/ArduPilot/ardupilot/workflows/test%20ap_periph/badge.svg?branch=master)](https://github.com/ArduPilot/ardupilot/actions/workflows/test_sitl_periph.yml) [![Test Chibios](https://github.com/ArduPilot/ardupilot/workflows/test%20chibios/badge.svg?branch=master)](https://github.com/ArduPilot/ardupilot/actions/workflows/test_chibios.yml) [![Test Linux SBC](https://github.com/ArduPilot/ardupilot/workflows/test%20Linux%20SBC/badge.svg?branch=master)](https://github.com/ArduPilot/ardupilot/actions/workflows/test_linux_sbc.yml) [![Test Replay](https://github.com/ArduPilot/ardupilot/workflows/test%20replay/badge.svg?branch=master)](https://github.com/ArduPilot/ardupilot/actions/workflows/test_replay.yml) -[![Test Unit Tests](https://github.com/ArduPilot/ardupilot/workflows/test%20unit%20tests/badge.svg?branch=master)](https://github.com/ArduPilot/ardupilot/ardupilot/actions/workflows/test_unit_tests.yml) [![test size](https://github.com/ArduPilot/ardupilot/actions/workflows/test_size.yml/badge.svg)](https://github.com/ArduPilot/ardupilot/actions/workflows/test_size.yml) +[![Test Unit Tests](https://github.com/ArduPilot/ardupilot/workflows/test%20unit%20tests/badge.svg?branch=master)](https://github.com/ArduPilot/ardupilot/actions/workflows/test_unit_tests.yml) [![test size](https://github.com/ArduPilot/ardupilot/actions/workflows/test_size.yml/badge.svg)](https://github.com/ArduPilot/ardupilot/actions/workflows/test_size.yml) [![Test Environment Setup](https://github.com/ArduPilot/ardupilot/actions/workflows/test_environment.yml/badge.svg?branch=master)](https://github.com/ArduPilot/ardupilot/actions/workflows/test_environment.yml) @@ -94,7 +94,7 @@ for reviewing patches on their specific area. - ***Bug Master*** - [Grant Morphett](https://github.com/gmorph): - ***Vehicle***: Rover -- [Jacob Walser](https://github.com/jaxxzer): +- [Willian Galvani](https://github.com/williangalvani): - ***Vehicle***: Sub - [Lucas De Marchi](https://github.com/lucasdemarchi): - ***Subsystem***: Linux diff --git a/Rover/AP_Arming.cpp b/Rover/AP_Arming.cpp index e25e3ea7da9..1fedf998e48 100644 --- a/Rover/AP_Arming.cpp +++ b/Rover/AP_Arming.cpp @@ -71,6 +71,11 @@ bool AP_Arming_Rover::gps_checks(bool display_failure) bool AP_Arming_Rover::pre_arm_checks(bool report) { + if (armed) { + // if we are already armed then skip the checks + return true; + } + //are arming checks disabled? if (checks_to_perform == 0) { return true; @@ -157,7 +162,7 @@ bool AP_Arming_Rover::disarm(const AP_Arming::Method method, bool do_disarm_chec // check object avoidance has initialised correctly bool AP_Arming_Rover::oa_check(bool report) { - char failure_msg[50]; + char failure_msg[50] = {}; if (rover.g2.oa.pre_arm_check(failure_msg, ARRAY_SIZE(failure_msg))) { return true; } @@ -205,7 +210,7 @@ bool AP_Arming_Rover::motor_checks(bool report) bool ret = rover.g2.motors.pre_arm_check(report); #if HAL_TORQEEDO_ENABLED - char failure_msg[50]; + char failure_msg[50] = {}; AP_Torqeedo *torqeedo = AP_Torqeedo::get_singleton(); if (torqeedo != nullptr) { if (!torqeedo->pre_arm_checks(failure_msg, ARRAY_SIZE(failure_msg))) { diff --git a/Rover/AP_Rally.cpp b/Rover/AP_Rally.cpp index 4442fee50ce..1a836159645 100644 --- a/Rover/AP_Rally.cpp +++ b/Rover/AP_Rally.cpp @@ -21,8 +21,10 @@ bool AP_Rally_Rover::is_valid(const Location &rally_point) const { - if (!rover.g2.fence.check_destination_within_fence(rally_point)) { +#if AP_FENCE_ENABLED + if (!rover.fence.check_destination_within_fence(rally_point)) { return false; } +#endif return true; } diff --git a/Rover/GCS_Mavlink.cpp b/Rover/GCS_Mavlink.cpp index af1dc6a4e57..85faeddb74f 100644 --- a/Rover/GCS_Mavlink.cpp +++ b/Rover/GCS_Mavlink.cpp @@ -2,7 +2,9 @@ #include "GCS_Mavlink.h" +#include #include +#include MAV_TYPE GCS_Rover::frame_type() const { @@ -149,8 +151,8 @@ int16_t GCS_MAVLINK_Rover::vfr_hud_throttle() const void GCS_MAVLINK_Rover::send_rangefinder() const { - float distance_cm; - float voltage; + float distance = 0; + float voltage = 0; bool got_one = false; // report smaller distance of all rangefinders @@ -160,8 +162,8 @@ void GCS_MAVLINK_Rover::send_rangefinder() const continue; } if (!got_one || - s->distance_cm() < distance_cm) { - distance_cm = s->distance_cm(); + s->distance() < distance) { + distance = s->distance(); voltage = s->voltage_mv(); got_one = true; } @@ -173,7 +175,7 @@ void GCS_MAVLINK_Rover::send_rangefinder() const mavlink_msg_rangefinder_send( chan, - distance_cm * 0.01f, + distance, voltage); } @@ -185,7 +187,7 @@ void GCS_MAVLINK_Rover::send_pid_tuning() Parameters &g = rover.g; ParametersG2 &g2 = rover.g2; - const AP_Logger::PID_Info *pid_info; + const AP_PIDInfo *pid_info; // steering PID if (g.gcs_pid_mask & 1) { @@ -288,6 +290,40 @@ void GCS_MAVLINK_Rover::send_pid_tuning() return; } } + + // Position Controller Velocity North PID + if (g.gcs_pid_mask & 64) { + pid_info = &g2.pos_control.get_vel_pid().get_pid_info_x(); + mavlink_msg_pid_tuning_send(chan, 10, + pid_info->target, + pid_info->actual, + pid_info->FF, + pid_info->P, + pid_info->I, + pid_info->D, + pid_info->slew_rate, + pid_info->Dmod); + if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) { + return; + } + } + + // Position Controller Velocity East PID + if (g.gcs_pid_mask & 128) { + pid_info = &g2.pos_control.get_vel_pid().get_pid_info_y(); + mavlink_msg_pid_tuning_send(chan, 11, + pid_info->target, + pid_info->actual, + pid_info->FF, + pid_info->P, + pid_info->I, + pid_info->D, + pid_info->slew_rate, + pid_info->Dmod); + if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) { + return; + } + } } void Rover::send_wheel_encoder_distance(const mavlink_channel_t chan) @@ -354,13 +390,6 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id) break; } - case MSG_AIS_VESSEL: { -#if HAL_AIS_ENABLED - rover.g2.ais.send(chan); -#endif - break; - } - default: return GCS_MAVLINK::try_send_message(id); } @@ -384,6 +413,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK_Parameters, streamRates[0], 1), @@ -393,6 +423,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK_Parameters, streamRates[1], 1), @@ -402,6 +433,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK_Parameters, streamRates[2], 1), @@ -411,6 +443,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("RAW_CTRL", 3, GCS_MAVLINK_Parameters, streamRates[3], 1), @@ -420,6 +453,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("POSITION", 4, GCS_MAVLINK_Parameters, streamRates[4], 1), @@ -429,6 +463,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK_Parameters, streamRates[5], 1), @@ -438,6 +473,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK_Parameters, streamRates[6], 1), @@ -447,6 +483,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK_Parameters, streamRates[7], 1), @@ -456,6 +493,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK_Parameters, streamRates[8], 10), @@ -465,6 +503,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Units: Hz // @Range: 0 50 // @Increment: 1 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("ADSB", 9, GCS_MAVLINK_Parameters, streamRates[9], 0), @@ -523,14 +562,19 @@ static const ap_message STREAM_EXTRA3_msgs[] = { MSG_SYSTEM_TIME, MSG_BATTERY2, MSG_BATTERY_STATUS, - MSG_MOUNT_STATUS, + MSG_GIMBAL_DEVICE_ATTITUDE_STATUS, MSG_MAG_CAL_REPORT, MSG_MAG_CAL_PROGRESS, MSG_EKF_STATUS_REPORT, MSG_VIBRATION, +#if AP_RPM_ENABLED MSG_RPM, +#endif MSG_WHEEL_DISTANCE, MSG_ESC_TELEMETRY, +#if HAL_EFI_ENABLED + MSG_EFI_STATUS, +#endif }; static const ap_message STREAM_PARAMS_msgs[] = { MSG_NEXT_PARAM @@ -1035,6 +1079,15 @@ void GCS_MAVLINK_Rover::handle_radio(const mavlink_message_t &msg) handle_radio_status(msg, rover.should_log(MASK_LOG_PM)); } +/* + handle a LANDING_TARGET command. The timestamp has been jitter corrected +*/ +void GCS_MAVLINK_Rover::handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms) +{ +#if PRECISION_LANDING == ENABLED + rover.precland.handle_msg(packet, timestamp_ms); +#endif +} uint64_t GCS_MAVLINK_Rover::capabilities() const { diff --git a/Rover/GCS_Mavlink.h b/Rover/GCS_Mavlink.h index 2b900f2f6d4..dab366b7305 100644 --- a/Rover/GCS_Mavlink.h +++ b/Rover/GCS_Mavlink.h @@ -42,6 +42,7 @@ class GCS_MAVLINK_Rover : public GCS_MAVLINK void handle_set_position_target_local_ned(const mavlink_message_t &msg); void handle_set_position_target_global_int(const mavlink_message_t &msg); void handle_radio(const mavlink_message_t &msg); + void handle_landing_target(const mavlink_landing_target_t &msg, uint32_t timestamp_ms) override; void send_servo_out(); diff --git a/Rover/Parameters.cpp b/Rover/Parameters.cpp index 8df3cc7fdad..866065b72f9 100644 --- a/Rover/Parameters.cpp +++ b/Rover/Parameters.cpp @@ -18,8 +18,8 @@ const AP_Param::Info Rover::var_info[] = { // @Param: LOG_BITMASK // @DisplayName: Log bitmask - // @Description: Bitmap of what log types to enable in on-board logger. This value is made up of the sum of each of the log types you want to be saved. On boards supporting microSD cards or other large block-storage devices it is usually best just to enable all log types by setting this to 65535. The individual bits are ATTITUDE_FAST=1, ATTITUDE_MEDIUM=2, GPS=4, PerformanceMonitoring=8, ControlTuning=16, NavigationTuning=32, Mode=64, IMU=128, Commands=256, Battery=512, Compass=1024, TECS=2048, Camera=4096, RCandServo=8192, Rangefinder=16384, Arming=32768, FullLogs=65535 - // @Bitmask: 0:ATTITUDE_FAST,1:ATTITUDE_MED,2:GPS,3:PM,4:THR,5:NTUN,7:IMU,8:CMD,9:CURRENT,10:RANGEFINDER,11:COMPASS,12:CAMERA,13:STEERING,14:RC,15:ARM/DISARM,19:IMU_RAW,20:VideoStabilization + // @Description: Bitmap of what log types to enable in on-board logger. This value is made up of the sum of each of the log types you want to be saved. On boards supporting microSD cards or other large block-storage devices it is usually best just to enable all basic log types by setting this to 65535. + // @Bitmask: 0:Fast Attitude,1:Medium Attitude,2:GPS,3:System Performance,4:Throttle,5:Navigation Tuning,7:IMU,8:Mission Commands,9:Battery Monitor,10:Rangefinder,11:Compass,12:Camera,13:Steering,14:RC Input-Output,19:Raw IMU,20:Video Stabilization // @User: Advanced GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK), @@ -63,8 +63,8 @@ const AP_Param::Info Rover::var_info[] = { // @DisplayName: GCS PID tuning mask // @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for // @User: Advanced - // @Values: 0:None,1:Steering,2:Throttle,4:Pitch,8:Left Wheel,16:Right Wheel,32:Sailboat Heel - // @Bitmask: 0:Steering,1:Throttle,2:Pitch,3:Left Wheel,4:Right Wheel,5:Sailboat Heel + // @Values: 0:None,1:Steering,2:Throttle,4:Pitch,8:Left Wheel,16:Right Wheel,32:Sailboat Heel,64:Velocity North,128:Velocity East + // @Bitmask: 0:Steering,1:Throttle,2:Pitch,3:Left Wheel,4:Right Wheel,5:Sailboat Heel,6:Velocity North,7:Velocity East GSCALAR(gcs_pid_mask, "GCS_PID_MASK", 0), // @Param: AUTO_TRIGGER_PIN @@ -282,10 +282,6 @@ const AP_Param::Info Rover::var_info[] = { // @Path: ../libraries/AP_SerialManager/AP_SerialManager.cpp GOBJECT(serial_manager, "SERIAL", AP_SerialManager), - // @Group: NAVL1_ - // @Path: ../libraries/AP_L1_Control/AP_L1_Control.cpp - GOBJECT(L1_controller, "NAVL1_", AP_L1_Control), - // @Group: RNGFND // @Path: ../libraries/AP_RangeFinder/AP_RangeFinder.cpp GOBJECT(rangefinder, "RNGFND", RangeFinder), @@ -294,7 +290,7 @@ const AP_Param::Info Rover::var_info[] = { // @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp GOBJECT(ins, "INS_", AP_InertialSensor), -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#if AP_SIM_ENABLED // @Group: SIM_ // @Path: ../libraries/SITL/SITL.cpp GOBJECT(sitl, "SIM_", SITL::SIM), @@ -310,6 +306,12 @@ const AP_Param::Info Rover::var_info[] = { GOBJECT(camera, "CAM_", AP_Camera), #endif +#if PRECISION_LANDING == ENABLED + // @Group: PLND_ + // @Path: ../libraries/AC_PrecLand/AC_PrecLand.cpp + GOBJECT(precland, "PLND_", AC_PrecLand), +#endif + #if HAL_MOUNT_ENABLED // @Group: MNT // @Path: ../libraries/AP_Mount/AP_Mount.cpp @@ -482,10 +484,6 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @User: Standard AP_GROUPINFO("FRAME_CLASS", 16, ParametersG2, frame_class, 1), - // @Group: FENCE_ - // @Path: ../libraries/AC_Fence/AC_Fence.cpp - AP_SUBGROUPINFO(fence, "FENCE_", 17, ParametersG2, AC_Fence), - #if HAL_PROXIMITY_ENABLED // @Group: PRX // @Path: ../libraries/AP_Proximity/AP_Proximity.cpp @@ -502,10 +500,10 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @DisplayName: BalanceBot Maximum Pitch // @Description: Pitch angle in degrees at 100% throttle // @Units: deg - // @Range: 0 5 + // @Range: 0 15 // @Increment: 0.1 // @User: Standard - AP_GROUPINFO("BAL_PITCH_MAX", 21, ParametersG2, bal_pitch_max, 2), + AP_GROUPINFO("BAL_PITCH_MAX", 21, ParametersG2, bal_pitch_max, 10), // @Param: CRASH_ANGLE // @DisplayName: Crash Angle @@ -613,7 +611,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Group: WP_ // @Path: ../libraries/AR_WPNav/AR_WPNav.cpp - AP_SUBGROUPINFO(wp_nav, "WP_", 43, ParametersG2, AR_WPNav), + AP_SUBGROUPINFO(wp_nav, "WP_", 43, ParametersG2, AR_WPNav_OA), // @Group: SAIL_ // @Path: sailboat.cpp @@ -641,8 +639,8 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { AP_GROUPINFO("LOIT_SPEED_GAIN", 47, ParametersG2, loiter_speed_gain, 0.5f), // @Param: FS_OPTIONS - // @DisplayName: Rover Failsafe Options - // @Description: Bitmask to enable Rover failsafe options + // @DisplayName: Failsafe Options + // @Description: Bitmask to enable failsafe options // @Values: 0:None,1:Failsafe enabled in Hold mode // @Bitmask: 0:Failsafe enabled in Hold mode // @User: Advanced @@ -654,10 +652,28 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { AP_SUBGROUPINFO(torqeedo, "TRQD_", 49, ParametersG2, AP_Torqeedo), #endif -#if HAL_AIS_ENABLED - // @Group: AIS_ - // @Path: ../libraries/AP_AIS/AP_AIS.cpp - AP_SUBGROUPINFO(ais, "AIS_", 50, ParametersG2, AP_AIS), + // @Group: PSC + // @Path: ../libraries/APM_Control/AR_PosControl.cpp + AP_SUBGROUPINFO(pos_control, "PSC", 51, ParametersG2, AR_PosControl), + + // @Param: GUID_OPTIONS + // @DisplayName: Guided mode options + // @Description: Options that can be applied to change guided mode behaviour + // @Bitmask: 6:SCurves used for navigation + // @User: Advanced + AP_GROUPINFO("GUID_OPTIONS", 52, ParametersG2, guided_options, 0), + + // @Param: MANUAL_OPTIONS + // @DisplayName: Manual mode options + // @Description: Manual mode specific options + // @Bitmask: 0:Enable steering speed scaling + // @User: Advanced + AP_GROUPINFO("MANUAL_OPTIONS", 53, ParametersG2, manual_options, 0), + +#if MODE_DOCK_ENABLED == ENABLED + // @Group: DOCK + // @Path: mode_dock.cpp + AP_SUBGROUPPTR(mode_dock_ptr, "DOCK", 54, ParametersG2, ModeDock), #endif AP_GROUPEND @@ -698,18 +714,22 @@ ParametersG2::ParametersG2(void) #if ADVANCED_FAILSAFE == ENABLED afs(), #endif - beacon(rover.serial_manager), + beacon(), motors(rover.ServoRelayEvents, wheel_rate_control), wheel_rate_control(wheel_encoder), attitude_control(), smart_rtl(), +#if MODE_DOCK_ENABLED == ENABLED + mode_dock_ptr(&rover.mode_dock), +#endif #if HAL_PROXIMITY_ENABLED proximity(), #endif avoid(), follow(), windvane(), - wp_nav(attitude_control, rover.L1_controller), + pos_control(attitude_control), + wp_nav(attitude_control, pos_control), sailboat() { AP_Param::setup_object_defaults(this, var_info); @@ -742,11 +762,10 @@ const AP_Param::ConversionInfo conversion_table[] = { { Parameters::k_param_throttle_min_old, 0, AP_PARAM_INT8, "MOT_THR_MIN" }, { Parameters::k_param_throttle_max_old, 0, AP_PARAM_INT8, "MOT_THR_MAX" }, { Parameters::k_param_compass_enabled_deprecated, 0, AP_PARAM_INT8, "COMPASS_ENABLE" }, - { Parameters::k_param_pivot_turn_angle_old, 0, AP_PARAM_INT16, "WP_PIVOT_ANGLE" }, { Parameters::k_param_waypoint_radius_old, 0, AP_PARAM_FLOAT, "WP_RADIUS" }, - { Parameters::k_param_waypoint_overshoot_old, 0, AP_PARAM_FLOAT, "WP_OVERSHOOT" }, - { Parameters::k_param_g2, 20, AP_PARAM_INT16, "WP_PIVOT_RATE" }, - + { Parameters::k_param_g2, 299, AP_PARAM_INT16, "WP_PIVOT_ANGLE" }, + { Parameters::k_param_g2, 363, AP_PARAM_INT16, "WP_PIVOT_RATE" }, + { Parameters::k_param_g2, 491, AP_PARAM_FLOAT, "WP_PIVOT_DELAY" }, { Parameters::k_param_g2, 32, AP_PARAM_FLOAT, "SAIL_ANGLE_MIN" }, { Parameters::k_param_g2, 33, AP_PARAM_FLOAT, "SAIL_ANGLE_MAX" }, { Parameters::k_param_g2, 34, AP_PARAM_FLOAT, "SAIL_ANGLE_IDEAL" }, @@ -754,8 +773,22 @@ const AP_Param::ConversionInfo conversion_table[] = { { Parameters::k_param_g2, 36, AP_PARAM_FLOAT, "SAIL_NO_GO_ANGLE" }, { Parameters::k_param_arming, 2, AP_PARAM_INT16, "ARMING_CHECK" }, { Parameters::k_param_turn_max_g_old, 0, AP_PARAM_FLOAT, "ATC_TURN_MAX_G" }, + { Parameters::k_param_g2, 82, AP_PARAM_INT8 , "PRX1_TYPE" }, + { Parameters::k_param_g2, 146, AP_PARAM_INT8 , "PRX1_ORIENT" }, + { Parameters::k_param_g2, 210, AP_PARAM_INT16, "PRX1_YAW_CORR" }, + { Parameters::k_param_g2, 274, AP_PARAM_INT16, "PRX1_IGN_ANG1" }, + { Parameters::k_param_g2, 338, AP_PARAM_INT8, "PRX1_IGN_WID1" }, + { Parameters::k_param_g2, 402, AP_PARAM_INT16, "PRX1_IGN_ANG2" }, + { Parameters::k_param_g2, 466, AP_PARAM_INT8, "PRX1_IGN_WID2" }, + { Parameters::k_param_g2, 530, AP_PARAM_INT16, "PRX1_IGN_ANG3" }, + { Parameters::k_param_g2, 594, AP_PARAM_INT8, "PRX1_IGN_WID3" }, + { Parameters::k_param_g2, 658, AP_PARAM_INT16, "PRX1_IGN_ANG4" }, + { Parameters::k_param_g2, 722, AP_PARAM_INT8, "PRX1_IGN_WID4" }, + { Parameters::k_param_g2, 1234, AP_PARAM_FLOAT, "PRX1_MIN" }, + { Parameters::k_param_g2, 1298, AP_PARAM_FLOAT, "PRX1_MAX" }, }; + void Rover::load_parameters(void) { if (!AP_Param::check_var_info()) { @@ -774,6 +807,7 @@ void Rover::load_parameters(void) g.format_version.set_and_save(Parameters::k_format_version); hal.console->printf("done.\n"); } + g.format_version.set_default(Parameters::k_format_version); const uint32_t before = micros(); // Load all auto-loaded EEPROM variables @@ -792,9 +826,6 @@ void Rover::load_parameters(void) SRV_Channels::upgrade_parameters(); hal.console->printf("load_all took %uus\n", unsigned(micros() - before)); - // set a more reasonable default NAVL1_PERIOD for rovers - L1_controller.set_default_period(NAVL1_PERIOD); - // convert CH7_OPTION to RC7_OPTION for Rover-3.4 to 3.5 upgrade const AP_Param::ConversionInfo ch7_option_info = { Parameters::k_param_ch7_option, 0, AP_PARAM_INT8, "RC7_OPTION" }; AP_Int8 ch7_opt_old; @@ -841,16 +872,28 @@ void Rover::load_parameters(void) AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_ARMED); #endif -// PARAMETER_CONVERSION - Added: JAN-2022 -#if AP_AIRSPEED_ENABLED +#if AP_AIRSPEED_ENABLED | AP_AIS_ENABLED | AP_FENCE_ENABLED // Find G2's Top Level Key AP_Param::ConversionInfo info; if (!AP_Param::find_top_level_key_by_pointer(&g2, info.old_key)) { return; } +#endif +// PARAMETER_CONVERSION - Added: JAN-2022 +#if AP_AIRSPEED_ENABLED const uint16_t old_index = 37; // Old parameter index in the tree const uint16_t old_top_element = 4069; // Old group element in the tree for the first subgroup element AP_Param::convert_class(info.old_key, &airspeed, airspeed.var_info, old_index, old_top_element, false); #endif + +// PARAMETER_CONVERSION - Added: MAR-2022 +#if AP_AIS_ENABLED + AP_Param::convert_class(info.old_key, &ais, ais.var_info, 50, 114, false); +#endif + +// PARAMETER_CONVERSION - Added: Mar-2022 +#if AP_FENCE_ENABLED + AP_Param::convert_class(info.old_key, &fence, fence.var_info, 17, 4049, false); +#endif } diff --git a/Rover/Parameters.h b/Rover/Parameters.h index 653dc5a5d06..cf9513fe6b4 100644 --- a/Rover/Parameters.h +++ b/Rover/Parameters.h @@ -3,10 +3,18 @@ #include #include "RC_Channel.h" +#include #include "AC_Sprayer/AC_Sprayer.h" +#include +#include +#include #include "AP_Gripper/AP_Gripper.h" +#include #include "AP_Rally.h" +#include +#include #include "AP_Torqeedo/AP_Torqeedo.h" +#include // Global parameter class. // @@ -47,6 +55,8 @@ class Parameters { k_param_battery_volt_pin, k_param_battery_curr_pin, + k_param_precland = 24, + // braking k_param_braking_percent_old = 30, // unused k_param_braking_speederr_old, // unused @@ -206,7 +216,7 @@ class Parameters { k_param_ins, k_param_compass, k_param_rcmap, - k_param_L1_controller, + k_param_L1_controller, // unused k_param_steerController_old, // unused k_param_barometer, k_param_notify, @@ -326,14 +336,16 @@ class ParametersG2 { // frame class for vehicle AP_Int8 frame_class; - // fence library - AC_Fence fence; - #if HAL_PROXIMITY_ENABLED // proximity library AP_Proximity proximity; #endif +#if MODE_DOCK_ENABLED == ENABLED + // we need a pointer to the mode for the G2 table + class ModeDock *mode_dock_ptr; +#endif + // avoidance library AC_Avoid avoid; @@ -385,7 +397,7 @@ class ParametersG2 { #endif // AP_SCRIPTING_ENABLED // waypoint navigation - AR_WPNav wp_nav; + AR_WPNav_OA wp_nav; // Sailboat functions Sailboat sailboat; @@ -407,10 +419,14 @@ class ParametersG2 { AP_Torqeedo torqeedo; #endif -#if HAL_AIS_ENABLED - // Automatic Identification System - for tracking sea-going vehicles - AP_AIS ais; -#endif + // position controller + AR_PosControl pos_control; + + // guided options bitmask + AP_Int32 guided_options; + + // Rover options + AP_Int32 manual_options; }; extern const AP_Param::Info var_info[]; diff --git a/Rover/RC_Channel.cpp b/Rover/RC_Channel.cpp index 80a8f2ccea3..e83a9fd0d01 100644 --- a/Rover/RC_Channel.cpp +++ b/Rover/RC_Channel.cpp @@ -139,6 +139,7 @@ bool RC_Channel_Rover::do_aux_function(const aux_func_t ch_option, const AuxSwit // if disarmed clear mission and set home to current location if (!rover.arming.is_armed()) { rover.mode_auto.mission.clear(); + gcs().send_text(MAV_SEVERITY_NOTICE, "SaveWP: Mission cleared!"); if (!rover.set_home_to_current_location(false)) { // ignored } diff --git a/Rover/Rover.cpp b/Rover/Rover.cpp index b4f552083f2..2d77a096871 100644 --- a/Rover/Rover.cpp +++ b/Rover/Rover.cpp @@ -82,7 +82,6 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = { SCHED_TASK_CLASS(AP_Proximity, &rover.g2.proximity, update, 50, 200, 27), #endif SCHED_TASK_CLASS(AP_WindVane, &rover.g2.windvane, update, 20, 100, 30), - SCHED_TASK_CLASS(AC_Fence, &rover.g2.fence, update, 10, 100, 33), SCHED_TASK(update_wheel_encoder, 50, 200, 36), SCHED_TASK(update_compass, 10, 200, 39), SCHED_TASK(update_logging1, 10, 200, 45), @@ -95,6 +94,9 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = { SCHED_TASK_CLASS(AP_ServoRelayEvents, &rover.ServoRelayEvents, update_events, 50, 200, 66), #if GRIPPER_ENABLED == ENABLED SCHED_TASK_CLASS(AP_Gripper, &rover.g2.gripper, update, 10, 75, 69), +#if PRECISION_LANDING == ENABLED + SCHED_TASK(update_precland, 400, 50, 70), +#endif #endif SCHED_TASK_CLASS(AP_RPM, &rover.rpm_sensor, update, 10, 100, 72), #if HAL_MOUNT_ENABLED @@ -112,7 +114,6 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = { #if HAL_SPRAYER_ENABLED SCHED_TASK_CLASS(AC_Sprayer, &rover.g2.sprayer, update, 3, 90, 99), #endif - SCHED_TASK_CLASS(Compass, &rover.compass, cal_update, 50, 200, 102), SCHED_TASK(compass_save, 0.1, 200, 105), #if LOGGING_ENABLED == ENABLED SCHED_TASK_CLASS(AP_Logger, &rover.logger, periodic_tasks, 50, 300, 108), @@ -130,9 +131,6 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = { #if ADVANCED_FAILSAFE == ENABLED SCHED_TASK(afs_fs_check, 10, 200, 129), #endif -#if HAL_AIS_ENABLED - SCHED_TASK_CLASS(AP_AIS, &rover.g2.ais, update, 5, 100, 135), -#endif }; @@ -214,6 +212,12 @@ bool Rover::set_desired_turn_rate_and_speed(float turn_rate, float speed) return true; } +// set desired nav speed (m/s). Used for scripting. +bool Rover::set_desired_speed(float speed) +{ + return control_mode->set_desired_speed(speed); +} + // get control output (for use in scripting) // returns true on success and control_value is set to a value in the range -1 to +1 bool Rover::get_control_output(AP_Vehicle::ControlOutput control_output, float &control_value) @@ -366,16 +370,21 @@ void Rover::update_logging1(void) if (should_log(MASK_LOG_THR)) { Log_Write_Throttle(); - logger.Write_Beacon(g2.beacon); + g2.beacon.log(); } if (should_log(MASK_LOG_NTUN)) { Log_Write_Nav_Tuning(); + if (g2.pos_control.is_active()) { + g2.pos_control.write_log(); + logger.Write_PID(LOG_PIDN_MSG, g2.pos_control.get_vel_pid().get_pid_info_x()); + logger.Write_PID(LOG_PIDE_MSG, g2.pos_control.get_vel_pid().get_pid_info_y()); + } } #if HAL_PROXIMITY_ENABLED if (should_log(MASK_LOG_RANGEFINDER)) { - logger.Write_Proximity(g2.proximity); + g2.proximity.log(); } #endif } @@ -396,6 +405,9 @@ void Rover::update_logging2(void) if (should_log(MASK_LOG_IMU)) { AP::ins().Write_Vibration(); +#if HAL_GYROFFT_ENABLED + gyro_fft.write_log_messages(); +#endif } } @@ -405,9 +417,6 @@ void Rover::update_logging2(void) */ void Rover::one_second_loop(void) { - // allow orientation change at runtime to aid config - ahrs.update_orientation(); - set_control_channels(); // cope with changes to aux functions @@ -433,6 +442,7 @@ void Rover::one_second_loop(void) // send latest param values to wp_nav g2.wp_nav.set_turn_params(g2.turn_radius, g2.motors.have_skid_steering()); + g2.pos_control.set_turn_params(g2.turn_radius, g2.motors.have_skid_steering()); } void Rover::update_current_mode(void) diff --git a/Rover/Rover.h b/Rover/Rover.h index 2cab6b2651d..87ec7776279 100644 --- a/Rover/Rover.h +++ b/Rover/Rover.h @@ -19,69 +19,40 @@ #include #include +#include // Libraries #include #include -#include -#include -#include // interface and maths for accelerometer calibration -#include // ArduPilot Mega DCM Library -#include #include // Battery monitor library -#include #include // Camera triggering -#include // ArduPilot Mega Magnetometer Library -#include // Compass declination library -#include // Inertial Sensor (uncalibated IMU) Library -#include -#include // ArduPilot Mega Vector/Matrix math Library -#include // Mission command library #include // Camera/Antenna mount -#include -#include -#include -#include // Optical Flow library #include #include // Range finder library #include // RC input mapping library +#include // RPM input library #include // main loop scheduler -#include // statistics library -#include #include // needed for AHRS build #include #include -#include -#include -#include #include -#include // Mode Filter from Filter library -#include // Filter library - butterworth filter -#include // Filter library -#include -#include // Mode Filter from Filter library -#include -#include -#include -#include -#include #include -#include #include -#include -#include +#include +#include +#include + +// Configuration +#include "defines.h" +#include "config.h" #if AP_SCRIPTING_ENABLED #include #endif // Local modules -#include "mode.h" #include "AP_Arming.h" #include "sailboat.h" -// Configuration -#include "config.h" -#include "defines.h" #if ADVANCED_FAILSAFE == ENABLED #include "afs_rover.h" #endif @@ -90,6 +61,11 @@ #include "GCS_Rover.h" #include "AP_Rally.h" #include "RC_Channel.h" // RC Channel Library +#if PRECISION_LANDING == ENABLED +#include +#endif + +#include "mode.h" class Rover : public AP_Vehicle { public: @@ -114,6 +90,9 @@ class Rover : public AP_Vehicle { friend class ModeSmartRTL; friend class ModeFollow; friend class ModeSimple; +#if MODE_DOCK_ENABLED == ENABLED + friend class ModeDock; +#endif friend class RC_Channel_Rover; friend class RC_Channels_Rover; @@ -156,16 +135,16 @@ class Rover : public AP_Vehicle { // Arming/Disarming management class AP_Arming_Rover arming; - AP_L1_Control L1_controller{ahrs, nullptr}; - #if AP_OPTICALFLOW_ENABLED - OpticalFlow optflow; + AP_OpticalFlow optflow; #endif #if OSD_ENABLED || OSD_PARAM_ENABLED AP_OSD osd; #endif - +#if PRECISION_LANDING == ENABLED + AC_PrecLand precland; +#endif // GCS handling GCS_Rover _gcs; // avoid using this; use gcs() GCS_Rover &gcs() { return _gcs; } @@ -254,6 +233,9 @@ class Rover : public AP_Vehicle { ModeSmartRTL mode_smartrtl; ModeFollow mode_follow; ModeSimple mode_simple; +#if MODE_DOCK_ENABLED == ENABLED + ModeDock mode_dock; +#endif // cruise throttle and speed learning typedef struct { @@ -273,6 +255,7 @@ class Rover : public AP_Vehicle { bool set_steering_and_throttle(float steering, float throttle) override; // set desired turn rate (degrees/sec) and speed (m/s). Used for scripting bool set_desired_turn_rate_and_speed(float turn_rate, float speed) override; + bool set_desired_speed(float speed) override; bool get_control_output(AP_Vehicle::ControlOutput control_output, float &control_value) override; bool nav_scripting_enable(uint8_t mode) override; bool nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2) override; @@ -343,6 +326,10 @@ class Rover : public AP_Vehicle { // Parameters.cpp void load_parameters(void) override; + // precision_landing.cpp + void init_precland(); + void update_precland(); + // radio.cpp void set_control_channels(void) override; void init_rc_in(); diff --git a/Rover/balance_bot.cpp b/Rover/balance_bot.cpp index cf351497942..9b50625b10d 100644 --- a/Rover/balance_bot.cpp +++ b/Rover/balance_bot.cpp @@ -7,15 +7,8 @@ void Rover::balancebot_pitch_control(float &throttle) // calculate desired pitch angle const float demanded_pitch = radians(-throttle * 0.01f * g2.bal_pitch_max) + radians(g2.bal_pitch_trim); - // calculate speed from wheel encoders - float veh_speed_pct = 0.0f; - if (g2.wheel_encoder.enabled(0) && g2.wheel_encoder.enabled(1) && is_positive(g2.wheel_rate_control.get_rate_max_rads())) { - veh_speed_pct = (g2.wheel_encoder.get_rate(0) + g2.wheel_encoder.get_rate(1)) / (2.0f * g2.wheel_rate_control.get_rate_max_rads()) * 100.0f; - veh_speed_pct = constrain_float(veh_speed_pct, -100.0f, 100.0f); - } - // calculate required throttle using PID controller - throttle = g2.attitude_control.get_throttle_out_from_pitch(demanded_pitch, veh_speed_pct, g2.motors.limit.throttle_lower, g2.motors.limit.throttle_upper, G_Dt) * 100.0f; + throttle = g2.attitude_control.get_throttle_out_from_pitch(demanded_pitch, radians(g2.bal_pitch_max), g2.motors.limit.throttle_lower || g2.motors.limit.throttle_upper, G_Dt) * 100.0f; } // returns true if vehicle is a balance bot diff --git a/Rover/commands.cpp b/Rover/commands.cpp index 1cd2b7bf763..4298c091859 100644 --- a/Rover/commands.cpp +++ b/Rover/commands.cpp @@ -76,7 +76,5 @@ void Rover::update_home() return; } - if (!ahrs.set_home(loc)) { - // silently ignored... - } + IGNORE_RETURN(ahrs.set_home(loc)); } diff --git a/Rover/config.h b/Rover/config.h index f5d44dd69f3..48b4c9aa630 100644 --- a/Rover/config.h +++ b/Rover/config.h @@ -14,11 +14,6 @@ // FrSky telemetry support // -#ifndef FRSKY_TELEM_ENABLED - #define FRSKY_TELEM_ENABLED ENABLED -#endif - - #ifndef CH7_OPTION #define CH7_OPTION CH7_SAVE_WP #endif @@ -57,6 +52,12 @@ #define AP_RALLY ENABLED #endif +////////////////////////////////////////////////////////////////////////////// +// Precision Landing with companion computer or IRLock sensor +#ifndef PRECISION_LANDING + # define PRECISION_LANDING ENABLED +#endif + ////////////////////////////////////////////////////////////////////////////// // NAVL1 // @@ -80,6 +81,12 @@ #define DEFAULT_LOG_BITMASK 0xffff +////////////////////////////////////////////////////////////////////////////// +// Dock mode - allows vehicle to dock to a docking target +#ifndef MODE_DOCK_ENABLED +# define MODE_DOCK_ENABLED PRECISION_LANDING +#endif + ////////////////////////////////////////////////////////////////////////////// // Developer Items diff --git a/Rover/createTags b/Rover/createTags old mode 100644 new mode 100755 diff --git a/Rover/defines.h b/Rover/defines.h index c3982e2246e..68aa99e6f06 100644 --- a/Rover/defines.h +++ b/Rover/defines.h @@ -102,3 +102,8 @@ enum frame_class { FRAME_BOAT = 2, FRAME_BALANCEBOT = 3, }; + +// manual mode options +enum ManualOptions { + SPEED_SCALING = (1 << 0), +}; diff --git a/Rover/failsafe.cpp b/Rover/failsafe.cpp index b5098688228..68a2f3ca0c4 100644 --- a/Rover/failsafe.cpp +++ b/Rover/failsafe.cpp @@ -149,6 +149,6 @@ void Rover::handle_battery_failsafe(const char* type_str, const int8_t action) void Rover::afs_fs_check(void) { // perform AFS failsafe checks - g2.afs.check(g2.fence.get_breaches() != 0, failsafe.last_valid_rc_ms); + g2.afs.check(fence.get_breaches() != 0, failsafe.last_valid_rc_ms); } #endif diff --git a/Rover/fence.cpp b/Rover/fence.cpp index 84722f4d1ba..fba0706bdef 100644 --- a/Rover/fence.cpp +++ b/Rover/fence.cpp @@ -3,11 +3,12 @@ // fence_check - ask fence library to check for breaches and initiate the response void Rover::fence_check() { +#if AP_FENCE_ENABLED uint8_t new_breaches; // the type of fence that has been breached - const uint8_t orig_breaches = g2.fence.get_breaches(); + const uint8_t orig_breaches = fence.get_breaches(); // check for a breach - new_breaches = g2.fence.check(); + new_breaches = fence.check(); // return immediately if motors are not armed if (!arming.is_armed()) { @@ -17,10 +18,10 @@ void Rover::fence_check() // if there is a new breach take action if (new_breaches) { // if the user wants some kind of response and motors are armed - if (g2.fence.get_action() != Failsafe_Action_None) { + if (fence.get_action() != Failsafe_Action_None) { // if within 100m of the fence, it will take the action specified by the FENCE_ACTION parameter - if (g2.fence.get_breach_distance(new_breaches) <= AC_FENCE_GIVE_UP_DISTANCE) { - switch (g2.fence.get_action()) { + if (fence.get_breach_distance(new_breaches) <= AC_FENCE_GIVE_UP_DISTANCE) { + switch (fence.get_action()) { case Failsafe_Action_None: break; case Failsafe_Action_RTL: @@ -56,4 +57,5 @@ void Rover::fence_check() AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode::ERROR_RESOLVED); } +#endif // AP_FENCE_ENABLED } diff --git a/Rover/mode.cpp b/Rover/mode.cpp index 415bbb2c288..1509b724367 100644 --- a/Rover/mode.cpp +++ b/Rover/mode.cpp @@ -1,4 +1,3 @@ -#include "mode.h" #include "Rover.h" Mode::Mode() : @@ -246,9 +245,9 @@ float Mode::get_desired_lat_accel() const } // set desired location -bool Mode::set_desired_location(const struct Location& destination, float next_leg_bearing_cd) +bool Mode::set_desired_location(const Location &destination, Location next_destination ) { - if (!g2.wp_nav.set_desired_location(destination, next_leg_bearing_cd)) { + if (!g2.wp_nav.set_desired_location(destination, next_destination)) { return false; } @@ -318,7 +317,9 @@ void Mode::calc_throttle(float target_speed, bool avoidance_enabled) bool stopped; throttle_out = 100.0f * attitude_control.get_throttle_out_stop(g2.motors.limit.throttle_lower, g2.motors.limit.throttle_upper, g.speed_cruise, g.throttle_cruise * 0.01f, rover.G_Dt, stopped); } else { - throttle_out = 100.0f * attitude_control.get_throttle_out_speed(target_speed, g2.motors.limit.throttle_lower, g2.motors.limit.throttle_upper, g.speed_cruise, g.throttle_cruise * 0.01f, rover.G_Dt); + bool motor_lim_low = g2.motors.limit.throttle_lower || attitude_control.pitch_limited(); + bool motor_lim_high = g2.motors.limit.throttle_upper || attitude_control.pitch_limited(); + throttle_out = 100.0f * attitude_control.get_throttle_out_speed(target_speed, motor_lim_low, motor_lim_high, g.speed_cruise, g.throttle_cruise * 0.01f, rover.G_Dt); } // if vehicle is balance bot, calculate actual throttle required for balancing @@ -420,14 +421,26 @@ float Mode::calc_speed_nudge(float target_speed, bool reversed) // this function updates _distance_to_destination void Mode::navigate_to_waypoint() { + // apply speed nudge from pilot + // calc_speed_nudge's "desired_speed" argument should be negative when vehicle is reversing + // AR_WPNav nudge_speed_max argu,ent should always be positive even when reversing + const float calc_nudge_input_speed = g2.wp_nav.get_speed_max() * (g2.wp_nav.get_reversed() ? -1.0 : 1.0); + const float nudge_speed_max = calc_speed_nudge(calc_nudge_input_speed, g2.wp_nav.get_reversed()); + g2.wp_nav.set_nudge_speed_max(fabsf(nudge_speed_max)); + // update navigation controller g2.wp_nav.update(rover.G_Dt); _distance_to_destination = g2.wp_nav.get_distance_to_destination(); - // pass speed to throttle controller after applying nudge from pilot - float desired_speed = g2.wp_nav.get_speed(); - desired_speed = calc_speed_nudge(desired_speed, g2.wp_nav.get_reversed()); - calc_throttle(desired_speed, true); + // sailboats trigger tack if simple avoidance becomes active + if (g2.sailboat.tack_enabled() && g2.avoid.limits_active()) { + // we are a sailboat trying to avoid fence, try a tack + rover.control_mode->handle_tack_request(); + } + + // pass desired speed to throttle controller + // do not do simple avoidance because this is already handled in the position controller + calc_throttle(g2.wp_nav.get_speed(), false); float desired_heading_cd = g2.wp_nav.oa_wp_bearing_cd(); if (g2.sailboat.use_indirect_route(desired_heading_cd)) { @@ -459,7 +472,7 @@ void Mode::calc_steering_from_turn_rate(float turn_rate) g2.motors.limit.steer_left, g2.motors.limit.steer_right, rover.G_Dt); - g2.motors.set_steering(steering_out * 4500.0f); + set_steering(steering_out * 4500.0f); } /* @@ -539,6 +552,11 @@ Mode *Rover::mode_from_mode_num(const enum Mode::Number num) case Mode::Number::INITIALISING: ret = &mode_initializing; break; +#if MODE_DOCK_ENABLED == ENABLED + case Mode::Number::DOCK: + ret = (Mode *)g2.mode_dock_ptr; + break; +#endif default: break; } diff --git a/Rover/mode.h b/Rover/mode.h index 67bea9e8dbb..e12fd710cf6 100644 --- a/Rover/mode.h +++ b/Rover/mode.h @@ -1,13 +1,6 @@ #pragma once -#include - -#include -#include -#include -#include - -#include "defines.h" +#include "Rover.h" // pre-define ModeRTL so Auto can appear higher in this file class ModeRTL; @@ -26,11 +19,14 @@ class Mode LOITER = 5, FOLLOW = 6, SIMPLE = 7, +#if MODE_DOCK_ENABLED == ENABLED + DOCK = 8, +#endif AUTO = 10, RTL = 11, SMART_RTL = 12, GUIDED = 15, - INITIALISING = 16 + INITIALISING = 16, }; // Constructor @@ -112,8 +108,8 @@ class Mode virtual bool get_desired_location(Location& destination) const WARN_IF_UNUSED { return false; } // set desired location (used in Guided, Auto) - // next_leg_bearing_cd should be heading to the following waypoint (used to slow the vehicle in order to make the turn) - virtual bool set_desired_location(const struct Location& destination, float next_leg_bearing_cd = AR_WPNAV_HEADING_UNKNOWN) WARN_IF_UNUSED; + // set next_destination (if known). If not provided vehicle stops at destination + virtual bool set_desired_location(const Location &destination, Location next_destination = Location()) WARN_IF_UNUSED; // true if vehicle has reached desired location. defaults to true because this is normally used by missions and we do not want the mission to become stuck virtual bool reached_destination() const { return true; } @@ -262,7 +258,7 @@ class ModeAuto : public Mode // get or set desired location bool get_desired_location(Location& destination) const override WARN_IF_UNUSED; - bool set_desired_location(const struct Location& destination, float next_leg_bearing_cd = AR_WPNAV_HEADING_UNKNOWN) override WARN_IF_UNUSED; + bool set_desired_location(const Location &destination, Location next_destination = Location()) override WARN_IF_UNUSED; bool reached_destination() const override; // set desired speed in m/s @@ -383,6 +379,9 @@ class ModeAuto : public Mode float arg2; // 2nd argument provided by mission command } nav_scripting; #endif + + // Mission change detector + AP_Mission_ChangeDetector mis_change_detector; }; @@ -402,6 +401,12 @@ class ModeGuided : public Mode // return if external control is allowed in this mode (Guided or Guided-within-Auto) bool in_guided_mode() const override { return true; } + // return heading (in degrees) and cross track error (in meters) for reporting to ground station (NAV_CONTROLLER_OUTPUT message) + float wp_bearing() const override; + float nav_bearing() const override; + float crosstrack_error() const override; + float get_desired_lat_accel() const override; + // return distance (in meters) to destination float get_distance_to_destination() const override; @@ -413,7 +418,7 @@ class ModeGuided : public Mode // get or set desired location bool get_desired_location(Location& destination) const override WARN_IF_UNUSED; - bool set_desired_location(const struct Location& destination, float next_leg_bearing_cd = AR_WPNAV_HEADING_UNKNOWN) override WARN_IF_UNUSED; + bool set_desired_location(const Location &destination, Location next_destination = Location()) override WARN_IF_UNUSED; // set desired heading and speed void set_desired_heading_and_speed(float yaw_angle_cd, float target_speed); @@ -448,8 +453,17 @@ class ModeGuided : public Mode Guided_Stop }; + // enum for GUID_OPTIONS parameter + enum class Options : int32_t { + SCurvesUsedForNavigation = (1U << 6) + }; + bool _enter() override; + // returns true if GUID_OPTIONS bit set to use scurve navigation instead of position controller input shaping + // scurves provide path planning and object avoidance but cannot handle fast updates to the destination (for fast updates use position controller input shaping) + bool use_scurves_for_navigation() const; + GuidedMode _guided_mode; // stores which GUIDED mode the vehicle is in // attitude control @@ -733,3 +747,54 @@ class ModeSimple : public Mode float _desired_heading_cd; // latest desired heading (in centi-degrees) from pilot }; +#if MODE_DOCK_ENABLED == ENABLED +class ModeDock : public Mode +{ +public: + + // need a constructor for parameters + ModeDock(void); + + // Does not allow copies + CLASS_NO_COPY(ModeDock); + + uint32_t mode_number() const override { return DOCK; } + const char *name4() const override { return "DOCK"; } + + // methods that affect movement of the vehicle in this mode + void update() override; + + bool is_autopilot_mode() const override { return true; } + + // return distance (in meters) to destination + float get_distance_to_destination() const override { return _distance_to_destination; } + + static const struct AP_Param::GroupInfo var_info[]; + +protected: + + AP_Float speed; // dock mode speed + AP_Float desired_dir; // desired direction of approach + AP_Int8 hdg_corr_enable; // enable heading correction + AP_Float hdg_corr_weight; // heading correction weight + AP_Float stopping_dist; // how far away from the docking target should we start stopping + + bool _enter() override; + + // return reduced speed of vehicle based on error in position and current distance from the dock + float apply_slowdown(float desired_speed); + + // calculate position of dock relative to the vehicle + bool calc_dock_pos_rel_vehicle_NE(Vector2f &dock_pos_rel_vehicle) const; + + // we force the vehicle to use real dock target vector when this much close to the docking station + const float _force_real_target_limit_cm = 300.0f; + // acceptable lateral error in vehicle's position with respect to dock. This is used while slowing down the vehicle + const float _acceptable_pos_error_cm = 20.0f; + + Vector2f _dock_pos_rel_origin_cm; // position vector towards docking target relative to ekf origin + Vector2f _desired_heading_NE; // unit vector in desired direction of docking + bool _docking_complete = false; // flag to mark docking complete when we are close enough to the dock + bool _loitering = false; // true if we are loitering after mission completion +}; +#endif diff --git a/Rover/mode_acro.cpp b/Rover/mode_acro.cpp index 7e1e5894022..d59f208f0aa 100644 --- a/Rover/mode_acro.cpp +++ b/Rover/mode_acro.cpp @@ -1,4 +1,3 @@ -#include "mode.h" #include "Rover.h" void ModeAcro::update() @@ -9,6 +8,12 @@ void ModeAcro::update() float desired_throttle; // convert pilot stick input into desired steering and throttle get_pilot_desired_steering_and_throttle(desired_steering, desired_throttle); + + // if vehicle is balance bot, calculate actual throttle required for balancing + if (rover.is_balancebot()) { + rover.balancebot_pitch_control(desired_throttle); + } + // no valid speed, just use the provided throttle g2.motors.set_throttle(desired_throttle); } else { diff --git a/Rover/mode_auto.cpp b/Rover/mode_auto.cpp index 3aeb363c6cd..68cbdc35a4f 100644 --- a/Rover/mode_auto.cpp +++ b/Rover/mode_auto.cpp @@ -1,4 +1,3 @@ -#include "mode.h" #include "Rover.h" #define AUTO_GUIDED_SEND_TARGET_MS 1000 @@ -11,8 +10,8 @@ bool ModeAuto::_enter() return false; } - // initialise waypoint speed - g2.wp_nav.set_desired_speed_to_default(); + // initialise waypoint navigation library + g2.wp_nav.init(); // other initialisation auto_triggered = false; @@ -53,25 +52,42 @@ void ModeAuto::update() // start/resume the mission (based on MIS_RESTART parameter) mission.start_or_resume(); waiting_to_start = false; + + // initialise mission change check + IGNORE_RETURN(mis_change_detector.check_for_mission_change()); } } else { + // check for mission changes + if (mis_change_detector.check_for_mission_change()) { + // if mission is running restart the current command if it is a waypoint command + if ((mission.state() == AP_Mission::MISSION_RUNNING) && (_submode == AutoSubMode::Auto_WP)) { + if (mission.restart_current_nav_cmd()) { + gcs().send_text(MAV_SEVERITY_CRITICAL, "Auto mission changed, restarted command"); + } else { + // failed to restart mission for some reason + gcs().send_text(MAV_SEVERITY_CRITICAL, "Auto mission changed but failed to restart command"); + } + } + } + mission.update(); } switch (_submode) { case Auto_WP: { - if (!g2.wp_nav.reached_destination()) { + // check if we've reached the destination + if (!g2.wp_nav.reached_destination() || g2.wp_nav.is_fast_waypoint()) { // update navigation controller navigate_to_waypoint(); } else { // we have reached the destination so stay here if (rover.is_boat()) { if (!start_loiter()) { - stop_vehicle(); + start_stop(); } } else { - stop_vehicle(); + start_stop(); } // update distance to destination _distance_to_destination = rover.current_loc.get_distance(g2.wp_nav.get_destination()); @@ -187,10 +203,10 @@ bool ModeAuto::get_desired_location(Location& destination) const } // set desired location to drive to -bool ModeAuto::set_desired_location(const struct Location& destination, float next_leg_bearing_cd) +bool ModeAuto::set_desired_location(const Location &destination, Location next_destination) { // call parent - if (!Mode::set_desired_location(destination, next_leg_bearing_cd)) { + if (!Mode::set_desired_location(destination, next_destination)) { return false; } @@ -233,11 +249,7 @@ bool ModeAuto::set_desired_speed(float speed) switch (_submode) { case Auto_WP: case Auto_Stop: - if (!is_negative(speed)) { - g2.wp_nav.set_desired_speed(speed); - return true; - } - return false; + return g2.wp_nav.set_speed_max(speed); case Auto_HeadingAndSpeed: _desired_speed = speed; return true; @@ -468,13 +480,15 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd) break; case MAV_CMD_DO_FENCE_ENABLE: +#if AP_FENCE_ENABLED if (cmd.p1 == 0) { //disable - g2.fence.enable(false); + rover.fence.enable(false); gcs().send_text(MAV_SEVERITY_INFO, "Fence Disabled"); } else { //enable fence - g2.fence.enable(true); + rover.fence.enable(true); gcs().send_text(MAV_SEVERITY_INFO, "Fence Enabled"); } +#endif break; case MAV_CMD_DO_GUIDED_LIMITS: @@ -602,29 +616,36 @@ void ModeAuto::do_RTL(void) bool ModeAuto::do_nav_wp(const AP_Mission::Mission_Command& cmd, bool always_stop_at_destination) { - // get heading to following waypoint (auto mode reduces speed to allow corning without large overshoot) - // in case of non-zero loiter duration, we provide heading-unknown to signal we should stop at the point - float next_leg_bearing_cd = AR_WPNAV_HEADING_UNKNOWN; - if (!always_stop_at_destination && loiter_duration == 0) { - next_leg_bearing_cd = mission.get_next_ground_course_cd(AR_WPNAV_HEADING_UNKNOWN); - } - // retrieve and sanitize target location Location cmdloc = cmd.content.location; cmdloc.sanitize(rover.current_loc); - if (!set_desired_location(cmdloc, next_leg_bearing_cd)) { - return false; + + // delayed stored in p1 in seconds + loiter_duration = ((int16_t) cmd.p1 < 0) ? 0 : cmd.p1; + loiter_start_time = 0; + if (loiter_duration > 0) { + always_stop_at_destination = true; + } + + // do not add next wp if there are no more navigation commands + AP_Mission::Mission_Command next_cmd; + if (always_stop_at_destination || !mission.get_next_nav_cmd(cmd.index+1, next_cmd)) { + // single destination + if (!set_desired_location(cmdloc)) { + return false; + } + } else { + // retrieve and sanitize next destination location + Location next_cmdloc = next_cmd.content.location; + next_cmdloc.sanitize(cmdloc); + if (!set_desired_location(cmdloc, next_cmdloc)) { + return false; + } } // just starting so we haven't previously reached the waypoint previously_reached_wp = false; - // this will be used to remember the time in millis after we reach or pass the WP. - loiter_start_time = 0; - - // this is the delay, stored in seconds, checked such that commanded delays < 0 delay 0 seconds - loiter_duration = ((int16_t) cmd.p1 < 0) ? 0 : cmd.p1; - return true; } @@ -679,7 +700,6 @@ void ModeAuto::do_nav_set_yaw_speed(const AP_Mission::Mission_Command& cmd) _desired_speed = constrain_float(cmd.content.set_yaw_speed.speed, -speed_max, speed_max); _desired_yaw_cd = desired_heading_cd; _reached_heading = false; - _reached_destination = false; _submode = Auto_HeadingAndSpeed; } diff --git a/Rover/mode_dock.cpp b/Rover/mode_dock.cpp new file mode 100644 index 00000000000..5bbfabfafb0 --- /dev/null +++ b/Rover/mode_dock.cpp @@ -0,0 +1,255 @@ +#include "Rover.h" + +#if MODE_DOCK_ENABLED == ENABLED + +const AP_Param::GroupInfo ModeDock::var_info[] = { + // @Param: _SPEED + // @DisplayName: Dock mode speed + // @Description: Vehicle speed limit in dock mode + // @Units: m/s + // @Range: 0 100 + // @Increment: 0.1 + // @User: Standard + AP_GROUPINFO("_SPEED", 1, ModeDock, speed, 0.0f), + + // @Param: _DIR + // @DisplayName: Dock mode direction of approach + // @Description: Compass direction in which vehicle should approach towards dock. -1 value represents unset parameter + // @Units: deg + // @Range: 0 360 + // @Increment: 1 + // @User: Advanced + AP_GROUPINFO("_DIR", 2, ModeDock, desired_dir, -1.00f), + + // @Param: _HDG_CORR_EN + // @DisplayName: Dock mode heading correction enable/disable + // @Description: When enabled, the autopilot modifies the path to approach the target head-on along desired line of approch in dock mode + // @Values: 0:Disabled,1:Enabled + // @User: Advanced + AP_GROUPINFO("_HDG_CORR_EN", 3, ModeDock, hdg_corr_enable, 0), + + // @Param: _HDG_CORR_WT + // @DisplayName: Dock mode heading correction weight + // @Description: This value describes how aggressively vehicle tries to correct its heading to be on desired line of approach + // @Range: 0.00 0.90 + // @Increment: 0.05 + // @User: Advanced + AP_GROUPINFO("_HDG_CORR_WT", 4, ModeDock, hdg_corr_weight, 0.75f), + + // @Param: _STOP_DIST + // @DisplayName: Distance from docking target when we should stop + // @Description: The vehicle starts stopping when it is this distance away from docking target + // @Units: m + // @Range: 0 2 + // @Increment: 0.01 + // @User: Standard + AP_GROUPINFO("_STOP_DIST", 5, ModeDock, stopping_dist, 0.30f), + + AP_GROUPEND +}; + +ModeDock::ModeDock(void) : Mode() +{ + AP_Param::setup_object_defaults(this, var_info); +} + +#define AR_DOCK_ACCEL_MAX 20.0 // acceleration used when user has specified no acceleration limit + +// initialize dock mode +bool ModeDock::_enter() +{ + // refuse to enter the mode if dock is not in sight + if (!rover.precland.enabled() || !rover.precland.target_acquired()) { + return false; + } + + if (hdg_corr_enable && is_negative(desired_dir)) { + // DOCK_DIR is required for heading correction + gcs().send_text(MAV_SEVERITY_NOTICE, "Dock: Set DOCK_DIR or disable heading correction"); + return false; + } + + // set speed limit to dock_speed param if available + // otherwise the vehicle uses wp_nav default speed limit + const float speed_max = is_positive(speed) ? speed : g2.wp_nav.get_default_speed(); + float atc_accel_max = MIN(g2.attitude_control.get_accel_max(), g2.attitude_control.get_decel_max()); + if (!is_positive(atc_accel_max)) { + // accel_max of zero means no limit so use maximum acceleration + atc_accel_max = AR_DOCK_ACCEL_MAX; + } + const float accel_max = is_positive(g2.wp_nav.get_default_accel()) ? MIN(g2.wp_nav.get_default_accel(), atc_accel_max) : atc_accel_max; + const float jerk_max = is_positive(g2.wp_nav.get_default_jerk()) ? g2.wp_nav.get_default_jerk() : accel_max; + + // initialise position controller + g2.pos_control.set_limits(speed_max, accel_max, g2.attitude_control.get_turn_lat_accel_max(), jerk_max); + g2.pos_control.init(); + + // set the position controller reversed in case the camera is mounted on vehicle's back + g2.pos_control.set_reversed(rover.precland.get_orient() == 4); + + // construct unit vector in the desired direction from where we want the vehicle to approach the dock + // this helps to dock the vehicle head-on even when we enter the dock mode at an angle towards the dock + _desired_heading_NE = Vector2f{cosf(radians(desired_dir)), sinf(radians(desired_dir))}; + + _docking_complete = false; + + return true; +} + +void ModeDock::update() +{ + // if docking is complete, rovers stop and boats loiter + if (_docking_complete) { + // rovers stop, boats loiter + // note that loiter update must be called after successfull initialisation on mode loiter + if (_loitering) { + // mode loiter must be initialised before calling update method + rover.mode_loiter.update(); + } else { + stop_vehicle(); + } + return; + } + + const bool real_dock_in_sight = rover.precland.get_target_position_cm(_dock_pos_rel_origin_cm); + Vector2f dock_pos_rel_vehicle_cm; + if (!calc_dock_pos_rel_vehicle_NE(dock_pos_rel_vehicle_cm)) { + g2.motors.set_throttle(0.0f); + g2.motors.set_steering(0.0f); + return; + } + + _distance_to_destination = dock_pos_rel_vehicle_cm.length() * 0.01f; + + // we force the vehicle to use real dock as target when we are too close to the dock + // note that heading correction does not work when we force real target + const bool force_real_target = _distance_to_destination < _force_real_target_limit_cm * 0.01f; + + // if we are close enough to the dock or the target is not in sight when we strictly require it + // we mark the docking to be completed so that the vehicle stops + if (_distance_to_destination <= stopping_dist || (force_real_target && !real_dock_in_sight)) { + _docking_complete = true; + + // send a one time notification to GCS + gcs().send_text(MAV_SEVERITY_INFO, "Dock: Docking complete"); + + // initialise mode loiter if it is a boat + if (rover.is_boat()) { + // if we fail to enter, we set _loitering to false + _loitering = rover.mode_loiter.enter(); + } + return; + } + + Vector2f target_cm = _dock_pos_rel_origin_cm; + + // ***** HEADING CORRECTION ***** + // to make to vehicle dock from a given direction we simulate a virtual moving target on the line of approach + // this target is always at DOCK_HDG_COR_WT times the distance from dock to vehicle (along the line of approach) + // For e.g., if the dock is 100 m away form dock, DOCK_HDG_COR_WT is 0.75 + // then the position target is 75 m from the dock, i.e., 25 m from the vehicle + // as the vehicle tries to reach this target, this target appears to move towards the dock and at last it is sandwiched b/w dock and vehicle + // since this target is moving along desired direction of approach, the vehicle also comes on that line while following it + if (!force_real_target && hdg_corr_enable) { + const float correction_vec_mag = hdg_corr_weight * dock_pos_rel_vehicle_cm.projected(_desired_heading_NE).length(); + target_cm = _dock_pos_rel_origin_cm - _desired_heading_NE * correction_vec_mag; + } + + const Vector2p target_pos { target_cm.topostype() * 0.01 }; + g2.pos_control.input_pos_target(target_pos, rover.G_Dt); + g2.pos_control.update(rover.G_Dt); + + // get desired speed and turn rate from pos_control + float desired_speed = g2.pos_control.get_desired_speed(); + float desired_turn_rate = g2.pos_control.get_desired_turn_rate_rads(); + + // slow down the vehicle as we approach the dock + desired_speed = apply_slowdown(desired_speed); + + // run steering and throttle controllers + calc_steering_from_turn_rate(desired_turn_rate); + calc_throttle(desired_speed, true); + +// @LoggerMessage: DOCK +// @Description: Dock mode target information +// @Field: TimeUS: Time since system startup +// @Field: DockX: Docking Station position, X-Axis +// @Field: DockY: Docking Station position, Y-Axis +// @Field: DockDist: Distance to docking station +// @Field: TPosX: Current Position Target, X-Axis +// @Field: TPosY: Current Position Target, Y-Axis +// @Field: DSpd: Desired speed +// @Field: DTrnRt: Desired Turn Rate + + AP::logger().WriteStreaming( + "DOCK", + "TimeUS,DockX,DockY,DockDist,TPosX,TPosY,DSpd,DTrnRt", + "smmmmmnE", + "FBB0BB00", + "Qfffffff", + AP_HAL::micros64(), + _dock_pos_rel_origin_cm.x, + _dock_pos_rel_origin_cm.y, + _distance_to_destination, + target_cm.x, + target_cm.y, + desired_speed, + desired_turn_rate); +} + +float ModeDock::apply_slowdown(float desired_speed) +{ + const float dock_speed_slowdown_lmt = 0.5f; + + // no slowdown for speed below dock_speed_slowdown_lmt + if (fabsf(desired_speed) < dock_speed_slowdown_lmt) { + return desired_speed; + } + + Vector3f target_vec_rel_vehicle_NED; + if(!calc_dock_pos_rel_vehicle_NE(target_vec_rel_vehicle_NED.xy())) { + return desired_speed; + } + + const Matrix3f &body_to_ned = AP::ahrs().get_rotation_body_to_ned(); + Vector3f target_vec_body = body_to_ned.mul_transpose(target_vec_rel_vehicle_NED); + const float target_error_cm = fabsf(target_vec_body.y); + float error_ratio = target_error_cm / _acceptable_pos_error_cm; + error_ratio = constrain_float(error_ratio, 0.0f, 1.0f); + + const float dock_slow_dist_max_m = 15.0f; + const float dock_slow_dist_min_m = 5.0f; + // approach slowdown is not applied when the vehicle is more than dock_slow_dist_max meters away + // within dock_slow_dist_max and dock_slow_dist_min the weight of the slowdown increases linearly + // once the vehicle reaches dock_slow_dist_min the slowdown weight becomes 1 + float slowdown_weight = 1 - (target_vec_body.x * 0.01f - dock_slow_dist_min_m) / (dock_slow_dist_max_m - dock_slow_dist_min_m); + slowdown_weight = constrain_float(slowdown_weight, 0.0f, 1.0f); + + desired_speed = MAX(dock_speed_slowdown_lmt, fabsf(desired_speed) * (1 - error_ratio * slowdown_weight)); + + // restrict speed to avoid going beyond stopping distance + desired_speed = MIN(desired_speed, safe_sqrt(2 * fabsf(_distance_to_destination - stopping_dist) * g2.pos_control.get_accel_max())); + + // we worked on absolute value of speed before + // make it negative again if reversed + if (g2.pos_control.get_reversed()) { + desired_speed *= -1; + } + + return desired_speed; +} + +// calculate position of dock relative to the vehicle +// we need this method here because there can be a window during heading correction when we might lose the target +// during that window precland won't be able to give us this vector +// we can calculate it based on most recent value from precland because the dock is assumed stationary wrt ekf origin +bool ModeDock::calc_dock_pos_rel_vehicle_NE(Vector2f &dock_pos_rel_vehicle) const { + Vector2f current_pos_m; + if (!AP::ahrs().get_relative_position_NE_origin(current_pos_m)) { + return false; + } + + dock_pos_rel_vehicle = _dock_pos_rel_origin_cm - current_pos_m * 100.0f; + return true; +} +#endif // MODE_DOCK_ENABLED diff --git a/Rover/mode_follow.cpp b/Rover/mode_follow.cpp index 60075b537ee..437cb53deb8 100644 --- a/Rover/mode_follow.cpp +++ b/Rover/mode_follow.cpp @@ -1,4 +1,3 @@ -#include "mode.h" #include "Rover.h" // initialize follow mode diff --git a/Rover/mode_guided.cpp b/Rover/mode_guided.cpp index 83c45599e9f..76f34367607 100644 --- a/Rover/mode_guided.cpp +++ b/Rover/mode_guided.cpp @@ -1,4 +1,3 @@ -#include "mode.h" #include "Rover.h" bool ModeGuided::_enter() @@ -12,8 +11,8 @@ bool ModeGuided::_enter() start_stop(); } - // initialise waypoint speed - g2.wp_nav.set_desired_speed_to_default(); + // initialise waypoint navigation library + g2.wp_nav.init(); send_notification = false; @@ -142,6 +141,83 @@ void ModeGuided::update() } } +// return heading (in degrees) and cross track error (in meters) for reporting to ground station (NAV_CONTROLLER_OUTPUT message) +float ModeGuided::wp_bearing() const +{ + switch (_guided_mode) { + case Guided_WP: + return g2.wp_nav.wp_bearing_cd() * 0.01f; + case Guided_HeadingAndSpeed: + case Guided_TurnRateAndSpeed: + return 0.0f; + case Guided_Loiter: + return rover.mode_loiter.wp_bearing(); + case Guided_SteeringAndThrottle: + case Guided_Stop: + return 0.0f; + } + + // we should never reach here but just in case, return 0 + return 0.0f; +} + +float ModeGuided::nav_bearing() const +{ + switch (_guided_mode) { + case Guided_WP: + return g2.wp_nav.nav_bearing_cd() * 0.01f; + case Guided_HeadingAndSpeed: + case Guided_TurnRateAndSpeed: + return 0.0f; + case Guided_Loiter: + return rover.mode_loiter.nav_bearing(); + case Guided_SteeringAndThrottle: + case Guided_Stop: + return 0.0f; + } + + // we should never reach here but just in case, return 0 + return 0.0f; +} + +float ModeGuided::crosstrack_error() const +{ + switch (_guided_mode) { + case Guided_WP: + return g2.wp_nav.crosstrack_error(); + case Guided_HeadingAndSpeed: + case Guided_TurnRateAndSpeed: + return 0.0f; + case Guided_Loiter: + return rover.mode_loiter.crosstrack_error(); + case Guided_SteeringAndThrottle: + case Guided_Stop: + return 0.0f; + } + + // we should never reach here but just in case, return 0 + return 0.0f; +} + +float ModeGuided::get_desired_lat_accel() const +{ + switch (_guided_mode) { + case Guided_WP: + return g2.wp_nav.get_lat_accel(); + case Guided_HeadingAndSpeed: + case Guided_TurnRateAndSpeed: + return 0.0f; + case Guided_Loiter: + return rover.mode_loiter.get_desired_lat_accel(); + case Guided_SteeringAndThrottle: + case Guided_Stop: + return 0.0f; + } + + // we should never reach here but just in case, return 0 + return 0.0f; +} + // return distance (in meters) to destination float ModeGuided::get_distance_to_destination() const { @@ -167,7 +243,7 @@ bool ModeGuided::reached_destination() const { switch (_guided_mode) { case Guided_WP: - return _reached_destination; + return g2.wp_nav.reached_destination(); case Guided_HeadingAndSpeed: case Guided_TurnRateAndSpeed: case Guided_Loiter: @@ -185,11 +261,7 @@ bool ModeGuided::set_desired_speed(float speed) { switch (_guided_mode) { case Guided_WP: - if (!is_negative(speed)) { - g2.wp_nav.set_desired_speed(speed); - return true; - } - return false; + return g2.wp_nav.set_speed_max(speed); case Guided_HeadingAndSpeed: case Guided_TurnRateAndSpeed: // speed is set from mavlink message @@ -232,18 +304,26 @@ bool ModeGuided::get_desired_location(Location& destination) const } // set desired location -bool ModeGuided::set_desired_location(const struct Location& destination, - float next_leg_bearing_cd) +bool ModeGuided::set_desired_location(const Location &destination, Location next_destination) { - if (g2.wp_nav.set_desired_location(destination, next_leg_bearing_cd)) { - - // handle guided specific initialisation and logging - _guided_mode = ModeGuided::Guided_WP; - send_notification = true; - rover.Log_Write_GuidedTarget(_guided_mode, Vector3f(destination.lat, destination.lng, 0), Vector3f(g2.wp_nav.get_desired_speed(), 0.0f, 0.0f)); - return true; + if (use_scurves_for_navigation()) { + // use scurves for navigation + if (!g2.wp_nav.set_desired_location(destination, next_destination)) { + return false; + } + } else { + // use position controller input shaping for navigation + // this does not support object avoidance but does allow faster updates of the target + if (!g2.wp_nav.set_desired_location_expect_fast_update(destination)) { + return false; + } } - return false; + + // handle guided specific initialisation and logging + _guided_mode = ModeGuided::Guided_WP; + send_notification = true; + rover.Log_Write_GuidedTarget(_guided_mode, Vector3f(destination.lat, destination.lng, 0), Vector3f(g2.wp_nav.get_speed_max(), 0.0f, 0.0f)); + return true; } // set desired attitude @@ -252,7 +332,6 @@ void ModeGuided::set_desired_heading_and_speed(float yaw_angle_cd, float target_ // initialisation and logging _guided_mode = ModeGuided::Guided_HeadingAndSpeed; _des_att_time_ms = AP_HAL::millis(); - _reached_destination = false; // record targets _desired_yaw_cd = yaw_angle_cd; @@ -279,7 +358,6 @@ void ModeGuided::set_desired_turn_rate_and_speed(float turn_rate_cds, float targ // handle initialisation _guided_mode = ModeGuided::Guided_TurnRateAndSpeed; _des_att_time_ms = AP_HAL::millis(); - _reached_destination = false; // record targets _desired_yaw_rate_cds = turn_rate_cds; @@ -354,3 +432,10 @@ bool ModeGuided::limit_breached() const // if we got this far we must be within limits return false; } + +// returns true if GUID_OPTIONS bit set to use scurve navigation instead of position controller input shaping +// scurves provide path planning and object avoidance but cannot handle fast updates to the destination (for fast updates use position controller input shaping) +bool ModeGuided::use_scurves_for_navigation() const +{ + return ((rover.g2.guided_options.get() & uint32_t(Options::SCurvesUsedForNavigation)) != 0); +} diff --git a/Rover/mode_hold.cpp b/Rover/mode_hold.cpp index df2759a51ca..ea989157e34 100644 --- a/Rover/mode_hold.cpp +++ b/Rover/mode_hold.cpp @@ -1,4 +1,3 @@ -#include "mode.h" #include "Rover.h" void ModeHold::update() diff --git a/Rover/mode_loiter.cpp b/Rover/mode_loiter.cpp index 31cd4b824b2..918144c9fa4 100644 --- a/Rover/mode_loiter.cpp +++ b/Rover/mode_loiter.cpp @@ -1,4 +1,3 @@ -#include "mode.h" #include "Rover.h" bool ModeLoiter::_enter() @@ -56,8 +55,20 @@ void ModeLoiter::update() _desired_speed *= yaw_error_ratio; } + // 0 turn rate is no limit + float turn_rate = 0.0; + + // make sure sailboats don't try and sail directly into the wind + if (g2.sailboat.use_indirect_route(_desired_yaw_cd)) { + _desired_yaw_cd = g2.sailboat.calc_heading(_desired_yaw_cd); + if (g2.sailboat.tacking()) { + // use pivot turn rate for tacks + turn_rate = g2.wp_nav.get_pivot_rate(); + } + } + // run steering and throttle controllers - calc_steering_to_heading(_desired_yaw_cd); + calc_steering_to_heading(_desired_yaw_cd, turn_rate); calc_throttle(_desired_speed, true); } diff --git a/Rover/mode_manual.cpp b/Rover/mode_manual.cpp index 622e7ec1629..1435aa2b925 100644 --- a/Rover/mode_manual.cpp +++ b/Rover/mode_manual.cpp @@ -1,4 +1,3 @@ -#include "mode.h" #include "Rover.h" void ModeManual::_exit() @@ -37,6 +36,6 @@ void ModeManual::update() // copy RC scaled inputs to outputs g2.motors.set_throttle(desired_throttle); - g2.motors.set_steering(desired_steering, false); + g2.motors.set_steering(desired_steering, (g2.manual_options & ManualOptions::SPEED_SCALING)); g2.motors.set_lateral(desired_lateral); } diff --git a/Rover/mode_rtl.cpp b/Rover/mode_rtl.cpp index 9da8bc5c458..b9a8ee49649 100644 --- a/Rover/mode_rtl.cpp +++ b/Rover/mode_rtl.cpp @@ -1,4 +1,3 @@ -#include "mode.h" #include "Rover.h" bool ModeRTL::_enter() @@ -8,6 +7,9 @@ bool ModeRTL::_enter() return false; } + // initialise waypoint navigation library + g2.wp_nav.init(MAX(0, g2.rtl_speed)); + // set target to the closest rally point or home #if AP_RALLY == ENABLED if (!g2.wp_nav.set_desired_location(g2.rally.calc_best_rally_or_home_location(rover.current_loc, ahrs.get_home().alt))) { @@ -20,13 +22,6 @@ bool ModeRTL::_enter() } #endif - // initialise waypoint speed - if (is_positive(g2.rtl_speed)) { - g2.wp_nav.set_desired_speed(g2.rtl_speed); - } else { - g2.wp_nav.set_desired_speed_to_default(); - } - send_notification = true; _loitering = false; return true; @@ -85,9 +80,5 @@ bool ModeRTL::reached_destination() const // set desired speed in m/s bool ModeRTL::set_desired_speed(float speed) { - if (is_negative(speed)) { - return false; - } - g2.wp_nav.set_desired_speed(speed); - return true; + return g2.wp_nav.set_speed_max(speed); } diff --git a/Rover/mode_simple.cpp b/Rover/mode_simple.cpp index c91313134bd..73bb4932a76 100644 --- a/Rover/mode_simple.cpp +++ b/Rover/mode_simple.cpp @@ -1,4 +1,3 @@ -#include "mode.h" #include "Rover.h" void ModeSimple::init_heading() diff --git a/Rover/mode_smart_rtl.cpp b/Rover/mode_smart_rtl.cpp index a28984e452b..0d083965e4b 100644 --- a/Rover/mode_smart_rtl.cpp +++ b/Rover/mode_smart_rtl.cpp @@ -1,4 +1,3 @@ -#include "mode.h" #include "Rover.h" bool ModeSmartRTL::_enter() @@ -14,18 +13,14 @@ bool ModeSmartRTL::_enter() return false; } + // initialise waypoint navigation library + g2.wp_nav.init(MAX(0, g2.rtl_speed)); + // set desired location to reasonable stopping point if (!g2.wp_nav.set_desired_location_to_stopping_location()) { return false; } - // initialise waypoint speed - if (is_positive(g2.rtl_speed)) { - g2.wp_nav.set_desired_speed(g2.rtl_speed); - } else { - g2.wp_nav.set_desired_speed_to_default(); - } - // init state smart_rtl_state = SmartRTL_WaitForPathCleanup; _loitering = false; @@ -49,20 +44,33 @@ void ModeSmartRTL::update() case SmartRTL_PathFollow: // load point if required if (_load_point) { - Vector3f next_point; - if (!g2.smart_rtl.pop_point(next_point)) { + Vector3f dest_NED; + if (!g2.smart_rtl.pop_point(dest_NED)) { // if not more points, we have reached home gcs().send_text(MAV_SEVERITY_INFO, "Reached destination"); smart_rtl_state = SmartRTL_StopAtHome; break; + } else { + // peek at the next point. this can fail if the IO task currently has the path semaphore + Vector3f next_dest_NED; + if (g2.smart_rtl.peek_point(next_dest_NED)) { + if (!g2.wp_nav.set_desired_location_NED(dest_NED, next_dest_NED)) { + // this should never happen because the EKF origin should already be set + gcs().send_text(MAV_SEVERITY_INFO, "SmartRTL: failed to set destination"); + smart_rtl_state = SmartRTL_Failure; + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + } + } else { + // no next point so add only immediate point + if (!g2.wp_nav.set_desired_location_NED(dest_NED)) { + // this should never happen because the EKF origin should already be set + gcs().send_text(MAV_SEVERITY_INFO, "SmartRTL: failed to set destination"); + smart_rtl_state = SmartRTL_Failure; + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + } + } } _load_point = false; - // set target destination to new point - if (!g2.wp_nav.set_desired_location_NED(next_point)) { - // this failure should never happen but we add it just in case - gcs().send_text(MAV_SEVERITY_INFO, "SmartRTL: failed to set destination"); - smart_rtl_state = SmartRTL_Failure; - } } // update navigation controller navigate_to_waypoint(); @@ -118,11 +126,7 @@ bool ModeSmartRTL::get_desired_location(Location& destination) const // set desired speed in m/s bool ModeSmartRTL::set_desired_speed(float speed) { - if (is_negative(speed)) { - return false; - } - g2.wp_nav.set_desired_speed(speed); - return true; + return g2.wp_nav.set_speed_max(speed); } // save current position for use by the smart_rtl flight mode diff --git a/Rover/mode_steering.cpp b/Rover/mode_steering.cpp index d46e2c5fac7..d86a155f357 100644 --- a/Rover/mode_steering.cpp +++ b/Rover/mode_steering.cpp @@ -1,4 +1,3 @@ -#include "mode.h" #include "Rover.h" void ModeSteering::update() diff --git a/Rover/motor_test.cpp b/Rover/motor_test.cpp index 549f3f82daf..eaca91d72cc 100644 --- a/Rover/motor_test.cpp +++ b/Rover/motor_test.cpp @@ -130,9 +130,9 @@ MAV_RESULT Rover::mavlink_motor_test_start(const GCS_MAVLINK &gcs_chan, AP_Motor } // disable failsafes - g.fs_gcs_enabled = 0; - g.fs_throttle_enabled = 0; - g.fs_crash_check = 0; + g.fs_gcs_enabled.set(0); + g.fs_throttle_enabled.set(0); + g.fs_crash_check.set(0); // turn on notify leds AP_Notify::flags.esc_calibration = true; diff --git a/Rover/precision_landing.cpp b/Rover/precision_landing.cpp new file mode 100644 index 00000000000..12b33174ebb --- /dev/null +++ b/Rover/precision_landing.cpp @@ -0,0 +1,19 @@ +// +// functions to support precision landing +// + +#include "Rover.h" + +#if PRECISION_LANDING == ENABLED + +void Rover::init_precland() +{ + rover.precland.init(400); +} + +void Rover::update_precland() +{ + // alt will be unused if we pass false through as the second parameter: + return precland.update(0, false); +} +#endif diff --git a/Rover/release-notes.txt b/Rover/release-notes.txt index 52146d4ce7e..01b5883d88e 100644 --- a/Rover/release-notes.txt +++ b/Rover/release-notes.txt @@ -1,5 +1,404 @@ Rover Release Notes: ------------------------------------------------------------------ +Rover 4.3.0-beta14 12-Aug-2023 +Changes from 4.3.0-beta13 +1) Bug fixes + - DroneCAN GPS RTK injection fix + - INAxxx battery monitors allow for battery reset remaining + - Notch filter gyro glitch caused by race condition fixed + - Scripting restart memory corruption bug fixed +------------------------------------------------------------------ +Rover 4.3.0-beta13 27-Mar-2023 +Changes from 4.3.0-beta12 +1) Bug fixes + a) EKF3 accel bias calculations bug fix + b) EKF3 accel bias process noise adjusted for greater robustness + c) GSF yaw numerical stability fix caused by compassmot + d) INS batch sampler fix to avoid watchdog if INS_LOG_BAT_CNT changed without rebooting + e) Memory corruption bug in the STM32H757 (very rare) + f) RC input on IOMCU bug fix (RC might not be regained if lost) +------------------------------------------------------------------ +Rover 4.3.0-beta11/beta12 27-Mar-2023 +Changes from 4.3.0-beta10 +1) Bi-directional DShot fix for possible motor stop approx 72min after startup +------------------------------------------------------------------ +Rover 4.3.0-beta10 01-Mar-2023 +Changes from 4.3.0-beta9 +1) Bug fixes + a) GPS unconfigured error fix for non-M10 uBlox GPS + b) Gremsy gimbal fix when attached to autopilot's serial3 (or higher) + c) MambaF405 2022 gets VTX power on support + d) MCU voltage enabled on H757 CPUs (including CubeOrangePlus) + e) PiccoloCAN fix for ESC voltage and current scaling + f) Servo gimbal mount yaw handling fix (only affects 3-axis servo gimbals) +------------------------------------------------------------------ +Rover 4.3.0-beta9 14-Feb-2023 +Changes from 4.3.0-beta8 +1) AutoPilot specific enhancements + a) CubeOrangePlusBG support + b) Foxeer ReaperF745 supports external compass + c) MambaH743v4 supports VTX power +2) Bug fixes + a) Arming check fix if BARO_FIELD_ELEV set + b) Compass calibration diagonals set to 1,1,1 if incorrectly set to 0,0,0 + c) Gimbal's yaw feed-forward set to zero when landed (affects Gremsy gimbals) + d) IOMCU double reset and safety disable fix + e) Logging fix for duplicate format messages + f) OpenDroneId sets emergency status on crash or chute deploy + g) Peripheral firmware updates using MAVCAN fixed + h) RC protocol cannot be changed once detected on boards with IOMCU +------------------------------------------------------------------ +Rover 4.3.0-beta8 20-Jan-2023 +Changes from 4.3.0-beta7 +1) Bug fixes + a) MAVFTP fix to terminate session error (could cause FTP failures) + b) IMU fast fifo reset log message max frequency reduced +------------------------------------------------------------------ +Rover 4.3.0-beta7 09-Jan-2023 +Changes from 4.3.0-beta6 +1) Autopilot related changes + a) AIRLink LTE module enable pin and HEAT_ params added + b) CUAV Nora/Nora+ bdshot firmware (allows Bi-directional DShot) + c) CubeOrange, CubeYellow gets fast reset of ICM20602 + d) MambaH743v2 with dual ICM42688 supported + e) PixPilot-V6 +2) MAVFTP speed improvement including faster param download +3) Bug fixes + a) Analog rangefinder GPIO pin arming check fixed + b) Arming check of AHRS/EKF vs GPS location disabled if GPS disabled + c) CRSF gets RC_OPTIONS for ELRS baudrate to avoid RC failsafes + d) Null pointer checks avoid watchdog when out of memory + e) Servo gimbal yaw jump to opposite side fixed + f) Siyi A8 gimbal driver's record video feature fixed + g) SToRM32 serial gimbal driver actual angle reporting fixed (pitch and yaw angle signs were reversed) +------------------------------------------------------------------ +Rover 4.3.0-beta6 10-Dec-2022 +Changes from 4.3.0-beta5 +1) Arming check that main loop is running at configured speed (e.g. SCHED_LOOP_RATE) +2) uBlox M10 support +3) Autopilot specific changes + a) CubeOrange defaults to using 2nd IMU as primary + b) SIRF and SBP GPS disabled on BeastF7v2, MatekF405-STD, MAtekF405-Wing, omnibusf4pro +4) Bug fixes + a) Camera driver's CAM_MIN_INTERVAL fixed if pilot manually triggers extra picture + b) Main loop slowdown after arming fixed (parameter logging was causing delays) + c) Main loop's fast tasks always run (caused twitches in Loiter on heavily loaded CPUs) + d) MAVLink commands received on private channels checked for valid target sysid + e) ModalAI cameras support fixed (ODOMETRY message frame was consumed incorrectly) + f) Param reset after firmware load fixed on these boards + - BeastF7v2 + - CubeYellow-bdshot + - f405-MatekAirspeed + - FlywooF745Nano + - KakuteF4Mini + - KakuteF7-bdshot + - MatekF405-bdshot + - MatekF405-STD + - MatekF405-Wing-bdshot + - MatekF765-SE + - MatekF765-Wing-bdshot + g) Siyi A8 gimbal support fixed + h) Windows builds move to compiling only 64-bit executables +------------------------------------------------------------------ +Rover 4.3.0-beta5 17-Nov-2022 +Changes from 4.3.0-beta4 +1) Autopilot specific enhancements + a) ARKV6X support + b) MatekH743 supports 8 bi-directional dshot channels + c) Pixhawk boards support MS5607 baros + d) SpeedbyBee F405v3 support +2) Balancebot pitch control improvements and pitch limiting +3) DroneCAN Airspeed sensor support including hygrometer (aka water vapour) readings +4) EFI support (electronic fuel injection engines) +5) Harmonic Notch support (Rover only) +6) Pre-arm warning if multiple UARTs with SERIALx_PROTOCOL = RCIN +7) Siyi gimbal support +8) Bug fixes + a) AtomRCF405NAVI bootloader file name fixed + b) BRD_SAFETY_MASK fixed on boards with both FMU safety switch and IOMCU + c) Compass calibration continues even if a single compass's cal fails + d) Gremsy gimbal driver sends autopilot info at lower rate to save bandwidth + e) Invensense 42605 and 42609 IMUs use anti-aliasing filter and notch filter + f) OSD stats screen fix + g) RC input on serial port uses first UART with SERIALx_PROTOCOL = 23 (was using last) + h) RunCam caching fix with enablement and setup on 3-pos switch + i) RTK CAN GPS fix when GPSs conneted to separate CAN ports on autopilot +------------------------------------------------------------------ +Rover 4.3.0-beta4 24-Oct-2022 +Changes from 4.3.0-beta3 +1) Scripting supports implementing AUX functions +2) Bug fixes + a) BMI085 accel scaling fixed + b) Build with gcc 11.3 fixed (developer only) + c) EKF3 alt discrepancy if GPS or baro alt changed soon after startup fixed + d) Harmonic Notch and ESC telem fix when motor outputs are non-contiguous + e) NMEA GPS's KSXT message parsing fixed (affected position accuracy) + f) Scripting random number generator fix +------------------------------------------------------------------ +Rover 4.3.0-beta3 14-Oct-2022 +Changes from 4.3.0-beta2 +1) Pixhawk1-1M, fmuv2, fmuv3 display warning if firmware mismatches board's flash size (1M and 2M) +2) Scripting support for multi-byte i2c reads +3) Bug fixes + a) Airspeed CAN sensor ordering fixed (ordering could change if using multiple airspeed sensors) + b) BRD_SAFETY_MASK fix for enabling outputs when safety is on + c) Defaults.parm file processing fixed when a line has >100 characters and/or no new line (developer only) + d) NMEA serial output precision fixed (was only accurate to 1m, now accurate to 1cm) +------------------------------------------------------------------ +Rover 4.3.0-beta2 04-Oct-2022 +Changes from 4.3.0-beta1 +1) Autopilot specific fixes and enhancements + a) AIRLink autopilot supports UART2 + b) CUAV V6X supports CAN battery monitor by default + c) MatekF405-CAN board uses less memory to fix compass calibration issues + d) Pixhawk1-1M only supports uBlox and NMEA GPSs to save flash space + e) SkystarsH7HD-bdshot (allows Bi-directional DShot) + f) SkystarsH7HD supports VTX power by default +2) EFI support + a) Currawong ECU support (added as Electronic Fuel Injection driver) + b) Scripting support for EFI drivers (allows writing EFI drivers in Lua) + c) SkyPower and HFE CAN EFI drivers (via scripting) +3) Safety features + a) Arming check that SPIN_MIN less than 0.3 and greater than SPIN_ARM + b) Arming option to disable itermittant display of pre-arm warnings (see ARMING_OPTIONS) +4) Minor enhancements + a) Autopilot board names max length increased to 23 characters (was 13) + b) CAN actuators can report PWM equivalent values (eases debugging) + c) Log download speed improved for boards with "block" backends + d) Notch filter slew limit reduces chance of notch freq moving incorrectly + e) SLCAN disabled when vehicle is armed to reduce CPU load +5) Bug fixes + a) DO_JUMP mission command fixed if active command changed before changing to Auto mode + b) EKF3 altitude error fix when using dual GPSs and affinity enabled + c) FFT indexing bug fixed + d) Gimbal mount fix to default mode (see MNTx_DEFLT_MODE parameter) + e) MSP fix to report arm status to DJI FPV goggles + f) Notch fix for non-throttle notch (was being incorrectly disabled) + g) OSD fixes for params, font and resolution + h) RPM reporting from harmonic notch fixed + i) "Sending unknown message (50)" warning removed + j) SBF/GSOF/NOVA GPS auto detction of baud rate fixed + k) VideoTX fixes for buffer overruns and Tramp video transmitter support +------------------------------------------------------------------ +Rover 4.3.0-beta1 14-Sep-2022 +Changes from 4.2.3 +1) Rover specific enhancements + a) Aux switch for SaveWP displays, "Mission Cleared" if vehicle not armed + b) Dock mode using modified precision landing library + c) Manual mode steering scaling with speed can be disabled using MANUAL_OPTIONS parameter + d) S-Curves for Auto, Guided, RTL +2) Rover specific bug fixes + a) Wheel encoder timestamp fix (WRC_xx params may need to be changed) + b) Auto mode stick mixing fixed (see STICK_MIXING parameter) + c) Arming check removed to support mixed Ackerman and skid-stering vehicles +3) New autopilot support + a) AtomRCF405 + b) CubeOrange-SimOnHardWare + c) DevEBoxH7v2 + d) KakuteH7Mini-Nand + e) KakuteH7v2 + f) Mamba F405 Mk4 + g) SkystarsH7HD + h) bi-directional dshot (aka "bdshot") versions for CubeOrange, CubeYellow, KakuteF7, KakuteH7, MatekF405-Wing, Matek F765, PH4-mini, Pixhawk-1M +4) EKF enhancements and fixes + a) EK3_GPS_VACC_MAX threshold to control when GPS altitude is used as alt source + b) EKF ring buffer fix for very slow sensor updates (those that update once every few seconds) + c) EKF3 source set change captured in Replay logs +5) Gimbal enhancements + a) Angle limit params renamed and scaled to degrees (e.g. MNT1_ROLL_MIN, MNT1_PITCH_MIN, etc) + b) BrushlessPWM driver (set MNT1_TYPE = 7) is unstabilized Servo driver + c) Dual mount support (see MNT1_, MNT2 params) + d) Gremsy driver added (set MNT1_TYPE = 6) + e) MAVLink gimbalv2 support including sending GIMBAL_DEVICE_STATUS_UPDATE (replaces MOUNT_STATUS message) + f) "Mount Lock" auxiliary switch supports follow and lock modes in RC targetting (aka earth-frame and body-frame) + g) RC channels to control gimbal set using RCx_OPTION = 212 (Roll), 213 (Pitch) or 214 (Yaw) + h) RC targetting rotation rate in deg/sec (see MNT1_RC_RATE which replaces MNT_JSTICK_SPD) + i) Yaw can be disabled on 3-axis gimbals (set MNTx_YAW_MIN = MNTx_YAW_MAX) +6) Notch filter enhancements + a) Attitude and filter logging at main loop rate + b) Batch sampler logging both pre and post-filter + c) FFT frame averaging + d) In-flight throttle notch parameter learning using averaged FFTs + e) Triple harmonic notch +7) RemoteId and SecureBoot enhancements + a) Remote update of secure boot's public keys (also allows remote unlocking of bootloader) +8) Safety enhancements + a) crash_dump.bin file saved to SD Card on startup (includes details re cause of software failures) + b) Disabling Fence clears any active breaches (e.g. FENCE_TYPE = 0 will clear breaches) + c) "GPS Glitch" message clarified to "GPS Glitch or Compass error" + d) Pre-arm check that configured AHRS is being used (e.g. checks AHRS_EKF_TYPE not changed since boot) + e) Pre-arm check that gimbals are healthy (currently only for Gremsy gimbals, others in future release) + f) Pre-arm check that scripts are running + g) Pre-arm messages are correctly prefixed with "PreArm:" (instead of "Arm:") + h) RC auxiliary switch option for Arm / Emergency Stop +9) Scripting enhancements + a) CAN2 port bindings to allow scripts to communicate on 2nd CAN bus + b) ESC RPM bindings to allow scripts to report engine RPM + c) Gimbal bingings to allow scripts to control gimbal + d) Pre-arm check bindings (allows scripts to check if pre-arm checks have passed) + e) Semicolon (:) and period (.) supported (e.g both Logger:write() and Logger.write will work) +10) Sensor driver enhancements + a) Benewake H30 radar support + b) BMI270 IMU performance improvements + c) IRC Tramp VTX suppor + d) Logging pause-able with auxiliary switch. see RCx_OPTION = 165 (Pause Stream Logging) + e) Proximity sensor support for up to 3 sensors + f) Precision Landing consumes LANDING_TARGET MAVLink message's PositionX,Y,Z fields + g) RichenPower generator maintenance-required messages can be suppressed using GEN_OPTIONS param + h) TeraRanger Neo rangefinder support + i) GPS support to provide ellipsoid altitude instead of AMSL (see GPS_DRV_OPTIONS) + j) W25N01GV 1Gb flash support +11) Bug fixes + a) Accel calibration throws away queued commands from GCS (avoids commands being run long after they were sent) + b) Cygbot proximity sensor fix to support different orientations (see PRXx_ORIENT) + c) Lutan EFI message flood reduced + d) Missions download to GCS corruption avoided by checking serial buffer has space + e) Safety switch disabled if IOMCU is disabled (see BRD_IO_ENABLE=0) + f) Script restart memory leak fixed +12) Developer items + a) Fast loop task list available in real-time using @SYS/tasks.txt + b) Parameter defaults sent to GCS with param FTP and recorded in onboard logs + c) ROS+ArduPilot environment installation script + d) Sim on Hardware allows simulator to run on autopilot (good for exhibitions) + e) Timer info available in real-time using @SYS/timers.txt +------------------------------------------------------------------ +Rover 4.2.3 30-Aug-2022 +Changes from 4.2.3-rc3 +1) OpenDroneId bug fix to consume open-drone-id-system-update message +------------------------------------------------------------------ +Rover 4.2.3-rc3 20-Aug-2022 +Changes from 4.2.3-rc2 +1) OpenDroneId improvements including reporting if operator location is lost +2) Firmware ID and CRC check (disabled by default) +3) Bug Fixes + a) Revert Notch filter ordering on loss of RPM source (see 4.2.3-rc1's 3g below) because fix is incomplete +------------------------------------------------------------------ +Rover 4.2.3-rc2 13-Aug-2022 +Changes from 4.2.3-rc1 +1) BlueRobotics Navigator autopilot filesystem fix +------------------------------------------------------------------ +Rover 4.2.3-rc1 12-Aug-2022 +Changes from 4.2.2 +1) OpenDroneId support (aka RemoteID) +2) New autopilot support + a) CubeOrange+ + b) Foxeer Reaper F745 + c) MFE PixSurveyA1 + d) Pixhawk6C and Pixhawk6X +3) Bug Fixes and minor enhancements + a) Battery monitor health check fixed to check all enabled monitors + b) ICE Lutan EFI update serial flood fixed + c) ICM42xxx IMU filter settings improved and allow for faster sample rates + d) INA2xx batteries may init after startup + e) KakuteH7 OSD parameter menu enabled + f) Lua script support to set desired speed in Auto mode + g) Notch filter ordering bug on loss of RPM source fixed + h) PreArm check of Rangefinder pin conflict and servo outputs + i) SCurve logs debug if internal error occurs + j) WSL2 upload fixed (developer issue only) +------------------------------------------------------------------ +Rover 4.2.2 28-Jun-2022 / 4.2.2-rc1 21-Jun-2022 +Changes from 4.2.1 +1) MambaH743v4 and MambaF405 MK4 autopilot support +2) Second full harmonic notches available (see INS_HNTC2_ parameters) +3) UAVCAN memory usage reduced (see CAN_Dn_UC_POOL parameter to control DroneCAN pool size) +5) Watchdog (caused by hardfault) saves crash dump logs to SD card +6) Bug fixes + a) CRSF protection against watchdog on bad frames + b) CRSF reset in flight handled + c) FFT init watchdog fix when ARMING_REQUIRE=0 + d) OSD flight modes menu includes newer flight modes + e) Param download (via MAVFTP) fixed for params with overlapping names + f) PWM rangefinder bug fix and added SCALING parameter support + g) Replay bug fix when EK3_SRCs changed + h) SERIALx_OPTION fix when "Don't forward mavlink to/from" selected (resolves MAVLink gimbal detection) + i) VL53L1X rangefinder preserves addresses +------------------------------------------------------------------ +Rover 4.2.1 07-Jun-2022 / 4.2.1-rc1 28-May-2022 +Changes from 4.2.0 +1) CAN ESCs bus bandwidth efficiency improvements (see CAN_Dx_UC_ESC_OF parameter) +2) DShot timing improvements to support for ESC variants +3) Luftan EFI measures fuel consumption (see EFI_COEF1, EFI_COEF2) +4) Bug fixes + b) CAN ESCs work on boards with no safety switch (e.g. MatekH743) + b) Inflight Compass calibration checks GSF yaw estimate is good + c) NeoPixel colour fix +------------------------------------------------------------------ +Rover 4.2.0 23-May-2022 / 4.2.0-rc4 14-May-2022 +Changes from 4.2.0-rc3 +1) FlyingMoon F407 and F427 autopilots supported +2) Bug fixes + a) Log file list with over 500 logs fixed + b) RSSI when using IOMCU pin 103 fixed +------------------------------------------------------------------ +Rover 4.2.0-rc3 07-May-2022 +Changes from 4.2.0-rc2 +1) Bug fixes + a) Blended Z axis accel calculation fix when not using first IMU + b) Custom compass orientation for DroneCAN compasses +------------------------------------------------------------------ +Rover 4.2.0-rc2 29-Apr-2022 +Changes from 4.2.0-rc1 +1) Minor Enhancements + a) Button, Relay and RPM GPIO pin conflict pre-arm check improved + b) DShot uses narrower bitwidths for more accurate timing (allows BLHeli BlueJay to work) + c) INS_NOTCH parameters renamed to INS_HNTC2 + d) Matek F765-Wing-bdshot firmware added + e) Matek H743 supports ICM42688 + f) QiotekZealot H743 supports ICM4xxxx + g) Scripting heap size increased to 100k on F7/H7 + h) SPRacingH7 improvements including external flash performance improvements +2) Bug fixes + a) BMI088 IMU FIFO overruns fixed + b) DO_SET_SERVO with SERVOn_FUNCTION=0 fixed, added pre-arm check of servo functions configured on disabled channels + c) Log file descriptor init fixed (issues only seen on Linux autopilots) + d) Log list cope with gaps, performance improvement to reduce impact on EKF and some ESCs + e) Proximity sensor fix when using MAVLink lidars in non-forward orientations + f) RPM sensor fix to avoid "failed to attach pin" spam to GCS + g) STM32 DMA fatal exceptions disabled (caused watch dogs reboots with zero information) +------------------------------------------------------------------ +Rover 4.2.0-rc1 10-Apr-2022 +Changes from 4.2.0-beta3 +1) Minor Enhancements + a) Log and monitor threads stack size increased + b) SPro H7 Extreme QSPI support improved +2) Bug fixes + a) EKF3 accel bias fixed when an IMU is disabled + b) MatekH743 buzzer fixed by reverting to 16 bit timer + c) STM32 H7 flash storage bug fixed that caused re-init on overflow + d) @SYS file logging fixed + e) Timer bug fixed that could cause a watchdog on boards using flash storage + f) UART driver incorrect lock class fixed +------------------------------------------------------------------ +Rover 4.2.0-beta3 30-Mar-2022 +Changes from 4.2.0-beta2 +1) Minor Enhancements + a) BATT_OPTIONS supports sending resting voltage (corrected for internal resistance) to the ground station + b) KakuteH7-bdshot support + c) MatekH743 uses a 32 bit timer to resolve occasional 68ms timing glitch + d) RC input protocol text message sent to GCS (helps pilot awareness during RC handover) +2) Bug fixes + a) Balance bot stands in acro mode even with no GPS + b) Battery remaining percentage fixed when using Sum battery + c) DShot reversal bug with IOMCU based boards (see SERVO_BLH_RVMASK) + d) DShot commands fixed (could cause random motor movements) + e) GPS blending fix that could have resulted in the wrong GPS being used for a short time + f) Param conversion bug (impacted airspeed enable) + g) RC handover between IOMCU RC input and a secondary RC input on a serial port fixed + h) QioTek Zealot H743 SLCAN port and relays fixed +------------------------------------------------------------------ +Rover 4.2.0-beta2 10-Mar-2022 +Changes from 4.2.0-beta1 +1) Follow mode supports FOLLOW_TARGET message (sent by QGC ground station) +2) Bug fixes + a) Arming checks ignore SERVOx_MIN, MAX if setup as GPIO pin + b) BeastH7v2 BMI270 baro support + c) DShot prescaler fix (ESCs were not initialising correctly) + d) EKF3 variance constraint fix used to prevent "ill-conditioning" + e) POWR log message MCU voltage fix (min and max voltage were swapped) + f) Sailboats loiter fix (could get stuck pointing directly into the wind) + g) SPRacingH7 firmware install fix +------------------------------------------------------------------ Rover 4.2.0-rc1 28-Feb-2022 Changes from 4.1.5 1) AHRS/EKF improvements diff --git a/Rover/sailboat.cpp b/Rover/sailboat.cpp index 7a8d1372129..c547a9cb1fa 100644 --- a/Rover/sailboat.cpp +++ b/Rover/sailboat.cpp @@ -141,6 +141,10 @@ void Sailboat::init() // sailboat defaults if (sail_enabled()) { rover.g2.crash_angle.set_default(0); + + // sailboats without motors may travel faster than WP_SPEED so allow waypoint navigation to + // speedup to catch the vehicle instead of asking the vehicle to slow down + rover.g2.wp_nav.enable_overspeed(motor_state != UseMotor::USE_MOTOR_ALWAYS); } if (tack_enabled()) { diff --git a/Rover/system.cpp b/Rover/system.cpp index 4d08c337971..11948e2e667 100644 --- a/Rover/system.cpp +++ b/Rover/system.cpp @@ -29,8 +29,6 @@ void Rover::init_ardupilot() g2.gripper.init(); #endif - g2.fence.init(); - // initialise notify system notify.init(); notify_mode(control_mode); @@ -58,10 +56,6 @@ void Rover::init_ardupilot() log_init(); #endif -#if HAL_AIS_ENABLED - g2.ais.init(); -#endif - // initialise compass AP::compass().set_log_bit(MASK_LOG_COMPASS); AP::compass().init(); @@ -111,6 +105,11 @@ void Rover::init_ardupilot() camera_mount.init(); #endif +#if PRECISION_LANDING == ENABLED + // initialise precision landing + init_precland(); +#endif + /* setup the 'main loop is dead' check. Note that this relies on the RC library being initialised. @@ -226,10 +225,12 @@ bool Rover::set_mode(Mode &new_mode, ModeReason reason) control_mode = &new_mode; +#if AP_FENCE_ENABLED // pilot requested flight mode change during a fence breach indicates pilot is attempting to manually recover // this flight mode change could be automatic (i.e. fence, battery, GPS or GCS failsafe) // but it should be harmless to disable the fence temporarily in these situations as well - g2.fence.manual_recovery_start(); + fence.manual_recovery_start(); +#endif #if CAMERA == ENABLED camera.set_is_auto_mode(control_mode->mode_number() == Mode::Number::AUTO); diff --git a/Rover/version.h b/Rover/version.h index 6ef44e62bd9..bf460fdd5bb 100644 --- a/Rover/version.h +++ b/Rover/version.h @@ -6,14 +6,14 @@ #include "ap_version.h" -#define THISFIRMWARE "ArduRover V4.2.0-dev" +#define THISFIRMWARE "ArduRover V4.3.0-beta14" // the following line is parsed by the autotest scripts -#define FIRMWARE_VERSION 4,2,0,FIRMWARE_VERSION_TYPE_DEV +#define FIRMWARE_VERSION 4,3,0,FIRMWARE_VERSION_TYPE_BETA+14 #define FW_MAJOR 4 -#define FW_MINOR 2 +#define FW_MINOR 3 #define FW_PATCH 0 -#define FW_TYPE FIRMWARE_VERSION_TYPE_DEV +#define FW_TYPE FIRMWARE_VERSION_TYPE_BETA #include diff --git a/Rover/wscript b/Rover/wscript index b564cbbadfa..b77de5b6e40 100644 --- a/Rover/wscript +++ b/Rover/wscript @@ -9,7 +9,6 @@ def build(bld): ap_libraries=bld.ap_common_vehicle_libraries() + [ 'APM_Control', 'AP_Arming', - 'AP_L1_Control', 'AP_Mount', 'AP_Navigation', 'AR_WPNav', @@ -18,7 +17,6 @@ def build(bld): 'AP_AdvancedFailsafe', 'AP_WheelEncoder', 'AP_SmartRTL', - 'AC_Fence', 'AC_AttitudeControl', 'AP_LTM_Telem', 'AP_Devo_Telem', @@ -27,7 +25,8 @@ def build(bld): 'AP_WindVane', 'AR_Motors', 'AP_Torqeedo', - 'AP_AIS', + 'AC_PrecLand', + 'AP_IRLock', ], ) diff --git a/Tools/AP_Bootloader/AP_Bootloader.cpp b/Tools/AP_Bootloader/AP_Bootloader.cpp index 58bde11adc9..bc8ec9ef8e5 100644 --- a/Tools/AP_Bootloader/AP_Bootloader.cpp +++ b/Tools/AP_Bootloader/AP_Bootloader.cpp @@ -35,6 +35,7 @@ #if EXT_FLASH_SIZE_MB #include #endif +#include extern "C" { int main(void); @@ -76,7 +77,7 @@ int main(void) AFIO->MAPR = mapr | AFIO_MAPR_CAN_REMAP_REMAP2 | AFIO_MAPR_SPI3_REMAP; #endif -#ifdef HAL_FLASH_PROTECTION +#if HAL_FLASH_PROTECTION stm32_flash_unprotect_flash(); #endif @@ -103,10 +104,12 @@ int main(void) try_boot = false; timeout = 0; } - if (!can_check_firmware()) { + const auto ok = check_good_firmware(); + if (ok != check_fw_result_t::CHECK_FW_OK) { // bad firmware CRC, don't try and boot timeout = 0; try_boot = false; + led_set(LED_BAD_FW); } #ifndef BOOTLOADER_DEV_LIST else if (timeout != 0) { @@ -123,7 +126,16 @@ int main(void) try_boot = false; timeout = 0; } +#elif AP_CHECK_FIRMWARE_ENABLED + const auto ok = check_good_firmware(); + if (ok != check_fw_result_t::CHECK_FW_OK) { + // bad firmware, don't try and boot + timeout = 0; + try_boot = false; + led_set(LED_BAD_FW); + } #endif + #if defined(HAL_GPIO_PIN_VBUS) && defined(HAL_ENABLE_VBUS_CHECK) #if HAL_USE_SERIAL_USB == TRUE else if (palReadLine(HAL_GPIO_PIN_VBUS) == 0) { @@ -163,7 +175,7 @@ int main(void) while (!ext_flash.init()) { // keep trying until we get it working // there's no future without it - chThdSleep(1000); + chThdSleep(chTimeMS2I(20)); } #endif diff --git a/Tools/AP_Bootloader/app_comms.h b/Tools/AP_Bootloader/app_comms.h index 619f7597c5c..04c0dcb0b98 100644 --- a/Tools/AP_Bootloader/app_comms.h +++ b/Tools/AP_Bootloader/app_comms.h @@ -15,35 +15,3 @@ struct app_bootloader_comms { uint8_t my_node_id; uint8_t path[201]; }; - -#ifndef FW_MAJOR -#define FW_MAJOR 0 -#define FW_MINOR 0 -#endif - -/* - the app_descriptor stored in flash in the main firmware and is used - by the bootloader to confirm that the firmware is not corrupt and is - suitable for this board. The build dependent values in this structure - are filled in by set_app_descriptor() in the waf build - */ -struct app_descriptor { - uint8_t sig[8] = { 0x40, 0xa2, 0xe4, 0xf1, 0x64, 0x68, 0x91, 0x06 }; - // crc1 is the crc32 from firmware start to start of image_crc1 - uint32_t image_crc1 = 0; - // crc2 is the crc32 from the start of version_major to the end of the firmware - uint32_t image_crc2 = 0; - // total size of firmware image in bytes - uint32_t image_size = 0; - uint32_t git_hash = 0; - // software version number - uint8_t version_major = FW_MAJOR; - uint8_t version_minor = FW_MINOR; - // APJ_BOARD_ID (hardware version). This is also used in CAN NodeInfo - // with high byte in HardwareVersion.major and low byte in HardwareVersion.minor - uint16_t board_id = APJ_BOARD_ID; - uint8_t reserved[8] = { 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff }; -}; - -#define APP_DESCRIPTOR_TOTAL_LENGTH 36 -static_assert(sizeof(app_descriptor) == APP_DESCRIPTOR_TOTAL_LENGTH, "app_descriptor incorrect length"); diff --git a/Tools/AP_Bootloader/bl_protocol.cpp b/Tools/AP_Bootloader/bl_protocol.cpp index 807d3500318..12b8cb3ba38 100644 --- a/Tools/AP_Bootloader/bl_protocol.cpp +++ b/Tools/AP_Bootloader/bl_protocol.cpp @@ -53,6 +53,8 @@ #if EXT_FLASH_SIZE_MB #include #endif +#include + // #pragma GCC optimize("O0") @@ -139,7 +141,7 @@ static virtual_timer_t systick_vt; #define TIMER_BL_WAIT 0 #define TIMER_LED 1 -static enum led_state {LED_BLINK, LED_ON, LED_OFF} led_state; +static enum led_state led_state; volatile unsigned timer[NTIMERS]; @@ -174,6 +176,11 @@ static void sys_tick_handler(void *ctx) led_toggle(LED_BOOTLOADER); timer[TIMER_LED] = 50; } + + if ((led_state == LED_BAD_FW) && (timer[TIMER_LED] == 0)) { + led_toggle(LED_BOOTLOADER); + timer[TIMER_LED] = 1000; + } } static void delay(unsigned msec) @@ -181,7 +188,7 @@ static void delay(unsigned msec) chThdSleep(chTimeMS2I(msec)); } -static void +void led_set(enum led_state state) { led_state = state; @@ -199,6 +206,10 @@ led_set(enum led_state state) /* restart the blink state machine ASAP */ timer[TIMER_LED] = 0; break; + + case LED_BAD_FW: + timer[TIMER_LED] = 0; + break; } } @@ -232,6 +243,15 @@ jump_to_app() { const uint32_t *app_base = (const uint32_t *)(APP_START_ADDRESS); +#if AP_CHECK_FIRMWARE_ENABLED + const auto ok = check_good_firmware(); + if (ok != check_fw_result_t::CHECK_FW_OK) { + // bad firmware, don't try and boot + led_set(LED_BAD_FW); + return; + } +#endif + // If we have QSPI chip start it #if EXT_FLASH_SIZE_MB uint8_t* ext_flash_start_addr; @@ -457,7 +477,10 @@ bootloader(unsigned timeout) } /* make the LED blink while we are idle */ - led_set(LED_BLINK); + // ensure we don't override BAD FW LED + if (led_state != LED_BAD_FW) { + led_set(LED_BLINK); + } while (true) { volatile int c; diff --git a/Tools/AP_Bootloader/bl_protocol.h b/Tools/AP_Bootloader/bl_protocol.h index 901f4913e4e..cb56bf6f383 100644 --- a/Tools/AP_Bootloader/bl_protocol.h +++ b/Tools/AP_Bootloader/bl_protocol.h @@ -16,3 +16,6 @@ void bootloader(unsigned timeout); #define MAX_DES_LENGTH 20 #define arraySize(a) (sizeof((a))/sizeof(((a)[0]))) + +enum led_state {LED_BLINK, LED_ON, LED_OFF, LED_BAD_FW}; +void led_set(enum led_state state); diff --git a/Tools/AP_Bootloader/board_types.txt b/Tools/AP_Bootloader/board_types.txt index d2a172b0213..87864143e18 100644 --- a/Tools/AP_Bootloader/board_types.txt +++ b/Tools/AP_Bootloader/board_types.txt @@ -43,11 +43,13 @@ TARGET_HW_ARK_CAN_GPS 81 TARGET_HW_ARK_CAN_RTK_GPS 82 TARGET_HW_FF_RTK_CAN_GPS 85 TARGET_HW_ATL_MANTIS_EDU 97 +TARGET_HW_ARK_FMU_V6X 57 Reserved PX4 [BL] FMU v5X.x 51 Reserved "PX4 [BL] FMU v6.x" 52 Reserved "PX4 [BL] FMU v6X.x" 53 +Reserved "PX4 [BL] FMU v6C.x" 56 Reserved "GUMSTIX [BL] FMU v6" 54 Reserved "ARK CAN FLOW" 80 @@ -132,7 +134,7 @@ AP_HW_KAKUTEF4_MINI 1030 AP_HW_H31_PIXC4_PI 1031 AP_HW_H31_PIXC4_JETSON 1032 AP_HW_CUBEORANGE_JOEY 1033 -AP_HW_SIERRAF9PGPS_PERIPH 1034 +AP_HW_SierraF9P 1034 AP_HW_HolybroGPS 1035 AP_HW_QioTekZealotH743 1036 AP_HW_HEREPRO 1037 @@ -154,13 +156,41 @@ AP_HW_SierraF405 1052 AP_HW_CarbonixL496 1053 AP_HW_MatekF405_TE 1054 AP_HW_SierraF412 1055 +AP_HW_BEASTH7v2 1056 AP_HW_BEASTF7v2 1057 AP_HW_KakuteH7Mini 1058 AP_HW_JHEMCUGSF405A 1059 AP_HW_SPRACINGH7 1060 AP_HW_DEVEBOXH7 1061 +AP_HW_MatekL431 1062 +AP_HW_CUBEORANGEPLUS 1063 +AP_HW_CarbonixF405 1064 +AP_HW_QioTekAdeptF407 1065 +AP_HW_QioTekAdeptF427 1066 +AP_HW_FlyingMoonF407 1067 +AP_HW_FlyingMoonF427 1068 +AP_HW_CUBERED 1069 +AP_HW_CUBERED_IO 1070 +AP_HW_GreenSight_UltraBlue 1071 +AP_HW_GreenSight_microBlue 1072 +AP_HW_MAMBAH743_V4 1073 +AP_HW_REAPERF745_V2 1074 +AP_HW_SKYSTARSH7HD 1075 +AP_HW_PixSurveyA1 1076 +AP_HW_AEROFOX_AIRSPEED 1077 +AP_HW_ATOMRCF405 1078 +AP_HW_CUBEPILOT_CANMOD 1079 +AP_HW_AEROFOX_PMU 1080 +AP_HW_JHEMCUGF16F405 1081 +AP_HW_SPEEDYBEEF4V3 1082 +AP_HW_PixPilot-V6 1083 AP_HW_CUBEORANGE_PERIPH 1400 AP_HW_CUBEBLACK_PERIPH 1401 AP_HW_PIXRACER_PERIPH 1402 AP_HW_SWBOOMBOARD_PERIPH 1403 + +# OpenDroneID enabled boards. Use 10000 + the base board ID +AP_HW_CubeOrange_ODID 10140 +AP_HW_Pixhawk6_ODID 10053 + diff --git a/Tools/AP_Bootloader/can.cpp b/Tools/AP_Bootloader/can.cpp index 76e39747595..b5605cea39c 100644 --- a/Tools/AP_Bootloader/can.cpp +++ b/Tools/AP_Bootloader/can.cpp @@ -38,7 +38,7 @@ #include #include #include - +#include static CanardInstance canard; static uint32_t canard_memory_pool[4096/4]; @@ -84,16 +84,6 @@ static struct { uint32_t sector_ofs; } fw_update; -enum { - FAIL_REASON_NO_APP_SIG = 10, - FAIL_REASON_BAD_LENGTH_APP = 11, - FAIL_REASON_BAD_BOARD_ID = 12, - FAIL_REASON_BAD_CRC = 13, - FAIL_REASON_IN_UPDATE = 14, - FAIL_REASON_WATCHDOG = 15, - FAIL_REASON_BAD_LENGTH_DESCRIPTOR = 16, -}; - /* get cpu unique ID */ @@ -152,7 +142,7 @@ static void handle_get_node_info(CanardInstance* ins, pkt.name.len = strlen(CAN_APP_NODE_NAME); pkt.name.data = (uint8_t *)name; - uint16_t total_size = uavcan_protocol_GetNodeInfoResponse_encode(&pkt, buffer); + uint16_t total_size = uavcan_protocol_GetNodeInfoResponse_encode(&pkt, buffer, true); canardRequestOrRespond(ins, transfer->source_node_id, @@ -238,7 +228,9 @@ static void handle_file_read_response(CanardInstance* ins, CanardRxTransfer* tra if (len < UAVCAN_PROTOCOL_FILE_READ_RESPONSE_DATA_MAX_LENGTH) { fw_update.node_id = 0; flash_write_flush(); - if (can_check_firmware()) { + const auto ok = check_good_firmware(); + node_status.vendor_specific_status_code = uint8_t(ok); + if (ok == check_fw_result_t::CHECK_FW_OK) { jump_to_app(); } } @@ -280,7 +272,7 @@ static void handle_begin_firmware_update(CanardInstance* ins, CanardRxTransfer* uavcan_protocol_file_BeginFirmwareUpdateResponse reply {}; reply.error = UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_ERROR_OK; - uint32_t total_size = uavcan_protocol_file_BeginFirmwareUpdateResponse_encode(&reply, buffer); + uint32_t total_size = uavcan_protocol_file_BeginFirmwareUpdateResponse_encode(&reply, buffer, true); canardRequestOrRespond(ins, transfer->source_node_id, UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_SIGNATURE, @@ -592,7 +584,7 @@ static void send_node_status(void) uint8_t buffer[UAVCAN_PROTOCOL_NODESTATUS_MAX_SIZE]; node_status.uptime_sec = AP_HAL::millis() / 1000U; - uint32_t len = uavcan_protocol_NodeStatus_encode(&node_status, buffer); + uint32_t len = uavcan_protocol_NodeStatus_encode(&node_status, buffer, true); static uint8_t transfer_id; // Note that the transfer ID variable MUST BE STATIC (or heap-allocated)! @@ -624,64 +616,6 @@ void can_set_node_id(uint8_t node_id) initial_node_id = node_id; } -/* - check firmware CRC to see if it matches - */ -bool can_check_firmware(void) -{ - if (fw_update.node_id != 0) { - // we're doing an update, don't boot this fw - node_status.vendor_specific_status_code = FAIL_REASON_IN_UPDATE; - return false; - } - const uint8_t sig[8] = { 0x40, 0xa2, 0xe4, 0xf1, 0x64, 0x68, 0x91, 0x06 }; - const uint8_t *flash = (const uint8_t *)(FLASH_LOAD_ADDRESS + (FLASH_BOOTLOADER_LOAD_KB + APP_START_OFFSET_KB)*1024); - const uint32_t flash_size = (BOARD_FLASH_SIZE - (FLASH_BOOTLOADER_LOAD_KB + APP_START_OFFSET_KB))*1024; - const app_descriptor *ad = (const app_descriptor *)memmem(flash, flash_size-sizeof(app_descriptor), sig, sizeof(sig)); - if (ad == nullptr) { - // no application signature - node_status.vendor_specific_status_code = FAIL_REASON_NO_APP_SIG; - printf("No app sig\n"); - return false; - } - // check length - if (ad->image_size > flash_size) { - node_status.vendor_specific_status_code = FAIL_REASON_BAD_LENGTH_APP; - printf("Bad fw length %u\n", ad->image_size); - return false; - } - - bool id_ok = (ad->board_id == APJ_BOARD_ID); -#ifdef ALT_BOARD_ID - id_ok |= (ad->board_id == ALT_BOARD_ID); -#endif - - if (!id_ok) { - node_status.vendor_specific_status_code = FAIL_REASON_BAD_BOARD_ID; - printf("Bad board_id %u should be %u\n", ad->board_id, APJ_BOARD_ID); - return false; - } - - const uint8_t desc_len = offsetof(app_descriptor, version_major) - offsetof(app_descriptor, image_crc1); - uint32_t len1 = ((const uint8_t *)&ad->image_crc1) - flash; - if ((len1 + desc_len) > ad->image_size) { - node_status.vendor_specific_status_code = FAIL_REASON_BAD_LENGTH_DESCRIPTOR; - printf("Bad fw descriptor length %u\n", ad->image_size); - return false; - } - - uint32_t len2 = ad->image_size - (len1 + desc_len); - uint32_t crc1 = crc32_small(0, flash, len1); - uint32_t crc2 = crc32_small(0, (const uint8_t *)&ad->version_major, len2); - if (crc1 != ad->image_crc1 || crc2 != ad->image_crc2) { - node_status.vendor_specific_status_code = FAIL_REASON_BAD_CRC; - printf("Bad app CRC 0x%08x:0x%08x 0x%08x:0x%08x\n", ad->image_crc1, ad->image_crc2, crc1, crc2); - return false; - } - printf("Good firmware\n"); - return true; -} - // check for a firmware update marker left by app bool can_check_update(void) { @@ -742,6 +676,7 @@ bool can_check_update(void) void can_start() { + node_status.vendor_specific_status_code = uint8_t(check_good_firmware()); node_status.mode = UAVCAN_PROTOCOL_NODESTATUS_MODE_MAINTENANCE; #if HAL_USE_CAN @@ -770,7 +705,7 @@ void can_start() get_random_range(UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MAX_FOLLOWUP_DELAY_MS); if (stm32_was_watchdog_reset()) { - node_status.vendor_specific_status_code = FAIL_REASON_WATCHDOG; + node_status.vendor_specific_status_code = uint8_t(check_fw_result_t::FAIL_REASON_WATCHDOG); } } diff --git a/Tools/AP_Bootloader/can.h b/Tools/AP_Bootloader/can.h index 22a8a24c9f2..96b662a072c 100644 --- a/Tools/AP_Bootloader/can.h +++ b/Tools/AP_Bootloader/can.h @@ -1,5 +1,4 @@ void can_start(); void can_update(); void can_set_node_id(uint8_t node_id); -bool can_check_firmware(void); bool can_check_update(void); diff --git a/Tools/AP_Bootloader/mcu_f4.h b/Tools/AP_Bootloader/mcu_f4.h index e189942568d..6f5ed616675 100644 --- a/Tools/AP_Bootloader/mcu_f4.h +++ b/Tools/AP_Bootloader/mcu_f4.h @@ -29,12 +29,12 @@ const mcu_des_t mcu_descriptions[] = { }; const mcu_rev_t silicon_revs[] = { - {MCU_REV_STM32F4_REV_3, '3', false}, /* Revision 3 */ + {MCU_REV_STM32F4_REV_3, '3'}, /* Revision 3 */ - {MCU_REV_STM32F4_REV_A, 'A', true}, /* Revision A */ - {MCU_REV_STM32F4_REV_Z, 'Z', true}, /* Revision Z */ - {MCU_REV_STM32F4_REV_Y, 'Y', true}, /* Revision Y */ - {MCU_REV_STM32F4_REV_1, '1', true}, /* Revision 1 */ + {MCU_REV_STM32F4_REV_A, 'A'}, /* Revision A */ + {MCU_REV_STM32F4_REV_Z, 'Z'}, /* Revision Z */ + {MCU_REV_STM32F4_REV_Y, 'Y'}, /* Revision Y */ + {MCU_REV_STM32F4_REV_1, '1'}, /* Revision 1 */ }; #endif // STM32F4 diff --git a/Tools/AP_Bootloader/mcu_h7.h b/Tools/AP_Bootloader/mcu_h7.h index 2b955778719..5a0cc2ae315 100644 --- a/Tools/AP_Bootloader/mcu_h7.h +++ b/Tools/AP_Bootloader/mcu_h7.h @@ -13,10 +13,10 @@ mcu_des_t mcu_descriptions[] = { }; const mcu_rev_t silicon_revs[] = { - {0x1001, 'Z', false}, - {0x1003, 'Y', false}, - {0x2001, 'X', false}, - {0x2003, 'V', false}, + {0x1001, 'Z'}, + {0x1003, 'Y'}, + {0x2001, 'X'}, + {0x2003, 'V'}, }; #endif // STM32H7 diff --git a/Tools/AP_Bootloader/support.cpp b/Tools/AP_Bootloader/support.cpp index 2f1b17ca085..1b92efac55f 100644 --- a/Tools/AP_Bootloader/support.cpp +++ b/Tools/AP_Bootloader/support.cpp @@ -274,24 +274,6 @@ uint32_t get_mcu_desc(uint32_t max, uint8_t *revstr) return strp - revstr; } -/* - see if we should limit flash to 1M on devices with older revisions - */ -bool check_limit_flash_1M(void) -{ -#ifdef STM32F427xx - uint32_t idcode = (*(uint32_t *)DBGMCU_BASE); - uint16_t revid = ((idcode & REVID_MASK) >> 16); - - for (int i = 0; i < ARRAY_SIZE(silicon_revs); i++) { - if (silicon_revs[i].revid == revid) { - return silicon_revs[i].limit_flash_size_1M; - } - } -#endif - return false; -} - void led_on(unsigned led) { #ifdef HAL_GPIO_PIN_LED_BOOTLOADER diff --git a/Tools/AP_Bootloader/support.h b/Tools/AP_Bootloader/support.h index 12a7730d110..cc2dd99c53c 100644 --- a/Tools/AP_Bootloader/support.h +++ b/Tools/AP_Bootloader/support.h @@ -36,7 +36,6 @@ bool flash_write_buffer(uint32_t address, const uint32_t *v, uint8_t nwords); uint32_t get_mcu_id(void); uint32_t get_mcu_desc(uint32_t len, uint8_t *buf); -bool check_limit_flash_1M(void); uint32_t board_get_rtc_signature(void); void board_set_rtc_signature(uint32_t sig); @@ -62,5 +61,4 @@ typedef struct mcu_des_t { typedef struct mcu_rev_t { uint16_t revid; char rev; - bool limit_flash_size_1M; } mcu_rev_t; diff --git a/Tools/AP_Bootloader/wscript b/Tools/AP_Bootloader/wscript index 413f383fb3d..73cd64f0119 100644 --- a/Tools/AP_Bootloader/wscript +++ b/Tools/AP_Bootloader/wscript @@ -25,7 +25,8 @@ def build(bld): name= 'AP_Bootloader_libs', ap_vehicle='AP_Bootloader', ap_libraries= flashiface_lib + [ - 'AP_Math' + 'AP_Math', + 'AP_CheckFirmware' ]) bld( diff --git a/Tools/AP_Periph/AP_Periph.cpp b/Tools/AP_Periph/AP_Periph.cpp index 8364ec59fb4..4d228cdab30 100644 --- a/Tools/AP_Periph/AP_Periph.cpp +++ b/Tools/AP_Periph/AP_Periph.cpp @@ -57,15 +57,6 @@ void loop(void) static uint32_t start_ms; -/* - declare constant app_descriptor in flash - */ -#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS -const struct app_descriptor app_descriptor __attribute__((section(".app_descriptor"))); -#else -const struct app_descriptor app_descriptor; -#endif - AP_Periph_FW::AP_Periph_FW() #if HAL_LOGGING_ENABLED : logger(g.log_bitmask) @@ -131,17 +122,16 @@ void AP_Periph_FW::init() logger.Init(log_structure, ARRAY_SIZE(log_structure)); #endif - printf("Booting %08x:%08x %u/%u len=%u 0x%08x\n", - app_descriptor.image_crc1, - app_descriptor.image_crc2, - app_descriptor.version_major, app_descriptor.version_minor, - app_descriptor.image_size, - app_descriptor.git_hash); + check_firmware_print(); if (hal.util->was_watchdog_reset()) { printf("Reboot after watchdog reset\n"); } +#if AP_STATS_ENABLED + node_stats.init(); +#endif + #ifdef HAL_PERIPH_ENABLE_GPS if (gps.get_type(0) != AP_GPS::GPS_Type::GPS_TYPE_NONE && g.gps_port >= 0) { serial_manager.set_protocol_and_baud(g.gps_port, AP_SerialManager::SerialProtocol_GPS, AP_SERIALMANAGER_GPS_BAUD); @@ -181,6 +171,17 @@ void AP_Periph_FW::init() adsb_init(); #endif +#ifdef HAL_PERIPH_ENABLE_EFI + if (efi.enabled() && g.efi_port >= 0) { + auto *uart = hal.serial(g.efi_port); + if (uart != nullptr) { + uart->begin(g.efi_baudrate); + serial_manager.set_protocol_and_baud(g.efi_port, AP_SerialManager::SerialProtocol_EFI, g.efi_baudrate); + efi.init(); + } + } +#endif + #ifdef HAL_PERIPH_ENABLE_AIRSPEED if (airspeed.enabled()){ #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS @@ -331,6 +332,10 @@ void AP_Periph_FW::show_stack_free() void AP_Periph_FW::update() { +#if AP_STATS_ENABLED + node_stats.update(); +#endif + static uint32_t last_led_ms; uint32_t now = AP_HAL::native_millis(); if (now - last_led_ms > 1000) { @@ -384,12 +389,21 @@ void AP_Periph_FW::update() #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && CH_DBG_ENABLE_STACK_CHECK == TRUE static uint32_t last_debug_ms; - if (g.debug==1 && now - last_debug_ms > 5000) { + if ((g.debug&(1< 5000) { last_debug_ms = now; show_stack_free(); } #endif - + + if ((g.debug&(1< 15000) { + // attempt reboot with HOLD after 15s + periph.prepare_reboot(); +#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS + set_fast_reboot((rtc_boot_magic)(RTC_BOOT_HOLD)); + NVIC_SystemReset(); +#endif + } + #ifdef HAL_PERIPH_ENABLE_BATTERY if (now - battery.last_read_ms >= 100) { // update battery at 10Hz diff --git a/Tools/AP_Periph/AP_Periph.h b/Tools/AP_Periph/AP_Periph.h index 77262b1634c..85f356659d8 100644 --- a/Tools/AP_Periph/AP_Periph.h +++ b/Tools/AP_Periph/AP_Periph.h @@ -11,13 +11,16 @@ #include #include #include +#include #include #include #include "../AP_Bootloader/app_comms.h" +#include #include "hwing_esc.h" #include #include #include +#include #if HAL_GCS_ENABLED #include "GCS_MAVLink.h" @@ -49,9 +52,13 @@ void stm32_watchdog_init(); void stm32_watchdog_pat(); #endif /* - app descriptor compatible with MissionPlanner + app descriptor for firmware checking */ -extern const struct app_descriptor app_descriptor; +extern const app_descriptor_t app_descriptor; + +extern "C" { +void can_printf(const char *fmt, ...) FMT_PRINTF(1,2); +} class AP_Periph_FW { public: @@ -85,6 +92,11 @@ class AP_Periph_FW { void load_parameters(); void prepare_reboot(); + bool canfdout() const { return (g.can_fdmode == 1); } + +#ifdef HAL_PERIPH_ENABLE_EFI + void can_efi_update(); +#endif #ifdef HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT void check_for_serial_reboot_cmd(const int8_t serial_index); @@ -98,6 +110,10 @@ class AP_Periph_FW { AP_SerialManager serial_manager; +#if AP_STATS_ENABLED + AP_Stats node_stats; +#endif + #ifdef HAL_PERIPH_ENABLE_GPS AP_GPS gps; #if HAL_NUM_CAN_IFACES >= 2 @@ -164,6 +180,7 @@ class AP_Periph_FW { #ifdef HAL_PERIPH_ENABLE_RANGEFINDER RangeFinder rangefinder; + uint32_t last_sample_ms; #endif #ifdef HAL_PERIPH_ENABLE_PWM_HARDPOINT @@ -184,6 +201,11 @@ class AP_Periph_FW { void hwesc_telem_update(); #endif +#ifdef HAL_PERIPH_ENABLE_EFI + AP_EFI efi; + uint32_t efi_update_ms; +#endif + #ifdef HAL_PERIPH_ENABLE_RC_OUT #if HAL_WITH_ESC_TELEM AP_ESC_Telem esc_telem; @@ -197,7 +219,8 @@ class AP_Periph_FW { void rcout_init(); void rcout_init_1Hz(); void rcout_esc(int16_t *rc, uint8_t num_channels); - void rcout_srv(const uint8_t actuator_id, const float command_value); + void rcout_srv_unitless(const uint8_t actuator_id, const float command_value); + void rcout_srv_PWM(const uint8_t actuator_id, const float command_value); void rcout_update(); void rcout_handle_safety_state(uint8_t safety_state); #endif @@ -247,10 +270,16 @@ class AP_Periph_FW { static AP_Periph_FW *_singleton; + enum { + DEBUG_SHOW_STACK, + DEBUG_AUTOREBOOT + }; + // show stack as DEBUG msgs void show_stack_free(); static bool no_iface_finished_dna; + static constexpr auto can_printf = ::can_printf; }; namespace AP @@ -260,7 +289,4 @@ namespace AP extern AP_Periph_FW periph; -extern "C" { -void can_printf(const char *fmt, ...) FMT_PRINTF(1,2); -} diff --git a/Tools/AP_Periph/Parameters.cpp b/Tools/AP_Periph/Parameters.cpp index 09943209406..394a77a6fed 100644 --- a/Tools/AP_Periph/Parameters.cpp +++ b/Tools/AP_Periph/Parameters.cpp @@ -39,6 +39,14 @@ extern const AP_HAL::HAL &hal; #define AP_PERIPH_BARO_ENABLE_DEFAULT 1 #endif +#ifndef AP_PERIPH_EFI_PORT_DEFAULT +#define AP_PERIPH_EFI_PORT_DEFAULT 3 +#endif + +#ifndef HAL_PERIPH_EFI_BAUDRATE_DEFAULT +#define HAL_PERIPH_EFI_BAUDRATE_DEFAULT 115200 +#endif + #ifndef HAL_DEFAULT_MAV_SYSTEM_ID #define MAV_SYSTEM_ID 3 #else @@ -84,7 +92,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { // @Param: CAN_PROTOCOL // @DisplayName: Enable use of specific protocol to be used on this port // @Description: Enabling this option starts selected protocol that will use this virtual driver. At least one CAN port must be UAVCAN or else CAN1 gets set to UAVCAN - // @Values: 0:Disabled,1:UAVCAN,3:ToshibaCAN,4:PiccoloCAN,5:CANTester,6:EFI_NWPMU,7:USD1,8:KDECAN + // @Values: 0:Disabled,1:UAVCAN,4:PiccoloCAN,5:CANTester,6:EFI_NWPMU,7:USD1,8:KDECAN // @User: Advanced // @RebootRequired: True GARRAY(can_protocol, 0, "CAN_PROTOCOL", AP_CANManager::Driver_Type_UAVCAN), @@ -100,7 +108,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { // @Param: CAN2_PROTOCOL // @DisplayName: Enable use of specific protocol to be used on this port // @Description: Enabling this option starts selected protocol that will use this virtual driver. At least one CAN port must be UAVCAN or else CAN1 gets set to UAVCAN - // @Values: 0:Disabled,1:UAVCAN,3:ToshibaCAN,4:PiccoloCAN,5:CANTester,6:EFI_NWPMU,7:USD1,8:KDECAN + // @Values: 0:Disabled,1:UAVCAN,4:PiccoloCAN,5:CANTester,6:EFI_NWPMU,7:USD1,8:KDECAN // @User: Advanced // @RebootRequired: True GARRAY(can_protocol, 1, "CAN2_PROTOCOL", AP_CANManager::Driver_Type_UAVCAN), @@ -118,12 +126,40 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { // @Param: CAN3_PROTOCOL // @DisplayName: Enable use of specific protocol to be used on this port // @Description: Enabling this option starts selected protocol that will use this virtual driver. At least one CAN port must be UAVCAN or else CAN1 gets set to UAVCAN - // @Values: 0:Disabled,1:UAVCAN,3:ToshibaCAN,4:PiccoloCAN,5:CANTester,6:EFI_NWPMU,7:USD1,8:KDECAN + // @Values: 0:Disabled,1:UAVCAN,4:PiccoloCAN,5:CANTester,6:EFI_NWPMU,7:USD1,8:KDECAN // @User: Advanced // @RebootRequired: True GARRAY(can_protocol, 2, "CAN3_PROTOCOL", AP_CANManager::Driver_Type_UAVCAN), #endif +#if HAL_CANFD_SUPPORTED + // @Param: CAN_FDMODE + // @DisplayName: Enable CANFD mode + // @Description: Enabling this option sets the CAN bus to be in CANFD mode with BRS. + // @Values: 0:Disabled,1:Enabled + // @User: Advanced + // @RebootRequired: True + GSCALAR(can_fdmode, "CAN_FDMODE", 0), + + // @Param: CAN_FDBAUDRATE + // @DisplayName: Set up bitrate for data section on CAN1 + // @Description: This sets the bitrate for the data section of CAN1. + // @Values: 1:1M, 2:2M, 4:4M, 5:5M, 8:8M + // @User: Advanced + // @RebootRequired: True + GARRAY(can_fdbaudrate, 0, "CAN_FDBAUDRATE", HAL_CANFD_SUPPORTED), + +#if HAL_NUM_CAN_IFACES >= 2 + // @Param: CAN2_FDBAUDRATE + // @DisplayName: Set up bitrate for data section on CAN2 + // @Description: This sets the bitrate for the data section of CAN2. + // @Values: 1:1M, 2:2M, 4:4M, 5:5M, 8:8M + // @User: Advanced + // @RebootRequired: True + GARRAY(can_fdbaudrate, 1, "CAN2_FDBAUDRATE", HAL_CANFD_SUPPORTED), +#endif +#endif + #if !defined(HAL_NO_FLASH_SUPPORT) && !defined(HAL_NO_ROMFS_SUPPORT) // @Param: FLASH_BOOTLOADER // @DisplayName: Trigger bootloader update @@ -136,10 +172,11 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { // @Param: DEBUG // @DisplayName: Debug // @Description: Debug - // @Values: 0:Disabled, 1:Show free stack space + // @Bitmask: 0:Disabled, 1:Show free stack space, 2:Auto Reboot after 15sec // @User: Advanced GSCALAR(debug, "DEBUG", 0), + // @Param: BRD_SERIAL_NUM // @DisplayName: Serial number of device // @Description: Non-zero positive values will be shown on the CAN App Name string @@ -173,7 +210,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { // @RebootRequired: True GSCALAR(gps_port, "GPS_PORT", HAL_PERIPH_GPS_PORT_DEFAULT), -#if HAL_NUM_CAN_IFACES >= 2 +#if GPS_MOVING_BASELINE // @Param: MB_CAN_PORT // @DisplayName: Moving Baseline CAN Port option // @Description: Autoselect dedicated CAN port on which moving baseline data will be transmitted. @@ -247,6 +284,15 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { // @RebootRequired: True GSCALAR(rangefinder_port, "RNGFND_PORT", AP_PERIPH_RANGEFINDER_PORT_DEFAULT), + // @Param: RNGFND_MAX_RATE + // @DisplayName: Rangefinder max rate + // @Description: This is the maximum rate we send rangefinder data in Hz. Zero means no limit + // @Units: Hz + // @Range: 0 200 + // @Increment: 1 + // @User: Advanced + GSCALAR(rangefinder_max_rate, "RNGFND_MAX_RATE", 50), + // Rangefinder driver // @Group: RNGFND // @Path: ../libraries/AP_RangeFinder/AP_RangeFinder.cpp @@ -373,6 +419,38 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { // @Path: ../libraries/AP_Scripting/AP_Scripting.cpp GOBJECT(scripting, "SCR_", AP_Scripting), #endif + +#if AP_STATS_ENABLED + // @Group: Node + // @Path: ../libraries/AP_Stats/AP_Stats.cpp + GOBJECT(node_stats, "STAT", AP_Stats), +#endif + +#ifdef HAL_PERIPH_ENABLE_EFI + // @Param: EFI_BAUDRATE + // @DisplayName: EFI serial baudrate + // @Description: EFI serial baudrate. + // @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,230:230400,256:256000,460:460800,500:500000,921:921600,1500:1500000 + // @Increment: 1 + // @User: Standard + // @RebootRequired: True + GSCALAR(efi_baudrate, "EFI_BAUDRATE", HAL_PERIPH_EFI_BAUDRATE_DEFAULT), + + // @Param: EFI_PORT + // @DisplayName: EFI Serial Port + // @Description: This is the serial port number where SERIALx_PROTOCOL will be set to EFI. + // @Range: 0 10 + // @Increment: 1 + // @User: Advanced + // @RebootRequired: True + GSCALAR(efi_port, "EFI_PORT", AP_PERIPH_EFI_PORT_DEFAULT), + + // EFI driver + // @Group: EFI + // @Path: ../libraries/AP_EFI/AP_EFI.cpp + GOBJECT(efi, "EFI", AP_EFI), +#endif + AP_VAREND }; @@ -394,6 +472,7 @@ void AP_Periph_FW::load_parameters(void) // save the current format version g.format_version.set_and_save(Parameters::k_format_version); } + g.format_version.set_default(Parameters::k_format_version); // Load all auto-loaded EEPROM variables AP_Param::load_all(); diff --git a/Tools/AP_Periph/Parameters.h b/Tools/AP_Periph/Parameters.h index 14a2714bfce..092b4106ad6 100644 --- a/Tools/AP_Periph/Parameters.h +++ b/Tools/AP_Periph/Parameters.h @@ -51,6 +51,14 @@ class Parameters { k_param_gps_mb_only_can_port, k_param_scripting, k_param_esc_telem_port, + k_param_can_fdmode, + k_param_can_fdbaudrate0, + k_param_can_fdbaudrate1, + k_param_node_stats, + k_param_rangefinder_max_rate, + k_param_efi, + k_param_efi_port, + k_param_efi_baudrate, }; AP_Int16 format_version; @@ -77,6 +85,7 @@ class Parameters { #ifdef HAL_PERIPH_ENABLE_RANGEFINDER AP_Int32 rangefinder_baud; AP_Int8 rangefinder_port; + AP_Int16 rangefinder_max_rate; #endif #ifdef HAL_PERIPH_ENABLE_ADSB @@ -95,7 +104,7 @@ class Parameters { #ifdef HAL_PERIPH_ENABLE_GPS AP_Int8 gps_port; -#if HAL_NUM_CAN_IFACES >= 2 +#if GPS_MOVING_BASELINE AP_Int8 gps_mb_only_can_port; #endif #endif @@ -123,6 +132,17 @@ class Parameters { AP_Int16 sysid_this_mav; #endif +#ifdef HAL_PERIPH_ENABLE_EFI + AP_Int32 efi_baudrate; + AP_Int8 efi_port; +#endif + +#if HAL_CANFD_SUPPORTED + AP_Int8 can_fdmode; + AP_Int8 can_fdbaudrate[HAL_NUM_CAN_IFACES]; +#else + static constexpr uint8_t can_fdmode = 0; +#endif Parameters() {} }; diff --git a/Tools/AP_Periph/ReleaseNotes.txt b/Tools/AP_Periph/ReleaseNotes.txt new file mode 100644 index 00000000000..d539abd43ff --- /dev/null +++ b/Tools/AP_Periph/ReleaseNotes.txt @@ -0,0 +1,104 @@ +Release 1.4.0 4th Sep 2022 +-------------------------- + +This is a major release with a significant number of changes: + + - use new AP_CheckFirmware system + - fixed passing of WGS84 height from GPS + - support CANFD on STM32H7 + - fixes for moving baseline yaw with DroneCAN GPS + - fixed GPS dropout issues on F4 and L4 GPS + - added EFI peripheral support + - fixed non-contiguous mask for ESC telem + +Release 1.3.1 15th Apr 2022 +--------------------------- + +This is a minor release with a single bug fix: + + - fixed intermittent loss of GPS packets on F4 and L4 GPS nodes which caused loss of GPS lock on the flight controller + +Release 1.3.0 18th Mar 2022 +--------------------------- + +This is a major release with several significant bug fixes and +improvements: + + - added new peripherals: BirdCANdy, MatekL431, CubeOrange-periph, + G4-ESC, HerePro, Hitec-Airspeed, HolybroG4GPS, HolybroGPS, + Sierra-F405, Sierra-F421, Sierra-F9P, Sierra-L431, + f103-QiotekPeriph, f405-MatekGPS, f405-MatekAirspeed, mRo-M10095, + ARK_GPS, HitecMosaic, MatekH743-periph, Pixracer-periph + + - support dshot for CAN ESC outputs + + - support a wider range of notify options + + - numerous small bug fixes + + - support lua scripting in peripherals + + - switched to DroneCAN compiler and libraries + + - support logging in peripherals + + - support dual CAN bus + + - support BLHeli monitoring of ESC telemetry + + - support mavlink in peripherals + + - support moving baseline yaw dual-GPS on dual-CAN GPS + + - support MPPT battery driver + + - fixed MSP GPS yaw + +Note that the next major release will add CANFD support. + +Release 1.2.0 6th Jan 2020 +-------------------------- + +This is a major release with several significant bug fixes and +improvements: + + - support for battery monitor nodes + + - support for testing in SITL + + - improvements in error reporting to the flight controller + + - fixes to stack sizes + + - MSP output support + + - support for BGR NCP5623 LEDs + + - switched to common CAN stack with main ArduPilot vehicle code + + - added several new board types + + +Release 1.1.0 14th May 2020 +--------------------------- + +This is a major release with several significant bug fixes: + + - fixed initial GPS timestamp which could cause ArduPilot to get bad + time sync + + - fixed airspeed pressure wrap + + - fixed rangefinder to send the RNGFND1_ADDR as sensor_id + + - added distinctive LED blink pattern when waiting for UAVCAN node ID + allocation + + - added HWESC build targets for HobbyWing ESC telemetry + + - fixed RM3100 compass scaling bug + +Release 1.0.0 9th November 2019 +------------------------------- + +Initial stable release diff --git a/Tools/AP_Periph/can.cpp b/Tools/AP_Periph/can.cpp index bdd7c5a87d8..d7759bda543 100644 --- a/Tools/AP_Periph/can.cpp +++ b/Tools/AP_Periph/can.cpp @@ -31,7 +31,6 @@ #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS #include -#include "../AP_Bootloader/app_comms.h" #include #include #include @@ -39,6 +38,7 @@ #include #endif +#define IFACE_ALL ((1U<<(HAL_NUM_CAN_IFACES+1U))-1U) #include "i2c.h" #include @@ -47,11 +47,21 @@ #include #endif + +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +extern const HAL_SITL &hal; +#else extern const AP_HAL::HAL &hal; +#endif + extern AP_Periph_FW periph; #ifndef HAL_CAN_POOL_SIZE -#define HAL_CAN_POOL_SIZE 4000 +#if HAL_CANFD_SUPPORTED + #define HAL_CAN_POOL_SIZE 16000 +#else + #define HAL_CAN_POOL_SIZE 4000 +#endif #endif #ifndef HAL_PERIPH_LOOP_DELAY_US @@ -59,7 +69,7 @@ extern AP_Periph_FW periph; #if defined(STM32H7) #define HAL_PERIPH_LOOP_DELAY_US 64 #else -#define HAL_PERIPH_LOOP_DELAY_US 512 +#define HAL_PERIPH_LOOP_DELAY_US 1024 #endif #endif @@ -73,6 +83,15 @@ extern AP_Periph_FW periph; static struct instance_t { uint8_t index; + +#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS + ChibiOS::CANIface* iface; +#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL + HALSITL::CANIface* iface; +#endif +} instances[HAL_NUM_CAN_IFACES]; + +static struct dronecan_protocol_t { CanardInstance canard; uint32_t canard_memory_pool[HAL_CAN_POOL_SIZE/sizeof(uint32_t)]; struct tid_map { @@ -87,13 +106,8 @@ static struct instance_t { uint32_t send_next_node_id_allocation_request_at_ms; ///< When the next node ID allocation request should be sent uint8_t node_id_allocation_unique_id_offset; ///< Depends on the stage of the next request uint8_t tx_fail_count; - -#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS - ChibiOS::CANIface* iface; -#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL - HALSITL::CANIface* iface; -#endif -} instances[HAL_NUM_CAN_IFACES]; + uint8_t dna_interface = 1; +} dronecan; #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && defined(HAL_GPIO_PIN_TERMCAN1) static ioline_t can_term_lines[] = { @@ -151,20 +165,6 @@ HALSITL::CANIface* AP_Periph_FW::can_iface_periph[HAL_NUM_CAN_IFACES]; */ static uavcan_protocol_NodeStatus node_status; -/** - * Get interface id given canard object pointer - */ -static instance_t* get_canard_iface_instance(CanardInstance* ins) -{ - for (auto &can_ins : instances) { - if (ins == &can_ins.canard) { - return &can_ins; - } - } - // something is not right if we got here - return nullptr; -} - /** * Returns a pseudo random integer in a given range */ @@ -219,7 +219,7 @@ static void handle_get_node_info(CanardInstance* ins, } pkt.name.len = strnlen((char*)pkt.name.data, sizeof(pkt.name.data)); - uint16_t total_size = uavcan_protocol_GetNodeInfoResponse_encode(&pkt, buffer); + uint16_t total_size = uavcan_protocol_GetNodeInfoResponse_encode(&pkt, buffer, !periph.canfdout()); const int16_t resp_res = canardRequestOrRespond(ins, transfer->source_node_id, @@ -229,7 +229,14 @@ static void handle_get_node_info(CanardInstance* ins, transfer->priority, CanardResponse, &buffer[0], - total_size); + total_size +#if CANARD_MULTI_IFACE + , IFACE_ALL +#endif +#if HAL_CANFD_SUPPORTED + , periph.canfdout() +#endif +); if (resp_res <= 0) { printf("Could not respond to GetNodeInfo: %d\n", resp_res); } @@ -321,7 +328,7 @@ static void handle_param_getset(CanardInstance* ins, CanardRxTransfer* transfer) } uint8_t buffer[UAVCAN_PROTOCOL_PARAM_GETSET_RESPONSE_MAX_SIZE] {}; - uint16_t total_size = uavcan_protocol_param_GetSetResponse_encode(&pkt, buffer); + uint16_t total_size = uavcan_protocol_param_GetSetResponse_encode(&pkt, buffer, !periph.canfdout()); canardRequestOrRespond(ins, transfer->source_node_id, @@ -331,7 +338,14 @@ static void handle_param_getset(CanardInstance* ins, CanardRxTransfer* transfer) transfer->priority, CanardResponse, &buffer[0], - total_size); + total_size +#if CANARD_MULTI_IFACE + , IFACE_ALL +#endif +#if HAL_CANFD_SUPPORTED + ,periph.canfdout() +#endif +); } @@ -374,7 +388,7 @@ static void handle_param_executeopcode(CanardInstance* ins, CanardRxTransfer* tr pkt.ok = true; uint8_t buffer[UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_RESPONSE_MAX_SIZE] {}; - uint16_t total_size = uavcan_protocol_param_ExecuteOpcodeResponse_encode(&pkt, buffer); + uint16_t total_size = uavcan_protocol_param_ExecuteOpcodeResponse_encode(&pkt, buffer, !periph.canfdout()); canardRequestOrRespond(ins, transfer->source_node_id, @@ -384,7 +398,14 @@ static void handle_param_executeopcode(CanardInstance* ins, CanardRxTransfer* tr transfer->priority, CanardResponse, &buffer[0], - total_size); + total_size +#if CANARD_MULTI_IFACE + , IFACE_ALL +#endif +#if HAL_CANFD_SUPPORTED + ,periph.canfdout() +#endif +); } static void canard_broadcast(uint64_t data_type_signature, @@ -423,7 +444,7 @@ static void handle_begin_firmware_update(CanardInstance* ins, CanardRxTransfer* uavcan_protocol_file_BeginFirmwareUpdateResponse reply {}; reply.error = UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_ERROR_OK; - uint32_t total_size = uavcan_protocol_file_BeginFirmwareUpdateResponse_encode(&reply, buffer); + uint32_t total_size = uavcan_protocol_file_BeginFirmwareUpdateResponse_encode(&reply, buffer, !periph.canfdout()); canardRequestOrRespond(ins, transfer->source_node_id, UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_SIGNATURE, @@ -432,7 +453,14 @@ static void handle_begin_firmware_update(CanardInstance* ins, CanardRxTransfer* transfer->priority, CanardResponse, &buffer[0], - total_size); + total_size +#if CANARD_MULTI_IFACE + ,IFACE_ALL +#endif +#if HAL_CANFD_SUPPORTED + ,periph.canfdout() +#endif +); uint8_t count = 50; while (count--) { processTx(); @@ -451,19 +479,15 @@ static void handle_begin_firmware_update(CanardInstance* ins, CanardRxTransfer* static void handle_allocation_response(CanardInstance* ins, CanardRxTransfer* transfer) { - instance_t *can_ins = get_canard_iface_instance(ins); - if (can_ins == nullptr) { - return; - } // Rule C - updating the randomized time interval - can_ins->send_next_node_id_allocation_request_at_ms = + dronecan.send_next_node_id_allocation_request_at_ms = AP_HAL::native_millis() + UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_REQUEST_PERIOD_MS + get_random_range(UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MAX_FOLLOWUP_DELAY_MS); if (transfer->source_node_id == CANARD_BROADCAST_NODE_ID) { printf("Allocation request from another allocatee\n"); - can_ins->node_id_allocation_unique_id_offset = 0; + dronecan.node_id_allocation_unique_id_offset = 0; return; } @@ -479,28 +503,28 @@ static void handle_allocation_response(CanardInstance* ins, CanardRxTransfer* tr // Matching the received UID against the local one if (memcmp(msg.unique_id.data, my_unique_id, msg.unique_id.len) != 0) { printf("Mismatching allocation response\n"); - can_ins->node_id_allocation_unique_id_offset = 0; + dronecan.node_id_allocation_unique_id_offset = 0; return; // No match, return } if (msg.unique_id.len < sizeof(msg.unique_id.data)) { // The allocator has confirmed part of unique ID, switching to the next stage and updating the timeout. - can_ins->node_id_allocation_unique_id_offset = msg.unique_id.len; - can_ins->send_next_node_id_allocation_request_at_ms -= UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_REQUEST_PERIOD_MS; + dronecan.node_id_allocation_unique_id_offset = msg.unique_id.len; + dronecan.send_next_node_id_allocation_request_at_ms -= UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_REQUEST_PERIOD_MS; printf("Matching allocation response: %d\n", msg.unique_id.len); } else { // Allocation complete - copying the allocated node ID from the message canardSetLocalNodeID(ins, msg.node_id); - printf("IF%d Node ID allocated: %d\n", can_ins->index, msg.node_id); + printf("IF%d Node ID allocated: %d\n", dronecan.dna_interface, msg.node_id); #if defined(HAL_PERIPH_ENABLE_GPS) && (HAL_NUM_CAN_IFACES >= 2) && GPS_MOVING_BASELINE if (periph.g.gps_mb_only_can_port) { // we need to assign the unallocated port to be used for Moving Baseline only - periph.gps_mb_can_port = (can_ins->index+1)%HAL_NUM_CAN_IFACES; - if (canardGetLocalNodeID(&instances[periph.gps_mb_can_port].canard) == CANARD_BROADCAST_NODE_ID) { + periph.gps_mb_can_port = (dronecan.dna_interface+1)%HAL_NUM_CAN_IFACES; + if (canardGetLocalNodeID(&dronecan.canard) == CANARD_BROADCAST_NODE_ID) { // copy node id from the primary iface - canardSetLocalNodeID(&instances[periph.gps_mb_can_port].canard, msg.node_id); + canardSetLocalNodeID(&dronecan.canard, msg.node_id); #ifdef HAL_GPIO_PIN_TERMCAN1 // also terminate the line as we don't have any other device on this port palWriteLine(can_term_lines[periph.gps_mb_can_port], 1); @@ -711,9 +735,9 @@ static void handle_lightscommand(CanardInstance* ins, CanardRxTransfer* transfer uavcan_equipment_indication_SingleLightCommand &cmd = req.commands.data[i]; // to get the right color proportions we scale the green so that is uses the // same number of bits as red and blue - uint8_t red = cmd.color.red<<3; - uint8_t green = (cmd.color.green>>1)<<3; - uint8_t blue = cmd.color.blue<<3; + uint8_t red = cmd.color.red<<3U; + uint8_t green = (cmd.color.green>>1U)<<3U; + uint8_t blue = cmd.color.blue<<3U; #ifdef HAL_PERIPH_ENABLE_NOTIFY const int8_t brightness = periph.notify.get_rgb_led_brightness_percent(); #elif defined(AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY) @@ -772,11 +796,14 @@ static void handle_act_command(CanardInstance* ins, CanardRxTransfer* transfer) } for (uint8_t i=0; i < data_count; i++) { - if (data[i].command_type != UAVCAN_EQUIPMENT_ACTUATOR_COMMAND_COMMAND_TYPE_UNITLESS) { - // this is the only type we support - continue; + switch (data[i].command_type) { + case UAVCAN_EQUIPMENT_ACTUATOR_COMMAND_COMMAND_TYPE_UNITLESS: + periph.rcout_srv_unitless(data[i].actuator_id, data[i].command_value); + break; + case UAVCAN_EQUIPMENT_ACTUATOR_COMMAND_COMMAND_TYPE_PWM: + periph.rcout_srv_PWM(data[i].actuator_id, data[i].command_value); + break; } - periph.rcout_srv(data[i].actuator_id, data[i].command_value); } } #endif // HAL_PERIPH_ENABLE_RC_OUT @@ -858,7 +885,7 @@ static void can_safety_button_update(void) pkt.press_time = counter; uint8_t buffer[ARDUPILOT_INDICATION_BUTTON_MAX_SIZE] {}; - uint16_t total_size = ardupilot_indication_Button_encode(&pkt, buffer); + uint16_t total_size = ardupilot_indication_Button_encode(&pkt, buffer, !periph.canfdout()); canard_broadcast(ARDUPILOT_INDICATION_BUTTON_SIGNATURE, ARDUPILOT_INDICATION_BUTTON_ID, @@ -1068,32 +1095,30 @@ static bool shouldAcceptTransfer(const CanardInstance* ins, static void cleanup_stale_transactions(uint64_t ×tamp_usec) { - for (auto &ins : instances) { - canardCleanupStaleTransfers(&ins.canard, timestamp_usec); - } + canardCleanupStaleTransfers(&dronecan.canard, timestamp_usec); } #define MAKE_TRANSFER_DESCRIPTOR(data_type_id, transfer_type, src_node_id, dst_node_id) \ (((uint32_t)(data_type_id)) | (((uint32_t)(transfer_type)) << 16U) | \ (((uint32_t)(src_node_id)) << 18U) | (((uint32_t)(dst_node_id)) << 25U)) -static uint8_t* get_tid_ptr(instance_t *ins, uint32_t transfer_desc) +static uint8_t* get_tid_ptr(uint32_t transfer_desc) { // check head - if (!ins->tid_map_head) { - ins->tid_map_head = (instance_t::tid_map*)calloc(1, sizeof(instance_t::tid_map)); - if (ins->tid_map_head == nullptr) { + if (!dronecan.tid_map_head) { + dronecan.tid_map_head = (dronecan_protocol_t::tid_map*)calloc(1, sizeof(dronecan_protocol_t::tid_map)); + if (dronecan.tid_map_head == nullptr) { return nullptr; } - ins->tid_map_head->transfer_desc = transfer_desc; - ins->tid_map_head->next = nullptr; - return &ins->tid_map_head->tid; - } else if (ins->tid_map_head->transfer_desc == transfer_desc) { - return &ins->tid_map_head->tid; + dronecan.tid_map_head->transfer_desc = transfer_desc; + dronecan.tid_map_head->next = nullptr; + return &dronecan.tid_map_head->tid; + } else if (dronecan.tid_map_head->transfer_desc == transfer_desc) { + return &dronecan.tid_map_head->tid; } // search through the list for an existing entry - instance_t::tid_map *tid_map_ptr = ins->tid_map_head; + dronecan_protocol_t::tid_map *tid_map_ptr = dronecan.tid_map_head; while(tid_map_ptr->next) { tid_map_ptr = tid_map_ptr->next; if (tid_map_ptr->transfer_desc == transfer_desc) { @@ -1102,7 +1127,7 @@ static uint8_t* get_tid_ptr(instance_t *ins, uint32_t transfer_desc) } // create a new entry, if not found - tid_map_ptr->next = (instance_t::tid_map*)calloc(1, sizeof(instance_t::tid_map)); + tid_map_ptr->next = (dronecan_protocol_t::tid_map*)calloc(1, sizeof(dronecan_protocol_t::tid_map)); if (tid_map_ptr->next == nullptr) { return nullptr; } @@ -1117,68 +1142,83 @@ static void canard_broadcast(uint64_t data_type_signature, const void* payload, uint16_t payload_len) { - for (auto &ins : instances) { - if (canardGetLocalNodeID(&ins.canard) == CANARD_BROADCAST_NODE_ID) { - continue; - } -#if defined(HAL_PERIPH_ENABLE_GPS) && HAL_NUM_CAN_IFACES >= 2 - if (ins.index != periph.gps_mb_can_port) -#endif - { - uint8_t *tid_ptr = get_tid_ptr(&ins, MAKE_TRANSFER_DESCRIPTOR(data_type_signature, data_type_id, 0, CANARD_BROADCAST_NODE_ID)); - if (tid_ptr == nullptr) { - return; - } + if (canardGetLocalNodeID(&dronecan.canard) == CANARD_BROADCAST_NODE_ID) { + return; + } + + uint8_t *tid_ptr = get_tid_ptr(MAKE_TRANSFER_DESCRIPTOR(data_type_signature, data_type_id, 0, CANARD_BROADCAST_NODE_ID)); + if (tid_ptr == nullptr) { + return; + } #if DEBUG_PKTS - const int16_t res = + const int16_t res = #endif - canardBroadcast(&ins.canard, - data_type_signature, - data_type_id, - tid_ptr, - priority, - payload, - payload_len); -#if DEBUG_PKTS - if (res < 0) { - printf("Tx error %d, IF%d %lx\n", res, ins.index); - } + canardBroadcast(&dronecan.canard, + data_type_signature, + data_type_id, + tid_ptr, + priority, + payload, + payload_len +#if CANARD_MULTI_IFACE + , IFACE_ALL // send over all ifaces #endif - } +#if HAL_CANFD_SUPPORTED + , periph.canfdout() +#endif + ); + +#if DEBUG_PKTS + if (res < 0) { + can_printf("Tx error %d\n", res); } +#endif } static void processTx(void) { - for (auto &ins : instances) { - if (ins.iface == NULL) { - continue; - } -#if HAL_NUM_CAN_IFACES >= 2 - if (periph.can_protocol_cached[ins.index] != AP_CANManager::Driver_Type_UAVCAN) { - continue; + for (const CanardCANFrame* txf = NULL; (txf = canardPeekTxQueue(&dronecan.canard)) != NULL;) { + AP_HAL::CANFrame txmsg {}; + txmsg.dlc = AP_HAL::CANFrame::dataLengthToDlc(txf->data_len); + memcpy(txmsg.data, txf->data, txf->data_len); + txmsg.id = (txf->id | AP_HAL::CANFrame::FlagEFF); +#if HAL_CANFD_SUPPORTED + txmsg.canfd = txf->canfd; +#endif + // push message with 1s timeout + bool sent = true; + const uint64_t deadline = AP_HAL::native_micros64() + 1000000; + // try sending to all interfaces + for (auto &ins : instances) { + if (ins.iface == NULL) { + continue; + } + #if CANARD_MULTI_IFACE + if (!(txf->iface_mask & (1U<= 2 + if (periph.can_protocol_cached[ins.index] != AP_CANManager::Driver_Type_UAVCAN) { + continue; + } + #endif + if (ins.iface->send(txmsg, deadline, 0) <= 0) { + sent = false; + } } -#endif - for (const CanardCANFrame* txf = NULL; (txf = canardPeekTxQueue(&ins.canard)) != NULL;) { - AP_HAL::CANFrame txmsg {}; - txmsg.dlc = txf->data_len; - memcpy(txmsg.data, txf->data, 8); - txmsg.id = (txf->id | AP_HAL::CANFrame::FlagEFF); - // push message with 1s timeout - const uint64_t deadline = AP_HAL::native_micros64() + 1000000; - if (ins.iface->send(txmsg, deadline, 0) > 0) { - canardPopTxQueue(&ins.canard); - ins.tx_fail_count = 0; + if (sent) { + canardPopTxQueue(&dronecan.canard); + dronecan.tx_fail_count = 0; + } else { + // just exit and try again later. If we fail 8 times in a row + // then start discarding to prevent the pool filling up + if (dronecan.tx_fail_count < 8) { + dronecan.tx_fail_count++; } else { - // just exit and try again later. If we fail 8 times in a row - // then start discarding to prevent the pool filling up - if (ins.tx_fail_count < 8) { - ins.tx_fail_count++; - } else { - canardPopTxQueue(&ins.canard); - } - break; + canardPopTxQueue(&dronecan.canard); } + break; } } } @@ -1207,14 +1247,22 @@ static void processRx(void) //palToggleLine(HAL_GPIO_PIN_LED); uint64_t timestamp; AP_HAL::CANIface::CanIOFlags flags; - ins.iface->receive(rxmsg, timestamp, flags); - memcpy(rx_frame.data, rxmsg.data, 8); - rx_frame.data_len = rxmsg.dlc; + if (ins.iface->receive(rxmsg, timestamp, flags) <= 0) { + break; + } + rx_frame.data_len = AP_HAL::CANFrame::dlcToDataLength(rxmsg.dlc); + memcpy(rx_frame.data, rxmsg.data, rx_frame.data_len); +#if HAL_CANFD_SUPPORTED + rx_frame.canfd = rxmsg.canfd; +#endif rx_frame.id = rxmsg.id; +#if CANARD_MULTI_IFACE + rx_frame.iface_id = ins.index; +#endif #if DEBUG_PKTS const int16_t res = #endif - canardHandleRxFrame(&ins.canard, &rx_frame, timestamp); + canardHandleRxFrame(&dronecan.canard, &rx_frame, timestamp); #if DEBUG_PKTS if (res < 0 && res != -CANARD_ERROR_RX_NOT_WANTED && @@ -1231,9 +1279,9 @@ static void processRx(void) } } -static uint16_t pool_peak_percent(instance_t &ins) +static uint16_t pool_peak_percent() { - const CanardPoolAllocatorStatistics stats = canardGetPoolAllocatorStatistics(&ins.canard); + const CanardPoolAllocatorStatistics stats = canardGetPoolAllocatorStatistics(&dronecan.canard); const uint16_t peak_percent = (uint16_t)(100U * stats.peak_usage_blocks / stats.capacity_blocks); return peak_percent; } @@ -1245,7 +1293,7 @@ static void node_status_send(void) node_status.vendor_specific_status_code = hal.util->available_memory(); - uint32_t len = uavcan_protocol_NodeStatus_encode(&node_status, buffer); + uint32_t len = uavcan_protocol_NodeStatus_encode(&node_status, buffer, !periph.canfdout()); canard_broadcast(UAVCAN_PROTOCOL_NODESTATUS_SIGNATURE, UAVCAN_PROTOCOL_NODESTATUS_ID, @@ -1273,10 +1321,9 @@ static void process1HzTasks(uint64_t timestamp_usec) * The recommended way to establish the minimal size of the memory pool is to stress-test the application and * record the worst case memory usage. */ - for (auto &ins : instances) { - if (pool_peak_percent(ins) > 70) { - printf("WARNING: ENLARGE MEMORY POOL on Iface %d\n", ins.index); - } + + if (pool_peak_percent() > 70) { + printf("WARNING: ENLARGE MEMORY POOL\n"); } } @@ -1314,6 +1361,11 @@ static void process1HzTasks(uint64_t timestamp_usec) case AP_HAL::Util::FlashBootloader::NO_CHANGE: can_printf("Bootloader unchanged\n"); break; +#if AP_SIGNED_FIRMWARE + case AP_HAL::Util::FlashBootloader::NOT_SIGNED: + can_printf("Bootloader not signed\n"); + break; +#endif default: can_printf("Flash bootloader FAILED\n"); break; @@ -1321,7 +1373,14 @@ static void process1HzTasks(uint64_t timestamp_usec) } #endif - node_status.mode = UAVCAN_PROTOCOL_NODESTATUS_MODE_OPERATIONAL; +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL + if (hal.run_in_maintenance_mode()) { + node_status.mode = UAVCAN_PROTOCOL_NODESTATUS_MODE_MAINTENANCE; + } else +#endif + { + node_status.mode = UAVCAN_PROTOCOL_NODESTATUS_MODE_OPERATIONAL; + } #if 0 // test code for watchdog reset @@ -1343,22 +1402,22 @@ static void process1HzTasks(uint64_t timestamp_usec) wait for dynamic allocation of node ID */ bool AP_Periph_FW::no_iface_finished_dna = true; -static bool can_do_dna(instance_t &ins) +static bool can_do_dna() { - if (canardGetLocalNodeID(&ins.canard) != CANARD_BROADCAST_NODE_ID) { + if (canardGetLocalNodeID(&dronecan.canard) != CANARD_BROADCAST_NODE_ID) { AP_Periph_FW::no_iface_finished_dna = false; return true; } const uint32_t now = AP_HAL::native_millis(); - uint8_t node_id_allocation_transfer_id = 0; + static uint8_t node_id_allocation_transfer_id = 0; if (AP_Periph_FW::no_iface_finished_dna) { - printf("Waiting for dynamic node ID allocation on IF%d... (pool %u)\n", ins.index, pool_peak_percent(ins)); + printf("Waiting for dynamic node ID allocation %x... (pool %u)\n", IFACE_ALL, pool_peak_percent()); } - ins.send_next_node_id_allocation_request_at_ms = + dronecan.send_next_node_id_allocation_request_at_ms = now + UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_REQUEST_PERIOD_MS + get_random_range(UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MAX_FOLLOWUP_DELAY_MS); @@ -1367,36 +1426,46 @@ static bool can_do_dna(instance_t &ins) uint8_t allocation_request[CANARD_CAN_FRAME_MAX_DATA_LEN - 1]; allocation_request[0] = (uint8_t)(PreferredNodeID << 1U); - if (ins.node_id_allocation_unique_id_offset == 0) { + if (dronecan.node_id_allocation_unique_id_offset == 0) { allocation_request[0] |= 1; // First part of unique ID + // set interface to try + dronecan.dna_interface++; + dronecan.dna_interface %= HAL_NUM_CAN_IFACES; } uint8_t my_unique_id[sizeof(uavcan_protocol_dynamic_node_id_Allocation::unique_id.data)]; readUniqueID(my_unique_id); static const uint8_t MaxLenOfUniqueIDInRequest = 6; - uint8_t uid_size = (uint8_t)(sizeof(uavcan_protocol_dynamic_node_id_Allocation::unique_id.data) - ins.node_id_allocation_unique_id_offset); + uint8_t uid_size = (uint8_t)(sizeof(uavcan_protocol_dynamic_node_id_Allocation::unique_id.data) - dronecan.node_id_allocation_unique_id_offset); if (uid_size > MaxLenOfUniqueIDInRequest) { uid_size = MaxLenOfUniqueIDInRequest; } - memmove(&allocation_request[1], &my_unique_id[ins.node_id_allocation_unique_id_offset], uid_size); + memmove(&allocation_request[1], &my_unique_id[dronecan.node_id_allocation_unique_id_offset], uid_size); // Broadcasting the request - const int16_t bcast_res = canardBroadcast(&ins.canard, + const int16_t bcast_res = canardBroadcast(&dronecan.canard, UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_SIGNATURE, UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID, &node_id_allocation_transfer_id, CANARD_TRANSFER_PRIORITY_LOW, &allocation_request[0], - (uint16_t) (uid_size + 1)); + (uint16_t) (uid_size + 1) +#if CANARD_MULTI_IFACE + ,(1U << dronecan.dna_interface) +#endif +#if HAL_CANFD_SUPPORTED + ,false +#endif + ); if (bcast_res < 0) { - printf("Could not broadcast ID allocation req; error %d, IF%d\n", bcast_res, ins.index); + printf("Could not broadcast ID allocation req; error %d\n", bcast_res); } // Preparing for timeout; if response is received, this value will be updated from the callback. - ins.node_id_allocation_unique_id_offset = 0; + dronecan.node_id_allocation_unique_id_offset = 0; return false; } @@ -1440,14 +1509,18 @@ void AP_Periph_FW::can_start() CANSensor::set_periph(i, can_protocol_cached[i], can_iface_periph[i]); #endif if (can_iface_periph[i] != nullptr) { +#if HAL_CANFD_SUPPORTED + can_iface_periph[i]->init(g.can_baudrate[i], g.can_fdbaudrate[i]*1000000U, AP_HAL::CANIface::NormalMode); +#else can_iface_periph[i]->init(g.can_baudrate[i], AP_HAL::CANIface::NormalMode); +#endif } - canardInit(&instances[i].canard, (uint8_t *)instances[i].canard_memory_pool, sizeof(instances[i].canard_memory_pool), - onTransferReceived, shouldAcceptTransfer, NULL); + } + canardInit(&dronecan.canard, (uint8_t *)dronecan.canard_memory_pool, sizeof(dronecan.canard_memory_pool), + onTransferReceived, shouldAcceptTransfer, NULL); - if (PreferredNodeID != CANARD_BROADCAST_NODE_ID) { - canardSetLocalNodeID(&instances[i].canard, PreferredNodeID); - } + if (PreferredNodeID != CANARD_BROADCAST_NODE_ID) { + canardSetLocalNodeID(&dronecan.canard, PreferredNodeID); } } @@ -1495,7 +1568,7 @@ void AP_Periph_FW::pwm_hardpoint_update() cmd.command = value; uint8_t buffer[UAVCAN_EQUIPMENT_HARDPOINT_COMMAND_MAX_SIZE] {}; - uint16_t total_size = uavcan_equipment_hardpoint_Command_encode(&cmd, buffer); + uint16_t total_size = uavcan_equipment_hardpoint_Command_encode(&cmd, buffer, !periph.canfdout()); canard_broadcast(UAVCAN_EQUIPMENT_HARDPOINT_COMMAND_SIGNATURE, UAVCAN_EQUIPMENT_HARDPOINT_COMMAND_ID, CANARD_TRANSFER_PRIORITY_LOW, @@ -1523,7 +1596,7 @@ void AP_Periph_FW::hwesc_telem_update() pkt.error_count = t.error_count; uint8_t buffer[UAVCAN_EQUIPMENT_ESC_STATUS_MAX_SIZE] {}; - uint16_t total_size = uavcan_equipment_esc_Status_encode(&pkt, buffer); + uint16_t total_size = uavcan_equipment_esc_Status_encode(&pkt, buffer, !periph.canfdout()); canard_broadcast(UAVCAN_EQUIPMENT_ESC_STATUS_SIGNATURE, UAVCAN_EQUIPMENT_ESC_STATUS_ID, CANARD_TRANSFER_PRIORITY_LOW, @@ -1539,12 +1612,10 @@ void AP_Periph_FW::hwesc_telem_update() */ void AP_Periph_FW::esc_telem_update() { - const uint8_t mask = esc_telem.get_active_esc_mask(); - const uint8_t num_escs = esc_telem.get_num_active_escs(); - for (uint8_t i=0; i ins.send_next_node_id_allocation_request_at_ms) { - can_do_dna(ins); - } + if (AP_HAL::millis() > dronecan.send_next_node_id_allocation_request_at_ms) { + can_do_dna(); } static uint32_t last_1Hz_ms; @@ -1622,33 +1691,42 @@ void AP_Periph_FW::can_update() last_1Hz_ms = now; process1HzTasks(AP_HAL::native_micros64()); } - can_mag_update(); - can_gps_update(); - can_battery_update(); - can_baro_update(); - can_airspeed_update(); - can_rangefinder_update(); -#if defined(HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY) || defined (HAL_PERIPH_ENABLE_NOTIFY) - can_buzzer_update(); -#endif -#ifdef HAL_GPIO_PIN_SAFE_LED - can_safety_LED_update(); -#endif -#ifdef HAL_GPIO_PIN_SAFE_BUTTON - can_safety_button_update(); -#endif -#ifdef HAL_PERIPH_ENABLE_PWM_HARDPOINT - pwm_hardpoint_update(); -#endif -#ifdef HAL_PERIPH_ENABLE_HWESC - hwesc_telem_update(); -#endif -#ifdef HAL_PERIPH_ENABLE_MSP - msp_sensor_update(); -#endif -#ifdef HAL_PERIPH_ENABLE_RC_OUT - rcout_update(); + +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL + if (!hal.run_in_maintenance_mode()) #endif + { + can_mag_update(); + can_gps_update(); + can_battery_update(); + can_baro_update(); + can_airspeed_update(); + can_rangefinder_update(); + #if defined(HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY) || defined (HAL_PERIPH_ENABLE_NOTIFY) + can_buzzer_update(); + #endif + #ifdef HAL_GPIO_PIN_SAFE_LED + can_safety_LED_update(); + #endif + #ifdef HAL_GPIO_PIN_SAFE_BUTTON + can_safety_button_update(); + #endif + #ifdef HAL_PERIPH_ENABLE_PWM_HARDPOINT + pwm_hardpoint_update(); + #endif + #ifdef HAL_PERIPH_ENABLE_HWESC + hwesc_telem_update(); + #endif + #ifdef HAL_PERIPH_ENABLE_MSP + msp_sensor_update(); + #endif + #ifdef HAL_PERIPH_ENABLE_RC_OUT + rcout_update(); + #endif + #ifdef HAL_PERIPH_ENABLE_EFI + can_efi_update(); + #endif + } const uint32_t now_us = AP_HAL::micros(); while ((AP_HAL::micros() - now_us) < 1000) { hal.scheduler->delay_microseconds(HAL_PERIPH_LOOP_DELAY_US); @@ -1695,7 +1773,7 @@ void AP_Periph_FW::can_mag_update(void) } uint8_t buffer[UAVCAN_EQUIPMENT_AHRS_MAGNETICFIELDSTRENGTH_MAX_SIZE] {}; - uint16_t total_size = uavcan_equipment_ahrs_MagneticFieldStrength_encode(&pkt, buffer); + uint16_t total_size = uavcan_equipment_ahrs_MagneticFieldStrength_encode(&pkt, buffer, !periph.canfdout()); canard_broadcast(UAVCAN_EQUIPMENT_AHRS_MAGNETICFIELDSTRENGTH_SIGNATURE, UAVCAN_EQUIPMENT_AHRS_MAGNETICFIELDSTRENGTH_ID, @@ -1756,7 +1834,7 @@ void AP_Periph_FW::can_battery_update(void) #endif //defined(HAL_PERIPH_BATTERY_SKIP_NAME) uint8_t buffer[UAVCAN_EQUIPMENT_POWER_BATTERYINFO_MAX_SIZE] {}; - const uint16_t total_size = uavcan_equipment_power_BatteryInfo_encode(&pkt, buffer); + const uint16_t total_size = uavcan_equipment_power_BatteryInfo_encode(&pkt, buffer, !periph.canfdout()); canard_broadcast(UAVCAN_EQUIPMENT_POWER_BATTERYINFO_SIGNATURE, UAVCAN_EQUIPMENT_POWER_BATTERYINFO_ID, @@ -1767,6 +1845,21 @@ void AP_Periph_FW::can_battery_update(void) #endif } +#ifdef HAL_PERIPH_ENABLE_GPS +/* + convert large values to NaN for float16 + */ +static void check_float16_range(float *v, uint8_t len) +{ + for (uint8_t i=0; i= f16max) { + v[i] = nanf(""); + } + } +} +#endif + /* update CAN GPS */ @@ -1801,8 +1894,12 @@ void AP_Periph_FW::can_gps_update(void) } pkt.longitude_deg_1e8 = uint64_t(loc.lng) * 10ULL; pkt.latitude_deg_1e8 = uint64_t(loc.lat) * 10ULL; - pkt.height_ellipsoid_mm = loc.alt * 10; pkt.height_msl_mm = loc.alt * 10; + pkt.height_ellipsoid_mm = loc.alt * 10; + float undulation; + if (gps.get_undulation(undulation)) { + pkt.height_ellipsoid_mm -= undulation*1000; + } for (uint8_t i=0; i<3; i++) { // the canard dsdl compiler doesn't understand float16 pkt.ned_velocity[i] = vel[i]; @@ -1835,6 +1932,7 @@ void AP_Periph_FW::can_gps_update(void) if (gps.horizontal_accuracy(hacc)) { pkt.position_covariance.data[0] = pkt.position_covariance.data[4] = sq(hacc); } + check_float16_range(pkt.position_covariance.data, pkt.position_covariance.len); pkt.velocity_covariance.len = 9; @@ -1843,9 +1941,10 @@ void AP_Periph_FW::can_gps_update(void) float vc3 = sq(sacc); pkt.velocity_covariance.data[0] = pkt.velocity_covariance.data[4] = pkt.velocity_covariance.data[8] = vc3; } + check_float16_range(pkt.velocity_covariance.data, pkt.velocity_covariance.len); uint8_t buffer[UAVCAN_EQUIPMENT_GNSS_FIX_MAX_SIZE] {}; - uint16_t total_size = uavcan_equipment_gnss_Fix_encode(&pkt, buffer); + uint16_t total_size = uavcan_equipment_gnss_Fix_encode(&pkt, buffer, !periph.canfdout()); canard_broadcast(UAVCAN_EQUIPMENT_GNSS_FIX_SIGNATURE, UAVCAN_EQUIPMENT_GNSS_FIX_ID, @@ -1878,6 +1977,10 @@ void AP_Periph_FW::can_gps_update(void) pkt.latitude_deg_1e8 = uint64_t(loc.lat) * 10ULL; pkt.height_ellipsoid_mm = loc.alt * 10; pkt.height_msl_mm = loc.alt * 10; + float undulation; + if (gps.get_undulation(undulation)) { + pkt.height_ellipsoid_mm -= undulation*1000; + } for (uint8_t i=0; i<3; i++) { pkt.ned_velocity[i] = vel[i]; } @@ -1934,8 +2037,10 @@ void AP_Periph_FW::can_gps_update(void) pkt.covariance.data[3] = pkt.covariance.data[4] = pkt.covariance.data[5] = vc3; } + check_float16_range(pkt.covariance.data, pkt.covariance.len); + uint8_t buffer[UAVCAN_EQUIPMENT_GNSS_FIX2_MAX_SIZE] {}; - uint16_t total_size = uavcan_equipment_gnss_Fix2_encode(&pkt, buffer); + uint16_t total_size = uavcan_equipment_gnss_Fix2_encode(&pkt, buffer, !periph.canfdout()); canard_broadcast(UAVCAN_EQUIPMENT_GNSS_FIX2_SIGNATURE, UAVCAN_EQUIPMENT_GNSS_FIX2_ID, @@ -1953,7 +2058,7 @@ void AP_Periph_FW::can_gps_update(void) aux.vdop = gps.get_vdop() * 0.01; uint8_t buffer[UAVCAN_EQUIPMENT_GNSS_AUXILIARY_MAX_SIZE] {}; - uint16_t total_size = uavcan_equipment_gnss_Auxiliary_encode(&aux, buffer); + uint16_t total_size = uavcan_equipment_gnss_Auxiliary_encode(&aux, buffer, !periph.canfdout()); canard_broadcast(UAVCAN_EQUIPMENT_GNSS_AUXILIARY_SIGNATURE, UAVCAN_EQUIPMENT_GNSS_AUXILIARY_ID, CANARD_TRANSFER_PRIORITY_LOW, @@ -1980,7 +2085,7 @@ void AP_Periph_FW::can_gps_update(void) } uint8_t buffer[ARDUPILOT_GNSS_STATUS_MAX_SIZE] {}; - const uint16_t total_size = ardupilot_gnss_Status_encode(&status, buffer); + const uint16_t total_size = ardupilot_gnss_Status_encode(&status, buffer, !periph.canfdout()); canard_broadcast(ARDUPILOT_GNSS_STATUS_SIGNATURE, ARDUPILOT_GNSS_STATUS_ID, CANARD_TRANSFER_PRIORITY_LOW, @@ -2010,18 +2115,25 @@ void AP_Periph_FW::send_moving_baseline_msg() mbldata.data.len = len; memcpy(mbldata.data.data, data, len); uint8_t buffer[ARDUPILOT_GNSS_MOVINGBASELINEDATA_MAX_SIZE] {}; - const uint16_t total_size = ardupilot_gnss_MovingBaselineData_encode(&mbldata, buffer); + const uint16_t total_size = ardupilot_gnss_MovingBaselineData_encode(&mbldata, buffer, !periph.canfdout()); #if HAL_NUM_CAN_IFACES >= 2 if (gps_mb_can_port != -1 && (gps_mb_can_port < HAL_NUM_CAN_IFACES)) { - uint8_t *tid_ptr = get_tid_ptr(&instances[gps_mb_can_port], MAKE_TRANSFER_DESCRIPTOR(ARDUPILOT_GNSS_MOVINGBASELINEDATA_SIGNATURE, ARDUPILOT_GNSS_MOVINGBASELINEDATA_ID, 0, CANARD_BROADCAST_NODE_ID)); - canardBroadcast(&instances[gps_mb_can_port].canard, + uint8_t *tid_ptr = get_tid_ptr(MAKE_TRANSFER_DESCRIPTOR(ARDUPILOT_GNSS_MOVINGBASELINEDATA_SIGNATURE, ARDUPILOT_GNSS_MOVINGBASELINEDATA_ID, 0, CANARD_BROADCAST_NODE_ID)); + canardBroadcast(&dronecan.canard, ARDUPILOT_GNSS_MOVINGBASELINEDATA_SIGNATURE, ARDUPILOT_GNSS_MOVINGBASELINEDATA_ID, tid_ptr, CANARD_TRANSFER_PRIORITY_LOW, &buffer[0], - total_size); + total_size +#if CANARD_MULTI_IFACE + ,(1U< 0 && + now - last_update_ms < 1000/g.rangefinder_max_rate) { + // limit to max rate return; } last_update_ms = now; @@ -2212,6 +2325,12 @@ void AP_Periph_FW::can_rangefinder_update(void) // don't send any data return; } + const uint32_t sample_ms = rangefinder.last_reading_ms(ROTATION_NONE); + if (last_sample_ms == sample_ms) { + return; + } + last_sample_ms = sample_ms; + uint16_t dist_cm = rangefinder.distance_cm_orient(ROTATION_NONE); uavcan_equipment_range_sensor_Measurement pkt {}; pkt.sensor_id = rangefinder.get_address(0); @@ -2247,7 +2366,7 @@ void AP_Periph_FW::can_rangefinder_update(void) pkt.range = dist_cm * 0.01; uint8_t buffer[UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_MAX_SIZE] {}; - uint16_t total_size = uavcan_equipment_range_sensor_Measurement_encode(&pkt, buffer); + uint16_t total_size = uavcan_equipment_range_sensor_Measurement_encode(&pkt, buffer, !periph.canfdout()); canard_broadcast(UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_SIGNATURE, UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_ID, @@ -2308,7 +2427,7 @@ void AP_Periph_FW::can_send_ADSB(struct __mavlink_adsb_vehicle_t &msg) pkt.baro_valid = (msg.flags & 0x0100) != 0; uint8_t buffer[ARDUPILOT_EQUIPMENT_TRAFFICMONITOR_TRAFFICREPORT_MAX_SIZE] {}; - uint16_t total_size = ardupilot_equipment_trafficmonitor_TrafficReport_encode(&pkt, buffer); + uint16_t total_size = ardupilot_equipment_trafficmonitor_TrafficReport_encode(&pkt, buffer, !periph.canfdout()); canard_broadcast(ARDUPILOT_EQUIPMENT_TRAFFICMONITOR_TRAFFICREPORT_SIGNATURE, ARDUPILOT_EQUIPMENT_TRAFFICMONITOR_TRAFFICREPORT_ID, @@ -2318,6 +2437,193 @@ void AP_Periph_FW::can_send_ADSB(struct __mavlink_adsb_vehicle_t &msg) } #endif // HAL_PERIPH_ENABLE_ADSB + +#ifdef HAL_PERIPH_ENABLE_EFI +/* + update CAN EFI + */ +void AP_Periph_FW::can_efi_update(void) +{ + if (!efi.enabled()) { + return; + } + efi.update(); + const uint32_t update_ms = efi.get_last_update_ms(); + if (!efi.is_healthy() || efi_update_ms == update_ms) { + return; + } + efi_update_ms = update_ms; + EFI_State state; + efi.get_state(state); + + { + /* + send status packet + */ + uavcan_equipment_ice_reciprocating_Status pkt {}; + + // state maps 1:1 from Engine_State + pkt.state = uint8_t(state.engine_state); + + switch (state.crankshaft_sensor_status) { + case Crankshaft_Sensor_Status::NOT_SUPPORTED: + break; + case Crankshaft_Sensor_Status::OK: + pkt.flags |= UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_CRANKSHAFT_SENSOR_ERROR_SUPPORTED; + break; + case Crankshaft_Sensor_Status::ERROR: + pkt.flags |= + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_CRANKSHAFT_SENSOR_ERROR_SUPPORTED | + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_CRANKSHAFT_SENSOR_ERROR; + break; + } + + switch (state.temperature_status) { + case Temperature_Status::NOT_SUPPORTED: + break; + case Temperature_Status::OK: + pkt.flags |= UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_TEMPERATURE_SUPPORTED; + break; + case Temperature_Status::BELOW_NOMINAL: + pkt.flags |= + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_TEMPERATURE_SUPPORTED | + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_TEMPERATURE_BELOW_NOMINAL; + break; + case Temperature_Status::ABOVE_NOMINAL: + pkt.flags |= + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_TEMPERATURE_SUPPORTED | + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_TEMPERATURE_ABOVE_NOMINAL; + break; + case Temperature_Status::OVERHEATING: + pkt.flags |= + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_TEMPERATURE_SUPPORTED | + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_TEMPERATURE_OVERHEATING; + break; + case Temperature_Status::EGT_ABOVE_NOMINAL: + pkt.flags |= + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_TEMPERATURE_SUPPORTED | + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_TEMPERATURE_EGT_ABOVE_NOMINAL; + break; + } + + switch (state.fuel_pressure_status) { + case Fuel_Pressure_Status::NOT_SUPPORTED: + break; + case Fuel_Pressure_Status::OK: + pkt.flags |= UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_FUEL_PRESSURE_SUPPORTED; + break; + case Fuel_Pressure_Status::BELOW_NOMINAL: + pkt.flags |= + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_FUEL_PRESSURE_SUPPORTED | + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_FUEL_PRESSURE_BELOW_NOMINAL; + break; + case Fuel_Pressure_Status::ABOVE_NOMINAL: + pkt.flags |= + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_FUEL_PRESSURE_SUPPORTED | + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_FUEL_PRESSURE_ABOVE_NOMINAL; + break; + } + + switch (state.oil_pressure_status) { + case Oil_Pressure_Status::NOT_SUPPORTED: + break; + case Oil_Pressure_Status::OK: + pkt.flags |= UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_OIL_PRESSURE_SUPPORTED; + break; + case Oil_Pressure_Status::BELOW_NOMINAL: + pkt.flags |= + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_OIL_PRESSURE_SUPPORTED | + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_OIL_PRESSURE_BELOW_NOMINAL; + break; + case Oil_Pressure_Status::ABOVE_NOMINAL: + pkt.flags |= + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_OIL_PRESSURE_SUPPORTED | + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_OIL_PRESSURE_ABOVE_NOMINAL; + break; + } + + switch (state.detonation_status) { + case Detonation_Status::NOT_SUPPORTED: + break; + case Detonation_Status::NOT_OBSERVED: + pkt.flags |= + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_DETONATION_SUPPORTED; + break; + case Detonation_Status::OBSERVED: + pkt.flags |= + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_DETONATION_SUPPORTED | + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_DETONATION_OBSERVED; + break; + } + + switch (state.misfire_status) { + case Misfire_Status::NOT_SUPPORTED: + break; + case Misfire_Status::NOT_OBSERVED: + pkt.flags |= + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_MISFIRE_SUPPORTED; + break; + case Misfire_Status::OBSERVED: + pkt.flags |= + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_MISFIRE_SUPPORTED | + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_MISFIRE_OBSERVED; + break; + } + + switch (state.debris_status) { + case Debris_Status::NOT_SUPPORTED: + break; + case Debris_Status::NOT_DETECTED: + pkt.flags |= + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_DEBRIS_SUPPORTED; + break; + case Debris_Status::DETECTED: + pkt.flags |= + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_DEBRIS_SUPPORTED | + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_DEBRIS_DETECTED; + break; + } + + pkt.engine_load_percent = state.engine_load_percent; + pkt.engine_speed_rpm = state.engine_speed_rpm; + pkt.spark_dwell_time_ms = state.spark_dwell_time_ms; + pkt.atmospheric_pressure_kpa = state.atmospheric_pressure_kpa; + pkt.intake_manifold_pressure_kpa = state.intake_manifold_pressure_kpa; + pkt.intake_manifold_temperature = state.intake_manifold_temperature; + pkt.coolant_temperature = state.coolant_temperature; + pkt.oil_pressure = state.oil_pressure; + pkt.oil_temperature = state.oil_temperature; + pkt.fuel_pressure = state.fuel_pressure; + pkt.fuel_consumption_rate_cm3pm = state.fuel_consumption_rate_cm3pm; + pkt.estimated_consumed_fuel_volume_cm3 = state.estimated_consumed_fuel_volume_cm3; + pkt.throttle_position_percent = state.throttle_position_percent; + pkt.ecu_index = state.ecu_index; + pkt.spark_plug_usage = uint8_t(state.spark_plug_usage); + + // assume single set of cylinder status + pkt.cylinder_status.len = 1; + auto &c = pkt.cylinder_status.data[0]; + const auto &state_c = state.cylinder_status[0]; + c.ignition_timing_deg = state_c.ignition_timing_deg; + c.injection_time_ms = state_c.injection_time_ms; + c.cylinder_head_temperature = state_c.cylinder_head_temperature; + c.exhaust_gas_temperature = state_c.exhaust_gas_temperature; + c.lambda_coefficient = state_c.lambda_coefficient; + + uint8_t buffer[UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_MAX_SIZE] {}; + const uint16_t total_size = uavcan_equipment_ice_reciprocating_Status_encode(&pkt, buffer, !periph.canfdout()); + + canard_broadcast(UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_SIGNATURE, + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_ID, + CANARD_TRANSFER_PRIORITY_LOW, + &buffer[0], + total_size); + } + +} +#endif // HAL_PERIPH_ENABLE_EFI + + // printf to CAN LogMessage for debugging void can_printf(const char *fmt, ...) { @@ -2329,7 +2635,7 @@ void can_printf(const char *fmt, ...) va_end(ap); pkt.text.len = MIN(n, sizeof(pkt.text.data)); - uint32_t len = uavcan_protocol_debug_LogMessage_encode(&pkt, buffer); + uint32_t len = uavcan_protocol_debug_LogMessage_encode(&pkt, buffer, !periph.canfdout()); canard_broadcast(UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_SIGNATURE, UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_ID, diff --git a/Tools/AP_Periph/rc_out.cpp b/Tools/AP_Periph/rc_out.cpp index d50cee638be..2b105184a63 100644 --- a/Tools/AP_Periph/rc_out.cpp +++ b/Tools/AP_Periph/rc_out.cpp @@ -21,7 +21,7 @@ // Raw ESC command normalized into [-8192, 8191] #define UAVCAN_ESC_MAX_VALUE 8191 -#define SERVO_OUT_RCIN_MAX 16 // SRV_Channel::k_rcin1 ... SRV_Channel::k_rcin16 +#define SERVO_OUT_RCIN_MAX 32 // note that we allow for more than is in the enum #define SERVO_OUT_MOTOR_MAX 12 // SRV_Channel::k_motor1 ... SRV_Channel::k_motor8, SRV_Channel::k_motor9 ... SRV_Channel::k_motor12 extern const AP_HAL::HAL &hal; @@ -49,7 +49,7 @@ void AP_Periph_FW::rcout_init() SRV_Channels::set_angle(SRV_Channel::Aux_servo_function_t(SRV_Channel::k_rcin1 + i), 1000); } - uint16_t esc_mask = 0; + uint32_t esc_mask = 0; for (uint8_t i=0; iset_output_mode(esc_mask, (AP_HAL::RCOutput::output_mode)g.esc_pwm_type.get()); + const auto esc_type = (AP_HAL::RCOutput::output_mode)g.esc_pwm_type.get(); + hal.rcout->set_output_mode(esc_mask, esc_type); + + if (esc_type >= AP_HAL::RCOutput::MODE_PWM_DSHOT150 && + esc_type <= AP_HAL::RCOutput::MODE_PWM_DSHOT1200) { + SRV_Channels::set_digital_outputs(esc_mask, 0); + } // run this once and at 1Hz to configure aux and esc ranges rcout_init_1Hz(); @@ -93,7 +99,7 @@ void AP_Periph_FW::rcout_esc(int16_t *rc, uint8_t num_channels) rcout_has_new_data_to_update = true; } -void AP_Periph_FW::rcout_srv(uint8_t actuator_id, const float command_value) +void AP_Periph_FW::rcout_srv_unitless(uint8_t actuator_id, const float command_value) { #if HAL_PWM_COUNT > 0 const SRV_Channel::Aux_servo_function_t function = SRV_Channel::Aux_servo_function_t(SRV_Channel::k_rcin1 + actuator_id - 1); @@ -103,6 +109,16 @@ void AP_Periph_FW::rcout_srv(uint8_t actuator_id, const float command_value) #endif } +void AP_Periph_FW::rcout_srv_PWM(uint8_t actuator_id, const float command_value) +{ +#if HAL_PWM_COUNT > 0 + const SRV_Channel::Aux_servo_function_t function = SRV_Channel::Aux_servo_function_t(SRV_Channel::k_rcin1 + actuator_id - 1); + SRV_Channels::set_output_pwm(function, uint16_t(command_value+0.5)); + + rcout_has_new_data_to_update = true; +#endif +} + void AP_Periph_FW::rcout_handle_safety_state(uint8_t safety_state) { if (safety_state == 255) { diff --git a/Tools/AP_Periph/release-notes.txt b/Tools/AP_Periph/release-notes.txt deleted file mode 100644 index 455b4efabbd..00000000000 --- a/Tools/AP_Periph/release-notes.txt +++ /dev/null @@ -1,46 +0,0 @@ -Release 1.2.0 6th Jan 2020 --------------------------- - -This is a major release with several significant bug fixes and -improvements: - - - support for battery monitor nodes - - - support for testing in SITL - - - improvements in error reporting to the flight controller - - - fixes to stack sizes - - - MSP output support - - - support for BGR NCP5623 LEDs - - - switched to common CAN stack with main ArduPilot vehicle code - - - added several new board types - - -Release 1.1.0 14th May 2020 ---------------------------- - -This is a major release with several significant bug fixes: - - - fixed initial GPS timestamp which could cause ArduPilot to get bad - time sync - - - fixed airspeed pressure wrap - - - fixed rangefinder to send the RNGFND1_ADDR as sensor_id - - - added distinctive LED blink pattern when waiting for UAVCAN node ID - allocation - - - added HWESC build targets for HobbyWing ESC telemetry - - - fixed RM3100 compass scaling bug - -Release 1.0.0 9th November 2019 -------------------------------- - -Initial stable release diff --git a/Tools/AP_Periph/version.h b/Tools/AP_Periph/version.h index 3d0f687fbbf..4e3f59b496c 100644 --- a/Tools/AP_Periph/version.h +++ b/Tools/AP_Periph/version.h @@ -1,12 +1,14 @@ #pragma once -#define THISFIRMWARE "AP_Periph V1.3dev" +#include + +#define THISFIRMWARE "AP_Periph V1.5dev" // the following line is parsed by the autotest scripts -#define FIRMWARE_VERSION 1,3,0,FIRMWARE_VERSION_TYPE_DEV +#define FIRMWARE_VERSION 1,5,0,FIRMWARE_VERSION_TYPE_DEV #define FW_MAJOR 1 -#define FW_MINOR 3 +#define FW_MINOR 5 #define FW_PATCH 0 #define FW_TYPE FIRMWARE_VERSION_TYPE_DEV diff --git a/Tools/AP_Periph/wscript b/Tools/AP_Periph/wscript index ecb1a880265..dd83e39bcaa 100644 --- a/Tools/AP_Periph/wscript +++ b/Tools/AP_Periph/wscript @@ -62,6 +62,9 @@ def build(bld): 'AC_PID', 'AP_BLHeli', 'AP_ESC_Telem', + 'AP_Stats', + 'AP_EFI', + 'AP_CheckFirmware', ] bld.ap_stlib( name= 'AP_Periph_libs', diff --git a/Tools/CPUInfo/CPUInfo.cpp b/Tools/CPUInfo/CPUInfo.cpp index 9ddca1b1d69..73d1c6a45a9 100644 --- a/Tools/CPUInfo/CPUInfo.cpp +++ b/Tools/CPUInfo/CPUInfo.cpp @@ -13,6 +13,10 @@ #include #include "EKF_Maths.h" +#if HAL_WITH_DSP && CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS +#include +#endif + void setup(); void loop(); @@ -132,24 +136,31 @@ static void show_timings(void) TIMEIT("dmul", v_out_d *= v_d, 100); TIMEIT("ddiv", v_out_d /= v_d, 100); - TIMEIT("sinf()", v_out = sinf(v_f), 20); - TIMEIT("cosf()", v_out = cosf(v_f), 20); - TIMEIT("tanf()", v_out = tanf(v_f), 20); - TIMEIT("acosf()", v_out = acosf(v_f * 0.2), 20); - TIMEIT("asinf()", v_out = asinf(v_f * 0.2), 20); - TIMEIT("atan2f()", v_out = atan2f(v_f * 0.2, v_f * 0.3), 20); - TIMEIT("sqrtf()",v_out = sqrtf(v_f), 20); - - TIMEIT("sin()", v_out = sin(v_f), 20); - TIMEIT("cos()", v_out = cos(v_f), 20); - TIMEIT("tan()", v_out = tan(v_f), 20); - TIMEIT("acos()", v_out = acos(v_f * 0.2), 20); - TIMEIT("asin()", v_out = asin(v_f * 0.2), 20); - TIMEIT("atan2()", v_out = atan2(v_f * 0.2, v_f * 0.3), 20); - TIMEIT("sqrt()",v_out = sqrt(v_f), 20); - TIMEIT("sq()",v_out = sq(v_f), 20); - TIMEIT("powf(v,2)",v_out = powf(v_f, 2), 20); - TIMEIT("powf(v,3.1)",v_out = powf(v_f, 3.1), 20); + TIMEIT("sinf()", v_out = sinf(v_f), 100); + TIMEIT("cosf()", v_out = cosf(v_f), 100); + #if HAL_WITH_DSP && CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS + TIMEIT("arm_sin_f32()", v_out = arm_sin_f32(v_f), 100); + TIMEIT("arm_cos_f32()", v_out = arm_cos_f32(v_f), 100); + #endif + TIMEIT("tanf()", v_out = tanf(v_f), 100); + TIMEIT("acosf()", v_out = acosf(v_f * 0.2), 100); + TIMEIT("asinf()", v_out = asinf(v_f * 0.2), 100); + TIMEIT("atan2f()", v_out = atan2f(v_f * 0.2, v_f * 0.3), 100); + TIMEIT("sqrtf()",v_out = sqrtf(v_f), 100); + + TIMEIT("sin()", v_out = sin(v_f), 100); + TIMEIT("cos()", v_out = cos(v_f), 100); + TIMEIT("tan()", v_out = tan(v_f), 100); + TIMEIT("acos()", v_out = acos(v_f * 0.2), 100); + TIMEIT("asin()", v_out = asin(v_f * 0.2), 100); + TIMEIT("atan2()", v_out = atan2(v_f * 0.2, v_f * 0.3), 100); + TIMEIT("sqrt()",v_out = sqrt(v_f), 100); + #if HAL_WITH_DSP && CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS + TIMEIT("arm_sqrt_f32()", arm_sqrt_f32(v_f, (float32_t*)&v_out), 100); + #endif + TIMEIT("sq()",v_out = sq(v_f), 100); + TIMEIT("powf(v,2)",v_out = powf(v_f, 2), 100); + TIMEIT("powf(v,3.1)",v_out = powf(v_f, 3.1), 100); TIMEIT("EKF",v_out = ekf.test(), 5); TIMEIT("iadd8", v_out_8 += v_8, 100); diff --git a/Tools/CPUInfo/Makefile b/Tools/CPUInfo/Makefile index 90eda1cb2a2..e5398174624 100644 --- a/Tools/CPUInfo/Makefile +++ b/Tools/CPUInfo/Makefile @@ -2,7 +2,7 @@ all: @cd ../../ && modules/waf/waf-light configure --board linux --debug - @cd ../../ && modules/waf/waf-light tools + @cd ../../ && modules/waf/waf-light tool @cp ../../build/linux/tool/CPUInfo CPUInfo.elf @echo Built CPUInfo.elf diff --git a/Tools/FilterTestTool/FilterTest.py b/Tools/FilterTestTool/FilterTest.py index 5b70641ad6b..a9a39fe11de 100644 --- a/Tools/FilterTestTool/FilterTest.py +++ b/Tools/FilterTestTool/FilterTest.py @@ -1,4 +1,3 @@ -#!/usr/bin/env python # -*- coding: utf-8 -*- """ ArduPilot IMU Filter Test Class @@ -455,10 +454,10 @@ def print_filter_param_info(self): filt_type = f.get_type() if filt_type == BiquadFilterType.PEAK: # NOTCH - print("INS_NOTCH_ENABLE,", 1) - print("INS_NOTCH_FREQ,", f.get_center_freq()) - print("INS_NOTCH_BW,", f.get_bandwidth()) - print("INS_NOTCH_ATT,", f.get_attenuation()) + print("INS_HNTC2_ENABLE,", 1) + print("INS_HNTC2_FREQ,", f.get_center_freq()) + print("INS_HNTC2_BW,", f.get_bandwidth()) + print("INS_HNTC2_ATT,", f.get_attenuation()) else: # LPF print("INS_GYRO_FILTER,", f.get_center_freq()) diff --git a/Tools/FilterTestTool/run_filter_test.py b/Tools/FilterTestTool/run_filter_test.py index 7a1f67859e6..6a073399e0f 100755 --- a/Tools/FilterTestTool/run_filter_test.py +++ b/Tools/FilterTestTool/run_filter_test.py @@ -38,6 +38,7 @@ parser.add_argument('file', nargs='?', default=None, help='bin log file containing raw IMU logs') parser.add_argument('--begin-time', '-b', type=int, default=0, help='start from second') parser.add_argument('--end-time', '-e', type=int, default=-1, help='end to second') +parser.add_argument('--instance', type=int, default=0, help='IMU instance') args = parser.parse_args() @@ -72,7 +73,7 @@ PARAMS_TO_CHECK = [ "INS_LOG_BAT_OPT", "INS_GYRO_FILTER", "INS_ACCEL_FILTER", - "INS_NOTCH_ENABLE", "INS_NOTCH_FREQ", "INS_NOTCH_BW", "INS_NOTCH_ATT", + "INS_HNTC2_ENABLE", "INS_HNTC2_FREQ", "INS_HNTC2_BW", "INS_HNTC2_ATT", "INS_NOTCA_ENABLE", "INS_NOTCA_FREQ", "INS_NOTCA_BW", "INS_NOTCA_ATT", "LOG_BITMASK" ] @@ -113,7 +114,7 @@ params = {} while True: - m = mlog._parse_next() + m = mlog.recv_match(type=['PARM', 'GYR', 'ACC']) """ @type m DFMessage """ @@ -142,13 +143,13 @@ except AttributeError: pass - if m.fmt.name == "ACC1": + if m.fmt.name == "ACC" and m.I == args.instance: ACC_t.append(m_time_sec) ACC_x.append(m.AccX) ACC_y.append(m.AccY) ACC_z.append(m.AccZ) - elif m.fmt.name == "GYR1": + elif m.fmt.name == "GYR" and m.I == args.instance: GYR_t.append(m_time_sec) GYR_x.append(m.GyrX) GYR_y.append(m.GyrY) @@ -226,18 +227,18 @@ def set_bit(number, bit_index, bit_value): if "INS_ACCEL_FILTER" in params: DEFAULT_ACC_FILTER = params["INS_ACCEL_FILTER"] -if "INS_NOTCH_ENABLE" in params: - if params["INS_NOTCH_ENABLE"] != 0: - if "INS_NOTCH_ATT" in params: - DEFAULT_GYR_NOTCH_ATTENUATION = params["INS_NOTCH_ATT"] +if "INS_HNTC2_ENABLE" in params: + if params["INS_HNTC2_ENABLE"] != 0: + if "INS_HNTC2_ATT" in params: + DEFAULT_GYR_NOTCH_ATTENUATION = params["INS_HNTC2_ATT"] else: DEFAULT_GYR_NOTCH_ATTENUATION = 0 - if "INS_NOTCH_BW" in params: - DEFAULT_GYR_NOTCH_BANDWIDTH = params["INS_NOTCH_BW"] + if "INS_HNTC2_BW" in params: + DEFAULT_GYR_NOTCH_BANDWIDTH = params["INS_HNTC2_BW"] - if "INS_NOTCH_FREQ" in params: - DEFAULT_GYR_NOTCH_FREQ = params["INS_NOTCH_FREQ"] + if "INS_HNTC2_FREQ" in params: + DEFAULT_GYR_NOTCH_FREQ = params["INS_HNTC2_FREQ"] if "INS_NOTCA_ENABLE" in params: if params["INS_NOTCA_ENABLE"] != 0: diff --git a/Tools/Frame_params/ArduRoller-balancebot.param b/Tools/Frame_params/ArduRoller-balancebot.param index 28993b19fd1..f628c760796 100644 --- a/Tools/Frame_params/ArduRoller-balancebot.param +++ b/Tools/Frame_params/ArduRoller-balancebot.param @@ -1,19 +1,18 @@ -#NOTE: ArduRoller balance bot parameters for Rover-3.5 and higher +#NOTE: ArduRoller balance bot parameters for Rover-4.3 and higher ACRO_TURN_RATE,90 AHRS_ORIENTATION,29 -ATC_ACCEL_MAX,1 -ATC_BAL_D,0.01 +ATC_ACCEL_MAX,5 +ATC_BAL_D,0.18 ATC_BAL_FF,0 +ATC_BAL_FLTD,0 ATC_BAL_FILT,0 ATC_BAL_FLTE,0 ATC_BAL_I,7 ATC_BAL_IMAX,1 -ATC_BAL_P,1.2 -ATC_BAL_SPD_FF,1.1 +ATC_BAL_P,5 ATC_BRAKE,1 -ATC_STR_ACC_MAX,180 +ATC_STR_ACC_MAX,120 BAL_PITCH_MAX,10 -BRD_PWM_COUNT,0 CRASH_ANGLE,45 CRUISE_SPEED,0.4 CRUISE_THROTTLE,50 @@ -36,33 +35,37 @@ SERVO3_MAX,2000 SERVO3_MIN,1000 SERVO3_REVERSED,1 SERVO3_TRIM,1500 +SERVO11_FUNCTION,-1 +SERVO12_FUNCTION,-1 +SERVO13_FUNCTION,-1 +SERVO14_FUNCTION,-1 ATC_TURN_MAX_G,0.2 -WENC_CPR,3200 +WENC_CPR,1600 WENC_PINA,55 WENC_PINB,54 WENC_POS_X,0 WENC_POS_Y,-0.1 WENC_POS_Z,0 -WENC_RADIUS,0.05 +WENC_RADIUS,0.06 WENC_TYPE,1 -WENC2_CPR,3200 +WENC2_CPR,1600 WENC2_PINA,53 WENC2_PINB,52 WENC2_POS_X,0 WENC2_POS_Y,0.1 WENC2_POS_Z,0 -WENC2_RADIUS,0.05 +WENC2_RADIUS,0.06 WENC2_TYPE,1 -WRC_RATE_D,0.01 -WRC_RATE_FF,8 -WRC_RATE_FILT,50 -WRC_RATE_I,2 +WRC_RATE_D,0.2 +WRC_RATE_FF,4.2 +WRC_RATE_FLTD,50 +WRC_RATE_I,4 WRC_RATE_IMAX,1 WRC_RATE_MAX,12 -WRC_RATE_P,2 -WRC2_RATE_D,0.01 -WRC2_RATE_FF,8 -WRC2_RATE_FILT,50 -WRC2_RATE_I,2 +WRC_RATE_P,0 +WRC2_RATE_D,0.2 +WRC2_RATE_FF,4.2 +WRC2_RATE_FLTD,50 +WRC2_RATE_I,4 WRC2_RATE_IMAX,1 -WRC2_RATE_P,2 +WRC2_RATE_P,0 diff --git a/Tools/Frame_params/Holybro-S500.param b/Tools/Frame_params/Holybro-S500.param index f831688cf8c..95a8f00d32e 100644 --- a/Tools/Frame_params/Holybro-S500.param +++ b/Tools/Frame_params/Holybro-S500.param @@ -7,10 +7,10 @@ ATC_ACCEL_Y_MAX,12000 ATC_ANG_PIT_P,11 ATC_ANG_RLL_P,11 ATC_ANG_YAW_P,7.2 -ATC_RAT_PIT_D,0.006 +ATC_RAT_PIT_D,0.003 ATC_RAT_PIT_I,0.110 ATC_RAT_PIT_P,0.110 -ATC_RAT_RLL_D,0.006 +ATC_RAT_RLL_D,0.003 ATC_RAT_RLL_I,0.110 ATC_RAT_RLL_P,0.110 ATC_RAT_YAW_FLTE,1 @@ -23,6 +23,9 @@ BATT_MONITOR,4 BATT_VOLT_MULT,18.182 BATT_VOLT_PIN,0 BRD_SAFETYENABLE,0 +EK3_DRAG_BCOEF_X,80 +EK3_DRAG_BCOEF_Y,54 +EK3_DRAG_MCOEF,0.11 FRAME_CLASS,1 FRAME_TYPE,1 INS_GYRO_FILTER,40 diff --git a/Tools/Frame_params/Parrot_Disco/gpio.sh b/Tools/Frame_params/Parrot_Disco/gpio.sh old mode 100644 new mode 100755 diff --git a/Tools/Frame_params/QuadPlanes/Foxtech_GreatShark.param b/Tools/Frame_params/QuadPlanes/Foxtech_GreatShark.param new file mode 100644 index 00000000000..c3098e966c4 --- /dev/null +++ b/Tools/Frame_params/QuadPlanes/Foxtech_GreatShark.param @@ -0,0 +1,112 @@ +# parameters for Foxtech GreatShark + +# https://www.foxtechfpv.com/foxtech-great-shark-330-vtol.html + +# airspeed +ARSPD_FBW_MAX 35 +ARSPD_FBW_MIN 18 +TRIM_ARSPD_CM 2300 +TRIM_THROTTLE 60 + +# notch filter +INS_HNTCH_ENABLE 1 +INS_HNTCH_ATT 50.000000 +INS_HNTCH_BW 38.000000 +INS_HNTCH_ENABLE 1.000000 +INS_HNTCH_FREQ 75.000000 +INS_HNTCH_HMNCS 15.000000 +INS_HNTCH_MODE 1.000000 +INS_HNTCH_REF 0.337000 + +# fixed wing limits +LIM_PITCH_MIN -2000 +LIM_ROLL_CD 4000 +LEVEL_ROLL_LIMIT 12 + +FBWB_CLIMB_RATE 5 +WP_LOITER_RAD 250 +WP_RADIUS 200 +RTL_RADIUS 200 + +# fixed wing tune +RLL2SRV_RMAX 75 +RLL_RATE_D 0.009886 +RLL_RATE_FF 0.442834 +RLL_RATE_FLTD 12.5 +RLL_RATE_FLTT 3.183099 +RLL_RATE_I 0.442834 +RLL_RATE_P 0.385863 +RLL_RATE_SMAX 100 + +PTCH2SRV_RMAX_DN 75 +PTCH2SRV_RMAX_UP 75 +PTCH2SRV_TCONST 0.75 +PTCH_RATE_D 0.027 +PTCH_RATE_FF 1.835124 +PTCH_RATE_FLTD 12.5 +PTCH_RATE_FLTT 2.122066 +PTCH_RATE_I 1.835124 +PTCH_RATE_P 1.113065 +PTCH_RATE_SMAX 100 + +# quadplane parameters +Q_ENABLE 1 +Q_FRAME_CLASS 1 +Q_FRAME_TYPE 1 +Q_ANGLE_MAX 1500 +Q_ASSIST_ANGLE 30 +Q_ASSIST_SPEED 15 +Q_A_ACCEL_P_MAX 30000 +Q_A_ACCEL_R_MAX 30000 +Q_A_ACCEL_Y_MAX 9000 +Q_A_ANG_PIT_P 3 +Q_A_ANG_RLL_P 3 +Q_A_ANG_YAW_P 3 +Q_A_RATE_P_MAX 60 +Q_A_RATE_R_MAX 60 +Q_A_RATE_Y_MAX 60 +Q_A_RAT_PIT_D 0.005523 +Q_A_RAT_PIT_FLTD 12.5 +Q_A_RAT_PIT_FLTT 12.5 +Q_A_RAT_PIT_I 0.198349 +Q_A_RAT_PIT_P 0.198349 +Q_A_RAT_RLL_D 0.003301 +Q_A_RAT_RLL_FLTD 12.5 +Q_A_RAT_RLL_FLTT 12.5 +Q_A_RAT_RLL_I 0.233438 +Q_A_RAT_RLL_P 0.233438 +Q_A_RAT_YAW_D 0.01 +Q_A_RAT_YAW_FLTD 12.5 +Q_A_RAT_YAW_FLTE 2 +Q_A_RAT_YAW_FLTT 12.5 +Q_A_RAT_YAW_P 1 +Q_A_SLEW_YAW 3000 +Q_LAND_FINAL_ALT 12 +Q_LAND_SPEED 40 +Q_M_BAT_IDX 1 +Q_M_BAT_VOLT_MAX 50.4 +Q_M_BAT_VOLT_MIN 40 +Q_M_THST_HOVER 0.338 + +# soften VTOL position controller +Q_P_POSXY_P 0.5 +Q_P_VELXY_D 0.17 +Q_P_VELXY_I 0.35 +Q_P_VELXY_P 0.7 + +Q_RTL_ALT 40 +Q_TRANS_DECEL 1.5 +Q_TRANS_FAIL 20 +Q_VELZ_MAX 200 +Q_VELZ_MAX_DN 130 +Q_VFWD_ALT 6 +Q_VFWD_GAIN 0.05 +Q_WVANE_GAIN 0.3 +Q_WVANE_TAKEOFF 0 + +# servo setup +SERVO1_REVERSED 1 +SERVO2_FUNCTION 79 +SERVO2_REVERSED 1 +SERVO4_FUNCTION 80 +SERVO_AUTO_TRIM 1 diff --git a/Tools/Frame_params/QuadPlanes/MFD_Crosswind_VTOL.param b/Tools/Frame_params/QuadPlanes/MFD_Crosswind_VTOL.param new file mode 100644 index 00000000000..a52093b3efd --- /dev/null +++ b/Tools/Frame_params/QuadPlanes/MFD_Crosswind_VTOL.param @@ -0,0 +1,108 @@ +# param file for MFD CrossWind VTOL + +# http://myflydream.com/products/c-0/369.html + +# airspeed +ARSPD_FBW_MAX 29 +ARSPD_FBW_MIN 16 +TRIM_ARSPD_CM 2000 +TRIM_THROTTLE 52 + +# fixed wing limits +LIM_PITCH_MAX 2200 +LIM_ROLL_CD 3500 +NAVL1_PERIOD 24 +ALT_HOLD_RTL 9000 +FBWB_CLIMB_RATE 5 +WP_LOITER_RAD 150 +WP_RADIUS 150 + +# fixed wing tuning +RLL2SRV_RMAX 90 +RLL2SRV_TCONST 0.3 +RLL_RATE_D 0.001916 +RLL_RATE_FF 0.473694 +RLL_RATE_FLTD 10 +RLL_RATE_FLTT 7.957747 +RLL_RATE_I 0.473694 +RLL_RATE_P 0.01 + +PTCH2SRV_RLL 1.2 +PTCH2SRV_RMAX_DN 75 +PTCH2SRV_RMAX_UP 75 +PTCH_RATE_D 0.012 +PTCH_RATE_FF 0.329676 +PTCH_RATE_FLTD 15 +PTCH_RATE_FLTT 5.305164 +PTCH_RATE_I 0.329676 +PTCH_RATE_P 0.148952 +PTCH_RATE_SMAX 300 + +# actuators +SERVO1_REVERSED 1 +SERVO2_REVERSED 1 +SERVO_AUTO_TRIM 1 +SERVO_RATE 150 + +# harmonic notch filter +INS_HNTCH_ENABLE 1 +INS_HNTCH_ATT 40 +INS_HNTCH_BW 40 +INS_HNTCH_FREQ 81 +INS_HNTCH_HMNCS 3 +INS_HNTCH_MODE 1 +INS_HNTCH_REF 0.39 + +# quadplane parameters +Q_ENABLE 1 +Q_FRAME_CLASS 1 +Q_FRAME_TYPE 1 + +Q_ANGLE_MAX 2000 +Q_ASSIST_ANGLE 45 +Q_ASSIST_SPEED 14 + +# vtol tune +Q_A_ANG_PIT_P 4 +Q_A_ANG_RLL_P 4 +Q_A_RAT_PIT_D 0.0105 +Q_A_RAT_PIT_FLTD 15 +Q_A_RAT_PIT_I 0.2 +Q_A_RAT_PIT_P 0.2 +Q_A_RAT_PIT_SMAX 40 +Q_A_RAT_RLL_D 0.0198 +Q_A_RAT_RLL_I 0.225 +Q_A_RAT_RLL_P 0.225 +Q_A_RAT_RLL_SMAX 40 + +Q_M_BAT_VOLT_MAX 25.2 +Q_M_BAT_VOLT_MIN 18.6 + +Q_M_THST_EXPO 0.7 +Q_M_THST_HOVER 0.445192 +Q_P_JERK_Z 2 +Q_P_POSXY_P 0.7 +Q_P_VELXY_P 1 + +Q_RTL_ALT 60 + +Q_TRANSITION_MS 8000 +Q_TRANS_DECEL 1.2 +Q_TRANS_FAIL 20 +Q_TRAN_PIT_MAX 5 +Q_VFWD_ALT 5 +Q_VFWD_GAIN 0.05 + +Q_WP_RADIUS 500 +Q_WP_RFND_USE 0 +Q_WP_SPEED 800 +Q_WP_SPEED_DN 100 +Q_WVANE_ANG_MIN 3 +Q_WVANE_GAIN 0.2 + +# TECS tuning +TECS_CLMB_MAX 3 +TECS_PTCH_DAMP 0.2 +TECS_THR_DAMP 0.6 +TECS_TIME_CONST 6 + diff --git a/Tools/Frame_params/QuadPlanes/MFE_StriverMini.param b/Tools/Frame_params/QuadPlanes/MFE_StriverMini.param new file mode 100644 index 00000000000..feac862bc69 --- /dev/null +++ b/Tools/Frame_params/QuadPlanes/MFE_StriverMini.param @@ -0,0 +1,111 @@ +# MakeFlyEasy Striver Mini Parameters + +# http://en.makeflyeasy.com/index.php/striver-mini-vtol/ + +SCALING_SPEED 15 +TECS_CLMB_MAX 3 +TECS_LAND_ARSPD 20 +TKOFF_THR_MAX 85 +TRIM_PITCH_CD 100 +TRIM_THROTTLE 40 +WP_LOITER_RAD 120 +WP_RADIUS 110 + +# harmonic notch filter +INS_HNTCH_ENABLE 1 +INS_HNTCH_ATT 60 +INS_HNTCH_BW 34 +INS_HNTCH_FREQ 68 +INS_HNTCH_HMNCS 15 +INS_HNTCH_MODE 1 +INS_HNTCH_REF 0.26 + +# airspeed +TRIM_ARSPD_CM 2300 +ARSPD_FBW_MAX 30 +ARSPD_FBW_MIN 15 + +# limits +LIM_PITCH_MAX 2000 +LIM_PITCH_MIN -2000 +LIM_ROLL_CD 5500 + +# pitch tuning +PTCH_RATE_D 0.017718 +PTCH_RATE_FF 0.600786 +PTCH_RATE_FLTD 15 +PTCH_RATE_FLTT 2.122066 +PTCH_RATE_I 0.600786 +PTCH_RATE_IMAX 0.666000 +PTCH_RATE_P 0.716340 +PTCH_RATE_SMAX 100 + +# roll tuning +RLL_RATE_D 0.003669 +RLL_RATE_FF 0.435239 +RLL_RATE_FLTD 15 +RLL_RATE_FLTT 3.183099 +RLL_RATE_I 0.435239 +RLL_RATE_IMAX 0.666000 +RLL_RATE_P 0.228321 +RLL_RATE_SMAX 100 + +# quadplane parameters +Q_ENABLE 1 +Q_ANGLE_MAX 2000 +Q_ASSIST_SPEED 13 +Q_A_ACCEL_P_MAX 70000 +Q_A_ACCEL_R_MAX 70000 +Q_A_ACCEL_Y_MAX 20000 +Q_A_ANG_PIT_P 5.500000 +Q_A_ANG_RLL_P 6 +Q_A_ANG_YAW_P 3 +Q_A_RATE_P_MAX 75 +Q_A_RATE_R_MAX 75 +Q_A_RATE_Y_MAX 75 +Q_A_RAT_PIT_D 0.004961 +Q_A_RAT_PIT_FF 0 +Q_A_RAT_PIT_FLTD 15 +Q_A_RAT_PIT_FLTT 15 +Q_A_RAT_PIT_I 0.257666 +Q_A_RAT_PIT_IMAX 0.500000 +Q_A_RAT_PIT_P 0.257666 +Q_A_RAT_PIT_SMAX 20 +Q_A_RAT_RLL_D 0.001420 +Q_A_RAT_RLL_FF 0 +Q_A_RAT_RLL_FLTD 15 +Q_A_RAT_RLL_FLTT 15 +Q_A_RAT_RLL_I 0.198000 +Q_A_RAT_RLL_IMAX 0.500000 +Q_A_RAT_RLL_P 0.198000 +Q_A_RAT_RLL_SMAX 20 +Q_A_RAT_YAW_D 0.003001 +Q_A_RAT_YAW_FF 0 +Q_A_RAT_YAW_FLTD 15 +Q_A_RAT_YAW_FLTE 2 +Q_A_RAT_YAW_FLTT 15 +Q_A_RAT_YAW_I 0.015000 +Q_A_RAT_YAW_IMAX 0.500000 +Q_A_RAT_YAW_P 0.150000 +Q_A_RAT_YAW_SMAX 20 +Q_A_THR_MIX_MAN 0.500000 +Q_A_THR_MIX_MAX 0.850000 +Q_A_THR_MIX_MIN 0.400000 +Q_FRAME_CLASS 1 +Q_FRAME_TYPE 1 +Q_M_BAT_IDX 0 +Q_M_BAT_VOLT_MAX 25.200001 +Q_M_BAT_VOLT_MIN 19.200001 +Q_M_THST_EXPO 0.650000 +Q_M_THST_HOVER 0.247719 +Q_RTL_ALT 30 +Q_TRANS_DECEL 1.700000 +Q_VELZ_MAX 150 +Q_VFWD_ALT 5 +Q_VFWD_GAIN 0.050000 +Q_WVANE_ENABLE 1 +Q_WVANE_GAIN 0.200000 +Q_WVANE_LAND 1 +Q_WVANE_TAKEOFF 0 + + diff --git a/Tools/Frame_params/QuadPlanes/Mugin_EV350.param b/Tools/Frame_params/QuadPlanes/Mugin_EV350.param new file mode 100644 index 00000000000..3797d770109 --- /dev/null +++ b/Tools/Frame_params/QuadPlanes/Mugin_EV350.param @@ -0,0 +1,127 @@ +# parameter file for Mugin EV350 quadplane + +# https://www.muginuav.com/product/mugin-ev350-carbon-fiber-full-electric-vtol-uav-platform/ + +ALT_HOLD_RTL 8000 +LIM_PITCH_MAX 2000 +LIM_PITCH_MIN -2000 +LIM_ROLL_CD 4000 +NAVL1_PERIOD 17 +PTCH2SRV_TCONST 0.75 +RTL_RADIUS 180 +SCALING_SPEED 15 +TRIM_THROTTLE 50 +WP_LOITER_RAD 300 +WP_RADIUS 220 + +# harmonic notch filter +INS_HNTCH_ENABLE 1 +INS_HNTCH_ATT 50 +INS_HNTCH_BW 30 +INS_HNTCH_FREQ 51 +INS_HNTCH_HMNCS 15 +INS_HNTCH_MODE 1 +INS_HNTCH_REF 0.245000 + +# airspeed +TRIM_ARSPD_CM 2300 +ARSPD_FBW_MAX 28 +ARSPD_FBW_MIN 18 + +# FW pitch tuning +PTCH_RATE_D 0.021381 +PTCH_RATE_FF 1.093860 +PTCH_RATE_FLTD 10 +PTCH_RATE_FLTE 0 +PTCH_RATE_FLTT 2.122066 +PTCH_RATE_I 1.093860 +PTCH_RATE_IMAX 0.666 +PTCH_RATE_P 0.786900 +PTCH_RATE_SMAX 100 + +# FW roll tuning +RLL2SRV_TCONST 0.5 +RLL_RATE_D 0.021381 +RLL_RATE_FF 0.541178 +RLL_RATE_FLTD 12 +RLL_RATE_FLTE 0 +RLL_RATE_FLTT 3 +RLL_RATE_I 0.541178 +RLL_RATE_IMAX 0.666 +RLL_RATE_P 0.325935 +RLL_RATE_SMAX 150 + +# quadplane parameters +Q_ENABLE 1 +Q_ANGLE_MAX 1500 +Q_ASSIST_ANGLE 30 +Q_ASSIST_SPEED 15 +Q_A_ACCEL_P_MAX 30000 +Q_A_ACCEL_R_MAX 30000 +Q_A_ACCEL_Y_MAX 15000 +Q_A_RATE_P_MAX 60 +Q_A_RATE_R_MAX 60 +Q_A_RATE_Y_MAX 30 +Q_A_RAT_PIT_D 0.015 +Q_A_RAT_PIT_FF 0 +Q_A_RAT_PIT_FLTD 10 +Q_A_RAT_PIT_FLTE 0 +Q_A_RAT_PIT_FLTT 20 +Q_A_RAT_PIT_I 0.3 +Q_A_RAT_PIT_IMAX 0.5 +Q_A_RAT_PIT_P 0.3 +Q_A_RAT_PIT_SMAX 20 +Q_A_RAT_RLL_D 0.004 +Q_A_RAT_RLL_FF 0 +Q_A_RAT_RLL_FLTD 10 +Q_A_RAT_RLL_FLTE 0 +Q_A_RAT_RLL_FLTT 10 +Q_A_RAT_RLL_I 0.1 +Q_A_RAT_RLL_IMAX 0.5 +Q_A_RAT_RLL_P 0.1 +Q_A_RAT_RLL_SMAX 20 +Q_A_RAT_YAW_D 0.01 +Q_A_RAT_YAW_FF 0 +Q_A_RAT_YAW_FLTD 0 +Q_A_RAT_YAW_FLTE 2.5 +Q_A_RAT_YAW_FLTT 20 +Q_A_RAT_YAW_I 0.018 +Q_A_RAT_YAW_IMAX 0.5 +Q_A_RAT_YAW_P 0.5 +Q_A_RAT_YAW_SMAX 10 +Q_A_THR_MIX_MAX 0.9 +Q_FRAME_CLASS 1 +Q_FRAME_TYPE 1 +Q_LAND_FINAL_ALT 12 +Q_LAND_SPEED 40 +Q_LOIT_ANG_MAX 20 +Q_LOIT_BRK_ACCEL 40 +Q_LOIT_BRK_JERK 200 +Q_LOIT_SPEED 600 +Q_M_BAT_IDX 0 +Q_M_BAT_VOLT_MAX 50.4 +Q_M_BAT_VOLT_MIN 39.0 +Q_M_THST_EXPO 0.7 +Q_M_THST_HOVER 0.264 +Q_M_YAW_HEADROOM 200 +Q_P_JERK_XY 2 +Q_P_POSXY_P 0.5 +Q_P_VELXY_D 0.17 +Q_P_VELXY_I 0.37 +Q_P_VELXY_P 0.7 +Q_RTL_ALT 40 +Q_THROTTLE_EXPO 0.2 +Q_TRANS_DECEL 1.5 +Q_TRAN_PIT_MAX 7 +Q_VELZ_MAX 200 +Q_VELZ_MAX_DN 130 +Q_VFWD_ALT 5 +Q_VFWD_GAIN 0.05 +Q_WP_RADIUS 300 +Q_WP_SPEED 600 +Q_WP_SPEED_DN 150 +Q_WP_SPEED_UP 220 +Q_WVANE_ANG_MIN 3 +Q_WVANE_ENABLE 1 +Q_WVANE_GAIN 0.3 +Q_WVANE_TAKEOFF 0 diff --git a/Tools/Frame_params/QuadPlanes/SparkleTech-EagleHero.param b/Tools/Frame_params/QuadPlanes/SparkleTech-EagleHero.param new file mode 100644 index 00000000000..c661c0c3c60 --- /dev/null +++ b/Tools/Frame_params/QuadPlanes/SparkleTech-EagleHero.param @@ -0,0 +1,100 @@ +# parameters for SparkleTech EagleHero VTOL + +# http://www.sparkletech.hk/%E9%B9%B0%E7%9C%BC-%E6%97%A0%E4%BA%BA%E6%9C%BA/electric-power/eagle-plus-vtol/ + +# airspeed +ARSPD_FBW_MAX 31 +ARSPD_FBW_MIN 22 +TRIM_ARSPD_CM 2400 +SCALING_SPEED 20 +TRIM_THROTTLE 55 + +LIM_ROLL_CD 5000 + +# fixed wing tuning +RLL2SRV_RMAX 75 +RLL_RATE_D 0.002386 +RLL_RATE_FF 0.377393 +RLL_RATE_FLTD 10 +RLL_RATE_FLTT 3.183099 +RLL_RATE_I 0.377393 +RLL_RATE_P 0.045467 +RLL_RATE_SMAX 100 + +PTCH2SRV_RMAX_DN 75 +PTCH2SRV_RMAX_UP 75 +PTCH2SRV_TCONST 0.75 +PTCH_RATE_D 0.004031 +PTCH_RATE_FF 0.627938 +PTCH_RATE_FLTD 10 +PTCH_RATE_FLTT 2.122066 +PTCH_RATE_I 0.627938 +PTCH_RATE_P 0.076867 +PTCH_RATE_SMAX 100 + +# notch filter +INS_HNTCH_ENABLE 1 +INS_HNTCH_ATT 60 +INS_HNTCH_BW 50 +INS_HNTCH_FREQ 100 +INS_HNTCH_HMNCS 7 +INS_HNTCH_MODE 1 +INS_HNTCH_REF 0.21 + +# quadplane setup +Q_ENABLE 1 +Q_FRAME_CLASS 1 +Q_FRAME_TYPE 1 + +Q_ANGLE_MAX 1300 +Q_ASSIST_SPEED 17 +Q_A_ACCEL_P_MAX 55000 +Q_A_ACCEL_R_MAX 55000 +Q_A_ACCEL_Y_MAX 20000 + +# VTOL rate tuning +Q_A_ANG_PIT_P 4 +Q_A_ANG_RLL_P 4 +Q_A_RAT_PIT_D 0.008 +Q_A_RAT_PIT_I 0.1 +Q_A_RAT_PIT_P 0.1 +Q_A_RAT_PIT_SMAX 15 +Q_A_RAT_RLL_D 0.008 +Q_A_RAT_RLL_I 0.14084 +Q_A_RAT_RLL_P 0.14084 +Q_A_RAT_RLL_SMAX 15 +Q_A_RAT_YAW_D 0.018 +Q_A_RAT_YAW_I 0.028 +Q_A_RAT_YAW_P 0.2835 +Q_A_RAT_YAW_SMAX 10 + +# VTOL battery on 2nd battery connector +Q_M_BAT_IDX 1 +Q_M_BAT_VOLT_MAX 33.6 +Q_M_BAT_VOLT_MIN 26.4 + +# ESC range +Q_M_PWM_MAX 1850 +Q_M_PWM_MIN 1100 + +# slow down ESC rates +Q_M_SLEW_DN_TIME 0.2 +Q_M_SLEW_UP_TIME 0.2 + +Q_M_THST_EXPO 0.7 +Q_M_THST_HOVER 0.19841 + +Q_P_ACCZ_I 0.5 +Q_P_ACCZ_P 0.15 +Q_P_POSZ_P 0.5 +Q_P_VELZ_P 2.5 + +Q_TRANS_DECEL 1.5 + +# weathervaning on landing only +Q_WVANE_ENABLE 1 +Q_WVANE_GAIN 0.2 +Q_WVANE_TAKEOFF 0 + +# auto-trim servos +SERVO_AUTO_TRIM 1 diff --git a/Tools/Frame_params/SToRM32-MAVLink.param b/Tools/Frame_params/SToRM32-MAVLink.param index cedfc4e7d45..54b6a85a645 100644 --- a/Tools/Frame_params/SToRM32-MAVLink.param +++ b/Tools/Frame_params/SToRM32-MAVLink.param @@ -1,11 +1,5 @@ #NOTE: SToRM32 3-axis gimbal using MAVlink on Telem2, RC6 controls tilt -MNT_ANGMAX_PAN,17999 -MNT_ANGMAX_ROL,4500 -MNT_ANGMAX_TIL,1000 -MNT_ANGMIN_PAN,-18000 -MNT_ANGMIN_ROL,-4500 -MNT_ANGMIN_TIL,-9000 -MNT_RC_IN_TILT,6 -MNT_TYPE,4 +MNT1_TYPE,4 +RC6_OPTION,213 SERIAL2_BAUD,115 SERIAL2_PROTOCOL,1 \ No newline at end of file diff --git a/Tools/Frame_params/SkyViper-2450GPS/defaults.parm b/Tools/Frame_params/SkyViper-2450GPS/defaults.parm index fbc2a3fac09..0ccc08dcf86 100644 --- a/Tools/Frame_params/SkyViper-2450GPS/defaults.parm +++ b/Tools/Frame_params/SkyViper-2450GPS/defaults.parm @@ -25,6 +25,9 @@ TMODE_TMIN 0.9 RELAY_PIN 54 RELAY_PIN2 55 RELAY_DEFAULT 1 +# Set to GPIO so they are used as RELAY +SERVO5_FUNCTION -1 +SERVO6_FUNCTION -1 AHRS_ORIENTATION 12 COMPASS_EXTERNAL 1 @@ -117,10 +120,10 @@ DISARM_DELAY 8 INS_FAST_SAMPLE 1 INS_GYRO_FILTER 20 LOG_BITMASK 65534 -INS_NOTCH_ENABLE 1 -INS_NOTCH_ATT 30 -INS_NOTCH_BW 60 -INS_NOTCH_FREQ 80 +INS_HNTC2_ENABLE 1 +INS_HNTC2_ATT 30 +INS_HNTC2_BW 60 +INS_HNTC2_FREQ 80 # rate controllers ANGLE_MAX 3500 diff --git a/Tools/Frame_params/Solo_Copter-4.param b/Tools/Frame_params/Solo_Copter-4.param index b1ecf7c488f..0d9f0961108 100644 --- a/Tools/Frame_params/Solo_Copter-4.param +++ b/Tools/Frame_params/Solo_Copter-4.param @@ -83,10 +83,10 @@ INS_HNTCH_ENABLE,1 INS_HNTCH_REF,0.26 INS_HNTCH_FREQ,200 INS_HNTCH_BW,100 -INS_NOTCH_ATT,40 -INS_NOTCH_ENABLE,1 -INS_NOTCH_FREQ,98 -INS_NOTCH_BW,49 +INS_HNTC2_ATT,40 +INS_HNTC2_ENABLE,1 +INS_HNTC2_FREQ,98 +INS_HNTC2_BW,49 INS_TRIM_OPTION,2 LAND_ALT_LOW,600 LAND_SPEED,45 diff --git a/Tools/Frame_params/Solo_Copter-4_GreenCube.param b/Tools/Frame_params/Solo_Copter-4_GreenCube.param index f58d904ef6f..221f9f39c8d 100644 --- a/Tools/Frame_params/Solo_Copter-4_GreenCube.param +++ b/Tools/Frame_params/Solo_Copter-4_GreenCube.param @@ -82,10 +82,10 @@ INS_HNTCH_ENABLE,1 INS_HNTCH_REF,0.26 INS_HNTCH_FREQ,200 INS_HNTCH_BW,100 -INS_NOTCH_ATT,40 -INS_NOTCH_ENABLE,1 -INS_NOTCH_FREQ,98 -INS_NOTCH_BW,49 +INS_HNTC2_ATT,40 +INS_HNTC2_ENABLE,1 +INS_HNTC2_FREQ,98 +INS_HNTC2_BW,49 INS_TRIM_OPTION,2 LAND_ALT_LOW,600 LAND_SPEED,45 diff --git a/Tools/Frame_params/Sub/bluerov2-4_0_0.params b/Tools/Frame_params/Sub/bluerov2-4_0_0.params index 08bf4748d1e..bc3f9053906 100644 --- a/Tools/Frame_params/Sub/bluerov2-4_0_0.params +++ b/Tools/Frame_params/Sub/bluerov2-4_0_0.params @@ -292,7 +292,7 @@ INS_LOG_BAT_LGCT,32 INS_LOG_BAT_LGIN,20 INS_LOG_BAT_MASK,0 INS_LOG_BAT_OPT,0 -INS_NOTCH_ENABLE,0 +INS_HNTC2_ENABLE,0 INS_POS1_X,0.0 INS_POS1_Y,0.0 INS_POS1_Z,0.0 diff --git a/Tools/Frame_params/Sub/bluerov2-heavy-4_0_0.params b/Tools/Frame_params/Sub/bluerov2-heavy-4_0_0.params index 9c76f4e1d13..4cbb5e830f8 100644 --- a/Tools/Frame_params/Sub/bluerov2-heavy-4_0_0.params +++ b/Tools/Frame_params/Sub/bluerov2-heavy-4_0_0.params @@ -292,7 +292,7 @@ INS_LOG_BAT_LGCT,32 INS_LOG_BAT_LGIN,20 INS_LOG_BAT_MASK,0 INS_LOG_BAT_OPT,0 -INS_NOTCH_ENABLE,0 +INS_HNTC2_ENABLE,0 INS_POS1_X,0.0 INS_POS1_Y,0.0 INS_POS1_Z,0.0 diff --git a/Tools/Frame_params/iflight-chimera7-4.2.param b/Tools/Frame_params/iflight-chimera7-4.2.param new file mode 100644 index 00000000000..aa4d0857cbf --- /dev/null +++ b/Tools/Frame_params/iflight-chimera7-4.2.param @@ -0,0 +1,73 @@ +#NOTE: iFlight Chimera7 params for ArduPilot Copter 4.2 + +ACRO_RP_EXPO,0.6 +ACRO_RP_RATE,600 +ACRO_Y_EXPO,0.6 +ACRO_Y_RATE,600 +ATC_ACCEL_P_MAX,281062.5 +ATC_ACCEL_R_MAX,301679.8 +ATC_ACCEL_Y_MAX,72000 +ATC_ANG_PIT_P,18 +ATC_ANG_RLL_P,18 +ATC_ANG_YAW_P,11 +ATC_RAT_PIT_D,0.001879093 +ATC_RAT_PIT_FLTD,60 +ATC_RAT_PIT_FLTT,30 +ATC_RAT_PIT_I,0.09663188 +ATC_RAT_PIT_P,0.09663188 +ATC_RAT_RLL_D,0.001453624 +ATC_RAT_RLL_FLTD,75 +ATC_RAT_RLL_FLTT,30 +ATC_RAT_RLL_I,0.07706726 +ATC_RAT_RLL_P,0.07706726 +ATC_RAT_YAW_D,0.02 +ATC_RAT_YAW_FF,0.0043 +ATC_RAT_YAW_FLTD,60 +ATC_RAT_YAW_FLTE,1.887445 +ATC_RAT_YAW_FLTT,30 +ATC_RAT_YAW_I,0.01927038 +ATC_RAT_YAW_P,0.1927038 +BATT_AMP_OFFSET,-0.04308 +BATT_AMP_PERVLT,52.706 +BATT_CURR_PIN,11 +BATT_LOW_VOLT,21.6 +BATT_MONITOR,4 +COMPASS_AUTO_ROT,0 +COMPASS_CUS_PIT,-15 +COMPASS_CUS_ROLL,0 +COMPASS_CUS_YAW,180 +COMPASS_ORIENT,100 +EK3_PRIMARY,1 +EK3_IMU_MASK,2 +FRAME_CLASS,1 +FRAME_TYPE,12 +INS_GYRO_FILTER,150 +INS_HNTCH_BW,20 +INS_HNTCH_ENABLE,1 +INS_HNTCH_FREQ,40 +INS_HNTCH_HMNCS,1 +INS_HNTCH_MODE,3 +INS_HNTCH_OPTS,6 +INS_HNTCH_REF,1 +INS_HNTC2_BW,75 +INS_HNTC2_ENABLE,1 +INS_HNTC2_FREQ,150 +INS_HNTC2_HMNCS,1 +INS_HNTC2_MODE,1 +INS_HNTC2_REF,1 +MOT_BAT_VOLT_MAX,25.2 +MOT_BAT_VOLT_MIN,19.8 +MOT_PWM_TYPE,6 +MOT_THST_EXPO,0.62 +MOT_THST_HOVER,0.12 +PILOT_Y_EXPO,0.4 +PILOT_Y_RATE,600 +PSC_ACCZ_I,0.24 +PSC_ACCZ_P,0.12 +SCHED_LOOP_RATE,800 +SERVO_BLH_AUTO,1 +SERVO_BLH_BDMASK,15 +SERVO_BLH_RVMASK,6 +SERVO_BLH_TRATE,5 +SERVO_DSHOT_ESC,1 +SERVO_DSHOT_RATE,2 diff --git a/Tools/GIT_Test/GIT_Success.txt b/Tools/GIT_Test/GIT_Success.txt index 872410cc003..6cc627d9c4a 100644 --- a/Tools/GIT_Test/GIT_Success.txt +++ b/Tools/GIT_Test/GIT_Success.txt @@ -163,4 +163,9 @@ xianglunkai Mike Lyons MiloÅ¡ PetraÅ¡inović (mpetrasinovic) Takeshi Yamada -Diego Borrajo \ No newline at end of file +Diego Borrajo +Lee Yong Ler (Retry) +Chenghao Tan +RuffaloLavoisier (Jeon sunghwan) was here. +Giovanni Rasera - Ciao Mondo from Italy - 2022 +Karmanov Semyon diff --git a/Tools/IO_Firmware/iofirmware_f103_8MHz_highpolh.bin b/Tools/IO_Firmware/iofirmware_f103_8MHz_highpolh.bin index 90686cb849c..5ed0930ff72 100755 Binary files a/Tools/IO_Firmware/iofirmware_f103_8MHz_highpolh.bin and b/Tools/IO_Firmware/iofirmware_f103_8MHz_highpolh.bin differ diff --git a/Tools/IO_Firmware/iofirmware_f103_8MHz_lowpolh.bin b/Tools/IO_Firmware/iofirmware_f103_8MHz_lowpolh.bin index c3023d68fcf..98a318a394f 100755 Binary files a/Tools/IO_Firmware/iofirmware_f103_8MHz_lowpolh.bin and b/Tools/IO_Firmware/iofirmware_f103_8MHz_lowpolh.bin differ diff --git a/Tools/IO_Firmware/iofirmware_highpolh.bin b/Tools/IO_Firmware/iofirmware_highpolh.bin index 80a2ea534d3..a1eaf942905 100755 Binary files a/Tools/IO_Firmware/iofirmware_highpolh.bin and b/Tools/IO_Firmware/iofirmware_highpolh.bin differ diff --git a/Tools/IO_Firmware/iofirmware_lowpolh.bin b/Tools/IO_Firmware/iofirmware_lowpolh.bin index a014de80d17..5afde36dc0d 100755 Binary files a/Tools/IO_Firmware/iofirmware_lowpolh.bin and b/Tools/IO_Firmware/iofirmware_lowpolh.bin differ diff --git a/Tools/Linux_HAL_Essentials/pru/rangefinderpru/pru_ctrl.h b/Tools/Linux_HAL_Essentials/pru/rangefinderpru/pru_ctrl.h old mode 100755 new mode 100644 index bcbc212acea..91e58cf8670 --- a/Tools/Linux_HAL_Essentials/pru/rangefinderpru/pru_ctrl.h +++ b/Tools/Linux_HAL_Essentials/pru/rangefinderpru/pru_ctrl.h @@ -117,4 +117,3 @@ typedef struct{ /* Definition of control register structures. */ #define PRU0_CTRL (*((volatile pruCtrl*)0x22000)) #define PRU1_CTRL (*((volatile pruCtrl*)0x24000)) - diff --git a/Tools/Linux_HAL_Essentials/startup.sh b/Tools/Linux_HAL_Essentials/startup.sh index 6b7c0d09f1c..82b3847f87f 100755 --- a/Tools/Linux_HAL_Essentials/startup.sh +++ b/Tools/Linux_HAL_Essentials/startup.sh @@ -1,3 +1,5 @@ +#!/bin/bash + if [ "`echo $1`" = "load" ]; then echo "Loading Test_Capes..." cp devicetree/pxf/BB-SPI0-PXF-01-00A0.dtbo /lib/firmware/ diff --git a/Tools/LogAnalyzer/DataflashLog.py b/Tools/LogAnalyzer/DataflashLog.py index e6515376a13..38fc82b2194 100644 --- a/Tools/LogAnalyzer/DataflashLog.py +++ b/Tools/LogAnalyzer/DataflashLog.py @@ -4,32 +4,39 @@ # Initial code by Andrew Chapman (amchapman@gmail.com), 16th Jan 2014 # -from __future__ import print_function -import collections -import numpy +# AP_FLAKE8_CLEAN + +from __future__ import print_function, division + import bisect -import sys import ctypes +import sys +import numpy from VehicleType import VehicleType, VehicleTypeString + class Format(object): '''Data channel format as specified by the FMT lines in the log file''' - def __init__(self,msgType,msgLen,name,types,labels): - self.NAME = 'FMT' + + def __init__(self, msgType, msgLen, name, types, labels): + self.NAME = 'FMT' self.msgType = msgType - self.msgLen = msgLen - self.name = name - self.types = types - self.labels = labels.split(',') + self.msgLen = msgLen + self.name = name + self.types = types + self.labels = labels.split(',') def __str__(self): return "%8s %s" % (self.name, repr(self.labels)) @staticmethod - def trycastToFormatType(value,valueType): - '''using format characters from libraries/DataFlash/DataFlash.h to cast strings to basic python int/float/string types - tries a cast, if it does not work, well, acceptable as the text logs do not match the format, e.g. MODE is expected to be int''' + def trycastToFormatType(value, valueType): + """ + Using format characters from libraries/DataFlash/DataFlash.h to cast strings to basic python int/float/string + types tries a cast, if it does not work, well, acceptable as the text logs do not match the format, e.g. MODE is + expected to be int + """ try: if valueType in "fcCeELd": return float(value) @@ -37,14 +44,14 @@ def trycastToFormatType(value,valueType): return int(value) elif valueType in "nNZ": return str(value) - except: + except ValueError: pass return value def to_class(self): members = dict( - NAME = self.name, - labels = self.labels[:], + NAME=self.name, + labels=self.labels[:], ) fieldtypes = [i for i in self.types] @@ -52,51 +59,54 @@ def to_class(self): # field access for (label, _type) in zip(fieldlabels, fieldtypes): + def createproperty(name, format): # extra scope for variable sanity # scaling via _NAME and def NAME(self): return self._NAME / SCALE propertyname = name attributename = '_' + name - p = property(lambda x:getattr(x, attributename), - lambda x, v:setattr(x,attributename, Format.trycastToFormatType(v,format))) + p = property( + lambda x: getattr(x, attributename), + lambda x, v: setattr(x, attributename, Format.trycastToFormatType(v, format)), + ) members[propertyname] = p members[attributename] = None + createproperty(label, _type) # repr shows all values but the header - members['__repr__'] = lambda x: "<{cls} {data}>".format(cls=x.__class__.__name__, data = ' '.join(["{}:{}".format(k,getattr(x,'_'+k)) for k in x.labels])) + members['__repr__'] = lambda x: "<{cls} {data}>".format( + cls=x.__class__.__name__, data=' '.join(["{}:{}".format(k, getattr(x, '_' + k)) for k in x.labels]) + ) def init(a, *x): if len(x) != len(a.labels): raise ValueError("Invalid Length") - #print(list(zip(a.labels, x))) - for (l,v) in zip(a.labels, x): + for (l, v) in zip(a.labels, x): try: setattr(a, l, v) except Exception as e: - print("{} {} {} failed".format(a,l,v)) + print("{} {} {} failed".format(a, l, v)) print(e) members['__init__'] = init # finally, create the class - cls = type(\ - 'Log__{:s}'.format(self.name), - (object,), - members - ) - #print(members) + cls = type('Log__{:s}'.format(self.name), (object,), members) return cls class logheader(ctypes.LittleEndianStructure): - _fields_ = [ \ + _fields_ = [ ('head1', ctypes.c_uint8), ('head2', ctypes.c_uint8), ('msgid', ctypes.c_uint8), ] + def __repr__(self): - return "".format(self=self) + return "".format( + self=self + ) class BinaryFormat(ctypes.LittleEndianStructure): @@ -116,10 +126,10 @@ class BinaryFormat(ctypes.LittleEndianStructure): 'n': ctypes.c_char * 4, 'N': ctypes.c_char * 16, 'Z': ctypes.c_char * 64, - 'c': ctypes.c_int16,# * 100, - 'C': ctypes.c_uint16,# * 100, - 'e': ctypes.c_int32,# * 100, - 'E': ctypes.c_uint32,# * 100, + 'c': ctypes.c_int16, # * 100, + 'C': ctypes.c_uint16, # * 100, + 'e': ctypes.c_int32, # * 100, + 'E': ctypes.c_uint32, # * 100, 'L': ctypes.c_int32, 'M': ctypes.c_uint8, 'q': ctypes.c_int64, @@ -134,7 +144,7 @@ class BinaryFormat(ctypes.LittleEndianStructure): } _packed_ = True - _fields_ = [ \ + _fields_ = [ ('head', logheader), ('type', ctypes.c_uint8), ('length', ctypes.c_uint8), @@ -142,17 +152,22 @@ class BinaryFormat(ctypes.LittleEndianStructure): ('types', ctypes.c_char * 16), ('labels', ctypes.c_char * 64), ] + def __repr__(self): - return "<{cls} {data}>".format(cls=self.__class__.__name__, data = ' '.join(["{}:{}".format(k,getattr(self,k)) for (k,_) in self._fields_[1:]])) + return "<{cls} {data}>".format( + cls=self.__class__.__name__, + data=' '.join(["{}:{}".format(k, getattr(self, k)) for (k, _) in self._fields_[1:]]), + ) def to_class(self): - labels = self.labels.decode('ascii') if self.labels else "" + labels = self.labels.decode(encoding="utf-8") if self.labels else "" members = dict( - NAME = self.name.decode('ascii'), - MSG = self.type, - SIZE = self.length, - labels = labels.split(","), - _pack_ = True) + NAME=self.name.decode(encoding="utf-8"), + MSG=self.type, + SIZE=self.length, + labels=labels.split(","), + _pack_=True, + ) if type(self.types[0]) == str: fieldtypes = [i for i in self.types] @@ -163,53 +178,55 @@ def to_class(self): print("Broken FMT message for {} .. ignoring".format(self.name), file=sys.stderr) return None - fields = [('head',logheader)] + fields = [('head', logheader)] # field access for (label, _type) in zip(fieldlabels, fieldtypes): + def createproperty(name, format): # extra scope for variable sanity # scaling via _NAME and def NAME(self): return self._NAME / SCALE propertyname = name attributename = '_' + name scale = BinaryFormat.FIELD_SCALE.get(format, None) + def get_message_attribute(x): ret = getattr(x, attributename) - if str(format) in ['Z','n','N']: - ret = ret.decode('ascii') + if str(format) in ['Z', 'n', 'N']: + ret = ret.decode(encoding="utf-8") return ret + p = property(get_message_attribute) if scale is not None: - p = property(lambda x:getattr(x, attributename) / scale) + p = property(lambda x: getattr(x, attributename) / scale) members[propertyname] = p try: fields.append((attributename, BinaryFormat.FIELD_FORMAT[format])) except KeyError: print('ERROR: Failed to add FMT type: {}, with format: {}'.format(attributename, format)) raise + createproperty(label, _type) members['_fields_'] = fields # repr shows all values but the header - members['__repr__'] = lambda x: "<{cls} {data}>".format(cls=x.__class__.__name__, data = ' '.join(["{}:{}".format(k,getattr(x,k)) for k in x.labels])) + members['__repr__'] = lambda x: "<{cls} {data}>".format( + cls=x.__class__.__name__, data=' '.join(["{}:{}".format(k, getattr(x, k)) for k in x.labels]) + ) # finally, create the class - cls = type(\ - 'Log__%s' % self.name, - (ctypes.LittleEndianStructure,), - members - ) + cls = type('Log__%s' % self.name, (ctypes.LittleEndianStructure,), members) if ctypes.sizeof(cls) != cls.SIZE: print("size mismatch for {} expected {} got {}".format(cls, ctypes.sizeof(cls), cls.SIZE), file=sys.stderr) -# for i in cls.labels: -# print("{} = {}".format(i,getattr(cls,'_'+i))) return None return cls + BinaryFormat.SIZE = ctypes.sizeof(BinaryFormat) + class Channel(object): '''storage for a single stream of data, i.e. all GPS.RelAlt values''' @@ -217,88 +234,107 @@ class Channel(object): # TODO: store data as a scipy spline curve so we can more easily interpolate and sample the slope? def __init__(self): - self.dictData = {} # dict of linenum->value # store dupe data in dict and list for now, until we decide which is the better way to go - self.listData = [] # list of (linenum,value) # store dupe data in dict and list for now, until we decide which is the better way to go + # store dupe data in dict and list for now, until we decide which is the better way to go + self.dictData = {} # dict of linenum->value + self.listData = [] # list of (linenum,value) + def getSegment(self, startLine, endLine): '''returns a segment of this data (from startLine to endLine, inclusive) as a new Channel instance''' segment = Channel() - segment.dictData = {k:v for k,v in self.dictData.items() if k >= startLine and k <= endLine} + segment.dictData = {k: v for k, v in self.dictData.items() if k >= startLine and k <= endLine} + segment.listData = [(k, v) for k, v in self.listData if k >= startLine and k <= endLine] return segment + def min(self): return min(self.dictData.values()) + def max(self): return max(self.dictData.values()) + def avg(self): return numpy.mean(self.dictData.values()) + def getNearestValueFwd(self, lineNumber): '''Returns (value,lineNumber)''' - index = bisect.bisect_left(self.listData, (lineNumber,-99999)) - while index= lineNumber: - return (self.listData[index][1],line) + return (self.listData[index][1], line) index += 1 - raise Exception("Error finding nearest value for line %d" % lineNumber) + raise ValueError("Error finding nearest value for line %d" % lineNumber) + def getNearestValueBack(self, lineNumber): '''Returns (value,lineNumber)''' - index = bisect.bisect_left(self.listData, (lineNumber,-99999)) - 1 - while index>=0: - line = self.listData[index][0] - #print("Looking backwards for nearest value to line number %d, starting at line %d" % (lineNumber,line)) # TEMP + index = bisect.bisect_left(self.listData, (lineNumber, -99999)) - 1 + while index >= 0: + line = self.listData[index][0] if line <= lineNumber: - return (self.listData[index][1],line) + return (self.listData[index][1], line) index -= 1 - raise Exception("Error finding nearest value for line %d" % lineNumber) + raise ValueError("Error finding nearest value for line %d" % lineNumber) + def getNearestValue(self, lineNumber, lookForwards=True): - '''find the nearest data value to the given lineNumber, defaults to first looking forwards. Returns (value,lineNumber)''' + """ + Find the nearest data value to the given lineNumber, defaults to first looking forwards. + Returns (value,lineNumber) + """ if lookForwards: try: return self.getNearestValueFwd(lineNumber) - except: + except ValueError: return self.getNearestValueBack(lineNumber) else: try: return self.getNearestValueBack(lineNumber) - except: + except ValueError: return self.getNearestValueFwd(lineNumber) raise Exception("Error finding nearest value for line %d" % lineNumber) + def getInterpolatedValue(self, lineNumber): - (prevValue,prevValueLine) = self.getNearestValue(lineNumber, lookForwards=False) - (nextValue,nextValueLine) = self.getNearestValue(lineNumber, lookForwards=True) + (prevValue, prevValueLine) = self.getNearestValue(lineNumber, lookForwards=False) + (nextValue, nextValueLine) = self.getNearestValue(lineNumber, lookForwards=True) if prevValueLine == nextValueLine: return prevValue - weight = (lineNumber-prevValueLine) / float(nextValueLine-prevValueLine) - return ((weight*prevValue) + ((1-weight)*nextValue)) + weight = (lineNumber - prevValueLine) / float(nextValueLine - prevValueLine) + return (weight * prevValue) + ((1 - weight) * nextValue) + def getIndexOf(self, lineNumber): '''returns the index within this channel's listData of the given lineNumber, or raises an Exception if not found''' - index = bisect.bisect_left(self.listData, (lineNumber,-99999)) - #print("INDEX of line %d: %d" % (lineNumber,index)) - #print("self.listData[index][0]: %d" % self.listData[index][0]) - if (self.listData[index][0] == lineNumber): + index = bisect.bisect_left(self.listData, (lineNumber, -99999)) + if self.listData[index][0] == lineNumber: return index else: raise Exception("Error finding index for line %d" % lineNumber) + class LogIterator: - '''Smart iterator that can move through a log by line number and maintain an index into the nearest values of all data channels''' - # TODO: LogIterator currently indexes the next available value rather than the nearest value, we should make it configurable between next/nearest + """ + Smart iterator that can move through a log by line number and maintain an index into the nearest values of all data + channels + """ + + # TODO: LogIterator currently indexes the next available value rather than the nearest value, we should make it + # configurable between next/nearest class LogIteratorSubValue: '''syntactic sugar to allow access by LogIterator[lineLabel][dataLabel]''' - logdata = None + + logdata = None iterators = None lineLabel = None + def __init__(self, logdata, iterators, lineLabel): self.logdata = logdata self.lineLabel = lineLabel self.iterators = iterators + def __getitem__(self, dataLabel): index = self.iterators[self.lineLabel][0] return self.logdata.channels[self.lineLabel][dataLabel].listData[index][1] - iterators = {} # lineLabel -> (listIndex,lineNumber) - logdata = None + iterators = {} # lineLabel -> (listIndex,lineNumber) + logdata = None currentLine = None def __init__(self, logdata, lineNumber=0): @@ -308,10 +344,13 @@ def __init__(self, logdata, lineNumber=0): if lineLabel in self.logdata.channels: self.iterators[lineLabel] = () self.jump(lineNumber) + def __iter__(self): return self + def __getitem__(self, lineLabel): return LogIterator.LogIteratorSubValue(self.logdata, self.iterators, lineLabel) + def next(self): '''increment iterator to next log line''' self.currentLine += 1 @@ -321,18 +360,23 @@ def next(self): # check if the currentLine has gone past our the line we're pointing to for this type of data dataLabel = self.logdata.formats[lineLabel].labels[0] (index, lineNumber) = self.iterators[lineLabel] - # if so, and it is not the last entry in the log, then increment the indices for all dataLabels under that lineLabel - if (self.currentLine > lineNumber) and (index < len(self.logdata.channels[lineLabel][dataLabel].listData)-1): + # if so, and it is not the last entry in the log, increment the indices for dataLabels under that lineLabel + if (self.currentLine > lineNumber) and ( + index < len(self.logdata.channels[lineLabel][dataLabel].listData) - 1 + ): index += 1 lineNumber = self.logdata.channels[lineLabel][dataLabel].listData[index][0] - self.iterators[lineLabel] = (index,lineNumber) + self.iterators[lineLabel] = (index, lineNumber) return self + + __next__ = next + def jump(self, lineNumber): '''jump iterator to specified log line''' self.currentLine = lineNumber for lineLabel in self.iterators.keys(): dataLabel = self.logdata.formats[lineLabel].labels[0] - (value,lineNumber) = self.logdata.channels[lineLabel][dataLabel].getNearestValue(self.currentLine) + (value, lineNumber) = self.logdata.channels[lineLabel][dataLabel].getNearestValue(self.currentLine) self.iterators[lineLabel] = (self.logdata.channels[lineLabel][dataLabel].getIndexOf(lineNumber), lineNumber) @@ -342,7 +386,7 @@ class DataflashLogHelper: @staticmethod def getTimeAtLine(logdata, lineNumber): '''returns the nearest GPS timestamp in milliseconds after the given line number''' - if not "GPS" in logdata.channels: + if "GPS" not in logdata.channels: raise Exception("no GPS log data found") # older logs use 'TIme', newer logs use 'TimeMS' # even newer logs use TimeUS @@ -363,12 +407,15 @@ def getTimeAtLine(logdata, lineNumber): @staticmethod def findLoiterChunks(logdata, minLengthSeconds=0, noRCInputs=True): - '''returns a list of (to,from) pairs defining sections of the log which are in loiter mode. Ordered from longest to shortest in time. If noRCInputs == True it only returns chunks with no control inputs''' + """ + Returns a list of (to, from) pairs defining sections of the log which are in loiter mode, ordered from longest + to shortest in time. If `noRCInputs == True` it only returns chunks with no control inputs + """ # TODO: implement noRCInputs handling when identifying stable loiter chunks, for now we're ignoring it def chunkSizeCompare(chunk1, chunk2): - chunk1Len = chunk1[1]-chunk1[0] - chunk2Len = chunk2[1]-chunk2[0] + chunk1Len = chunk1[1] - chunk1[0] + chunk2Len = chunk2[1] - chunk2[0] if chunk1Len == chunk2Len: return 0 elif chunk1Len > chunk2Len: @@ -376,22 +423,23 @@ def chunkSizeCompare(chunk1, chunk2): else: return 1 - od = collections.OrderedDict(sorted(logdata.modeChanges.items(), key=lambda t: t[0])) + changes = [{"line": k, "modeName": v[0], "modeNum": v[1]} for k, v in sorted(logdata.modeChanges.items())] chunks = [] - for i in range(len(od.keys())): - if od.values()[i][0] == "LOITER": - startLine = od.keys()[i] - endLine = None - if i == len(od.keys())-1: + for i in range(len(changes)): + if changes[i]["modeName"] == "LOITER": + startLine = changes[i]["line"] + try: + endLine = changes[i + 1]["line"] + except IndexError: endLine = logdata.lineCount - else: - endLine = od.keys()[i+1]-1 - chunkTimeSeconds = (DataflashLogHelper.getTimeAtLine(logdata,endLine)-DataflashLogHelper.getTimeAtLine(logdata,startLine)+1) / 1000.0 + chunkTimeSeconds = ( + DataflashLogHelper.getTimeAtLine(logdata, endLine) + - DataflashLogHelper.getTimeAtLine(logdata, startLine) + + 1 + ) / 1000.0 if chunkTimeSeconds > minLengthSeconds: - chunks.append((startLine,endLine)) - #print("LOITER chunk: %d to %d, %d lines" % (startLine,endLine,endLine-startLine+1)) - #print(" (time %d to %d, %d seconds)" % (DataflashLogHelper.getTimeAtLine(logdata,startLine), DataflashLogHelper.getTimeAtLine(logdata,endLine), chunkTimeSeconds)) - chunks.sort(chunkSizeCompare) + chunks.append((startLine, endLine)) + chunks.sort(key=lambda chunk: chunk[1] - chunk[0]) return chunks @staticmethod @@ -400,11 +448,11 @@ def isLogEmpty(logdata): # naive check for now, see if the throttle output was ever above 20% throttleThreshold = 20 if logdata.vehicleType == VehicleType.Copter: - throttleThreshold = 200 # copter uses 0-1000, plane+rover use 0-100 + throttleThreshold = 200 # copter uses 0-1000, plane+rover use 0-100 if "CTUN" in logdata.channels: try: maxThrottle = logdata.channels["CTUN"]["ThrOut"].max() - except KeyError as e: + except KeyError: # ThrOut was shorted to ThO at some stage... maxThrottle = logdata.channels["CTUN"]["ThO"].max() # at roughly the same time ThO became a range from 0 to 1 @@ -415,32 +463,35 @@ def isLogEmpty(logdata): class DataflashLog(object): - '''ArduPilot Dataflash log file reader and container class. Keep this simple, add more advanced or specific functions to DataflashLogHelper class''' + """ + ArduPilot Dataflash log file reader and container class. Keep this simple, add more advanced or specific functions + to DataflashLogHelper class + """ knownHardwareTypes = ["APM", "PX4", "MPNG"] def __init__(self, logfile=None, format="auto", ignoreBadlines=False): self.filename = None - self.vehicleType = None # from VehicleType enumeration; value derived from header - self.vehicleTypeString = None # set at same time has the enum value + self.vehicleType = None # from VehicleType enumeration; value derived from header + self.vehicleTypeString = None # set at same time has the enum value self.firmwareVersion = "" - self.firmwareHash = "" - self.freeRAM = 0 - self.hardwareType = "" # APM 1, APM 2, PX4, MPNG, etc What is VRBrain? BeagleBone, etc? Needs more testing - - self.formats = {} # name -> Format - self.parameters = {} # token -> value - self.messages = {} # lineNum -> message - self.modeChanges = {} # lineNum -> (mode,value) - self.channels = {} # lineLabel -> {dataLabel:Channel} - - self.filesizeKB = 0 + self.firmwareHash = "" + self.freeRAM = 0 + self.hardwareType = "" # APM 1, APM 2, PX4, MPNG, etc What is VRBrain? BeagleBone, etc? Needs more testing + + self.formats = {} # name -> Format + self.parameters = {} # token -> value + self.messages = {} # lineNum -> message + self.modeChanges = {} # lineNum -> (mode,value) + self.channels = {} # lineLabel -> {dataLabel:Channel} + + self.filesizeKB = 0 self.durationSecs = 0 - self.lineCount = 0 + self.lineCount = 0 self.skippedLines = 0 self.backpatch_these_modechanges = [] - self.frame = None + self.frame = None if logfile: self.read(logfile, format, ignoreBadlines) @@ -450,7 +501,7 @@ def getCopterType(self): if self.vehicleType != VehicleType.Copter: return None motLabels = [] - if "MOT" in self.formats: # not listed in PX4 log header for some reason? + if "MOT" in self.formats: # not listed in PX4 log header for some reason? motLabels = self.formats["MOT"].labels if "GGain" in motLabels: return "tradheli" @@ -471,20 +522,20 @@ def num_motor_channels(self): "OCTA": 8, "OCTA_QUAD": 8, "DECA": 10, -# "HELI": 1, -# "HELI_DUAL": 2, + # "HELI": 1, + # "HELI_DUAL": 2, "TRI": 3, "SINGLE": 1, "COAX": 2, "TAILSITTER": 1, - "DODECA_HEXA" : 12, + "DODECA_HEXA": 12, } return motor_channels_for_frame[self.frame] def read(self, logfile, format="auto", ignoreBadlines=False): '''returns on successful log read (including bad lines if ignoreBadlines==True), will throw an Exception otherwise''' # TODO: dataflash log parsing code is pretty hacky, should re-write more methodically - df_header = bytearray([0xa3, 0x95, 0x80, 0x80]) + df_header = bytearray([0xA3, 0x95, 0x80, 0x80]) self.filename = logfile if self.filename == '': f = sys.stdin @@ -498,7 +549,6 @@ def read(self, logfile, format="auto", ignoreBadlines=False): elif format == 'auto': if self.filename == '': # assuming TXT format -# raise ValueError("Invalid log format for stdin: {}".format(format)) head = "" else: head = f.read(4) @@ -513,22 +563,22 @@ def read(self, logfile, format="auto", ignoreBadlines=False): numBytes, lineNumber = self.read_text(f, ignoreBadlines) # gather some general stats about the log - self.lineCount = lineNumber + self.lineCount = lineNumber self.filesizeKB = numBytes / 1024.0 # TODO: switch duration calculation to use TimeMS values rather than GPS timestemp if "GPS" in self.channels: # the GPS time label changed at some point, need to handle both timeLabel = None - for i in 'TimeMS','TimeUS','Time': + for i in 'TimeMS', 'TimeUS', 'Time': if i in self.channels["GPS"]: timeLabel = i break firstTimeGPS = int(self.channels["GPS"][timeLabel].listData[0][1]) - lastTimeGPS = int(self.channels["GPS"][timeLabel].listData[-1][1]) + lastTimeGPS = int(self.channels["GPS"][timeLabel].listData[-1][1]) if timeLabel == 'TimeUS': firstTimeGPS /= 1000 lastTimeGPS /= 1000 - self.durationSecs = (lastTimeGPS-firstTimeGPS) / 1000 + self.durationSecs = (lastTimeGPS - firstTimeGPS) / 1000 # TODO: calculate logging rate based on timestamps # ... @@ -537,7 +587,7 @@ def read(self, logfile, format="auto", ignoreBadlines=False): "ArduCopter": VehicleType.Copter, "APM:Copter": VehicleType.Copter, "ArduPlane": VehicleType.Plane, - "ArduRover": VehicleType.Rover + "ArduRover": VehicleType.Rover, } # takes the vehicle type supplied via "MSG" and sets vehicleType from @@ -552,26 +602,26 @@ def set_vehicleType_from_MSG_vehicle(self, MSG_vehicle): def handleModeChange(self, lineNumber, e): if self.vehicleType == VehicleType.Copter: modes = { - 0:'STABILIZE', - 1:'ACRO', - 2:'ALT_HOLD', - 3:'AUTO', - 4:'GUIDED', - 5:'LOITER', - 6:'RTL', - 7:'CIRCLE', - 9:'LAND', - 10:'OF_LOITER', - 11:'DRIFT', - 13:'SPORT', - 14:'FLIP', - 15:'AUTOTUNE', - 16:'POSHOLD', - 17:'BRAKE', - 18:'THROW', - 19:'AVOID_ADSB', - 20:'GUIDED_NOGPS', - 21:'SMART_RTL', + 0: 'STABILIZE', + 1: 'ACRO', + 2: 'ALT_HOLD', + 3: 'AUTO', + 4: 'GUIDED', + 5: 'LOITER', + 6: 'RTL', + 7: 'CIRCLE', + 9: 'LAND', + 10: 'OF_LOITER', + 11: 'DRIFT', + 13: 'SPORT', + 14: 'FLIP', + 15: 'AUTOTUNE', + 16: 'POSHOLD', + 17: 'BRAKE', + 18: 'THROW', + 19: 'AVOID_ADSB', + 20: 'GUIDED_NOGPS', + 21: 'SMART_RTL', } try: if hasattr(e, 'ThrCrs'): @@ -579,7 +629,7 @@ def handleModeChange(self, lineNumber, e): else: # assume it has ModeNum: self.modeChanges[lineNumber] = (modes[int(e.Mode)], e.ModeNum) - except ValueError as x: + except ValueError: if hasattr(e, 'ThrCrs'): self.modeChanges[lineNumber] = (e.Mode, e.ThrCrs) else: @@ -599,7 +649,9 @@ def handleModeChange(self, lineNumber, e): else: # if you've gotten to here the chances are we don't # know what vehicle you're flying... - raise Exception("Unknown log type for MODE line vehicletype=({}) line=({})".format(self.vehicleTypeString, repr(e))) + raise Exception( + "Unknown log type for MODE line vehicletype=({}) line=({})".format(self.vehicleTypeString, repr(e)) + ) def backPatchModeChanges(self): for (lineNumber, e) in self.backpatch_these_modechanges: @@ -611,8 +663,8 @@ def set_frame(self, frame): def process(self, lineNumber, e): if e.NAME == 'FMT': cls = e.to_class() - if cls is not None: # FMT messages can be broken ... - if hasattr(e, 'type') and e.type not in self._formats: # binary log specific + if cls is not None: # FMT messages can be broken ... + if hasattr(e, 'type') and e.type not in self._formats: # binary log specific self._formats[e.type] = cls if cls.NAME not in self.formats: self.formats[cls.NAME] = cls @@ -625,7 +677,7 @@ def process(self, lineNumber, e): self.set_frame(tokens[1]) if not self.vehicleType: try: - self.set_vehicleType_from_MSG_vehicle(tokens[0]); + self.set_vehicleType_from_MSG_vehicle(tokens[0]) except ValueError: return self.backPatchModeChanges() @@ -636,7 +688,7 @@ def process(self, lineNumber, e): self.messages[lineNumber] = e.Message elif e.NAME == "MODE": if self.vehicleType is None: - self.backpatch_these_modechanges.append( (lineNumber, e) ) + self.backpatch_these_modechanges.append((lineNumber, e)) else: self.handleModeChange(lineNumber, e) # anything else must be the log data @@ -644,7 +696,7 @@ def process(self, lineNumber, e): groupName = e.NAME # first time seeing this type of log line, create the channel storage - if not groupName in self.channels: + if groupName not in self.channels: self.channels[groupName] = {} for label in e.labels: self.channels[groupName][label] = Channel() @@ -656,42 +708,46 @@ def process(self, lineNumber, e): channel.dictData[lineNumber] = value channel.listData.append((lineNumber, value)) - def read_text(self, f, ignoreBadlines): - self.formats = {'FMT':Format} + self.formats = {'FMT': Format} lineNumber = 0 numBytes = 0 knownHardwareTypes = ["APM", "PX4", "MPNG"] for line in f: lineNumber = lineNumber + 1 numBytes += len(line) + 1 + line = line.decode(encoding="utf-8") try: - #print("Reading line: %d" % lineNumber) line = line.strip('\n\r') tokens = line.split(', ') # first handle the log header lines if line == " Ready to drive." or line == " Ready to FLY.": continue if line == "----------------------------------------": # present in pre-3.0 logs - raise Exception("Log file seems to be in the older format (prior to self-describing logs), which isn't supported") + raise Exception( + "Log file seems to be in the older format (prior to self-describing logs), which isn't supported" + ) if len(tokens) == 1: tokens2 = line.split(' ') if line == "": pass - elif len(tokens2) == 1 and tokens2[0].isdigit(): # log index + elif len(tokens2) == 1 and tokens2[0].isdigit(): # log index pass elif len(tokens2) == 3 and tokens2[0] == "Free" and tokens2[1] == "RAM:": self.freeRAM = int(tokens2[2]) elif tokens2[0] in knownHardwareTypes: - self.hardwareType = line # not sure if we can parse this more usefully, for now only need to report it back verbatim - elif (len(tokens2) == 2 or len(tokens2) == 3) and tokens2[1][0].lower() == "v": # e.g. ArduCopter V3.1 (5c6503e2) + # not sure if we can parse this more usefully, for now only need to report it back verbatim + self.hardwareType = line + elif (len(tokens2) == 2 or len(tokens2) == 3) and tokens2[1][ + 0 + ].lower() == "v": # e.g. ArduCopter V3.1 (5c6503e2) try: self.set_vehicleType_from_MSG_vehicle(tokens2[0]) except ValueError: pass self.firmwareVersion = tokens2[1] if len(tokens2) == 3: - self.firmwareHash = tokens2[2][1:-1] + self.firmwareHash = tokens2[2][1:-1] else: errorMsg = "Error parsing line %d of log file: %s" % (lineNumber, self.filename) if ignoreBadlines: @@ -707,8 +763,10 @@ def read_text(self, f, ignoreBadlines): except Exception as e: print("BAD LINE: " + str(line), file=sys.stderr) if not ignoreBadlines: - raise Exception("Error parsing line %d of log file %s - %s" % (lineNumber,self.filename,e.args[0])) - return (numBytes,lineNumber) + raise Exception( + "Error parsing line %d of log file %s - %s" % (lineNumber, self.filename, e.args[0]) + ) + return (numBytes, lineNumber) def read_binary(self, f, ignoreBadlines): lineNumber = 0 @@ -718,22 +776,27 @@ def read_binary(self, f, ignoreBadlines): if e is None: continue numBytes += e.SIZE -# print(e) + # print(e) self.process(lineNumber, e) - return (numBytes,lineNumber) + return (numBytes, lineNumber) def _read_binary(self, f, ignoreBadlines): - self._formats = {128:BinaryFormat} + self._formats = {128: BinaryFormat} data = bytearray(f.read()) offset = 0 while len(data) > offset + ctypes.sizeof(logheader): h = logheader.from_buffer(data, offset) - if not (h.head1 == 0xa3 and h.head2 == 0x95): - if ignoreBadlines == False: + if not (h.head1 == 0xA3 and h.head2 == 0x95): + if ignoreBadlines is False: raise ValueError(h) else: - if h.head1 == 0xff and h.head2 == 0xff and h.msgid == 0xff: - print("Assuming EOF due to dataflash block tail filled with \\xff... (offset={off})".format(off=offset), file=sys.stderr) + if h.head1 == 0xFF and h.head2 == 0xFF and h.msgid == 0xFF: + print( + "Assuming EOF due to dataflash block tail filled with \\xff... (offset={off})".format( + off=offset + ), + file=sys.stderr, + ) break offset += 1 continue @@ -744,8 +807,12 @@ def _read_binary(self, f, ignoreBadlines): break try: e = typ.from_buffer(data, offset) - except: - print("data:{} offset:{} size:{} sizeof:{} sum:{}".format(len(data),offset,typ.SIZE,ctypes.sizeof(typ),offset+typ.SIZE)) + except ValueError: + print( + "data:{} offset:{} size:{} sizeof:{} sum:{}".format( + len(data), offset, typ.SIZE, ctypes.sizeof(typ), offset + typ.SIZE + ) + ) raise offset += typ.SIZE else: diff --git a/Tools/LogAnalyzer/LogAnalyzer.py b/Tools/LogAnalyzer/LogAnalyzer.py index a083df29f78..748cbe793b9 100755 --- a/Tools/LogAnalyzer/LogAnalyzer.py +++ b/Tools/LogAnalyzer/LogAnalyzer.py @@ -5,13 +5,15 @@ # Initial code by Andrew Chapman (amchapman@gmail.com), 16th Jan 2014 # +# AP_FLAKE8_CLEAN # some logging oddities noticed while doing this, to be followed up on: # - tradheli MOT labels Mot1,Mot2,Mot3,Mot4,GGain # - Pixhawk doesn't output one of the FMT labels... forget which one # - MAG offsets seem to be constant (only seen data on Pixhawk) # - MAG offsets seem to be cast to int before being output? (param is -84.67, logged as -84) -# - copter+plane use 'V' in their vehicle type/version/build line, rover uses lower case 'v'. Copter+Rover give a build number, plane does not +# - copter+plane use 'V' in their vehicle type/version/build line, rover uses lower case 'v'. +# Copter+Rover give a build number, plane does not # - CTUN.ThrOut on copter is 0-1000, on plane+rover it is 0-100 # TODO: add test for noisy baro values @@ -19,36 +21,41 @@ from __future__ import print_function -import DataflashLog - -import pprint # temp -import imp -import glob -import inspect -import os, sys import argparse import datetime +import glob +import os +import sys import time from xml.sax.saxutils import escape +import DataflashLog from VehicleType import VehicleType + class TestResult(object): '''all tests return a standardized result type''' + class StatusType: - # NA means not applicable for this log (e.g. copter tests against a plane log), UNKNOWN means it is missing data required for the test + # NA means not applicable for this log (e.g. copter tests against a plane log) + # UNKNOWN means it is missing data required for the test GOOD, FAIL, WARN, UNKNOWN, NA = range(5) + status = None - statusMessage = "" # can be multi-line + statusMessage = "" # can be multi-line class Test(object): - '''base class to be inherited by log tests. Each test should be quite granular so we have lots of small tests with clear results''' + """ + Base class to be inherited by log tests. Each test should be quite granular so we have lots of small tests with + clear results + """ + def __init__(self): - self.name = "" - self.result = None # will be an instance of TestResult after being run + self.name = "" + self.result = None # will be an instance of TestResult after being run self.execTime = None - self.enable = True + self.enable = True def run(self, logdata, verbose=False): pass @@ -56,24 +63,43 @@ def run(self, logdata, verbose=False): class TestSuite(object): '''registers test classes, loading using a basic plugin architecture, and can run them all in one run() operation''' + def __init__(self): - self.tests = [] + self.tests = [] self.logfile = None - self.logdata = None + self.logdata = None # dynamically load in Test subclasses from the 'tests' folder # to prevent one being loaded, move it out of that folder, or set that test's .enable attribute to False dirName = os.path.dirname(os.path.abspath(__file__)) testScripts = glob.glob(dirName + '/tests/*.py') - testClasses = [] + + def getTests(module_path): + import inspect + + tests = [] + module_name = os.path.basename(module_path)[:-3] + if sys.version_info >= (3, 5): + from importlib.util import spec_from_file_location, module_from_spec + + spec = spec_from_file_location(module_name, module_path) + m = module_from_spec(spec) + spec.loader.exec_module(m) + else: + from imp import load_source + + m = load_source(module_name, module_path) + for _, _class in inspect.getmembers(m, inspect.isclass): + if _class.__module__ == m.__name__: + tests.append(_class()) + return tests + for script in testScripts: - m = imp.load_source("m",script) - for name, obj in inspect.getmembers(m, inspect.isclass): - if name not in testClasses and inspect.getsourcefile(obj) == script: - testClasses.append(name) - self.tests.append(obj()) + self.tests.extend(getTests(script)) # and here's an example of explicitly loading a Test class if you wanted to do that - # m = imp.load_source("m", dirName + '/tests/TestBadParams.py') + # spec = importlib.util.spec_from_file_location("m", dirName + "/tests/TestBadParams.py") + # m = importlib.util.module_from_spec(spec) + # spec.loader.exec_module(m) # self.tests.append(m.TestBadParams()) def run(self, logdata, verbose): @@ -90,7 +116,7 @@ def run(self, logdata, verbose): startTime = time.time() test.run(self.logdata, verbose) # RUN THE TEST endTime = time.time() - test.execTime = 1000 * (endTime-startTime) + test.execTime = 1000 * (endTime - startTime) def outputPlainText(self, outputStats): '''output test results in plain text''' @@ -114,7 +140,7 @@ def outputPlainText(self, outputStats): if not test.enable: continue statusMessageFirstLine = test.result.statusMessage.strip('\n\r').split('\n')[0] - statusMessageExtra = test.result.statusMessage.strip('\n\r').split('\n')[1:] + statusMessageExtra = test.result.statusMessage.strip('\n\r').split('\n')[1:] execTime = "" if outputStats: execTime = " (%6.2fms)" % (test.execTime) @@ -129,12 +155,15 @@ def outputPlainText(self, outputStats): continue else: print(" %20s: UNKNOWN %-55s%s" % (test.name, statusMessageFirstLine, execTime)) - #if statusMessageExtra: + # if statusMessageExtra: for line in statusMessageExtra: - print(" %29s %s" % ("",line)) + print(" %29s %s" % ("", line)) print('\n') - print('The Log Analyzer is currently BETA code.\nFor any support or feedback on the log analyzer please email Andrew Chapman (amchapman@gmail.com)') + print( + "The Log Analyzer is currently BETA code." + "\nFor any support or feedback on the log analyzer please email Andrew Chapman (amchapman@gmail.com)" + ) print('\n') def outputXML(self, xmlFile): @@ -147,22 +176,21 @@ def outputXML(self, xmlFile): xml = sys.stdout else: xml = open(xmlFile, 'w') - except: + except IOError: sys.stderr.write("Error opening output xml file: %s" % xmlFile) sys.exit(1) - # output header info xml.write("\n") xml.write("\n") xml.write("
\n") - xml.write(" " + escape(self.logfile) + "\n") - xml.write(" " + escape(repr(self.logdata.filesizeKB)) + "\n") + xml.write(" " + escape(self.logfile) + "\n") + xml.write(" " + escape(repr(self.logdata.filesizeKB)) + "\n") xml.write(" " + escape(repr(self.logdata.lineCount)) + "\n") - xml.write(" " + escape(str(datetime.timedelta(seconds=self.logdata.durationSecs))) + "\n") + xml.write(" " + escape(str(datetime.timedelta(seconds=self.logdata.durationSecs))) + "\n") xml.write(" " + escape(self.logdata.vehicleTypeString) + "\n") if self.logdata.vehicleType == VehicleType.Copter and self.logdata.getCopterType(): - xml.write(" " + escape(self.logdata.getCopterType()) + "\n") + xml.write(" " + escape(self.logdata.getCopterType()) + "\n") xml.write(" " + escape(self.logdata.firmwareVersion) + "\n") xml.write(" " + escape(self.logdata.firmwareHash) + "\n") xml.write(" " + escape(self.logdata.hardwareType) + "\n") @@ -173,7 +201,7 @@ def outputXML(self, xmlFile): # output parameters xml.write("\n") for param, value in self.logdata.parameters.items(): - xml.write(" \n" % (param,escape(repr(value)))) + xml.write(" \n" % (param, escape(repr(value)))) xml.write("\n") # output test results @@ -212,26 +240,50 @@ def outputXML(self, xmlFile): def main(): - dirName = os.path.dirname(os.path.abspath(__file__)) - # deal with command line arguments parser = argparse.ArgumentParser(description='Analyze an APM Dataflash log for known issues') parser.add_argument('logfile', type=argparse.FileType('r'), help='path to Dataflash log file (or - for stdin)') - parser.add_argument('-f', '--format', metavar='', type=str, action='store', choices=['bin','log','auto'], default='auto', help='log file format: \'bin\',\'log\' or \'auto\'') - parser.add_argument('-q', '--quiet', metavar='', action='store_const', const=True, help='quiet mode, do not print results') - parser.add_argument('-p', '--profile', metavar='', action='store_const', const=True, help='output performance profiling data') - parser.add_argument('-s', '--skip_bad', metavar='', action='store_const', const=True, help='skip over corrupt dataflash lines') - parser.add_argument('-e', '--empty', metavar='', action='store_const', const=True, help='run an initial check for an empty log') - parser.add_argument('-x', '--xml', type=str, metavar='XML file', nargs='?', const='', default='', help='write output to specified XML file (or - for stdout)') + parser.add_argument( + '-f', + '--format', + metavar='', + type=str, + action='store', + choices=['bin', 'log', 'auto'], + default='auto', + help='log file format: \'bin\',\'log\' or \'auto\'', + ) + parser.add_argument( + '-q', '--quiet', metavar='', action='store_const', const=True, help='quiet mode, do not print results' + ) + parser.add_argument( + '-p', '--profile', metavar='', action='store_const', const=True, help='output performance profiling data' + ) + parser.add_argument( + '-s', '--skip_bad', metavar='', action='store_const', const=True, help='skip over corrupt dataflash lines' + ) + parser.add_argument( + '-e', '--empty', metavar='', action='store_const', const=True, help='run an initial check for an empty log' + ) + parser.add_argument( + '-x', + '--xml', + type=str, + metavar='XML file', + nargs='?', + const='', + default='', + help='write output to specified XML file (or - for stdout)', + ) parser.add_argument('-v', '--verbose', metavar='', action='store_const', const=True, help='verbose output') args = parser.parse_args() # load the log startTime = time.time() - logdata = DataflashLog.DataflashLog(args.logfile.name, format=args.format, ignoreBadlines=args.skip_bad) # read log + logdata = DataflashLog.DataflashLog(args.logfile.name, format=args.format, ignoreBadlines=args.skip_bad) # read log endTime = time.time() if args.profile: - print("Log file read time: %.2f seconds" % (endTime-startTime)) + print("Log file read time: %.2f seconds" % (endTime - startTime)) # check for empty log if requested if args.empty: @@ -240,13 +292,13 @@ def main(): sys.stderr.write("Empty log file: %s, %s" % (logdata.filename, emptyErr)) sys.exit(1) - #run the tests, and gather timings + # run the tests, and gather timings testSuite = TestSuite() startTime = time.time() testSuite.run(logdata, args.verbose) # run tests endTime = time.time() if args.profile: - print("Test suite run time: %.2f seconds" % (endTime-startTime)) + print("Test suite run time: %.2f seconds" % (endTime - startTime)) # deal with output if not args.quiet: @@ -259,4 +311,3 @@ def main(): if __name__ == "__main__": main() - diff --git a/Tools/LogAnalyzer/UnitTest.py b/Tools/LogAnalyzer/UnitTest.py index 7c414d5ccb0..4f94a2eeecf 100755 --- a/Tools/LogAnalyzer/UnitTest.py +++ b/Tools/LogAnalyzer/UnitTest.py @@ -5,74 +5,400 @@ # # +# AP_FLAKE8_CLEAN + # TODO: implement more unit+regression tests from __future__ import print_function -import DataflashLog import traceback + +import DataflashLog from VehicleType import VehicleType try: - # test DataflashLog reading 1 - logdata = DataflashLog.DataflashLog() - logdata.read("examples/robert_lefebvre_octo_PM.log", ignoreBadlines=False) - assert(logdata.filename == "examples/robert_lefebvre_octo_PM.log") - assert(logdata.vehicleType == VehicleType.Copter) - assert(logdata.vehicleTypeString == "ArduCopter") - assert(logdata.firmwareVersion == "V3.0.1") - assert(logdata.firmwareHash == "5c6503e2") - assert(logdata.freeRAM == 1331) - assert(logdata.hardwareType == "APM 2") - assert(len(logdata.formats) == 27) - assert(logdata.formats['GPS'].labels == ['Status', 'Time', 'NSats', 'HDop', 'Lat', 'Lng', 'RelAlt', 'Alt', 'Spd', 'GCrs']) - assert(logdata.formats['ATT'].labels == ['RollIn', 'Roll', 'PitchIn', 'Pitch', 'YawIn', 'Yaw', 'NavYaw']) - assert(logdata.parameters == {'RC7_REV': 1.0, 'MNT_MODE': 3.0, 'LOITER_LON_P': 1.0, 'FLTMODE1': 1.0, 'FLTMODE3': 0.0, 'FLTMODE2': 6.0, 'TUNE_HIGH': 10000.0, 'FLTMODE4': 5.0, 'FLTMODE6': 2.0, 'SYSID_SW_TYPE': 10.0, 'LOITER_LON_D': 0.0, 'RC5_REV': 1.0, 'THR_RATE_IMAX': 300.0, 'MNT_RC_IN_PAN': 0.0, 'RC2_MIN': 1110.0, 'LOITER_LON_I': 0.5, 'HLD_LON_P': 1.0, 'STB_RLL_I': 0.0, 'LOW_VOLT': 10.5, 'MNT_CONTROL_Y': 0.0, 'MNT_CONTROL_X': 0.0, 'FRAME': 1.0, 'MNT_CONTROL_Z': 0.0, 'OF_PIT_IMAX': 100.0, 'AHRS_ORIENTATION': 0.0, 'SIMPLE': 0.0, 'RC2_MAX': 1929.0, 'MNT_JSTICK_SPD': 0.0, 'RC8_FUNCTION': 0.0, 'INS_ACCSCAL_X': 0.992788, 'ACRO_P': 4.5, 'MNT_ANGMIN_ROL': -4500.0, 'OF_RLL_P': 2.5, 'STB_RLL_P': 3.5, 'STB_YAW_P': 3.0, 'SR0_RAW_SENS': 2.0, 'FLTMODE5': 0.0, 'RATE_YAW_I': 0.02, 'MAG_ENABLE': 1.0, 'MNT_RETRACT_Y': 0.0, 'MNT_RETRACT_X': 0.0, 'RATE_YAW_IMAX': 800.0, 'WPNAV_SPEED_DN': 150.0, 'WP_YAW_BEHAVIOR': 2.0, 'RC11_REV': 1.0, 'SYSID_THISMAV': 1.0, 'SR0_EXTRA1': 10.0, 'SR0_EXTRA2': 10.0, 'ACRO_BAL_PITCH': 200.0, 'STB_YAW_I': 0.0, 'INS_ACCSCAL_Z': 0.97621, 'INS_ACCSCAL_Y': 1.00147, 'LED_MODE': 9.0, 'FS_GCS_ENABLE': 0.0, 'MNT_RC_IN_ROLL': 0.0, 'INAV_TC_Z': 8.0, 'RATE_PIT_IMAX': 4500.0, 'HLD_LON_IMAX': 3000.0, 'THR_RATE_I': 0.0, 'SR3_EXTRA1': 0.0, 'STB_PIT_IMAX': 800.0, 'AHRS_TRIM_Z': 0.0, 'RC2_REV': 1.0, 'INS_MPU6K_FILTER': 20.0, 'THR_MIN': 130.0, 'AHRS_TRIM_Y': 0.021683, 'RC11_DZ': 0.0, 'THR_MAX': 1000.0, 'SR3_EXTRA2': 0.0, 'MNT_NEUTRAL_Z': 0.0, 'THR_MID': 300.0, 'MNT_NEUTRAL_X': 0.0, 'AMP_PER_VOLT': 18.002001, 'SR0_POSITION': 3.0, 'MNT_STAB_PAN': 0.0, 'FS_BATT_ENABLE': 0.0, 'LAND_SPEED': 50.0, 'OF_PIT_D': 0.12, 'SR0_PARAMS': 50.0, 'COMPASS_ORIENT': 0.0, 'WPNAV_ACCEL': 200.0, 'THR_ACCEL_IMAX': 5000.0, 'SR3_POSITION': 0.0, 'WPNAV_RADIUS': 100.0, 'WP_TOTAL': 14.0, 'RC8_MAX': 1856.0, 'OF_PIT_P': 2.5, 'SR3_RAW_SENS': 0.0, 'RTL_ALT_FINAL': 0.0, 'SR3_PARAMS': 0.0, 'SR0_EXTRA3': 2.0, 'LOITER_LAT_I': 0.5, 'RC6_DZ': 0.0, 'RC4_TRIM': 1524.0, 'RATE_RLL_P': 0.07, 'LOITER_LAT_D': 0.0, 'STB_PIT_P': 3.5, 'OF_PIT_I': 0.5, 'RATE_RLL_I': 1.0, 'AHRS_TRIM_X': 0.003997, 'RC3_REV': 1.0, 'STB_PIT_I': 0.0, 'FS_THR_ENABLE': 0.0, 'LOITER_LAT_P': 1.0, 'AHRS_RP_P': 0.1, 'FENCE_ACTION': 1.0, 'TOY_RATE': 1.0, 'RATE_RLL_D': 0.006, 'RC5_MIN': 1151.0, 'RC5_TRIM': 1676.0, 'STB_RLL_IMAX': 800.0, 'RC4_DZ': 40.0, 'AHRS_YAW_P': 0.1, 'RC11_TRIM': 1500.0, 'MOT_TCRV_ENABLE': 1.0, 'CAM_TRIGG_TYPE': 1.0, 'STB_YAW_IMAX': 800.0, 'RC4_MAX': 1942.0, 'LOITER_LAT_IMAX': 400.0, 'CH7_OPT': 9.0, 'RC11_FUNCTION': 7.0, 'SR0_EXT_STAT': 2.0, 'SONAR_TYPE': 0.0, 'RC3_MAX': 1930.0, 'RATE_YAW_D': 0.0, 'FENCE_ALT_MAX': 30.0, 'COMPASS_MOT_Y': 0.0, 'AXIS_ENABLE': 1.0, 'FENCE_ENABLE': 0.0, 'RC10_DZ': 0.0, 'PILOT_VELZ_MAX': 250.0, 'BATT_CAPACITY': 1760.0, 'FS_THR_VALUE': 975.0, 'RC4_MIN': 1115.0, 'MNT_ANGMAX_TIL': 4500.0, 'RTL_LOIT_TIME': 5000.0, 'ARMING_CHECK': 1.0, 'THR_RATE_P': 6.0, 'OF_RLL_IMAX': 100.0, 'RC6_MIN': 971.0, 'SR0_RAW_CTRL': 0.0, 'RC6_MAX': 2078.0, 'RC5_MAX': 1829.0, 'LOITER_LON_IMAX': 400.0, 'MNT_STAB_TILT': 0.0, 'MOT_TCRV_MIDPCT': 52.0, 'COMPASS_OFS_Z': -5.120774, 'COMPASS_OFS_Y': 46.709824, 'COMPASS_OFS_X': -20.490345, 'THR_ALT_I': 0.0, 'RC10_TRIM': 1500.0, 'INS_PRODUCT_ID': 88.0, 'RC11_MIN': 1100.0, 'FS_GPS_ENABLE': 1.0, 'HLD_LAT_IMAX': 3000.0, 'RC3_TRIM': 1476.0, 'RC6_FUNCTION': 0.0, 'TRIM_THROTTLE': 260.0, 'MNT_STAB_ROLL': 0.0, 'INAV_TC_XY': 2.5, 'RC1_DZ': 30.0, 'MNT_RETRACT_Z': 0.0, 'THR_ACC_ENABLE': 1.0, 'LOG_BITMASK': 830.0, 'TUNE_LOW': 0.0, 'CIRCLE_RATE': 5.0, 'CAM_DURATION': 10.0, 'MNT_NEUTRAL_Y': 0.0, 'RC10_MIN': 1100.0, 'INS_ACCOFFS_X': -0.019376, 'THR_RATE_D': 0.0, 'INS_ACCOFFS_Z': 1.370947, 'RC4_REV': 1.0, 'CIRCLE_RADIUS': 10.0, 'RATE_RLL_IMAX': 4500.0, 'HLD_LAT_P': 1.0, 'AHRS_GPS_MINSATS': 6.0, 'FLOW_TYPE': 0.0, 'RC8_REV': 1.0, 'SONAR_GAIN': 0.2, 'RC2_TRIM': 1521.0, 'WP_INDEX': 0.0, 'RC1_REV': 1.0, 'RC7_DZ': 0.0, 'AHRS_GPS_USE': 1.0, 'MNT_ANGMIN_PAN': -4500.0, 'SR3_RC_CHAN': 0.0, 'COMPASS_LEARN': 0.0, 'ACRO_TRAINER': 1.0, 'CAM_SERVO_OFF': 1100.0, 'RC5_DZ': 0.0, 'SCHED_DEBUG': 0.0, 'RC11_MAX': 1900.0, 'AHRS_WIND_MAX': 0.0, 'SR3_EXT_STAT': 0.0, 'MNT_ANGMAX_PAN': 4500.0, 'MNT_ANGMAX_ROL': 4500.0, 'RC_SPEED': 490.0, 'SUPER_SIMPLE': 0.0, 'VOLT_DIVIDER': 10.0, 'COMPASS_MOTCT': 0.0, 'SR3_RAW_CTRL': 0.0, 'SONAR_ENABLE': 0.0, 'INS_ACCOFFS_Y': 0.362242, 'SYSID_SW_MREV': 120.0, 'WPNAV_LOIT_SPEED': 1000.0, 'BATT_MONITOR': 4.0, 'MNT_RC_IN_TILT': 8.0, 'CH8_OPT': 0.0, 'RTL_ALT': 1000.0, 'SR0_RC_CHAN': 2.0, 'RC1_MIN': 1111.0, 'RSSI_PIN': -1.0, 'MOT_TCRV_MAXPCT': 93.0, 'GND_ABS_PRESS': 101566.97, 'RC1_MAX': 1936.0, 'FENCE_TYPE': 3.0, 'RC5_FUNCTION': 0.0, 'OF_RLL_D': 0.12, 'BATT_VOLT_PIN': 13.0, 'WPNAV_SPEED': 1000.0, 'RC7_MAX': 1884.0, 'CAM_SERVO_ON': 1300.0, 'RATE_PIT_I': 1.0, 'RC7_MIN': 969.0, 'AHRS_COMP_BETA': 0.1, 'OF_RLL_I': 0.5, 'COMPASS_DEC': 0.0, 'RC3_MIN': 1113.0, 'RC2_DZ': 30.0, 'FENCE_RADIUS': 30.0, 'HLD_LON_I': 0.0, 'ACRO_BAL_ROLL': 200.0, 'COMPASS_AUTODEC': 1.0, 'SR3_EXTRA3': 0.0, 'COMPASS_USE': 1.0, 'RC10_MAX': 1900.0, 'RATE_PIT_P': 0.07, 'GND_TEMP': 21.610104, 'RC7_TRIM': 970.0, 'RC10_REV': 1.0, 'RATE_YAW_P': 0.2, 'THR_ALT_P': 1.0, 'RATE_PIT_D': 0.006, 'ESC': 0.0, 'MNT_ANGMIN_TIL': -4500.0, 'SERIAL3_BAUD': 57.0, 'RC8_MIN': 968.0, 'THR_ALT_IMAX': 300.0, 'SYSID_MYGCS': 255.0, 'INS_GYROFFS_Y': 0.581989, 'TUNE': 0.0, 'RC8_TRIM': 970.0, 'RC3_DZ': 30.0, 'AHRS_GPS_GAIN': 1.0, 'THR_ACCEL_D': 0.0, 'TELEM_DELAY': 0.0, 'THR_ACCEL_I': 0.5, 'COMPASS_MOT_X': 0.0, 'COMPASS_MOT_Z': 0.0, 'RC10_FUNCTION': 0.0, 'INS_GYROFFS_X': -0.001698, 'INS_GYROFFS_Z': 0.01517, 'RC6_TRIM': 1473.0, 'THR_ACCEL_P': 1.2, 'RC8_DZ': 0.0, 'HLD_LAT_I': 0.0, 'RC7_FUNCTION': 0.0, 'RC6_REV': 1.0, 'BATT_CURR_PIN': 12.0, 'WPNAV_SPEED_UP': 250.0, 'RC1_TRIM': 1524.0}) - assert(logdata.messages == {}) - assert(logdata.modeChanges == {2204: ('LOITER', 269), 4594: ('STABILIZE', 269), 644: ('ALT_HOLD', 269), 4404: ('ALT_HOLD', 269)}) - assert(logdata.channels['GPS']['NSats'].min() == 6) - assert(logdata.channels['GPS']['NSats'].max() == 8) - assert(logdata.channels['GPS']['HDop'].listData[0] == (552, 4.68)) - assert(logdata.channels['GPS']['HDop'].listData[44] == (768, 4.67)) - assert(logdata.channels['GPS']['HDop'].listData[157] == (1288, 2.28)) - assert(logdata.channels['CTUN']['ThrOut'].listData[5] == (321, 139)) - assert(logdata.channels['CTUN']['ThrOut'].listData[45] == (409, 242)) - assert(logdata.channels['CTUN']['ThrOut'].listData[125] == (589, 266)) - assert(logdata.channels['CTUN']['CRate'].listData[3] == (317, 35)) - assert(logdata.channels['CTUN']['CRate'].listData[51] == (421, 31)) - assert(logdata.channels['CTUN']['CRate'].listData[115] == (563, -8)) - assert(int(logdata.filesizeKB) == 307) - assert(logdata.durationSecs == 155) - assert(logdata.lineCount == 4750) - - # test LogIterator class - lit = DataflashLog.LogIterator(logdata) - assert(lit.currentLine == 0) - assert(lit.iterators == {'CURR': (0, 310), 'ERR': (0, 307), 'NTUN': (0, 2206), 'CTUN': (0, 308), 'GPS': (0, 552), 'CMD': (0, 607), 'D32': (0, 305), 'ATT': (0, 311), 'EV': (0, 306), 'DU32': (0, 309), 'PM': (0, 479)}) - lit.jump(500) - assert(lit.iterators == {'CURR': (9, 514), 'ERR': (1, 553), 'NTUN': (0, 2206), 'CTUN': (87, 500), 'GPS': (0, 552), 'CMD': (0, 607), 'D32': (0, 305), 'ATT': (83, 501), 'EV': (4, 606), 'DU32': (9, 513), 'PM': (1, 719)}) - assert(lit['CTUN']['ThrIn'] == 450) - assert(lit['ATT']['RollIn'] == 11.19) - assert(lit['CURR']['CurrTot'] == 25.827288) - assert(lit['D32']['Value'] == 11122) - next(lit) - assert(lit.iterators == {'CURR': (9, 514), 'ERR': (1, 553), 'NTUN': (0, 2206), 'CTUN': (88, 502), 'GPS': (0, 552), 'CMD': (0, 607), 'D32': (0, 305), 'ATT': (83, 501), 'EV': (4, 606), 'DU32': (9, 513), 'PM': (1, 719)}) - lit.jump(4750) - next(lit) - assert(lit.currentLine == 4751) - assert(lit['ATT']['Roll'] == 2.99) - + # test DataflashLog reading 1 + logdata = DataflashLog.DataflashLog() + logdata.read("examples/robert_lefebvre_octo_PM.log", ignoreBadlines=False) + assert logdata.filename == "examples/robert_lefebvre_octo_PM.log" + assert logdata.vehicleType == VehicleType.Copter + assert logdata.vehicleTypeString == "ArduCopter" + assert logdata.firmwareVersion == "V3.0.1" + assert logdata.firmwareHash == "5c6503e2" + assert logdata.freeRAM == 1331 + assert logdata.hardwareType == "APM 2" + assert len(logdata.formats) == 27 + assert logdata.formats['GPS'].labels == [ + 'Status', + 'Time', + 'NSats', + 'HDop', + 'Lat', + 'Lng', + 'RelAlt', + 'Alt', + 'Spd', + 'GCrs', + ] + assert logdata.formats['ATT'].labels == ['RollIn', 'Roll', 'PitchIn', 'Pitch', 'YawIn', 'Yaw', 'NavYaw'] + assert logdata.parameters == { + 'RC7_REV': 1.0, + 'MNT_MODE': 3.0, + 'LOITER_LON_P': 1.0, + 'FLTMODE1': 1.0, + 'FLTMODE3': 0.0, + 'FLTMODE2': 6.0, + 'TUNE_HIGH': 10000.0, + 'FLTMODE4': 5.0, + 'FLTMODE6': 2.0, + 'SYSID_SW_TYPE': 10.0, + 'LOITER_LON_D': 0.0, + 'RC5_REV': 1.0, + 'THR_RATE_IMAX': 300.0, + 'MNT_RC_IN_PAN': 0.0, + 'RC2_MIN': 1110.0, + 'LOITER_LON_I': 0.5, + 'HLD_LON_P': 1.0, + 'STB_RLL_I': 0.0, + 'LOW_VOLT': 10.5, + 'MNT_CONTROL_Y': 0.0, + 'MNT_CONTROL_X': 0.0, + 'FRAME': 1.0, + 'MNT_CONTROL_Z': 0.0, + 'OF_PIT_IMAX': 100.0, + 'AHRS_ORIENTATION': 0.0, + 'SIMPLE': 0.0, + 'RC2_MAX': 1929.0, + 'RC8_FUNCTION': 0.0, + 'INS_ACCSCAL_X': 0.992788, + 'ACRO_P': 4.5, + 'MNT_ANGMIN_ROL': -4500.0, + 'OF_RLL_P': 2.5, + 'STB_RLL_P': 3.5, + 'STB_YAW_P': 3.0, + 'SR0_RAW_SENS': 2.0, + 'FLTMODE5': 0.0, + 'RATE_YAW_I': 0.02, + 'MAG_ENABLE': 1.0, + 'MNT_RETRACT_Y': 0.0, + 'MNT_RETRACT_X': 0.0, + 'RATE_YAW_IMAX': 800.0, + 'WPNAV_SPEED_DN': 150.0, + 'WP_YAW_BEHAVIOR': 2.0, + 'RC11_REV': 1.0, + 'SYSID_THISMAV': 1.0, + 'SR0_EXTRA1': 10.0, + 'SR0_EXTRA2': 10.0, + 'ACRO_BAL_PITCH': 200.0, + 'STB_YAW_I': 0.0, + 'INS_ACCSCAL_Z': 0.97621, + 'INS_ACCSCAL_Y': 1.00147, + 'LED_MODE': 9.0, + 'FS_GCS_ENABLE': 0.0, + 'MNT_RC_IN_ROLL': 0.0, + 'INAV_TC_Z': 8.0, + 'RATE_PIT_IMAX': 4500.0, + 'HLD_LON_IMAX': 3000.0, + 'THR_RATE_I': 0.0, + 'SR3_EXTRA1': 0.0, + 'STB_PIT_IMAX': 800.0, + 'AHRS_TRIM_Z': 0.0, + 'RC2_REV': 1.0, + 'INS_MPU6K_FILTER': 20.0, + 'THR_MIN': 130.0, + 'AHRS_TRIM_Y': 0.021683, + 'RC11_DZ': 0.0, + 'THR_MAX': 1000.0, + 'SR3_EXTRA2': 0.0, + 'MNT_NEUTRAL_Z': 0.0, + 'THR_MID': 300.0, + 'MNT_NEUTRAL_X': 0.0, + 'AMP_PER_VOLT': 18.002001, + 'SR0_POSITION': 3.0, + 'MNT_STAB_PAN': 0.0, + 'FS_BATT_ENABLE': 0.0, + 'LAND_SPEED': 50.0, + 'OF_PIT_D': 0.12, + 'SR0_PARAMS': 50.0, + 'COMPASS_ORIENT': 0.0, + 'WPNAV_ACCEL': 200.0, + 'THR_ACCEL_IMAX': 5000.0, + 'SR3_POSITION': 0.0, + 'WPNAV_RADIUS': 100.0, + 'WP_TOTAL': 14.0, + 'RC8_MAX': 1856.0, + 'OF_PIT_P': 2.5, + 'SR3_RAW_SENS': 0.0, + 'RTL_ALT_FINAL': 0.0, + 'SR3_PARAMS': 0.0, + 'SR0_EXTRA3': 2.0, + 'LOITER_LAT_I': 0.5, + 'RC6_DZ': 0.0, + 'RC4_TRIM': 1524.0, + 'RATE_RLL_P': 0.07, + 'LOITER_LAT_D': 0.0, + 'STB_PIT_P': 3.5, + 'OF_PIT_I': 0.5, + 'RATE_RLL_I': 1.0, + 'AHRS_TRIM_X': 0.003997, + 'RC3_REV': 1.0, + 'STB_PIT_I': 0.0, + 'FS_THR_ENABLE': 0.0, + 'LOITER_LAT_P': 1.0, + 'AHRS_RP_P': 0.1, + 'FENCE_ACTION': 1.0, + 'TOY_RATE': 1.0, + 'RATE_RLL_D': 0.006, + 'RC5_MIN': 1151.0, + 'RC5_TRIM': 1676.0, + 'STB_RLL_IMAX': 800.0, + 'RC4_DZ': 40.0, + 'AHRS_YAW_P': 0.1, + 'RC11_TRIM': 1500.0, + 'MOT_TCRV_ENABLE': 1.0, + 'CAM_TRIGG_TYPE': 1.0, + 'STB_YAW_IMAX': 800.0, + 'RC4_MAX': 1942.0, + 'LOITER_LAT_IMAX': 400.0, + 'CH7_OPT': 9.0, + 'RC11_FUNCTION': 7.0, + 'SR0_EXT_STAT': 2.0, + 'SONAR_TYPE': 0.0, + 'RC3_MAX': 1930.0, + 'RATE_YAW_D': 0.0, + 'FENCE_ALT_MAX': 30.0, + 'COMPASS_MOT_Y': 0.0, + 'AXIS_ENABLE': 1.0, + 'FENCE_ENABLE': 0.0, + 'RC10_DZ': 0.0, + 'PILOT_VELZ_MAX': 250.0, + 'BATT_CAPACITY': 1760.0, + 'FS_THR_VALUE': 975.0, + 'RC4_MIN': 1115.0, + 'MNT_ANGMAX_TIL': 4500.0, + 'RTL_LOIT_TIME': 5000.0, + 'ARMING_CHECK': 1.0, + 'THR_RATE_P': 6.0, + 'OF_RLL_IMAX': 100.0, + 'RC6_MIN': 971.0, + 'SR0_RAW_CTRL': 0.0, + 'RC6_MAX': 2078.0, + 'RC5_MAX': 1829.0, + 'LOITER_LON_IMAX': 400.0, + 'MNT_STAB_TILT': 0.0, + 'MOT_TCRV_MIDPCT': 52.0, + 'COMPASS_OFS_Z': -5.120774, + 'COMPASS_OFS_Y': 46.709824, + 'COMPASS_OFS_X': -20.490345, + 'THR_ALT_I': 0.0, + 'RC10_TRIM': 1500.0, + 'INS_PRODUCT_ID': 88.0, + 'RC11_MIN': 1100.0, + 'FS_GPS_ENABLE': 1.0, + 'HLD_LAT_IMAX': 3000.0, + 'RC3_TRIM': 1476.0, + 'RC6_FUNCTION': 0.0, + 'TRIM_THROTTLE': 260.0, + 'MNT_STAB_ROLL': 0.0, + 'INAV_TC_XY': 2.5, + 'RC1_DZ': 30.0, + 'MNT_RETRACT_Z': 0.0, + 'THR_ACC_ENABLE': 1.0, + 'LOG_BITMASK': 830.0, + 'TUNE_LOW': 0.0, + 'CIRCLE_RATE': 5.0, + 'CAM_DURATION': 10.0, + 'MNT_NEUTRAL_Y': 0.0, + 'RC10_MIN': 1100.0, + 'INS_ACCOFFS_X': -0.019376, + 'THR_RATE_D': 0.0, + 'INS_ACCOFFS_Z': 1.370947, + 'RC4_REV': 1.0, + 'CIRCLE_RADIUS': 10.0, + 'RATE_RLL_IMAX': 4500.0, + 'HLD_LAT_P': 1.0, + 'AHRS_GPS_MINSATS': 6.0, + 'RC8_REV': 1.0, + 'SONAR_GAIN': 0.2, + 'RC2_TRIM': 1521.0, + 'WP_INDEX': 0.0, + 'RC1_REV': 1.0, + 'RC7_DZ': 0.0, + 'AHRS_GPS_USE': 1.0, + 'MNT_ANGMIN_PAN': -4500.0, + 'SR3_RC_CHAN': 0.0, + 'COMPASS_LEARN': 0.0, + 'ACRO_TRAINER': 1.0, + 'CAM_SERVO_OFF': 1100.0, + 'RC5_DZ': 0.0, + 'SCHED_DEBUG': 0.0, + 'RC11_MAX': 1900.0, + 'AHRS_WIND_MAX': 0.0, + 'SR3_EXT_STAT': 0.0, + 'MNT_ANGMAX_PAN': 4500.0, + 'MNT_ANGMAX_ROL': 4500.0, + 'RC_SPEED': 490.0, + 'SUPER_SIMPLE': 0.0, + 'VOLT_DIVIDER': 10.0, + 'COMPASS_MOTCT': 0.0, + 'SR3_RAW_CTRL': 0.0, + 'SONAR_ENABLE': 0.0, + 'INS_ACCOFFS_Y': 0.362242, + 'SYSID_SW_MREV': 120.0, + 'WPNAV_LOIT_SPEED': 1000.0, + 'BATT_MONITOR': 4.0, + 'MNT_RC_IN_TILT': 8.0, + 'CH8_OPT': 0.0, + 'RTL_ALT': 1000.0, + 'SR0_RC_CHAN': 2.0, + 'RC1_MIN': 1111.0, + 'RSSI_PIN': -1.0, + 'MOT_TCRV_MAXPCT': 93.0, + 'GND_ABS_PRESS': 101566.97, + 'RC1_MAX': 1936.0, + 'FENCE_TYPE': 3.0, + 'RC5_FUNCTION': 0.0, + 'OF_RLL_D': 0.12, + 'BATT_VOLT_PIN': 13.0, + 'WPNAV_SPEED': 1000.0, + 'RC7_MAX': 1884.0, + 'CAM_SERVO_ON': 1300.0, + 'RATE_PIT_I': 1.0, + 'RC7_MIN': 969.0, + 'AHRS_COMP_BETA': 0.1, + 'OF_RLL_I': 0.5, + 'COMPASS_DEC': 0.0, + 'RC3_MIN': 1113.0, + 'RC2_DZ': 30.0, + 'FENCE_RADIUS': 30.0, + 'HLD_LON_I': 0.0, + 'ACRO_BAL_ROLL': 200.0, + 'COMPASS_AUTODEC': 1.0, + 'SR3_EXTRA3': 0.0, + 'COMPASS_USE': 1.0, + 'RC10_MAX': 1900.0, + 'RATE_PIT_P': 0.07, + 'GND_TEMP': 21.610104, + 'RC7_TRIM': 970.0, + 'RC10_REV': 1.0, + 'RATE_YAW_P': 0.2, + 'THR_ALT_P': 1.0, + 'RATE_PIT_D': 0.006, + 'ESC': 0.0, + 'MNT_ANGMIN_TIL': -4500.0, + 'SERIAL3_BAUD': 57.0, + 'RC8_MIN': 968.0, + 'THR_ALT_IMAX': 300.0, + 'SYSID_MYGCS': 255.0, + 'INS_GYROFFS_Y': 0.581989, + 'TUNE': 0.0, + 'RC8_TRIM': 970.0, + 'RC3_DZ': 30.0, + 'AHRS_GPS_GAIN': 1.0, + 'THR_ACCEL_D': 0.0, + 'TELEM_DELAY': 0.0, + 'THR_ACCEL_I': 0.5, + 'COMPASS_MOT_X': 0.0, + 'COMPASS_MOT_Z': 0.0, + 'RC10_FUNCTION': 0.0, + 'INS_GYROFFS_X': -0.001698, + 'INS_GYROFFS_Z': 0.01517, + 'RC6_TRIM': 1473.0, + 'THR_ACCEL_P': 1.2, + 'RC8_DZ': 0.0, + 'HLD_LAT_I': 0.0, + 'RC7_FUNCTION': 0.0, + 'RC6_REV': 1.0, + 'BATT_CURR_PIN': 12.0, + 'WPNAV_SPEED_UP': 250.0, + 'RC1_TRIM': 1524.0, + "MNT_JSTICK_SPD": 0.0, + "FLOW_ENABLE": 0.0, + } + assert logdata.messages == {} + assert logdata.modeChanges == { + 2204: ('LOITER', 269), + 4594: ('STABILIZE', 269), + 644: ('ALT_HOLD', 269), + 4404: ('ALT_HOLD', 269), + } + assert logdata.channels['GPS']['NSats'].min() == 6 + assert logdata.channels['GPS']['NSats'].max() == 8 + assert logdata.channels['GPS']['HDop'].listData[0] == (552, 4.68) + assert logdata.channels['GPS']['HDop'].listData[44] == (768, 4.67) + assert logdata.channels['GPS']['HDop'].listData[157] == (1288, 2.28) + assert logdata.channels['CTUN']['ThrOut'].listData[5] == (321, 139) + assert logdata.channels['CTUN']['ThrOut'].listData[45] == (409, 242) + assert logdata.channels['CTUN']['ThrOut'].listData[125] == (589, 266) + assert logdata.channels['CTUN']['CRate'].listData[3] == (317, 35) + assert logdata.channels['CTUN']['CRate'].listData[51] == (421, 31) + assert logdata.channels['CTUN']['CRate'].listData[115] == (563, -8) + assert int(logdata.filesizeKB) == 307 + assert abs(logdata.durationSecs - 155.399) < 1e-9 + assert logdata.lineCount == 4750 - # TODO: unit test DataflashLog reading 2 - # ... + # test LogIterator class + lit = DataflashLog.LogIterator(logdata) + assert lit.currentLine == 0 + assert lit.iterators == { + 'CURR': (0, 310), + 'ERR': (0, 307), + 'NTUN': (0, 2206), + 'CTUN': (0, 308), + 'GPS': (0, 552), + 'CMD': (0, 607), + 'D32': (0, 305), + 'ATT': (0, 311), + 'EV': (0, 306), + 'DU32': (0, 309), + 'PM': (0, 479), + } + lit.jump(500) + assert lit.iterators == { + 'CURR': (9, 514), + 'ERR': (1, 553), + 'NTUN': (0, 2206), + 'CTUN': (87, 500), + 'GPS': (0, 552), + 'CMD': (0, 607), + 'D32': (0, 305), + 'ATT': (83, 501), + 'EV': (4, 606), + 'DU32': (9, 513), + 'PM': (1, 719), + } + assert lit['CTUN']['ThrIn'] == 450 + assert lit['ATT']['RollIn'] == 11.19 + assert lit['CURR']['CurrTot'] == 25.827288 + assert lit['D32']['Value'] == 11122 + next(lit) + assert lit.iterators == { + 'CURR': (9, 514), + 'ERR': (1, 553), + 'NTUN': (0, 2206), + 'CTUN': (88, 502), + 'GPS': (0, 552), + 'CMD': (0, 607), + 'D32': (0, 305), + 'ATT': (83, 501), + 'EV': (4, 606), + 'DU32': (9, 513), + 'PM': (1, 719), + } + lit.jump(4750) + next(lit) + assert lit.currentLine == 4751 + assert lit['ATT']['Roll'] == 2.99 - # TODO: unit test the log test classes - # ... + # TODO: unit test DataflashLog reading 2 + # ... + # TODO: unit test the log test classes + # ... - print("All unit/regression tests GOOD\n") + print("All unit/regression tests GOOD\n") -except Exception as e: - print("Error found: " + traceback.format_exc()) - print("UNIT TEST FAILED\n") +except Exception: + print("Error found: " + traceback.format_exc()) + print("UNIT TEST FAILED\n") diff --git a/Tools/LogAnalyzer/VehicleType.py b/Tools/LogAnalyzer/VehicleType.py index 98fa9fc1210..00df6759302 100644 --- a/Tools/LogAnalyzer/VehicleType.py +++ b/Tools/LogAnalyzer/VehicleType.py @@ -1,12 +1,12 @@ -class VehicleType(): +# AP_FLAKE8_CLEAN + + +class VehicleType: Plane = 17 Copter = 23 Rover = 37 + # these should really be "Plane", "Copter" and "Rover", but many # things use these values as triggers in their code: -VehicleTypeString = { - 17: "ArduPlane", - 23: "ArduCopter", - 37: "ArduRover" -} +VehicleTypeString = {17: "ArduPlane", 23: "ArduCopter", 37: "ArduRover"} diff --git a/Tools/LogAnalyzer/tests/TestAutotune.py b/Tools/LogAnalyzer/tests/TestAutotune.py index fb7fbc08b16..16c04e39cdc 100644 --- a/Tools/LogAnalyzer/tests/TestAutotune.py +++ b/Tools/LogAnalyzer/tests/TestAutotune.py @@ -1,25 +1,31 @@ +# AP_FLAKE8_CLEAN + from LogAnalyzer import Test, TestResult -import DataflashLog from VehicleType import VehicleType # from ArduCopter/defines.h -AUTOTUNE_INITIALISED = 30 -AUTOTUNE_OFF = 31 -AUTOTUNE_RESTART = 32 -AUTOTUNE_SUCCESS = 33 -AUTOTUNE_FAILED = 34 -AUTOTUNE_REACHED_LIMIT = 35 -AUTOTUNE_PILOT_TESTING = 36 -AUTOTUNE_SAVEDGAINS = 37 - -AUTOTUNE_EVENTS = frozenset([AUTOTUNE_INITIALISED, - AUTOTUNE_OFF, - AUTOTUNE_RESTART, - AUTOTUNE_SUCCESS, - AUTOTUNE_FAILED, - AUTOTUNE_REACHED_LIMIT, - AUTOTUNE_PILOT_TESTING, - AUTOTUNE_SAVEDGAINS]) +AUTOTUNE_INITIALISED = 30 +AUTOTUNE_OFF = 31 +AUTOTUNE_RESTART = 32 +AUTOTUNE_SUCCESS = 33 +AUTOTUNE_FAILED = 34 +AUTOTUNE_REACHED_LIMIT = 35 +AUTOTUNE_PILOT_TESTING = 36 +AUTOTUNE_SAVEDGAINS = 37 + +AUTOTUNE_EVENTS = frozenset( + [ + AUTOTUNE_INITIALISED, + AUTOTUNE_OFF, + AUTOTUNE_RESTART, + AUTOTUNE_SUCCESS, + AUTOTUNE_FAILED, + AUTOTUNE_REACHED_LIMIT, + AUTOTUNE_PILOT_TESTING, + AUTOTUNE_SAVEDGAINS, + ] +) + class TestAutotune(Test): '''test for autotune success (copter only)''' @@ -27,25 +33,29 @@ class TestAutotune(Test): class AutotuneSession(object): def __init__(self, events): self.events = events + @property def linestart(self): return self.events[0][0] + @property def linestop(self): return self.events[-1][0] + @property def success(self): - return AUTOTUNE_SUCCESS in [i for _,i in self.events] + return AUTOTUNE_SUCCESS in [i for _, i in self.events] + @property def failure(self): - return AUTOTUNE_FAILED in [i for _,i in self.events] + return AUTOTUNE_FAILED in [i for _, i in self.events] + @property def limit(self): - return AUTOTUNE_REACHED_LIMIT in [i for _,i in self.events] + return AUTOTUNE_REACHED_LIMIT in [i for _, i in self.events] def __repr__(self): - return "".format(self.linestart,self.linestop) - + return "".format(self.linestart, self.linestop) def __init__(self): Test.__init__(self) @@ -59,9 +69,9 @@ def run(self, logdata, verbose): self.result.status = TestResult.StatusType.NA return - for i in ['EV','ATDE','ATUN']: + for i in ['EV', 'ATDE', 'ATUN']: r = False - if not i in logdata.channels: + if i not in logdata.channels: self.result.status = TestResult.StatusType.UNKNOWN self.result.statusMessage = "No {} log data".format(i) r = True @@ -72,8 +82,8 @@ def run(self, logdata, verbose): attempts = [] j = None - for i in range(0,len(events)): - line,ev = events[i] + for i in range(0, len(events)): + line, ev = events[i] if ev == AUTOTUNE_INITIALISED: if j is not None: attempts.append(TestAutotune.AutotuneSession(events[j:i])) @@ -84,43 +94,42 @@ def run(self, logdata, verbose): attempts.append(TestAutotune.AutotuneSession(events[j:])) for a in attempts: - # this should not be necessary! - def class_from_channel(c): - members = dict({'__init__':lambda x: setattr(x,i,None) for i in logdata.channels[c]}) - cls = type(\ - 'Channel__{:s}'.format(c), - (object,), - members - ) - return cls - - # last wins - if a.success: - self.result.status = TestResult.StatusType.GOOD - s = "[+]" - elif a.failure: - self.result.status = TestResult.StatusType.FAIL - s = "[-]" - else: - self.result.status = TestResult.StatusType.UNKNOWN - s = "[?]" - - s += " Autotune {}-{}\n".format(a.linestart,a.linestop) - self.result.statusMessage += s - - if verbose: - linenext = a.linestart + 1 - while linenext < a.linestop: - try: - line = logdata.channels['ATUN']['RateMax'].getNearestValueFwd(linenext)[1] - if line > a.linestop: - break - except: - break - atun = class_from_channel('ATUN')() - for key in logdata.channels['ATUN']: - setattr(atun, key, logdata.channels['ATUN'][key].getNearestValueFwd(linenext)[0]) - linenext = logdata.channels['ATUN'][key].getNearestValueFwd(linenext)[1] + 1 - self.result.statusMessage += 'ATUN Axis:{atun.Axis} TuneStep:{atun.TuneStep} RateMin:{atun.RateMin:5.0f} RateMax:{atun.RateMax:5.0f} RPGain:{atun.RPGain:1.4f} RDGain:{atun.RDGain:1.4f} SPGain:{atun.SPGain:1.1f} (@line:{l})\n'.format(l=linenext,s=s, atun=atun) - self.result.statusMessage += '\n' + # this should not be necessary! + def class_from_channel(c): + members = dict({'__init__': lambda x: setattr(x, i, None) for i in logdata.channels[c]}) + cls = type('Channel__{:s}'.format(c), (object,), members) + return cls + + # last wins + if a.success: + self.result.status = TestResult.StatusType.GOOD + s = "[+]" + elif a.failure: + self.result.status = TestResult.StatusType.FAIL + s = "[-]" + else: + self.result.status = TestResult.StatusType.UNKNOWN + s = "[?]" + + s += " Autotune {}-{}\n".format(a.linestart, a.linestop) + self.result.statusMessage += s + if verbose: + linenext = a.linestart + 1 + while linenext < a.linestop: + try: + line = logdata.channels['ATUN']['RateMax'].getNearestValueFwd(linenext)[1] + if line > a.linestop: + break + except ValueError: + break + atun = class_from_channel('ATUN')() + for key in logdata.channels['ATUN']: + setattr(atun, key, logdata.channels['ATUN'][key].getNearestValueFwd(linenext)[0]) + linenext = logdata.channels['ATUN'][key].getNearestValueFwd(linenext)[1] + 1 + self.result.statusMessage += ( + "ATUN Axis:{atun.Axis} TuneStep:{atun.TuneStep} RateMin:{atun.RateMin:5.0f}" + " RateMax:{atun.RateMax:5.0f} RPGain:{atun.RPGain:1.4f} RDGain:{atun.RDGain:1.4f}" + " SPGain:{atun.SPGain:1.1f} (@line:{l})\n" + ).format(l=linenext, atun=atun) + self.result.statusMessage += '\n' diff --git a/Tools/LogAnalyzer/tests/TestBrownout.py b/Tools/LogAnalyzer/tests/TestBrownout.py index 72c1c5d94c9..a72281e965c 100644 --- a/Tools/LogAnalyzer/tests/TestBrownout.py +++ b/Tools/LogAnalyzer/tests/TestBrownout.py @@ -1,44 +1,47 @@ -from LogAnalyzer import Test,TestResult -import DataflashLog +# AP_FLAKE8_CLEAN + +from LogAnalyzer import Test, TestResult -import collections class TestBrownout(Test): - '''test for a log that has been truncated in flight''' - - def __init__(self): - Test.__init__(self) - self.name = "Brownout" - - def run(self, logdata, verbose): - self.result = TestResult() - self.result.status = TestResult.StatusType.GOOD - - isArmed = False - # FIXME: cope with LOG_ARM_DISARM_MSG message - if "EV" in logdata.channels: - # step through the arm/disarm events in order, to see if they're symmetrical - # note: it seems landing detection isn't robust enough to rely upon here, so we'll only consider arm+disarm, not takeoff+land - for line,ev in logdata.channels["EV"]["Id"].listData: - if ev == 10: - isArmed = True - elif ev == 11: - isArmed = False - - if "CTUN" not in logdata.channels: - self.result.status = TestResult.StatusType.UNKNOWN - self.result.statusMessage = "No CTUN log data" - return - - if "BarAlt" in logdata.channels['CTUN']: - self.ctun_baralt_att = 'BarAlt' - else: - self.ctun_baralt_att = 'BAlt' - - # check for relative altitude at end - (finalAlt,finalAltLine) = logdata.channels["CTUN"][self.ctun_baralt_att].getNearestValue(logdata.lineCount, lookForwards=False) - - finalAltMax = 3.0 # max alt offset that we'll still consider to be on the ground - if isArmed and finalAlt > finalAltMax: - self.result.status = TestResult.StatusType.FAIL - self.result.statusMessage = "Truncated Log? Ends while armed at altitude %.2fm" % finalAlt + '''test for a log that has been truncated in flight''' + + def __init__(self): + Test.__init__(self) + self.name = "Brownout" + + def run(self, logdata, verbose): + self.result = TestResult() + self.result.status = TestResult.StatusType.GOOD + + isArmed = False + # FIXME: cope with LOG_ARM_DISARM_MSG message + if "EV" in logdata.channels: + # step through the arm/disarm events in order, to see if they're symmetrical + # note: it seems landing detection isn't robust enough to rely upon here, so we'll only consider arm+disarm, + # not takeoff+land + for line, ev in logdata.channels["EV"]["Id"].listData: + if ev == 10: + isArmed = True + elif ev == 11: + isArmed = False + + if "CTUN" not in logdata.channels: + self.result.status = TestResult.StatusType.UNKNOWN + self.result.statusMessage = "No CTUN log data" + return + + if "BarAlt" in logdata.channels['CTUN']: + self.ctun_baralt_att = 'BarAlt' + else: + self.ctun_baralt_att = 'BAlt' + + # check for relative altitude at end + (finalAlt, finalAltLine) = logdata.channels["CTUN"][self.ctun_baralt_att].getNearestValue( + logdata.lineCount, lookForwards=False + ) + + finalAltMax = 3.0 # max alt offset that we'll still consider to be on the ground + if isArmed and finalAlt > finalAltMax: + self.result.status = TestResult.StatusType.FAIL + self.result.statusMessage = "Truncated Log? Ends while armed at altitude %.2fm" % finalAlt diff --git a/Tools/LogAnalyzer/tests/TestCompass.py b/Tools/LogAnalyzer/tests/TestCompass.py index 8fc9fb513c6..b4e6dc5f5a9 100644 --- a/Tools/LogAnalyzer/tests/TestCompass.py +++ b/Tools/LogAnalyzer/tests/TestCompass.py @@ -1,8 +1,10 @@ -from LogAnalyzer import Test,TestResult -import DataflashLog +# AP_FLAKE8_CLEAN + -from functools import reduce import math +from functools import reduce + +from LogAnalyzer import Test, TestResult class TestCompass(Test): @@ -17,7 +19,7 @@ def run(self, logdata, verbose): self.result.status = TestResult.StatusType.GOOD def vec_len(x): - return math.sqrt(x[0]**2+x[1]**2+x[2]**2) + return math.sqrt(x[0] ** 2 + x[1] ** 2 + x[2] ** 2) def FAIL(): self.result.status = TestResult.StatusType.FAIL @@ -32,30 +34,46 @@ def WARN(): param_offsets = ( logdata.parameters["COMPASS_OFS_X"], logdata.parameters["COMPASS_OFS_Y"], - logdata.parameters["COMPASS_OFS_Z"] - ) + logdata.parameters["COMPASS_OFS_Z"], + ) if vec_len(param_offsets) > failOffset: FAIL() - self.result.statusMessage = "FAIL: Large compass offset params (X:%.2f, Y:%.2f, Z:%.2f)\n" % (param_offsets[0],param_offsets[1],param_offsets[2]) + self.result.statusMessage = "FAIL: Large compass offset params (X:%.2f, Y:%.2f, Z:%.2f)\n" % ( + param_offsets[0], + param_offsets[1], + param_offsets[2], + ) elif vec_len(param_offsets) > warnOffset: WARN() - self.result.statusMessage = "WARN: Large compass offset params (X:%.2f, Y:%.2f, Z:%.2f)\n" % (param_offsets[0],param_offsets[1],param_offsets[2]) + self.result.statusMessage = "WARN: Large compass offset params (X:%.2f, Y:%.2f, Z:%.2f)\n" % ( + param_offsets[0], + param_offsets[1], + param_offsets[2], + ) if "MAG" in logdata.channels: max_log_offsets = zip( - map(lambda x: x[1],logdata.channels["MAG"]["OfsX"].listData), - map(lambda x: x[1],logdata.channels["MAG"]["OfsY"].listData), - map(lambda x: x[1],logdata.channels["MAG"]["OfsZ"].listData) - ) - max_log_offsets = reduce(lambda x,y: x if vec_len(x) > vec_len(y) else y, max_log_offsets) + map(lambda x: x[1], logdata.channels["MAG"]["OfsX"].listData), + map(lambda x: x[1], logdata.channels["MAG"]["OfsY"].listData), + map(lambda x: x[1], logdata.channels["MAG"]["OfsZ"].listData), + ) + max_log_offsets = reduce(lambda x, y: x if vec_len(x) > vec_len(y) else y, max_log_offsets) if vec_len(max_log_offsets) > failOffset: FAIL() - self.result.statusMessage += "FAIL: Large compass offset in MAG data (X:%.2f, Y:%.2f, Z:%.2f)\n" % (max_log_offsets[0],max_log_offsets[1],max_log_offsets[2]) + self.result.statusMessage += "FAIL: Large compass offset in MAG data (X:%.2f, Y:%.2f, Z:%.2f)\n" % ( + max_log_offsets[0], + max_log_offsets[1], + max_log_offsets[2], + ) elif vec_len(max_log_offsets) > warnOffset: WARN() - self.result.statusMessage += "WARN: Large compass offset in MAG data (X:%.2f, Y:%.2f, Z:%.2f)\n" % (max_log_offsets[0],max_log_offsets[1],max_log_offsets[2]) + self.result.statusMessage += "WARN: Large compass offset in MAG data (X:%.2f, Y:%.2f, Z:%.2f)\n" % ( + max_log_offsets[0], + max_log_offsets[1], + max_log_offsets[2], + ) # check for mag field length change, and length outside of recommended range if "MAG" in logdata.channels: @@ -66,54 +84,77 @@ def WARN(): index = 0 length = len(logdata.channels["MAG"]["MagX"].listData) magField = [] - (minMagField, maxMagField) = (None,None) - (minMagFieldLine, maxMagFieldLine) = (None,None) + (minMagField, maxMagField) = (None, None) + (minMagFieldLine, maxMagFieldLine) = (None, None) zerosFound = False - while indexmaxMagField: + if mf > maxMagField: maxMagField = mf maxMagFieldLine = logdata.channels["MAG"]["MagX"].listData[index][0] if index == 0: - (minMagField, maxMagField) = (mf,mf) + (minMagField, maxMagField) = (mf, mf) index += 1 if minMagField is None: FAIL() self.result.statusMessage = self.result.statusMessage + "No valid mag data found\n" else: - percentDiff = (maxMagField-minMagField) / minMagField + percentDiff = (maxMagField - minMagField) / minMagField if percentDiff > percentDiffThresholdFAIL: FAIL() - self.result.statusMessage = self.result.statusMessage + "Large change in mag_field (%.2f%%)\n" % (percentDiff*100) + self.result.statusMessage = ( + self.result.statusMessage + "Large change in mag_field (%.2f%%)\n" % (percentDiff * 100) + ) elif percentDiff > percentDiffThresholdWARN: WARN() - self.result.statusMessage = self.result.statusMessage + "Moderate change in mag_field (%.2f%%)\n" % (percentDiff*100) + self.result.statusMessage = ( + self.result.statusMessage + "Moderate change in mag_field (%.2f%%)\n" % (percentDiff * 100) + ) else: - self.result.statusMessage = self.result.statusMessage + "mag_field interference within limits (%.2f%%)\n" % (percentDiff*100) + self.result.statusMessage = ( + self.result.statusMessage + + "mag_field interference within limits (%.2f%%)\n" % (percentDiff * 100) + ) if minMagField < minMagFieldThreshold: - self.result.statusMessage = self.result.statusMessage + "Min mag field length (%.2f) < recommended (%.2f)\n" % (minMagField,minMagFieldThreshold) + self.result.statusMessage = ( + self.result.statusMessage + + "Min mag field length (%.2f) < recommended (%.2f)\n" % (minMagField, minMagFieldThreshold) + ) if maxMagField > maxMagFieldThreshold: - self.result.statusMessage = self.result.statusMessage + "Max mag field length (%.2f) > recommended (%.2f)\n" % (maxMagField,maxMagFieldThreshold) + self.result.statusMessage = ( + self.result.statusMessage + + "Max mag field length (%.2f) > recommended (%.2f)\n" % (maxMagField, maxMagFieldThreshold) + ) if verbose: - self.result.statusMessage = self.result.statusMessage + "Min mag_field of %.2f on line %d\n" % (minMagField,minMagFieldLine) - self.result.statusMessage = self.result.statusMessage + "Max mag_field of %.2f on line %d\n" % (maxMagField,maxMagFieldLine) + self.result.statusMessage = self.result.statusMessage + "Min mag_field of %.2f on line %d\n" % ( + minMagField, + minMagFieldLine, + ) + self.result.statusMessage = self.result.statusMessage + "Max mag_field of %.2f on line %d\n" % ( + maxMagField, + maxMagFieldLine, + ) if zerosFound: if self.result.status == TestResult.StatusType.GOOD: WARN() self.result.statusMessage = self.result.statusMessage + "All zeros found in MAG X/Y/Z log data\n" else: - self.result.statusMessage = self.result.statusMessage + "No MAG data, unable to test mag_field interference\n" + self.result.statusMessage = ( + self.result.statusMessage + "No MAG data, unable to test mag_field interference\n" + ) except KeyError as e: self.result.status = TestResult.StatusType.FAIL diff --git a/Tools/LogAnalyzer/tests/TestDualGyroDrift.py b/Tools/LogAnalyzer/tests/TestDualGyroDrift.py index cc92f97ab5b..b2e91c7a1ab 100644 --- a/Tools/LogAnalyzer/tests/TestDualGyroDrift.py +++ b/Tools/LogAnalyzer/tests/TestDualGyroDrift.py @@ -1,7 +1,7 @@ from __future__ import print_function -from LogAnalyzer import Test,TestResult import DataflashLog +from LogAnalyzer import Test, TestResult # import scipy # import pylab #### TEMP!!! only for dev @@ -9,113 +9,102 @@ class TestDualGyroDrift(Test): - '''test for gyro drift between dual IMU data''' - - def __init__(self): - Test.__init__(self) - self.name = "Gyro Drift" - self.enable = False - - def run(self, logdata, verbose): - self.result = TestResult() - self.result.status = TestResult.StatusType.GOOD - - # if "IMU" not in logdata.channels or "IMU2" not in logdata.channels: - # self.result.status = TestResult.StatusType.NA - # return - - # imuX = logdata.channels["IMU"]["GyrX"].listData - # imu2X = logdata.channels["IMU2"]["GyrX"].listData - - # # NOTE: weird thing about Holger's log is that the counts of IMU+IMU2 are different - # print("length 1: %.2f, length 2: %.2f" % (len(imuX),len(imu2X))) - # #assert(len(imuX) == len(imu2X)) - - # # divide the curve into segments and get the average of each segment - # # we will get the diff between those averages, rather than a per-sample diff as the IMU+IMU2 arrays are often not the same length - # diffThresholdWARN = 0.03 - # diffThresholdFAIL = 0.05 - # nSamples = 10 - # imu1XAverages, imu1YAverages, imu1ZAverages, imu2XAverages, imu2YAverages, imu2ZAverages = ([],[],[],[],[],[]) - # imuXDiffAverages, imuYDiffAverages, imuZDiffAverages = ([],[],[]) - # maxDiffX, maxDiffY, maxDiffZ = (0,0,0) - # sliceLength1 = len(logdata.channels["IMU"]["GyrX"].dictData.values()) / nSamples - # sliceLength2 = len(logdata.channels["IMU2"]["GyrX"].dictData.values()) / nSamples - # for i in range(0,nSamples): - # imu1XAverages.append(numpy.mean(logdata.channels["IMU"]["GyrX"].dictData.values()[i*sliceLength1:i*sliceLength1+sliceLength1])) - # imu1YAverages.append(numpy.mean(logdata.channels["IMU"]["GyrY"].dictData.values()[i*sliceLength1:i*sliceLength1+sliceLength1])) - # imu1ZAverages.append(numpy.mean(logdata.channels["IMU"]["GyrZ"].dictData.values()[i*sliceLength1:i*sliceLength1+sliceLength1])) - # imu2XAverages.append(numpy.mean(logdata.channels["IMU2"]["GyrX"].dictData.values()[i*sliceLength2:i*sliceLength2+sliceLength2])) - # imu2YAverages.append(numpy.mean(logdata.channels["IMU2"]["GyrY"].dictData.values()[i*sliceLength2:i*sliceLength2+sliceLength2])) - # imu2ZAverages.append(numpy.mean(logdata.channels["IMU2"]["GyrZ"].dictData.values()[i*sliceLength2:i*sliceLength2+sliceLength2])) - # imuXDiffAverages.append(imu2XAverages[-1]-imu1XAverages[-1]) - # imuYDiffAverages.append(imu2YAverages[-1]-imu1YAverages[-1]) - # imuZDiffAverages.append(imu2ZAverages[-1]-imu1ZAverages[-1]) - # if abs(imuXDiffAverages[-1]) > maxDiffX: - # maxDiffX = imuXDiffAverages[-1] - # if abs(imuYDiffAverages[-1]) > maxDiffY: - # maxDiffY = imuYDiffAverages[-1] - # if abs(imuZDiffAverages[-1]) > maxDiffZ: - # maxDiffZ = imuZDiffAverages[-1] - - # if max(maxDiffX,maxDiffY,maxDiffZ) > diffThresholdFAIL: - # self.result.status = TestResult.StatusType.FAIL - # self.result.statusMessage = "IMU/IMU2 gyro averages differ by more than %s radians" % diffThresholdFAIL - # elif max(maxDiffX,maxDiffY,maxDiffZ) > diffThresholdWARN: - # self.result.status = TestResult.StatusType.WARN - # self.result.statusMessage = "IMU/IMU2 gyro averages differ by more than %s radians" % diffThresholdWARN - - # # pylab.plot(zip(*imuX)[0], zip(*imuX)[1], 'g') - # # pylab.plot(zip(*imu2X)[0], zip(*imu2X)[1], 'r') - - # #pylab.plot(range(0,(nSamples*sliceLength1),sliceLength1), imu1ZAverages, 'b') - - # print("Gyro averages1X: " + repr(imu1XAverages)) - # print("Gyro averages1Y: " + repr(imu1YAverages)) - # print("Gyro averages1Z: " + repr(imu1ZAverages) + "\n") - # print("Gyro averages2X: " + repr(imu2XAverages)) - # print("Gyro averages2Y: " + repr(imu2YAverages)) - # print("Gyro averages2Z: " + repr(imu2ZAverages) + "\n") - # print("Gyro averages diff X: " + repr(imuXDiffAverages)) - # print("Gyro averages diff Y: " + repr(imuYDiffAverages)) - # print("Gyro averages diff Z: " + repr(imuZDiffAverages)) - - # # lowpass filter using numpy - # # cutoff = 100 - # # fs = 10000.0 - # # b,a = scipy.signal.filter_design.butter(5,cutoff/(fs/2)) - # # imuXFiltered = scipy.signal.filtfilt(b,a,zip(*imuX)[1]) - # # imu2XFiltered = scipy.signal.filtfilt(b,a,zip(*imu2X)[1]) - # #pylab.plot(imuXFiltered, 'r') - - - # # TMP: DISPLAY BEFORE+AFTER plots - # pylab.show() - - # # print("imuX average before lowpass filter: %.8f" % logdata.channels["IMU"]["GyrX"].avg()) - # # print("imuX average after lowpass filter: %.8f" % numpy.mean(imuXFiltered)) - # # print("imu2X average before lowpass filter: %.8f" % logdata.channels["IMU2"]["GyrX"].avg()) - # # print("imu2X average after lowpass filter: %.8f" % numpy.mean(imu2XFiltered)) - - # avg1X = logdata.channels["IMU"]["GyrX"].avg() - # avg1Y = logdata.channels["IMU"]["GyrY"].avg() - # avg1Z = logdata.channels["IMU"]["GyrZ"].avg() - # avg2X = logdata.channels["IMU2"]["GyrX"].avg() - # avg2Y = logdata.channels["IMU2"]["GyrY"].avg() - # avg2Z = logdata.channels["IMU2"]["GyrZ"].avg() - - # avgRatioX = (max(avg1X,avg2X) - min(avg1X,avg2X)) / #abs(max(avg1X,avg2X) / min(avg1X,avg2X)) - # avgRatioY = abs(max(avg1Y,avg2Y) / min(avg1Y,avg2Y)) - # avgRatioZ = abs(max(avg1Z,avg2Z) / min(avg1Z,avg2Z)) - - # self.result.statusMessage = "IMU gyro avg: %.4f,%.4f,%.4f\nIMU2 gyro avg: %.4f,%.4f,%.4f\nAvg ratio: %.4f,%.4f,%.4f" % (avg1X,avg1Y,avg1Z, avg2X,avg2Y,avg2Z, avgRatioX,avgRatioY,avgRatioZ) - - - - - - - - - - + '''test for gyro drift between dual IMU data''' + + def __init__(self): + Test.__init__(self) + self.name = "Gyro Drift" + self.enable = False + + def run(self, logdata, verbose): + self.result = TestResult() + self.result.status = TestResult.StatusType.GOOD + + # if "IMU" not in logdata.channels or "IMU2" not in logdata.channels: + # self.result.status = TestResult.StatusType.NA + # return + + # imuX = logdata.channels["IMU"]["GyrX"].listData + # imu2X = logdata.channels["IMU2"]["GyrX"].listData + + # # NOTE: weird thing about Holger's log is that the counts of IMU+IMU2 are different + # print("length 1: %.2f, length 2: %.2f" % (len(imuX),len(imu2X))) + # #assert(len(imuX) == len(imu2X)) + + # # divide the curve into segments and get the average of each segment + # # we will get the diff between those averages, rather than a per-sample diff as the IMU+IMU2 arrays are often not the same length + # diffThresholdWARN = 0.03 + # diffThresholdFAIL = 0.05 + # nSamples = 10 + # imu1XAverages, imu1YAverages, imu1ZAverages, imu2XAverages, imu2YAverages, imu2ZAverages = ([],[],[],[],[],[]) + # imuXDiffAverages, imuYDiffAverages, imuZDiffAverages = ([],[],[]) + # maxDiffX, maxDiffY, maxDiffZ = (0,0,0) + # sliceLength1 = len(logdata.channels["IMU"]["GyrX"].dictData.values()) / nSamples + # sliceLength2 = len(logdata.channels["IMU2"]["GyrX"].dictData.values()) / nSamples + # for i in range(0,nSamples): + # imu1XAverages.append(numpy.mean(logdata.channels["IMU"]["GyrX"].dictData.values()[i*sliceLength1:i*sliceLength1+sliceLength1])) + # imu1YAverages.append(numpy.mean(logdata.channels["IMU"]["GyrY"].dictData.values()[i*sliceLength1:i*sliceLength1+sliceLength1])) + # imu1ZAverages.append(numpy.mean(logdata.channels["IMU"]["GyrZ"].dictData.values()[i*sliceLength1:i*sliceLength1+sliceLength1])) + # imu2XAverages.append(numpy.mean(logdata.channels["IMU2"]["GyrX"].dictData.values()[i*sliceLength2:i*sliceLength2+sliceLength2])) + # imu2YAverages.append(numpy.mean(logdata.channels["IMU2"]["GyrY"].dictData.values()[i*sliceLength2:i*sliceLength2+sliceLength2])) + # imu2ZAverages.append(numpy.mean(logdata.channels["IMU2"]["GyrZ"].dictData.values()[i*sliceLength2:i*sliceLength2+sliceLength2])) + # imuXDiffAverages.append(imu2XAverages[-1]-imu1XAverages[-1]) + # imuYDiffAverages.append(imu2YAverages[-1]-imu1YAverages[-1]) + # imuZDiffAverages.append(imu2ZAverages[-1]-imu1ZAverages[-1]) + # if abs(imuXDiffAverages[-1]) > maxDiffX: + # maxDiffX = imuXDiffAverages[-1] + # if abs(imuYDiffAverages[-1]) > maxDiffY: + # maxDiffY = imuYDiffAverages[-1] + # if abs(imuZDiffAverages[-1]) > maxDiffZ: + # maxDiffZ = imuZDiffAverages[-1] + + # if max(maxDiffX,maxDiffY,maxDiffZ) > diffThresholdFAIL: + # self.result.status = TestResult.StatusType.FAIL + # self.result.statusMessage = "IMU/IMU2 gyro averages differ by more than %s radians" % diffThresholdFAIL + # elif max(maxDiffX,maxDiffY,maxDiffZ) > diffThresholdWARN: + # self.result.status = TestResult.StatusType.WARN + # self.result.statusMessage = "IMU/IMU2 gyro averages differ by more than %s radians" % diffThresholdWARN + + # # pylab.plot(zip(*imuX)[0], zip(*imuX)[1], 'g') + # # pylab.plot(zip(*imu2X)[0], zip(*imu2X)[1], 'r') + + # #pylab.plot(range(0,(nSamples*sliceLength1),sliceLength1), imu1ZAverages, 'b') + + # print("Gyro averages1X: " + repr(imu1XAverages)) + # print("Gyro averages1Y: " + repr(imu1YAverages)) + # print("Gyro averages1Z: " + repr(imu1ZAverages) + "\n") + # print("Gyro averages2X: " + repr(imu2XAverages)) + # print("Gyro averages2Y: " + repr(imu2YAverages)) + # print("Gyro averages2Z: " + repr(imu2ZAverages) + "\n") + # print("Gyro averages diff X: " + repr(imuXDiffAverages)) + # print("Gyro averages diff Y: " + repr(imuYDiffAverages)) + # print("Gyro averages diff Z: " + repr(imuZDiffAverages)) + + # # lowpass filter using numpy + # # cutoff = 100 + # # fs = 10000.0 + # # b,a = scipy.signal.filter_design.butter(5,cutoff/(fs/2)) + # # imuXFiltered = scipy.signal.filtfilt(b,a,zip(*imuX)[1]) + # # imu2XFiltered = scipy.signal.filtfilt(b,a,zip(*imu2X)[1]) + # #pylab.plot(imuXFiltered, 'r') + + # # TMP: DISPLAY BEFORE+AFTER plots + # pylab.show() + + # # print("imuX average before lowpass filter: %.8f" % logdata.channels["IMU"]["GyrX"].avg()) + # # print("imuX average after lowpass filter: %.8f" % numpy.mean(imuXFiltered)) + # # print("imu2X average before lowpass filter: %.8f" % logdata.channels["IMU2"]["GyrX"].avg()) + # # print("imu2X average after lowpass filter: %.8f" % numpy.mean(imu2XFiltered)) + + # avg1X = logdata.channels["IMU"]["GyrX"].avg() + # avg1Y = logdata.channels["IMU"]["GyrY"].avg() + # avg1Z = logdata.channels["IMU"]["GyrZ"].avg() + # avg2X = logdata.channels["IMU2"]["GyrX"].avg() + # avg2Y = logdata.channels["IMU2"]["GyrY"].avg() + # avg2Z = logdata.channels["IMU2"]["GyrZ"].avg() + + # avgRatioX = (max(avg1X,avg2X) - min(avg1X,avg2X)) / #abs(max(avg1X,avg2X) / min(avg1X,avg2X)) + # avgRatioY = abs(max(avg1Y,avg2Y) / min(avg1Y,avg2Y)) + # avgRatioZ = abs(max(avg1Z,avg2Z) / min(avg1Z,avg2Z)) + + # self.result.statusMessage = "IMU gyro avg: %.4f,%.4f,%.4f\nIMU2 gyro avg: %.4f,%.4f,%.4f\nAvg ratio: %.4f,%.4f,%.4f" % (avg1X,avg1Y,avg1Z, avg2X,avg2Y,avg2Z, avgRatioX,avgRatioY,avgRatioZ) diff --git a/Tools/LogAnalyzer/tests/TestDupeLogData.py b/Tools/LogAnalyzer/tests/TestDupeLogData.py index 0e995b404b7..d570f579f4f 100644 --- a/Tools/LogAnalyzer/tests/TestDupeLogData.py +++ b/Tools/LogAnalyzer/tests/TestDupeLogData.py @@ -1,79 +1,73 @@ -from __future__ import print_function - -from LogAnalyzer import Test,TestResult -import DataflashLog - - -class TestDupeLogData(Test): - '''test for duplicated data in log, which has been happening on PX4/Pixhawk''' - - def __init__(self): - Test.__init__(self) - self.name = "Dupe Log Data" - - def __matchSample(self, sample, sampleStartIndex, logdata): - '''return the line number where a match is found, otherwise return False''' - - # ignore if all data in sample is the same value - nSame = 0 - for s in sample: - if s[1] == sample[0][1]: - nSame += 1 - if nSame == 20: - return False - - # c - data = logdata.channels["ATT"]["Pitch"].listData - for i in range(sampleStartIndex, len(data)): - #print("Checking against index %d" % i) - if i == sampleStartIndex: - continue # skip matching against ourselves - j = 0 - while j<20 and (i+j)= len(sampleStartIndices): - break - +# AP_FLAKE8_CLEAN +from __future__ import print_function +from LogAnalyzer import Test, TestResult +class TestDupeLogData(Test): + '''test for duplicated data in log, which has been happening on PX4/Pixhawk''' + + def __init__(self): + Test.__init__(self) + self.name = "Dupe Log Data" + + def __matchSample(self, sample, sampleStartIndex, logdata): + '''return the line number where a match is found, otherwise return False''' + + # ignore if all data in sample is the same value + nSame = 0 + for s in sample: + if s[1] == sample[0][1]: + nSame += 1 + if nSame == 20: + return False + + # c + data = logdata.channels["ATT"]["Pitch"].listData + for i in range(sampleStartIndex, len(data)): + if i == sampleStartIndex: + continue # skip matching against ourselves + j = 0 + while j < 20 and (i + j) < len(data) and data[i + j][1] == sample[j][1]: + j += 1 + if j == 20: # all samples match + return data[i][0] + + return False + + def run(self, logdata, verbose): + self.result = TestResult() + self.result.status = TestResult.StatusType.GOOD + + # this could be made more flexible by not hard-coding to use ATT data, could make it dynamic based on whatever + # is available as long as it is highly variable + if "ATT" not in logdata.channels: + self.result.status = TestResult.StatusType.UNKNOWN + self.result.statusMessage = "No ATT log data" + return + + # pick 10 sample points within the range of ATT data we have + sampleStartIndices = [] + attEndIndex = len(logdata.channels["ATT"]["Pitch"].listData) - 1 + step = int(attEndIndex / 11) + for i in range(step, attEndIndex - step, step): + sampleStartIndices.append(i) + + # get 20 datapoints of pitch from each sample location and check for a match elsewhere + sampleIndex = 0 + for i in range(sampleStartIndices[0], len(logdata.channels["ATT"]["Pitch"].listData)): + if i == sampleStartIndices[sampleIndex]: + sample = logdata.channels["ATT"]["Pitch"].listData[i : i + 20] + matchedLine = self.__matchSample(sample, i, logdata) + if matchedLine: + self.result.status = TestResult.StatusType.FAIL + self.result.statusMessage = "Duplicate data chunks found in log (%d and %d)" % ( + sample[0][0], + matchedLine, + ) + return + sampleIndex += 1 + if sampleIndex >= len(sampleStartIndices): + break diff --git a/Tools/LogAnalyzer/tests/TestEmpty.py b/Tools/LogAnalyzer/tests/TestEmpty.py index fc4f4c92f27..e247702a5ed 100644 --- a/Tools/LogAnalyzer/tests/TestEmpty.py +++ b/Tools/LogAnalyzer/tests/TestEmpty.py @@ -1,20 +1,23 @@ -from LogAnalyzer import Test,TestResult +# AP_FLAKE8_CLEAN + + import DataflashLog +from LogAnalyzer import Test, TestResult class TestEmpty(Test): - '''test for empty or near-empty logs''' + '''test for empty or near-empty logs''' + + def __init__(self): + Test.__init__(self) + self.name = "Empty" - def __init__(self): - Test.__init__(self) - self.name = "Empty" - - def run(self, logdata, verbose): - self.result = TestResult() - self.result.status = TestResult.StatusType.GOOD + def run(self, logdata, verbose): + self.result = TestResult() + self.result.status = TestResult.StatusType.GOOD - # all the logic for this test is in the helper function, as it can also be called up front as an early exit - emptyErr = DataflashLog.DataflashLogHelper.isLogEmpty(logdata) - if emptyErr: - self.result.status = TestResult.StatusType.FAIL - self.result.statusMessage = "Empty log? " + emptyErr + # all the logic for this test is in the helper function, as it can also be called up front as an early exit + emptyErr = DataflashLog.DataflashLogHelper.isLogEmpty(logdata) + if emptyErr: + self.result.status = TestResult.StatusType.FAIL + self.result.statusMessage = "Empty log? " + emptyErr diff --git a/Tools/LogAnalyzer/tests/TestEvents.py b/Tools/LogAnalyzer/tests/TestEvents.py index b6058468118..b8556b5baf8 100644 --- a/Tools/LogAnalyzer/tests/TestEvents.py +++ b/Tools/LogAnalyzer/tests/TestEvents.py @@ -1,56 +1,57 @@ -from LogAnalyzer import Test,TestResult -import DataflashLog +# AP_FLAKE8_CLEAN +from LogAnalyzer import Test, TestResult -class TestEvents(Test): - '''test for erroneous events and failsafes''' - # TODO: need to check for vehicle-specific codes - - def __init__(self): - Test.__init__(self) - self.name = "Event/Failsafe" - - def run(self, logdata, verbose): - self.result = TestResult() - self.result.status = TestResult.StatusType.GOOD - - errors = set() - - if "ERR" in logdata.channels: - assert(len(logdata.channels["ERR"]["Subsys"].listData) == len(logdata.channels["ERR"]["ECode"].listData)) - for i in range(len(logdata.channels["ERR"]["Subsys"].listData)): - subSys = logdata.channels["ERR"]["Subsys"].listData[i][1] - eCode = logdata.channels["ERR"]["ECode"].listData[i][1] - if subSys == 2 and (eCode == 1): - errors.add("PPM") - elif subSys == 3 and (eCode == 1 or eCode == 2): - errors.add("COMPASS") - elif subSys == 5 and (eCode == 1): - errors.add("FS_THR") - elif subSys == 6 and (eCode == 1): - errors.add("FS_BATT") - elif subSys == 7 and (eCode == 1): - errors.add("GPS") - elif subSys == 8 and (eCode == 1): - errors.add("GCS") - elif subSys == 9 and (eCode == 1 or eCode == 2): - errors.add("FENCE") - elif subSys == 10: - errors.add("FLT_MODE") - elif subSys == 11 and (eCode == 2): - errors.add("GPS_GLITCH") - elif subSys == 12 and (eCode == 1): - errors.add("CRASH") - - if errors: - if len(errors) == 1 and "FENCE" in errors: - self.result.status = TestResult.StatusType.WARN - else: - self.result.status = TestResult.StatusType.FAIL - if len(errors) == 1: - self.result.statusMessage = "ERR found: " - else: - self.result.statusMessage = "ERRs found: " - for err in errors: - self.result.statusMessage = self.result.statusMessage + err + " " +class TestEvents(Test): + '''test for erroneous events and failsafes''' + + # TODO: need to check for vehicle-specific codes + + def __init__(self): + Test.__init__(self) + self.name = "Event/Failsafe" + + def run(self, logdata, verbose): + self.result = TestResult() + self.result.status = TestResult.StatusType.GOOD + + errors = set() + + if "ERR" in logdata.channels: + assert len(logdata.channels["ERR"]["Subsys"].listData) == len(logdata.channels["ERR"]["ECode"].listData) + for i in range(len(logdata.channels["ERR"]["Subsys"].listData)): + subSys = logdata.channels["ERR"]["Subsys"].listData[i][1] + eCode = logdata.channels["ERR"]["ECode"].listData[i][1] + if subSys == 2 and (eCode == 1): + errors.add("PPM") + elif subSys == 3 and (eCode == 1 or eCode == 2): + errors.add("COMPASS") + elif subSys == 5 and (eCode == 1): + errors.add("FS_THR") + elif subSys == 6 and (eCode == 1): + errors.add("FS_BATT") + elif subSys == 7 and (eCode == 1): + errors.add("GPS") + elif subSys == 8 and (eCode == 1): + errors.add("GCS") + elif subSys == 9 and (eCode == 1 or eCode == 2): + errors.add("FENCE") + elif subSys == 10: + errors.add("FLT_MODE") + elif subSys == 11 and (eCode == 2): + errors.add("GPS_GLITCH") + elif subSys == 12 and (eCode == 1): + errors.add("CRASH") + + if errors: + if len(errors) == 1 and "FENCE" in errors: + self.result.status = TestResult.StatusType.WARN + else: + self.result.status = TestResult.StatusType.FAIL + if len(errors) == 1: + self.result.statusMessage = "ERR found: " + else: + self.result.statusMessage = "ERRs found: " + for err in errors: + self.result.statusMessage = self.result.statusMessage + err + " " diff --git a/Tools/LogAnalyzer/tests/TestGPSGlitch.py b/Tools/LogAnalyzer/tests/TestGPSGlitch.py index cf967412eb2..294351e2be1 100644 --- a/Tools/LogAnalyzer/tests/TestGPSGlitch.py +++ b/Tools/LogAnalyzer/tests/TestGPSGlitch.py @@ -1,3 +1,6 @@ +# AP_FLAKE8_CLEAN + + from LogAnalyzer import Test, TestResult @@ -32,8 +35,7 @@ def run(self, logdata, verbose): # leaving the test in for all gpsGlitchCount = 0 if "ERR" in logdata.channels: - assert(len(logdata.channels["ERR"]["Subsys"].listData) == - len(logdata.channels["ERR"]["ECode"].listData)) + assert len(logdata.channels["ERR"]["Subsys"].listData) == len(logdata.channels["ERR"]["ECode"].listData) for i in range(len(logdata.channels["ERR"]["Subsys"].listData)): subSys = logdata.channels["ERR"]["Subsys"].listData[i][1] eCode = logdata.channels["ERR"]["ECode"].listData[i][1] @@ -41,8 +43,7 @@ def run(self, logdata, verbose): gpsGlitchCount += 1 if gpsGlitchCount: self.result.status = TestResult.StatusType.FAIL - self.result.statusMessage = ("GPS glitch errors found (%d)" % - gpsGlitchCount) + self.result.statusMessage = "GPS glitch errors found (%d)" % gpsGlitchCount # define and check different thresholds for WARN level and # FAIL level @@ -58,11 +59,9 @@ def run(self, logdata, verbose): foundBadHDopWarn = hdopChan.max() > maxHDopWARN foundBadSatsFail = satsChan.min() < minSatsFAIL foundBadHDopFail = hdopChan.max() > maxHDopFAIL - satsMsg = ("Min satellites: %s, Max HDop: %s" % - (satsChan.min(), hdopChan.max())) + satsMsg = "Min satellites: %s, Max HDop: %s" % (satsChan.min(), hdopChan.max()) if gpsGlitchCount: - self.result.statusMessage = "\n".join([self.result.statusMessage, - satsMsg]) + self.result.statusMessage = "\n".join([self.result.statusMessage, satsMsg]) if foundBadSatsFail or foundBadHDopFail: if not gpsGlitchCount: self.result.status = TestResult.StatusType.FAIL diff --git a/Tools/LogAnalyzer/tests/TestIMUMatch.py b/Tools/LogAnalyzer/tests/TestIMUMatch.py index ce7dd1f4006..e26c68756f0 100644 --- a/Tools/LogAnalyzer/tests/TestIMUMatch.py +++ b/Tools/LogAnalyzer/tests/TestIMUMatch.py @@ -1,9 +1,12 @@ +# AP_FLAKE8_CLEAN + + from __future__ import print_function -from LogAnalyzer import Test,TestResult -import DataflashLog from math import sqrt +from LogAnalyzer import Test, TestResult + class TestIMUMatch(Test): '''test for empty or near-empty logs''' @@ -14,20 +17,20 @@ def __init__(self): def run(self, logdata, verbose): - #tuning parameters: - warn_threshold = .75 + # tuning parameters: + warn_threshold = 0.75 fail_threshold = 1.5 filter_tc = 5.0 self.result = TestResult() self.result.status = TestResult.StatusType.GOOD - if ("IMU" in logdata.channels) and (not "IMU2" in logdata.channels): + if ("IMU" in logdata.channels) and ("IMU2" not in logdata.channels): self.result.status = TestResult.StatusType.NA self.result.statusMessage = "No IMU2" return - if (not "IMU" in logdata.channels) or (not "IMU2" in logdata.channels): + if ("IMU" not in logdata.channels) or ("IMU2" not in logdata.channels): self.result.status = TestResult.StatusType.UNKNOWN self.result.statusMessage = "No IMU log data" return @@ -36,7 +39,7 @@ def run(self, logdata, verbose): imu2 = logdata.channels["IMU2"] timeLabel = None - for i in 'TimeMS','TimeUS','Time': + for i in 'TimeMS', 'TimeUS', 'Time': if i in logdata.channels["GPS"]: timeLabel = i break @@ -50,18 +53,32 @@ def run(self, logdata, verbose): imu2_accy = imu2["AccY"].listData imu2_accz = imu2["AccZ"].listData - imu_multiplier = 1.0E-3 + imu_multiplier = 1.0e-3 if timeLabel == 'TimeUS': - imu_multiplier = 1.0E-6 + imu_multiplier = 1.0e-6 imu1 = [] imu2 = [] for i in range(len(imu1_timems)): - imu1.append({ 't': imu1_timems[i][1]*imu_multiplier, 'x': imu1_accx[i][1], 'y': imu1_accy[i][1], 'z': imu1_accz[i][1]}) + imu1.append( + { + 't': imu1_timems[i][1] * imu_multiplier, + 'x': imu1_accx[i][1], + 'y': imu1_accy[i][1], + 'z': imu1_accz[i][1], + } + ) for i in range(len(imu2_timems)): - imu2.append({ 't': imu2_timems[i][1]*imu_multiplier, 'x': imu2_accx[i][1], 'y': imu2_accy[i][1], 'z': imu2_accz[i][1]}) + imu2.append( + { + 't': imu2_timems[i][1] * imu_multiplier, + 'x': imu2_accx[i][1], + 'y': imu2_accy[i][1], + 'z': imu2_accz[i][1], + } + ) imu1.sort(key=lambda x: x['t']) imu2.sort(key=lambda x: x['t']) @@ -76,40 +93,47 @@ def run(self, logdata, verbose): max_diff_filtered = 0 for i in range(len(imu1)): - #find closest imu2 value + # find closest imu2 value t = imu1[i]['t'] - dt = 0 if last_t is None else t-last_t - dt=min(dt,.1) + dt = 0 if last_t is None else t - last_t + dt = min(dt, 0.1) next_imu2 = None - for i in range(imu2_index,len(imu2)): + for i in range(imu2_index, len(imu2)): next_imu2 = imu2[i] - imu2_index=i + imu2_index = i if next_imu2['t'] >= t: break - prev_imu2 = imu2[imu2_index-1] - closest_imu2 = next_imu2 if abs(next_imu2['t']-t) fail_threshold: - self.result.statusMessage = "Check vibration or accelerometer calibration. (Mismatch: %.2f, WARN: %.2f, FAIL: %.2f)" % (max_diff_filtered,warn_threshold,fail_threshold) + self.result.statusMessage = ( + "Check vibration or accelerometer calibration. (Mismatch: %.2f, WARN: %.2f, FAIL: %.2f)" + % (max_diff_filtered, warn_threshold, fail_threshold) + ) self.result.status = TestResult.StatusType.FAIL elif max_diff_filtered > warn_threshold: - self.result.statusMessage = "Check vibration or accelerometer calibration. (Mismatch: %.2f, WARN: %.2f, FAIL: %.2f)" % (max_diff_filtered,warn_threshold,fail_threshold) + self.result.statusMessage = ( + "Check vibration or accelerometer calibration. (Mismatch: %.2f, WARN: %.2f, FAIL: %.2f)" + % (max_diff_filtered, warn_threshold, fail_threshold) + ) self.result.status = TestResult.StatusType.WARN else: - self.result.statusMessage = "(Mismatch: %.2f, WARN: %.2f, FAIL: %.2f)" % (max_diff_filtered,warn_threshold, fail_threshold) - - + self.result.statusMessage = "(Mismatch: %.2f, WARN: %.2f, FAIL: %.2f)" % ( + max_diff_filtered, + warn_threshold, + fail_threshold, + ) diff --git a/Tools/LogAnalyzer/tests/TestMotorBalance.py b/Tools/LogAnalyzer/tests/TestMotorBalance.py index 250bf6ff95d..398d9941d33 100644 --- a/Tools/LogAnalyzer/tests/TestMotorBalance.py +++ b/Tools/LogAnalyzer/tests/TestMotorBalance.py @@ -1,10 +1,12 @@ -from LogAnalyzer import Test,TestResult -import DataflashLog +# AP_FLAKE8_CLEAN +from LogAnalyzer import Test, TestResult from VehicleType import VehicleType + class TestBalanceTwist(Test): '''test for badly unbalanced copter, including yaw twist''' + def __init__(self): Test.__init__(self) self.name = "Motor Balance" @@ -18,21 +20,21 @@ def run(self, logdata, verbose): return self.result.status = TestResult.StatusType.UNKNOWN - if not "RCOU" in logdata.channels: + if "RCOU" not in logdata.channels: return ch = [] for i in range(8): for prefix in "Chan", "Ch", "C": - if prefix+repr((i+1)) in logdata.channels["RCOU"]: - ch.append(map(lambda x: x[1], logdata.channels["RCOU"][prefix+repr((i+1))].listData)) + if prefix + repr((i + 1)) in logdata.channels["RCOU"]: + ch.append(map(lambda x: x[1], logdata.channels["RCOU"][prefix + repr((i + 1))].listData)) ch = zip(*ch) num_channels = 0 ch = list(ch) for i in range(len(ch)): - ch[i] = list(filter(lambda x: (x>0 and x<3000), ch[i])) + ch[i] = list(filter(lambda x: (x > 0 and x < 3000), ch[i])) if num_channels < len(ch[i]): num_channels = len(ch[i]) @@ -43,11 +45,20 @@ def run(self, logdata, verbose): return try: - min_throttle = logdata.parameters["RC3_MIN"] + logdata.parameters["THR_MIN"] / (logdata.parameters["RC3_MAX"]-logdata.parameters["RC3_MIN"])/1000.0 - except KeyError as e: - min_throttle = logdata.parameters["MOT_PWM_MIN"] / (logdata.parameters["MOT_PWM_MAX"]-logdata.parameters["RC3_MIN"])/1000.0 - - ch = list(filter(lambda x:sum(x)/num_channels > min_throttle, ch)) + min_throttle = ( + logdata.parameters["RC3_MIN"] + + logdata.parameters["THR_MIN"] + / (logdata.parameters["RC3_MAX"] - logdata.parameters["RC3_MIN"]) + / 1000.0 + ) + except KeyError: + min_throttle = ( + logdata.parameters["MOT_PWM_MIN"] + / (logdata.parameters["MOT_PWM_MAX"] - logdata.parameters["RC3_MIN"]) + / 1000.0 + ) + + ch = list(filter(lambda x: sum(x) / num_channels > min_throttle, ch)) if len(ch) == 0: return @@ -55,17 +66,20 @@ def run(self, logdata, verbose): avg_sum = 0 avg_ch = [] for i in range(num_channels): - avg = list(map(lambda x: x[i],ch)) - avg = sum(avg)/len(avg) + avg = list(map(lambda x: x[i], ch)) + avg = sum(avg) / len(avg) avg_ch.append(avg) avg_sum += avg avg_all = avg_sum / num_channels - self.result.statusMessage = "Motor channel averages = %s\nAverage motor output = %.0f\nDifference between min and max motor averages = %.0f" % (str(avg_ch),avg_all,abs(min(avg_ch)-max(avg_ch))) + self.result.statusMessage = ( + "Motor channel averages = %s\nAverage motor output = %.0f\nDifference between min and max motor averages = %.0f" + % (str(avg_ch), avg_all, abs(min(avg_ch) - max(avg_ch))) + ) self.result.status = TestResult.StatusType.GOOD - if abs(min(avg_ch)-max(avg_ch)) > 75: + if abs(min(avg_ch) - max(avg_ch)) > 75: self.result.status = TestResult.StatusType.WARN - if abs(min(avg_ch)-max(avg_ch)) > 150: + if abs(min(avg_ch) - max(avg_ch)) > 150: self.result.status = TestResult.StatusType.FAIL diff --git a/Tools/LogAnalyzer/tests/TestNaN.py b/Tools/LogAnalyzer/tests/TestNaN.py index ea30918c266..d53949a71ec 100644 --- a/Tools/LogAnalyzer/tests/TestNaN.py +++ b/Tools/LogAnalyzer/tests/TestNaN.py @@ -1,6 +1,11 @@ -from LogAnalyzer import Test,TestResult +# AP_FLAKE8_CLEAN + + import math +from LogAnalyzer import Test, TestResult + + class TestNaN(Test): '''test for NaNs present in log''' @@ -16,8 +21,8 @@ def FAIL(): self.result.status = TestResult.StatusType.FAIL nans_ok = { - "CTUN": [ "DSAlt", "TAlt" ], - "POS": [ "RelOriginAlt"], + "CTUN": ["DSAlt", "TAlt"], + "POS": ["RelOriginAlt"], } for channel in logdata.channels.keys(): @@ -29,7 +34,10 @@ def FAIL(): (ts, val) = tupe if isinstance(val, float) and math.isnan(val): FAIL() - self.result.statusMessage += "Found NaN in %s.%s\n" % (channel, field,) + self.result.statusMessage += "Found NaN in %s.%s\n" % ( + channel, + field, + ) raise ValueError() - except ValueError as e: + except ValueError: continue diff --git a/Tools/LogAnalyzer/tests/TestOptFlow.py b/Tools/LogAnalyzer/tests/TestOptFlow.py index 06444b6b108..32ef7251d82 100644 --- a/Tools/LogAnalyzer/tests/TestOptFlow.py +++ b/Tools/LogAnalyzer/tests/TestOptFlow.py @@ -1,12 +1,16 @@ -from LogAnalyzer import Test,TestResult -import DataflashLog +# AP_FLAKE8_CLEAN + from math import sqrt -import numpy as np + import matplotlib.pyplot as plt +import numpy as np +from LogAnalyzer import Test, TestResult + class TestFlow(Test): '''test optical flow sensor scale factor calibration''' + # # Use the following procedure to log the calibration data. is assumed that the optical flow sensor has been # correctly aligned, is focussed and the test is performed over a textured surface with adequate lighting. @@ -42,13 +46,21 @@ def WARN(): try: # tuning parameters used by the algorithm - tilt_threshold = 15 # roll and pitch threshold used to start and stop calibration (deg) - quality_threshold = 124 # minimum flow quality required for data to be used by the curve fit (N/A) - min_rate_threshold = 0.0 # if the gyro rate is less than this, the data will not be used by the curve fit (rad/sec) - max_rate_threshold = 2.0 # if the gyro rate is greter than this, the data will not be used by the curve fit (rad/sec) - param_std_threshold = 5.0 # maximum allowable 1-std uncertainty in scaling parameter (scale factor * 1000) - param_abs_threshold = 200 # max/min allowable scale factor parameter. Values of FLOW_FXSCALER and FLOW_FYSCALER outside the range of +-param_abs_threshold indicate a sensor configuration problem. - min_num_points = 100 # minimum number of points required for a curve fit - this is necessary, but not sufficient condition - the standard deviation estimate of the fit gradient is also important. + tilt_threshold = 15 # roll and pitch threshold used to start and stop calibration (deg) + quality_threshold = 124 # minimum flow quality required for data to be used by the curve fit (N/A) + min_rate_threshold = ( + 0.0 # if the gyro rate is less than this, the data will not be used by the curve fit (rad/sec) + ) + max_rate_threshold = ( + 2.0 # if the gyro rate is greter than this, the data will not be used by the curve fit (rad/sec) + ) + param_std_threshold = 5.0 # maximum allowable 1-std uncertainty in scaling parameter (scale factor * 1000) + # max/min allowable scale factor parameter. Values of FLOW_FXSCALER and FLOW_FYSCALER outside the range + # of +-param_abs_threshold indicate a sensor configuration problem. + param_abs_threshold = 200 + # minimum number of points required for a curve fit - this is necessary, but not sufficient condition - the + # standard deviation estimate of the fit gradient is also important. + min_num_points = 100 # get the existing scale parameters flow_fxscaler = logdata.parameters["FLOW_FXSCALER"] @@ -58,27 +70,27 @@ def WARN(): if "OF" in logdata.channels: flowX = np.zeros(len(logdata.channels["OF"]["flowX"].listData)) for i in range(len(logdata.channels["OF"]["flowX"].listData)): - (line, flowX[i]) = logdata.channels["OF"]["flowX"].listData[i] + (line, flowX[i]) = logdata.channels["OF"]["flowX"].listData[i] bodyX = np.zeros(len(logdata.channels["OF"]["bodyX"].listData)) for i in range(len(logdata.channels["OF"]["bodyX"].listData)): - (line, bodyX[i]) = logdata.channels["OF"]["bodyX"].listData[i] + (line, bodyX[i]) = logdata.channels["OF"]["bodyX"].listData[i] flowY = np.zeros(len(logdata.channels["OF"]["flowY"].listData)) for i in range(len(logdata.channels["OF"]["flowY"].listData)): - (line, flowY[i]) = logdata.channels["OF"]["flowY"].listData[i] + (line, flowY[i]) = logdata.channels["OF"]["flowY"].listData[i] bodyY = np.zeros(len(logdata.channels["OF"]["bodyY"].listData)) for i in range(len(logdata.channels["OF"]["bodyY"].listData)): - (line, bodyY[i]) = logdata.channels["OF"]["bodyY"].listData[i] + (line, bodyY[i]) = logdata.channels["OF"]["bodyY"].listData[i] flow_time_us = np.zeros(len(logdata.channels["OF"]["TimeUS"].listData)) for i in range(len(logdata.channels["OF"]["TimeUS"].listData)): - (line, flow_time_us[i]) = logdata.channels["OF"]["TimeUS"].listData[i] + (line, flow_time_us[i]) = logdata.channels["OF"]["TimeUS"].listData[i] flow_qual = np.zeros(len(logdata.channels["OF"]["Qual"].listData)) for i in range(len(logdata.channels["OF"]["Qual"].listData)): - (line, flow_qual[i]) = logdata.channels["OF"]["Qual"].listData[i] + (line, flow_qual[i]) = logdata.channels["OF"]["Qual"].listData[i] else: FAIL() @@ -89,15 +101,15 @@ def WARN(): if "ATT" in logdata.channels: Roll = np.zeros(len(logdata.channels["ATT"]["Roll"].listData)) for i in range(len(logdata.channels["ATT"]["Roll"].listData)): - (line, Roll[i]) = logdata.channels["ATT"]["Roll"].listData[i] + (line, Roll[i]) = logdata.channels["ATT"]["Roll"].listData[i] Pitch = np.zeros(len(logdata.channels["ATT"]["Pitch"].listData)) for i in range(len(logdata.channels["ATT"]["Pitch"].listData)): - (line, Pitch[i]) = logdata.channels["ATT"]["Pitch"].listData[i] + (line, Pitch[i]) = logdata.channels["ATT"]["Pitch"].listData[i] att_time_us = np.zeros(len(logdata.channels["ATT"]["TimeUS"].listData)) for i in range(len(logdata.channels["ATT"]["TimeUS"].listData)): - (line, att_time_us[i]) = logdata.channels["ATT"]["TimeUS"].listData[i] + (line, att_time_us[i]) = logdata.channels["ATT"]["TimeUS"].listData[i] else: FAIL() @@ -119,17 +131,17 @@ def WARN(): # calculate the end time for the roll calibration endTime = int(0) endRollIndex = int(0) - for i in range(len(Roll)-1,-1,-1): + for i in range(len(Roll) - 1, -1, -1): if abs(Roll[i]) > tilt_threshold: endTime = att_time_us[i] break - for i in range(len(flow_time_us)-1,-1,-1): + for i in range(len(flow_time_us) - 1, -1, -1): if flow_time_us[i] < endTime: endRollIndex = i break # check we have enough roll data points - if (endRollIndex - startRollIndex <= min_num_points): + if endRollIndex - startRollIndex <= min_num_points: FAIL() self.result.statusMessage = "FAIL: insufficient roll data pointsa\n" return @@ -140,7 +152,13 @@ def WARN(): bodyX_resampled = [] flowX_time_us_resampled = [] for i in range(len(Roll)): - if (i >= startRollIndex) and (i <= endRollIndex) and (abs(bodyX[i]) > min_rate_threshold) and (abs(bodyX[i]) < max_rate_threshold) and (flow_qual[i] > quality_threshold): + if ( + (i >= startRollIndex) + and (i <= endRollIndex) + and (abs(bodyX[i]) > min_rate_threshold) + and (abs(bodyX[i]) < max_rate_threshold) + and (flow_qual[i] > quality_threshold) + ): flowX_resampled.append(flowX[i]) bodyX_resampled.append(bodyX[i]) flowX_time_us_resampled.append(flow_time_us[i]) @@ -160,17 +178,17 @@ def WARN(): # calculate the end time for the pitch calibration endTime = 0 endPitchIndex = int(0) - for i in range(len(Pitch)-1,-1,-1): + for i in range(len(Pitch) - 1, -1, -1): if abs(Pitch[i]) > tilt_threshold: endTime = att_time_us[i] break - for i in range(len(flow_time_us)-1,-1,-1): + for i in range(len(flow_time_us) - 1, -1, -1): if flow_time_us[i] < endTime: endPitchIndex = i break # check we have enough pitch data points - if (endPitchIndex - startPitchIndex <= min_num_points): + if endPitchIndex - startPitchIndex <= min_num_points: FAIL() self.result.statusMessage = "FAIL: insufficient pitch data pointsa\n" return @@ -181,34 +199,66 @@ def WARN(): bodyY_resampled = [] flowY_time_us_resampled = [] for i in range(len(Roll)): - if (i >= startPitchIndex) and (i <= endPitchIndex) and (abs(bodyY[i]) > min_rate_threshold) and (abs(bodyY[i]) < max_rate_threshold) and (flow_qual[i] > quality_threshold): + if ( + (i >= startPitchIndex) + and (i <= endPitchIndex) + and (abs(bodyY[i]) > min_rate_threshold) + and (abs(bodyY[i]) < max_rate_threshold) + and (flow_qual[i] > quality_threshold) + ): flowY_resampled.append(flowY[i]) bodyY_resampled.append(bodyY[i]) flowY_time_us_resampled.append(flow_time_us[i]) - # fit a straight line to the flow vs body rate data and calculate the scale factor parameter required to achieve a slope of 1 - coef_flow_x , cov_x = np.polyfit(bodyX_resampled,flowX_resampled,1,rcond=None, full=False, w=None, cov=True) - coef_flow_y , cov_y = np.polyfit(bodyY_resampled,flowY_resampled,1,rcond=None, full=False, w=None, cov=True) + # fit a straight line to the flow vs body rate data and calculate the scale factor parameter required to + # achieve a slope of 1 + coef_flow_x, cov_x = np.polyfit( + bodyX_resampled, flowX_resampled, 1, rcond=None, full=False, w=None, cov=True + ) + coef_flow_y, cov_y = np.polyfit( + bodyY_resampled, flowY_resampled, 1, rcond=None, full=False, w=None, cov=True + ) - # taking the exisiting scale factor parameters into account, calculate the parameter values reequired to achieve a unity slope - flow_fxscaler_new = int(1000 * (((1 + 0.001 * float(flow_fxscaler))/coef_flow_x[0] - 1))) - flow_fyscaler_new = int(1000 * (((1 + 0.001 * float(flow_fyscaler))/coef_flow_y[0] - 1))) + # taking the exisiting scale factor parameters into account, calculate the parameter values reequired to + # achieve a unity slope + flow_fxscaler_new = int(1000 * (((1 + 0.001 * float(flow_fxscaler)) / coef_flow_x[0] - 1))) + flow_fyscaler_new = int(1000 * (((1 + 0.001 * float(flow_fyscaler)) / coef_flow_y[0] - 1))) # Do a sanity check on the scale factor variance if sqrt(cov_x[0][0]) > param_std_threshold or sqrt(cov_y[0][0]) > param_std_threshold: FAIL() - self.result.statusMessage = "FAIL: inaccurate fit - poor quality or insufficient data\nFLOW_FXSCALER 1STD = %u\nFLOW_FYSCALER 1STD = %u\n" % (round(1000*sqrt(cov_x[0][0])),round(1000*sqrt(cov_y[0][0]))) + self.result.statusMessage = ( + "FAIL: inaccurate fit - poor quality or insufficient data" + "\nFLOW_FXSCALER 1STD = %u" + "\nFLOW_FYSCALER 1STD = %u\n" % (round(1000 * sqrt(cov_x[0][0])), round(1000 * sqrt(cov_y[0][0]))) + ) # Do a sanity check on the scale factors if abs(flow_fxscaler_new) > param_abs_threshold or abs(flow_fyscaler_new) > param_abs_threshold: FAIL() - self.result.statusMessage = "FAIL: required scale factors are excessive\nFLOW_FXSCALER=%i\nFLOW_FYSCALER=%i\n" % (flow_fxscaler,flow_fyscaler) + self.result.statusMessage = ( + "FAIL: required scale factors are excessive\nFLOW_FXSCALER=%i\nFLOW_FYSCALER=%i\n" + % (flow_fxscaler, flow_fyscaler) + ) # display recommended scale factors - self.result.statusMessage = "Set FLOW_FXSCALER to %i\nSet FLOW_FYSCALER to %i\n\nCal plots saved to flow_calibration.pdf\nCal parameters saved to flow_calibration.param\n\nFLOW_FXSCALER 1STD = %u\nFLOW_FYSCALER 1STD = %u\n" % (flow_fxscaler_new,flow_fyscaler_new,round(1000*sqrt(cov_x[0][0])),round(1000*sqrt(cov_y[0][0]))) + self.result.statusMessage = ( + "Set FLOW_FXSCALER to %i" + "\nSet FLOW_FYSCALER to %i" + "\n\nCal plots saved to flow_calibration.pdf" + "\nCal parameters saved to flow_calibration.param" + "\n\nFLOW_FXSCALER 1STD = %u" + "\nFLOW_FYSCALER 1STD = %u\n" + % ( + flow_fxscaler_new, + flow_fyscaler_new, + round(1000 * sqrt(cov_x[0][0])), + round(1000 * sqrt(cov_y[0][0])), + ) + ) # calculate fit display data - body_rate_display = [-max_rate_threshold,max_rate_threshold] + body_rate_display = [-max_rate_threshold, max_rate_threshold] fit_coef_x = np.poly1d(coef_flow_x) flowX_display = fit_coef_x(body_rate_display) fit_coef_y = np.poly1d(coef_flow_y) @@ -216,13 +266,14 @@ def WARN(): # plot and save calibration test points to PDF from matplotlib.backends.backend_pdf import PdfPages + output_plot_filename = "flow_calibration.pdf" pp = PdfPages(output_plot_filename) - plt.figure(1,figsize=(20,13)) - plt.subplot(2,1,1) - plt.plot(bodyX_resampled,flowX_resampled,'b', linestyle=' ', marker='o',label="test points") - plt.plot(body_rate_display,flowX_display,'r',linewidth=2.5,label="linear fit") + plt.figure(1, figsize=(20, 13)) + plt.subplot(2, 1, 1) + plt.plot(bodyX_resampled, flowX_resampled, 'b', linestyle=' ', marker='o', label="test points") + plt.plot(body_rate_display, flowX_display, 'r', linewidth=2.5, label="linear fit") plt.title('X axis flow rate vs gyro rate') plt.ylabel('flow rate (rad/s)') plt.xlabel('gyro rate (rad/sec)') @@ -230,9 +281,9 @@ def WARN(): plt.legend(loc='upper left') # draw plots - plt.subplot(2,1,2) - plt.plot(bodyY_resampled,flowY_resampled,'b', linestyle=' ', marker='o',label="test points") - plt.plot(body_rate_display,flowY_display,'r',linewidth=2.5,label="linear fit") + plt.subplot(2, 1, 2) + plt.plot(bodyY_resampled, flowY_resampled, 'b', linestyle=' ', marker='o', label="test points") + plt.plot(body_rate_display, flowY_display, 'r', linewidth=2.5, label="linear fit") plt.title('Y axis flow rate vs gyro rate') plt.ylabel('flow rate (rad/s)') plt.xlabel('gyro rate (rad/sec)') @@ -241,12 +292,12 @@ def WARN(): pp.savefig() - plt.figure(2,figsize=(20,13)) - plt.subplot(2,1,1) - plt.plot(flow_time_us,flowX,'b',label="flow rate - all") - plt.plot(flow_time_us,bodyX,'r',label="gyro rate - all") - plt.plot(flowX_time_us_resampled,flowX_resampled,'c', linestyle=' ', marker='o',label="flow rate - used") - plt.plot(flowX_time_us_resampled,bodyX_resampled,'m', linestyle=' ', marker='o',label="gyro rate - used") + plt.figure(2, figsize=(20, 13)) + plt.subplot(2, 1, 1) + plt.plot(flow_time_us, flowX, 'b', label="flow rate - all") + plt.plot(flow_time_us, bodyX, 'r', label="gyro rate - all") + plt.plot(flowX_time_us_resampled, flowX_resampled, 'c', linestyle=' ', marker='o', label="flow rate - used") + plt.plot(flowX_time_us_resampled, bodyX_resampled, 'm', linestyle=' ', marker='o', label="gyro rate - used") plt.title('X axis flow and body rate vs time') plt.ylabel('rate (rad/s)') plt.xlabel('time (usec)') @@ -254,11 +305,11 @@ def WARN(): plt.legend(loc='upper left') # draw plots - plt.subplot(2,1,2) - plt.plot(flow_time_us,flowY,'b',label="flow rate - all") - plt.plot(flow_time_us,bodyY,'r',label="gyro rate - all") - plt.plot(flowY_time_us_resampled,flowY_resampled,'c', linestyle=' ', marker='o',label="flow rate - used") - plt.plot(flowY_time_us_resampled,bodyY_resampled,'m', linestyle=' ', marker='o',label="gyro rate - used") + plt.subplot(2, 1, 2) + plt.plot(flow_time_us, flowY, 'b', label="flow rate - all") + plt.plot(flow_time_us, bodyY, 'r', label="gyro rate - all") + plt.plot(flowY_time_us_resampled, flowY_resampled, 'c', linestyle=' ', marker='o', label="flow rate - used") + plt.plot(flowY_time_us_resampled, bodyY_resampled, 'm', linestyle=' ', marker='o', label="gyro rate - used") plt.title('Y axis flow and body rate vs time') plt.ylabel('rate (rad/s)') plt.xlabel('time (usec)') @@ -275,21 +326,11 @@ def WARN(): # write correction parameters to file test_results_filename = "flow_calibration.param" - file = open(test_results_filename,"w") - file.write("FLOW_FXSCALER"+" "+str(flow_fxscaler_new)+"\n") - file.write("FLOW_FYSCALER"+" "+str(flow_fyscaler_new)+"\n") + file = open(test_results_filename, "w") + file.write("FLOW_FXSCALER" + " " + str(flow_fxscaler_new) + "\n") + file.write("FLOW_FYSCALER" + " " + str(flow_fyscaler_new) + "\n") file.close() except KeyError as e: self.result.status = TestResult.StatusType.FAIL self.result.statusMessage = str(e) + ' not found' - - - - - - - - - - diff --git a/Tools/LogAnalyzer/tests/TestParams.py b/Tools/LogAnalyzer/tests/TestParams.py index a98bca562d9..aedcf762166 100644 --- a/Tools/LogAnalyzer/tests/TestParams.py +++ b/Tools/LogAnalyzer/tests/TestParams.py @@ -1,9 +1,11 @@ +# AP_FLAKE8_CLEAN + + +import math # for isnan() + from LogAnalyzer import Test, TestResult -import DataflashLog from VehicleType import VehicleType -import math # for isnan() - class TestParams(Test): '''test for any obviously bad parameters in the config''' @@ -12,44 +14,58 @@ def __init__(self): Test.__init__(self) self.name = "Parameters" - # helper functions def __checkParamIsEqual(self, paramName, expectedValue, logdata): value = logdata.parameters[paramName] if value != expectedValue: self.result.status = TestResult.StatusType.FAIL - self.result.statusMessage = self.result.statusMessage + "%s set to %s, expecting %s\n" % (paramName, repr(value), repr(expectedValue)) + self.result.statusMessage = self.result.statusMessage + "%s set to %s, expecting %s\n" % ( + paramName, + repr(value), + repr(expectedValue), + ) + def __checkParamIsLessThan(self, paramName, maxValue, logdata): value = logdata.parameters[paramName] if value >= maxValue: self.result.status = TestResult.StatusType.FAIL - self.result.statusMessage = self.result.statusMessage + "%s set to %s, expecting less than %s\n" % (paramName, repr(value), repr(maxValue)) + self.result.statusMessage = self.result.statusMessage + "%s set to %s, expecting less than %s\n" % ( + paramName, + repr(value), + repr(maxValue), + ) + def __checkParamIsMoreThan(self, paramName, minValue, logdata): value = logdata.parameters[paramName] if value <= minValue: self.result.status = TestResult.StatusType.FAIL - self.result.statusMessage = self.result.statusMessage + "%s set to %s, expecting less than %s\n" % (paramName, repr(value), repr(minValue)) - + self.result.statusMessage = self.result.statusMessage + "%s set to %s, expecting less than %s\n" % ( + paramName, + repr(value), + repr(minValue), + ) def run(self, logdata, verbose): self.result = TestResult() self.result.status = TestResult.StatusType.GOOD # GOOD by default, tests below will override it if they fail # check all params for NaN - for name,value in logdata.parameters.items(): + for name, value in logdata.parameters.items(): if math.isnan(value): self.result.status = TestResult.StatusType.FAIL self.result.statusMessage = self.result.statusMessage + name + " is NaN\n" try: - # add parameter checks below using the helper functions, any failures will trigger a FAIL status and accumulate info in statusMessage - # if more complex checking or correlations are required you can access parameter values directly using the logdata.parameters[paramName] dict + # add parameter checks below using the helper functions, any failures will trigger a FAIL status and + # accumulate info in statusMessage. + # If more complex checking or correlations are required you can access parameter values directly using the + # logdata.parameters[paramName] dict if logdata.vehicleType == VehicleType.Copter: - self.__checkParamIsEqual ("MAG_ENABLE", 1, logdata) + self.__checkParamIsEqual("MAG_ENABLE", 1, logdata) if "THR_MIN" in logdata.parameters: - self.__checkParamIsLessThan("THR_MIN", 200, logdata) - self.__checkParamIsLessThan("THR_MID", 701, logdata) - self.__checkParamIsMoreThan("THR_MID", 299, logdata) + self.__checkParamIsLessThan("THR_MIN", 200, logdata) + self.__checkParamIsLessThan("THR_MID", 701, logdata) + self.__checkParamIsMoreThan("THR_MID", 299, logdata) # TODO: add more parameter tests, these are just an example... elif logdata.vehicleType == VehicleType.Plane: # TODO: add parameter checks for plane... diff --git a/Tools/LogAnalyzer/tests/TestPerformance.py b/Tools/LogAnalyzer/tests/TestPerformance.py index d420e5250ee..a4e2ebddc2a 100644 --- a/Tools/LogAnalyzer/tests/TestPerformance.py +++ b/Tools/LogAnalyzer/tests/TestPerformance.py @@ -1,9 +1,12 @@ +# AP_FLAKE8_CLEAN + + from __future__ import print_function from LogAnalyzer import Test, TestResult -import DataflashLog from VehicleType import VehicleType + class TestPerformance(Test): '''check performance monitoring messages (PM) for issues with slow loops, etc''' @@ -20,7 +23,8 @@ def run(self, logdata, verbose): self.result.status = TestResult.StatusType.NA return - # NOTE: we'll ignore MaxT altogether for now, it seems there are quite regularly one or two high values in there, even ignoring the ones expected after arm/disarm events + # NOTE: we'll ignore MaxT altogether for now, it seems there are quite regularly one or two high values in + # there, even ignoring the ones expected after arm/disarm events. # gather info on arm/disarm lines, we will ignore the MaxT data from the first line found after each of these # armingLines = [] # for line,ev in logdata.channels["EV"]["Id"].listData: @@ -29,9 +33,8 @@ def run(self, logdata, verbose): # ignoreMaxTLines = [] # for maxT in logdata.channels["PM"]["MaxT"].listData: # if not armingLines: - # break + # break # if maxT[0] > armingLines[0]: - # #print("Ignoring maxT from line %d, as it is the first PM line after arming on line %d" % (maxT[0],armingLines[0])) # ignoreMaxTLines.append(maxT[0]) # armingLines.pop(0) @@ -45,22 +48,26 @@ def run(self, logdata, verbose): maxPercentSlowLine = 0 slowLoopLineCount = 0 for i in range(len(logdata.channels["PM"]["NLon"].listData)): - (line, nLon) = logdata.channels["PM"]["NLon"].listData[i] + (line, nLon) = logdata.channels["PM"]["NLon"].listData[i] (line, nLoop) = logdata.channels["PM"]["NLoop"].listData[i] - (line, maxT) = logdata.channels["PM"]["MaxT"].listData[i] + (line, maxT) = logdata.channels["PM"]["MaxT"].listData[i] percentSlow = (nLon / float(nLoop)) * 100 if percentSlow > 6.0: slowLoopLineCount = slowLoopLineCount + 1 if percentSlow > maxPercentSlow: maxPercentSlow = percentSlow maxPercentSlowLine = line - #if (maxT > 13000) and line not in ignoreMaxTLines: - # print("MaxT of %d detected on line %d" % (maxT,line)) if (maxPercentSlow > 10) or (slowLoopLineCount > 6): self.result.status = TestResult.StatusType.FAIL - self.result.statusMessage = "%d slow loop lines found, max %.2f%% on line %d" % (slowLoopLineCount,maxPercentSlow,maxPercentSlowLine) - elif (maxPercentSlow > 6): + self.result.statusMessage = "%d slow loop lines found, max %.2f%% on line %d" % ( + slowLoopLineCount, + maxPercentSlow, + maxPercentSlowLine, + ) + elif maxPercentSlow > 6: self.result.status = TestResult.StatusType.WARN - self.result.statusMessage = "%d slow loop lines found, max %.2f%% on line %d" % (slowLoopLineCount,maxPercentSlow,maxPercentSlowLine) - - + self.result.statusMessage = "%d slow loop lines found, max %.2f%% on line %d" % ( + slowLoopLineCount, + maxPercentSlow, + maxPercentSlowLine, + ) diff --git a/Tools/LogAnalyzer/tests/TestPitchRollCoupling.py b/Tools/LogAnalyzer/tests/TestPitchRollCoupling.py index 69a19450b7f..1da9f6df809 100644 --- a/Tools/LogAnalyzer/tests/TestPitchRollCoupling.py +++ b/Tools/LogAnalyzer/tests/TestPitchRollCoupling.py @@ -1,18 +1,22 @@ -from LogAnalyzer import Test,TestResult -import DataflashLog -from VehicleType import VehicleType +# AP_FLAKE8_CLEAN + import collections +import DataflashLog +from LogAnalyzer import Test, TestResult +from VehicleType import VehicleType + class TestPitchRollCoupling(Test): '''test for divergence between input and output pitch/roll, i.e. mechanical failure or bad PID tuning''' - # TODO: currently we're only checking for roll/pitch outside of max lean angle, will come back later to analyze roll/pitch in versus out values + + # TODO: currently we're only checking for roll/pitch outside of max lean angle, will come back later to analyze + # roll/pitch in versus out values def __init__(self): Test.__init__(self) self.name = "Pitch/Roll" - self.enable = True # TEMP def run(self, logdata, verbose): self.result = TestResult() @@ -22,12 +26,12 @@ def run(self, logdata, verbose): self.result.status = TestResult.StatusType.NA return - if not "ATT" in logdata.channels: + if "ATT" not in logdata.channels: self.result.status = TestResult.StatusType.UNKNOWN self.result.statusMessage = "No ATT log data" return - if not "CTUN" in logdata.channels: + if "CTUN" not in logdata.channels: self.result.status = TestResult.StatusType.UNKNOWN self.result.statusMessage = "No CTUN log data" return @@ -37,105 +41,123 @@ def run(self, logdata, verbose): else: self.ctun_baralt_att = 'BAlt' - # figure out where each mode begins and ends, so we can treat auto and manual modes differently and ignore acro/tune modes - autoModes = ["RTL", - "AUTO", - "LAND", - "LOITER", - "GUIDED", - "CIRCLE", - "OF_LOITER", - "POSHOLD", - "BRAKE", - "AVOID_ADSB", - "GUIDED_NOGPS", - "SMARTRTL"] + # figure out where each mode begins and ends, so we can treat auto and manual modes differently and ignore + # acro/tune modes + autoModes = [ + "RTL", + "AUTO", + "LAND", + "LOITER", + "GUIDED", + "CIRCLE", + "OF_LOITER", + "POSHOLD", + "BRAKE", + "AVOID_ADSB", + "GUIDED_NOGPS", + "SMARTRTL", + ] # use CTUN RollIn/DesRoll + PitchIn/DesPitch manualModes = ["STABILIZE", "DRIFT", "ALTHOLD", "ALT_HOLD", "POSHOLD"] # ignore data from these modes: - ignoreModes = ["ACRO", "SPORT", "FLIP", "AUTOTUNE","", "THROW",] - autoSegments = [] # list of (startLine,endLine) pairs + ignoreModes = [ + "ACRO", + "SPORT", + "FLIP", + "AUTOTUNE", + "", + "THROW", + ] + autoSegments = [] # list of (startLine,endLine) pairs manualSegments = [] # list of (startLine,endLine) pairs orderedModes = collections.OrderedDict(sorted(logdata.modeChanges.items(), key=lambda t: t[0])) - isAuto = False # we always start in a manual control mode + isAuto = False # we always start in a manual control mode prevLine = 0 mode = "" - for line,modepair in orderedModes.items(): + for line, modepair in orderedModes.items(): mode = modepair[0].upper() if prevLine == 0: prevLine = line if mode in autoModes: if not isAuto: - manualSegments.append((prevLine,line-1)) + manualSegments.append((prevLine, line - 1)) prevLine = line isAuto = True elif mode in manualModes: if isAuto: - autoSegments.append((prevLine,line-1)) + autoSegments.append((prevLine, line - 1)) prevLine = line isAuto = False elif mode in ignoreModes: if isAuto: - autoSegments.append((prevLine,line-1)) + autoSegments.append((prevLine, line - 1)) else: - manualSegments.append((prevLine,line-1)) + manualSegments.append((prevLine, line - 1)) prevLine = 0 else: raise Exception("Unknown mode in TestPitchRollCoupling: %s" % mode) # and handle the last segment, which doesn't have an ending if mode in autoModes: - autoSegments.append((prevLine,logdata.lineCount)) + autoSegments.append((prevLine, logdata.lineCount)) elif mode in manualModes: - manualSegments.append((prevLine,logdata.lineCount)) + manualSegments.append((prevLine, logdata.lineCount)) # figure out max lean angle, the ANGLE_MAX param was added in AC3.1 maxLeanAngle = 45.0 if "ANGLE_MAX" in logdata.parameters: maxLeanAngle = logdata.parameters["ANGLE_MAX"] / 100.0 - maxLeanAngleBuffer = 10 # allow a buffer margin + maxLeanAngleBuffer = 10 # allow a buffer margin # ignore anything below this altitude, to discard any data while not flying minAltThreshold = 2.0 # look through manual+auto flight segments # TODO: filter to ignore single points outside range? - (maxRoll, maxRollLine) = (0.0, 0) + (maxRoll, maxRollLine) = (0.0, 0) (maxPitch, maxPitchLine) = (0.0, 0) - for (startLine,endLine) in manualSegments+autoSegments: + for (startLine, endLine) in manualSegments + autoSegments: # quick up-front test, only fallover into more complex line-by-line check if max()>threshold - rollSeg = logdata.channels["ATT"]["Roll"].getSegment(startLine,endLine) - pitchSeg = logdata.channels["ATT"]["Pitch"].getSegment(startLine,endLine) + rollSeg = logdata.channels["ATT"]["Roll"].getSegment(startLine, endLine) + pitchSeg = logdata.channels["ATT"]["Pitch"].getSegment(startLine, endLine) if not rollSeg.dictData and not pitchSeg.dictData: continue # check max roll+pitch for any time where relative altitude is above minAltThreshold - roll = max(abs(rollSeg.min()), abs(rollSeg.max())) + roll = max(abs(rollSeg.min()), abs(rollSeg.max())) pitch = max(abs(pitchSeg.min()), abs(pitchSeg.max())) - if (roll>(maxLeanAngle+maxLeanAngleBuffer) and abs(roll)>abs(maxRoll)) or (pitch>(maxLeanAngle+maxLeanAngleBuffer) and abs(pitch)>abs(maxPitch)): + if (roll > (maxLeanAngle + maxLeanAngleBuffer) and abs(roll) > abs(maxRoll)) or ( + pitch > (maxLeanAngle + maxLeanAngleBuffer) and abs(pitch) > abs(maxPitch) + ): lit = DataflashLog.LogIterator(logdata, startLine) - assert(lit.currentLine == startLine) + assert lit.currentLine == startLine while lit.currentLine <= endLine: relativeAlt = lit["CTUN"][self.ctun_baralt_att] if relativeAlt > minAltThreshold: - roll = lit["ATT"]["Roll"] + roll = lit["ATT"]["Roll"] pitch = lit["ATT"]["Pitch"] - if abs(roll)>(maxLeanAngle+maxLeanAngleBuffer) and abs(roll)>abs(maxRoll): + if abs(roll) > (maxLeanAngle + maxLeanAngleBuffer) and abs(roll) > abs(maxRoll): maxRoll = roll maxRollLine = lit.currentLine - if abs(pitch)>(maxLeanAngle+maxLeanAngleBuffer) and abs(pitch)>abs(maxPitch): + if abs(pitch) > (maxLeanAngle + maxLeanAngleBuffer) and abs(pitch) > abs(maxPitch): maxPitch = pitch maxPitchLine = lit.currentLine next(lit) # check for breaking max lean angles - if maxRoll and abs(maxRoll)>abs(maxPitch): + if maxRoll and abs(maxRoll) > abs(maxPitch): self.result.status = TestResult.StatusType.FAIL - self.result.statusMessage = "Roll (%.2f, line %d) > maximum lean angle (%.2f)" % (maxRoll, maxRollLine, maxLeanAngle) + self.result.statusMessage = "Roll (%.2f, line %d) > maximum lean angle (%.2f)" % ( + maxRoll, + maxRollLine, + maxLeanAngle, + ) return if maxPitch: self.result.status = TestResult.StatusType.FAIL - self.result.statusMessage = "Pitch (%.2f, line %d) > maximum lean angle (%.2f)" % (maxPitch, maxPitchLine, maxLeanAngle) + self.result.statusMessage = "Pitch (%.2f, line %d) > maximum lean angle (%.2f)" % ( + maxPitch, + maxPitchLine, + maxLeanAngle, + ) return - - # TODO: use numpy/scipy to check Roll+RollIn curves for fitness (ignore where we're not airborne) # ... diff --git a/Tools/LogAnalyzer/tests/TestThrust.py b/Tools/LogAnalyzer/tests/TestThrust.py index af3e14a4146..c33ebc9cb03 100644 --- a/Tools/LogAnalyzer/tests/TestThrust.py +++ b/Tools/LogAnalyzer/tests/TestThrust.py @@ -1,7 +1,9 @@ +# AP_FLAKE8_CLEAN + + from __future__ import print_function from LogAnalyzer import Test, TestResult -import DataflashLog from VehicleType import VehicleType @@ -11,7 +13,7 @@ class TestThrust(Test): def __init__(self): Test.__init__(self) self.name = "Thrust" - + def run(self, logdata, verbose): self.result = TestResult() self.result.status = TestResult.StatusType.GOOD @@ -20,11 +22,11 @@ def run(self, logdata, verbose): self.result.status = TestResult.StatusType.NA return - if not "CTUN" in logdata.channels: + if "CTUN" not in logdata.channels: self.result.status = TestResult.StatusType.UNKNOWN self.result.statusMessage = "No CTUN log data" return - if not "ATT" in logdata.channels: + if "ATT" not in logdata.channels: self.result.status = TestResult.StatusType.UNKNOWN self.result.statusMessage = "No ATT log data" return @@ -42,31 +44,31 @@ def run(self, logdata, verbose): # check for throttle (CTUN.ThrOut) above 700 for a chunk of time with copter not rising highThrottleThreshold = 700 - tiltThreshold = 20 # ignore high throttle when roll or tilt is above this value + tiltThreshold = 20 # ignore high throttle when roll or tilt is above this value climbThresholdWARN = 100 climbThresholdFAIL = 50 minSampleLength = 50 highThrottleSegments = [] - # find any contiguous chunks where CTUN.ThrOut > highThrottleThreshold, ignore high throttle if tilt > tiltThreshold, and discard any segments shorter than minSampleLength + # find any contiguous chunks where CTUN.ThrOut > highThrottleThreshold, ignore high throttle if + # tilt > tiltThreshold, and discard any segments shorter than minSampleLength start = None data = logdata.channels["CTUN"][throut_key].listData - for i in range(0,len(data)): - (lineNumber,value) = data[i] + for i in range(0, len(data)): + (lineNumber, value) = data[i] isBelowTiltThreshold = True if value > highThrottleThreshold: - (roll,meh) = logdata.channels["ATT"]["Roll"].getNearestValue(lineNumber) - (pitch,meh) = logdata.channels["ATT"]["Pitch"].getNearestValue(lineNumber) + (roll, meh) = logdata.channels["ATT"]["Roll"].getNearestValue(lineNumber) + (pitch, meh) = logdata.channels["ATT"]["Pitch"].getNearestValue(lineNumber) if (abs(roll) > tiltThreshold) or (abs(pitch) > tiltThreshold): isBelowTiltThreshold = False if (value > highThrottleThreshold) and isBelowTiltThreshold: - if start == None: + if start is None: start = i - elif start != None: - if (i-start) > minSampleLength: - #print("Found high throttle chunk from line %d to %d (%d samples)" % (data[start][0],data[i][0],i-start+1)) - highThrottleSegments.append((start,i)) + elif start is not None: + if (i - start) > minSampleLength: + highThrottleSegments.append((start, i)) start = None climbRate = "CRate" @@ -76,16 +78,13 @@ def run(self, logdata, verbose): # loop through each checking climbRate, if < 50 FAIL, if < 100 WARN # TODO: we should filter climbRate and use its slope rather than value for this test for seg in highThrottleSegments: - (startLine,endLine) = (data[seg[0]][0], data[seg[1]][0]) - avgClimbRate = logdata.channels["CTUN"][climbRate].getSegment(startLine,endLine).avg() - avgThrOut = logdata.channels["CTUN"][throut_key].getSegment(startLine,endLine).avg() + (startLine, endLine) = (data[seg[0]][0], data[seg[1]][0]) + avgClimbRate = logdata.channels["CTUN"][climbRate].getSegment(startLine, endLine).avg() + avgThrOut = logdata.channels["CTUN"][throut_key].getSegment(startLine, endLine).avg() if avgClimbRate < climbThresholdFAIL: self.result.status = TestResult.StatusType.FAIL - self.result.statusMessage = "Avg climb rate %.2f cm/s for throttle avg %d" % (avgClimbRate,avgThrOut) + self.result.statusMessage = "Avg climb rate %.2f cm/s for throttle avg %d" % (avgClimbRate, avgThrOut) return if avgClimbRate < climbThresholdWARN: self.result.status = TestResult.StatusType.WARN - self.result.statusMessage = "Avg climb rate %.2f cm/s for throttle avg %d" % (avgClimbRate,avgThrOut) - - - + self.result.statusMessage = "Avg climb rate %.2f cm/s for throttle avg %d" % (avgClimbRate, avgThrOut) diff --git a/Tools/LogAnalyzer/tests/TestVCC.py b/Tools/LogAnalyzer/tests/TestVCC.py index 95cd833943b..fedef39d16e 100644 --- a/Tools/LogAnalyzer/tests/TestVCC.py +++ b/Tools/LogAnalyzer/tests/TestVCC.py @@ -1,7 +1,6 @@ -from LogAnalyzer import Test,TestResult -import DataflashLog +# AP_FLAKE8_CLEAN -import collections +from LogAnalyzer import Test, TestResult class TestVCC(Test): @@ -15,28 +14,30 @@ def run(self, logdata, verbose): self.result = TestResult() self.result.status = TestResult.StatusType.GOOD - if not "CURR" in logdata.channels: + if "CURR" not in logdata.channels: self.result.status = TestResult.StatusType.UNKNOWN self.result.statusMessage = "No CURR log data" return # just a naive min/max test for now try: - vccMin = logdata.channels["CURR"]["Vcc"].min() - vccMax = logdata.channels["CURR"]["Vcc"].max() - except KeyError as e: - vccMin = logdata.channels["POWR"]["Vcc"].min() - vccMax = logdata.channels["POWR"]["Vcc"].max() + vccMin = logdata.channels["CURR"]["Vcc"].min() + vccMax = logdata.channels["CURR"]["Vcc"].max() + except KeyError: + vccMin = logdata.channels["POWR"]["Vcc"].min() + vccMax = logdata.channels["POWR"]["Vcc"].max() vccMin *= 1000 vccMax *= 1000 - vccDiff = vccMax - vccMin; - vccMinThreshold = 4.6 * 1000; - vccMaxDiff = 0.3 * 1000; + vccDiff = vccMax - vccMin + vccMinThreshold = 4.6 * 1000 + vccMaxDiff = 0.3 * 1000 if vccDiff > vccMaxDiff: self.result.status = TestResult.StatusType.WARN - self.result.statusMessage = "VCC min/max diff %sv, should be <%sv" % (vccDiff/1000.0, vccMaxDiff/1000.0) + self.result.statusMessage = "VCC min/max diff %sv, should be <%sv" % (vccDiff / 1000.0, vccMaxDiff / 1000.0) elif vccMin < vccMinThreshold: self.result.status = TestResult.StatusType.FAIL - self.result.statusMessage = "VCC below minimum of %sv (%sv)" % (repr(vccMinThreshold/1000.0),repr(vccMin/1000.0)) - + self.result.statusMessage = "VCC below minimum of %sv (%sv)" % ( + repr(vccMinThreshold / 1000.0), + repr(vccMin / 1000.0), + ) diff --git a/Tools/LogAnalyzer/tests/TestVibration.py b/Tools/LogAnalyzer/tests/TestVibration.py index a7dc9fa1c3e..ac7d6e9979b 100644 --- a/Tools/LogAnalyzer/tests/TestVibration.py +++ b/Tools/LogAnalyzer/tests/TestVibration.py @@ -1,10 +1,12 @@ +# AP_FLAKE8_CLEAN + + from __future__ import print_function -from LogAnalyzer import Test, TestResult import DataflashLog -from VehicleType import VehicleType - import numpy +from LogAnalyzer import Test, TestResult +from VehicleType import VehicleType class TestVibration(Test): @@ -14,7 +16,6 @@ def __init__(self): Test.__init__(self) self.name = "Vibration" - def run(self, logdata, verbose): self.result = TestResult() @@ -23,13 +24,12 @@ def run(self, logdata, verbose): return # constants - gravity = -9.81 aimRangeWarnXY = 1.5 aimRangeFailXY = 3.0 - aimRangeWarnZ = 2.0 # gravity +/- aim range - aimRangeFailZ = 5.0 # gravity +/- aim range + aimRangeWarnZ = 2.0 # gravity +/- aim range + aimRangeFailZ = 5.0 # gravity +/- aim range - if not "IMU" in logdata.channels: + if "IMU" not in logdata.channels: self.result.status = TestResult.StatusType.UNKNOWN self.result.statusMessage = "No IMU log data" return @@ -38,33 +38,39 @@ def run(self, logdata, verbose): chunks = DataflashLog.DataflashLogHelper.findLoiterChunks(logdata, minLengthSeconds=10, noRCInputs=True) if not chunks: self.result.status = TestResult.StatusType.UNKNOWN - self.result.statusMessage = "No stable LOITER log data found" + self.result.statusMessage = "No stable LOITER log data found" return # for now we'll just use the first (largest) chunk of LOITER data - # TODO: ignore the first couple of secs to avoid bad data during transition - or can we check more analytically that we're stable? + # TODO: ignore the first couple of secs to avoid bad data during transition - or can we check more analytically + # that we're stable? # TODO: accumulate all LOITER chunks over min size, or just use the largest one? startLine = chunks[0][0] - endLine = chunks[0][1] - #print("TestVibration using LOITER chunk from lines %s to %s" % (repr(startLine), repr(endLine))) + endLine = chunks[0][1] - def getStdDevIMU(logdata, channelName, startLine,endLine): - loiterData = logdata.channels["IMU"][channelName].getSegment(startLine,endLine) - numpyData = numpy.array(loiterData.dictData.values()) + def getStdDevIMU(logdata, channelName, startLine, endLine): + loiterData = logdata.channels["IMU"][channelName].getSegment(startLine, endLine) + numpyData = numpy.array(loiterData.dictData.values()) return numpy.std(numpyData) # use 2x standard deviations as the metric, so if 95% of samples lie within the aim range we're good - stdDevX = abs(2 * getStdDevIMU(logdata,"AccX",startLine,endLine)) - stdDevY = abs(2 * getStdDevIMU(logdata,"AccY",startLine,endLine)) - stdDevZ = abs(2 * getStdDevIMU(logdata,"AccZ",startLine,endLine)) + stdDevX = abs(2 * getStdDevIMU(logdata, "AccX", startLine, endLine)) + stdDevY = abs(2 * getStdDevIMU(logdata, "AccY", startLine, endLine)) + stdDevZ = abs(2 * getStdDevIMU(logdata, "AccZ", startLine, endLine)) if (stdDevX > aimRangeFailXY) or (stdDevY > aimRangeFailXY) or (stdDevZ > aimRangeFailZ): self.result.status = TestResult.StatusType.FAIL - self.result.statusMessage = "Vibration too high (X:%.2fg, Y:%.2fg, Z:%.2fg)" % (stdDevX,stdDevY,stdDevZ) + self.result.statusMessage = "Vibration too high (X:%.2fg, Y:%.2fg, Z:%.2fg)" % (stdDevX, stdDevY, stdDevZ) elif (stdDevX > aimRangeWarnXY) or (stdDevY > aimRangeWarnXY) or (stdDevZ > aimRangeWarnZ): self.result.status = TestResult.StatusType.WARN - self.result.statusMessage = "Vibration slightly high (X:%.2fg, Y:%.2fg, Z:%.2fg)" % (stdDevX,stdDevY,stdDevZ) + self.result.statusMessage = "Vibration slightly high (X:%.2fg, Y:%.2fg, Z:%.2fg)" % ( + stdDevX, + stdDevY, + stdDevZ, + ) else: self.result.status = TestResult.StatusType.GOOD - self.result.statusMessage = "Good vibration values (X:%.2fg, Y:%.2fg, Z:%.2fg)" % (stdDevX,stdDevY,stdDevZ) - - + self.result.statusMessage = "Good vibration values (X:%.2fg, Y:%.2fg, Z:%.2fg)" % ( + stdDevX, + stdDevY, + stdDevZ, + ) diff --git a/Tools/Pozyx/IndoorLoiter/IndoorLoiter.ino b/Tools/Pozyx/IndoorLoiter/IndoorLoiter.ino index 0b004b99a39..e09934fe72d 100644 --- a/Tools/Pozyx/IndoorLoiter/IndoorLoiter.ino +++ b/Tools/Pozyx/IndoorLoiter/IndoorLoiter.ino @@ -471,4 +471,4 @@ void send_message(uint8_t msg_id, uint8_t data_len, uint8_t data_buf[]) num_sent += fcboardSerial.write(&checksum, 1); fcboardSerial.flush(); } - + diff --git a/Tools/PrintVersion.py b/Tools/PrintVersion.py old mode 100644 new mode 100755 index 982c3a5b829..4e42b445d28 --- a/Tools/PrintVersion.py +++ b/Tools/PrintVersion.py @@ -2,6 +2,9 @@ """ Extract version information for the various vehicle types, print it + +AP_FLAKE8_CLEAN + """ import os @@ -39,8 +42,8 @@ file = open(includefilepath) -firmware_version_regex = re.compile(".*define +FIRMWARE_VERSION.*") -firmware_version_extract_regex = re.compile(".*define +FIRMWARE_VERSION[ ]+(?P\d+)[ ]*,[ ]*(?P\d+)[ ]*,[ ]*(?P\d+)[ ]*,[ ]*(?P[A-Z_]+)[ ]*") +firmware_version_regex = re.compile(r".*define +FIRMWARE_VERSION.*") +firmware_version_extract_regex = re.compile(r".*define +FIRMWARE_VERSION[ ]+(?P\d+)[ ]*,[ ]*(?P\d+)[ ]*,[ ]*(?P\d+)[ ]*,[ ]*(?P[A-Z_]+)[ ]*") # noqa: E501 for line in file: if not firmware_version_regex.match(line): diff --git a/Tools/Replay/LR_MsgHandler.cpp b/Tools/Replay/LR_MsgHandler.cpp index 8af008248d1..8b9d2bd4315 100644 --- a/Tools/Replay/LR_MsgHandler.cpp +++ b/Tools/Replay/LR_MsgHandler.cpp @@ -71,6 +71,8 @@ void LR_MsgHandler_REV2::process_message(uint8_t *msgbytes) case AP_DAL::Event::checkLaneSwitch: ekf2.checkLaneSwitch(); break; + case AP_DAL::Event::setSourceSet0 ... AP_DAL::Event::setSourceSet2: + break; } if (replay_force_ekf3) { LR_MsgHandler_REV3 h{f, ekf2, ekf3}; @@ -128,6 +130,9 @@ void LR_MsgHandler_REV3::process_message(uint8_t *msgbytes) case AP_DAL::Event::checkLaneSwitch: ekf3.checkLaneSwitch(); break; + case AP_DAL::Event::setSourceSet0 ... AP_DAL::Event::setSourceSet2: + ekf3.setPosVelYawSourceSet(uint8_t(msg.event)-uint8_t(AP_DAL::Event::setSourceSet0)); + break; } if (replay_force_ekf2) { diff --git a/Tools/Replay/Replay.cpp b/Tools/Replay/Replay.cpp index c42085e5b75..84c8cd96a19 100644 --- a/Tools/Replay/Replay.cpp +++ b/Tools/Replay/Replay.cpp @@ -25,6 +25,7 @@ #include #include #include +#include #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX #include @@ -110,8 +111,10 @@ bool AP_AdvancedFailsafe::gcs_terminate(bool should_terminate, const char *reaso // dummy method to avoid linking AP_Avoidance // AP_Avoidance *AP::ap_avoidance() { return nullptr; } +#if AP_LTM_TELEM_ENABLED // avoid building/linking LTM: void AP_LTM_Telem::init() {}; +#endif #if AP_DEVO_TELEM_ENABLED // avoid building/linking Devo: void AP_DEVO_Telem::init() {}; diff --git a/Tools/Replay/Replay.h b/Tools/Replay/Replay.h index 2e72bb5ba54..fd1c4b2a77f 100644 --- a/Tools/Replay/Replay.h +++ b/Tools/Replay/Replay.h @@ -31,7 +31,7 @@ class ReplayVehicle : public AP_Vehicle { public: friend class Replay; - ReplayVehicle() { unused = -1; } + ReplayVehicle() { unused.set(-1); } // HAL::Callbacks implementation. void load_parameters(void) override; void get_scheduler_tasks(const AP_Scheduler::Task *&tasks, diff --git a/Tools/Replay/check_replay.py b/Tools/Replay/check_replay.py index be30f2cb680..32a49ea5556 100755 --- a/Tools/Replay/check_replay.py +++ b/Tools/Replay/check_replay.py @@ -6,7 +6,7 @@ from __future__ import print_function -def check_log(logfile, progress=print, ekf2_only=False, ekf3_only=False, verbose=False, accuracy=0.0): +def check_log(logfile, progress=print, ekf2_only=False, ekf3_only=False, verbose=False, accuracy=0.0, ignores=set()): '''check replay log for matching output''' from pymavlink import mavutil progress("Processing log %s" % logfile) @@ -56,6 +56,8 @@ def check_log(logfile, progress=print, ekf2_only=False, ekf3_only=False, verbose for f in m._fieldnames: if f == 'C': continue + if "%s.%s" % (mtype, f) in ignores: + continue v1 = getattr(m,f) v2 = getattr(mb,f) ok = v1 == v2 @@ -91,13 +93,14 @@ def check_log(logfile, progress=print, ekf2_only=False, ekf3_only=False, verbose parser.add_argument("--ekf3-only", action='store_true', help="only check EKF3") parser.add_argument("--verbose", action='store_true', help="verbose output") parser.add_argument("--accuracy", type=float, default=0.0, help="accuracy percentage for match") + parser.add_argument("--ignore-field", action='append', default=[], help="ignore message field when comparing") parser.add_argument("logs", metavar="LOG", nargs="+") args = parser.parse_args() failed = False for filename in args.logs: - if not check_log(filename, print, args.ekf2_only, args.ekf3_only, args.verbose, accuracy=args.accuracy): + if not check_log(filename, print, args.ekf2_only, args.ekf3_only, args.verbose, accuracy=args.accuracy, ignores=args.ignore_field): failed = True if failed: diff --git a/Tools/ardupilotwaf/ardupilotwaf.py b/Tools/ardupilotwaf/ardupilotwaf.py index d0513a28e5f..8495b8bff79 100644 --- a/Tools/ardupilotwaf/ardupilotwaf.py +++ b/Tools/ardupilotwaf/ardupilotwaf.py @@ -1,4 +1,3 @@ -#!/usr/bin/env python # encoding: utf-8 from __future__ import print_function @@ -89,10 +88,10 @@ 'AC_Avoidance', 'AP_LandingGear', 'AP_RobotisServo', - 'AP_ToshibaCAN', 'AP_NMEA_Output', 'AP_Filesystem', 'AP_ADSB', + 'AP_ADSB/sagetech-sdk', 'AC_PID', 'AP_SerialLED', 'AP_EFI', @@ -109,6 +108,10 @@ 'AP_VideoTX', 'AP_FETtecOneWire', 'AP_Torqeedo', + 'AP_CustomRotations', + 'AP_AIS', + 'AP_OpenDroneID', + 'AP_CheckFirmware', ] def get_legacy_defines(sketch_name, bld): @@ -379,7 +382,7 @@ def ap_version_append_str(ctx, k, v): @conf def ap_version_append_int(ctx, k, v): - ctx.env['AP_VERSION_ITEMS'] += [(k,v)] + ctx.env['AP_VERSION_ITEMS'] += [(k, '{}'.format(os.environ.get(k, v)))] @conf def write_version_header(ctx, tgt): @@ -562,6 +565,10 @@ def options(opt): action='store_true', help='Output all test programs.') + g.add_option('--define', + action='append', + help='Add C++ define to build.') + g = opt.ap_groups['clean'] g.add_option('--clean-all-sigs', @@ -581,6 +588,14 @@ def options(opt): This option is only supported on macOS versions of clang. ''') + g.add_option('--ubsan', + action='store_true', + help='''Build using the gcc undefined behaviour sanitizer''') + + g.add_option('--ubsan-abort', + action='store_true', + help='''Build using the gcc undefined behaviour sanitizer and abort on error''') + def build(bld): bld.add_pre_fun(_process_build_command) bld.add_pre_fun(_select_programs_from_group) diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index a64818ee7cf..fff7575df42 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -1,4 +1,3 @@ -#!/usr/bin/env python # encoding: utf-8 from collections import OrderedDict @@ -95,6 +94,51 @@ def srcpath(path): ENABLE_ONVIF=0, ) + # allow enable of OpenDroneID for any board + if cfg.options.enable_opendroneid: + env.ENABLE_OPENDRONEID = True + env.DEFINES.update( + AP_OPENDRONEID_ENABLED=1, + ) + cfg.msg("Enabled OpenDroneID", 'yes') + else: + cfg.msg("Enabled OpenDroneID", 'no', color='YELLOW') + + # allow enable of firmware ID checking for any board + if cfg.options.enable_check_firmware: + env.CHECK_FIRMWARE_ENABLED = True + env.DEFINES.update( + AP_CHECK_FIRMWARE_ENABLED=1, + ) + cfg.msg("Enabled firmware ID checking", 'yes') + else: + cfg.msg("Enabled firmware ID checking", 'no', color='YELLOW') + + if cfg.options.enable_gps_logging: + env.DEFINES.update( + AP_GPS_DEBUG_LOGGING_ENABLED=1, + ) + cfg.msg("GPS Debug Logging", 'yes') + else: + cfg.msg("GPS Debug Logging", 'no', color='YELLOW') + + # allow enable of custom controller for any board + # enabled on sitl by default + if (cfg.options.enable_custom_controller or self.get_name() == "sitl") and not cfg.options.no_gcs: + env.ENABLE_CUSTOM_CONTROLLER = True + env.DEFINES.update( + AP_CUSTOMCONTROL_ENABLED=1, + ) + env.AP_LIBRARIES += [ + 'AC_CustomControl' + ] + cfg.msg("Enabled custom controller", 'yes') + else: + env.DEFINES.update( + AP_CUSTOMCONTROL_ENABLED=0, + ) + cfg.msg("Enabled custom controller", 'no', color='YELLOW') + d = env.get_merged_dict() # Always prepend so that arguments passed in the command line get # the priority. @@ -137,6 +181,13 @@ def configure_env(self, cfg, env): # make easy to override them. Convert back to list before consumption. env.DEFINES = {} + # potentially set extra defines from an environment variable: + if cfg.options.define is not None: + for (n, v) in [d.split("=") for d in cfg.options.define]: + cfg.msg("Defining: %s" % (n, ), v) + env.CFLAGS += ['-D%s=%s' % (n, v)] + env.CXXFLAGS += ['-D%s=%s' % (n, v)] + env.CFLAGS += [ '-ffunction-sections', '-fdata-sections', @@ -198,6 +249,9 @@ def configure_env(self, cfg, env): env.CXXFLAGS += [ '-Werror=implicit-fallthrough', ] + env.CXXFLAGS += [ + '-fcheck-new', + ] if cfg.env.DEBUG: env.CFLAGS += [ @@ -207,6 +261,10 @@ def configure_env(self, cfg, env): env.DEFINES.update( HAL_DEBUG_BUILD = 1, ) + elif cfg.options.g: + env.CFLAGS += [ + '-g', + ] if cfg.env.COVERAGE: env.CFLAGS += [ '-fprofile-arcs', @@ -227,6 +285,10 @@ def configure_env(self, cfg, env): if cfg.options.bootloader: # don't let bootloaders try and pull scripting in cfg.options.disable_scripting = True + if cfg.options.signed_fw: + env.DEFINES.update( + ENABLE_HEAP = 1, + ) else: env.DEFINES.update( ENABLE_HEAP = 1, @@ -235,6 +297,9 @@ def configure_env(self, cfg, env): if cfg.options.enable_math_check_indexes: env.CXXFLAGS += ['-DMATH_CHECK_INDEXES'] + if cfg.options.private_key: + env.PRIVATE_KEY = cfg.options.private_key + env.CXXFLAGS += [ '-std=gnu++11', @@ -545,17 +610,38 @@ def configure_env(self, cfg, env): HAL_PROBE_EXTERNAL_I2C_BAROS = 1, ) + cfg.define('AP_SIM_ENABLED', 1) cfg.define('HAL_WITH_SPI', 1) cfg.define('HAL_WITH_RAMTRON', 1) + cfg.define('AP_GENERATOR_RICHENPOWER_ENABLED', 1) + cfg.define('AP_OPENDRONEID_ENABLED', 1) + cfg.define('AP_SIGNED_FIRMWARE', 0) if self.with_can: cfg.define('HAL_NUM_CAN_IFACES', 2) cfg.define('UAVCAN_EXCEPTIONS', 0) + cfg.define('UAVCAN_SUPPORT_CANFD', 1) env.CXXFLAGS += [ '-Werror=float-equal' ] + if cfg.options.ubsan or cfg.options.ubsan_abort: + env.CXXFLAGS += [ + "-fsanitize=undefined", + "-fsanitize=float-cast-overflow", + "-DUBSAN_ENABLED", + ] + env.LINKFLAGS += [ + "-fsanitize=undefined", + "-lubsan", + ] + + if cfg.options.ubsan_abort: + env.CXXFLAGS += [ + "-fno-sanitize-recover" + ] + if not cfg.env.DEBUG: env.CXXFLAGS += [ '-O3', @@ -666,6 +752,7 @@ def configure_env(self, cfg, env): HAL_BUILD_AP_PERIPH = 1, PERIPH_FW = 1, CAN_APP_NODE_NAME = '"org.ardupilot.ap_periph_gps"', + AP_AIRSPEED_ENABLED = 0, HAL_PERIPH_ENABLE_GPS = 1, HAL_WITH_DSP = 1, HAL_CAN_DEFAULT_NODE_ID = 0, @@ -674,9 +761,11 @@ def configure_env(self, cfg, env): HAL_GCS_ENABLED = 0, HAL_LOGGING_ENABLED = 0, HAL_LOGGING_MAVLINK_ENABLED = 0, - HAL_MISSION_ENABLED = 0, + AP_MISSION_ENABLED = 0, HAL_RALLY_ENABLED = 0, HAL_SCHEDULER_ENABLED = 0, + CANARD_ENABLE_CANFD = 1, + CANARD_MULTI_IFACE = 1, ) # libcanard is written for 32bit platforms env.CXXFLAGS += [ @@ -706,7 +795,8 @@ def expand_path(p): super(esp32, self).configure_env(cfg, env) cfg.load('esp32') env.DEFINES.update( - CONFIG_HAL_BOARD = 'HAL_BOARD_ESP32' + CONFIG_HAL_BOARD = 'HAL_BOARD_ESP32', + AP_SIM_ENABLED = 0, ) tt = self.name[5:] #leave off 'esp32' so we just get 'buzz','diy','icarus, etc @@ -918,6 +1008,18 @@ def configure_env(self, cfg, env): else: cfg.msg("Enabling ChibiOS thread statistics", "no") + if cfg.env.SIM_ENABLED: + env.DEFINES.update( + AP_SIM_ENABLED = 1, + ) + env.AP_LIBRARIES += [ + 'SITL', + ] + else: + env.DEFINES.update( + AP_SIM_ENABLED = 0, + ) + env.LIB += ['gcc', 'm'] env.GIT_SUBMODULES += [ @@ -937,6 +1039,16 @@ def configure_env(self, cfg, env): ('10','2','1'), ] + if cfg.env.AP_PERIPH: + if cfg.env.HAL_CANFD_SUPPORTED: + env.DEFINES.update(CANARD_ENABLE_CANFD=1) + else: + env.DEFINES.update(CANARD_ENABLE_TAO_OPTION=1) + if not cfg.options.bootloader: + if int(cfg.env.HAL_NUM_CAN_IFACES) > 1: + env.DEFINES.update(CANARD_MULTI_IFACE=1) + else: + env.DEFINES.update(CANARD_MULTI_IFACE=0) if cfg.options.Werror or cfg.env.CC_VERSION in gcc_whitelist: cfg.msg("Enabling -Werror", "yes") if '-Werror' not in env.CXXFLAGS: @@ -944,6 +1056,17 @@ def configure_env(self, cfg, env): else: cfg.msg("Enabling -Werror", "no") + if cfg.options.signed_fw: + cfg.define('AP_SIGNED_FIRMWARE', 1) + env.CFLAGS += [ + '-DAP_SIGNED_FIRMWARE=1', + ] + else: + cfg.define('AP_SIGNED_FIRMWARE', 0) + env.CFLAGS += [ + '-DAP_SIGNED_FIRMWARE=0', + ] + try: import intelhex env.HAVE_INTEL_HEX = True @@ -976,6 +1099,7 @@ def configure_env(self, cfg, env): env.DEFINES.update( CONFIG_HAL_BOARD = 'HAL_BOARD_LINUX', CONFIG_HAL_BOARD_SUBTYPE = 'HAL_BOARD_SUBTYPE_LINUX_NONE', + AP_SIM_ENABLED = 0, ) if not cfg.env.DEBUG: diff --git a/Tools/ardupilotwaf/build_summary.py b/Tools/ardupilotwaf/build_summary.py index b7469c7fdce..d7002543965 100644 --- a/Tools/ardupilotwaf/build_summary.py +++ b/Tools/ardupilotwaf/build_summary.py @@ -1,4 +1,3 @@ -#!/usr/bin/env python # encoding: utf-8 # Copyright (C) 2016 Intel Corporation. All rights reserved. diff --git a/Tools/ardupilotwaf/chibios.py b/Tools/ardupilotwaf/chibios.py index 7143ac1ae36..24533c8c2fd 100644 --- a/Tools/ardupilotwaf/chibios.py +++ b/Tools/ardupilotwaf/chibios.py @@ -1,4 +1,3 @@ -#!/usr/bin/env python # encoding: utf-8 """ @@ -14,6 +13,7 @@ import re import pickle import struct +import base64 _dynamic_env_data = {} def _load_dynamic_env_data(bld): @@ -53,18 +53,74 @@ class upload_fw(Task.Task): color='BLUE' always_run = True def run(self): + import platform upload_tools = self.env.get_flat('UPLOAD_TOOLS') upload_port = self.generator.bld.options.upload_port src = self.inputs[0] # Refer Tools/scripts/macos_remote_upload.sh for details if 'AP_OVERRIDE_UPLOAD_CMD' in os.environ: cmd = "{} '{}'".format(os.environ['AP_OVERRIDE_UPLOAD_CMD'], src.abspath()) + elif "microsoft-standard-WSL2" in platform.release(): + if not self.wsl2_prereq_checks(): + return + print("If this takes takes too long here, try power-cycling your hardware\n") + cmd = "{} '{}/uploader.py' '{}'".format('python.exe', upload_tools, src.abspath()) else: cmd = "{} '{}/uploader.py' '{}'".format(self.env.get_flat('PYTHON'), upload_tools, src.abspath()) if upload_port is not None: cmd += " '--port' '%s'" % upload_port return self.exec_command(cmd) + def wsl2_prereq_checks(self): + # As of July 2022 WSL2 does not support native USB support. The workaround from Microsoft + # using 'usbipd' does not work due to the following workflow: + # + # 1) connect USB device to Windows computer running WSL2 + # 2) device boots into app + # 3) use 'usbipd' from Windows Cmd/PowerShell to determine busid, this is very hard to automate on Windows + # 4) use 'usbipd' from Windows Cmd/PowerShell to attach, this is very hard to automate on Windows + # -- device is now viewable via 'lsusb' but you need sudo to read from it. + # either run 'chmod666 /dev/ttyACM*' or use udev to automate chmod on device connect + # 5) uploader.py detects device, sends reboot command which disconnects the USB port and reboots into + # bootloader (different USB device) + # 6) manually repeat steps 3 & 4 + # 7) doing steps 3 and 4 will most likely take several seconds and in many cases the bootloader has + # moved on into the app + # + # Solution: simply call "python.exe" instead of 'python' which magically calls it from the windows + # system using the same absolute path back into the WSL2's user's directory + # Requirements: Windows must have Python3.9.x (NTO 3.10.x) installed and a few packages. + import subprocess + try: + where_python = subprocess.check_output('where.exe python.exe', shell=True, text=True) + except subprocess.CalledProcessError: + #if where.exe can't find the file it returns a non-zero result which throws this exception + where_python = "" + if not where_python or not "\Python\Python" in where_python or "python.exe" not in where_python: + print(self.get_full_wsl2_error_msg("Windows python.exe not found")) + return False + python_version = subprocess.check_output('python.exe --version', shell=True, text=True) + if "3.10." in python_version: + print(self.get_full_wsl2_error_msg("Your Windows %s version is not compatible" % python_version.strip())) + return False + return True + + def get_full_wsl2_error_msg(self, error_msg): + return (""" + **************************************** + **************************************** + WSL2 firmware uploads use the host's Windows Python.exe so it has access to the COM ports. + + %s + Please download Windows Installer 3.9.x (not 3.10) from https://www.python.org/downloads/ + and make sure to add it to your path during the installation. Once installed, run this + command in Powershell or Command Prompt to install some packages: + + pip.exe install empy pyserial + **************************************** + **************************************** + """ % error_msg) + def exec_command(self, cmd, **kw): kw['stdout'] = sys.stdout return super(upload_fw, self).exec_command(cmd, **kw) @@ -174,6 +230,29 @@ def to_unsigned(i): i += 2**32 return i +def sign_firmware(image, private_keyfile): + '''sign firmware with private key''' + try: + import monocypher + except ImportError: + Logs.error("Please install monocypher with: python3 -m pip install pymonocypher==3.1.3.2") + return None + try: + key = open(private_keyfile, 'r').read() + except Exception as ex: + Logs.error("Failed to open %s" % private_keyfile) + return None + keytype = "PRIVATE_KEYV1:" + if not key.startswith(keytype): + Logs.error("Bad private key file %s" % private_keyfile) + return None + key = base64.b64decode(key[len(keytype):]) + sig = monocypher.signature_sign(key, image) + sig_len = len(sig) + sig_version = 30437 + return struct.pack(" timeout: - return - m = self.mav.recv_match(type='VFR_HUD', blocking=True) - if m.alt <= min_alt: - raise NotAchievedException("Altitude not maintained: want >%f got=%f" % (min_alt, m.alt)) - - def test_mode_ALT_HOLD(self): + def ModeAltHold(self): + '''Test AltHold Mode''' self.takeoff(10, mode="ALT_HOLD") - self.watch_altitude_maintained(9, 11, timeout=5) + self.watch_altitude_maintained(altitude_min=9, altitude_max=11) # feed in full elevator and aileron input and make sure we # retain altitude: self.set_rc_from_map({ 1: 1000, 2: 1000, }) - self.watch_altitude_maintained(9, 11, timeout=5) + self.watch_altitude_maintained(altitude_min=9, altitude_max=11) self.set_rc_from_map({ 1: 1500, 2: 1500, @@ -328,9 +318,8 @@ def setGCSfailsafe(self, paramValue=0): "FS_GCS_ENABLE": paramValue, }) - # fly a square in alt_hold mode - def fly_square(self, side=50, timeout=300): - + def RecordThenPlayMission(self, side=50, timeout=300): + '''Use switches to toggle in mission, then fly it''' self.takeoff(20, mode="ALT_HOLD") """Fly a square, flying N then E .""" @@ -422,8 +411,7 @@ def fly_square(self, side=50, timeout=300): os.path.join(testdir, "ch7_mission.txt")) self.stop_mavproxy(mavproxy) if not num_wp: - self.fail_list.append("save_mission_to_file") - self.progress("save_mission_to_file failed") + raise NotAchievedException("save_mission_to_file failed") self.progress("test: Fly a mission from 1 to %u" % num_wp) self.change_mode('AUTO') @@ -468,8 +456,8 @@ def wait_rtl_complete(self, check_alt=True, distance_max=10, timeout=250): raise AutoTestTimeoutException("Did not get home and disarm") - def fly_loiter_to_alt(self): - """loiter to alt""" + def LoiterToAlt(self): + """Loiter-To-Alt""" self.context_push() @@ -489,6 +477,7 @@ def fly_loiter_to_alt(self): self.change_mode('LOITER') + self.install_terrain_handlers_context() self.wait_ready_to_arm() self.arm_vehicle() @@ -515,7 +504,8 @@ def fly_loiter_to_alt(self): raise ex # Tests all actions and logic behind the radio failsafe - def fly_throttle_failsafe(self, side=60, timeout=360): + def ThrottleFailsafe(self, side=60, timeout=360): + '''Test Throttle Failsafe''' self.start_subtest("If you haven't taken off yet RC failure should be instant disarm") self.change_mode("STABILIZE") self.set_parameter("DISARM_DELAY", 0) @@ -728,7 +718,8 @@ def fly_throttle_failsafe(self, side=60, timeout=360): self.reboot_sitl() # Tests all actions and logic behind the GCS failsafe - def fly_gcs_failsafe(self, side=60, timeout=360): + def GCSFailsafe(self, side=60, timeout=360): + '''Test GCS Failsafe''' try: self.test_gcs_failsafe(side=side, timeout=timeout) except Exception as ex: @@ -901,10 +892,51 @@ def ensure_smartrtl(mav, m): self.setGCSfailsafe(0) self.set_parameter('FS_OPTIONS', 0) self.progress("All GCS failsafe tests complete") + + def CustomController(self, timeout=300): + '''Test Custom Controller''' + self.progress("Configure custom controller parameters") + self.set_parameters({ + 'CC_TYPE': 2, + 'CC_AXIS_MASK': 7, + 'RC6_OPTION': 109, + }) + self.set_rc(6, 1000) self.reboot_sitl() + if self.get_parameter("CC_TYPE") != 2 : + raise NotAchievedException("Custom controller is not switched to PID backend.") + + # check if we can retrive any param inside PID backend + self.get_parameter("CC2_RAT_YAW_P") + + # takeoff in GPS mode and switch to CIRCLE + self.takeoff(10, mode="LOITER", takeoff_throttle=2000) + self.change_mode("CIRCLE") + + self.context_push() + self.context_collect('STATUSTEXT') + + # switch custom controller on + self.set_rc(6, 2000) + self.wait_statustext("Custom controller is ON", check_context=True) + + # wait 20 second to see if the custom controller destabilize the aircraft + if self.wait_altitude(7, 13, relative=True, minimum_duration=20) : + raise NotAchievedException("Custom controller is not stable.") + + # switch custom controller off + self.set_rc(6, 1000) + self.wait_statustext("Custom controller is OFF", check_context=True) + + self.context_pop() + self.do_RTL() + self.progress("Custom controller test complete") + # Tests all actions and logic behind the battery failsafe - def fly_battery_failsafe(self, timeout=300): + def BatteryFailsafe(self, timeout=300): + '''Fly Battery Failsafe''' + self.context_push() ex = None try: self.test_battery_failsafe(timeout=timeout) @@ -912,14 +944,7 @@ def fly_battery_failsafe(self, timeout=300): self.print_exception_caught(e) self.disarm_vehicle(force=True) ex = e - - self.set_parameters({ - 'BATT_LOW_VOLT': 0, - 'BATT_CRT_VOLT': 0, - 'BATT_FS_LOW_ACT': 0, - 'BATT_FS_CRT_ACT': 0, - 'FS_OPTIONS': 0, - }) + self.context_pop() self.reboot_sitl() if ex is not None: @@ -1065,8 +1090,8 @@ def test_battery_failsafe(self, timeout=300): self.progress("All Battery failsafe tests complete") - # Tests the vibration failsafe - def test_vibration_failsafe(self): + def VibrationFailsafe(self): + '''Test Vibration Failsafe''' self.context_push() # takeoff in Loiter to 20m @@ -1084,7 +1109,7 @@ def test_vibration_failsafe(self): self.change_mode("LAND") # check vehicle descends to 2m or less within 40 seconds - self.wait_altitude(-5, 2, timeout=40, relative=True) + self.wait_altitude(-5, 2, timeout=50, relative=True) # force disarm of vehicle (it will likely not automatically disarm) self.disarm_vehicle(force=True) @@ -1093,13 +1118,171 @@ def test_vibration_failsafe(self): self.context_pop() self.reboot_sitl() - # fly_stability_patch - fly south, then hold loiter within 5m - # position and altitude and reduce 1 motor to 60% efficiency - def fly_stability_patch(self, - holdtime=30, - maxaltchange=5, - maxdistchange=10): + def test_takeoff_check_mode(self, mode, user_takeoff=False): + # stabilize check + self.progress("Motor takeoff check in %s" % mode) + self.change_mode(mode) + self.zero_throttle() + self.wait_ready_to_arm() + self.context_collect('STATUSTEXT') + self.send_mavlink_arm_command() + self.mav.recv_match(blocking=True, timeout=1) + if user_takeoff: + self.run_cmd(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 0, 0, 0, 0, 10) + else: + self.set_rc(3, 1700) + # we may never see ourselves as armed in a heartbeat + self.wait_statustext("Takeoff blocked: ESC RPM too low", check_context=True) + self.zero_throttle() + self.disarm_vehicle() + self.wait_disarmed() + + # Tests the motor failsafe + def TakeoffCheck(self): + '''Test takeoff check''' + self.set_parameters({ + "AHRS_EKF_TYPE": 10, + 'SIM_ESC_TELEM': 1, + 'SIM_ESC_ARM_RPM': 500, + 'TKOFF_RPM_MIN': 1000, + }) + + self.test_takeoff_check_mode("STABILIZE") + self.test_takeoff_check_mode("ACRO") + self.test_takeoff_check_mode("LOITER") + self.test_takeoff_check_mode("ALT_HOLD") + # self.test_takeoff_check_mode("FLOWHOLD") + self.test_takeoff_check_mode("GUIDED", True) + self.test_takeoff_check_mode("POSHOLD") + # self.test_takeoff_check_mode("SPORT") + + def assert_dataflash_message_field_level_at(self, + mtype, + field, + level, + maintain=1, + tolerance=0.05, + timeout=30, + condition=None, + dfreader_start_timestamp=None, + verbose=False): + '''wait for EKF's accel bias to reach a level and maintain it''' + + if verbose: + self.progress("current onboard log filepath: %s" % self.current_onboard_log_filepath()) + dfreader = self.dfreader_for_current_onboard_log() + + achieve_start = None + current_value = None + while True: + m = dfreader.recv_match(type=mtype, condition=condition) + if m is None: + raise NotAchievedException("%s.%s did not maintain %f" % + (mtype, field, level)) + if dfreader_start_timestamp is not None: + if m.TimeUS < dfreader_start_timestamp: + continue + if verbose: + print("m=%s" % str(m)) + current_value = getattr(m, field) + + if abs(current_value - level) > tolerance: + if achieve_start is not None: + self.progress("Achieve stop at %u" % m.TimeUS) + achieve_start = None + continue + + dfreader_now = m.TimeUS + if achieve_start is None: + self.progress("Achieve start at %u (got=%f want=%f)" % + (dfreader_now, current_value, level)) + if maintain is None: + return + achieve_start = m.TimeUS + continue + + # we're achieving.... + if dfreader_now - achieve_start > maintain*1e6: + return dfreader_now + + # Tests any EK3 accel bias is subtracted from the correct IMU data + def EK3AccelBias(self): + '''Test EK3 Accel Bias data''' + self.context_push() + + self.start_test("Test zero bias") + dfreader_tstart = self.assert_dataflash_message_field_level_at( + "XKF2", + "AZ", + 0.0, + condition="XKF2.C==1", + ) + + # Add 2m/s/s bias to the second IMU + self.set_parameters({ + 'SIM_ACC2_BIAS_Z': 0.7, + }) + + self.start_subtest("Ensuring second core has bias") + self.delay_sim_time(30) + dfreader_tstart = self.assert_dataflash_message_field_level_at( + "XKF2", "AZ", 0.7, + condition="XKF2.C==1", + ) + + self.start_subtest("Ensuring earth frame is compensated") + self.assert_dataflash_message_field_level_at( + "RATE", "A", 0, + maintain=1, + tolerance=2, # RATE.A is in cm/s/s + dfreader_start_timestamp=dfreader_tstart, + ) + + # now switch the EKF to only using the second core: + self.set_parameters({ + 'SIM_ACC2_BIAS_Z': 0.0, + "EK3_IMU_MASK": 0b10, + }) + self.reboot_sitl() + + self.delay_sim_time(30) + dfreader_tstart = self.assert_dataflash_message_field_level_at( + "XKF2", "AZ", 0.0, + condition="XKF2.C==0", + ) + + # Add 2m/s/s bias to the second IMU + self.set_parameters({ + 'SIM_ACC2_BIAS_Z': 0.7, + }) + + self.start_subtest("Ensuring first core now has bias") + self.delay_sim_time(30) + dfreader_tstart = self.assert_dataflash_message_field_level_at( + "XKF2", "AZ", 0.7, + condition="XKF2.C==0", + ) + + self.start_subtest("Ensuring earth frame is compensated") + self.assert_dataflash_message_field_level_at( + "RATE", "A", 0, + maintain=1, + tolerance=2, # RATE.A is in cm/s/s + dfreader_start_timestamp=dfreader_tstart, + verbose=True, + ) + # revert simulated accel bias and reboot to restore EKF health + self.context_pop() + self.reboot_sitl() + + # StabilityPatch - fly south, then hold loiter within 5m + # position and altitude and reduce 1 motor to 60% efficiency + def StabilityPatch(self, + holdtime=30, + maxaltchange=5, + maxdistchange=10): + '''Fly stability patch''' self.takeoff(10, mode="LOITER") # first south @@ -1225,12 +1408,14 @@ def fly_fence_avoid_test_radius_check(self, timeout=180, avoid_behave=avoid_beha self.set_rc(2, 1500) self.do_RTL() - def fly_fence_avoid_test(self, timeout=180): + def HorizontalAvoidFence(self, timeout=180): + '''Test horizontal Avoidance fence''' self.fly_fence_avoid_test_radius_check(avoid_behave=1, timeout=timeout) self.fly_fence_avoid_test_radius_check(avoid_behave=0, timeout=timeout) # fly_fence_test - fly east until you hit the horizontal circular fence - def fly_fence_test(self, timeout=180): + def HorizontalFence(self, timeout=180): + '''Test horizontal fence''' # enable fence, disable avoidance self.set_parameters({ "FENCE_ENABLE": 1, @@ -1328,8 +1513,9 @@ def fly_fence_test(self, timeout=180): "Fence test failed to reach home (%fm distance) - " "timed out after %u seconds" % (home_distance, timeout,)) - # fly_alt_max_fence_test - fly up until you hit the fence ceiling - def fly_alt_max_fence_test(self): + # MaxAltFence - fly up until you hit the fence ceiling + def MaxAltFence(self): + '''Test Max Alt Fence''' self.takeoff(10, mode="LOITER") """Hold loiter position.""" @@ -1366,7 +1552,8 @@ def fly_alt_max_fence_test(self): self.zero_throttle() # fly_alt_min_fence_test - fly down until you hit the fence floor - def fly_alt_min_fence_test(self): + def MinAltFence(self): + '''Test Min Alt Fence''' self.takeoff(30, mode="LOITER", timeout=60) # enable fence, disable avoidance @@ -1408,9 +1595,10 @@ def fly_alt_min_fence_test(self): self.zero_throttle() - def fly_fence_floor_enabled_landing(self): - """ fly_fence_floor_enabled_landing. Ensures we can initiate and complete - an RTL while the fence is enabled. """ + def FenceFloorEnabledLanding(self): + """Ensures we can initiate and complete an RTL while the fence is + enabled. + """ fence_bit = mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE self.progress("Test Landing while fence floor enabled") @@ -1446,7 +1634,7 @@ def fly_fence_floor_enabled_landing(self): self.do_fence_disable() self.assert_fence_disabled() - def fly_gps_glitch_loiter_test(self, timeout=30, max_distance=20): + def GPSGlitchLoiter(self, timeout=30, max_distance=20): """fly_gps_glitch_loiter_test. Fly south east in loiter and test reaction to gps glitch.""" self.takeoff(10, mode="LOITER") @@ -1558,7 +1746,7 @@ def fly_gps_glitch_loiter_test(self, timeout=30, max_distance=20): # re-arming is problematic because the GPS is glitching! self.reboot_sitl() - def fly_gps_glitch_loiter_test2(self): + def GPSGlitchLoiter2(self): """test vehicle handles GPS glitch (aka EKF Reset) without twitching""" self.context_push() self.takeoff(10, mode="LOITER") @@ -1584,8 +1772,8 @@ def fly_gps_glitch_loiter_test2(self): self.context_pop() self.reboot_sitl() - # fly_gps_glitch_auto_test - fly mission and test reaction to gps glitch - def fly_gps_glitch_auto_test(self, timeout=180): + def GPSGlitchAuto(self, timeout=180): + '''fly mission and test reaction to gps glitch''' # set-up gps glitch array glitch_lat = [0.0002996, 0.0006958, @@ -1688,7 +1876,8 @@ def fly_gps_glitch_auto_test(self, timeout=180): # fly_simple - assumes the simple bearing is initialised to be # directly north flies a box with 100m west, 15 seconds north, # 50 seconds east, 15 seconds south - def fly_simple(self, side=50): + def SimpleMode(self, side=50): + '''Fly in SIMPLE mode''' self.takeoff(10, mode="LOITER") # set SIMPLE mode for all flight modes @@ -1732,7 +1921,8 @@ def fly_simple(self, side=50): self.do_RTL(timeout=500) # fly_super_simple - flies a circle around home for 45 seconds - def fly_super_simple(self, timeout=45): + def SuperSimpleCircle(self, timeout=45): + '''Fly a circle in SUPER SIMPLE mode''' self.takeoff(10, mode="LOITER") # fly forward 20m @@ -1772,7 +1962,8 @@ def fly_super_simple(self, timeout=45): self.do_RTL() # fly_circle - flies a circle with 20m radius - def fly_circle(self, holdtime=36): + def ModeCircle(self, holdtime=36): + '''Fly CIRCLE mode''' # the following should not be required. But there appears to # be a physics failure in the simulation which is causing CI # to fall over a lot. -pb 202007021209 @@ -1812,8 +2003,8 @@ def fly_circle(self, holdtime=36): self.do_RTL() - # test_mag_fail - test failover of compass in EKF - def test_mag_fail(self): + def MagFail(self): + '''test failover of compass in EKF''' # we want both EK2 and EK3 self.set_parameters({ "EK2_ENABLE": 1, @@ -1863,7 +2054,8 @@ def test_mag_fail(self): self.do_RTL() - def fly_flip(self): + def ModeFlip(self): + '''Fly Flip Mode''' ex = None try: self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_ATTITUDE, 100) @@ -1917,7 +2109,7 @@ def configure_EKFs_to_use_optical_flow_instead_of_GPS(self): "EK3_SRC1_VELZ": 0, }) - def optical_flow(self): + def OpticalFlow(self): '''test optical low works''' self.start_subtest("Make sure no crash if no rangefinder") self.set_parameter("SIM_FLOW_ENABLE", 1) @@ -1930,8 +2122,8 @@ def optical_flow(self): self.delay_sim_time(5) self.wait_statustext("Need Position Estimate", timeout=300) - # fly_optical_flow_limits - test EKF navigation limiting - def fly_optical_flow_limits(self): + def OpticalFlowLimits(self): + '''test EKF navigation limiting''' ex = None self.context_push() try: @@ -1996,8 +2188,8 @@ def fly_optical_flow_limits(self): if ex is not None: raise ex - # fly_optical_flow_calibration - test optical flow calibration - def fly_optical_flow_calibration(self): + def OpticalFlowCalibration(self): + '''test optical flow calibration''' ex = None self.context_push() try: @@ -2079,7 +2271,7 @@ def fly_optical_flow_calibration(self): if ex is not None: raise ex - def fly_autotune(self): + def AutoTune(self): """Test autotune mode""" rlld = self.get_parameter("ATC_RAT_RLL_D") @@ -2117,7 +2309,7 @@ def fly_autotune(self): raise NotAchievedException("AUTOTUNE failed (%u seconds)" % (self.get_sim_time() - tstart)) - def fly_autotune_switch(self): + def AutoTuneSwitch(self): """Test autotune on a switch with gains being saved""" # autotune changes a set of parameters on the vehicle which @@ -2218,8 +2410,8 @@ def fly_autotune_switch_body(self): raise NotAchievedException("AUTOTUNE failed (%u seconds)" % (self.get_sim_time() - tstart)) - # fly_auto_test - fly mission which tests a significant number of commands - def fly_auto_test(self): + def CopterMission(self): + '''fly mission which tests a significant number of commands''' # Fly mission #1 self.progress("# Load copter_mission") # load the waypoint count @@ -2254,8 +2446,8 @@ def fly_loaded_mission(self, num_wp): self.wait_disarmed() self.progress("MOTORS DISARMED OK") - # fly_auto_test using CAN GPS - fly mission which tests normal operation alongside CAN GPS - def fly_auto_test_using_can_gps(self): + def CANGPSCopterMission(self): + '''fly mission which tests normal operation alongside CAN GPS''' self.set_parameters({ "CAN_P1_DRIVER": 1, "GPS_TYPE": 9, @@ -2341,11 +2533,31 @@ def fly_auto_test_using_can_gps(self): self.wait_statustext(case[4], check_context=True) self.context_stop_collecting('STATUSTEXT') self.progress("############################### All GPS Order Cases Tests Passed") + self.progress("############################### Test Healthy Prearm check") + self.set_parameter("ARMING_CHECK", 1) + self.stop_sup_program(instance=0) + self.start_sup_program(instance=0, args="-M") + self.delay_sim_time(2) + self.context_collect('STATUSTEXT') + self.run_cmd(mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM, + 1, # ARM + 0, + 0, + 0, + 0, + 0, + 0, + timeout=10, + want_result=mavutil.mavlink.MAV_RESULT_FAILED) + self.wait_statustext("Node {} unhealthy".format(gps1_nodeid), check_context=True) + self.stop_sup_program(instance=0) + self.start_sup_program(instance=0) + self.context_stop_collecting('STATUSTEXT') self.context_pop() - self.fly_auto_test() + self.CopterMission() - # test takeoff altitude - def test_takeoff_alt(self): + def TakeoffAlt(self): + '''Test Takeoff command altitude''' # Test case #1 (set target altitude to relative -10m from the ground, -10m is invalid, so it is set to 1m) self.progress("Testing relative alt from the ground") self.do_takeoff_alt("copter_takeoff.txt", 1, False) @@ -2390,7 +2602,55 @@ def do_takeoff_alt(self, mission_file, target_alt, during_flight=False): self.wait_disarmed() self.progress("MOTORS DISARMED OK") - def fly_motor_fail(self, fail_servo=0, fail_mul=0.0, holdtime=30): + def GuidedEKFLaneChange(self): + '''test lane change with GPS diff on startup''' + self.set_parameters({ + "EK3_SRC1_POSZ": 3, + "EK3_AFFINITY" : 1, + "GPS_TYPE2" : 1, + "SIM_GPS2_DISABLE" : 0, + "SIM_GPS2_GLTCH_Z" : -30 + }) + self.reboot_sitl() + + self.change_mode("GUIDED") + self.wait_ready_to_arm() + + self.progress("waiting for both EKF lanes to init") + self.delay_sim_time(10) + + self.set_parameters({ + "SIM_GPS2_GLTCH_Z" : 0 + }) + + self.progress("waiting for EKF to do a position Z reset") + self.delay_sim_time(20) + + self.arm_vehicle() + self.user_takeoff(alt_min=20) + m = self.mav.recv_match(type='GPS_RAW_INT', blocking=True) + gps_alt = m.alt*0.001 + self.progress("Initial guided alt=%.1fm" % gps_alt) + + self.context_collect('STATUSTEXT') + self.progress("force a lane change") + self.set_parameters({ + "INS_ACCOFFS_X" : 5 + }) + self.wait_statustext("EKF3 lane switch 1", timeout=10, check_context=True) + + self.delay_sim_time(10) + m = self.mav.recv_match(type='GPS_RAW_INT', blocking=True) + gps_alt2 = m.alt*0.001 + alt_change = gps_alt - gps_alt2 + self.progress("GPS Alt change by %.1fm" % abs(alt_change)) + + if abs(alt_change) > 2: + raise NotAchievedException("Altitude changed on lane switch %.1fm" % alt_change) + self.disarm_vehicle(force=True) + self.reboot_sitl() + + def MotorFail(self, fail_servo=0, fail_mul=0.0, holdtime=30): """Test flight with reduced motor efficiency""" # we only expect an octocopter to survive ATM: @@ -2509,7 +2769,19 @@ def fly_motor_fail(self, fail_servo=0, fail_mul=0.0, holdtime=30): self.do_RTL() - def fly_motor_vibration(self): + def hover_for_interval(self, hover_time): + '''hovers for an interval of hover_time seconds. Returns the bookend + times for that interval (in time-since-boot frame), and the + output throttle level at the end of the period. + ''' + self.progress("Hovering for %u seconds" % hover_time) + tstart = self.get_sim_time() + self.delay_sim_time(hover_time, reason='data collection') + vfr_hud = self.poll_message('VFR_HUD') + tend = self.get_sim_time() + return tstart, tend, vfr_hud.throttle + + def MotorVibration(self): """Test flight with motor vibration""" self.context_push() @@ -2532,19 +2804,14 @@ def fly_motor_vibration(self): }) self.reboot_sitl() + # do a simple up-and-down flight to gather data: self.takeoff(15, mode="ALT_HOLD") - - hover_time = 15 - tstart = self.get_sim_time() - self.progress("Hovering for %u seconds" % hover_time) - while self.get_sim_time_cached() < tstart + hover_time: - self.mav.recv_match(type='ATTITUDE', blocking=True) - tend = self.get_sim_time() - + tstart, tend, hover_throttle = self.hover_for_interval(15) # if we don't reduce vibes here then the landing detector # may not trigger self.set_parameter("SIM_VIB_MOT_MAX", 0) self.do_RTL() + psd = self.mavfft_fttd(1, 0, tstart * 1.0e6, tend * 1.0e6) # ignore the first 20Hz and look for a peak at -15dB or more ignore_bins = 20 @@ -2559,23 +2826,21 @@ def fly_motor_vibration(self): # now add a notch and check that post-filter the peak is squashed below 40dB self.set_parameters({ "INS_LOG_BAT_OPT": 2, - "INS_NOTCH_ENABLE": 1, - "INS_NOTCH_FREQ": freq, - "INS_NOTCH_ATT": 50, - "INS_NOTCH_BW": freq/2, + "INS_HNTC2_ENABLE": 1, + "INS_HNTC2_FREQ": freq, + "INS_HNTC2_ATT": 50, + "INS_HNTC2_BW": freq/2, + "INS_HNTC2_MODE": 0, "SIM_VIB_MOT_MAX": 350, }) self.reboot_sitl() + # do a simple up-and-down flight to gather data: self.takeoff(15, mode="ALT_HOLD") - - tstart = self.get_sim_time() - self.progress("Hovering for %u seconds" % hover_time) - while self.get_sim_time_cached() < tstart + hover_time: - self.mav.recv_match(type='ATTITUDE', blocking=True) - tend = self.get_sim_time() + tstart, tend, hover_throttle = self.hover_for_interval(15) self.set_parameter("SIM_VIB_MOT_MAX", 0) self.do_RTL() + psd = self.mavfft_fttd(1, 0, tstart * 1.0e6, tend * 1.0e6) freq = psd["F"][numpy.argmax(psd["X"][ignore_bins:]) + ignore_bins] peakdB = numpy.amax(psd["X"][ignore_bins:]) @@ -2595,7 +2860,7 @@ def fly_motor_vibration(self): if ex is not None: raise ex - def fly_vision_position(self): + def VisionPosition(self): """Disable GPS navigation, enable Vicon input.""" # scribble down a location we can set origin to: @@ -2693,7 +2958,7 @@ def fly_vision_position(self): if ex is not None: raise ex - def fly_body_frame_odom(self): + def BodyFrameOdom(self): """Disable GPS navigation, enable input of VISION_POSITION_DELTA.""" if self.get_parameter("AHRS_EKF_TYPE") != 3: @@ -2752,7 +3017,7 @@ def fly_body_frame_odom(self): if not self.current_onboard_log_contains_message("XKFD"): raise NotAchievedException("Did not find expected XKFD message") - def fly_gps_vicon_switching(self): + def GPSViconSwitching(self): """Fly GPS and Vicon switching test""" self.customise_SITL_commandline(["--uartF=sim:vicon:"]) @@ -2831,7 +3096,7 @@ def fly_gps_vicon_switching(self): if ex is not None: raise ex - def fly_rtl_speed(self): + def RTLSpeed(self): """Test RTL Speed parameters""" rtl_speed_ms = 7 wpnav_speed_ms = 4 @@ -2860,7 +3125,7 @@ def fly_rtl_speed(self): self.monitor_groundspeed(wpnav_speed_ms, tolerance=0.6, timeout=5) self.do_RTL() - def fly_nav_delay(self): + def NavDelay(self): """Fly a simple mission that has a delay in it.""" self.load_mission("copter_nav_delay.txt") @@ -2907,7 +3172,8 @@ def fly_nav_delay(self): if calculated_delay < want_delay: raise NotAchievedException("Did not delay for long enough") - def test_rangefinder(self): + def RangeFinder(self): + '''Test RangeFinder Basic Functionality''' ex = None self.context_push() @@ -2989,12 +3255,13 @@ def test_rangefinder(self): if ex is not None: raise ex - def test_terrain_spline_mission(self): + def SplineTerrain(self): + '''Test Splines and Terrain''' self.set_parameter("TERRAIN_ENABLE", 0) self.fly_mission("wp.txt") def WPNAV_SPEED(self): - '''ensure resetting WPNAV_SPEED works''' + '''ensure resetting WPNAV_SPEED during a mission works''' loc = self.poll_home_position() alt = 20 @@ -3024,7 +3291,7 @@ def WPNAV_SPEED(self): self.do_RTL() def WPNAV_SPEED_UP(self): - '''ensure resetting WPNAV_SPEED_UP works''' + '''Change speed (up) during mission''' items = [] @@ -3049,7 +3316,7 @@ def WPNAV_SPEED_UP(self): self.do_RTL(timeout=240) def WPNAV_SPEED_DN(self): - '''ensure resetting WPNAV_SPEED_DN works''' + '''Change speed (down) during mission''' items = [] @@ -3082,14 +3349,12 @@ def fly_mission(self, filename, strict=True): self.wait_waypoint(num_wp-1, num_wp-1) self.wait_disarmed() - def test_surface_tracking(self): + def SurfaceTracking(self): + '''Test Surface Tracking''' ex = None self.context_push() - # we must start mavproxy here as otherwise we can't get the - # terrain database tiles - this leads to random failures in - # CI! - mavproxy = self.start_mavproxy() + self.install_terrain_handlers_context() try: self.set_analog_rangefinder_parameters() @@ -3139,8 +3404,6 @@ def test_surface_tracking(self): self.disarm_vehicle(force=True) ex = e - self.stop_mavproxy(mavproxy) - self.context_pop() self.reboot_sitl() if ex is not None: @@ -3195,8 +3458,8 @@ def test_rangefinder_switchover(self): if ex is not None: raise ex - def test_parachute(self): - + def Parachute(self): + '''Test Parachute Functionality''' self.set_rc(9, 1000) self.set_parameters({ "CHUTE_ENABLED": 1, @@ -3358,7 +3621,8 @@ def test_parachute(self): self.disarm_vehicle(force=True) self.reboot_sitl() - def test_motortest(self, timeout=60): + def MotorTest(self, timeout=60): + '''Run Motor Tests''' self.start_subtest("Testing PWM output") pwm_in = 1300 # default frame is "+" - start motor of 2 is "B", which is @@ -3399,7 +3663,7 @@ def test_motortest(self, timeout=60): self.wait_statustext("finished motor test") self.end_subtest("Testing percentage output") - def fly_precision_landing_drivers(self): + def PrecisionLanding(self): """Use PrecLand backends precision messages to land aircraft.""" self.context_push() @@ -3460,6 +3724,54 @@ def fly_precision_landing_drivers(self): if ex is not None: raise ex + def Landing(self): + """Test landing the aircraft.""" + + def check_landing_speeds(land_speed_high, land_speed_low, land_alt_low, land_speed_high_accuracy=0.1): + self.progress("Checking landing speeds (speed_high=%f speed_low=%f alt_low=%f" % + (land_speed_high, land_speed_low, land_alt_low)) + land_high_maintain = 5 + land_low_maintain = land_alt_low / land_speed_low / 2 + + takeoff_alt = (land_high_maintain * land_speed_high + land_alt_low) + 20 + # this is pretty rough, but takes *so much longer* in LOITER + self.takeoff(takeoff_alt, mode='STABILIZE', timeout=200, takeoff_throttle=2000) + # check default landing speeds: + self.change_mode('LAND') + # ensure higher-alt descent rate: + self.wait_descent_rate(land_speed_high, + minimum_duration=land_high_maintain, + accuracy=land_speed_high_accuracy) + self.wait_descent_rate(land_speed_low) + # ensure we transition to low descent rate at correct height: + self.assert_altitude(land_alt_low, relative=True) + # now make sure we maintain that descent rate: + self.wait_descent_rate(land_speed_low, minimum_duration=land_low_maintain) + self.wait_disarmed() + + # test the defaults. By default LAND_SPEED_HIGH is 0 so + # WPNAV_SPEED_DN is used + check_landing_speeds( + self.get_parameter("WPNAV_SPEED_DN") / 100, # cm/s -> m/s + self.get_parameter("LAND_SPEED") / 100, # cm/s -> m/s + self.get_parameter("LAND_ALT_LOW") / 100 # cm -> m + ) + + def test_landing_speeds(land_speed_high, land_speed_low, land_alt_low, **kwargs): + self.set_parameters({ + "LAND_SPEED_HIGH": land_speed_high * 100, # m/s -> cm/s + "LAND_SPEED": land_speed_low * 100, # m/s -> cm/s + "LAND_ALT_LOW": land_alt_low * 100, # m -> cm + }) + check_landing_speeds(land_speed_high, land_speed_low, land_alt_low, **kwargs) + + test_landing_speeds( + 5, # descent speed high + 1, # descent speed low + 30, # transition altitude + land_speed_high_accuracy=0.5 + ) + def get_system_clock_utc(self, time_seconds): # this is a copy of ArduPilot's AP_RTC function! # separate time into ms, sec, min, hour and days but all expressed @@ -3581,7 +3893,7 @@ def reset_delay_item(self, seq, seconds_in_future): timeout=1) self.progress("Received ack: %s" % str(ack)) - def fly_nav_delay_abstime(self): + def NavDelayAbsTime(self): """fly a simple mission that has a delay in it""" self.fly_nav_delay_abstime_x(87) @@ -3629,7 +3941,7 @@ def fly_nav_delay_abstime_x(self, delay_for, expected_delay=None): if error > 2: raise NotAchievedException("delay outside expectations") - def fly_nav_takeoff_delay_abstime(self): + def NavDelayTakeoffAbsTime(self): """make sure taking off at a specific time works""" self.load_mission("copter_nav_delay_takeoff.txt") @@ -3670,9 +3982,8 @@ def fly_nav_takeoff_delay_abstime(self): if not took_off: raise NotAchievedException("Did not take off") - def fly_zigzag_mode(self): + def ModeZigZag(self): '''test zigzag mode''' - # set channel 8 for zigzag savewp and recentre it self.set_parameter("RC8_OPTION", 61) @@ -3756,7 +4067,8 @@ def fly_zigzag_mode(self): self.do_RTL() - def test_setting_modes_via_modeswitch(self): + def SetModesViaModeSwitch(self): + '''Set modes via modeswitch''' self.context_push() ex = None try: @@ -3798,7 +4110,8 @@ def test_setting_modes_via_modeswitch(self): if ex is not None: raise ex - def test_setting_modes_via_auxswitch(self): + def SetModesViaAuxSwitch(self): + '''"Set modes via auxswitch"''' self.context_push() ex = None try: @@ -3961,7 +4274,7 @@ def test_guided_local_position_target(self, x, y, z_up): if not (m.type_mask == (target_typemask | MAV_POS_TARGET_TYPE_MASK.LAST_BYTE) or m.type_mask == target_typemask): raise NotAchievedException("Did not receive proper mask: expected=%u or %u, got=%u" % - ((target_typemask | MAV_POS_TARGET_TYPE_MASK.LAST_BYTE), target_typemask, m.type_mask)) + ((target_typemask | MAV_POS_TARGET_TYPE_MASK.LAST_BYTE), target_typemask, m.type_mask)) if x - m.x > 0.1: raise NotAchievedException("Did not receive proper target position x: wanted=%f got=%f" % (x, m.x)) @@ -4012,7 +4325,7 @@ def test_guided_local_velocity_target(self, vx, vy, vz_up, timeout=3): # Check the last received message if not (m.type_mask == (target_typemask | MAV_POS_TARGET_TYPE_MASK.LAST_BYTE) or m.type_mask == target_typemask): raise NotAchievedException("Did not receive proper mask: expected=%u or %u, got=%u" % - ((target_typemask | MAV_POS_TARGET_TYPE_MASK.LAST_BYTE), target_typemask, m.type_mask)) + ((target_typemask | MAV_POS_TARGET_TYPE_MASK.LAST_BYTE), target_typemask, m.type_mask)) if vx - m.vx > 0.1: raise NotAchievedException("Did not receive proper target velocity vx: wanted=%f got=%f" % (vx, m.vx)) @@ -4025,6 +4338,47 @@ def test_guided_local_velocity_target(self, vx, vy, vz_up, timeout=3): self.progress("Received proper target velocity commands") + def wait_for_local_velocity(self, vx, vy, vz_up, timeout=10): + """ Wait for local target velocity""" + + # debug messages + self.progress("Waiting for local NED velocity target: (%f, %f, %f)" % (vx, vy, -vz_up)) + self.progress("Setting LOCAL_POSITION_NED message rate to 10Hz") + + # set position local ned message stream rate + self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_LOCAL_POSITION_NED, 10) + + # wait for position local ned message + tstart = self.get_sim_time() + while self.get_sim_time_cached() - tstart < timeout: + + # get position target local ned message + m = self.mav.recv_match(type="LOCAL_POSITION_NED", blocking=True, timeout=1) + + # could not be able to get a valid target local ned message within given time + if m is None: + + # raise an error that did not receive a valid target local ned message within given time + raise NotAchievedException("Did not receive any position local ned message for 1 second!") + + # got a valid target local ned message within given time + else: + + # debug message + self.progress("Received local position ned message: %s" % str(m)) + + # check if velocity values are in range + if vx - m.vx <= 0.1 and vy - m.vy <= 0.1 and vz_up - (-m.vz) <= 0.1: + + # get out of function + self.progress("Vehicle successfully reached to target velocity!") + return + + # raise an exception + error_message = "Did not receive target velocities vx, vy, vz_up, wanted=(%f, %f, %f) got=(%f, %f, %f)" + error_message = error_message % (vx, vy, vz_up, m.vx, m.vy, -m.vz) + raise NotAchievedException(error_message) + def test_position_target_message_mode(self): " Ensure that POSITION_TARGET_LOCAL_NED messages are sent in Guided Mode only " self.hover() @@ -4047,15 +4401,16 @@ def earth_to_body(self, vector): # print("r=%s" % str(r)) return r * vector - def loiter_to_ne(self, x, y, z, timeout=40): - '''loiter to x, y, z from origin (in metres), z is *up*''' + def precision_loiter_to_pos(self, x, y, z, timeout=40): + '''send landing_target messages at vehicle until it arrives at + location to x, y, z from origin (in metres), z is *up*''' dest_ned = rotmat.Vector3(x, y, -z) tstart = self.get_sim_time() success_start = -1 while True: now = self.get_sim_time_cached() if now - tstart > timeout: - raise NotAchievedException("Did not loiter to ne!") + raise NotAchievedException("Did not loiter to position!") m_pos = self.mav.recv_match(type='LOCAL_POSITION_NED', blocking=True) pos_ned = rotmat.Vector3(m_pos.x, m_pos.y, m_pos.z) @@ -4102,7 +4457,7 @@ def loiter_to_ne(self, x, y, z, timeout=40): 0.01 # size of target in radians, Y-axis ) - def fly_payload_place_mission(self): + def PayLoadPlaceMission(self): """Test payload placing in auto.""" self.context_push() @@ -4115,25 +4470,31 @@ def fly_payload_place_mission(self): "SIM_GRPS_ENABLE": 1, "SIM_GRPS_PIN": 8, "SERVO8_FUNCTION": 28, - "RC9_OPTION": 19, }) self.reboot_sitl() - self.set_rc(9, 2000) - # load the mission: + self.load_mission("copter_payload_place.txt") + if self.mavproxy is not None: + self.mavproxy.send('wp list\n') - self.progress("Waiting for location") - self.mav.location() - self.zero_throttle() - self.change_mode('STABILIZE') + self.set_parameter("AUTO_OPTIONS", 3) + self.change_mode('AUTO') self.wait_ready_to_arm() self.arm_vehicle() - self.change_mode('AUTO') - - self.set_rc(3, 1500) self.wait_text("Gripper load releas", timeout=90) + dist_limit = 1 + # this is a copy of the point in the mission file: + target_loc = mavutil.location(-35.363106, + 149.165436, + 0, + 0) + dist = self.get_distance(target_loc, self.mav.location()) + self.progress("dist=%f" % (dist,)) + if dist > dist_limit: + raise NotAchievedException("Did not honour target lat/lng (dist=%f want <%f" % + (dist, dist_limit)) self.wait_disarmed() @@ -4148,7 +4509,7 @@ def fly_payload_place_mission(self): if ex is not None: raise ex - def fly_guided_change_submode(self): + def GuidedSubModeChange(self): """"Ensure we can move around in guided after a takeoff command.""" '''start by disabling GCS failsafe, otherwise we immediately disarm @@ -4177,6 +4538,17 @@ def fly_guided_change_submode(self): self.fly_guided_stop(groundspeed_tolerance=0.1) self.fly_guided_move_local(5, 5, 10) + self.start_subtest("Checking that WP_YAW_BEHAVIOUR 0 works") + self.set_parameter('WP_YAW_BEHAVIOR', 0) + self.delay_sim_time(2) + orig_heading = self.get_heading() + self.fly_guided_move_local(5, 0, 10) + # ensure our heading hasn't changed: + self.assert_heading(orig_heading) + self.fly_guided_move_local(0, 5, 10) + # ensure our heading hasn't changed: + self.assert_heading(orig_heading) + self.start_subtest("Check target position received by vehicle using SET_MESSAGE_INTERVAL") self.test_guided_local_position_target(5, 5, 10) self.test_guided_local_velocity_target(2, 2, 1) @@ -4184,7 +4556,8 @@ def fly_guided_change_submode(self): self.do_RTL() - def test_gripper_mission(self): + def TestGripperMission(self): + '''Test Gripper mission items''' self.context_push() ex = None try: @@ -4206,7 +4579,8 @@ def test_gripper_mission(self): if ex is not None: raise ex - def test_spline_last_waypoint(self): + def SplineLastWaypoint(self): + '''Test Spline as last waypoint''' self.context_push() ex = None try: @@ -4226,7 +4600,8 @@ def test_spline_last_waypoint(self): if ex is not None: raise ex - def fly_manual_throttle_mode_change(self): + def ManualThrottleModeChange(self): + '''Check manual throttle mode changes denied on high throttle''' self.set_parameter("FS_GCS_ENABLE", 0) # avoid GUIDED instant disarm self.change_mode("STABILIZE") self.wait_ready_to_arm() @@ -4235,7 +4610,7 @@ def fly_manual_throttle_mode_change(self): self.change_mode("STABILIZE") self.change_mode("GUIDED") self.set_rc(3, 1700) - self.watch_altitude_maintained(-1, 0.2) # should not take off in guided + self.watch_altitude_maintained(altitude_min=-1, altitude_max=0.2) # should not take off in guided self.run_cmd_do_set_mode( "ACRO", want_result=mavutil.mavlink.MAV_RESULT_FAILED) @@ -4270,16 +4645,10 @@ def test_mount_pitch(self, despitch, despitch_tolerance, mount_mode, timeout=10, if now - tstart > timeout: raise NotAchievedException("Mount pitch not achieved") - m = self.mav.recv_match(type='MOUNT_STATUS', - blocking=True, - timeout=5) - - if m.mount_mode != mount_mode: - raise NotAchievedException("MAV_MOUNT_MODE Not: %s" % (mount_mode)) + '''retrieve latest angles from GIMBAL_DEVICE_ATTITUDE_STATUS''' + mount_roll, mount_pitch, mount_yaw = self.get_mount_roll_pitch_yaw_deg() -# self.progress("pitch=%f roll=%f yaw=%f" % -# (m.pointing_a, m.pointing_b, m.pointing_c)) - mount_pitch = m.pointing_a/100.0 # centidegrees to degrees + self.progress("despitch=%f roll=%f pitch=%f yaw=%f" % (despitch, mount_roll, mount_pitch, mount_yaw)) if abs(despitch - mount_pitch) > despitch_tolerance: self.progress("Mount pitch incorrect: got=%f want=%f (+/- %f)" % (mount_pitch, despitch, despitch_tolerance)) @@ -4311,13 +4680,35 @@ def setup_servo_mount(self, roll_servo=5, pitch_servo=6, yaw_servo=7): '''configure a rpy servo mount; caller responsible for required rebooting''' self.progress("Setting up servo mount") self.set_parameters({ - "MNT_TYPE": 1, + "MNT1_TYPE": 1, + "MNT1_PITCH_MIN": -45, + "MNT1_PITCH_MAX": 45, + "RC6_OPTION": 213, # MOUNT1_PITCH "SERVO%u_FUNCTION" % roll_servo: 8, # roll "SERVO%u_FUNCTION" % pitch_servo: 7, # pitch "SERVO%u_FUNCTION" % yaw_servo: 6, # yaw }) - def test_mount(self): + def get_mount_roll_pitch_yaw_deg(self): + '''return mount (aka gimbal) roll, pitch and yaw angles in degrees''' + # wait for gimbal attitude message + m = self.assert_receive_message('GIMBAL_DEVICE_ATTITUDE_STATUS', timeout=5) + + # convert quaternion to euler angles and return + q = quaternion.Quaternion(m.q) + euler = q.euler + return math.degrees(euler[0]), math.degrees(euler[1]), math.degrees(euler[2]) + + def set_mount_mode(self, mount_mode): + '''set mount mode''' + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_MOUNT_CONFIGURE, + mount_mode, + 0, # stabilize roll (unsupported) + 0, # stabilize pitch (unsupported) + 0, 0, 0, 0) + + def Mount(self): + '''Test Camera/Antenna Mount''' ex = None self.context_push() old_srcSystem = self.mav.mav.srcSystem @@ -4329,26 +4720,19 @@ def test_mount(self): too long. This is probably a function of --speedup''' self.set_parameter("FS_GCS_ENABLE", 0) + # setup mount parameters self.setup_servo_mount() self.reboot_sitl() # to handle MNT_TYPE changing - # make sure we're getting mount status and gimbal reports - self.mav.recv_match(type='MOUNT_STATUS', - blocking=True, - timeout=5) - self.mav.recv_match(type='GIMBAL_REPORT', - blocking=True, - timeout=5) - - # test pitch isn't stabilising: - m = self.mav.recv_match(type='MOUNT_STATUS', - blocking=True, - timeout=5) + # make sure we're getting gimbal device attitude status + self.assert_receive_message('GIMBAL_DEVICE_ATTITUDE_STATUS', timeout=5) - if m.mount_mode != mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING: - raise NotAchievedException("Mount_Mode: Default Not MAV_MOUNT_MODE_RC_TARGETING") + # change mount to neutral mode (point forward, not stabilising) + self.set_mount_mode(mavutil.mavlink.MAV_MOUNT_MODE_NEUTRAL) - if m.pointing_a != 0 or m.pointing_b != 0 or m.pointing_c != 0: + # test pitch is not stabilising + mount_roll_deg, mount_pitch_deg, mount_yaw_deg = self.get_mount_roll_pitch_yaw_deg() + if mount_roll_deg != 0 or mount_pitch_deg != 0 or mount_yaw_deg != 0: raise NotAchievedException("Mount stabilising when not requested") self.change_mode('GUIDED') @@ -4357,6 +4741,7 @@ def test_mount(self): self.user_takeoff() + # pitch vehicle back and confirm gimbal is still not stabilising despitch = 10 despitch_tolerance = 3 @@ -4365,74 +4750,41 @@ def test_mount(self): self.wait_pitch(despitch, despitch_tolerance) - # check we haven't modified: - m = self.mav.recv_match(type='MOUNT_STATUS', - blocking=True, - timeout=5) - - if m.mount_mode != mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING: - raise NotAchievedException("Mount_Mode: changed when not requested") - - if m.pointing_a != 0 or m.pointing_b != 0 or m.pointing_c != 0: + # check gimbal is still not stabilising + mount_roll_deg, mount_pitch_deg, mount_yaw_deg = self.get_mount_roll_pitch_yaw_deg() + if mount_roll_deg != 0 or mount_pitch_deg != 0 or mount_yaw_deg != 0: raise NotAchievedException("Mount stabilising when not requested") - self.progress("Enable pitch stabilization using MOUNT_CONFIGURE") - self.mav.mav.mount_configure_send( - 1, # target system - 1, # target component - mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING, - 0, # stab-roll - 1, # stab-pitch - 0) + # center RC tilt control and change mount to RC_TARGETING mode + self.progress("Gimbal to RC Targetting mode") + self.set_rc(6, 1500) + self.set_mount_mode(mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) + # pitch vehicle back and confirm gimbal is stabilising + self.progress("Pitching vehicle") self.do_pitch(despitch) + self.wait_pitch(despitch, despitch_tolerance) self.test_mount_pitch(-despitch, 1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) - self.progress("Disable pitch using MAV_CMD_DO_MOUNT_CONFIGURE") - self.do_pitch(despitch) - self.run_cmd(mavutil.mavlink.MAV_CMD_DO_MOUNT_CONFIGURE, - mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING, - 0, - 0, - 0, - 0, - 0, - 0, - ) - self.test_mount_pitch(0, 0, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) - - self.progress("Point somewhere using MOUNT_CONTROL (ANGLE)") - self.do_pitch(despitch) - self.run_cmd(mavutil.mavlink.MAV_CMD_DO_MOUNT_CONFIGURE, - mavutil.mavlink.MAV_MOUNT_MODE_MAVLINK_TARGETING, - 0, - 0, - 0, - 0, - 0, - 0, - ) - self.mav.mav.mount_control_send( - 1, # target system - 1, # target component - 20 * 100, # pitch - 20 * 100, # roll (centidegrees) - 0, # yaw - 0 # save position - ) - self.test_mount_pitch(20, 1, mavutil.mavlink.MAV_MOUNT_MODE_MAVLINK_TARGETING) - - self.progress("Point somewhere using MOUNT_CONTROL (GPS)") + # point gimbal at specified angle + self.progress("Point gimbal using GIMBAL_MANAGER_PITCHYAW (ANGLE)") + self.do_pitch(0) # level vehicle + self.wait_pitch(0, despitch_tolerance) + self.set_mount_mode(mavutil.mavlink.MAV_MOUNT_MODE_MAVLINK_TARGETING) + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW, + -20, # pitch angle in degrees + 0, # yaw angle in degrees + 0, # pitch rate in degrees (NaN to ignore) + 0, # yaw rate in degrees (NaN to ignore) + 0, # flags (0=Body-frame, 16/GIMBAL_MANAGER_FLAGS_YAW_LOCK=Earth Frame) + 0, # unused + 0) # gimbal id + self.test_mount_pitch(-20, 1, mavutil.mavlink.MAV_MOUNT_MODE_MAVLINK_TARGETING) + + # point gimbal at specified location + self.progress("Point gimbal at Location using MOUNT_CONTROL (GPS)") self.do_pitch(despitch) - self.run_cmd(mavutil.mavlink.MAV_CMD_DO_MOUNT_CONFIGURE, - mavutil.mavlink.MAV_MOUNT_MODE_GPS_POINT, - 0, - 0, - 0, - 0, - 0, - 0, - ) + self.set_mount_mode(mavutil.mavlink.MAV_MOUNT_MODE_GPS_POINT) # Delay here to allow the attitude to command to timeout and level out the copter a bit self.delay_sim_time(3) @@ -4471,21 +4823,20 @@ def test_mount(self): 0, # yaw rate (rad/s) 0.5) # thrust, 0 to 1, translated to a climb/descent rate - self.run_cmd(mavutil.mavlink.MAV_CMD_DO_MOUNT_CONFIGURE, - mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING, - 0, - 0, - 0, - 0, - 0, - 0, - ) + self.set_mount_mode(mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) + try: self.context_push() self.set_parameters({ - 'MNT_RC_IN_ROLL': 11, - 'MNT_RC_IN_TILT': 12, - 'MNT_RC_IN_PAN': 13, + 'RC6_OPTION': 0, + 'RC11_OPTION': 212, # MOUNT1_ROLL + 'RC12_OPTION': 213, # MOUNT1_PITCH + 'RC13_OPTION': 214, # MOUNT1_YAW + 'RC12_MIN': 1100, + 'RC12_MAX': 1900, + 'RC12_TRIM': 1500, + 'MNT1_PITCH_MIN': -45, + 'MNT1_PITCH_MAX': 45, }) self.progress("Testing RC angular control") # default RC min=1100 max=1900 @@ -4499,9 +4850,9 @@ def test_mount(self): rc12_in = 1400 rc12_min = 1100 # default rc12_max = 1900 # default - angmin_tilt = -45.0 # default - angmax_tilt = 45.0 # default - expected_pitch = (float(rc12_in-rc12_min)/float(rc12_max-rc12_min) * (angmax_tilt-angmin_tilt)) + angmin_tilt + mpitch_min = -45.0 + mpitch_max = 45.0 + expected_pitch = (float(rc12_in-rc12_min)/float(rc12_max-rc12_min) * (mpitch_max-mpitch_min)) + mpitch_min self.progress("expected mount pitch: %f" % expected_pitch) if expected_pitch != -11.25: raise NotAchievedException("Calculation wrong - defaults changed?!") @@ -4516,30 +4867,26 @@ def test_mount(self): }) try: - self.progress( - "Issue https://discuss.ardupilot.org/t/" - "gimbal-limits-with-storm32-backend-mavlink-not-applied-correctly/51438" - ) self.context_push() self.set_parameters({ "RC12_MIN": 1000, "RC12_MAX": 2000, - "MNT_ANGMIN_TIL": -9000, - "MNT_ANGMAX_TIL": 1000, + "MNT1_PITCH_MIN": -90, + "MNT1_PITCH_MAX": 10, }) self.set_rc(12, 1000) - self.test_mount_pitch(-90.00, 0.01, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) + self.test_mount_pitch(-90.00, 0.1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) self.set_rc(12, 2000) - self.test_mount_pitch(10.00, 0.01, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) + self.test_mount_pitch(10.00, 0.1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) self.set_rc(12, 1500) - self.test_mount_pitch(-40.00, 0.01, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) + self.test_mount_pitch(-40.00, 0.1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) finally: self.context_pop() self.set_rc(12, 1500) self.progress("Testing RC rate control") - self.set_parameter('MNT_JSTICK_SPD', 10) + self.set_parameter('MNT1_RC_RATE', 10) self.test_mount_pitch(0, 1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) self.set_rc(12, 1300) self.test_mount_pitch(-5, 1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) @@ -4554,7 +4901,7 @@ def test_mount(self): self.test_mount_pitch(5, 1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) self.progress("Reverting to angle mode") - self.set_parameter('MNT_JSTICK_SPD', 0) + self.set_parameter('MNT1_RC_RATE', 0) self.set_rc(12, 1500) self.test_mount_pitch(0, 0.1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) @@ -4566,7 +4913,6 @@ def test_mount(self): raise e self.progress("Testing mount ROI behaviour") - self.drain_mav_unparsed() self.test_mount_pitch(0, 0.1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) start = self.mav.location() self.progress("start=%s" % str(start)) @@ -4639,15 +4985,7 @@ def test_mount(self): ) self.test_mount_pitch(-70, 1, mavutil.mavlink.MAV_MOUNT_MODE_GPS_POINT, hold=2) - self.run_cmd(mavutil.mavlink.MAV_CMD_DO_MOUNT_CONFIGURE, - mavutil.mavlink.MAV_MOUNT_MODE_NEUTRAL, - 0, - 0, - 0, - 0, - 0, - 0, - ) + self.set_mount_mode(mavutil.mavlink.MAV_MOUNT_MODE_NEUTRAL) self.test_mount_pitch(0, 0.1, mavutil.mavlink.MAV_MOUNT_MODE_NEUTRAL) self.progress("Testing mount roi-sysid behaviour") @@ -4661,7 +4999,7 @@ def test_mount(self): roi_alt = 0 self.progress("Using MAV_CMD_DO_SET_ROI_SYSID") self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_ROI_SYSID, - 250, + self.mav.source_system, 0, 0, 0, @@ -4695,15 +5033,7 @@ def test_mount(self): ) self.test_mount_pitch(68, 5, mavutil.mavlink.MAV_MOUNT_MODE_SYSID_TARGET, hold=2) - self.run_cmd(mavutil.mavlink.MAV_CMD_DO_MOUNT_CONFIGURE, - mavutil.mavlink.MAV_MOUNT_MODE_NEUTRAL, - 0, - 0, - 0, - 0, - 0, - 0, - ) + self.set_mount_mode(mavutil.mavlink.MAV_MOUNT_MODE_NEUTRAL) self.test_mount_pitch(0, 0.1, mavutil.mavlink.MAV_MOUNT_MODE_NEUTRAL) except Exception as e: @@ -4714,18 +5044,19 @@ def test_mount(self): self.mav.mav.srcSystem = old_srcSystem self.disarm_vehicle(force=True) - self.reboot_sitl() # to handle MNT_TYPE changing + self.reboot_sitl() # to handle MNT1_TYPE changing if ex is not None: raise ex def MountYawVehicleForMountROI(self): + '''Test Camera/Antenna Mount vehicle yawing for ROI''' self.context_push() self.set_parameter("SYSID_MYGCS", self.mav.source_system) yaw_servo = 7 self.setup_servo_mount(yaw_servo=yaw_servo) - self.reboot_sitl() # to handle MNT_TYPE changing + self.reboot_sitl() # to handle MNT1_TYPE changing self.progress("checking ArduCopter yaw-aircraft-for-roi") ex = None @@ -4813,7 +5144,8 @@ def MountYawVehicleForMountROI(self): if ex is not None: raise ex - def fly_throw_mode(self): + def ThrowMode(self): + '''Fly Throw Mode''' # test boomerang mode: self.progress("Throwing vehicle away") self.set_parameters({ @@ -4842,19 +5174,15 @@ def fly_throw_mode(self): (tdelta, max_good_tdelta)) self.progress("Vehicle returned") - def hover_and_check_matched_frequency_with_fft(self, dblevel=-15, minhz=200, maxhz=300, peakhz=None, reverse=None): + def hover_and_check_matched_frequency_with_fft(self, dblevel=-15, minhz=200, maxhz=300, peakhz=None, + reverse=None, takeoff=True): # find a motor peak - self.takeoff(10, mode="ALT_HOLD") - - hover_time = 15 - tstart = self.get_sim_time() - self.progress("Hovering for %u seconds" % hover_time) - while self.get_sim_time_cached() < tstart + hover_time: - self.mav.recv_match(type='ATTITUDE', blocking=True) - vfr_hud = self.mav.recv_match(type='VFR_HUD', blocking=True) - tend = self.get_sim_time() + if takeoff: + self.takeoff(10, mode="ALT_HOLD") + tstart, tend, hover_throttle = self.hover_for_interval(15) self.do_RTL() + psd = self.mavfft_fttd(1, 0, tstart * 1.0e6, tend * 1.0e6) # batch sampler defaults give 1024 fft and sample rate of 1kz so roughly 1hz/bin @@ -4869,13 +5197,14 @@ def hover_and_check_matched_frequency_with_fft(self, dblevel=-15, minhz=200, max if reverse is not None: raise NotAchievedException( "Detected motor peak at %fHz, throttle %f%%, %fdB" % - (freq, vfr_hud.throttle, peakdb)) + (freq, hover_throttle, peakdb)) else: - self.progress("Detected motor peak at %fHz, throttle %f%%, %fdB" % (freq, vfr_hud.throttle, peakdb)) + self.progress("Detected motor peak at %fHz, throttle %f%%, %fdB" % + (freq, hover_throttle, peakdb)) - return freq, vfr_hud, peakdb + return freq, hover_throttle, peakdb - def fly_dynamic_notches(self): + def DynamicNotches(self): """Use dynamic harmonic notch to control motor noise.""" self.progress("Flying with dynamic notches") self.context_push() @@ -4897,27 +5226,27 @@ def fly_dynamic_notches(self): self.takeoff(10, mode="ALT_HOLD") # find a motor peak - freq, vfr_hud, peakdb = self.hover_and_check_matched_frequency_with_fft(-15, 200, 300) + freq, hover_throttle, peakdb = self.hover_and_check_matched_frequency_with_fft(-15, 200, 300) # now add a dynamic notch and check that the peak is squashed self.set_parameters({ "INS_LOG_BAT_OPT": 2, "INS_HNTCH_ENABLE": 1, "INS_HNTCH_FREQ": freq, - "INS_HNTCH_REF": vfr_hud.throttle/100., + "INS_HNTCH_REF": hover_throttle/100., "INS_HNTCH_HMNCS": 5, # first and third harmonic "INS_HNTCH_ATT": 50, "INS_HNTCH_BW": freq/2, }) self.reboot_sitl() - freq, vfr_hud, peakdb1 = self.hover_and_check_matched_frequency_with_fft(-10, 20, 350, reverse=True) + freq, hover_throttle, peakdb1 = self.hover_and_check_matched_frequency_with_fft(-10, 20, 350, reverse=True) # now add double dynamic notches and check that the peak is squashed self.set_parameter("INS_HNTCH_OPTS", 1) self.reboot_sitl() - freq, vfr_hud, peakdb2 = self.hover_and_check_matched_frequency_with_fft(-15, 20, 350, reverse=True) + freq, hover_throttle, peakdb2 = self.hover_and_check_matched_frequency_with_fft(-15, 20, 350, reverse=True) # double-notch should do better, but check for within 5% if peakdb2 * 1.05 > peakdb1: @@ -4925,16 +5254,28 @@ def fly_dynamic_notches(self): "Double-notch peak was higher than single-notch peak %fdB > %fdB" % (peakdb2, peakdb1)) - except Exception as e: - self.print_exception_caught(e) - ex = e + # now add triple dynamic notches and check that the peak is squashed + self.set_parameter("INS_HNTCH_OPTS", 16) + self.reboot_sitl() + + freq, hover_throttle, peakdb2 = self.hover_and_check_matched_frequency_with_fft(-15, 20, 350, reverse=True) + + # triple-notch should do better, but check for within 5% + if peakdb2 * 1.05 > peakdb1: + raise NotAchievedException( + "Triple-notch peak was higher than single-notch peak %fdB > %fdB" % + (peakdb2, peakdb1)) + + except Exception as e: + self.print_exception_caught(e) + ex = e self.context_pop() if ex is not None: raise ex - def fly_esc_telemetry_notches(self): + def DynamicRpmNotches(self): """Use dynamic harmonic notch to control motor noise via ESC telemetry.""" self.progress("Flying with ESC telemetry driven dynamic notches") @@ -4948,14 +5289,14 @@ def fly_esc_telemetry_notches(self): "LOG_DISARMED": 0, "SIM_VIB_MOT_MAX": 350, "SIM_GYR1_RND": 20, - "SIM_ESC_TELEM": 1, + "SIM_ESC_TELEM": 1 }) self.reboot_sitl() self.takeoff(10, mode="ALT_HOLD") # find a motor peak - freq, vfr_hud, peakdb = self.hover_and_check_matched_frequency_with_fft(-15, 200, 300) + freq, hover_throttle, peakdb = self.hover_and_check_matched_frequency_with_fft(-15, 200, 300) # now add a dynamic notch and check that the peak is squashed self.set_parameters({ @@ -4970,13 +5311,13 @@ def fly_esc_telemetry_notches(self): }) self.reboot_sitl() - freq, vfr_hud, peakdb1 = self.hover_and_check_matched_frequency_with_fft(-10, 20, 350, reverse=True) + freq, hover_throttle, peakdb1 = self.hover_and_check_matched_frequency_with_fft(-10, 20, 350, reverse=True) # now add notch-per motor and check that the peak is squashed self.set_parameter("INS_HNTCH_OPTS", 2) self.reboot_sitl() - freq, vfr_hud, peakdb2 = self.hover_and_check_matched_frequency_with_fft(-15, 20, 350, reverse=True) + freq, hover_throttle, peakdb2 = self.hover_and_check_matched_frequency_with_fft(-15, 20, 350, reverse=True) # notch-per-motor should do better, but check for within 5% if peakdb2 * 1.05 > peakdb1: @@ -4995,14 +5336,14 @@ def fly_esc_telemetry_notches(self): defaults_filepath=','.join(self.model_defaults_filepath("octa")), model="octa" ) - freq, vfr_hud, peakdb1 = self.hover_and_check_matched_frequency_with_fft(-10, 20, 350, reverse=True) + freq, hover_throttle, peakdb1 = self.hover_and_check_matched_frequency_with_fft(-10, 20, 350, reverse=True) # now add notch-per motor and check that the peak is squashed self.set_parameter("INS_HNTCH_HMNCS", 1) self.set_parameter("INS_HNTCH_OPTS", 2) self.reboot_sitl() - freq, vfr_hud, peakdb2 = self.hover_and_check_matched_frequency_with_fft(-15, 20, 350, reverse=True) + freq, hover_throttle, peakdb2 = self.hover_and_check_matched_frequency_with_fft(-15, 20, 350, reverse=True) # notch-per-motor should do better, but check for within 5% if peakdb2 * 1.05 > peakdb1: @@ -5018,18 +5359,13 @@ def fly_esc_telemetry_notches(self): raise ex def hover_and_check_matched_frequency(self, dblevel=-15, minhz=200, maxhz=300, fftLength=32, peakhz=None): - # find a motor peak + '''do a simple up-and-down test flight with current vehicle state. + Check that the onboard filter comes up with the same peak-frequency that + post-processing does.''' self.takeoff(10, mode="ALT_HOLD") - - hover_time = 15 - tstart = self.get_sim_time() - self.progress("Hovering for %u seconds" % hover_time) - while self.get_sim_time_cached() < tstart + hover_time: - self.mav.recv_match(type='ATTITUDE', blocking=True) - vfr_hud = self.mav.recv_match(type='VFR_HUD', blocking=True) - tend = self.get_sim_time() - + tstart, tend, hover_throttle = self.hover_for_interval(15) self.do_RTL() + psd = self.mavfft_fttd(1, 0, tstart * 1.0e6, tend * 1.0e6) # batch sampler defaults give 1024 fft and sample rate of 1kz so roughly 1hz/bin @@ -5038,53 +5374,60 @@ def hover_and_check_matched_frequency(self, dblevel=-15, minhz=200, maxhz=300, f smaxhz = int(maxhz * scale) freq = psd["F"][numpy.argmax(psd["X"][sminhz:smaxhz]) + sminhz] peakdb = numpy.amax(psd["X"][sminhz:smaxhz]) + + self.progress("Post-processing FFT detected motor peak at %fHz/%fdB, throttle %f%%" % + (freq, peakdb, hover_throttle)) + if peakdb < dblevel: - raise NotAchievedException("Did not detect a motor peak, found %fHz at %fdB" % (freq, peakdb)) - elif peakhz is not None and abs(freq - peakhz) / peakhz > 0.05: - raise NotAchievedException("Did not detect a motor peak at %fHz, found %fHz at %fdB" % (peakhz, freq, peakdb)) - else: - self.progress("Detected motor peak at %fHz, throttle %f%%, %fdB" % (freq, vfr_hud.throttle, peakdb)) + raise NotAchievedException( + "Detected motor peak not strong enough; want=%fdB got=%fdB" % + (peakdb, dblevel)) - # we have a peak make sure that the FFT detected something close - # logging is at 10Hz - mlog = self.dfreader_for_current_onboard_log() - # accuracy is determined by sample rate and fft length, given our use of quinn we could probably use half of this - freqDelta = 1000. / fftLength - pkAvg = freq - nmessages = 1 + # caller can supply an expected frequency: + if peakhz is not None and abs(freq - peakhz) / peakhz > 0.05: + raise NotAchievedException( + "Post-processing detected motor peak at wrong frequency; want=%fHz got=%fHz" % + (peakhz, freq)) - m = mlog.recv_match( - type='FTN1', - blocking=False, - condition="FTN1.TimeUS>%u and FTN1.TimeUS<%u" % (tstart * 1.0e6, tend * 1.0e6) - ) - freqs = [] - while m is not None: - nmessages = nmessages + 1 - freqs.append(m.PkAvg) - m = mlog.recv_match( - type='FTN1', - blocking=False, - condition="FTN1.TimeUS>%u and FTN1.TimeUS<%u" % (tstart * 1.0e6, tend * 1.0e6) - ) + # we have a peak make sure that the onboard filter detected + # something close logging is at 10Hz # peak within resolution of FFT length - pkAvg = numpy.median(numpy.asarray(freqs)) - self.progress("Detected motor peak at %fHz processing %d messages" % (pkAvg, nmessages)) + pkAvg, nmessages = self.extract_median_FTN1_PkAvg_from_current_onboard_log(tstart, tend) + self.progress("Onboard-FFT detected motor peak at %fHz (processed %d FTN1 messages)" % (pkAvg, nmessages)) - # peak within 5% + # accuracy is determined by sample rate and fft length, given + # our use of quinn we could probably use half of this + freqDelta = 1000. / fftLength if abs(pkAvg - freq) > freqDelta: - raise NotAchievedException("FFT did not detect a motor peak at %f, found %f, wanted %f" % (dblevel, pkAvg, freq)) - + raise NotAchievedException( + "post-processed FFT does not agree with onboard filter on peak frequency; onboard=%fHz post-processed=%fHz/%fdB" % # noqa + (pkAvg, freq, dblevel) + ) return freq - def fly_gyro_fft_harmonic(self): + def extract_median_FTN1_PkAvg_from_current_onboard_log(self, tstart, tend): + '''extracts FTN1 messages from log, returns median of pkAvg values and + the number of samples''' + mlog = self.dfreader_for_current_onboard_log() + freqs = [] + while True: + m = mlog.recv_match( + type='FTN1', + blocking=False, + condition="FTN1.TimeUS>%u and FTN1.TimeUS<%u" % (tstart * 1.0e6, tend * 1.0e6)) + if m is None: + break + freqs.append(m.PkAvg) + return numpy.median(numpy.asarray(freqs)), len(freqs) + + def test_gyro_fft_harmonic(self, averaging): """Use dynamic harmonic notch to control motor noise with harmonic matching of the first harmonic.""" # basic gyro sample rate test self.progress("Flying with gyro FFT harmonic - Gyro sample rate") self.context_push() ex = None - # we are dealing with probabalistic scenarios involving threads, have two bites at the cherry + # we are dealing with probabalistic scenarios involving threads try: self.start_subtest("Hover to calculate approximate hover frequency") # magic tridge EKF type that dramatically speeds up the test @@ -5103,6 +5446,7 @@ def fly_gyro_fft_harmonic(self): "FFT_THR_REF": self.get_parameter("MOT_THST_HOVER"), "SIM_GYR1_RND": 20, # enable a noisy gyro }) + # motor peak enabling FFT will also enable the arming # check, self-testing the functionality self.set_parameters({ @@ -5111,6 +5455,8 @@ def fly_gyro_fft_harmonic(self): "FFT_MAXHZ": 450, "FFT_SNR_REF": 10, }) + if averaging: + self.set_parameter("FFT_NUM_FRAMES", 8) # Step 1: inject actual motor noise and use the FFT to track it self.set_parameters({ @@ -5143,37 +5489,18 @@ def fly_gyro_fft_harmonic(self): self.takeoff(10, mode="ALT_HOLD") hover_time = 10 - tstart = self.get_sim_time() - self.progress("Hovering for %u seconds" % hover_time) - while self.get_sim_time_cached() < tstart + hover_time: - self.mav.recv_match(type='ATTITUDE', blocking=True) - vfr_hud = self.mav.recv_match(type='VFR_HUD', blocking=True) + tstart, tend_unused, hover_throttle = self.hover_for_interval(hover_time) + self.progress("Switching motor vibration multiplier") self.set_parameter("SIM_VIB_MOT_MULT", 5.0) - self.progress("Hovering for %u seconds" % hover_time) - while self.get_sim_time_cached() < tstart + hover_time: - self.mav.recv_match(type='ATTITUDE', blocking=True) - vfr_hud = self.mav.recv_match(type='VFR_HUD', blocking=True) - tend = self.get_sim_time() + tstart_unused, tend, hover_throttle = self.hover_for_interval(hover_time) self.do_RTL() - mlog = self.dfreader_for_current_onboard_log() - m = mlog.recv_match( - type='FTN1', - blocking=False, - condition="FTN1.TimeUS>%u and FTN1.TimeUS<%u" % (tstart * 1.0e6, tend * 1.0e6)) - freqs = [] - while m is not None: - freqs.append(m.PkAvg) - m = mlog.recv_match( - type='FTN1', - blocking=False, - condition="FTN1.TimeUS>%u and FTN1.TimeUS<%u" % (tstart * 1.0e6, tend * 1.0e6)) - # peak within resolution of FFT length, the highest energy peak switched but our detection should not - pkAvg = numpy.median(numpy.asarray(freqs)) + pkAvg, nmessages = self.extract_median_FTN1_PkAvg_from_current_onboard_log(tstart, tend) + freqDelta = 1000. / self.get_parameter("FFT_WINDOW_SIZE") if abs(pkAvg - freq) > freqDelta: @@ -5182,7 +5509,7 @@ def fly_gyro_fft_harmonic(self): # Step 4: dynamic harmonic self.start_subtest("Enable dynamic harmonics and make sure both frequency peaks are attenuated") # find a motor peak - freq, vfr_hud, peakdb = self.hover_and_check_matched_frequency_with_fft(-15, 100, 350) + freq, hover_throttle, peakdb = self.hover_and_check_matched_frequency_with_fft(-15, 100, 350) # now add a dynamic notch and check that the peak is squashed self.set_parameters({ @@ -5191,7 +5518,7 @@ def fly_gyro_fft_harmonic(self): "INS_HNTCH_HMNCS": 1, "INS_HNTCH_MODE": 4, "INS_HNTCH_FREQ": freq, - "INS_HNTCH_REF": vfr_hud.throttle/100.0, + "INS_HNTCH_REF": hover_throttle/100.0, "INS_HNTCH_ATT": 100, "INS_HNTCH_BW": freq/2, "INS_HNTCH_OPTS": 3, @@ -5225,7 +5552,16 @@ def fly_gyro_fft_harmonic(self): if ex is not None: raise ex - def fly_gyro_fft(self): + def GyroFFTHarmonic(self): + """Use dynamic harmonic notch to control motor noise with harmonic matching of the first harmonic.""" + self.test_gyro_fft_harmonic(False) + + def GyroFFTContinuousAveraging(self): + """Use dynamic harmonic notch with FFT averaging to control motor noise + with harmonic matching of the first harmonic.""" + self.test_gyro_fft_harmonic(True) + + def GyroFFT(self): """Use dynamic harmonic notch to control motor noise.""" # basic gyro sample rate test self.progress("Flying with gyro FFT - Gyro sample rate") @@ -5239,7 +5575,7 @@ def fly_gyro_fft(self): "EK2_ENABLE": 0, "EK3_ENABLE": 0, "INS_LOG_BAT_MASK": 3, - "INS_LOG_BAT_OPT": 0, + "INS_LOG_BAT_OPT": 4, "INS_GYRO_FILTER": 100, "INS_FAST_SAMPLE": 0, "LOG_BITMASK": 958, @@ -5315,22 +5651,17 @@ def fly_gyro_fft(self): }) self.reboot_sitl() + # do test flight: self.takeoff(10, mode="ALT_HOLD") - hover_time = 15 - self.progress("Hovering for %u seconds" % hover_time) - tstart = self.get_sim_time() - while self.get_sim_time_cached() < tstart + hover_time: - self.mav.recv_match(type='ATTITUDE', blocking=True) - tend = self.get_sim_time() - + tstart, tend, hover_throttle = self.hover_for_interval(15) # fly fast forrest! self.set_rc(3, 1900) self.set_rc(2, 1200) self.wait_groundspeed(5, 1000) self.set_rc(3, 1500) self.set_rc(2, 1500) - self.do_RTL() + psd = self.mavfft_fttd(1, 0, tstart * 1.0e6, tend * 1.0e6) # batch sampler defaults give 1024 fft and sample rate of 1kz so roughly 1hz/bin @@ -5349,7 +5680,7 @@ def fly_gyro_fft(self): # we are limited to half the loop rate for frequency detection self.set_parameters({ "FFT_MAXHZ": 185, - "INS_LOG_BAT_OPT": 0, + "INS_LOG_BAT_OPT": 4, "SIM_VIB_MOT_MAX": 220, "FFT_WINDOW_SIZE": 64, "FFT_WINDOW_OLAP": 0.75, @@ -5357,15 +5688,155 @@ def fly_gyro_fft(self): }) self.reboot_sitl() + # do test flight: self.takeoff(10, mode="ALT_HOLD") + tstart, tend, hover_throttle = self.hover_for_interval(15) + self.do_RTL() - self.progress("Hovering for %u seconds" % hover_time) - tstart = self.get_sim_time() - while self.get_sim_time_cached() < tstart + hover_time: - self.mav.recv_match(type='ATTITUDE', blocking=True) - tend = self.get_sim_time() + # why are we not checking the results from that flight? -pb20220613 + + # prevent update parameters from messing with the settings + # when we pop the context + self.set_parameter("FFT_ENABLE", 0) + self.reboot_sitl() + + except Exception as e: + self.print_exception_caught(e) + ex = e + + self.context_pop() + + # must reboot after we move away from EKF type 10 to EKF2 or EKF3 + self.reboot_sitl() + + if ex is not None: + raise ex + + def GyroFFTAverage(self): + """Use dynamic harmonic notch to control motor noise setup via FFT averaging.""" + # basic gyro sample rate test + self.progress("Flying with gyro FFT harmonic - Gyro sample rate") + self.context_push() + ex = None + try: + # Step 1 + self.start_subtest("Hover to calculate approximate hover frequency and see that it is tracked") + # magic tridge EKF type that dramatically speeds up the test + self.set_parameters({ + "AHRS_EKF_TYPE": 10, + "EK2_ENABLE": 0, + "EK3_ENABLE": 0, + "INS_LOG_BAT_MASK": 3, + "INS_LOG_BAT_OPT": 2, + "INS_GYRO_FILTER": 100, + "INS_FAST_SAMPLE": 0, + "INS_HNTCH_ATT": 100, + "LOG_BITMASK": 958, + "LOG_DISARMED": 0, + "SIM_DRIFT_SPEED": 0, + "SIM_DRIFT_TIME": 0, + "SIM_GYR1_RND": 20, # enable a noisy gyro + }) + # motor peak enabling FFT will also enable the arming + # check, self-testing the functionality + self.set_parameters({ + "FFT_ENABLE": 1, + "FFT_WINDOW_SIZE": 64, # not the default, but makes the test more reliable + "FFT_SNR_REF": 10, + }) + + # Step 1: inject actual motor noise and use the FFT to track it + self.set_parameters({ + "SIM_VIB_MOT_MAX": 250, # gives a motor peak at about 175Hz + "RC7_OPTION" : 162, # FFT tune + }) + + self.reboot_sitl() + + # hover and engage FFT tracker + self.takeoff(10, mode="ALT_HOLD") + + hover_time = 60 + + # start the tune + self.set_rc(7, 2000) + + tstart, tend, hover_throttle = self.hover_for_interval(hover_time) + + # finish the tune + self.set_rc(7, 1000) + + psd = self.mavfft_fttd(1, 0, tstart * 1.0e6, tend * 1.0e6) + + # batch sampler defaults give 1024 fft and sample rate of 1kz so roughly 1hz/bin + freq = psd["F"][numpy.argmax(psd["X"][50:450]) + 50] * (1000. / 1024.) + + detected_ref = self.get_parameter("INS_HNTCH_REF") + detected_freq = self.get_parameter("INS_HNTCH_FREQ") + self.progress("FFT detected parameters were %fHz, ref %f" % (detected_freq, detected_ref)) + + # approximate the scaled frequency + scaled_freq_at_hover = math.sqrt((hover_throttle / 100.) / detected_ref) * detected_freq + + # Check we matched + if abs(scaled_freq_at_hover - freq) / scaled_freq_at_hover > 0.05: + raise NotAchievedException("Detected frequency %fHz did not match required %fHz" % + (scaled_freq_at_hover, freq)) + + if self.get_parameter("INS_HNTCH_ENABLE") != 1: + raise NotAchievedException("Harmonic notch was not enabled") + + # Step 2: now rerun the test and check that the peak is squashed + self.start_subtest("Verify that noise is suppressed by the harmonic notch") + self.hover_and_check_matched_frequency_with_fft(0, 100, 350, reverse=True, takeoff=False) + + # Step 3: add a second harmonic and check the first is still tracked + self.start_subtest("Add a fixed frequency harmonic at twice the hover frequency " + "and check the right harmonic is found") + self.set_parameters({ + "SIM_VIB_FREQ_X": freq * 2, + "SIM_VIB_FREQ_Y": freq * 2, + "SIM_VIB_FREQ_Z": freq * 2, + "SIM_VIB_MOT_MULT": 0.25, # halve the motor noise so that the higher harmonic dominates + }) + self.reboot_sitl() + + # hover and engage FFT tracker + self.takeoff(10, mode="ALT_HOLD") + + hover_time = 60 + + # start the tune + self.set_rc(7, 2000) + + tstart, tend, hover_throttle = self.hover_for_interval(hover_time) + + # finish the tune + self.set_rc(7, 1000) self.do_RTL() + + detected_ref = self.get_parameter("INS_HNTCH_REF") + detected_freq = self.get_parameter("INS_HNTCH_FREQ") + self.progress("FFT detected parameters were %fHz, ref %f" % (detected_freq, detected_ref)) + + # approximate the scaled frequency + scaled_freq_at_hover = math.sqrt((hover_throttle / 100.) / detected_ref) * detected_freq + + # Check we matched + if abs(scaled_freq_at_hover - freq) / scaled_freq_at_hover > 0.05: + raise NotAchievedException("Detected frequency %fHz did not match required %fHz" % + (scaled_freq_at_hover, freq)) + + if self.get_parameter("INS_HNTCH_ENABLE") != 1: + raise NotAchievedException("Harmonic notch was not enabled") + + self.set_parameters({ + "SIM_VIB_FREQ_X": 0, + "SIM_VIB_FREQ_Y": 0, + "SIM_VIB_FREQ_Z": 0, + "SIM_VIB_MOT_MULT": 1.0, + }) # prevent update parameters from messing with the settings when we pop the context self.set_parameter("FFT_ENABLE", 0) self.reboot_sitl() @@ -5376,13 +5847,15 @@ def fly_gyro_fft(self): self.context_pop() - # must reboot after we move away from EKF type 10 to EKF2 or EKF3 + # need a final reboot because weird things happen to your + # vehicle state when switching back from EKF type 10! self.reboot_sitl() if ex is not None: raise ex - def fly_brake_mode(self): + def BrakeMode(self): + '''Fly Brake Mode''' # test brake mode self.progress("Testing brake mode") self.takeoff(10, mode="LOITER") @@ -5430,7 +5903,8 @@ def fly_guided_move_to(self, destination, timeout=30): if delta < 1: break - def test_altitude_types(self): + def AltTypes(self): + '''Test Different Altitude Types''' '''start by disabling GCS failsafe, otherwise we immediately disarm due to (apparently) not receiving traffic from the GCS for too long. This is probably a function of --speedup''' @@ -5442,10 +5916,7 @@ def test_altitude_types(self): ''' - # we must start mavproxy here as otherwise we can't get the - # terrain database tiles - this leads to random failures in - # CI! - mavproxy = self.start_mavproxy() + self.install_terrain_handlers_context() self.set_parameter("FS_GCS_ENABLE", 0) self.change_mode('GUIDED') @@ -5506,43 +5977,30 @@ def test_altitude_types(self): self.wait_disarmed() - self.stop_mavproxy(mavproxy) - - def fly_precision_companion(self): + def PrecisionLoiterCompanion(self): """Use Companion PrecLand backend precision messages to loiter.""" self.context_push() ex = None try: - self.set_parameter("PLND_ENABLED", 1) - # enable companion backend: - self.set_parameter("PLND_TYPE", 1) - + self.set_parameters({ + "PLND_ENABLED": 1, + "PLND_TYPE": 1, # enable companion backend: + "RC7_OPTION": 39, # set up a channel switch to enable precision loiter: + }) self.set_analog_rangefinder_parameters() - - # set up a channel switch to enable precision loiter: - self.set_parameter("RC7_OPTION", 39) - self.reboot_sitl() self.progress("Waiting for location") - self.mav.location() - self.zero_throttle() - self.change_mode('STABILIZE') + self.change_mode('LOITER') self.wait_ready_to_arm() # we should be doing precision loiter at this point - start = self.mav.recv_match(type='LOCAL_POSITION_NED', - blocking=True) + start = self.assert_receive_message('LOCAL_POSITION_NED') + + self.takeoff(20, mode='ALT_HOLD') - self.arm_vehicle() - self.set_rc(3, 1800) - alt_min = 10 - self.wait_altitude(alt_min, - (alt_min + 5), - relative=True) - self.set_rc(3, 1500) # move away a little self.set_rc(2, 1550) self.wait_distance(5, accuracy=1) @@ -5550,18 +6008,21 @@ def fly_precision_companion(self): self.change_mode('LOITER') # turn precision loiter on: + self.context_collect('STATUSTEXT') self.set_rc(7, 2000) # try to drag aircraft to a position 5 metres north-east-east: - self.loiter_to_ne(start.x + 5, start.y + 10, start.z + 10) - self.loiter_to_ne(start.x + 5, start.y - 10, start.z + 10) + self.precision_loiter_to_pos(start.x + 5, start.y + 10, start.z + 10) + self.wait_statustext("PrecLand: Target Found", check_context=True, timeout=10) + self.wait_statustext("PrecLand: Init Complete", check_context=True, timeout=10) + # .... then northwest + self.precision_loiter_to_pos(start.x + 5, start.y - 10, start.z + 10) except Exception as e: self.print_exception_caught(e) ex = e self.context_pop() - self.zero_throttle() self.disarm_vehicle(force=True) self.reboot_sitl() self.progress("All done") @@ -5609,15 +6070,17 @@ def loiter_requires_position(self): self.context_pop() self.reboot_sitl() - def test_arm_feature(self): + def ArmFeatures(self): + '''Arm features''' self.loiter_requires_position() - super(AutoTestCopter, self).test_arm_feature() + super(AutoTestCopter, self).ArmFeatures() - def test_parameter_checks(self): + def ParameterChecks(self): + '''Test Arming Parameter Checks''' self.test_parameter_checks_poscontrol("PSC") - def fly_poshold_takeoff(self): + def PosHoldTakeOff(self): """ensure vehicle stays put until it is ready to fly""" self.context_push() @@ -5687,8 +6150,8 @@ def rc_defaults(self): ret[5] = 1800 # mode switch return ret - def test_manual_control(self): - '''test manual_control mavlink message''' + def MANUAL_CONTROL(self): + '''test MANUAL_CONTROL mavlink message''' self.set_parameter("SYSID_MYGCS", self.mav.source_system) self.change_mode('STABILIZE') @@ -5765,10 +6228,11 @@ def OBSTACLE_DISTANCE_3D_test_angle(self, angle): tstart = self.get_sim_time() last_send = 0 + m = None while True: now = self.get_sim_time_cached() - if now - tstart > 10: - raise NotAchievedException("Did not get correct angle back") + if now - tstart > 100: + raise NotAchievedException("Did not get correct angle back (last-message=%s)" % str(m)) if now - last_send > 0.1: self.progress("ang=%f sending front=%f right=%f" % @@ -5803,26 +6267,22 @@ def OBSTACLE_DISTANCE_3D_test_angle(self, angle): break def OBSTACLE_DISTANCE_3D(self): + '''Check round-trip behaviour of distance sensors''' self.context_push() - ex = None - try: - self.set_parameters({ - "SERIAL5_PROTOCOL": 1, - "PRX_TYPE": 2, - }) - self.reboot_sitl() + self.set_parameters({ + "SERIAL5_PROTOCOL": 1, + "PRX1_TYPE": 2, + "SIM_SPEEDUP": 8, # much GCS interaction + }) + self.reboot_sitl() + # need yaw estimate to stabilise: + self.wait_ekf_happy(require_absolute=True) - for angle in range(0, 360): - self.OBSTACLE_DISTANCE_3D_test_angle(angle) + for angle in range(0, 360): + self.OBSTACLE_DISTANCE_3D_test_angle(angle) - except Exception as e: - self.print_exception_caught(e) - ex = e self.context_pop() - self.disarm_vehicle(force=True) self.reboot_sitl() - if ex is not None: - raise ex def fly_proximity_avoidance_test_corners(self): self.start_subtest("Corners") @@ -5832,13 +6292,18 @@ def fly_proximity_avoidance_test_corners(self): self.load_fence("copter-avoidance-fence.txt") self.set_parameters({ "FENCE_ENABLE": 1, - "PRX_TYPE": 10, + "PRX1_TYPE": 10, + "PRX_LOG_RAW": 1, "RC10_OPTION": 40, # proximity-enable }) self.reboot_sitl() self.progress("Enabling proximity") self.set_rc(10, 2000) self.check_avoidance_corners() + + self.assert_current_onboard_log_contains_message("PRX") + self.assert_current_onboard_log_contains_message("PRXR") + except Exception as e: self.print_exception_caught(e) ex = e @@ -5895,7 +6360,7 @@ def ProximitySensors(self): home_string = "%s,%s,%s,%s" % (51.8752066, 14.6487840, 54.15, 0) for (name, prx_type, expected_distances) in sensors: self.start_subtest("Testing %s" % name) - self.set_parameter("PRX_TYPE", prx_type) + self.set_parameter("PRX1_TYPE", prx_type) self.customise_SITL_commandline([ "--uartF=sim:%s:" % name, "--home", home_string, @@ -5932,7 +6397,7 @@ def fly_proximity_avoidance_test_alt_no_avoid(self): ex = None try: self.set_parameters({ - "PRX_TYPE": 2, + "PRX1_TYPE": 2, "AVOID_ALT_MIN": 10, }) self.set_analog_rangefinder_parameters() @@ -6005,11 +6470,13 @@ def shove(a, b): if ex is not None: raise ex - def fly_proximity_avoidance_test(self): + def AC_Avoidance_Proximity(self): + '''Test proximity avoidance slide behaviour''' self.fly_proximity_avoidance_test_alt_no_avoid() self.fly_proximity_avoidance_test_corners() - def fly_fence_avoidance_test(self): + def AC_Avoidance_Fence(self): + '''Test fence avoidance slide behaviour''' self.context_push() ex = None try: @@ -6038,7 +6505,8 @@ def global_position_int_for_location(self, loc, time_boot, heading=0): hdg=heading ) - def fly_follow_mode(self): + def ModeFollow(self): + '''Fly follow mode''' foll_ofs_x = 30 # metres self.set_parameters({ "FOLL_ENABLE": 1, @@ -6099,7 +6567,8 @@ def get_global_position_int(self, timeout=30): if m.lat != 0 or m.lon != 0: return m - def fly_beacon_position(self): + def BeaconPosition(self): + '''Fly Beacon Position''' self.reboot_sitl() self.wait_ready_to_arm(require_absolute=True) @@ -6177,6 +6646,8 @@ def fly_beacon_position(self): self.wait_groundspeed(0, 0.3, timeout=120) self.land_and_disarm() + self.assert_current_onboard_log_contains_message("BCN") + except Exception as e: self.print_exception_caught(e) ex = e @@ -6187,7 +6658,8 @@ def fly_beacon_position(self): if ex is not None: raise ex - def fly_beacon_avoidance_test(self): + def AC_Avoidance_Beacon(self): + '''Test beacon avoidance slide behaviour''' self.context_push() ex = None try: @@ -6228,7 +6700,8 @@ def fly_beacon_avoidance_test(self): if ex is not None: raise ex - def fly_wind_baro_compensation(self): + def BaroWindCorrection(self): + '''Test wind estimation and baro position error compensation''' self.context_push() ex = None try: @@ -6247,9 +6720,6 @@ def fly_wind_baro_compensation(self): }) self.reboot_sitl() self.set_parameters({ - "EK3_DRAG_BCOEF_X": 361.000000, - "EK3_DRAG_BCOEF_Y": 361.000000, - "EK3_DRAG_MCOEF": 0.082000, "BARO1_WCF_FWD": -0.300000, "BARO1_WCF_BCK": -0.300000, "BARO1_WCF_RGT": 0.300000, @@ -6312,7 +6782,6 @@ def fly_wind_baro_compensation(self): raise ex def wait_generator_speed_and_state(self, rpm_min, rpm_max, want_state, timeout=240): - self.drain_mav() tstart = self.get_sim_time() while True: if self.get_sim_time_cached() - tstart > timeout: @@ -6331,7 +6800,8 @@ def wait_generator_speed_and_state(self, rpm_min, rpm_max, want_state, timeout=2 break self.progress("Got generator speed and state") - def test_richenpower(self): + def RichenPower(self): + '''Test RichenPower generator''' self.set_parameters({ "SERIAL5_PROTOCOL": 30, "SIM_RICH_ENABLE": 1, @@ -6348,23 +6818,12 @@ def test_richenpower(self): self.wait_statustext("requested state is not RUN", timeout=60) self.set_message_rate_hz("GENERATOR_STATUS", 10) - self.drain_mav_unparsed() self.wait_generator_speed_and_state(0, 0, mavutil.mavlink.MAV_GENERATOR_STATUS_FLAG_OFF) - messages = [] - - def my_message_hook(mav, m): - if m.get_type() != 'STATUSTEXT': - return - messages.append(m) - self.install_message_hook(my_message_hook) - try: - self.set_rc(9, 2000) # remember this is a switch position - run - finally: - self.remove_message_hook(my_message_hook) - if "Generator HIGH" not in [x.text for x in messages]: - self.wait_statustext("Generator HIGH", timeout=60) + self.context_collect('STATUSTEXT') + self.set_rc(9, 2000) # remember this is a switch position - run + self.wait_statustext("Generator HIGH", check_context=True) self.set_rc(9, 1000) # remember this is a switch position - stop self.wait_statustext("requested state is not RUN", timeout=200) @@ -6402,7 +6861,8 @@ def my_message_hook(mav, m): if not self.current_onboard_log_contains_message("GEN"): raise NotAchievedException("Did not find expected GEN message") - def test_ie24(self): + def IE24(self): + '''Test IntelligentEnergy 2.4kWh generator''' self.context_push() ex = None try: @@ -6447,7 +6907,8 @@ def test_ie24(self): if ex is not None: raise ex - def test_aux_switch_options(self): + def AuxSwitchOptions(self): + '''Test random aux mode options''' self.set_parameter("RC7_OPTION", 58) # clear waypoints self.load_mission("copter_loiter_to_alt.txt") self.set_rc(7, 1000) @@ -6466,11 +6927,11 @@ def test_aux_switch_options(self): self.progress("Reset mission") self.set_rc(7, 2000) self.delay_sim_time(1) - self.drain_mav() self.wait_current_waypoint(0, timeout=10) self.set_rc(7, 1000) - def test_aux_functions_in_mission(self): + def AuxFunctionsInMission(self): + '''Test use of auxilliary functions in missions''' self.load_mission("aux_functions.txt") self.change_mode('LOITER') self.wait_ready_to_arm() @@ -6523,13 +6984,14 @@ def fly_rangefinder_drivers_fly(self, rangefinders): if not self.current_onboard_log_contains_message("RFND"): raise NotAchievedException("No RFND messages in log") - def fly_proximity_mavlink_distance_sensor(self): + def MAVProximity(self): + '''Test MAVLink proximity driver''' self.start_subtest("Test mavlink proximity sensor using DISTANCE_SENSOR messages") # noqa self.context_push() ex = None try: self.set_parameter("SERIAL5_PROTOCOL", 1) - self.set_parameter("PRX_TYPE", 2) # mavlink + self.set_parameter("PRX1_TYPE", 2) # mavlink self.reboot_sitl() self.progress("Should be unhealthy while we don't send messages") @@ -6625,7 +7087,13 @@ def my_message_hook(mav, m): def fly_rangefinder_mavlink_distance_sensor(self): self.start_subtest("Test mavlink rangefinder using DISTANCE_SENSOR messages") self.context_push() - self.set_parameter('RTL_ALT_TYPE', 0) + self.set_parameters({ + "RTL_ALT_TYPE": 0, + "LGR_ENABLE": 1, + "LGR_DEPLOY_ALT": 1, + "LGR_RETRACT_ALT": 10, # metres + "SERVO10_FUNCTION": 29 + }) ex = None try: self.set_parameter("SERIAL5_PROTOCOL", 1) @@ -6678,11 +7146,6 @@ def fly_rangefinder_mavlink_distance_sensor(self): 255 # covariance ) self.arm_vehicle() - self.set_parameters({ - "SERVO10_FUNCTION": 29, - "LGR_DEPLOY_ALT": 1, - "LGR_RETRACT_ALT": 10, # metres - }) self.delay_sim_time(1) # servo function maps only periodically updated # self.send_debug_trap() @@ -6750,7 +7213,7 @@ def fly_rangefinder_mavlink_distance_sensor(self): if ex is not None: raise ex - def test_gsf(self): + def GSF(self): '''test the Gaussian Sum filter''' ex = None self.context_push() @@ -6832,7 +7295,8 @@ def fly_rangefinder_mavlink(self): self.progress("mavlink rangefinder OK") self.land_and_disarm() - def fly_rangefinder_driver_maxbotix(self): + def MaxBotixI2CXL(self): + '''Test maxbotix rangefinder drivers''' ex = None try: self.context_push() @@ -6909,7 +7373,8 @@ def fly_rangefinder_driver_maxbotix(self): if ex is not None: raise ex - def fly_rangefinder_drivers(self): + def RangeFinderDrivers(self): + '''Test rangefinder drivers''' self.set_parameters({ "RTL_ALT": 500, "RTL_ALT_TYPE": 1, @@ -6929,6 +7394,7 @@ def fly_rangefinder_drivers(self): ("lanbao", 26), ("benewake_tf03", 27), ("gyus42v2", 31), + ("teraranger_serial", 35), ] while len(drivers): do_drivers = drivers[0:3] @@ -6971,7 +7437,7 @@ def fly_rangefinder_drivers(self): self.reboot_sitl() self.fly_rangefinder_drivers_fly([x[0] for x in do_drivers]) - def fly_rangefinder_drivers_maxalt(self): + def RangeFinderDriversMaxAlt(self): '''test max-height behaviour''' # lightwareserial goes to 130m when out of range self.set_parameters({ @@ -7002,7 +7468,8 @@ def fly_rangefinder_drivers_maxalt(self): self.do_RTL() - def fly_ship_takeoff(self): + def ShipTakeoff(self): + '''Fly Simulated Ship Takeoff''' # test ship takeoff self.wait_groundspeed(0, 2) self.set_parameters({ @@ -7020,7 +7487,8 @@ def fly_ship_takeoff(self): # ship will have moved on, so we land on the water which isn't moving self.wait_groundspeed(0, 2) - def test_parameter_validation(self): + def ParameterValidation(self): + '''Test parameters are checked for validity''' # wait 10 seconds for initialisation self.delay_sim_time(10) self.progress("invalid; min must be less than max:") @@ -7038,7 +7506,36 @@ def test_parameter_validation(self): self.drain_mav() self.assert_prearm_failure("Check MOT_PWM_MIN/MAX") - def test_alt_estimate_prearm(self): + def SensorErrorFlags(self): + '''Test we get ERR messages when sensors have issues''' + self.reboot_sitl() + + for (param_names, param_value, expected_subsys, expected_ecode, desc) in [ + (['SIM_BARO_DISABLE', 'SIM_BAR2_DISABLE'], 1, 18, 4, 'unhealthy'), + (['SIM_BARO_DISABLE', 'SIM_BAR2_DISABLE'], 0, 18, 0, 'healthy'), + (['SIM_MAG1_FAIL', 'SIM_MAG2_FAIL', 'SIM_MAG3_FAIL'], 1, 3, 4, 'unhealthy'), + (['SIM_MAG1_FAIL', 'SIM_MAG2_FAIL', 'SIM_MAG3_FAIL'], 0, 3, 0, 'healthy'), + ]: + sp = dict() + for name in param_names: + sp[name] = param_value + self.set_parameters(sp) + self.delay_sim_time(1) + mlog = self.dfreader_for_current_onboard_log() + success = False + while True: + m = mlog.recv_match(type='ERR') + print("Got (%s)" % str(m)) + if m is None: + break + if m.Subsys == expected_subsys and m.ECode == expected_ecode: # baro / ecode + success = True + break + if not success: + raise NotAchievedException("Did not find %s log message" % desc) + + def AltEstimation(self): + '''Test that Alt Estimation is mandatory for ALT_HOLD''' self.context_push() ex = None try: @@ -7047,6 +7544,7 @@ def test_alt_estimate_prearm(self): "SIM_BARO_DISABLE": 1, "SIM_BARO2_DISABL": 1, }) + self.wait_gps_disable(position_vertical=True) # turn off arming checks (mandatory arming checks will still be run) @@ -7079,7 +7577,8 @@ def test_alt_estimate_prearm(self): if ex is not None: raise ex - def test_ekf_source(self): + def EKFSource(self): + '''Check EKF Source Prearms work''' self.context_push() ex = None try: @@ -7144,6 +7643,8 @@ def test_replay_gps_bit(self): }) self.reboot_sitl() + self.wait_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_LOGGING, True, True, True) + current_log_filepath = self.current_onboard_log_filepath() self.progress("Current log path: %s" % str(current_log_filepath)) @@ -7164,7 +7665,7 @@ def test_replay_beacon_bit(self): }) old_onboard_logs = sorted(self.log_list()) - self.fly_beacon_position() + self.BeaconPosition() new_onboard_logs = sorted(self.log_list()) log_difference = [x for x in new_onboard_logs if x not in old_onboard_logs] @@ -7177,14 +7678,15 @@ def test_replay_optical_flow_bit(self): }) old_onboard_logs = sorted(self.log_list()) - self.fly_optical_flow_limits() + self.OpticalFlowLimits() new_onboard_logs = sorted(self.log_list()) log_difference = [x for x in new_onboard_logs if x not in old_onboard_logs] print("log difference: %s" % str(log_difference)) return log_difference[0] - def test_gps_blending(self): + def GPSBlending(self): + '''Test GPS Blending''' '''ensure we get dataflash log messages for blended instance''' self.context_push() @@ -7258,7 +7760,8 @@ def test_gps_blending(self): if ex is not None: raise ex - def test_callisto(self): + def Callisto(self): + '''Test Callisto''' self.customise_SITL_commandline( ["--defaults", ','.join(self.model_defaults_filepath('Callisto')), ], model="octa-quad:@ROMFS/models/Callisto.json", @@ -7267,7 +7770,8 @@ def test_callisto(self): self.takeoff(10) self.do_RTL() - def fly_each_frame(self): + def FlyEachFrame(self): + '''Fly each supported internal frame''' vinfo = vehicleinfo.VehicleInfo() copter_vinfo_options = vinfo.options[self.vehicleinfo_key()] known_broken_frames = { @@ -7337,7 +7841,7 @@ def verify_rollpitch(mav, m): self.do_RTL() - def test_replay(self): + def Replay(self): '''test replay correctness''' self.progress("Building Replay") util.build_SITL('tool/Replay', clean=False, configure=False) @@ -7356,7 +7860,9 @@ def test_replay_bit(self, bit): self.context_push() current_log_filepath = bit() - self.progress("Running replay on (%s)" % current_log_filepath) + self.progress("Running replay on (%s) (%u bytes)" % ( + (current_log_filepath, os.path.getsize(current_log_filepath)) + )) util.run_cmd( ['build/sitl/tool/Replay', current_log_filepath], @@ -7378,6 +7884,7 @@ def test_replay_bit(self, bit): raise NotAchievedException("check_replay failed") def DefaultIntervalsFromFiles(self): + '''Test setting default mavlink message intervals from files''' ex = None intervals_filepath = util.reltopdir("message-intervals-chan0.txt") self.progress("Using filepath (%s)" % intervals_filepath) @@ -7387,6 +7894,7 @@ def DefaultIntervalsFromFiles(self): 28 100 29 200 """) + f.close() # other tests may have explicitly set rates, so wipe parameters: def custom_stream_rate_setter(): @@ -7414,6 +7922,7 @@ def custom_stream_rate_setter(): raise ex def BaroDrivers(self): + '''Test Baro Drivers''' sensors = [ ("MS5611", 2), ] @@ -7468,7 +7977,8 @@ def check_pressure(mav, m): self.context_pop() self.reboot_sitl() - def test_copter_gps_zero(self): + def PositionWhenGPSIsZero(self): + '''Ensure position doesn't zero when GPS lost''' # https://github.com/ArduPilot/ardupilot/issues/14236 self.progress("arm the vehicle and takeoff in Guided") self.takeoff(20, mode='GUIDED') @@ -7490,7 +8000,8 @@ def test_copter_gps_zero(self): self.wait_disarmed() self.reboot_sitl() - def test_SMART_RTL(self): + def SMART_RTL(self): + '''Check SMART_RTL''' self.context_push() ex = None try: @@ -7568,7 +8079,7 @@ def get_touchdownexpected_durations_from_current_onboard_log(self, ignore_multi= return self.get_ground_effect_duration_from_current_onboard_log(12, ignore_multi=ignore_multi) def ThrowDoubleDrop(self): - # test boomerang mode: + '''Test a more complicated drop-mode scenario''' self.progress("Getting a lift to altitude") self.set_parameters({ "SIM_SHOVE_Z": -11, @@ -7622,6 +8133,7 @@ def ThrowDoubleDrop(self): self.wait_disarmed(timeout=240) def GroundEffectCompensation_takeOffExpected(self): + '''Test EKF's handling of takeoff-expected''' self.change_mode('ALT_HOLD') self.set_parameter("LOG_FILE_DSRMROT", 1) self.progress("Making sure we'll have a short log to look at") @@ -7725,10 +8237,12 @@ def MAV_CMD_CONDITION_YAW_relative(self): pass def MAV_CMD_CONDITION_YAW(self): + '''Test response to MAV_CMD_CONDITION_YAW''' self.MAV_CMD_CONDITION_YAW_absolute() self.MAV_CMD_CONDITION_YAW_relative() def GroundEffectCompensation_touchDownExpected(self): + '''Test EKF's handling of touchdown-expected''' self.zero_throttle() self.change_mode('ALT_HOLD') self.set_parameter("LOG_FILE_DSRMROT", 1) @@ -7764,6 +8278,7 @@ def upload_square_mission_items_around_location(self, loc): self.upload_simple_relhome_mission(items) def RefindGPS(self): + '''Refind the GPS and attempt to RTL rather than continue to land''' # https://github.com/ArduPilot/ardupilot/issues/14236 self.progress("arm the vehicle and takeoff in Guided") self.takeoff(20, mode='GUIDED') @@ -7786,6 +8301,7 @@ def RefindGPS(self): self.do_RTL() def GPSForYaw(self): + '''Moving baseline GPS yaw''' self.context_push() self.load_default_params_file("copter-gps-for-yaw.parm") self.reboot_sitl() @@ -7810,6 +8326,7 @@ def GPSForYaw(self): raise ex def AP_Avoidance(self): + '''ADSB-based avoidance''' self.set_parameters({ "AVD_ENABLE": 1, "ADSB_TYPE": 1, # mavlink @@ -7850,41 +8367,178 @@ def AP_Avoidance(self): self.context_pop() def PAUSE_CONTINUE(self): - self.load_mission("copter_mission.txt", strict=False) + '''Test MAV_CMD_DO_PAUSE_CONTINUE in AUTO mode''' + self.load_mission(filename="copter_mission.txt", strict=False) + self.set_parameter(name="AUTO_OPTIONS", value=3) + self.change_mode(mode="AUTO") + self.wait_ready_to_arm() + self.arm_vehicle() - self.set_parameter("AUTO_OPTIONS", 3) - self.change_mode('AUTO') + self.wait_current_waypoint(wpnum=3, timeout=500) + self.send_pause_command() + self.wait_groundspeed(speed_min=0, speed_max=1, minimum_duration=5) + self.send_resume_command() + + self.wait_current_waypoint(wpnum=4, timeout=500) + self.send_pause_command() + self.wait_groundspeed(speed_min=0, speed_max=1, minimum_duration=5) + self.send_resume_command() + + self.wait_disarmed(timeout=500) + + def PAUSE_CONTINUE_GUIDED(self): + '''Test MAV_CMD_DO_PAUSE_CONTINUE in GUIDED mode''' + self.start_subtest("Started test for Pause/Continue in GUIDED mode with LOCATION!") + self.change_mode(mode="GUIDED") self.wait_ready_to_arm() self.arm_vehicle() + self.set_parameter(name="GUID_TIMEOUT", value=120) + self.user_takeoff(alt_min=30) - self.wait_waypoint(4, 4) - self.run_cmd(mavutil.mavlink.MAV_CMD_DO_PAUSE_CONTINUE, - 0, # param1 - 0, # param2 - 0, # param3 - 0, # param4 - 0, # param5 - 0, # param6 - 0 # param7 - ) + # send vehicle to global position target + location = self.home_relative_loc_ne(n=300, e=0) + target_typemask = MAV_POS_TARGET_TYPE_MASK.POS_ONLY + self.mav.mav.set_position_target_global_int_send( + 0, # timestamp + 1, # target system_id + 1, # target component id + mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, # relative altitude frame + target_typemask | MAV_POS_TARGET_TYPE_MASK.LAST_BYTE, # target typemask as pos only + int(location.lat * 1e7), # lat + int(location.lng * 1e7), # lon + 30, # alt + 0, # vx + 0, # vy + 0, # vz + 0, # afx + 0, # afy + 0, # afz + 0, # yaw + 0) # yawrate - self.wait_groundspeed(0, 1, minimum_duration=5) + self.wait_distance_to_home(distance_min=100, distance_max=150, timeout=120) + self.send_pause_command() + self.wait_groundspeed(speed_min=0, speed_max=1, minimum_duration=5) + self.send_resume_command() + self.wait_location(loc=location, timeout=120) - self.run_cmd(mavutil.mavlink.MAV_CMD_DO_PAUSE_CONTINUE, - 1, # param1 - 0, # param2 - 0, # param3 - 0, # param4 - 0, # param5 - 0, # param6 - 0 # param7 - ) + self.end_subtest("Ended test for Pause/Continue in GUIDED mode with LOCATION!") + self.start_subtest("Started test for Pause/Continue in GUIDED mode with DESTINATION!") + self.guided_achieve_heading(heading=270) + + # move vehicle on x direction + location = self.offset_location_ne(location=self.mav.location(), metres_north=0, metres_east=-300) + self.mav.mav.set_position_target_global_int_send( + 0, # system time in milliseconds + 1, # target system + 1, # target component + mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, # coordinate frame MAV_FRAME_BODY_NED + MAV_POS_TARGET_TYPE_MASK.POS_ONLY, # type mask (pos only) + int(location.lat*1e7), # position x + int(location.lng*1e7), # position y + 30, # position z + 0, # velocity x + 0, # velocity y + 0, # velocity z + 0, # accel x + 0, # accel y + 0, # accel z + 0, # yaw + 0) # yaw rate + + self.wait_location(loc=location, accuracy=200, timeout=120) + self.send_pause_command() + self.wait_groundspeed(speed_min=0, speed_max=1, minimum_duration=5) + self.send_resume_command() + self.wait_location(loc=location, timeout=120) + + self.end_subtest("Ended test for Pause/Continue in GUIDED mode with DESTINATION!") + self.start_subtest("Started test for Pause/Continue in GUIDED mode with VELOCITY!") + + # give velocity command + vx, vy, vz_up = (5, 5, 0) + self.test_guided_local_velocity_target(vx=vx, vy=vy, vz_up=vz_up, timeout=10) + + self.wait_for_local_velocity(vx=vx, vy=vy, vz_up=vz_up, timeout=10) + self.send_pause_command() + self.wait_for_local_velocity(vx=0, vy=0, vz_up=0, timeout=10) + self.send_resume_command() + self.wait_for_local_velocity(vx=vx, vy=vy, vz_up=vz_up, timeout=10) + self.test_guided_local_velocity_target(vx=0, vy=0, vz_up=0, timeout=10) + self.wait_for_local_velocity(vx=0, vy=0, vz_up=0, timeout=10) + + self.end_subtest("Ended test for Pause/Continue in GUIDED mode with VELOCITY!") + self.start_subtest("Started test for Pause/Continue in GUIDED mode with ACCELERATION!") + + # give acceleration command + ax, ay, az_up = (1, 1, 0) + target_typemask = (MAV_POS_TARGET_TYPE_MASK.POS_IGNORE | MAV_POS_TARGET_TYPE_MASK.VEL_IGNORE | + MAV_POS_TARGET_TYPE_MASK.YAW_IGNORE | MAV_POS_TARGET_TYPE_MASK.YAW_RATE_IGNORE) + self.mav.mav.set_position_target_local_ned_send( + 0, # timestamp + 1, # target system_id + 1, # target component id + mavutil.mavlink.MAV_FRAME_LOCAL_NED, + target_typemask | MAV_POS_TARGET_TYPE_MASK.LAST_BYTE, + 0, # x + 0, # y + 0, # z + 0, # vx + 0, # vy + 0, # vz + ax, # afx + ay, # afy + -az_up, # afz + 0, # yaw + 0, # yawrate + ) + + self.wait_for_local_velocity(vx=5, vy=5, vz_up=0, timeout=10) + self.send_pause_command() + self.wait_for_local_velocity(vx=0, vy=0, vz_up=0, timeout=10) + self.send_resume_command() + self.wait_for_local_velocity(vx=5, vy=5, vz_up=0, timeout=10) + self.test_guided_local_velocity_target(vx=0, vy=0, vz_up=0, timeout=10) + self.wait_for_local_velocity(vx=0, vy=0, vz_up=0, timeout=10) + self.end_subtest("Ended test for Pause/Continue in GUIDED mode with ACCELERATION!") + + # start pause/continue subtest with posvelaccel + self.start_subtest("Started test for Pause/Continue in GUIDED mode with POSITION and VELOCITY and ACCELERATION!") + self.guided_achieve_heading(heading=0) + + # give posvelaccel command + x, y, z_up = (-300, 0, 30) + target_typemask = (MAV_POS_TARGET_TYPE_MASK.YAW_IGNORE | MAV_POS_TARGET_TYPE_MASK.YAW_RATE_IGNORE) + self.mav.mav.set_position_target_local_ned_send( + 0, # timestamp + 1, # target system_id + 1, # target component id + mavutil.mavlink.MAV_FRAME_LOCAL_NED, + target_typemask | MAV_POS_TARGET_TYPE_MASK.LAST_BYTE, + x, # x + y, # y + -z_up, # z + 0, # vx + 0, # vy + 0, # vz + 0, # afx + 0, # afy + 0, # afz + 0, # yaw + 0, # yawrate + ) - self.wait_groundspeed(5, 100) + self.wait_distance_to_local_position(local_position=(x, y, -z_up), distance_min=400, distance_max=450, timeout=120) + self.send_pause_command() + self.wait_for_local_velocity(0, 0, 0, timeout=10) + self.send_resume_command() + self.wait_distance_to_local_position(local_position=(x, y, -z_up), distance_min=0, distance_max=10, timeout=120) - self.wait_disarmed() + self.end_subtest("Ended test for Pause/Continue in GUIDED mode with POSITION and VELOCITY and ACCELERATION!") + self.do_RTL(timeout=120) def DO_CHANGE_SPEED(self): + '''Change speed during misison using waypoint items''' self.load_mission("mission.txt", strict=False) self.set_parameters({ @@ -7920,15 +8574,88 @@ def DO_CHANGE_SPEED(self): self.wait_disarmed() - # a wrapper around all the 1A,1B,1C..etc tests for travis - def tests1(self): - ret = ([]) - ret.extend(self.tests1a()) - ret.extend(self.tests1b()) - ret.extend(self.tests1c()) - ret.extend(self.tests1d()) - ret.extend(self.tests1e()) - return ret + def AUTO_LAND_TO_BRAKE(self): + '''ensure terrain altitude is taken into account when braking''' + self.load_mission('mission.txt') + home_loc = self.get_home_tuple_from_mission("mission.txt") + + self.set_parameters({ + "PLND_ACC_P_NSE": 2.500000, + "PLND_ALT_MAX": 8.000000, + "PLND_ALT_MIN": 0.750000, + "PLND_BUS": -1, + "PLND_CAM_POS_X": 0.000000, + "PLND_CAM_POS_Y": 0.000000, + "PLND_CAM_POS_Z": 0.000000, + "PLND_ENABLED": 1, + "PLND_EST_TYPE": 1, + "PLND_LAG": 0.020000, + "PLND_LAND_OFS_X": 0.000000, + "PLND_LAND_OFS_Y": 0.000000, + "PLND_OPTIONS": 0, + "PLND_RET_BEHAVE": 0, + "PLND_RET_MAX": 4, + "PLND_STRICT": 1, + "PLND_TIMEOUT": 4.000000, + "PLND_TYPE": 4, + "PLND_XY_DIST_MAX": 2.500000, + "PLND_YAW_ALIGN": 0.000000, + + "SIM_PLD_ALT_LMT": 15.000000, + "SIM_PLD_DIST_LMT": 10.000000, + "SIM_PLD_ENABLE": 1, + "SIM_PLD_HEIGHT": 942.0000000, + "SIM_PLD_LAT": -20.558929, + "SIM_PLD_LON": -47.415035, + "SIM_PLD_RATE": 100, + "SIM_PLD_TYPE": 1, + "SIM_PLD_YAW": 87, + + "SIM_SONAR_SCALE": 12, + }) + + self.set_analog_rangefinder_parameters() + + self.customise_SITL_commandline([ + "--home", "%s,%s,%s,%s" % home_loc + ]) + + self.set_parameter('AUTO_OPTIONS', 3) + self.change_mode('AUTO') + self.wait_ready_to_arm() + self.arm_vehicle() + + self.wait_current_waypoint(7) + self.wait_altitude(10, 15, relative=True, timeout=60) + self.change_mode('BRAKE') + # monitor altitude here + self.wait_altitude(10, 15, relative=True, minimum_duration=20) + self.change_mode('AUTO') + self.wait_disarmed() + + def MAVLandedStateTakeoff(self): + '''check EXTENDED_SYS_STATE message''' + ex = None + try: + self.set_message_rate_hz(id=mavutil.mavlink.MAVLINK_MSG_ID_EXTENDED_SYS_STATE, rate_hz=1) + self.wait_extended_sys_state(vtol_state=mavutil.mavlink.MAV_VTOL_STATE_MC, + landed_state=mavutil.mavlink.MAV_LANDED_STATE_ON_GROUND, timeout=10) + self.load_mission(filename="copter_mission.txt") + self.set_parameter(name="AUTO_OPTIONS", value=3) + self.change_mode(mode="AUTO") + self.wait_ready_to_arm() + self.arm_vehicle() + self.wait_extended_sys_state(vtol_state=mavutil.mavlink.MAV_VTOL_STATE_MC, + landed_state=mavutil.mavlink.MAV_LANDED_STATE_TAKEOFF, timeout=30) + self.wait_extended_sys_state(vtol_state=mavutil.mavlink.MAV_VTOL_STATE_MC, + landed_state=mavutil.mavlink.MAV_LANDED_STATE_IN_AIR, timeout=60) + self.land_and_disarm() + except Exception as e: + self.print_exception_caught(e) + ex = e + self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_EXTENDED_SYS_STATE, -1) + if ex is not None: + raise ex def ATTITUDE_FAST(self): '''ensure that when ATTITDE_FAST is set we get many messages''' @@ -8067,12 +8794,13 @@ def FETtecESC_safety_switch(self): def FETtecESC_btw_mask_checks(self): '''ensure prearm checks work as expected''' - for bad_mask in [0b1000000000000, 0b10100000000000]: + for bad_mask in [0b1000000000000000, 0b10100000000000000]: self.fettec_assert_bad_mask(bad_mask) for good_mask in [0b00001, 0b00101, 0b110000000000]: self.fettec_assert_good_mask(good_mask) def FETtecESC(self): + '''Test FETtecESC''' self.set_parameters({ "SERIAL5_PROTOCOL": 38, "SERVO_FTW_MASK": 0b11101000, @@ -8093,586 +8821,279 @@ def FETtecESC(self): self.FETtecESC_flight() def PerfInfo(self): + '''Test Scheduler PerfInfo output''' self.set_parameter('SCHED_OPTIONS', 1) # enable gathering # sometimes we need to trigger collection.... content = self.fetch_file_via_ftp("@SYS/tasks.txt") self.delay_sim_time(5) content = self.fetch_file_via_ftp("@SYS/tasks.txt") self.progress("Got content (%s)" % str(content)) - if "fast_loop" not in content: - raise NotAchievedException("Did not find fast_loop in content") lines = content.split("\n") if not lines[0].startswith("TasksV2"): raise NotAchievedException("Expected TasksV2 as first line first not (%s)" % lines[0]) - if not lines[1].startswith("fast_loop"): - raise NotAchievedException("Expected fast_loop first, not (%s)" % lines[1]) # last line is empty, so -2 here - if not lines[-2].startswith("AP_EFI::update"): + if not lines[-2].startswith("AP_Vehicle::update_arming"): raise NotAchievedException("Expected EFI last not (%s)" % lines[-2]) + def RTL_TO_RALLY(self, target_system=1, target_component=1): + '''Check RTL to rally point''' + self.wait_ready_to_arm() + rally_loc = self.home_relative_loc_ne(50, -25) + rally_alt = 37 + items = [ + self.mav.mav.mission_item_int_encode( + target_system, + target_component, + 0, # seq + mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, + mavutil.mavlink.MAV_CMD_NAV_RALLY_POINT, + 0, # current + 0, # autocontinue + 0, # p1 + 0, # p2 + 0, # p3 + 0, # p4 + int(rally_loc.lat * 1e7), # latitude + int(rally_loc.lng * 1e7), # longitude + rally_alt, # altitude + mavutil.mavlink.MAV_MISSION_TYPE_RALLY), + ] + self.upload_using_mission_protocol( + mavutil.mavlink.MAV_MISSION_TYPE_RALLY, + items + ) + self.set_parameters({ + 'RALLY_INCL_HOME': 0, + }) + self.takeoff(10) + self.change_mode('RTL') + self.wait_location(rally_loc) + self.assert_altitude(rally_alt, relative=True) + self.progress("Ensuring we're descending") + self.wait_altitude(20, 25, relative=True) + self.change_mode('LOITER') + self.progress("Flying home") + self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_RALLY) + self.change_mode('RTL') + self.wait_disarmed() + self.assert_at_home() + + def NoRCOnBootPreArmFailure(self): + '''Ensure we can't arm with no RC on boot if THR_FS_VALUE set''' + self.context_push() + for rc_failure_mode in 1, 2: + self.set_parameters({ + "SIM_RC_FAIL": rc_failure_mode, + }) + self.reboot_sitl() + self.assert_prearm_failure("Throttle below failsafe", + other_prearm_failures_fatal=False) + self.context_pop() + self.reboot_sitl() + def tests1a(self): '''return list of all tests''' ret = super(AutoTestCopter, self).tests() # about 5 mins and ~20 initial tests from autotest/common.py ret.extend([ - ("NavDelayTakeoffAbsTime", - "Fly Nav Delay (takeoff)", - self.fly_nav_takeoff_delay_abstime), # 19s - - ("NavDelayAbsTime", - "Fly Nav Delay (AbsTime)", - self.fly_nav_delay_abstime), # 20s - - ("NavDelay", - "Fly Nav Delay", - self.fly_nav_delay), # 19s - - ("GuidedSubModeChange", - "Test submode change", - self.fly_guided_change_submode), - - ("MAV_CMD_CONDITION_YAW", - "Test response to MAV_CMD_CONDITION_YAW", - self.MAV_CMD_CONDITION_YAW), - - ("LoiterToAlt", - "Loiter-To-Alt", - self.fly_loiter_to_alt), # 25s - - ("PayLoadPlaceMission", - "Payload Place Mission", - self.fly_payload_place_mission), # 44s - - ("PrecisionLoiterCompanion", - "Precision Loiter (Companion)", - self.fly_precision_companion), # 29s - - ("PrecisionLandingSITL", - "Precision Landing drivers (SITL)", - self.fly_precision_landing_drivers), # 29s - - ("SetModesViaModeSwitch", - "Set modes via modeswitch", - self.test_setting_modes_via_modeswitch), - - ("SetModesViaAuxSwitch", - "Set modes via auxswitch", - self.test_setting_modes_via_auxswitch), - - ("AuxSwitchOptions", - "Test random aux mode options", - self.test_aux_switch_options), - - ("AuxFunctionsInMission", - "Test use of auxilliary functions in missions", - self.test_aux_functions_in_mission), - - ("AutoTune", - "Fly AUTOTUNE mode", - self.fly_autotune), # 73s + self.NavDelayTakeoffAbsTime, + self.NavDelayAbsTime, + self.NavDelay, + self.GuidedSubModeChange, + self.MAV_CMD_CONDITION_YAW, + self.LoiterToAlt, + self.PayLoadPlaceMission, + self.PrecisionLoiterCompanion, + self.Landing, + self.PrecisionLanding, + self.SetModesViaModeSwitch, + self.SetModesViaAuxSwitch, + self.AuxSwitchOptions, + self.AuxFunctionsInMission, + self.AutoTune, + self.NoRCOnBootPreArmFailure, ]) return ret def tests1b(self): '''return list of all tests''' ret = ([ - ("ThrowMode", "Fly Throw Mode", self.fly_throw_mode), - - ("BrakeMode", "Fly Brake Mode", self.fly_brake_mode), - - ("RecordThenPlayMission", - "Use switches to toggle in mission, then fly it", - self.fly_square), # 27s - - ("ThrottleFailsafe", - "Test Throttle Failsafe", - self.fly_throttle_failsafe), # 173s - - ("GCSFailsafe", - "Test GCS Failsafe", - self.fly_gcs_failsafe), # 239s - - # this group has the smallest runtime right now at around - # 5mins, so add more tests here, till its around - # 9-10mins, then make a new group + self.ThrowMode, + self.BrakeMode, + self.RecordThenPlayMission, + self.ThrottleFailsafe, + self.GCSFailsafe, + self.CustomController, ]) return ret def tests1c(self): '''return list of all tests''' ret = ([ - ("BatteryFailsafe", - "Fly Battery Failsafe", - self.fly_battery_failsafe), # 164s - - ("VibrationFailsafe", - "Test Vibration Failsafe", - self.test_vibration_failsafe), - - ("StabilityPatch", - "Fly stability patch", - lambda: self.fly_stability_patch(30)), # 17s - - ("OBSTACLE_DISTANCE_3D", - "Test proximity avoidance slide behaviour in 3D", - self.OBSTACLE_DISTANCE_3D), # ??s - - ("AC_Avoidance_Proximity", - "Test proximity avoidance slide behaviour", - self.fly_proximity_avoidance_test), # 41s - - ("AC_Avoidance_Fence", - "Test fence avoidance slide behaviour", - self.fly_fence_avoidance_test), - - ("AC_Avoidance_Beacon", - "Test beacon avoidance slide behaviour", - self.fly_beacon_avoidance_test), # 28s - - ("BaroWindCorrection", - "Test wind estimation and baro position error compensation", - self.fly_wind_baro_compensation), - - ("SetpointGlobalPos", - "Test setpoint global position", - self.test_set_position_global_int), - - ("ThrowDoubleDrop", - "Test a more complicated drop-mode scenario", - self.ThrowDoubleDrop), - - ("SetpointGlobalVel", - "Test setpoint global velocity", - self.test_set_velocity_global_int), - - ("SplineTerrain", - "Test Splines and Terrain", - self.test_terrain_spline_mission), - + self.BatteryFailsafe, + self.VibrationFailsafe, + self.EK3AccelBias, + self.StabilityPatch, + self.OBSTACLE_DISTANCE_3D, + self.AC_Avoidance_Proximity, + self.AC_Avoidance_Fence, + self.AC_Avoidance_Beacon, + self.BaroWindCorrection, + self.SetpointGlobalPos, + self.ThrowDoubleDrop, + self.SetpointGlobalVel, + self.SplineTerrain, + self.TakeoffCheck, ]) return ret def tests1d(self): '''return list of all tests''' ret = ([ - ("HorizontalFence", - "Test horizontal fence", - self.fly_fence_test), # 20s - - ("HorizontalAvoidFence", - "Test horizontal Avoidance fence", - self.fly_fence_avoid_test), - - ("MaxAltFence", - "Test Max Alt Fence", - self.fly_alt_max_fence_test), # 26s - - ("MinAltFence", - "Test Min Alt Fence", - self.fly_alt_min_fence_test), # 26s - - ("FenceFloorEnabledLanding", - "Test Landing with Fence floor enabled", - self.fly_fence_floor_enabled_landing), - - ("AutoTuneSwitch", - "Fly AUTOTUNE on a switch", - self.fly_autotune_switch), # 105s - - ("GPSGlitchLoiter", - "GPS Glitch Loiter Test", - self.fly_gps_glitch_loiter_test), # 30s - - ("GPSGlitchLoiter2", - "GPS Glitch Loiter Test2", - self.fly_gps_glitch_loiter_test2), # 30s - - ("GPSGlitchAuto", - "GPS Glitch Auto Test", - self.fly_gps_glitch_auto_test), - - ("ModeAltHold", - "Test AltHold Mode", - self.test_mode_ALT_HOLD), - - ("ModeLoiter", - "Test Loiter Mode", - self.loiter), - - ("SimpleMode", - "Fly in SIMPLE mode", - self.fly_simple), - - ("SuperSimpleCircle", - "Fly a circle in SUPER SIMPLE mode", - self.fly_super_simple), # 38s - - ("ModeCircle", - "Fly CIRCLE mode", - self.fly_circle), # 27s - - ("MagFail", - "Test magnetometer failure", - self.test_mag_fail), - - ("OpticalFlow", - "Test Optical Flow", - self.optical_flow), - - ("OpticalFlowLimits", - "Fly Optical Flow limits", - self.fly_optical_flow_limits), # 27s - - ("OpticalFlowCalibration", - "Fly Optical Flow calibration", - self.fly_optical_flow_calibration), - - ("MotorFail", - "Fly motor failure test", - self.fly_motor_fail), - - ("Flip", - "Fly Flip Mode", - self.fly_flip), - - ("CopterMission", - "Fly copter mission", - self.fly_auto_test), # 37s - - ("TakeoffAlt", - "Test Takeoff command altitude", - self.test_takeoff_alt), # 12s - - ("SplineLastWaypoint", - "Test Spline as last waypoint", - self.test_spline_last_waypoint), - - ("Gripper", - "Test gripper", - self.test_gripper), # 28s - - ("TestGripperMission", - "Test Gripper mission items", - self.test_gripper_mission), - - ("VisionPosition", - "Fly Vision Position", - self.fly_vision_position), # 24s - - ("ATTITUDE_FAST", - "Ensure ATTITUTDE_FAST logging works", - self.ATTITUDE_FAST), - - ("BaseLoggingRates", - "Ensure base logging rates as expected", - self.BaseLoggingRates), - - ("BodyFrameOdom", - "Fly Body Frame Odometry Code", - self.fly_body_frame_odom), # 24s - - ("GPSViconSwitching", - "Fly GPS and Vicon Switching", - self.fly_gps_vicon_switching), + self.HorizontalFence, + self.HorizontalAvoidFence, + self.MaxAltFence, + self.MinAltFence, + self.FenceFloorEnabledLanding, + self.AutoTuneSwitch, + self.GPSGlitchLoiter, + self.GPSGlitchLoiter2, + self.GPSGlitchAuto, + self.ModeAltHold, + self.ModeLoiter, + self.SimpleMode, + self.SuperSimpleCircle, + self.ModeCircle, + self.MagFail, + self.OpticalFlow, + self.OpticalFlowLimits, + self.OpticalFlowCalibration, + self.MotorFail, + self.ModeFlip, + self.CopterMission, + self.TakeoffAlt, + self.SplineLastWaypoint, + self.Gripper, + self.TestGripperMission, + self.VisionPosition, + self.ATTITUDE_FAST, + self.BaseLoggingRates, + self.BodyFrameOdom, + self.GPSViconSwitching, ]) return ret def tests1e(self): '''return list of all tests''' ret = ([ - ("BeaconPosition", - "Fly Beacon Position", - self.fly_beacon_position), # 56s - - ("RTLSpeed", - "Fly RTL Speed", - self.fly_rtl_speed), - - ("Mount", - "Test Camera/Antenna Mount", - self.test_mount), # 74s - - ("MountYawVehicleForMountROI", - "Test Camera/Antenna Mount vehicle yawing for ROI", - self.MountYawVehicleForMountROI), - - ("Button", - "Test Buttons", - self.test_button), - - ("ShipTakeoff", - "Fly Simulated Ship Takeoff", - self.fly_ship_takeoff), - - ("RangeFinder", - "Test RangeFinder Basic Functionality", - self.test_rangefinder), # 23s - - ("BaroDrivers", - "Test Baro Drivers", - self.BaroDrivers), - - ("SurfaceTracking", - "Test Surface Tracking", - self.test_surface_tracking), # 45s - - ("Parachute", - "Test Parachute Functionality", - self.test_parachute), - - ("ParameterChecks", - "Test Arming Parameter Checks", - self.test_parameter_checks), - - ("ManualThrottleModeChange", - "Check manual throttle mode changes denied on high throttle", - self.fly_manual_throttle_mode_change), - - ("MANUAL_CONTROL", - "Test mavlink MANUAL_CONTROL", - self.test_manual_control), - - ("ZigZag", - "Fly ZigZag Mode", - self.fly_zigzag_mode), # 58s - - ("PosHoldTakeOff", - "Fly POSHOLD takeoff", - self.fly_poshold_takeoff), - - ("FOLLOW", - "Fly follow mode", - self.fly_follow_mode), # 80s - - ("RangeFinderDrivers", - "Test rangefinder drivers", - self.fly_rangefinder_drivers), # 62s - - ("RangeFinderDriversMaxAlt", - "Test rangefinder drivers - test max alt", - self.fly_rangefinder_drivers_maxalt), # 25s - - ("MaxBotixI2CXL", - "Test maxbotix rangefinder drivers", - self.fly_rangefinder_driver_maxbotix), # 62s - - ("MAVProximity", - "Test MAVLink proximity driver", - self.fly_proximity_mavlink_distance_sensor, - ), - - ("ParameterValidation", - "Test parameters are checked for validity", - self.test_parameter_validation), - - ("AltTypes", - "Test Different Altitude Types", - self.test_altitude_types), - - ("PAUSE_CONTINUE", - "Test MAV_CMD_PAUSE_CONTINUE", - self.PAUSE_CONTINUE), - - ("RichenPower", - "Test RichenPower generator", - self.test_richenpower), - - ("IE24", - "Test IntelligentEnergy 2.4kWh generator", - self.test_ie24), - - ("LogUpload", - "Log upload", - self.log_upload), + self.BeaconPosition, + self.RTLSpeed, + self.Mount, + self.MountYawVehicleForMountROI, + self.Button, + self.ShipTakeoff, + self.RangeFinder, + self.BaroDrivers, + self.SurfaceTracking, + self.Parachute, + self.ParameterChecks, + self.ManualThrottleModeChange, + self.MANUAL_CONTROL, + self.ModeZigZag, + self.PosHoldTakeOff, + self.ModeFollow, + self.RangeFinderDrivers, + self.RangeFinderDriversMaxAlt, + self.MaxBotixI2CXL, + self.MAVProximity, + self.ParameterValidation, + self.AltTypes, + self.PAUSE_CONTINUE, + self.PAUSE_CONTINUE_GUIDED, + self.RichenPower, + self.IE24, + self.MAVLandedStateTakeoff, ]) return ret - # a wrapper around all the 2A,2B,2C..etc tests for travis - def tests2(self): - ret = ([]) - ret.extend(self.tests2a()) - ret.extend(self.tests2b()) - return ret - def tests2a(self): '''return list of all tests''' ret = ([ # something about SITLCompassCalibration appears to fail # this one, so we put it first: - ("FixedYawCalibration", - "Test Fixed Yaw Calibration", # about 20 secs - self.test_fixed_yaw_calibration), - - # we run this single 8min-and-40s test on its own, apart from - # requiring FixedYawCalibration right before it because without it, it fails to calibrate - ("SITLCompassCalibration", # this autotest appears to interfere with FixedYawCalibration, no idea why. - "Test SITL onboard compass calibration", - self.test_mag_calibration), + self.FixedYawCalibration, + + # we run this single 8min-and-40s test on its own, apart + # from requiring FixedYawCalibration right before it + # because without it, it fails to calibrate this + # autotest appears to interfere with + # FixedYawCalibration, no idea why. + self.SITLCompassCalibration, ]) return ret def tests2b(self): # this block currently around 9.5mins here '''return list of all tests''' ret = ([ - Test("MotorVibration", - "Fly motor vibration test", - self.fly_motor_vibration), - - Test("DynamicNotches", - "Fly Dynamic Notches", - self.fly_dynamic_notches, - attempts=8), - - Test("PositionWhenGPSIsZero", - "Ensure position doesn't zero when GPS lost", - self.test_copter_gps_zero), - - Test("DynamicRpmNotches", - "Fly Dynamic Notches driven by ESC Telemetry", - self.fly_esc_telemetry_notches, - attempts=8), - - Test("RefindGPS", - "Refind the GPS and attempt to RTL rather than continue to land", - self.RefindGPS), - - Test("GyroFFT", - "Fly Gyro FFT", - self.fly_gyro_fft, - attempts=8), - - Test("GyroFFTHarmonic", - "Fly Gyro FFT Harmonic Matching", - self.fly_gyro_fft_harmonic, - attempts=8), - - Test("CompassReordering", - "Test Compass reordering when priorities are changed", - self.test_mag_reordering), # 40sec? - - Test("CRSF", - "Test RC CRSF", - self.test_crsf), # 20secs ish - - Test("MotorTest", - "Run Motor Tests", - self.test_motortest), # 20secs ish - - Test("AltEstimation", - "Test that Alt Estimation is mandatory for ALT_HOLD", - self.test_alt_estimate_prearm), # 20secs ish - - Test("EKFSource", - "Check EKF Source Prearms work", - self.test_ekf_source), - - Test("GSF", - "Check GSF", - self.test_gsf), - - Test("AP_Avoidance", - "ADSB-based avoidance", - self.AP_Avoidance), - - Test("SMART_RTL", - "Check SMART_RTL", - self.test_SMART_RTL), - - Test("FlyEachFrame", - "Fly each supported internal frame", - self.fly_each_frame), - - Test("GPSBlending", - "Test GPS Blending", - self.test_gps_blending), - - Test("DataFlash", - "Test DataFlash Block backend", - self.test_dataflash_sitl), - - Test("DataFlashErase", - "Test DataFlash Block backend erase", - self.test_dataflash_erase), - - Test("Callisto", - "Test Callisto", - self.test_callisto), - - Test("PerfInfo", - "Test Scheduler PerfInfo output", - self.PerfInfo), - - Test("Replay", - "Test Replay", - self.test_replay), - - Test("FETtecESC", - "Test FETtecESC", - self.FETtecESC), - - Test("ProximitySensors", - "Test Proximity Sensors", - self.ProximitySensors), - - Test("GroundEffectCompensation_touchDownExpected", - "Test EKF's handling of touchdown-expected", - self.GroundEffectCompensation_touchDownExpected), - - Test("GroundEffectCompensation_takeOffExpected", - "Test EKF's handling of takeoff-expected", - self.GroundEffectCompensation_takeOffExpected), - - Test("DO_CHANGE_SPEED", - "Change speed during misison using waypoint items", - self.DO_CHANGE_SPEED), - - Test("WPNAV_SPEED", - "Change speed during misison", - self.WPNAV_SPEED), - - Test("WPNAV_SPEED_UP", - "Change speed (up) during misison", - self.WPNAV_SPEED_UP), - - Test("WPNAV_SPEED_DN", - "Change speed (down) during misison", - self.WPNAV_SPEED_DN), - - Test("GPSForYaw", - "Moving baseline GPS yaw", - self.GPSForYaw), - - ("DefaultIntervalsFromFiles", - "Test setting default mavlink message intervals from files", - self.DefaultIntervalsFromFiles), - - Test("GPSTypes", - "Test simulated GPS types", - self.GPSTypes), - - Test("MultipleGPS", - "Test multi-GPS behaviour", - self.MultipleGPS), - - Test("LogUpload", - "Log upload", - self.log_upload), + self.MotorVibration, + Test(self.DynamicNotches, attempts=8), + self.PositionWhenGPSIsZero, + Test(self.DynamicRpmNotches, attempts=8), + self.RefindGPS, + Test(self.GyroFFT, attempts=8), + Test(self.GyroFFTHarmonic, attempts=8), + self.GyroFFTAverage, + Test(self.GyroFFTContinuousAveraging, attempts=8), + self.CompassReordering, + self.CRSF, + self.MotorTest, + self.AltEstimation, + self.EKFSource, + self.GSF, + self.AP_Avoidance, + self.SMART_RTL, + self.RTL_TO_RALLY, + self.FlyEachFrame, + self.GPSBlending, + self.DataFlash, + Test(self.DataFlashErase, attempts=8), + self.Callisto, + self.PerfInfo, + self.Replay, + self.FETtecESC, + self.ProximitySensors, + self.GroundEffectCompensation_touchDownExpected, + self.GroundEffectCompensation_takeOffExpected, + self.DO_CHANGE_SPEED, + self.AUTO_LAND_TO_BRAKE, + self.WPNAV_SPEED, + self.WPNAV_SPEED_UP, + self.WPNAV_SPEED_DN, + self.SensorErrorFlags, + self.GPSForYaw, + self.DefaultIntervalsFromFiles, + self.GPSTypes, + self.MultipleGPS, + self.GuidedEKFLaneChange, ]) return ret def testcan(self): ret = ([ - ("CANGPSCopterMission", - "Fly copter mission", - self.fly_auto_test_using_can_gps), + self.CANGPSCopterMission, ]) return ret def tests(self): ret = [] - ret.extend(self.tests1()) - ret.extend(self.tests2()) + ret.extend(self.tests1a()) + ret.extend(self.tests1b()) + ret.extend(self.tests1c()) + ret.extend(self.tests1d()) + ret.extend(self.tests1e()) + ret.extend(self.tests2a()) + ret.extend(self.tests2b()) return ret def disabled_tests(self): @@ -8685,11 +9106,6 @@ def disabled_tests(self): } -class AutoTestCopterTests1(AutoTestCopter): - def tests(self): - return self.tests1() - - class AutoTestCopterTests1a(AutoTestCopter): def tests(self): return self.tests1a() @@ -8715,11 +9131,6 @@ def tests(self): return self.tests1e() -class AutoTestCopterTests2(AutoTestCopter): - def tests(self): - return self.tests2() - - class AutoTestCopterTests2a(AutoTestCopter): def tests(self): return self.tests2a() diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index 8a250572ac7..81a6824c8e4 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -1,5 +1,3 @@ -#!/usr/bin/env python - ''' Fly ArduPlane in SITL @@ -21,6 +19,7 @@ from common import AutoTestTimeoutException from common import NotAchievedException from common import PreconditionFailedException +from common import WaitModeTimeout from pymavlink.rotmat import Vector3 from pysim import vehicleinfo @@ -56,6 +55,9 @@ def get_normal_armable_modes_list(): def log_name(self): return "ArduPlane" + def default_speedup(self): + return 100 + def test_filepath(self): return os.path.realpath(__file__) @@ -159,10 +161,10 @@ def fly_RTL(self): timeout=180) self.progress("RTL Complete") - def test_need_ekf_to_arm(self): - """Loiter where we are.""" + def NeedEKFToArm(self): + """Ensure the EKF must be healthy for the vehicle to arm.""" self.progress("Ensuring we need EKF to be healthy to arm") - self.reboot_sitl() + self.set_parameter("SIM_GPS_DISABLE", 1) self.context_collect("STATUSTEXT") tstart = self.get_sim_time() success = False @@ -171,7 +173,7 @@ def test_need_ekf_to_arm(self): raise NotAchievedException("Did not get correct failure reason") self.send_mavlink_arm_command() try: - self.wait_statustext(".*(AHRS not healthy|AHRS: Not healthy).*", timeout=1, check_context=True, regex=True) + self.wait_statustext(".*AHRS: not using configured AHRS type.*", timeout=1, check_context=True, regex=True) success = True continue except AutoTestTimeoutException: @@ -179,6 +181,9 @@ def test_need_ekf_to_arm(self): if self.armed(): raise NotAchievedException("Armed unexpectedly") + self.set_parameter("SIM_GPS_DISABLE", 0) + self.wait_ready_to_arm() + def fly_LOITER(self, num_circles=4): """Loiter where we are.""" self.progress("Testing LOITER for %u turns" % num_circles) @@ -529,17 +534,24 @@ def fly_mission(self, filename, mission_timeout=60.0, strict=True, quadplane=Fal """Fly a mission from a file.""" self.progress("Flying mission %s" % filename) num_wp = self.load_mission(filename, strict=strict)-1 + self.fly_mission_waypoints(num_wp, mission_timeout=mission_timeout, quadplane=quadplane) + + def fly_mission_waypoints(self, num_wp, mission_timeout=60.0, quadplane=False): self.set_current_waypoint(0, check_afterwards=False) + self.context_push() + self.context_collect('STATUSTEXT') self.change_mode('AUTO') self.wait_waypoint(1, num_wp, max_dist=60, timeout=mission_timeout) self.wait_groundspeed(0, 0.5, timeout=mission_timeout) if quadplane: - self.wait_statustext("Throttle disarmed", timeout=200) + self.wait_statustext("Throttle disarmed", timeout=200, check_context=True) else: - self.wait_statustext("Auto disarmed", timeout=60) + self.wait_statustext("Auto disarmed", timeout=60, check_context=True) + self.context_pop() self.progress("Mission OK") - def fly_do_reposition(self): + def DO_REPOSITION(self): + '''Test mavlink DO_REPOSITION command''' self.progress("Takeoff") self.takeoff(alt=50) self.set_rc(3, 1500) @@ -564,57 +576,81 @@ def fly_do_reposition(self): self.fly_home_land_and_disarm() - def fly_deepstall(self): + def DeepStall(self): + '''Test DeepStall Landing''' # self.fly_deepstall_absolute() self.fly_deepstall_relative() def fly_deepstall_absolute(self): self.start_subtest("DeepStall Relative Absolute") - self.set_parameter("LAND_TYPE", 1) deepstall_elevator_pwm = 1661 - self.set_parameter("LAND_DS_ELEV_PWM", deepstall_elevator_pwm) + self.set_parameters({ + "LAND_TYPE": 1, + "LAND_DS_ELEV_PWM": deepstall_elevator_pwm, + "RTL_AUTOLAND": 1, + }) self.load_mission("plane-deepstall-mission.txt") self.change_mode("AUTO") self.wait_ready_to_arm() self.arm_vehicle() self.progress("Waiting for deepstall messages") - self.wait_text("Deepstall: Entry: ", timeout=240) + # note that the following two don't necessarily happen in this + # order, but at very high speedups we may miss the elevator + # PWM if we first look for the text (due to the get_sim_time() + # in wait_servo_channel_value) + + self.context_collect('STATUSTEXT') # assume elevator is on channel 2: - self.wait_servo_channel_value(2, deepstall_elevator_pwm) + self.wait_servo_channel_value(2, deepstall_elevator_pwm, timeout=240) + + self.wait_text("Deepstall: Entry: ", check_context=True) self.disarm_wait(timeout=120) self.progress("Flying home") + self.set_current_waypoint(0, check_afterwards=False) self.takeoff(10) self.set_parameter("LAND_TYPE", 0) self.fly_home_land_and_disarm() def fly_deepstall_relative(self): self.start_subtest("DeepStall Relative") - self.set_parameter("LAND_TYPE", 1) deepstall_elevator_pwm = 1661 - self.set_parameter("LAND_DS_ELEV_PWM", deepstall_elevator_pwm) + self.set_parameters({ + "LAND_TYPE": 1, + "LAND_DS_ELEV_PWM": deepstall_elevator_pwm, + "RTL_AUTOLAND": 1, + }) self.load_mission("plane-deepstall-relative-mission.txt") self.change_mode("AUTO") self.wait_ready_to_arm() self.arm_vehicle() self.progress("Waiting for deepstall messages") - self.wait_text("Deepstall: Entry: ", timeout=240) + # note that the following two don't necessarily happen in this + # order, but at very high speedups we may miss the elevator + # PWM if we first look for the text (due to the get_sim_time() + # in wait_servo_channel_value) + self.context_collect('STATUSTEXT') # assume elevator is on channel 2: - self.wait_servo_channel_value(2, deepstall_elevator_pwm) + self.wait_servo_channel_value(2, deepstall_elevator_pwm, timeout=240) + + self.wait_text("Deepstall: Entry: ", check_context=True) self.disarm_wait(timeout=120) + self.set_current_waypoint(0, check_afterwards=False) self.progress("Flying home") + self.set_current_waypoint(0, check_afterwards=False) self.takeoff(100) self.set_parameter("LAND_TYPE", 0) self.fly_home_land_and_disarm(timeout=240) def SmartBattery(self): + '''Test smart battery logging etc''' self.set_parameters({ "BATT_MONITOR": 16, # Maxell battery monitor }) @@ -640,14 +676,49 @@ def SmartBattery(self): if not self.current_onboard_log_contains_message("BCL2"): raise NotAchievedException("Expected BCL2 message") - def fly_do_change_speed(self): + def DO_CHANGE_SPEED(self): + '''Test DO_CHANGE_SPEED command/item''' # the following lines ensure we revert these parameter values # - DO_CHANGE_AIRSPEED is a permanent vehicle change! self.set_parameters({ "TRIM_ARSPD_CM": self.get_parameter("TRIM_ARSPD_CM"), "MIN_GNDSPD_CM": self.get_parameter("MIN_GNDSPD_CM"), + "RTL_AUTOLAND": 1, }) + self.DO_CHANGE_SPEED_mavlink() + self.DO_CHANGE_SPEED_mission() + + def DO_CHANGE_SPEED_mission(self): + '''test DO_CHANGE_SPEED as a mission item''' + self.start_subtest("DO_CHANGE_SPEED_mission") + self.load_mission("mission.txt") + self.set_current_waypoint(1) + + self.progress("Takeoff") + self.set_rc(3, 1000) + self.takeoff(alt=10) + self.set_rc(3, 1500) + + self.start_subtest("Check initial speed") + + self.change_mode('AUTO') + + checks = [ + (1, self.get_parameter("TRIM_ARSPD_CM") * 0.01), + (3, 10), + (5, 20), + (7, 15), + ] + + for (current_waypoint, want_airspeed) in checks: + self.wait_current_waypoint(current_waypoint, timeout=120) + self.wait_airspeed(want_airspeed-1, want_airspeed+1, minimum_duration=5, timeout=120) + + self.fly_home_land_and_disarm() + + def DO_CHANGE_SPEED_mavlink(self): + '''test DO_CHANGE_SPEED as a mavlink command''' self.progress("Takeoff") self.takeoff(alt=100) self.set_rc(3, 1500) @@ -666,17 +737,9 @@ def fly_do_change_speed(self): ) self.delay_sim_time(10) self.progress("Ensuring initial speed is known and relatively constant") - initial_speed = 21.5 - timeout = 10 - tstart = self.get_sim_time() - while True: - if self.get_sim_time_cached() - tstart > timeout: - break - m = self.mav.recv_match(type='VFR_HUD', blocking=True) - self.progress("GroundSpeed: %f want=%f" % - (m.groundspeed, initial_speed)) - if abs(initial_speed - m.groundspeed) > 1: - raise NotAchievedException("Initial speed not as expected (want=%f got=%f" % (initial_speed, m.groundspeed)) + initial_speed = 22.0 + timeout = 15 + self.wait_airspeed(initial_speed-1, initial_speed+1, minimum_duration=5, timeout=timeout) self.progress("Setting groundspeed") new_target_groundspeed = initial_speed + 5 @@ -696,6 +759,17 @@ def fly_do_change_speed(self): self.wait_groundspeed(new_target_groundspeed-0.5, new_target_groundspeed+0.5, timeout=40) self.set_parameter("SIM_WIND_SPD", 0) + # clear target groundspeed + self.run_cmd( + mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED, + 1, # groundspeed + 0, + -1, # throttle / no change + 0, # absolute values + 0, + 0, + 0) + self.progress("Setting airspeed") new_target_airspeed = initial_speed + 5 self.run_cmd( @@ -707,10 +781,10 @@ def fly_do_change_speed(self): 0, 0, 0) - self.wait_groundspeed(new_target_airspeed-0.5, new_target_airspeed+0.5) + self.wait_airspeed(new_target_airspeed-0.5, new_target_airspeed+0.5) self.progress("Adding some wind, hoping groundspeed increases/decreases") self.set_parameters({ - "SIM_WIND_SPD": 5, + "SIM_WIND_SPD": 7, "SIM_WIND_DIR": 270, }) self.delay_sim_time(5) @@ -721,7 +795,7 @@ def fly_do_change_speed(self): raise NotAchievedException("Did not achieve groundspeed delta") m = self.mav.recv_match(type='VFR_HUD', blocking=True) delta = abs(m.airspeed - m.groundspeed) - want_delta = 4 + want_delta = 5 self.progress("groundspeed and airspeed should be different (have=%f want=%f)" % (delta, want_delta)) if delta > want_delta: break @@ -737,14 +811,13 @@ def fly_home_land_and_disarm(self, timeout=120): # waypoint: self.wait_distance_to_waypoint(8, 100, 10000000) self.set_current_waypoint(8) - self.drain_mav() # TODO: reflect on file to find this magic waypoint number? # self.wait_waypoint(7, num_wp-1, timeout=500) # we # tend to miss the final waypoint by a fair bit, and # this is probably too noisy anyway? self.wait_disarmed(timeout=timeout) - def fly_flaps(self): + def TestFlaps(self): """Test flaps functionality.""" filename = "flaps.txt" self.context_push() @@ -766,6 +839,7 @@ def fly_flaps(self): "RC%u_OPTION" % flaps_ch: 208, # Flaps RCx_OPTION "LAND_FLAP_PERCNT": 50, "LOG_DISARMED": 1, + "RTL_AUTOLAND": 1, "RC%u_MIN" % flaps_ch: flaps_ch_min, "RC%u_MAX" % flaps_ch: flaps_ch_max, @@ -836,8 +910,8 @@ def fly_flaps(self): self.disarm_vehicle() raise ex - def test_rc_relay(self): - '''test toggling channel 12 toggles relay''' + def TestRCRelay(self): + '''Test Relay RC Channel Option''' self.set_parameter("RC12_OPTION", 28) # Relay On/Off self.set_rc(12, 1000) self.reboot_sitl() # needed for RC12_OPTION to take effect @@ -863,8 +937,8 @@ def test_rc_relay(self): if off: raise NotAchievedException("SIM_PIN_MASK doesn't reflect OFF") - def test_rc_option_camera_trigger(self): - '''test toggling channel 12 takes picture''' + def TestRCCamera(self): + '''Test RC Option - Camera Trigger''' self.set_parameter("RC12_OPTION", 9) # CameraTrigger self.reboot_sitl() # needed for RC12_OPTION to take effect @@ -898,7 +972,8 @@ def test_rc_option_camera_trigger(self): raise NotAchievedException("Bad absalt (want=%f vs got=%f)" % (original_alt+30, x.alt_msl)) self.fly_home_land_and_disarm() - def test_throttle_failsafe(self): + def ThrottleFailsafe(self): + '''Fly throttle failsafe''' self.change_mode('MANUAL') m = self.mav.recv_match(type='SYS_STATUS', blocking=True) receiver_bit = mavutil.mavlink.MAV_SYS_STATUS_SENSOR_RC_RECEIVER @@ -925,8 +1000,8 @@ def test_throttle_failsafe(self): raise NotAchievedException("Did not go via circle mode") self.progress("Ensure we've had our throttle squashed to 950") self.wait_rc_channel_value(3, 950) - self.drain_mav_unparsed() - m = self.mav.recv_match(type='SYS_STATUS', blocking=True) + self.do_timesync_roundtrip() + m = self.assert_receive_message('SYS_STATUS') self.progress("Got (%s)" % str(m)) self.progress("Testing receiver enabled") if (not (m.onboard_control_sensors_enabled & receiver_bit)): @@ -939,10 +1014,10 @@ def test_throttle_failsafe(self): # if (m.onboard_control_sensors_health & receiver_bit): # raise NotAchievedException("Sensor healthy when it shouldn't be") self.set_parameter("SIM_RC_FAIL", 0) - self.drain_mav_unparsed() # have to allow time for RC to be fetched from SITL self.delay_sim_time(0.5) - m = self.mav.recv_match(type='SYS_STATUS', blocking=True) + self.do_timesync_roundtrip() + m = self.assert_receive_message('SYS_STATUS') self.progress("Testing receiver enabled") if (not (m.onboard_control_sensors_enabled & receiver_bit)): raise NotAchievedException("Receiver not enabled") @@ -961,8 +1036,8 @@ def test_throttle_failsafe(self): if (not self.get_mode_from_mode_mapping("CIRCLE") in [x.custom_mode for x in self.context_stop_collecting("HEARTBEAT")]): raise NotAchievedException("Did not go via circle mode") - self.drain_mav_unparsed() - m = self.mav.recv_match(type='SYS_STATUS', blocking=True) + self.do_timesync_roundtrip() + m = self.assert_receive_message('SYS_STATUS') self.progress("Got (%s)" % str(m)) self.progress("Testing receiver enabled") if (not (m.onboard_control_sensors_enabled & receiver_bit)): @@ -978,8 +1053,8 @@ def test_throttle_failsafe(self): # have to allow time for RC to be fetched from SITL self.progress("Giving receiver time to recover") self.delay_sim_time(0.5) - self.drain_mav_unparsed() - m = self.mav.recv_match(type='SYS_STATUS', blocking=True) + self.do_timesync_roundtrip() + m = self.assert_receive_message('SYS_STATUS') self.progress("Testing receiver enabled") if (not (m.onboard_control_sensors_enabled & receiver_bit)): raise NotAchievedException("Receiver not enabled") @@ -1000,11 +1075,11 @@ def test_throttle_failsafe(self): "FS_SHORT_ACTN": 3, # 3 means disabled "SIM_RC_FAIL": 1, }) - self.wait_statustext("Long event on", check_context=True) + self.wait_statustext("Long failsafe on", check_context=True) self.wait_mode("RTL") # self.context_clear_collection("STATUSTEXT") self.set_parameter("SIM_RC_FAIL", 0) - self.wait_text("Long event off", check_context=True) + self.wait_text("Long Failsafe Cleared", check_context=True) self.change_mode("MANUAL") self.progress("Trying again with THR_FS_VALUE") @@ -1012,7 +1087,7 @@ def test_throttle_failsafe(self): "THR_FS_VALUE": 960, "SIM_RC_FAIL": 2, }) - self.wait_statustext("Long event on", check_context=True) + self.wait_statustext("Long Failsafe on", check_context=True) self.wait_mode("RTL") except Exception as e: self.print_exception_caught(e) @@ -1021,7 +1096,29 @@ def test_throttle_failsafe(self): if ex is not None: raise ex - def test_throttle_failsafe_fence(self): + self.start_subtest("Not use RC throttle input when THR_FAILSAFE==2") + self.takeoff(100) + self.set_rc(3, 1800) + self.set_rc(1, 2000) + self.wait_attitude(desroll=45, timeout=1) + self.context_push() + self.set_parameters({ + "THR_FAILSAFE": 2, + "SIM_RC_FAIL": 1, # no pulses + }) + self.delay_sim_time(1) + self.wait_attitude(desroll=0, timeout=5) + self.assert_servo_channel_value(3, self.get_parameter("RC3_MIN")) + self.set_parameters({ + "SIM_RC_FAIL": 0, # fix receiver + }) + self.zero_throttle() + self.disarm_vehicle(force=True) + self.context_pop() + self.reboot_sitl() + + def ThrottleFailsafeFence(self): + '''Fly fence survives throttle failsafe''' fence_bit = mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE self.progress("Checking fence is not present before being configured") @@ -1060,20 +1157,21 @@ def test_throttle_failsafe_fence(self): self.set_parameter("SIM_RC_FAIL", 2) # throttle-to-950 self.wait_mode("CIRCLE") self.delay_sim_time(1) # give - self.drain_mav_unparsed() + self.do_timesync_roundtrip() self.progress("Checking fence is OK after receiver failure (bind-values)") fence_bit = mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE - m = self.mav.recv_match(type='SYS_STATUS', blocking=True) - self.progress("Got (%s)" % str(m)) + m = self.assert_receive_message('SYS_STATUS') if (not (m.onboard_control_sensors_enabled & fence_bit)): raise NotAchievedException("Fence not enabled after RC fail") self.do_fence_disable() # Ensure the fence is disabled after test - def test_gripper_mission(self): + def TestGripperMission(self): + '''Test Gripper mission items''' self.context_push() ex = None try: + self.set_parameter("RTL_AUTOLAND", 1) self.load_mission("plane-gripper-mission.txt") self.set_current_waypoint(1) self.change_mode('AUTO') @@ -1091,7 +1189,7 @@ def test_gripper_mission(self): def assert_fence_sys_status(self, present, enabled, health): self.delay_sim_time(1) - self.drain_mav_unparsed() + self.do_timesync_roundtrip() m = self.assert_receive_message('SYS_STATUS', timeout=1) tests = [ ("present", present, m.onboard_control_sensors_present), @@ -1149,7 +1247,8 @@ def wait_circling_point_with_radius(self, loc, want_radius, epsilon=5.0, min_cir on_radius_start_heading = None circle_time_start = 0 - def test_fence_static(self): + def FenceStatic(self): + '''Test Basic Fence Functionality''' ex = None try: self.progress("Checking for bizarre healthy-when-not-present-or-enabled") @@ -1159,7 +1258,6 @@ def test_fence_static(self): m = self.mav.recv_match(type='FENCE_STATUS', blocking=True, timeout=2) if m is not None: raise NotAchievedException("Got FENCE_STATUS unexpectedly") - self.drain_mav_unparsed() self.set_parameter("FENCE_ACTION", 0) # report only self.assert_fence_sys_status(True, False, True) self.set_parameter("FENCE_ACTION", 1) # RTL @@ -1325,14 +1423,16 @@ def test_fence_breach_circle_at(self, loc, disable_on_breach=False): if ex is not None: raise ex - def test_fence_rtl(self): + def FenceRTL(self): + '''Test Fence RTL''' self.progress("Testing FENCE_ACTION_RTL no rally point") # have to disable the fence once we've breached or we breach # it as part of the loiter-at-home! self.test_fence_breach_circle_at(self.home_position_as_mav_location(), disable_on_breach=True) - def test_fence_rtl_rally(self): + def FenceRTLRally(self): + '''Test Fence RTL Rally''' ex = None target_system = 1 target_component = 1 @@ -1364,7 +1464,7 @@ def test_fence_rtl_rally(self): if ex is not None: raise ex - def test_fence_ret_rally(self): + def FenceRetRally(self): """ Tests the FENCE_RET_RALLY flag, either returning to fence return point, or rally point """ target_system = 1 @@ -1435,6 +1535,9 @@ def test_fence_ret_rally(self): self.wait_circling_point_with_radius(rally_loc, return_radius) self.set_parameter("FENCE_ALT_MIN", 0) # Clear fence breach + # 10 second fence min retrigger time + self.delay_sim_time(15) + # Fly up before re-triggering fence breach. Fly to fence return point self.change_altitude(self.homeloc.alt+30) self.set_parameters({ @@ -1448,7 +1551,8 @@ def test_fence_ret_rally(self): self.do_fence_disable() # Disable fence so we can land self.fly_home_land_and_disarm() # Pack it up, we're going home. - def test_parachute(self): + def Parachute(self): + '''Test Parachute''' self.set_rc(9, 1000) self.set_parameters({ "CHUTE_ENABLED": 1, @@ -1467,7 +1571,8 @@ def test_parachute(self): self.disarm_vehicle(force=True) self.reboot_sitl() - def test_parachute_sinkrate(self): + def ParachuteSinkRate(self): + '''Test Parachute (SinkRate triggering)''' self.set_rc(9, 1000) self.set_parameters({ "CHUTE_ENABLED": 1, @@ -1578,8 +1683,8 @@ def fly_ahrs2_test(self): self.check_attitudes_match(1, 2) - def test_main_flight(self): - + def MainFlight(self): + '''Lots of things in one flight''' self.change_mode('MANUAL') self.progress("Asserting we do support transfer of fence via mission item protocol") @@ -1618,25 +1723,76 @@ def test_main_flight(self): self.run_subtest("Mission test", lambda: self.fly_mission("ap1.txt", strict=False)) - def airspeed_autocal(self): + def PitotBlockage(self): + '''Test detection and isolation of a blocked pitot tube''' + self.set_parameters({ + "ARSPD_OPTIONS": 15, + "ARSPD_USE": 1, + "SIM_WIND_SPD": 7, + "SIM_WIND_DIR": 0, + "ARSPD_WIND_MAX": 15, + }) + self.change_mode("TAKEOFF") + self.wait_ready_to_arm() + self.arm_vehicle() + # simulate the effect of a blocked pitot tube + self.set_parameter("ARSPD_RATIO", 0.1) + self.delay_sim_time(10) + if (self.get_parameter("ARSPD_USE") == 0): + self.progress("Faulty Sensor Disabled") + else: + raise NotAchievedException("Airspeed Sensor Not Disabled") + self.delay_sim_time(20) + # simulate the effect of blockage partially clearing + self.set_parameter("ARSPD_RATIO", 1.0) + self.delay_sim_time(60) + if (self.get_parameter("ARSPD_USE") == 0): + self.progress("Faulty Sensor Remains Disabled") + else: + raise NotAchievedException("Fault Sensor Re-Enabled") + # simulate the effect of blockage fully clearing + self.set_parameter("ARSPD_RATIO", 2.0) + self.delay_sim_time(60) + if (self.get_parameter("ARSPD_USE") == 1): + self.progress("Sensor Re-Enabled") + else: + raise NotAchievedException("Airspeed Sensor Not Re-Enabled") + self.disarm_vehicle(force=True) + + def AIRSPEED_AUTOCAL(self): + '''Test AIRSPEED_AUTOCAL''' self.progress("Ensure no AIRSPEED_AUTOCAL on ground") - self.set_parameter("ARSPD_AUTOCAL", 1) - m = self.mav.recv_match(type='AIRSPEED_AUTOCAL', - blocking=True, - timeout=5) - if m is not None: - raise NotAchievedException("Got autocal on ground") + self.set_parameters({ + "ARSPD_AUTOCAL": 1, + "ARSPD_PIN": 2, + "ARSPD_RATIO": 0, + "ARSPD2_RATIO": 4, + "ARSPD2_TYPE": 3, # MS5525 + "ARSPD2_BUS": 1, + "ARSPD2_AUTOCAL": 1, + "SIM_ARSPD2_OFS": 1900, # default is 2013 + + "RTL_AUTOLAND": 1, + }) + self.context_collect('STATUSTEXT') + self.reboot_sitl() + + self.assert_not_receive_message('AIRSPEED_AUTOCAL', timeout=5) + + # these are boot-time calibration messages: + self.wait_statustext('Airspeed 1 calibrated', check_context=True, timeout=30) + self.wait_statustext('Airspeed 2 calibrated', check_context=True) + mission_filepath = "flaps.txt" - num_wp = self.load_mission(mission_filepath) + self.load_mission(mission_filepath) self.wait_ready_to_arm() self.arm_vehicle() self.change_mode("AUTO") self.progress("Ensure AIRSPEED_AUTOCAL in air") - m = self.mav.recv_match(type='AIRSPEED_AUTOCAL', - blocking=True, - timeout=5) - self.wait_waypoint(7, num_wp-1, max_dist=5, timeout=500) - self.wait_disarmed(timeout=120) + self.assert_receive_message('AIRSPEED_AUTOCAL') + self.wait_statustext("Airspeed 0 ratio reset", check_context=True, timeout=70) + self.wait_statustext("Airspeed 1 ratio reset", check_context=True, timeout=70) + self.fly_home_land_and_disarm() def deadreckoning_main(self, disable_airspeed_sensor=False): self.wait_ready_to_arm() @@ -1707,17 +1863,21 @@ def validate_global_position_int_against_simstate(mav, m): finally: self.remove_message_hook(validate_global_position_int_against_simstate) - def deadreckoning(self): + def Deadreckoning(self): + '''Test deadreckoning support''' self.deadreckoning_main() - def deadreckoning_no_airspeed_sensor(self): + def DeadreckoningNoAirSpeed(self): + '''Test deadreckoning support with no airspeed sensor''' self.deadreckoning_main(disable_airspeed_sensor=True) - def climb_before_turn(self): + def ClimbBeforeTurn(self): + '''Test climb-before-turn''' self.wait_ready_to_arm() self.set_parameters({ "FLIGHT_OPTIONS": 0, "ALT_HOLD_RTL": 8000, + "RTL_AUTOLAND": 1, }) takeoff_alt = 10 self.takeoff(alt=takeoff_alt) @@ -1729,7 +1889,7 @@ def climb_before_turn(self): home = self.home_position_as_mav_location() distance = self.get_distance(home, self.mav.location()) - self.wait_altitude(expected_alt - 10, expected_alt + 10, relative=True) + self.wait_altitude(expected_alt - 10, expected_alt + 10, relative=True, timeout=80) new_distance = self.get_distance(home, self.mav.location()) # We should be closer to home. @@ -1740,6 +1900,8 @@ def climb_before_turn(self): ) self.fly_home_land_and_disarm() + self.set_current_waypoint(0, check_afterwards=False) + self.change_mode("MANUAL") self.set_rc(3, 1000) @@ -1756,7 +1918,7 @@ def climb_before_turn(self): home = self.home_position_as_mav_location() distance = self.get_distance(home, self.mav.location()) - self.wait_altitude(expected_alt - 10, expected_alt + 10, relative=True) + self.wait_altitude(expected_alt - 10, expected_alt + 10, relative=True, timeout=80) new_distance = self.get_distance(home, self.mav.location()) # We should be farther from to home. @@ -1768,7 +1930,8 @@ def climb_before_turn(self): self.fly_home_land_and_disarm(timeout=240) - def rtl_climb_min(self): + def RTL_CLIMB_MIN(self): + '''Test RTL_CLIMB_MIN''' self.wait_ready_to_arm() rtl_climb_min = 100 self.set_parameter("RTL_CLIMB_MIN", rtl_climb_min) @@ -1786,7 +1949,7 @@ def rtl_climb_min(self): self.wait_distance_to_nav_target( 0, 500, - timeout=120, + timeout=240, ) alt = self.get_altitude(relative=True) expected_halfway_alt = expected_alt + (post_cruise_alt + rtl_climb_min - expected_alt)/2.0 @@ -1814,7 +1977,8 @@ def rtl_climb_min(self): def sample_enable_parameter(self): return "Q_ENABLE" - def test_rangefinder(self): + def RangeFinder(self): + '''Test RangeFinder Basic Functionality''' ex = None self.context_push() self.progress("Making sure we don't ordinarily get RANGEFINDER") @@ -1836,6 +2000,7 @@ def test_rangefinder(self): '''ensure rangefinder gives height-above-ground''' self.load_mission("plane-gripper-mission.txt") # borrow this + self.set_parameter("RTL_AUTOLAND", 1) self.set_current_waypoint(1) self.change_mode('AUTO') self.wait_ready_to_arm() @@ -1877,11 +2042,13 @@ def initial_mode_switch_mode(self): def default_mode(self): return "MANUAL" - def test_pid_tuning(self): + def PIDTuning(self): + '''Test PID Tuning''' self.change_mode("FBWA") # we don't update PIDs in MANUAL - super(AutoTestPlane, self).test_pid_tuning() + super(AutoTestPlane, self).PIDTuning() - def test_setting_modes_via_auxswitches(self): + def AuxModeSwitch(self): + '''Set modes via auxswitches''' self.set_parameter("FLTMODE1", 1) # circle self.set_rc(8, 950) self.wait_mode("CIRCLE") @@ -1927,8 +2094,7 @@ def wait_for_collision_threat_to_clear(self): last_collision = now def SimADSB(self): - '''trivial tests to ensure simulated ADSB sensor continues to -function''' + '''Tests to ensure simulated ADSB sensor continues to function''' self.set_parameters({ "SIM_ADSB_COUNT": 1, "ADSB_TYPE": 1, @@ -1936,7 +2102,50 @@ def SimADSB(self): self.reboot_sitl() self.assert_receive_message('ADSB_VEHICLE', timeout=30) - def test_adsb(self): + def ADSB(self): + '''Test ADSB''' + self.ADSB_f_action_rtl() + self.ADSB_r_action_resume_or_loiter() + + def ADSB_r_action_resume_or_loiter(self): + '''ensure we resume auto mission or enter loiter''' + self.set_parameters({ + "ADSB_TYPE": 1, + "AVD_ENABLE": 1, + "AVD_F_ACTION": mavutil.mavlink.MAV_COLLISION_ACTION_MOVE_HORIZONTALLY, + "AVD_F_RCVRY": 3, # resume auto or loiter + }) + self.reboot_sitl() + self.takeoff(50) + # fly North, create thread to east, wait for flying east + self.start_subtest("Testing loiter resume") + self.reach_heading_manual(0) + here = self.mav.location() + self.test_adsb_send_threatening_adsb_message(here, offset_ne=(0, 30)) + self.wait_mode('AVOID_ADSB') + # recovery has the vehicle circling a point... but we don't + # know which point. So wait 'til it looks like it is + # circling, then grab the point, then check we're circling + # it... + self.wait_heading(290) + self.wait_heading(300) + dest = self.position_target_loc() + REALLY_BAD_FUDGE_FACTOR = 1.25 # FIXME + expected_radius = REALLY_BAD_FUDGE_FACTOR * self.get_parameter('WP_LOITER_RAD') + self.wait_circling_point_with_radius(dest, expected_radius) + + self.start_subtest("Testing mission resume") + self.reach_heading_manual(270) + self.load_generic_mission("CMAC-circuit.txt", strict=False) + self.change_mode('AUTO') + self.wait_current_waypoint(2) + self.test_adsb_send_threatening_adsb_message(here, offset_ne=(0, 30)) + self.wait_mode('AVOID_ADSB') + self.wait_mode('AUTO') + + self.fly_home_land_and_disarm() + + def ADSB_f_action_rtl(self): self.context_push() ex = None try: @@ -1999,7 +2208,8 @@ def test_adsb(self): if ex is not None: raise ex - def fly_do_guided_request(self, target_system=1, target_component=1): + def GuidedRequest(self, target_system=1, target_component=1): + '''Test handling of MISSION_ITEM in guided mode''' self.progress("Takeoff") self.takeoff(alt=50) self.set_rc(3, 1500) @@ -2085,6 +2295,9 @@ def fly_do_guided_request(self, target_system=1, target_component=1): self.fly_home_land_and_disarm() def LOITER(self): + '''Test Loiter mode''' + # first test old loiter behavour + self.set_parameter("FLIGHT_OPTIONS", 0) self.takeoff(alt=200) self.set_rc(3, 1500) self.change_mode("LOITER") @@ -2130,17 +2343,33 @@ def LOITER(self): self.progress("Centering elevator and ensuring we get back to loiter altitude") self.set_rc(2, 1500) self.wait_altitude(initial_alt-1, initial_alt+1) + # Test new loiter behavour + self.set_parameter("FLIGHT_OPTIONS", 1 << 12) + # should decend at max stick + self.set_rc(2, int(rc2_max)) + self.wait_altitude(initial_alt - 110, initial_alt - 90, timeout=90) + # should not climb back at mid stick + self.set_rc(2, 1500) + self.delay_sim_time(60) + self.wait_altitude(initial_alt - 110, initial_alt - 90) + # should climb at min stick + self.set_rc(2, 1100) + self.wait_altitude(initial_alt - 10, initial_alt + 10, timeout=90) + # return stick to center and fly home + self.set_rc(2, 1500) self.fly_home_land_and_disarm() def CPUFailsafe(self): '''In lockup Plane should copy RC inputs to RC outputs''' self.plane_CPUFailsafe() - def test_large_missions(self): + def LargeMissions(self): + '''Test Manipulation of Large missions''' self.load_mission("Kingaroy-vlarge.txt", strict=False) self.load_mission("Kingaroy-vlarge2.txt", strict=False) - def fly_soaring(self): + def Soaring(self): + '''Test Soaring feature''' model = "plane-soaring" @@ -2241,17 +2470,18 @@ def fly_soaring(self): self.set_rc(rc_chan, 1500) # Make sure this causes throttle down. - self.wait_servo_channel_value(3, 1200, timeout=2, comparator=operator.lt) + self.wait_servo_channel_value(3, 1200, timeout=3, comparator=operator.lt) self.progress("Waiting for next WP with no thermalling") self.wait_waypoint(4, 4, timeout=1200, max_dist=120) # Disarm - self.disarm_vehicle() + self.disarm_vehicle_expect_fail() self.progress("Mission OK") - def fly_soaring_speed_to_fly(self): + def SpeedToFly(self): + '''Test soaring speed-to-fly''' model = "plane-soaring" @@ -2263,8 +2493,10 @@ def fly_soaring_speed_to_fly(self): self.load_mission('CMAC-soar.txt', strict=False) - # Turn of environmental thermals. - self.set_parameter("SIM_THML_SCENARI", 0) + self.set_parameters({ + "SIM_THML_SCENARI": 0, # Turn off environmental thermals. + "SOAR_ALT_MAX": 1000, # remove source of random failure + }) # Get thermalling RC channel rc_chan = 0 @@ -2294,64 +2526,99 @@ def fly_soaring_speed_to_fly(self): # Enable soaring (no automatic thermalling) self.set_rc(rc_chan, 1500) - # Enable speed to fly. - self.set_parameter("SOAR_CRSE_ARSPD", -1) - - # Set appropriate McCready. - self.set_parameter("SOAR_VSPEED", 1) - self.set_parameter("SIM_WIND_SPD", 0) + self.set_parameters({ + "SOAR_CRSE_ARSPD": -1, # Enable speed to fly. + "SOAR_VSPEED": 1, # Set appropriate McCready. + "SIM_WIND_SPD": 0, + }) - # Wait a few seconds before determining the "trim" airspeed. + self.progress('Waiting a few seconds before determining the "trim" airspeed.') self.delay_sim_time(20) - m = self.mav.recv_match(type='VFR_HUD', blocking=True) + m = self.assert_receive_message('VFR_HUD') trim_airspeed = m.airspeed + self.progress("Using trim_airspeed=%f" % (trim_airspeed,)) min_airspeed = self.get_parameter("ARSPD_FBW_MIN") max_airspeed = self.get_parameter("ARSPD_FBW_MAX") - # Add updraft - self.set_parameter("SIM_WIND_SPD", 1) - self.set_parameter('SIM_WIND_DIR_Z', 90) - self.delay_sim_time(20) - m = self.mav.recv_match(type='VFR_HUD', blocking=True) + if trim_airspeed > max_airspeed: + raise NotAchievedException("trim airspeed > max_airspeed (%f>%f)" % + (trim_airspeed, max_airspeed)) + if trim_airspeed < min_airspeed: + raise NotAchievedException("trim airspeed < min_airspeed (%f<%f)" % + (trim_airspeed, min_airspeed)) - if not m.airspeed < trim_airspeed and trim_airspeed > min_airspeed: - raise NotAchievedException("Airspeed did not reduce in updraft") + self.progress("Adding updraft") + self.set_parameters({ + "SIM_WIND_SPD": 1, + 'SIM_WIND_DIR_Z': 90, + }) + self.progress("Waiting for vehicle to move slower in updraft") + self.wait_airspeed(0, trim_airspeed-0.5, minimum_duration=10, timeout=120) - # Add downdraft + self.progress("Adding downdraft") self.set_parameter('SIM_WIND_DIR_Z', -90) - self.delay_sim_time(20) - m = self.mav.recv_match(type='VFR_HUD', blocking=True) + self.progress("Waiting for vehicle to move faster in downdraft") + self.wait_airspeed(trim_airspeed+0.5, trim_airspeed+100, minimum_duration=10, timeout=120) - if not m.airspeed > trim_airspeed and trim_airspeed < max_airspeed: - raise NotAchievedException("Airspeed did not increase in downdraft") + self.progress("Zeroing wind and increasing McCready") + self.set_parameters({ + "SIM_WIND_SPD": 0, + "SOAR_VSPEED": 2, + }) + self.progress("Waiting for airspeed to increase with higher VSPEED") + self.wait_airspeed(trim_airspeed+0.5, trim_airspeed+100, minimum_duration=10, timeout=120) - # Zero the wind and increase McCready. - self.set_parameter("SIM_WIND_SPD", 0) - self.set_parameter("SOAR_VSPEED", 2) - self.delay_sim_time(20) - m = self.mav.recv_match(type='VFR_HUD', blocking=True) + # mcReady tests don't work ATM, so just return early: + # takes too long to land, so just make it all go away: + self.disarm_vehicle(force=True) + self.reboot_sitl() + return + + self.start_subtest('Test McReady values') + # Disable soaring + self.set_rc(rc_chan, 1100) + + # Wait for to 400m before starting. + self.wait_altitude(390, 400, timeout=600, relative=True) - if not m.airspeed > trim_airspeed and trim_airspeed < max_airspeed: - raise NotAchievedException("Airspeed did not increase with higher SOAR_VSPEED") + # Enable soaring + self.set_rc(rc_chan, 2000) - # Reduce McCready. - self.set_parameter("SOAR_VSPEED", 0) + self.progress("Find airspeed with 1m/s updraft and mcready=1") + self.set_parameters({ + "SOAR_VSPEED": 1, + "SIM_WIND_SPD": 1, + }) self.delay_sim_time(20) - m = self.mav.recv_match(type='VFR_HUD', blocking=True) + m = self.assert_receive_message('VFR_HUD') + mcready1_speed = m.airspeed + self.progress("airspeed is %f" % mcready1_speed) - if not m.airspeed < trim_airspeed and trim_airspeed > min_airspeed: - raise NotAchievedException("Airspeed did not reduce with lower SOAR_VSPEED") + self.progress("Reducing McCready") + self.set_parameters({ + "SOAR_VSPEED": 0.5, + }) + self.progress("Waiting for airspeed to decrease with lower McReady") + self.wait_airspeed(0, mcready1_speed-0.5, minimum_duration=10, timeout=120) - # Disarm - self.disarm_vehicle() + self.progress("Increasing McCready") + self.set_parameters({ + "SOAR_VSPEED": 1.5, + }) + self.progress("Waiting for airspeed to decrease with lower McReady") + self.wait_airspeed(mcready1_speed+0.5, mcready1_speed+100, minimum_duration=10, timeout=120) - self.progress("Mission OK") + # takes too long to land, so just make it all go away: + self.disarm_vehicle(force=True) + self.reboot_sitl() - def test_airspeed_drivers(self): + def AirspeedDrivers(self): + '''Test AirSpeed drivers''' airspeed_sensors = [ ("MS5525", 3, 1), ("DLVR", 7, 2), + ("SITL", 100, 0), ] for (name, t, bus) in airspeed_sensors: self.context_push() @@ -2364,8 +2631,13 @@ def test_airspeed_drivers(self): # insert listener to compare airspeeds: airspeed = [None, None] + # don't start testing until we've seen real speed from + # both sensors. This gets us out of the noise area. + global initial_airspeed_threshold_reached + initial_airspeed_threshold_reached = False def check_airspeeds(mav, m): + global initial_airspeed_threshold_reached m_type = m.get_type() if (m_type == 'NAMED_VALUE_FLOAT' and m.name == 'AS2'): @@ -2376,6 +2648,14 @@ def check_airspeeds(mav, m): return if airspeed[0] is None or airspeed[1] is None: return + if airspeed[0] < 2 or airspeed[1] < 2: + # this mismatch can occur on takeoff, or when we + # smack into the ground at the end of the mission + return + if not initial_airspeed_threshold_reached: + if not (airspeed[0] > 10 or airspeed[1] > 10): + return + initial_airspeed_threshold_reached = True delta = abs(airspeed[0] - airspeed[1]) if delta > 2: raise NotAchievedException("Airspeed mismatch (as1=%f as2=%f)" % (airspeed[0], airspeed[1])) @@ -2389,17 +2669,36 @@ def check_airspeeds(mav, m): self.reboot_sitl() def TerrainMission(self): + '''Test terrain following in mission''' + self.install_terrain_handlers_context() + + num_wp = self.load_mission("ap-terrain.txt") self.wait_ready_to_arm() self.arm_vehicle() - self.fly_mission("ap-terrain.txt", mission_timeout=600) + global max_alt + max_alt = 0 + + def record_maxalt(mav, m): + global max_alt + if m.get_type() != 'GLOBAL_POSITION_INT': + return + if m.relative_alt/1000.0 > max_alt: + max_alt = m.relative_alt/1000.0 + + self.install_message_hook(record_maxalt) + + self.fly_mission_waypoints(num_wp-1, mission_timeout=600) + + if max_alt < 200: + raise NotAchievedException("Did not follow terrain") def Terrain(self): '''test AP_Terrain''' self.reboot_sitl() # we know the terrain height at CMAC - mavproxy = self.start_mavproxy() + self.install_terrain_handlers_context() self.wait_ready_to_arm() loc = self.mav.location() @@ -2410,8 +2709,10 @@ def Terrain(self): # FIXME: once we have a pre-populated terrain cache this # should require an instantly correct report to pass tstart = self.get_sim_time_cached() + last_terrain_report_pending = -1 while True: - if self.get_sim_time_cached() - tstart > 60: + now = self.get_sim_time_cached() + if now - tstart > 60: raise NotAchievedException("Did not get correct terrain report") self.mav.mav.terrain_check_send(lat_int, lng_int) @@ -2421,6 +2722,14 @@ def Terrain(self): if report.spacing != 0: break + # we will keep trying to long as the number of pending + # tiles is dropping: + if last_terrain_report_pending == -1: + last_terrain_report_pending = report.pending + elif report.pending < last_terrain_report_pending: + last_terrain_report_pending = report.pending + tstart = now + self.delay_sim_time(1) self.progress(self.dump_message_verbose(report)) @@ -2430,10 +2739,9 @@ def Terrain(self): raise NotAchievedException("Expected terrain height=%f got=%f" % (expected_terrain_height, report.terrain_height)) - self.stop_mavproxy(mavproxy) - - def test_loiter_terrain(self): - default_rad = self.get_parameter("WP_LOITER_RAD") + def TerrainLoiter(self): + '''Test terrain following in loiter''' + self.context_push() self.set_parameters({ "TERRAIN_FOLLOW": 1, # enable terrain following in loiter "WP_LOITER_RAD": 2000, # set very large loiter rad to get some terrain changes @@ -2444,26 +2752,18 @@ def test_loiter_terrain(self): self.change_mode("LOITER") self.progress("loitering at %um" % alt) tstart = self.get_sim_time() + timeout = 60*15 # enough time to do one and a bit circles while True: now = self.get_sim_time_cached() - if now - tstart > 60*15: # enough time to do one and a bit circles + if now - tstart > timeout: break - terrain = self.mav.recv_match( - type='TERRAIN_REPORT', - blocking=True, - timeout=1 - ) - if terrain is None: - raise NotAchievedException("Did not get TERRAIN_REPORT message") + terrain = self.assert_receive_message('TERRAIN_REPORT') rel_alt = terrain.current_height self.progress("%um above terrain" % rel_alt) if rel_alt > alt*1.2 or rel_alt < alt * 0.8: raise NotAchievedException("Not terrain following") + self.context_pop() self.progress("Returning home") - self.set_parameters({ - "TERRAIN_FOLLOW": 0, - "WP_LOITER_RAD": default_rad, - }) self.fly_home_land_and_disarm(240) def fly_external_AHRS(self, sim, eahrs_type, mission): @@ -2479,6 +2779,7 @@ def fly_external_AHRS(self, sim, eahrs_type, mission): "INS_GYR_CAL": 1, }) self.reboot_sitl() + self.delay_sim_time(5) self.progress("Running accelcal") self.run_cmd(mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, 0, 0, 0, 0, 4, 0, 0, @@ -2488,10 +2789,12 @@ def fly_external_AHRS(self, sim, eahrs_type, mission): self.arm_vehicle() self.fly_mission(mission) - def test_vectornav(self): + def VectorNavEAHRS(self): + '''Test VectorNav EAHRS support''' self.fly_external_AHRS("VectorNav", 1, "ap1.txt") - def test_lord(self): + def LordEAHRS(self): + '''Test LORD Microstrain EAHRS support''' self.fly_external_AHRS("LORD", 2, "ap1.txt") def get_accelvec(self, m): @@ -2500,7 +2803,8 @@ def get_accelvec(self, m): def get_gyrovec(self, m): return Vector3(m.xgyro, m.ygyro, m.zgyro) * 0.001 * math.degrees(1) - def test_imu_tempcal(self): + def IMUTempCal(self): + '''Test IMU temperature calibration''' self.progress("Setting up SITL temperature profile") self.set_parameters({ "SIM_IMUT1_ENABLE" : 1, @@ -2669,7 +2973,8 @@ def test_imu_tempcal(self): # parameters). So wipe the vehicle's eeprom: self.reset_SITL_commandline() - def ekf_lane_switch(self): + def EKFlaneswitch(self): + '''Test EKF3 Affinity and Lane Switching''' self.context_push() ex = None @@ -2851,7 +3156,7 @@ def fail_speed(): self.context_clear_collection("STATUSTEXT") ################################################################### - self.disarm_vehicle() + self.disarm_vehicle(force=True) except Exception as e: self.print_exception_caught(e) @@ -2867,7 +3172,8 @@ def fail_speed(): if ex is not None: raise ex - def test_fence_alt_ceil_floor(self): + def FenceAltCeilFloor(self): + '''Tests the fence ceiling and floor''' fence_bit = mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE self.set_parameters({ "FENCE_TYPE": 9, # Set fence type to max and min alt @@ -2912,9 +3218,10 @@ def test_fence_alt_ceil_floor(self): self.fly_home_land_and_disarm(timeout=150) - def test_fence_breached_change_mode(self): + def FenceBreachedChangeMode(self): + '''Tests manual mode change after fence breach, as set with FENCE_OPTIONS''' """ Attempts to change mode while a fence is breached. - This should revert to the mode specified by the fence action. """ + mode should change should fail if fence option bit is set""" self.set_parameters({ "FENCE_ACTION": 1, "FENCE_TYPE": 4, @@ -2936,7 +3243,7 @@ def test_fence_breached_change_mode(self): self.wait_ready_to_arm() self.takeoff(alt=50) self.change_mode("CRUISE") - self.wait_distance(90, accuracy=15) + self.wait_distance(250, accuracy=15) self.progress("Enable fence and initiate fence action") self.do_fence_enable() @@ -2944,14 +3251,35 @@ def test_fence_breached_change_mode(self): self.wait_mode("RTL") # We should RTL because of fence breach self.progress("User mode change to cruise should retrigger fence action") - self.change_mode("CRUISE") - self.wait_mode("RTL", timeout=5) + try: + # mode change should time out, 'WaitModeTimeout' exception is the desired resut + # cant wait too long or the vehicle will be inside fence and allow the mode change + self.change_mode("CRUISE", timeout=10) + raise NotAchievedException("Should not change mode in fence breach") + except WaitModeTimeout: + pass + except Exception as e: + raise e + + # enable mode change + self.set_parameter("FENCE_OPTIONS", 0) + self.progress("Check user mode change to LOITER is allowed") + self.change_mode("LOITER") + + # Fly for 20 seconds and make sure still in LOITER mode + self.delay_sim_time(20) + if not self.mode_is("LOITER"): + raise NotAchievedException("Fence should not re-trigger") + + # reset options parameter + self.set_parameter("FENCE_OPTIONS", 1) self.progress("Test complete, disable fence and come home") self.do_fence_disable() self.fly_home_land_and_disarm() - def test_fence_breach_no_return_point(self): + def FenceNoFenceReturnPoint(self): + '''Tests calculated return point during fence breach when no fence return point present''' """ Attempts to change mode while a fence is breached. This should revert to the mode specified by the fence action. """ want_radius = 100 # Fence Return Radius @@ -3026,7 +3354,8 @@ def test_fence_breach_no_return_point(self): self.do_fence_disable() self.fly_home_land_and_disarm() - def test_fence_breach_no_return_point_no_inclusion(self): + def FenceNoFenceReturnPointInclusion(self): + '''Tests using home as fence return point when none is present, and no inclusion fence is uploaded''' """ Test result when a breach occurs and No fence return point is present and no inclusion fence is present and exclusion fence is present """ want_radius = 100 # Fence Return Radius @@ -3074,7 +3403,8 @@ def test_fence_breach_no_return_point_no_inclusion(self): self.do_fence_disable() self.fly_home_land_and_disarm() - def test_fence_disable_under_breach_action(self): + def FenceDisableUnderAction(self): + '''Tests Disabling fence while undergoing action caused by breach''' """ Fence breach will cause the vehicle to enter guided mode. Upon breach clear, check the vehicle is in the expected mode""" self.set_parameters({ @@ -3099,23 +3429,8 @@ def attempt_fence_breached_disable(start_mode, end_mode, expected_mode, action): attempt_fence_breached_disable(start_mode="FBWA", end_mode="FBWA", expected_mode="GUIDED", action=6) attempt_fence_breached_disable(start_mode="FBWA", end_mode="FBWA", expected_mode="GUIDED", action=7) - def run_auxfunc(self, - function, - level, - want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED): - self.run_cmd( - mavutil.mavlink.MAV_CMD_DO_AUX_FUNCTION, - function, # p1 - level, # p2 - 0, # p3 - 0, # p4 - 0, # p5 - 0, # p6 - 0, # p7 - want_result=want_result - ) - - def fly_aux_function(self): + def MAV_DO_AUX_FUNCTION(self): + '''Test triggering Auxiliary Functions via mavlink''' self.context_collect('STATUSTEXT') self.run_auxfunc(64, 2) # 64 == reverse throttle self.wait_statustext("RevThrottle: ENABLE", check_context=True) @@ -3137,7 +3452,8 @@ def fly_aux_function(self): want_result=mavutil.mavlink.MAV_RESULT_DENIED ) - def fly_each_frame(self): + def FlyEachFrame(self): + '''Fly each supported internal frame''' vinfo = vehicleinfo.VehicleInfo() vinfo_options = vinfo.options[self.vehicleinfo_key()] known_broken_frames = { @@ -3185,6 +3501,7 @@ def fly_each_frame(self): self.wait_disarmed() def RCDisableAirspeedUse(self): + '''Test RC DisableAirspeedUse option''' self.set_parameter("RC9_OPTION", 106) self.delay_sim_time(5) self.set_rc(9, 1000) @@ -3207,6 +3524,7 @@ def RCDisableAirspeedUse(self): True) def WatchdogHome(self): + '''Ensure home is restored after watchdog reset''' if self.gdb: # we end up signalling the wrong process. I think. # Probably need to have a "sitl_pid()" method to get the @@ -3260,6 +3578,7 @@ def WatchdogHome(self): raise ex def AUTOTUNE(self): + '''Test AutoTune mode''' self.takeoff(100) self.change_mode('AUTOTUNE') self.context_collect('STATUSTEXT') @@ -3310,8 +3629,8 @@ def AUTOTUNE(self): self.change_mode('FBWA') self.fly_home_land_and_disarm(timeout=tdelta+240) - def fly_landing_baro_drift(self): - + def LandingDrift(self): + '''Circuit with baro drift''' self.customise_SITL_commandline([], wipe=True) self.set_analog_rangefinder_parameters() @@ -3348,6 +3667,7 @@ def fly_landing_baro_drift(self): self.wait_disarmed(timeout=180) def DCMFallback(self): + '''Really annoy the EKF and force fallback''' self.reboot_sitl() self.delay_sim_time(30) self.wait_ready_to_arm() @@ -3372,7 +3692,7 @@ def DCMFallback(self): self.fly_home_land_and_disarm() def ForcedDCM(self): - + '''Switch to DCM mid-flight''' self.wait_ready_to_arm() self.arm_vehicle() @@ -3385,6 +3705,7 @@ def ForcedDCM(self): self.fly_home_land_and_disarm() def MegaSquirt(self): + '''Test MegaSquirt EFI''' self.assert_not_receiving_message('EFI_STATUS') self.set_parameters({ 'SIM_EFI_TYPE': 1, @@ -3402,7 +3723,8 @@ def MegaSquirt(self): if m.intake_manifold_temperature < 20: raise NotAchievedException("Bad intake manifold temperature") - def test_glide_slope_threshold(self): + def GlideSlopeThresh(self): + '''Test rebuild glide slope if above and climbing''' # Test that GLIDE_SLOPE_THRESHOLD correctly controls re-planning glide slope # in the scenario that aircraft is above planned slope and slope is positive (climbing). @@ -3487,279 +3809,255 @@ def test_glide_slope_threshold(self): self.progress("Mission OK") - def tests(self): - '''return list of all tests''' - ret = super(AutoTestPlane, self).tests() - ret.extend([ - - ("AuxModeSwitch", - "Set modes via auxswitches", - self.test_setting_modes_via_auxswitches), - - ("TestRCCamera", - "Test RC Option - Camera Trigger", - self.test_rc_option_camera_trigger), - - ("TestRCRelay", "Test Relay RC Channel Option", self.test_rc_relay), - - ("ThrottleFailsafe", - "Fly throttle failsafe", - self.test_throttle_failsafe), - - ("NeedEKFToArm", - "Ensure we need EKF to be healthy to arm", - self.test_need_ekf_to_arm), - - ("ThrottleFailsafeFence", - "Fly fence survives throttle failsafe", - self.test_throttle_failsafe_fence), - - ("TestFlaps", "Flaps", self.fly_flaps), - - ("DO_CHANGE_SPEED", "Test mavlink DO_CHANGE_SPEED command", self.fly_do_change_speed), - - ("DO_REPOSITION", - "Test mavlink DO_REPOSITION command", - self.fly_do_reposition), - - ("GuidedRequest", - "Test handling of MISSION_ITEM in guided mode", - self.fly_do_guided_request), - - ("MainFlight", - "Lots of things in one flight", - self.test_main_flight), - - ("TestGripperMission", - "Test Gripper mission items", - self.test_gripper_mission), - - ("Parachute", "Test Parachute", self.test_parachute), - - ("ParachuteSinkRate", "Test Parachute (SinkRate triggering)", self.test_parachute_sinkrate), - - ("AIRSPEED_AUTOCAL", "Test AIRSPEED_AUTOCAL", self.airspeed_autocal), - - ("RangeFinder", - "Test RangeFinder Basic Functionality", - self.test_rangefinder), - - ("FenceStatic", - "Test Basic Fence Functionality", - self.test_fence_static), - - ("FenceRTL", - "Test Fence RTL", - self.test_fence_rtl), - - ("FenceRTLRally", - "Test Fence RTL Rally", - self.test_fence_rtl_rally), - - ("FenceRetRally", - "Test Fence Ret_Rally", - self.test_fence_ret_rally), - - ("FenceAltCeilFloor", - "Tests the fence ceiling and floor", - self.test_fence_alt_ceil_floor), - - ("FenceBreachedChangeMode", - "Tests retrigger of fence action when changing of mode while fence is breached", - self.test_fence_breached_change_mode), - - ("FenceNoFenceReturnPoint", - "Tests calculated return point during fence breach when no fence return point present", - self.test_fence_breach_no_return_point), - - ("FenceNoFenceReturnPointInclusion", - "Tests using home as fence return point when none is present, and no inclusion fence is uploaded", - self.test_fence_breach_no_return_point_no_inclusion), - - ("FenceDisableUnderAction", - "Tests Disabling fence while undergoing action caused by breach", - self.test_fence_disable_under_breach_action), - - ("ADSB", - "Test ADSB", - self.test_adsb), - - ("SimADSB", - "Test SIM_ADSB", - self.SimADSB), - - ("Button", - "Test Buttons", - self.test_button), - - ("FRSkySPort", - "Test FrSky SPort mode", - self.test_frsky_sport), - - ("FRSkyPassThrough", - "Test FrSky PassThrough serial output", - self.test_frsky_passthrough), - - ("FRSkyMAVlite", - "Test FrSky MAVlite serial output", - self.test_frsky_mavlite), - - ("FRSkyD", - "Test FrSkyD serial output", - self.test_frsky_d), - - ("LTM", - "Test LTM serial output", - self.test_ltm), - - ("DEVO", - "Test DEVO serial output", - self.DEVO), - - ("AdvancedFailsafe", - "Test Advanced Failsafe", - self.test_advanced_failsafe), - - ("LOITER", - "Test Loiter mode", - self.LOITER), - - ("DeepStall", - "Test DeepStall Landing", - self.fly_deepstall), - - ("WatchdogHome", - "Ensure home is restored after watchdog reset", - self.WatchdogHome), - - ("LargeMissions", - "Test Manipulation of Large missions", - self.test_large_missions), - - ("Soaring", - "Test Soaring feature", - self.fly_soaring), - - ("Terrain", - "Test AP_Terrain", - self.Terrain), - - ("TerrainMission", - "Test terrain following in mission", - self.TerrainMission), - - ("Terrain-loiter", - "Test terrain following in loiter", - self.test_loiter_terrain), - - ("VectorNavEAHRS", - "Test VectorNav EAHRS support", - self.test_vectornav), - - ("LordEAHRS", - "Test LORD Microstrain EAHRS support", - self.test_lord), - - ("Deadreckoning", - "Test deadreckoning support", - self.deadreckoning), - - ("DeadreckoningNoAirSpeed", - "Test deadreckoning support with no airspeed sensor", - self.deadreckoning_no_airspeed_sensor), - - ("EKFlaneswitch", - "Test EKF3 Affinity and Lane Switching", - self.ekf_lane_switch), - - ("AirspeedDrivers", - "Test AirSpeed drivers", - self.test_airspeed_drivers), - - ("RTL_CLIMB_MIN", - "Test RTL_CLIMB_MIN", - self.rtl_climb_min), - - ("ClimbBeforeTurn", - "Test climb-before-turn", - self.climb_before_turn), - - ("IMUTempCal", - "Test IMU temperature calibration", - self.test_imu_tempcal), - - ("MAV_DO_AUX_FUNCTION", - "Test triggering Auxillary Functions via mavlink", - self.fly_aux_function), - - ("SmartBattery", - "Test smart battery logging etc", - self.SmartBattery), - - ("FlyEachFrame", - "Fly each supported internal frame", - self.fly_each_frame), + def MAV_CMD_NAV_LOITER_TURNS(self, target_system=1, target_component=1): + '''test MAV_CMD_NAV_LOITER_TURNS mission item''' + alt = 100 + seq = 0 + items = [] + tests = [ + (self.home_relative_loc_ne(50, -50), 100), + (self.home_relative_loc_ne(100, 50), 1005), + ] + # add a home position: + items.append(self.mav.mav.mission_item_int_encode( + target_system, + target_component, + seq, # seq + mavutil.mavlink.MAV_FRAME_GLOBAL, + mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, + 0, # current + 0, # autocontinue + 0, # p1 + 0, # p2 + 0, # p3 + 0, # p4 + 0, # latitude + 0, # longitude + 0, # altitude + mavutil.mavlink.MAV_MISSION_TYPE_MISSION)) + seq += 1 - ("RCDisableAirspeedUse", - "Test RC DisableAirspeedUse option", - self.RCDisableAirspeedUse), + # add takeoff + items.append(self.mav.mav.mission_item_int_encode( + target_system, + target_component, + seq, # seq + mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, + mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, + 0, # current + 0, # autocontinue + 0, # p1 + 0, # p2 + 0, # p3 + 0, # p4 + 0, # latitude + 0, # longitude + alt, # altitude + mavutil.mavlink.MAV_MISSION_TYPE_MISSION)) + seq += 1 + + # add circles + for (loc, radius) in tests: + items.append(self.mav.mav.mission_item_int_encode( + target_system, + target_component, + seq, # seq + mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, + mavutil.mavlink.MAV_CMD_NAV_LOITER_TURNS, + 0, # current + 0, # autocontinue + 3, # p1 + 0, # p2 + radius, # p3 + 0, # p4 + int(loc.lat*1e7), # latitude + int(loc.lng*1e7), # longitude + alt, # altitude + mavutil.mavlink.MAV_MISSION_TYPE_MISSION)) + seq += 1 + + # add an RTL + items.append(self.mav.mav.mission_item_int_encode( + target_system, + target_component, + seq, # seq + mavutil.mavlink.MAV_FRAME_GLOBAL, + mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, + 0, # current + 0, # autocontinue + 0, # p1 + 0, # p2 + 0, # p3 + 0, # p4 + 0, # latitude + 0, # longitude + 0, # altitude + mavutil.mavlink.MAV_MISSION_TYPE_MISSION)) + seq += 1 + + self.upload_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_MISSION, items) + downloaded_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_MISSION) + ofs = 2 + self.progress("Checking downloaded mission is as expected") + for (loc, radius) in tests: + downloaded = downloaded_items[ofs] + if radius > 255: + # ArduPilot only stores % 10 + radius = radius - radius % 10 + if downloaded.param3 != radius: + raise NotAchievedException( + "Did not get expected radius for item %u; want=%f got=%f" % + (ofs, radius, downloaded.param3)) + ofs += 1 - ("AHRS_ORIENTATION", - "Test AHRS_ORIENTATION parameter", - self.AHRS_ORIENTATION), + self.change_mode('AUTO') + self.wait_ready_to_arm() + self.arm_vehicle() + self.set_parameter("NAVL1_LIM_BANK", 50) - ("AHRSTrim", - "AHRS trim testing", - self.ahrstrim), + self.wait_current_waypoint(2) - ("Landing-Drift", - "Circuit with baro drift", - self.fly_landing_baro_drift), + for (loc, expected_radius) in tests: + self.wait_circling_point_with_radius( + loc, + expected_radius, + epsilon=20.0, + timeout=240, + ) + self.set_current_waypoint(self.current_waypoint()+1) - ("ForcedDCM", - "Switch to DCM mid-flight", - self.ForcedDCM), + self.fly_home_land_and_disarm(timeout=180) - ("DCMFallback", - "Really annoy the EKF and force fallback", - self.DCMFallback), + def MidAirDisarmDisallowed(self): + '''Ensure mid-air disarm is not possible''' + self.takeoff(50) + disarmed = False + try: + self.disarm_vehicle() + disarmed = True + except ValueError as e: + self.progress("Got %s" % repr(e)) + if "Expected MAV_RESULT_ACCEPTED got MAV_RESULT_FAILED" not in str(e): + raise e + if disarmed: + raise NotAchievedException("Disarmed when we shouldn't have") + # should still be able to force-disarm: + self.disarm_vehicle(force=True) + self.reboot_sitl() - ("MAVFTP", - "Test MAVProxy can talk FTP to autopilot", - self.MAVFTP), + def AltResetBadGPS(self): + '''Tests the handling of poor GPS lock pre-arm alt resets''' + self.set_parameters({ + "SIM_GPS_GLITCH_Z": 0, + "SIM_GPS_ACC": 0.3, + }) + self.wait_ready_to_arm() - ("AUTOTUNE", - "Test AutoTune mode", - self.AUTOTUNE), + m = self.assert_receive_message('GLOBAL_POSITION_INT') + relalt = m.relative_alt*0.001 + if abs(relalt) > 3: + raise NotAchievedException("Bad relative alt %.1f" % relalt) - ("MegaSquirt", - "Test MegaSquirt EFI", - self.MegaSquirt), + self.progress("Setting low accuracy, glitching GPS") + self.set_parameter("SIM_GPS_ACC", 40) + self.set_parameter("SIM_GPS_GLITCH_Z", -47) - ("MSP_DJI", - "Test MSP DJI serial output", - self.test_msp_dji), + self.progress("Waiting 10s for height update") + self.delay_sim_time(10) - ("SpeedToFly", - "Test soaring speed-to-fly", - self.fly_soaring_speed_to_fly), + self.wait_ready_to_arm() + self.arm_vehicle() - ("GlideSlopeThresh", - "Test rebuild glide slope if above and climbing", - self.test_glide_slope_threshold), + m = self.assert_receive_message('GLOBAL_POSITION_INT') + relalt = m.relative_alt*0.001 + if abs(relalt) > 3: + raise NotAchievedException("Bad glitching relative alt %.1f" % relalt) - ("LogUpload", - "Log upload", - self.log_upload), + self.disarm_vehicle() + # reboot to clear potentially bad state + self.reboot_sitl() - ("HIGH_LATENCY2", - "Set sending of HIGH_LATENCY2", - self.HIGH_LATENCY2), + def tests(self): + '''return list of all tests''' + ret = super(AutoTestPlane, self).tests() + ret.extend([ + self.AuxModeSwitch, + self.TestRCCamera, + self.TestRCRelay, + self.ThrottleFailsafe, + self.NeedEKFToArm, + self.ThrottleFailsafeFence, + self.TestFlaps, + self.DO_CHANGE_SPEED, + self.DO_REPOSITION, + self.GuidedRequest, + self.MainFlight, + self.TestGripperMission, + self.Parachute, + self.ParachuteSinkRate, + self.PitotBlockage, + self.AIRSPEED_AUTOCAL, + self.RangeFinder, + self.FenceStatic, + self.FenceRTL, + self.FenceRTLRally, + self.FenceRetRally, + self.FenceAltCeilFloor, + self.FenceBreachedChangeMode, + self.FenceNoFenceReturnPoint, + self.FenceNoFenceReturnPointInclusion, + self.FenceDisableUnderAction, + self.ADSB, + self.SimADSB, + self.Button, + self.FRSkySPort, + self.FRSkyPassThroughStatustext, + self.FRSkyPassThroughSensorIDs, + self.FRSkyMAVlite, + self.FRSkyD, + self.LTM, + self.DEVO, + self.AdvancedFailsafe, + self.LOITER, + self.MAV_CMD_NAV_LOITER_TURNS, + self.DeepStall, + self.WatchdogHome, + self.LargeMissions, + self.Soaring, + self.Terrain, + self.TerrainMission, + self.TerrainLoiter, + self.VectorNavEAHRS, + self.LordEAHRS, + self.Deadreckoning, + self.DeadreckoningNoAirSpeed, + self.EKFlaneswitch, + self.AirspeedDrivers, + self.RTL_CLIMB_MIN, + self.ClimbBeforeTurn, + self.IMUTempCal, + self.MAV_DO_AUX_FUNCTION, + self.SmartBattery, + self.FlyEachFrame, + self.RCDisableAirspeedUse, + self.AHRS_ORIENTATION, + self.AHRSTrim, + self.LandingDrift, + self.ForcedDCM, + self.DCMFallback, + self.MAVFTP, + self.AUTOTUNE, + self.MegaSquirt, + self.MSP_DJI, + self.SpeedToFly, + self.GlideSlopeThresh, + self.HIGH_LATENCY2, + self.MidAirDisarmDisallowed, + self.AltResetBadGPS, ]) return ret def disabled_tests(self): return { - "Terrain-loiter": "Loading of terrain data is not reliable", - "Landing-Drift": "Flapping test. See https://github.com/ArduPilot/ardupilot/issues/20054", + "LandingDrift": "Flapping test. See https://github.com/ArduPilot/ardupilot/issues/20054", } diff --git a/Tools/autotest/ardusub.py b/Tools/autotest/ardusub.py index 8f2a46839d6..ef3bfc9d6d2 100644 --- a/Tools/autotest/ardusub.py +++ b/Tools/autotest/ardusub.py @@ -1,5 +1,3 @@ -#!/usr/bin/env python - ''' Dive ArduSub in SITL @@ -81,7 +79,7 @@ def default_frame(self): def is_sub(self): return True - def watch_altitude_maintained(self, delta=1, timeout=5.0): + def watch_altitude_maintained(self, delta=0.3, timeout=5.0): """Watch and wait for the actual altitude to be maintained Keyword Arguments: @@ -105,9 +103,8 @@ def watch_altitude_maintained(self, delta=1, timeout=5.0): "Altitude not maintained: want %.2f (+/- %.2f) got=%.2f" % (previous_altitude, delta, m.alt)) - def test_alt_hold(self): - """Test ALT_HOLD mode - """ + def AltitudeHold(self): + """Test ALT_HOLD mode""" self.wait_ready_to_arm() self.arm_vehicle() self.change_mode('ALT_HOLD') @@ -115,10 +112,10 @@ def test_alt_hold(self): msg = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True, timeout=5) if msg is None: raise NotAchievedException("Did not get GLOBAL_POSITION_INT") - pwm = 1000 - if msg.relative_alt/1000.0 < -5.5: + pwm = 1300 + if msg.relative_alt/1000.0 < -6.0: # need to g`o up, not down! - pwm = 2000 + pwm = 1700 self.set_rc(Joystick.Throttle, pwm) self.wait_altitude(altitude_min=-6, altitude_max=-5) self.set_rc(Joystick.Throttle, 1500) @@ -152,12 +149,24 @@ def test_alt_hold(self): # let the vehicle settle (momentum / stopping point shenanigans....) self.delay_sim_time(1) + self.watch_altitude_maintained() + # Make sure the code can handle buoyancy changes + self.set_parameter("SIM_BUOYANCY", 10) + self.watch_altitude_maintained() + self.set_parameter("SIM_BUOYANCY", -10) self.watch_altitude_maintained() + # Make sure that the ROV will dive with a small input down even if there is a 10N buoyancy force upwards + self.set_parameter("SIM_BUOYANCY", 10) + self.set_rc(Joystick.Throttle, 1350) + self.wait_altitude(altitude_min=-6, altitude_max=-5.5) + + self.set_rc(Joystick.Throttle, 1500) + self.watch_altitude_maintained() self.disarm_vehicle() - def test_pos_hold(self): + def PositionHold(self): """Test POSHOLD mode""" self.wait_ready_to_arm() self.arm_vehicle() @@ -203,9 +212,8 @@ def test_pos_hold(self): raise NotAchievedException("Position Hold was unable to move north 2 meters, moved {} at {} degrees instead".format(distance_m, bearing)) # noqa self.disarm_vehicle() - def test_mot_thst_hover_ignore(self): - """Test if we are ignoring MOT_THST_HOVER parameter - """ + def MotorThrustHoverParameterIgnore(self): + """Test if we are ignoring MOT_THST_HOVER parameter""" # Test default parameter value mot_thst_hover_value = self.get_parameter("MOT_THST_HOVER") @@ -215,9 +223,10 @@ def test_mot_thst_hover_ignore(self): # Test if parameter is being ignored for value in [0.25, 0.75]: self.set_parameter("MOT_THST_HOVER", value) - self.test_alt_hold() + self.AltitudeHold() - def dive_manual(self): + def DiveManual(self): + '''Dive manual''' self.wait_ready_to_arm() self.arm_vehicle() @@ -249,7 +258,9 @@ def dive_manual(self): if m.temperature != 2650: raise NotAchievedException("Did not get correct TSYS01 temperature") - def dive_mission(self, filename): + def DiveMission(self): + '''Dive mission''' + filename = "sub_mission.txt" self.progress("Executing mission %s" % filename) self.load_mission(filename) self.set_rc_default() @@ -264,7 +275,8 @@ def dive_mission(self, filename): self.progress("Mission OK") - def test_gripper_mission(self): + def GripperMission(self): + '''Test gripper mission items''' try: self.get_parameter("GRIP_ENABLE", timeout=5) except NotAchievedException: @@ -279,7 +291,8 @@ def test_gripper_mission(self): self.wait_statustext("Gripper Grabbed", timeout=60) self.wait_statustext("Gripper Released", timeout=60) - def dive_set_position_target(self): + def SET_POSITION_TARGET_GLOBAL_INT(self): + '''Move vehicle using SET_POSITION_TARGET_GLOBAL_INT''' self.change_mode('GUIDED') self.wait_ready_to_arm() self.arm_vehicle() @@ -366,6 +379,7 @@ def reboot_sitl(self): self.initialise_after_reboot_sitl() def DoubleCircle(self): + '''Test entering circle twice''' self.change_mode('CIRCLE') self.wait_ready_to_arm() self.arm_vehicle() @@ -390,36 +404,15 @@ def tests(self): ret = super(AutoTestSub, self).tests() ret.extend([ - ("DiveManual", "Dive manual", self.dive_manual), - - ("AltitudeHold", "Test altitude holde mode", self.test_alt_hold), - ("PositionHold", "Test position hold mode", self.test_pos_hold), - - ("DiveMission", - "Dive mission", - lambda: self.dive_mission("sub_mission.txt")), - - ("GripperMission", - "Test gripper mission items", - self.test_gripper_mission), - - ("DoubleCircle", - "Test entering circle twice", - self.DoubleCircle), - - ("MotorThrustHoverParameterIgnore", "Test if we are ignoring MOT_THST_HOVER", self.test_mot_thst_hover_ignore), - - ("SET_POSITION_TARGET_GLOBAL_INT", - "Move vehicle using SET_POSITION_TARGET_GLOBAL_INT", - self.dive_set_position_target), - - ("TestLogDownloadMAVProxy", - "Test Onboard Log Download using MAVProxy", - self.test_log_download_mavproxy), - - ("LogUpload", - "Upload logs", - self.log_upload), + self.DiveManual, + self.AltitudeHold, + self.PositionHold, + self.DiveMission, + self.GripperMission, + self.DoubleCircle, + self.MotorThrustHoverParameterIgnore, + self.SET_POSITION_TARGET_GLOBAL_INT, + self.TestLogDownloadMAVProxy, ]) return ret diff --git a/Tools/autotest/autotest.py b/Tools/autotest/autotest.py index 5e45c0eff84..6a9aed6bc60 100755 --- a/Tools/autotest/autotest.py +++ b/Tools/autotest/autotest.py @@ -9,6 +9,12 @@ from __future__ import print_function import atexit import fnmatch +import copy +try: + import distutils.dir_util +except ImportError: + # we copy with this with try/except in copy_tree, below + pass import glob import optparse import os @@ -19,7 +25,6 @@ import sys import time import traceback -from distutils.dir_util import copy_tree import rover import arducopter @@ -40,6 +45,8 @@ tester = None +build_opts = None + def buildlogs_dirpath(): """Return BUILDLOGS directory path.""" @@ -305,14 +312,12 @@ def should_run_step(step): __bin_names = { "Copter": "arducopter", - "CopterTests1": "arducopter", "CopterTests1a": "arducopter", "CopterTests1b": "arducopter", "CopterTests1c": "arducopter", "CopterTests1d": "arducopter", "CopterTests1e": "arducopter", - "CopterTests2": "arducopter", "CopterTests2a": "arducopter", "CopterTests2b": "arducopter", @@ -381,13 +386,11 @@ def find_specific_test_to_run(step): tester_class_map = { "test.Copter": arducopter.AutoTestCopter, - "test.CopterTests1": arducopter.AutoTestCopterTests1, # travis-ci "test.CopterTests1a": arducopter.AutoTestCopterTests1a, # 8m43s "test.CopterTests1b": arducopter.AutoTestCopterTests1b, # 8m5s "test.CopterTests1c": arducopter.AutoTestCopterTests1c, # 5m17s "test.CopterTests1d": arducopter.AutoTestCopterTests1d, # 8m20s "test.CopterTests1e": arducopter.AutoTestCopterTests1e, # 8m32s - "test.CopterTests2": arducopter.AutoTestCopterTests2, # travis-ci "test.CopterTests2a": arducopter.AutoTestCopterTests2a, # 8m23s "test.CopterTests2b": arducopter.AutoTestCopterTests2b, # 8m18s "test.Plane": arduplane.AutoTestPlane, @@ -419,11 +422,11 @@ def run_specific_test(step, *args, **kwargs): print("Got %s" % str(tester)) for a in tester.tests(): - if not hasattr(a, 'name'): - a = Test(a[0], a[1], a[2]) + if type(a) != Test: + a = Test(a) print("Got %s" % (a.name)) if a.name == test: - return tester.run_tests([a]) + return (tester.autotest(tests=[a], allow_skips=False), tester) print("Failed to find test %s on %s" % (test, testname)) sys.exit(1) @@ -447,11 +450,15 @@ def run_step(step): "extra_configure_args": opts.waf_configure_args, "coverage": opts.coverage, "sitl_32bit" : opts.sitl_32bit, + "ubsan" : opts.ubsan, + "ubsan_abort" : opts.ubsan_abort, } if opts.Werror: build_opts['extra_configure_args'].append("--Werror") + build_opts = build_opts + vehicle_binary = None if step == 'build.Plane': vehicle_binary = 'bin/arduplane' @@ -531,6 +538,7 @@ def run_step(step): "logs_dir": buildlogs_dirpath(), "sup_binaries": supplementary_binaries, "reset_after_every_test": opts.reset_after_every_test, + "build_opts": copy.copy(build_opts), } if opts.speedup is not None: fly_opts["speedup"] = opts.speedup @@ -657,6 +665,13 @@ def generate_badge(self): f.write(badge) +def copy_tree(f, t, dirs_exist_ok=False): + try: + distutils.dir_util.copy_tree(f, t) + except Exception: + shutil.copytree(f, t, dirs_exist_ok=dirs_exist_ok) + + def write_webresults(results_to_write): """Write webpage results.""" t = mavtemplate.MAVTemplate() @@ -667,7 +682,7 @@ def write_webresults(results_to_write): f.close() for f in glob.glob(util.reltopdir('Tools/autotest/web/*.png')): shutil.copy(f, buildlogs_path(os.path.basename(f))) - copy_tree(util.reltopdir("Tools/autotest/web/css"), buildlogs_path("css")) + copy_tree(util.reltopdir("Tools/autotest/web/css"), buildlogs_path("css"), dirs_exist_ok=True) results_to_write.generate_badge() @@ -781,8 +796,7 @@ def run_tests(steps): print(" %s:" % key) for testinstance in failed_testinstances[key]: for failure in testinstance.fail_list: - (desc, exception, debug_filename) = failure - print(" %s (%s) (see %s)" % (desc, exception, debug_filename)) + print(" " + str(failure)) print("FAILED %u tests: %s" % (len(failed), failed)) @@ -828,11 +842,9 @@ def list_subtests_for_vehicle(vehicle_type): subtests = tester.tests() sorted_list = [] for subtest in subtests: - if type(subtest) is tuple: - (name, description, function) = subtest - sorted_list.append([name, description]) - else: - sorted_list.append([subtest.name, subtest.description]) + if type(subtest) != Test: + subtest = Test(subtest) + sorted_list.append([subtest.name, subtest.description]) sorted_list.sort() for subtest in sorted_list: print("%s " % subtest[0], end='') @@ -959,6 +971,16 @@ def format_epilog(self, formatter): action='store_true', dest="sitl_32bit", help="compile sitl using 32-bit") + group_build.add_option("", "--ubsan", + default=False, + action='store_true', + dest="ubsan", + help="compile sitl with undefined behaviour sanitiser") + group_build.add_option("", "--ubsan-abort", + default=False, + action='store_true', + dest="ubsan_abort", + help="compile sitl with undefined behaviour sanitiser and abort on error") parser.add_option_group(group_build) group_sim = optparse.OptionGroup(parser, "Simulation options") @@ -1094,18 +1116,17 @@ def format_epilog(self, formatter): 'build.SITLPeriphGPS', 'test.CAN', - 'convertgpx', + # convertgps disabled as it takes 5 hours + # 'convertgpx', ] moresteps = [ - 'test.CopterTests1', 'test.CopterTests1a', 'test.CopterTests1b', 'test.CopterTests1c', 'test.CopterTests1d', 'test.CopterTests1e', - 'test.CopterTests2', 'test.CopterTests2a', 'test.CopterTests2b', @@ -1136,14 +1157,12 @@ def format_epilog(self, formatter): "defaults.ArduSub": "defaults.Sub", "defaults.APMrover2": "defaults.Rover", "defaults.AntennaTracker": "defaults.Tracker", - "fly.ArduCopterTests1": "test.CopterTests1", "fly.ArduCopterTests1a": "test.CopterTests1a", "fly.ArduCopterTests1b": "test.CopterTests1b", "fly.ArduCopterTests1c": "test.CopterTests1c", "fly.ArduCopterTests1d": "test.CopterTests1d", "fly.ArduCopterTests1e": "test.CopterTests1e", - "fly.ArduCopterTests2": "test.CopterTests2", "fly.ArduCopterTests2a": "test.CopterTests2a", "fly.ArduCopterTests2b": "test.CopterTests2b", diff --git a/Tools/autotest/balancebot.py b/Tools/autotest/balancebot.py index 820298fa2d4..efeb4875109 100644 --- a/Tools/autotest/balancebot.py +++ b/Tools/autotest/balancebot.py @@ -1,5 +1,3 @@ -#!/usr/bin/env python - ''' Drive a BalanceBot in SITL @@ -20,12 +18,11 @@ testdir = os.path.dirname(os.path.realpath(__file__)) -def log_name(self): - return "BalanceBot" - - class AutoTestBalanceBot(AutoTestRover): + def log_name(self): + return "BalanceBot" + def vehicleinfo_key(self): return "Rover" @@ -34,7 +31,8 @@ def init(self): self.frame = 'balancebot' super(AutoTestBalanceBot, self).init() - def test_do_set_mode_via_command_long(self): + def DO_SET_MODE(self): + '''Set mode via MAV_COMMAND_DO_SET_MODE''' self.do_set_mode_via_command_long("HOLD") self.do_set_mode_via_command_long("MANUAL") @@ -51,17 +49,17 @@ def drive_rtl_mission_max_distance_from_home(self): '''balancebot tends to wander backwards, away from the target''' return 8 - def drive_rtl_mission(self): + def DriveRTL(self): + '''Drive an RTL Mission''' # if we Hold then the balancebot continues to wander # indefinitely at ~1m/s, hence we set to Acro self.set_parameter("MIS_DONE_BEHAVE", 2) - super(AutoTestBalanceBot, self).drive_rtl_mission() + super(AutoTestBalanceBot, self).DriveRTL() - def test_wheelencoders(self): + def TestWheelEncoder(self): '''make sure wheel encoders are generally working''' ex = None try: - self.set_parameter("ATC_BAL_SPD_FF", 0) self.set_parameter("WENC_TYPE", 10) self.set_parameter("AHRS_EKF_TYPE", 10) self.reboot_sitl() @@ -98,6 +96,10 @@ def test_wheelencoders(self): if ex is not None: raise ex + def DriveMission(self): + '''Drive Mission rover1.txt''' + self.drive_mission("balancebot1.txt", strict=False) + def tests(self): '''return list of all tests''' @@ -106,32 +108,12 @@ def tests(self): ret = AutoTest.tests(self) ret.extend([ - - ("DriveRTL", - "Drive an RTL Mission", - self.drive_rtl_mission), - - ("DriveMission", - "Drive Mission %s" % "balancebot1.txt", - lambda: self.drive_mission("balancebot1.txt", strict=False)), - - ("TestWheelEncoder", - "Test wheel encoders", - self.test_wheelencoders), - - ("GetBanner", "Get Banner", self.do_get_banner), - - ("DO_SET_MODE", - "Set mode via MAV_COMMAND_DO_SET_MODE", - self.test_do_set_mode_via_command_long), - - ("ServoRelayEvents", - "Test ServoRelayEvents", - self.test_servorelayevents), - - ("LogUpload", - "Upload logs", - self.log_upload), + self.DriveRTL, + self.DriveMission, + self.TestWheelEncoder, + self.GetBanner, + self.DO_SET_MODE, + self.ServoRelayEvents, ]) return ret diff --git a/Tools/autotest/build-with-disabled-features.py b/Tools/autotest/build-with-disabled-features.py index 22e8189857e..4b467c023d0 100755 --- a/Tools/autotest/build-with-disabled-features.py +++ b/Tools/autotest/build-with-disabled-features.py @@ -19,7 +19,7 @@ >>>> PASSED STEP: build.ArduCopter at Thu Feb 22 09:46:43 2018 check step: build.ArduCopter BWFD: ADVANCED_FAILSAFE OK -BWFD: Successes: ['MOUNT', 'AUTOTUNE_ENABLED', 'AC_FENCE', 'CAMERA', 'RANGEFINDER_ENABLED', 'PROXIMITY_ENABLED', 'AC_RALLY', 'AC_AVOID_ENABLED', 'PARACHUTE', 'NAV_GUIDED', 'OPTFLOW', 'VISUAL_ODOMETRY_ENABLED', 'FRSKY_TELEM_ENABLED', 'ADSB_ENABLED', 'PRECISION_LANDING', 'SPRAYER', 'WINCH_ENABLED', 'ADVANCED_FAILSAFE'] +BWFD: Successes: ['MOUNT', 'AUTOTUNE_ENABLED', 'AP_FENCE_ENABLED', 'CAMERA', 'RANGEFINDER_ENABLED', 'PROXIMITY_ENABLED', 'AC_RALLY', 'AC_AVOID_ENABLED', 'PARACHUTE', 'NAV_GUIDED', 'OPTFLOW', 'VISUAL_ODOMETRY_ENABLED', 'ADSB_ENABLED', 'PRECISION_LANDING', 'SPRAYER', 'WINCH_ENABLED', 'ADVANCED_FAILSAFE'] BWFD: Failures: ['LOGGING_ENABLED'] pbarker@bluebottle:~/rc/ardupilot(build-with-disabled-features)$ q @@ -205,7 +205,7 @@ def get_config_variables(self): "autotest_target": "build.Copter", "target_binary": "bin/arducopter", "reverse-deps": { - "AC_FENCE": ["AC_AVOID_ENABLED", "MODE_FOLLOW_ENABLED"], + "AP_FENCE_ENABLED": ["AC_AVOID_ENABLED", "MODE_FOLLOW_ENABLED"], "PROXIMITY_ENABLED": ["AC_AVOID_ENABLED", "MODE_FOLLOW_ENABLED"], "MODE_AUTO_ENABLED": ["MODE_GUIDED", "ADVANCED_FAILSAFE"], "MODE_RTL_ENABLED": ["MODE_AUTO_ENABLED", "MODE_SMARTRTL_ENABLED"], @@ -226,7 +226,7 @@ def get_config_variables(self): "MODE_ACRO_ENABLED", "AUTOTUNE_ENABLED"], "reverse-deps": { - "AC_FENCE": ["AC_AVOID_ENABLED", "MODE_FOLLOW_ENABLED"], + "AP_FENCE_ENABLED": ["AC_AVOID_ENABLED", "MODE_FOLLOW_ENABLED"], "PROXIMITY_ENABLED": ["AC_AVOID_ENABLED", "MODE_FOLLOW_ENABLED"], "MODE_AUTO_ENABLED": ["MODE_GUIDED", "ADVANCED_FAILSAFE"], "MODE_RTL_ENABLED": ["MODE_AUTO_ENABLED", "MODE_SMARTRTL_ENABLED"], @@ -256,7 +256,7 @@ def get_config_variables(self): "autotest_target": "build.Sub", "target_binary": "bin/ardusub", "reverse-deps": { - "AC_FENCE": ["AVOIDANCE_ENABLED"], + "AP_FENCE_ENABLED": ["AVOIDANCE_ENABLED"], "PROXIMITY_ENABLED": ["AVOIDANCE_ENABLED"], }, }, { diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index 358d6b09e96..16aa49a89ae 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -14,6 +14,7 @@ import os import re import shutil +import signal import sys import time import traceback @@ -29,6 +30,7 @@ import enum from MAVProxy.modules.lib import mp_util +from MAVProxy.modules.lib import mp_elevation from pymavlink import mavparm from pymavlink import mavwp, mavutil, DFReader @@ -1433,11 +1435,37 @@ def __init__(self, lat, lon, alt, yaw): class Test(object): '''a test definition - information about a test''' - def __init__(self, name, description, function, attempts=1): - self.name = name - self.description = description + def __init__(self, function, attempts=1, speedup=None): + self.name = function.__name__ + self.description = function.__doc__ + if self.description is None: + raise ValueError("%s is missing a docstring" % self.name) self.function = function self.attempts = attempts + self.speedup = speedup + + +class Result(object): + '''a test result - pass, fail, exception, runtime, ....''' + def __init__(self, test): + self.test = test + self.reason = None + self.exception = None + self.debug_filename = None + # self.passed = False + + def __str__(self): + ret = " %s (%s)" % (self.test.name, self.test.description) + if self.passed: + return ret + " OK" + if self.reason is not None: + ret += " (" + self.reason + ")" + if self.exception is not None: + ret += " (" + str(self.exception) + ")" + if self.debug_filename is not None: + ret += " (see " + self.debug_filename + ")" + + return ret class AutoTest(ABC): @@ -1465,11 +1493,12 @@ def __init__(self, replay=False, sup_binaries=[], reset_after_every_test=False, - sitl_32bit=False): + sitl_32bit=False, + ubsan=False, + ubsan_abort=False, + build_opts={}): self.start_time = time.time() - global __autotest__ # FIXME; make progress a non-staticmethod - __autotest__ = self if binary is None: raise ValueError("Should always have a binary") @@ -1491,6 +1520,9 @@ def __init__(self, self.sup_binaries = sup_binaries self.reset_after_every_test = reset_after_every_test self.sitl_32bit = sitl_32bit + self.ubsan = ubsan + self.ubsan_abort = ubsan_abort + self.build_opts = build_opts self.mavproxy = None self._mavproxy = None # for auto-cleanup on failed tests @@ -1505,7 +1537,6 @@ def __init__(self, self.max_set_rc_timeout = 0 self.last_wp_load = 0 self.forced_post_test_sitl_reboots = 0 - self.skip_list = [] self.run_tests_called = False self._show_test_timings = _show_test_timings self.test_timings = dict() @@ -1534,6 +1565,17 @@ def __init__(self, self.last_sim_time_cached = 0 self.last_sim_time_cached_wallclock = 0 + # to autopilot we do not want to go to the internet for tiles, + # usually. Set this to False to gather tiles from internet in + # the cae there are new tiles required, then add them to the + # repo and set this back to false: + self.terrain_in_offline_mode = True + self.elevationmodel = mp_elevation.ElevationModel( + cachedir=util.reltopdir("Tools/autotest/tilecache/srtm"), + offline=self.terrain_in_offline_mode + ) + self.terrain_data_messages_sent = 0 # count of messages back + def __del__(self): if self.rc_thread is not None: self.progress("Joining RC thread in __del__") @@ -1546,8 +1588,7 @@ def default_speedup(self): def progress(self, text, send_statustext=True): """Display autotest progress text.""" - global __autotest__ - delta_time = time.time() - __autotest__.start_time + delta_time = time.time() - self.start_time formatted_text = "AT-%06.1f: %s" % (delta_time, text) print(formatted_text) if (send_statustext and @@ -1829,6 +1870,33 @@ def run_cmd_reboot(self): 0, 0) + def run_cmd_run_prearms(self): + self.run_cmd(mavutil.mavlink.MAV_CMD_RUN_PREARM_CHECKS, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0) + + def run_cmd_enable_high_latency(self, new_state): + p1 = 0 + if new_state: + p1 = 1 + + self.run_cmd( + mavutil.mavlink.MAV_CMD_CONTROL_HIGH_LATENCY, + p1, # p1 - enable/disable + 0, # p2 + 0, # p3 + 0, # p4 + 0, # p5 + 0, # p6 + 0, # p7 + ) + def reboot_sitl_mav(self, required_bootcount=None): """Reboot SITL instance using mavlink and wait for it to reconnect.""" # we must make sure that stats have been reset - otherwise @@ -1844,6 +1912,7 @@ def reboot_sitl_mav(self, required_bootcount=None): old_bootcount = self.get_parameter('STAT_BOOTCNT') # ardupilot SITL may actually NAK the reboot; replace with # run_cmd when we don't do that. + do_context = False if self.valgrind or self.callgrind: self.reboot_check_valgrind_log() self.progress("Stopping and restarting SITL") @@ -1857,10 +1926,37 @@ def reboot_sitl_mav(self, required_bootcount=None): self.stop_SITL() self.start_SITL(wipe=False) else: - self.progress("Executing reboot command") - self.run_cmd_reboot() + # receiving an ACK from the process turns out to be really + # quite difficult. So just send it and hope for the best. + self.progress("Sending reboot command") + self.send_cmd( + mavutil.mavlink.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, + 1, + 1, + 0, + 0, + 0, + 0, + 0) + do_context = True + if do_context: + self.context_push() + + def hook(mav, m): + if m.get_type() != 'COMMAND_ACK': + return + if m.command != mavutil.mavlink.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN: + return + self.progress("While awaiting reboot received (%s)" % str(m)) + if m.result != mavutil.mavlink.MAV_RESULT_ACCEPTED: + raise NotAchievedException("Bad reboot ACK detected") + self.install_message_hook_context(hook) + self.detect_and_handle_reboot(old_bootcount, required_bootcount=required_bootcount) + if do_context: + self.context_pop() + def send_cmd_enter_cpu_lockup(self): """Poke ArduPilot to stop the main loop from running""" self.mav.mav.command_long_send(self.sysid_thismav(), @@ -1993,12 +2089,15 @@ def htree_from_xml(self, xml_filepath): htree[n] = p return htree - def test_adsb_send_threatening_adsb_message(self, here): + def test_adsb_send_threatening_adsb_message(self, here, offset_ne=None): self.progress("Sending ABSD_VEHICLE message") + new = here + if offset_ne is not None: + new = self.offset_location_ne(new, offset_ne[0], offset_ne[1]) self.mav.mav.adsb_vehicle_send( 37, # ICAO address - int(here.lat * 1e7), - int(here.lng * 1e7), + int(new.lat * 1e7), + int(new.lng * 1e7), mavutil.mavlink.ADSB_ALTITUDE_TYPE_PRESSURE_QNH, int(here.alt*1000 + 10000), # 10m up 0, # heading in cdeg @@ -2105,74 +2204,95 @@ def all_log_format_ids(self): structure_lines = [] for f in structure_files: structure_lines.extend(open(f).readlines()) - ids = {} - state_outside = 0 - state_inside = 1 - state = state_outside defines = self.find_format_defines(structure_lines) - linestate_none = 45 - linestate_within = 46 - linestate = linestate_none + ids = {} message_infos = [] - for line in structure_lines: - # print("line: %s" % line) - if type(line) == bytes: - line = line.decode("utf-8") - line = re.sub("//.*", "", line) # trim comments - if re.match(r"\s*$", line): - # blank line - continue - if state == state_outside: - if ("#define LOG_COMMON_STRUCTURES" in line or - re.match("#define LOG_STRUCTURE_FROM_.*", line)): - # self.progress("Moving inside") - state = state_inside - continue - if state == state_inside: - if linestate == linestate_none: - allowed_list = ['LOG_STRUCTURE_FROM_'] - - allowed = False - for a in allowed_list: - if a in line: - allowed = True - if allowed: - continue - m = re.match(r"\s*{(.*)},\s*", line) - if m is not None: - # complete line - # print("Complete line: %s" % str(line)) - message_infos.append(m.group(1)) - continue - m = re.match(r"\s*{(.*)\\", line) - if m is None: - state = state_outside - continue - partial_line = m.group(1) - linestate = linestate_within + for f in structure_files: + self.progress("structure file: %s" % f) + state_outside = 0 + state_inside = 1 + state = state_outside + + linestate_none = 45 + linestate_within = 46 + linestate = linestate_none + debug = False + if f == "/home/pbarker/rc/ardupilot/libraries/AP_HAL_ChibiOS/LogStructure.h": + debug = True + for line in open(f).readlines(): + if debug: + print("line: %s" % line) + if type(line) == bytes: + line = line.decode("utf-8") + line = re.sub("//.*", "", line) # trim comments + if re.match(r"\s*$", line): + # blank line continue - if linestate == linestate_within: - m = re.match("(.*)}", line) - if m is None: - line = line.rstrip() - newline = re.sub(r"\\$", "", line) - if newline == line: - raise NotAchievedException("Expected backslash at end of line") - line = newline - line = line.rstrip() - # cpp-style string concatenation: - line = re.sub(r'"\s*"', '', line) - partial_line += line - continue - message_infos.append(partial_line + m.group(1)) - linestate = linestate_none + if state == state_outside: + if ("#define LOG_COMMON_STRUCTURES" in line or + re.match("#define LOG_STRUCTURE_FROM_.*", line)): + if debug: + self.progress("Moving inside") + state = state_inside continue - raise NotAchievedException("Bad line (%s)") + if state == state_inside: + if linestate == linestate_none: + allowed_list = ['LOG_STRUCTURE_FROM_'] + + allowed = False + for a in allowed_list: + if a in line: + allowed = True + if allowed: + continue + m = re.match(r"\s*{(.*)},\s*", line) + if m is not None: + # complete line + if debug: + print("Complete line: %s" % str(line)) + message_infos.append(m.group(1)) + continue + m = re.match(r"\s*{(.*)\\", line) + if m is None: + if debug: + self.progress("Moving outside") + state = state_outside + continue + partial_line = m.group(1) + if debug: + self.progress("partial line") + linestate = linestate_within + continue + if linestate == linestate_within: + if debug: + self.progress("Looking for close-brace") + m = re.match("(.*)}", line) + if m is None: + if debug: + self.progress("no close-brace") + line = line.rstrip() + newline = re.sub(r"\\$", "", line) + if newline == line: + raise NotAchievedException("Expected backslash at end of line") + line = newline + line = line.rstrip() + # cpp-style string concatenation: + if debug: + self.progress("more partial line") + line = re.sub(r'"\s*"', '', line) + partial_line += line + continue + if debug: + self.progress("found close-brace") + message_infos.append(partial_line + m.group(1)) + linestate = linestate_none + continue + raise NotAchievedException("Bad line (%s)") - if linestate != linestate_none: - raise NotAchievedException("Must be linestate-none at end of file") + if linestate != linestate_none: + raise NotAchievedException("Must be linestate-none at end of file") # now look in the vehicle-specific logfile: filepath = os.path.join(self.vehicle_code_dirpath(), "Log.cpp") @@ -2243,10 +2363,12 @@ def all_log_format_ids(self): raise NotAchievedException("Should not be in state_inside at end") for message_info in message_infos: + print("message_info: %s" % str(message_info)) for define in defines: message_info = re.sub(define, defines[define], message_info) - m = re.match(r'\s*LOG_\w+\s*,\s*sizeof\([^)]+\)\s*,\s*"(\w+)"\s*,\s*"(\w+)"\s*,\s*"([\w,]+)"\s*,\s*"([^"]+)"\s*,\s*"([^"]+)"\s*(,\s*true)?\s*$', message_info) # noqa + m = re.match(r'\s*LOG_\w+\s*,\s*sizeof\([^)]+\)\s*,\s*"(\w+)"\s*,\s*"(\w+)"\s*,\s*"([\w,]+)"\s*,\s*"([^"]+)"\s*,\s*"([^"]+)"\s*(,\s*(true|false))?\s*$', message_info) # noqa if m is None: + print("NO MATCH") continue (name, fmt, labels, units, multipliers) = (m.group(1), m.group(2), m.group(3), m.group(4), m.group(5)) if name in ids: @@ -2290,6 +2412,8 @@ def all_log_format_ids(self): continue if state == state_inside: line = re.sub("//.*", "", line) # trim comments + # cpp-style string concatenation: + line = re.sub(r'"\s*"', '', line) log_write_statement += line if re.match(r".*\);", line): log_write_statements.append(log_write_statement) @@ -2332,8 +2456,8 @@ def all_log_format_ids(self): return ids - def test_onboard_logging_generation(self): - '''just generates, as we can't do a lot of testing''' + def LoggerDocumentation(self): + '''Test Onboard Logging Generation''' xml_filepath = os.path.join(self.buildlogs_dirpath(), "LogMessages.xml") parse_filepath = os.path.join(self.rootdir(), 'Tools', 'autotest', 'logger_metadata', 'parse.py') try: @@ -2341,6 +2465,9 @@ def test_onboard_logging_generation(self): except OSError: pass vehicle = self.log_name() + if vehicle == 'BalanceBot': + # same binary and parameters as Rover + return vehicle_map = { "ArduCopter": "Copter", "HeliCopter": "Copter", @@ -2442,11 +2569,13 @@ def customise_SITL_commandline(self, set_streamrate_callback=None): '''customisations could be "--uartF=sim:nmea" ''' self.contexts[-1].sitl_commandline_customised = True + self.mav.close() self.stop_SITL() self.start_SITL(model=model, defaults_filepath=defaults_filepath, customisations=customisations, wipe=wipe) + self.mav.do_connect() tstart = time.time() while True: if time.time() - tstart > 30: @@ -2508,6 +2637,16 @@ def reset_SITL_commandline(self): self.apply_default_parameters() self.progress("Reset SITL commandline to default") + def pause_SITL(self): + '''temporarily stop the SITL process from running. Note that + simulation time will not move forward!''' + # self.progress("Pausing SITL") + self.sitl.kill(signal.SIGSTOP) + + def unpause_SITL(self): + # self.progress("Unpausing SITL") + self.sitl.kill(signal.SIGCONT) + def stop_SITL(self): self.progress("Stopping SITL") self.expect_list_remove(self.sitl) @@ -2548,7 +2687,7 @@ def try_symlink_tlog(self): os.link(self.logfile, self.buildlog) except OSError as error: self.progress("OSError [%d]: %s" % (error.errno, error.strerror)) - self.progress("WARN: Failed to create symlink: %s => %s, " + self.progress("WARN: Failed to create link: %s => %s, " "will copy tlog manually to target location" % (self.logfile, self.buildlog)) self.copy_tlog = True @@ -2657,15 +2796,28 @@ def expect_callback(self, e): self.do_heartbeats() def drain_mav_unparsed(self, mav=None, quiet=True, freshen_sim_time=False): + '''drain all data on mavlink connection mav (defaulting to self.mav). + It is assumed that this connection is connected to the normal + simulation.''' if mav is None: mav = self.mav count = 0 tstart = time.time() + self.pause_SITL() + # sometimes we recv() when the process is likely to go away.. + old_autoreconnect = mav.autoreconnect + mav.autoreconnect = False while True: - this = self.mav.recv(1000000) + try: + this = mav.recv(1000000) + except Exception: + mav.autoreconnect = old_autoreconnect + raise if len(this) == 0: break count += len(this) + mav.autoreconnect = old_autoreconnect + self.unpause_SITL() if quiet: return tdelta = time.time() - tstart @@ -2678,6 +2830,9 @@ def drain_mav_unparsed(self, mav=None, quiet=True, freshen_sim_time=False): self.get_sim_time() def drain_mav(self, mav=None, unparsed=False, quiet=True): + '''parse all data available on connection mav (defaulting to + self.mav). It is assumed that mav is connected to the normal + simulation''' if unparsed: return self.drain_mav_unparsed(quiet=quiet, mav=mav) if mav is None: @@ -2685,8 +2840,29 @@ def drain_mav(self, mav=None, unparsed=False, quiet=True): self.in_drain_mav = True count = 0 tstart = time.time() - while mav.recv_match(blocking=False) is not None: + timeout = 120 + failed_to_drain = False + self.pause_SITL() + # sometimes we recv() when the process is likely to go away.. + old_autoreconnect = mav.autoreconnect + mav.autoreconnect = False + while True: + try: + receive_result = mav.recv_msg() + except Exception: + mav.autoreconnect = True + raise + if receive_result is None: + break count += 1 + if time.time() - tstart > timeout: + # ArduPilot can produce messages faster than we can + # consume them. Until a better solution is found, + # just die if that seems to be the case: + failed_to_drain = True + quiet = False + mav.autoreconnect = old_autoreconnect + self.unpause_SITL() if quiet: self.in_drain_mav = False return @@ -2698,6 +2874,10 @@ def drain_mav(self, mav=None, unparsed=False, quiet=True): if not quiet: self.progress("Drained %u messages from mav (%s)" % (count, rate), send_statustext=False) + + if failed_to_drain: + raise NotAchievedException("Did not fully drain MAV within %ss" % timeout) + self.in_drain_mav = False def do_timesync_roundtrip(self, quiet=False, timeout_in_wallclock=False): @@ -2798,8 +2978,90 @@ def HIGH_LATENCY2(self): if m.temperature_air == -128: # High_Latency2 defaults to INT8_MIN for no temperature available raise NotAchievedException("Air Temperature not received from HIGH_LATENCY2") + self.HIGH_LATENCY2_links() + + def HIGH_LATENCY2_links(self): + + self.start_subtest("SerialProtocol_MAVLinkHL links") + + ex = None + self.context_push() + mav2 = None + try: + + self.set_parameter("SERIAL2_PROTOCOL", 43) # HL) + + self.reboot_sitl() + + mav2 = mavutil.mavlink_connection( + "tcp:localhost:5763", + robust_parsing=True, + source_system=7, + source_component=7, + ) + + self.start_subsubtest("Don't get HIGH_LATENCY2 by default") + for mav in self.mav, mav2: + self.assert_not_receive_message('HIGH_LATENCY2', mav=mav, timeout=10) + + self.start_subsubtest("Get HIGH_LATENCY2 upon link enabled only on HL link") + self.run_cmd_enable_high_latency(True) + self.assert_receive_message("HIGH_LATENCY2", mav=mav2, timeout=10) + self.assert_not_receive_message("HIGH_LATENCY2", mav=self.mav, timeout=10) + + self.start_subsubtest("Not get HIGH_LATENCY2 upon HL disable") + self.run_cmd_enable_high_latency(False) + self.delay_sim_time(10) + self.assert_not_receive_message('HIGH_LATENCY2', mav=self.mav, timeout=10) + self.drain_mav(mav2) + self.assert_not_receive_message('HIGH_LATENCY2', mav=mav2, timeout=10) + + self.start_subsubtest("Stream rate adjustments") + self.run_cmd_enable_high_latency(True) + self.assert_message_rate_hz("HIGH_LATENCY2", 0.2, ndigits=1, mav=mav2, sample_period=60) + for test_rate in (1, 0.1, 2): + self.test_rate( + "HIGH_LATENCY2 on enabled link", + test_rate, + test_rate, + mav=mav2, + ndigits=1, + victim_message="HIGH_LATENCY2", + message_rate_sample_period=60, + ) + self.assert_not_receive_message("HIGH_LATENCY2", mav=self.mav, timeout=10) + self.run_cmd_enable_high_latency(False) + + self.start_subsubtest("Not get HIGH_LATENCY2 after disabling after playing with rates") + self.assert_not_receive_message('HIGH_LATENCY2', mav=self.mav, timeout=10) + self.delay_sim_time(1) + self.drain_mav(mav2) + self.assert_not_receive_message('HIGH_LATENCY2', mav=mav2, timeout=10) + + self.start_subsubtest("Enable and disable should not affect non-HL links getting HIGH_LATENCY2") + self.set_message_rate_hz("HIGH_LATENCY2", 5, mav=self.mav) + self.assert_message_rate_hz("HIGH_LATENCY2", 5, mav=self.mav) + + self.run_cmd_enable_high_latency(True) + self.assert_message_rate_hz("HIGH_LATENCY2", 5, mav=self.mav), + + self.run_cmd_enable_high_latency(False) + self.assert_message_rate_hz("HIGH_LATENCY2", 5, mav=self.mav) + except Exception as e: + self.print_exception_caught(e) + ex = e + + self.context_pop() + + self.reboot_sitl() - def test_log_download(self): + self.set_message_rate_hz("HIGH_LATENCY2", 0) + + if ex is not None: + raise ex + + def LogDownload(self): + '''Test Onboard Log Download''' if self.is_tracker(): # tracker starts armed, which is annoying return @@ -2904,12 +3166,9 @@ def test_log_download(self): 1, # target component log_id, log_id) - log_entry = self.mav.recv_match(type='LOG_ENTRY', - blocking=True, - timeout=2) + log_entry = self.assert_receive_message('LOG_ENTRY', timeout=2, verbose=True) if log_entry.size != len(actual_bytes): raise NotAchievedException("Incorrect bytecount") - self.progress("Using log entry (%s)" % str(log_entry)) if log_entry.id != log_id: raise NotAchievedException("Incorrect log id received") @@ -3029,9 +3288,10 @@ def test_log_download(self): ################################################# # SIM UTILITIES ################################################# - def get_sim_time(self, timeout=60): + def get_sim_time(self, timeout=60, drain_mav=True): """Get SITL time in seconds.""" - self.drain_mav() + if drain_mav: + self.drain_mav() tstart = time.time() while True: self.drain_all_pexpects() @@ -3057,7 +3317,7 @@ def get_sim_time_cached(self): timeout = 30 if self.valgrind: timeout *= 10 - if time.time() - self.last_sim_time_cached_wallclock > timeout: + if time.time() - self.last_sim_time_cached_wallclock > timeout and not self.gdb: raise AutoTestTimeoutException("sim_time_cached is not updating!") return ret @@ -3138,6 +3398,22 @@ def upload_simple_relhome_mission(self, items, target_system=1, target_component def get_mission_count(self): return self.get_parameter("MIS_TOTAL") + def run_auxfunc(self, + function, + level, + want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED): + self.run_cmd( + mavutil.mavlink.MAV_CMD_DO_AUX_FUNCTION, + function, # p1 + level, # p2 + 0, # p3 + 0, # p4 + 0, # p5 + 0, # p6 + 0, # p7 + want_result=want_result + ) + def assert_mission_count(self, expected): count = self.get_mission_count() if count != expected: @@ -3186,21 +3462,44 @@ def assert_reach_imu_temperature(self, target, timeout): if not temp_ok: raise NotAchievedException("target temperature") - def assert_message_field_values(self, m, fieldvalues, verbose=True): + def message_has_field_values(self, m, fieldvalues, verbose=True, epsilon=None): for (fieldname, value) in fieldvalues.items(): got = getattr(m, fieldname) - if got != value: - raise NotAchievedException("Expected %s.%s to be %s, got %s" % - (m.get_type(), fieldname, value, got)) + if math.isnan(value) or math.isnan(got): + equal = math.isnan(value) and math.isnan(got) + elif epsilon is not None: + equal = abs(got - value) <= epsilon + else: + equal = got == value + + if not equal: + self.progress("Expected %s.%s to be %s, got %s" % + (m.get_type(), fieldname, value, got)) + return False if verbose: self.progress("%s.%s has expected value %s" % (m.get_type(), fieldname, value)) + return True + + def assert_message_field_values(self, m, fieldvalues, verbose=True, epsilon=None): + if self.message_has_field_values(m, fieldvalues, verbose=verbose, epsilon=epsilon): + return + raise NotAchievedException("Did not get expected field values") - def assert_received_message_field_values(self, message, fieldvalues, verbose=True, very_verbose=False): + def assert_received_message_field_values(self, message, fieldvalues, verbose=True, very_verbose=False, epsilon=None): m = self.assert_receive_message(message, verbose=verbose, very_verbose=very_verbose) - self.assert_message_field_values(m, fieldvalues, verbose=verbose) + self.assert_message_field_values(m, fieldvalues, verbose=verbose, epsilon=epsilon) return m + def wait_message_field_values(self, message, fieldvalues, timeout=10, epsilon=None): + tstart = self.get_sim_time_cached() + while True: + if self.get_sim_time_cached() - tstart > timeout: + raise NotAchievedException("Field never reached values") + m = self.assert_receive_message(message) + if self.message_has_field_values(m, fieldvalues, epsilon=epsilon): + break + def onboard_logging_not_log_disarmed(self): self.start_subtest("Test LOG_DISARMED-is-false behaviour") self.set_parameter("LOG_DISARMED", 0) @@ -3367,14 +3666,15 @@ def onboard_logging_forced_arm(self): if len(post_arming_list) <= len(pre_arming_list): raise NotAchievedException("Did not get a log on forced arm") - def test_onboard_logging(self): + def Logging(self): + '''Test Onboard Logging''' if self.is_tracker(): return self.onboard_logging_forced_arm() self.onboard_logging_log_disarmed() self.onboard_logging_not_log_disarmed() - def test_log_download_mavproxy(self, upload_logs=False): + def TestLogDownloadMAVProxy(self, upload_logs=False): """Download latest log.""" filename = "MAVProxy-downloaded-log.BIN" mavproxy = self.start_mavproxy() @@ -3389,23 +3689,6 @@ def test_log_download_mavproxy(self, upload_logs=False): self.mavproxy_unload_module(mavproxy, 'log') self.stop_mavproxy(mavproxy) - def log_upload(self): - self.progress("Log upload disabled as CI artifacts are good") - return - if len(self.fail_list) > 0 and os.getenv("AUTOTEST_UPLOAD"): - # optionally upload logs to server so we can see travis failure logs - import datetime - import glob - import subprocess - logdir = self.buildlogs_dirpath() - datedir = datetime.datetime.now().strftime("%Y-%m-%d-%H-%M") - flist = glob.glob("logs/*.BIN") - for e in ['BIN', 'bin', 'tlog']: - flist += glob.glob(os.path.join(logdir, '*.%s' % e)) - self.progress("Uploading %u logs to https://firmware.ardupilot.org/CI-Logs/%s" % (len(flist), datedir)) - cmd = ['rsync', '-avz'] + flist + ['cilogs@autotest.ardupilot.org::CI-Logs/%s/' % datedir] - subprocess.call(cmd) - def show_gps_and_sim_positions(self, on_off): """Allow to display gps and actual position on map.""" if on_off is True: @@ -3436,13 +3719,11 @@ def install_message_hook_context(self, hook): self.context_get().message_hooks.append(hook) def remove_message_hook(self, hook): + '''remove hook from list of message hooks. Assumes it exists exactly + once''' if self.mav is None: return - oldlen = len(self.mav.message_hooks) - self.mav.message_hooks = list(filter(lambda x: x != hook, - self.mav.message_hooks)) - if len(self.mav.message_hooks) == oldlen: - raise NotAchievedException("Failed to remove hook") + self.mav.message_hooks.remove(hook) def rootdir(self): this_dir = os.path.dirname(__file__) @@ -3543,16 +3824,55 @@ def assert_mission_files_same(self, file1, file2, match_comments=False): raise ValueError("count %u not handled" % count) self.progress("Files same") - def assert_receive_message(self, type, timeout=1, verbose=False, very_verbose=False): - m = self.mav.recv_match(type=type, blocking=True, timeout=timeout) + def assert_not_receive_message(self, message, timeout=1, mav=None): + '''this is like assert_not_receiving_message but uses sim time not + wallclock time''' + self.progress("making sure we're not getting %s messages" % message) + if mav is None: + mav = self.mav + + tstart = self.get_sim_time_cached() + while True: + m = mav.recv_match(type=message, blocking=True, timeout=0.1) + if m is not None: + self.progress("Received: %s" % self.dump_message_verbose(m)) + raise PreconditionFailedException("Receiving %s messages" % message) + if mav != self.mav: + # update timestamp.... + self.drain_mav(self.mav) + if self.get_sim_time_cached() - tstart > timeout: + return + + def assert_receive_message(self, type, timeout=1, verbose=False, very_verbose=False, mav=None): + if mav is None: + mav = self.mav + m = None + tstart = time.time() # timeout in wallclock + while m is None: + m = mav.recv_match(type=type, blocking=True, timeout=0.05) + if time.time() - tstart > timeout: + raise NotAchievedException("Did not get %s" % type) if verbose: self.progress("Received (%s)" % str(m)) if very_verbose: self.progress(self.dump_message_verbose(m)) - if m is None: - raise NotAchievedException("Did not get %s" % type) return m + def assert_receive_named_value_float(self, name, timeout=10): + tstart = self.get_sim_time_cached() + while True: + if self.get_sim_time_cached() - tstart > timeout: + raise NotAchievedException("Did not get NAMED_VALUE_FLOAT %s" % name) + m = self.assert_receive_message('NAMED_VALUE_FLOAT', verbose=1, very_verbose=1, timeout=timeout) + if m.name != name: + continue + return m + + def assert_receive_named_value_float_value(self, name, value, epsilon=0.0001, timeout=10): + m = self.assert_receive_named_value_float_value(name, timeout=timeout) + if abs(m.value - value) > epsilon: + raise NotAchievedException("Bad %s want=%f got=%f" % (name, value, m.value)) + def assert_rally_files_same(self, file1, file2): self.progress("Comparing (%s) and (%s)" % (file1, file2, )) f1 = open(file1) @@ -3692,7 +4012,8 @@ def wp_to_mission_item_int(self, wp): wp.z) return wp_int - def load_mission_from_filepath(self, filepath, filename, target_system=1, target_component=1, strict=True): + def mission_from_filepath(self, filepath, filename, target_system=1, target_component=1): + '''returns a list of mission-item-ints from filepath''' self.progress("Loading mission (%s)" % filename) path = os.path.join(testdir, filepath, filename) wploader = mavwp.MAVWPLoader( @@ -3700,8 +4021,40 @@ def load_mission_from_filepath(self, filepath, filename, target_system=1, target target_component=target_component ) wploader.load(path) - wpoints_int = [self.wp_to_mission_item_int(x) for x in wploader.wpoints] + return [self.wp_to_mission_item_int(x) for x in wploader.wpoints] + + def get_home_tuple_from_mission(self, filename): + '''gets item 0 from the mission file, returns a tuple suitable for + passing to customise_SITL_commandline as --home. Yaw will be + 0, so the caller may want to fill that in + ''' + items = self.mission_from_filepath( + self.current_test_name_directory, + filename, + ) + home_item = items[0] + return (home_item.x * 1e-7, home_item.y * 1e-7, home_item.z, 0) + + # TODO: rename the following to "upload_mission_from_filepath" + def load_mission_from_filepath(self, + filepath, + filename, + target_system=1, + target_component=1, + strict=True, + reset_current_wp=True): + wpoints_int = self.mission_from_filepath( + filepath, + filename, + target_system=target_system, + target_component=target_component + ) self.check_mission_upload_download(wpoints_int, strict=strict) + if reset_current_wp: + # ArduPilot doesn't reset the current waypoint by default + # we may be in auto mode and running waypoints, so we + # can't check the current waypoint after resetting it. + self.set_current_waypoint(0, check_afterwards=False) return len(wpoints_int) def load_mission_using_mavproxy(self, mavproxy, filename): @@ -3725,7 +4078,7 @@ def load_mission_from_filepath_using_mavproxy(self, # the following hack is to get around MAVProxy statustext deduping: while time.time() - self.last_wp_load < 3: self.progress("Waiting for MAVProxy de-dupe timer to expire") - self.drain_mav_unparsed() + self.drain_mav() time.sleep(0.1) mavproxy.send('wp load %s\n' % path) mavproxy.expect('Loaded ([0-9]+) waypoints from') @@ -3847,9 +4200,9 @@ def check_mission_items_same(self, raise NotAchievedException("Frame not same (got=%s want=%s)" % (self.string_for_frame(downloaded_item_val), self.string_for_frame(item_val))) - if abs(item.z - downloaded_item.z) > 0.00001: + if abs(item.z - downloaded_item.z) > 1.0E-3: # error should be less than 1 mm raise NotAchievedException("Z not preserved (got=%f want=%f)" % - (item.z, downloaded_item.z)) + (downloaded_item.z, item.z)) def check_fence_items_same(self, want, got, strict=True): check_atts = ['mission_type', 'command', 'x', 'y', 'seq', 'param1'] @@ -3860,7 +4213,7 @@ def check_mission_waypoint_items_same(self, want, got, strict=True): return self.check_mission_items_same(check_atts, want, got, skip_first_item=True, strict=strict) def check_mission_item_upload_download(self, items, itype, mission_type, strict=True): - self.progress("check %s _upload/download: upload %u items" % + self.progress("check %s upload/download: upload %u items" % (itype, len(items),)) self.upload_using_mission_protocol(mission_type, items) self.progress("check %s upload/download: download items" % itype) @@ -3920,8 +4273,8 @@ def check_dflog_message_rates(self, log_filepath, message_rates): for (t, want_rate) in message_rates.items(): if t not in counts: raise NotAchievedException("Wanted %s but got none" % t) - self.progress("Got (%u)" % counts[t]) - got_rate = counts[t] / delta_time_us * 1000000 + self.progress("Got (%u) in (%uus)" % (counts[t], delta_time_us)) + got_rate = float(counts[t]) / delta_time_us * 1000000 if abs(want_rate - got_rate) > 5: raise NotAchievedException("Not getting %s data at wanted rate want=%f got=%f" % @@ -3958,6 +4311,9 @@ def rc_defaults(self): def set_rc_from_map(self, _map, timeout=20): map_copy = _map.copy() + for v in map_copy.values(): + if type(v) != int: + raise NotAchievedException("RC values must be integers") self.rc_queue.put(map_copy) if self.rc_thread is None: @@ -4001,8 +4357,12 @@ def rc_thread_main(self): # the autopilot at 20Hz - that's our 50Hz wallclock, , not # the autopilot's simulated 20Hz, so if speedup is 10 the # autopilot will see ~2Hz. + timeout = 0.02 + # ... and 2Hz is too slow when we now run at 100x speedup: + timeout /= (self.speedup / 10.0) + try: - map_copy = self.rc_queue.get(timeout=0.02) + map_copy = self.rc_queue.get(timeout=timeout) # 16 packed entries: for i in range(1, 17): @@ -4137,14 +4497,33 @@ def send_mavlink_arm_command(self): 0, 0) - def set_analog_rangefinder_parameters(self): - self.set_parameters({ + def send_mavlink_run_prearms_command(self): + target_sysid = 1 + target_compid = 1 + self.mav.mav.command_long_send( + target_sysid, + target_compid, + mavutil.mavlink.MAV_CMD_RUN_PREARM_CHECKS, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0) + + def analog_rangefinder_parameters(self): + return { "RNGFND1_TYPE": 1, "RNGFND1_MIN_CM": 0, "RNGFND1_MAX_CM": 4000, "RNGFND1_SCALING": 12.12, "RNGFND1_PIN": 0, - }) + } + + def set_analog_rangefinder_parameters(self): + self.set_parameters(self.analog_rangefinder_parameters()) def send_debug_trap(self, timeout=6000): self.progress("Sending trap to autopilot") @@ -4192,7 +4571,6 @@ def try_arm(self, result=True, expect_msg=None, timeout=60): def arm_vehicle(self, timeout=20, force=False): """Arm vehicle with mavlink arm message.""" self.progress("Arm motors with MAVLink cmd") - self.drain_mav() p2 = 0 if force: p2 = 2989 @@ -4219,7 +4597,7 @@ def arm_vehicle(self, timeout=20, force=False): def wait_armed(self, timeout=20): tstart = self.get_sim_time() while self.get_sim_time_cached() - tstart < timeout: - self.wait_heartbeat() + self.wait_heartbeat(drain_mav=False) if self.mav.motors_armed(): self.progress("Motors ARMED") return @@ -4228,7 +4606,6 @@ def wait_armed(self, timeout=20): def disarm_vehicle(self, timeout=60, force=False): """Disarm vehicle with mavlink disarm message.""" self.progress("Disarm motors with MAVLink cmd") - self.drain_mav_unparsed() p2 = 0 if force: p2 = 21196 # magic force disarm value @@ -4241,7 +4618,23 @@ def disarm_vehicle(self, timeout=60, force=False): 0, 0, timeout=timeout) - return self.wait_disarmed() + self.wait_disarmed() + + def disarm_vehicle_expect_fail(self): + '''disarm, checking first that non-forced disarm fails, then doing a forced disarm''' + self.progress("Disarm - expect to fail") + self.run_cmd(mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM, + 0, # DISARM + 0, + 0, + 0, + 0, + 0, + 0, + timeout=10, + want_result=mavutil.mavlink.MAV_RESULT_FAILED) + self.progress("Disarm - forced") + self.disarm_vehicle(force=True) def wait_disarmed_default_wait_time(self): return 30 @@ -4262,12 +4655,13 @@ def wait_disarmed(self, timeout=None, tstart=None): if now - last_print_time > 1: self.progress("Waiting for disarm (%.2fs so far of allowed %.2f)" % (delta, timeout)) last_print_time = now - self.wait_heartbeat(quiet=True) -# self.progress("Got heartbeat") - if not self.mav.motors_armed(): - self.progress("DISARMED after %.2f seconds (allowed=%.2f)" % - (delta, timeout)) - return True + msg = self.wait_heartbeat(quiet=True) + if msg.base_mode & mavutil.mavlink.MAV_MODE_FLAG_SAFETY_ARMED: + # still armed + continue + self.progress("DISARMED after %.2f seconds (allowed=%.2f)" % + (delta, timeout)) + return def wait_attitude(self, desroll=None, despitch=None, timeout=2, tolerance=10, message_type='ATTITUDE'): '''wait for an attitude (degrees)''' @@ -4318,7 +4712,8 @@ def wait_attitude_quaternion(self, return def CPUFailsafe(self): - '''Most vehicles just disarm on failsafe''' + '''Ensure we do something appropriate when the main loop stops''' + # Most vehicles just disarm on failsafe # customising the SITL commandline ensures the process will # get stopped/started at the end of the test if self.frame is None: @@ -4391,7 +4786,7 @@ def mavproxy_arm_vehicle(self, mavproxy): """Arm vehicle with mavlink arm message send from MAVProxy.""" self.progress("Arm motors with MavProxy") mavproxy.send('arm throttle\n') - self.mav.motors_armed_wait() + self.wait_armed() self.progress("ARMED") return True @@ -4400,7 +4795,6 @@ def mavproxy_disarm_vehicle(self, mavproxy): self.progress("Disarm motors with MavProxy") mavproxy.send('disarm\n') self.wait_disarmed() - return True def arm_motors_with_rc_input(self, timeout=20): """Arm motors with radio.""" @@ -4723,6 +5117,10 @@ def context_stop_collecting(self, msg_type): def context_pop(self): """Set parameters to origin values in reverse order.""" dead = self.contexts.pop() + # remove hooks first; these hooks can raise exceptions which + # we really don't want... + for hook in dead.message_hooks: + self.remove_message_hook(hook) if dead.sitl_commandline_customised and len(self.contexts): self.contexts[-1].sitl_commandline_customised = True @@ -4730,8 +5128,33 @@ def context_pop(self): for p in dead.parameters: dead_parameters_dict[p[0]] = p[1] self.set_parameters(dead_parameters_dict, add_to_context=False) - for hook in dead.message_hooks: - self.remove_message_hook(hook) + + if getattr(self, "old_binary", None) is not None: + self.stop_SITL() + with open(self.binary, "wb") as f: + f.write(self.old_binary) + f.close() + self.start_SITL(wipe=False) + self.set_streamrate(self.sitl_streamrate()) + + # the following method is broken under Python2; can't **build_opts + # def context_start_custom_binary(self, extra_defines={}): + # # grab copy of current binary: + # context = self.context_get() + # if getattr(context, "old_binary", None) is not None: + # raise ValueError("Not nestable at the moment") + # with open(self.binary, "rb") as f: + # self.old_binary = f.read() + # f.close() + # build_opts = copy.copy(self.build_opts) + # build_opts["extra_defines"] = extra_defines + # util.build_SITL( + # 'bin/arducopter', # FIXME! + # **build_opts, + # ) + # self.stop_SITL() + # self.start_SITL(wipe=False) + # self.set_streamrate(self.sitl_streamrate()) class Context(object): def __init__(self, testsuite): @@ -4796,8 +5219,11 @@ def send_cmd(self, p7, target_sysid=None, target_compid=None, + mav=None, ): """Send a MAVLink command long.""" + if mav is None: + mav = self.mav if target_sysid is None: target_sysid = self.sysid_thismav() if target_compid is None: @@ -4818,17 +5244,17 @@ def send_cmd(self, p5, p6, p7)) - self.mav.mav.command_long_send(target_sysid, - target_compid, - command, - 1, # confirmation - p1, - p2, - p3, - p4, - p5, - p6, - p7) + mav.mav.command_long_send(target_sysid, + target_compid, + command, + 1, # confirmation + p1, + p2, + p3, + p4, + p5, + p6, + p7) def run_cmd(self, command, @@ -4843,8 +5269,9 @@ def run_cmd(self, target_sysid=None, target_compid=None, timeout=10, - quiet=False): - self.drain_mav() + quiet=False, + mav=None): + self.drain_mav(mav=mav) self.get_sim_time() # required for timeout in run_cmd_get_ack to work self.send_cmd( command, @@ -4857,20 +5284,25 @@ def run_cmd(self, p7, target_sysid=target_sysid, target_compid=target_compid, + mav=mav, ) - self.run_cmd_get_ack(command, want_result, timeout, quiet=quiet) + self.run_cmd_get_ack(command, want_result, timeout, quiet=quiet, mav=mav) - def run_cmd_get_ack(self, command, want_result, timeout, quiet=False): + def run_cmd_get_ack(self, command, want_result, timeout, quiet=False, mav=None): # note that the caller should ensure that this cached # timestamp is reasonably up-to-date! + if mav is None: + mav = self.mav tstart = self.get_sim_time_cached() while True: + if mav != self.mav: + self.drain_mav() delta_time = self.get_sim_time_cached() - tstart if delta_time > timeout: raise AutoTestTimeoutException("Did not get good COMMAND_ACK within %fs" % timeout) - m = self.mav.recv_match(type='COMMAND_ACK', - blocking=True, - timeout=0.1) + m = mav.recv_match(type='COMMAND_ACK', + blocking=True, + timeout=0.1) if m is None: continue if not quiet: @@ -5081,12 +5513,15 @@ def get_autopilot_capabilities(self): m = self.assert_receive_message('AUTOPILOT_VERSION', timeout=10) return m.capabilities - def test_get_autopilot_capabilities(self): + def GetCapabilities(self): + '''Get Capabilities''' self.assert_capability(mavutil.mavlink.MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT) self.assert_capability(mavutil.mavlink.MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION) def get_mode_from_mode_mapping(self, mode): """Validate and return the mode number from a string or int.""" + if isinstance(mode, int): + return mode mode_map = self.mav.mode_mapping() if mode_map is None: mav_type = self.mav.messages['HEARTBEAT'].type @@ -5155,7 +5590,9 @@ def reach_heading_manual(self, heading, turn_right=True): self.wait_heading(heading) self.set_rc(4, 1500) if self.is_plane(): - self.progress("NOT IMPLEMENTED") + self.set_rc(1, 1800) + self.wait_heading(heading) + self.set_rc(1, 1500) if self.is_rover(): steering_pwm = 1700 if not turn_right: @@ -5223,6 +5660,13 @@ def guided_achieve_heading(self, heading, accuracy=None): if m.heading == int(heading): return + def assert_heading(self, heading, accuracy=1): + '''assert vehicle yaw is to heading (0-360)''' + m = self.assert_receive_message('VFR_HUD') + if self.heading_delta(heading, m.heading) > accuracy: + raise NotAchievedException("Unexpected heading=%f want=%f" % + (m.heading, heading)) + def do_set_relay(self, relay_num, on_off, timeout=10): """Set relay with a command long message.""" self.progress("Set relay %d to %d" % (relay_num, on_off)) @@ -5269,7 +5713,6 @@ def do_fence_disable(self, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED): ################################################# def delay_sim_time(self, seconds_to_wait, reason=None): """Wait some second in SITL time.""" - self.drain_mav() tstart = self.get_sim_time() tnow = tstart r = "Delaying %f seconds" @@ -5277,19 +5720,21 @@ def delay_sim_time(self, seconds_to_wait, reason=None): r += " for %s" % reason self.progress(r % (seconds_to_wait,)) while tstart + seconds_to_wait > tnow: - tnow = self.get_sim_time() + tnow = self.get_sim_time(drain_mav=False) def get_altitude(self, relative=False, timeout=30): '''returns vehicles altitude in metres, possibly relative-to-home''' - msg = self.mav.recv_match(type='GLOBAL_POSITION_INT', - blocking=True, - timeout=timeout) - if msg is None: - raise MsgRcvTimeoutException("Failed to get Global Position") + msg = self.assert_receive_message("GLOBAL_POSITION_INT", timeout=timeout) if relative: return msg.relative_alt / 1000.0 # mm -> m return msg.alt / 1000.0 # mm -> m + def assert_altitude(self, alt, accuracy=1, **kwargs): + got_alt = self.get_altitude(**kwargs) + if abs(alt - got_alt) > accuracy: + raise NotAchievedException("Incorrect alt; want=%f got=%f" % + (alt, got_alt)) + def assert_rangefinder_distance_between(self, dist_min, dist_max): m = self.assert_receive_message('RANGEFINDER') @@ -5346,6 +5791,32 @@ def find_first_set_bit(self, mask): pos += 1 return None + def get_rpm(self, rpm_sensor): + m = self.assert_receive_message('RPM') + if rpm_sensor == 1: + ret = m.rpm1 + elif rpm_sensor == 2: + ret = m.rpm2 + else: + raise ValueError("Bad sensor id") + if ret < 0.000001: + # yay filtering! + return 0 + return ret + + def wait_rpm(self, rpm_sensor, rpm_min, rpm_max, **kwargs): + '''wait for RPM to be between rpm_min and rpm_max''' + def validator(value2, target2=None): + return rpm_min <= value2 <= rpm_max + self.wait_and_maintain( + value_name="RPM%u" % rpm_sensor, + target=(rpm_min+rpm_max)/2.0, + current_value_getter=lambda: self.get_rpm(rpm_sensor), + accuracy=rpm_max-rpm_min, + validator=lambda value2, target2: validator(value2, target2), + **kwargs + ) + def wait_esc_telem_rpm(self, esc, rpm_min, rpm_max, **kwargs): '''wait for ESC to be between rpm_min and rpm_max''' def validator(value2, target2=None): @@ -5382,15 +5853,21 @@ def validator(value2, target2=None): **kwargs ) + def watch_altitude_maintained(self, altitude_min, altitude_max, minimum_duration=5, relative=True): + """Watch altitude is maintained or not between altitude_min and altitude_max during minimum_duration""" + return self.wait_altitude(altitude_min=altitude_min, + altitude_max=altitude_max, + relative=relative, + minimum_duration=minimum_duration, + timeout=minimum_duration + 1) + def wait_climbrate(self, speed_min, speed_max, timeout=30, **kwargs): """Wait for a given vertical rate.""" assert speed_min <= speed_max, "Minimum speed should be less than maximum speed." def get_climbrate(timeout2): - msg = self.mav.recv_match(type='VFR_HUD', blocking=True, timeout=timeout2) - if msg: - return msg.climb - raise MsgRcvTimeoutException("Failed to get climb rate") + msg = self.assert_receive_message('VFR_HUD', timeout=timeout2) + return msg.climb def validator(value2, target2=None): if speed_min <= value2 <= speed_max: @@ -5409,27 +5886,25 @@ def validator(value2, target2=None): ) def wait_groundspeed(self, speed_min, speed_max, timeout=30, **kwargs): + self.wait_vfr_hud_speed("groundspeed", speed_min, speed_max, timeout=timeout, **kwargs) + + def wait_airspeed(self, speed_min, speed_max, timeout=30, **kwargs): + self.wait_vfr_hud_speed("airspeed", speed_min, speed_max, timeout=timeout, **kwargs) + + def wait_vfr_hud_speed(self, field, speed_min, speed_max, timeout=30, **kwargs): """Wait for a given ground speed range.""" assert speed_min <= speed_max, "Minimum speed should be less than maximum speed." - def get_groundspeed(timeout2): - msg = self.mav.recv_match(type='VFR_HUD', blocking=True, timeout=timeout2) - if msg: - return msg.groundspeed - raise MsgRcvTimeoutException("Failed to get Groundspeed") + def get_speed(timeout2): + msg = self.assert_receive_message('VFR_HUD', timeout=timeout2) + return getattr(msg, field) - def validator(value2, target2=None): - if speed_min <= value2 <= speed_max: - return True - else: - return False - - self.wait_and_maintain( - value_name="Groundspeed", - target=(speed_min+speed_max)/2, - current_value_getter=lambda: get_groundspeed(timeout), - accuracy=(speed_max - speed_min)/2, - validator=lambda value2, target2: validator(value2, target2), + self.wait_and_maintain_range( + value_name=field, + minimum=speed_min, + maximum=speed_max, + current_value_getter=lambda: get_speed(timeout), + validator=None, timeout=timeout, **kwargs ) @@ -5437,13 +5912,11 @@ def validator(value2, target2=None): def wait_roll(self, roll, accuracy, timeout=30, **kwargs): """Wait for a given roll in degrees.""" def get_roll(timeout2): - msg = self.mav.recv_match(type='ATTITUDE', blocking=True, timeout=timeout2) - if msg: - p = math.degrees(msg.pitch) - r = math.degrees(msg.roll) - self.progress("Roll %d Pitch %d" % (r, p)) - return r - raise MsgRcvTimeoutException("Failed to get Roll") + msg = self.assert_receive_message('ATTITUDE', timeout=timeout2) + p = math.degrees(msg.pitch) + r = math.degrees(msg.roll) + self.progress("Roll %d Pitch %d" % (r, p)) + return r def validator(value2, target2): return math.fabs((value2 - target2 + 180) % 360 - 180) <= accuracy @@ -5461,13 +5934,11 @@ def validator(value2, target2): def wait_pitch(self, pitch, accuracy, timeout=30, **kwargs): """Wait for a given pitch in degrees.""" def get_pitch(timeout2): - msg = self.mav.recv_match(type='ATTITUDE', blocking=True, timeout=timeout2) - if msg: - p = math.degrees(msg.pitch) - r = math.degrees(msg.roll) - self.progress("Pitch %d Roll %d" % (p, r)) - return p - raise MsgRcvTimeoutException("Failed to get Pitch") + msg = self.assert_receive_message('ATTITUDE', timeout=timeout2) + p = math.degrees(msg.pitch) + r = math.degrees(msg.roll) + self.progress("Pitch %d Roll %d" % (p, r)) + return p def validator(value2, target2): return math.fabs((value2 - target2 + 180) % 360 - 180) <= accuracy @@ -5483,57 +5954,82 @@ def validator(value2, target2): ) def wait_and_maintain(self, value_name, target, current_value_getter, validator=None, accuracy=2.0, timeout=30, **kwargs): + if type(target) is Vector3: + return self.wait_and_maintain_vector( + value_name, + target, + current_value_getter, + validator, + timeout=30, + **kwargs + ) + return self.wait_and_maintain_range( + value_name, + minimum=target - accuracy/2, + maximum=target + accuracy/2, + current_value_getter=current_value_getter, + validator=validator, + timeout=timeout, + print_diagnostics_as_target_not_range=True, + **kwargs + ) + + def wait_and_maintain_vector(self, + value_name, + target, + current_value_getter, + validator, + timeout=30, + **kwargs): tstart = self.get_sim_time() achieving_duration_start = None - if type(target) is Vector3: - sum_of_achieved_values = Vector3() - last_value = Vector3() - else: - sum_of_achieved_values = 0.0 - last_value = 0.0 + sum_of_achieved_values = Vector3() + last_value = Vector3() count_of_achieved_values = 0 called_function = kwargs.get("called_function", None) minimum_duration = kwargs.get("minimum_duration", 0) - if type(target) is Vector3: - self.progress("Waiting for %s=(%s) with accuracy %.02f" % (value_name, str(target), accuracy)) - else: - self.progress("Waiting for %s=%.02f with accuracy %.02f" % (value_name, target, accuracy)) + if minimum_duration >= timeout: + raise ValueError("minimum_duration >= timeout") + + self.progress("Waiting for %s=(%s)" % (value_name, str(target))) + last_print_time = 0 while self.get_sim_time_cached() < tstart + timeout: # if we failed to received message with the getter the sim time isn't updated # noqa last_value = current_value_getter() if called_function is not None: called_function(last_value, target) + is_value_valid = validator(last_value, target) if self.get_sim_time_cached() - last_print_time > 1: - if type(target) is Vector3: - self.progress("%s=(%s) (want (%s) +- %f)" % - (value_name, str(last_value), str(target), accuracy)) + if is_value_valid: + want_or_got = "got" else: - self.progress("%s=%0.2f (want %f +- %f)" % - (value_name, last_value, target, accuracy)) + want_or_got = "want" + achieved_duration_bit = "" + if achieving_duration_start is not None: + so_far = self.get_sim_time_cached() - achieving_duration_start + achieved_duration_bit = " (maintain=%.1f/%.1f)" % (so_far, minimum_duration) + self.progress( + "%s=(%s) (%s (%s))%s" % + (value_name, + str(last_value), + want_or_got, + str(target), + achieved_duration_bit) + ) last_print_time = self.get_sim_time_cached() - if validator is not None: - is_value_valid = validator(last_value, target) - else: - is_value_valid = math.fabs(last_value - target) <= accuracy if is_value_valid: sum_of_achieved_values += last_value count_of_achieved_values += 1.0 if achieving_duration_start is None: achieving_duration_start = self.get_sim_time_cached() if self.get_sim_time_cached() - achieving_duration_start >= minimum_duration: - if type(target) is Vector3: - self.progress("Attained %s=%s" % ( - value_name, - str(sum_of_achieved_values * (1.0 / count_of_achieved_values)))) - else: - self.progress("Attained %s=%f" % (value_name, sum_of_achieved_values / count_of_achieved_values)) + self.progress("Attained %s=%s" % ( + value_name, + str(sum_of_achieved_values * (1.0 / count_of_achieved_values)))) return True else: achieving_duration_start = None - if type(target) is Vector3: - sum_of_achieved_values.zero() - else: - sum_of_achieved_values = 0.0 + sum_of_achieved_values.zero() count_of_achieved_values = 0 raise AutoTestTimeoutException( "Failed to attain %s want %s, reached %s" % @@ -5541,16 +6037,126 @@ def wait_and_maintain(self, value_name, target, current_value_getter, validator= str(target), str(sum_of_achieved_values / count_of_achieved_values) if count_of_achieved_values != 0 else str(last_value))) + def validate_kwargs(self, kwargs, valid={}): + for key in kwargs: + if key not in valid: + raise NotAchievedException("Invalid kwarg %s" % str(key)) + + def wait_and_maintain_range(self, + value_name, + minimum, + maximum, + current_value_getter, + validator=None, + timeout=30, + print_diagnostics_as_target_not_range=False, + **kwargs): + self.validate_kwargs(kwargs, valid=frozenset([ + "called_function", + "minimum_duration", + ])) + + if print_diagnostics_as_target_not_range: + target = (minimum + maximum) / 2 + accuracy = (maximum - minimum) / 2 + tstart = self.get_sim_time() + achieving_duration_start = None + sum_of_achieved_values = 0.0 + last_value = 0.0 + count_of_achieved_values = 0 + called_function = kwargs.get("called_function", None) + minimum_duration = kwargs.get("minimum_duration", 0) + if minimum_duration >= timeout: + raise ValueError("minimum_duration >= timeout") + if print_diagnostics_as_target_not_range: + self.progress("Waiting for %s=%.02f with accuracy %.02f" % (value_name, target, accuracy)) + else: + self.progress("Waiting for %s between (%s) and (%s)" % (value_name, str(minimum), str(maximum))) + last_print_time = 0 + while self.get_sim_time_cached() < tstart + timeout: # if we failed to received message with the getter the sim time isn't updated # noqa + last_value = current_value_getter() + if called_function is not None: + called_function(last_value, target) + if validator is not None: + if print_diagnostics_as_target_not_range: + is_value_valid = validator(last_value, target) + else: + is_value_valid = validator(last_value, minimum, maximum) + else: + is_value_valid = (minimum <= last_value) and (last_value <= maximum) + if self.get_sim_time_cached() - last_print_time > 1: + if is_value_valid: + want_or_got = "got" + else: + want_or_got = "want" + achieved_duration_bit = "" + if achieving_duration_start is not None: + so_far = self.get_sim_time_cached() - achieving_duration_start + achieved_duration_bit = " (maintain=%.1f/%.1f)" % (so_far, minimum_duration) + + if print_diagnostics_as_target_not_range: + self.progress( + "%s=%0.2f (%s %f +- %f)%s" % + (value_name, + last_value, + want_or_got, + target, + accuracy, + achieved_duration_bit) + ) + else: + self.progress( + "%s=%0.2f (%s between %s and %s)%s" % + (value_name, + last_value, + want_or_got, + str(minimum), + str(maximum), + achieved_duration_bit) + ) + last_print_time = self.get_sim_time_cached() + if is_value_valid: + sum_of_achieved_values += last_value + count_of_achieved_values += 1.0 + if achieving_duration_start is None: + achieving_duration_start = self.get_sim_time_cached() + if self.get_sim_time_cached() - achieving_duration_start >= minimum_duration: + self.progress("Attained %s=%f" % (value_name, sum_of_achieved_values / count_of_achieved_values)) + return True + else: + achieving_duration_start = None + sum_of_achieved_values = 0.0 + count_of_achieved_values = 0 + if print_diagnostics_as_target_not_range: + raise AutoTestTimeoutException( + "Failed to attain %s want %s, reached %s" % + (value_name, + str(target), + str(sum_of_achieved_values / count_of_achieved_values) if count_of_achieved_values != 0 else str(last_value))) + else: + raise AutoTestTimeoutException( + "Failed to attain %s between %s and %s, reached %s" % + (value_name, + str(minimum), + str(maximum), + str(sum_of_achieved_values / count_of_achieved_values) if count_of_achieved_values != 0 else str(last_value))) + + def heading_delta(self, heading1, heading2): + '''return angle between two 0-360 headings''' + return math.fabs((heading1 - heading2 + 180) % 360 - 180) + + def get_heading(self, timeout=1): + '''return heading 0-359''' + m = self.assert_receive_message('VFR_HUD', timeout=timeout) + return m.heading + def wait_heading(self, heading, accuracy=5, timeout=30, **kwargs): """Wait for a given heading.""" def get_heading_wrapped(timeout2): - msg = self.mav.recv_match(type='VFR_HUD', blocking=True, timeout=timeout2) - if msg: - return msg.heading - raise MsgRcvTimeoutException("Failed to get heading") + return self.get_heading(timeout=timeout2) def validator(value2, target2): - return math.fabs((value2 - target2 + 180) % 360 - 180) <= accuracy + return self.heading_delta(value2, target2) <= accuracy self.wait_and_maintain( value_name="Heading", @@ -5565,10 +6171,8 @@ def validator(value2, target2): def wait_yaw_speed(self, yaw_speed, accuracy=0.1, timeout=30, **kwargs): """Wait for a given yaw speed in radians per second.""" def get_yawspeed(timeout2): - msg = self.mav.recv_match(type='ATTITUDE', blocking=True, timeout=timeout2) - if msg: - return msg.yawspeed - raise MsgRcvTimeoutException("Failed to get yaw speed") + msg = self.assert_receive_message('ATTITUDE', timeout=timeout2) + return msg.yawspeed def validator(value2, target2): return math.fabs(value2 - target2) <= accuracy @@ -5583,14 +6187,13 @@ def validator(value2, target2): **kwargs ) - def wait_speed_vector(self, speed_vector, accuracy=0.2, timeout=30, **kwargs): - """Wait for a given speed vector.""" - def get_speed_vector(timeout2): - msg = self.mav.recv_match(type='LOCAL_POSITION_NED', blocking=True, timeout=timeout2) - if msg: - return Vector3(msg.vx, msg.vy, msg.vz) - raise MsgRcvTimeoutException("Failed to get local speed vector") + def get_speed_vector(self, timeout=1): + '''return speed vector, NED''' + msg = self.assert_receive_message('LOCAL_POSITION_NED', timeout=timeout) + return Vector3(msg.vx, msg.vy, msg.vz) + """Wait for a given speed vector.""" + def wait_speed_vector(self, speed_vector, accuracy=0.2, timeout=30, **kwargs): def validator(value2, target2): return (math.fabs(value2.x - target2.x) <= accuracy and math.fabs(value2.y - target2.y) <= accuracy and @@ -5599,20 +6202,34 @@ def validator(value2, target2): self.wait_and_maintain( value_name="SpeedVector", target=speed_vector, - current_value_getter=lambda: get_speed_vector(timeout), + current_value_getter=lambda: self.get_speed_vector(timeout=timeout), validator=lambda value2, target2: validator(value2, target2), accuracy=accuracy, timeout=timeout, **kwargs ) + def get_descent_rate(self): + '''get descent rate - a positive number if you are going down''' + return abs(self.get_speed_vector().z) + + def wait_descent_rate(self, rate, accuracy=0.1, **kwargs): + '''wait for descent rate rate, a positive number if going down''' + def validator(value, target): + return math.fabs(value - target) <= accuracy + + self.wait_and_maintain( + value_name="DescentRate", + target=rate, + current_value_getter=lambda: self.get_descent_rate(), + validator=lambda value, target: validator(value, target), + accuracy=accuracy, + **kwargs + ) + def get_body_frame_velocity(self): - gri = self.mav.recv_match(type='GPS_RAW_INT', blocking=True, timeout=1) - if gri is None: - raise NotAchievedException("No GPS_RAW_INT") - att = self.mav.recv_match(type='ATTITUDE', blocking=True, timeout=1) - if att is None: - raise NotAchievedException("No ATTITUDE") + gri = self.assert_receive_message('GPS_RAW_INT', timeout=1) + att = self.assert_receive_message('ATTITUDE', timeout=1) return mavextra.gps_velocity_body(gri, att) def wait_speed_vector_bf(self, speed_vector, accuracy=0.2, timeout=30, **kwargs): @@ -5702,6 +6319,10 @@ def validator(value2, target2=None): **kwargs ) + def assert_at_home(self, accuracy=1): + if self.distance_to_home() > accuracy: + raise NotAchievedException("Not at home") + def wait_distance_to_nav_target(self, distance_min, distance_max, @@ -5731,10 +6352,7 @@ def validator(value2, target2=None): def distance_to_local_position(self, local_pos, timeout=30): (x, y, z_down) = local_pos # alt is *up* - pos = self.mav.recv_match( - type='LOCAL_POSITION_NED', - blocking=True - ) + pos = self.assert_receive_message('LOCAL_POSITION_NED', timeout=timeout) delta_x = pos.x - x delta_y = pos.y - y @@ -5822,6 +6440,21 @@ def wait_servo_channel_value(self, channel, value, timeout=2, comparator=operato if comparator(m_value, value): return m_value + def assert_servo_channel_value(self, channel, value, comparator=operator.eq): + """assert channel value (default condition is equality)""" + channel_field = "servo%u_raw" % channel + opstring = ("%s" % comparator)[-3:-1] + m = self.assert_receive_message('SERVO_OUTPUT_RAW', timeout=1) + m_value = getattr(m, channel_field, None) + if m_value is None: + raise ValueError("message (%s) has no field %s" % + (str(m), channel_field)) + self.progress("assert SERVO_OUTPUT_RAW.%s=%u %s %u" % + (channel_field, m_value, opstring, value)) + if comparator(m_value, value): + return m_value + raise NotAchievedException("Wrong value") + def get_rc_channel_value(self, channel, timeout=2): """wait for channel to hit value""" channel_field = "chan%u_raw" % channel @@ -5854,6 +6487,16 @@ def wait_rc_channel_value(self, channel, value, timeout=2): if value == m_value: return + def assert_rc_channel_value(self, channel, value): + channel_field = "chan%u_raw" % channel + + m_value = self.get_rc_channel_value(channel, timeout=1) + self.progress("RC_CHANNELS.%s=%u want=%u" % + (channel_field, m_value, value)) + if value != m_value: + raise NotAchievedException("Expected %s to be %u got %u" % + (channel, value, m_value)) + def wait_location(self, loc, accuracy=5.0, @@ -5887,6 +6530,11 @@ def validator(value2, empty=None): **kwargs ) + def assert_current_waypoint(self, wpnum): + seq = self.mav.waypoint_current() + if seq != wpnum: + raise NotAchievedException("Incorrect current wp") + def wait_current_waypoint(self, wpnum, timeout=60): tstart = self.get_sim_time() while True: @@ -5927,7 +6575,7 @@ def wait_waypoint(self, seq = self.mav.waypoint_current() m = self.assert_receive_message('NAV_CONTROLLER_OUTPUT') wp_dist = m.wp_dist - m = self.mav.recv_match(type='VFR_HUD', blocking=True) + m = self.assert_receive_message('VFR_HUD') # if we changed mode, fail if self.mav.flightmode != mode: @@ -5939,7 +6587,7 @@ def wait_waypoint(self, (seq, wp_dist, m.alt, current_wp, wpnum_end)) last_wp_msg = self.get_sim_time_cached() if seq == current_wp+1 or (seq > current_wp+1 and allow_skip): - self.progress("test: Starting new waypoint %u" % seq) + self.progress("WW: Starting new waypoint %u" % seq) tstart = self.get_sim_time() current_wp = seq # the wp_dist check is a hack until we can sort out @@ -6056,6 +6704,9 @@ def wait_sensor_state(self, sensor, present=True, enabled=True, healthy=True, ti if self.sensor_has_state(sensor, present=present, enabled=enabled, healthy=healthy, verbose=verbose): break + def wait_not_ready_to_arm(self): + self.wait_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_PREARM_CHECK, True, True, False) + def wait_prearm_sys_status_healthy(self, timeout=60): self.do_timesync_roundtrip() tstart = self.get_sim_time() @@ -6070,19 +6721,57 @@ def wait_prearm_sys_status_healthy(self, timeout=60): def assert_fence_enabled(self, timeout=2): # Check fence is enabled - m = self.mav.recv_match(type='FENCE_STATUS', blocking=True, timeout=timeout) + m = self.assert_receive_message('FENCE_STATUS', timeout=timeout) self.progress("Got (%s)" % str(m)) - if m is None: - raise NotAchievedException("Fence status was not received") def assert_fence_disabled(self, timeout=2): # Check fence is not enabled - m = self.mav.recv_match(type='FENCE_STATUS', blocking=True, timeout=timeout) - self.progress("Got (%s)" % str(m)) - if m is not None: - raise NotAchievedException("Fence status received unexpectedly") + self.assert_not_receiving_message('FENCE_STATUS', timeout=timeout) + + def assert_prearm_failure(self, + expected_statustext, + timeout=5, + ignore_prearm_failures=[], + other_prearm_failures_fatal=True): + seen_statustext = False + seen_command_ack = False - def assert_prearm_failure(self, expected_statustext, timeout=5, ignore_prearm_failures=[]): + self.drain_mav() + tstart = self.get_sim_time_cached() + arm_last_send = 0 + while True: + if seen_command_ack and seen_statustext: + break + now = self.get_sim_time_cached() + if now - tstart > timeout: + raise NotAchievedException( + "Did not see failure-to-arm messages (statustext=%s command_ack=%s" % + (seen_statustext, seen_command_ack)) + if now - arm_last_send > 1: + arm_last_send = now + self.send_mavlink_run_prearms_command() + m = self.mav.recv_match(blocking=True, timeout=1) + if m is None: + continue + if m.get_type() == "STATUSTEXT": + if expected_statustext in m.text: + self.progress("Got: %s" % str(m)) + seen_statustext = True + elif other_prearm_failures_fatal and "PreArm" in m.text and m.text[8:] not in ignore_prearm_failures: + self.progress("Got: %s" % str(m)) + raise NotAchievedException("Unexpected prearm failure (%s)" % m.text) + + if m.get_type() == "COMMAND_ACK": + print("Got: %s" % str(m)) + if m.command == mavutil.mavlink.MAV_CMD_RUN_PREARM_CHECKS: + if m.result != mavutil.mavlink.MAV_RESULT_ACCEPTED: + raise NotAchievedException("command-ack says we didn't run prearms") + self.progress("Got: %s" % str(m)) + seen_command_ack = True + if self.mav.motors_armed(): + raise NotAchievedException("Armed when we shouldn't have") + + def assert_arm_failure(self, expected_statustext, timeout=5, ignore_prearm_failures=[]): seen_statustext = False seen_command_ack = False @@ -6181,7 +6870,6 @@ def wait_ekf_happy(self, timeout=45, require_absolute=True): def wait_ekf_flags(self, required_value, error_bits, timeout=30): self.progress("Waiting for EKF value %u" % required_value) - self.drain_mav() last_print_time = 0 tstart = self.get_sim_time() while timeout is None or self.get_sim_time_cached() < tstart + timeout: @@ -6392,6 +7080,8 @@ def show_test_timings(self): self.progress(fmt % ("**--tests_total_time--**", tests_total_time)) self.progress("mavproxy_start was called %u times" % (self.start_mavproxy_count,)) + self.progress("Supplied terrain data to autopilot in %u messages" % + (self.terrain_data_messages_sent,)) def send_statustext(self, text): if sys.version_info.major >= 3 and not isinstance(text, bytes): @@ -6406,10 +7096,12 @@ def get_stacktrace(self): def get_exception_stacktrace(self, e): if sys.version_info[0] >= 3: ret = "%s\n" % e - ret += ''.join(traceback.format_exception(etype=type(e), - value=e, + ret += ''.join(traceback.format_exception(type(e), + e, tb=e.__traceback__)) return ret + + # Python2: return traceback.format_exc(e) def bin_logs(self): @@ -6418,6 +7110,10 @@ def bin_logs(self): def remove_bin_logs(self): util.run_cmd('/bin/rm -f logs/*.BIN logs/LASTLOG.TXT') + def remove_ardupilot_terrain_cache(self): + '''removes the terrain files ArduPilot keeps in its onboiard storage''' + util.run_cmd('/bin/rm -f %s' % util.reltopdir("terrain/*.DAT")) + def check_logs(self, name): '''called to move relevant log files from our working directory to the buildlogs directory''' @@ -6452,10 +7148,11 @@ def check_logs(self, name): def run_one_test(self, test, interact=False): '''new-style run-one-test used by run_tests''' for i in range(0, test.attempts-1): - if self.run_one_test_attempt(test, interact=interact, attempt=i+2, do_fail_list=False): - return + result = self.run_one_test_attempt(test, interact=interact, attempt=i+2) + if result.passed: + return result self.progress("Run attempt failed. Retrying") - self.run_one_test_attempt(test, interact=interact, attempt=1) + return self.run_one_test_attempt(test, interact=interact, attempt=1) def print_exception_caught(self, e, send_statustext=True): self.progress("Exception caught: %s" % @@ -6472,7 +7169,7 @@ def progress_file_content(self, filepath): for line in f: self.progress(line.rstrip()) - def run_one_test_attempt(self, test, interact=False, attempt=1, do_fail_list=True): + def run_one_test_attempt(self, test, interact=False, attempt=1): '''called by run_one_test to actually run the test in a retry loop''' name = test.name desc = test.description @@ -6487,7 +7184,7 @@ def run_one_test_attempt(self, test, interact=False, attempt=1, do_fail_list=Tru tee = TeeBoth(test_output_filename, 'w', self.mavproxy_logfile) - start_num_message_hooks = len(self.mav.message_hooks) + start_message_hooks = self.mav.message_hooks prettyname = "%s (%s)" % (name, desc) self.start_test(prettyname) @@ -6497,20 +7194,37 @@ def run_one_test_attempt(self, test, interact=False, attempt=1, do_fail_list=Tru start_time = time.time() + orig_speedup = None + ex = None try: self.check_rc_defaults() self.change_mode(self.default_mode()) + # ArduPilot can still move the current waypoint from 0, + # even if we are not in AUTO mode, so cehck_afterwards=False: + self.set_current_waypoint(0, check_afterwards=False) self.drain_mav() self.drain_all_pexpects() + if test.speedup is not None: + self.progress("Overriding speedup to %u" % test.speedup) + orig_speedup = self.get_parameter("SIM_SPEEDUP") + self.set_parameter("SIM_SPEEDUP", test.speedup) test_function() except Exception as e: self.print_exception_caught(e) ex = e + # reset the message hooks; we've failed-via-exception and + # can't expect the hooks to have been cleaned up + for h in self.mav.message_hooks: + if h not in start_message_hooks: + self.mav.message_hooks.remove(h) self.test_timings[desc] = time.time() - start_time reset_needed = self.contexts[-1].sitl_commandline_customised + if orig_speedup is not None: + self.set_parameter("SIM_SPEEDUP", orig_speedup) + passed = True if ex is not None: passed = False @@ -6521,6 +7235,8 @@ def run_one_test_attempt(self, test, interact=False, attempt=1, do_fail_list=Tru self.print_exception_caught(e, send_statustext=False) passed = False + result = Result(test) + ardupilot_alive = False try: self.wait_heartbeat() @@ -6534,7 +7250,9 @@ def run_one_test_attempt(self, test, interact=False, attempt=1, do_fail_list=Tru tool_filepath = os.path.join(self.rootdir(), 'Tools', 'scripts', tool) if util.run_cmd([tool_filepath, str(self.sitl.pid)]) != 0: self.progress("Failed %s" % (tool,)) - return False + result.description + result.passed = False + return result else: self.progress("pexpect says it is dead") @@ -6553,7 +7271,10 @@ def run_one_test_attempt(self, test, interact=False, attempt=1, do_fail_list=Tru if ex is None: ex = ArmedAtEndOfTestException("Still armed at end of test") self.progress("Armed at end of test; force-rebooting SITL") - self.disarm_vehicle(force=True) + try: + self.disarm_vehicle(force=True) + except AutoTestTimeoutException: + reset_needed = True self.forced_post_test_sitl_reboots += 1 if reset_needed: self.progress("Force-resetting SITL") @@ -6581,14 +7302,21 @@ def run_one_test_attempt(self, test, interact=False, attempt=1, do_fail_list=Tru passed = False if len(self.contexts) != old_contexts_length: - self.progress("context count mismatch (want=%u got=%u)" % + self.progress("context count mismatch (want=%u got=%u); popping extras" % (old_contexts_length, len(self.contexts))) passed = False + # pop off old contexts to clean up message hooks etc + while len(self.contexts) > old_contexts_length: + try: + self.context_pop() + except Exception as e: + self.print_exception_caught(e, send_statustext=False) + self.progress("Done popping extra contexts") # make sure we don't leave around stray listeners: - if len(self.mav.message_hooks) != start_num_message_hooks: - self.progress("Stray message listeners: %s" % - str(self.mav.message_hooks)) + if len(self.mav.message_hooks) != len(start_message_hooks): + self.progress("Stray message listeners: %s vs start %s" % + (str(self.mav.message_hooks), str(start_message_hooks))) passed = False if passed: @@ -6604,8 +7332,8 @@ def run_one_test_attempt(self, test, interact=False, attempt=1, do_fail_list=Tru else: self.progress('FAILED: "%s": %s (see %s)' % (prettyname, repr(ex), test_output_filename)) - if do_fail_list: - self.fail_list.append((prettyname, ex, test_output_filename)) + result.exception = ex + result.debug_filename = test_output_filename if interact: self.progress("Starting MAVProxy interaction as directed") self.mavproxy.interact() @@ -6618,30 +7346,12 @@ def run_one_test_attempt(self, test, interact=False, attempt=1, do_fail_list=Tru if not self.is_tracker(): # FIXME - more to the point, fix Tracker's mission handling self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_ALL) + self.set_current_waypoint(0, check_afterwards=False) tee.close() - return passed - - def check_test_syntax(self, test_file): - """Check mistake on autotest function syntax.""" - self.start_test("Check for syntax mistake in autotest lambda") - if not os.path.isfile(test_file): - self.progress("File %s does not exist" % test_file) - test_file = test_file.rstrip('c') - try: - with open(test_file) as f: - # check for lambda: test_function without paranthesis - faulty_strings = re.findall(r"lambda\s*:\s*\w+.\w+\s*\)", f.read()) - if faulty_strings: - desc = "Syntax error in autotest lambda at : \n" - for x in range(len(faulty_strings)): - desc += faulty_strings[x] + "\n" - raise ErrorException(desc) - except ErrorException as msg: - self.progress("FAILED: Check for syntax mistake in autotest lambda. \n" + str(msg)) - exit(1) - self.progress("PASSED: Check for syntax mistake in autotest lambda") + result.passed = passed + return result def defaults_filepath(self): return None @@ -6717,6 +7427,55 @@ def start_SITL(self, **sitl_args): def get_suplementary_programs(self): return self.sup_prog + def stop_sup_program(self, instance=None): + self.progress("Stopping supplementary program") + if instance is None: + # close all sup programs + for prog in self.sup_prog: + self.expect_list_remove(prog) + self.sup_prog.remove(prog) + util.pexpect_close(prog) + else: + # close only the instance passed + prog = self.sup_prog[instance] + self.expect_list_remove(prog) + self.sup_prog[instance] = None + util.pexpect_close(prog) + + def start_sup_program(self, instance=None, args=None): + self.progress("Starting supplementary program") + start_sitl_args = { + "breakpoints": self.breakpoints, + "disable_breakpoints": self.disable_breakpoints, + "gdb": self.gdb, + "gdb_no_tui": self.gdb_no_tui, + "gdbserver": self.gdbserver, + "lldb": self.lldb, + "home": self.sitl_home(), + "speedup": self.speedup, + "valgrind": self.valgrind, + "callgrind": self.callgrind, + "wipe": True, + } + if instance is None: + for sup_binary in self.sup_binaries: + start_sitl_args["customisations"] = [sup_binary[1]] + if args is not None: + start_sitl_args["customisations"] = [sup_binary[1], args] + start_sitl_args["supplementary"] = True + sup_prog_link = util.start_SITL(sup_binary[0], **start_sitl_args) + self.sup_prog.append(sup_prog_link) # add to list + self.expect_list_add(sup_prog_link) # add to expect list + else: + # start only the instance passed + start_sitl_args["customisations"] = [self.sup_binaries[instance][1]] + if args is not None: + start_sitl_args["customisations"] = [self.sup_binaries[instance][1], args] + start_sitl_args["supplementary"] = True + sup_prog_link = util.start_SITL(self.sup_binaries[instance][0], **start_sitl_args) + self.sup_prog[instance] = sup_prog_link # add to list + self.expect_list_add(sup_prog_link) # add to expect list + def sitl_is_running(self): if self.sitl is None: return False @@ -6727,8 +7486,6 @@ def autostart_mavproxy(self): def init(self): """Initilialize autotest feature.""" - self.check_test_syntax(test_file=self.test_filepath()) - self.mavproxy_logfile = self.open_mavproxy_logfile() if self.frame is None: @@ -6781,8 +7538,9 @@ def upload_using_mission_protocol(self, mission_type, items): mission_type) remaining_to_send = set(range(0, len(items))) sent = set() + timeout = (10 + len(items)/10.0) while True: - if self.get_sim_time_cached() - tstart > (10 + len(items)/10): + if self.get_sim_time_cached() - tstart > timeout: raise NotAchievedException("timeout uploading %s" % str(mission_type)) if len(remaining_to_send) == 0: self.progress("All sent") @@ -6829,6 +7587,9 @@ def upload_using_mission_protocol(self, mission_type, items): self.mav.mav.send(items[m.seq]) remaining_to_send.discard(m.seq) sent.add(m.seq) + + timeout += 10 # we received a good request for item; be generous with our timeouts + m = self.assert_receive_message('MISSION_ACK', timeout=1) if m.mission_type != mission_type: raise NotAchievedException("Mission ack not of expected mission type") @@ -6841,7 +7602,6 @@ def download_using_mission_protocol(self, mission_type, verbose=False, timeout=1 '''mavlink2 required''' target_system = 1 target_component = 1 - self.drain_mav() self.progress("Sending mission_request_list") tstart = self.get_sim_time() self.mav.mav.mission_request_list_send(target_system, @@ -6864,7 +7624,7 @@ def download_using_mission_protocol(self, mission_type, verbose=False, timeout=1 raise NotAchievedException("Received MISSION_ACK while waiting for MISSION_COUNT") if m.get_type() != 'MISSION_COUNT': continue - if m.target_component != 250: # FIXME: constant?! + if m.target_component != self.mav.source_system: continue if m.mission_type != mission_type: raise NotAchievedException("Mission count response of incorrect type") @@ -6874,15 +7634,21 @@ def download_using_mission_protocol(self, mission_type, verbose=False, timeout=1 tstart = self.get_sim_time_cached() remaining_to_receive = set(range(0, m.count)) next_to_request = 0 - timeout = (10 + m.count/10) + timeout = m.count + timeout *= self.speedup / 10.0 + timeout += 10 while True: - if self.get_sim_time_cached() - tstart > timeout: - raise NotAchievedException("timeout downloading type=%s" % - (mavutil.mavlink.enums["MAV_MISSION_TYPE"][mission_type].name)) + delta_t = self.get_sim_time_cached() - tstart + if delta_t > timeout: + raise NotAchievedException( + "timeout downloading type=%s after %s seconds of %s allowed" % + (mavutil.mavlink.enums["MAV_MISSION_TYPE"][mission_type].name, + delta_t, timeout)) if len(remaining_to_receive) == 0: self.progress("All received") return items - self.progress("Requesting item %u" % next_to_request) + self.progress("Requesting item %u (remaining=%u)" % + (next_to_request, len(remaining_to_receive))) self.mav.mav.mission_request_int_send(target_system, target_component, next_to_request, @@ -6893,12 +7659,18 @@ def download_using_mission_protocol(self, mission_type, verbose=False, timeout=1 condition='MISSION_ITEM_INT.mission_type==%u' % mission_type) if m is None: raise NotAchievedException("Did not receive MISSION_ITEM_INT") + if m.target_system != self.mav.source_system: + raise NotAchievedException("Wrong target system (want=%u got=%u)" % + (self.mav.source_system, m.target_system)) + if m.target_component != self.mav.source_component: + raise NotAchievedException("Wrong target component") self.progress("Got (%s)" % str(m)) if m.mission_type != mission_type: raise NotAchievedException("Received waypoint of wrong type") if m.seq != next_to_request: raise NotAchievedException("Received waypoint is out of sequence") self.progress("Item %u OK" % m.seq) + timeout += 10 # we received an item; be generous with our timeouts items.append(m) next_to_request += 1 remaining_to_receive.discard(m.seq) @@ -6941,6 +7713,15 @@ def poll_home_position(self, quiet=True, timeout=30): self.progress("Polled home position (%s)" % str(m)) return m + def position_target_loc(self): + '''returns target location based on POSITION_TARGET_GLOBAL_INT''' + m = self.mav.messages.get("POSITION_TARGET_GLOBAL_INT", None) + return mavutil.location(m.lat_int*1e-7, m.lon_int*1e-7, m.alt) + + def current_waypoint(self): + m = self.assert_receive_message('MISSION_CURRENT') + return m.seq + def distance_to_nav_target(self, use_cached_nav_controller_output=False): '''returns distance to waypoint navigation target in metres''' m = self.mav.messages.get("NAV_CONTROLLER_OUTPUT", None) @@ -6952,8 +7733,7 @@ def distance_to_home(self, use_cached_home=False): m = self.mav.messages.get("HOME_POSITION", None) if use_cached_home is False or m is None: m = self.poll_home_position(quiet=True) - here = self.mav.recv_match(type='GLOBAL_POSITION_INT', - blocking=True) + here = self.assert_receive_message('GLOBAL_POSITION_INT') return self.get_distance_int(m, here) def home_position_as_mav_location(self): @@ -6976,7 +7756,7 @@ def monitor_groundspeed(self, want, tolerance=0.5, timeout=5): while True: if self.get_sim_time_cached() - tstart > timeout: break - m = self.mav.recv_match(type='VFR_HUD', blocking=True) + m = self.assert_receive_message('VFR_HUD', timeout=timeout) if m.groundspeed > want+tolerance: raise NotAchievedException("Too fast (%f > %f)" % (m.groundspeed, want)) @@ -6986,7 +7766,8 @@ def monitor_groundspeed(self, want, tolerance=0.5, timeout=5): self.progress("GroundSpeed OK (got=%f) (want=%f)" % (m.groundspeed, want)) - def fly_test_set_home(self): + def SetHome(self): + '''Setting and fetching of home''' if self.is_tracker(): # tracker starts armed... self.disarm_vehicle(force=True) @@ -7108,7 +7889,6 @@ def fly_test_set_home(self): def zero_mag_offset_parameters(self, compass_count=3): self.progress("Zeroing Mag OFS parameters") - self.drain_mav() self.get_sim_time() self.run_cmd(mavutil.mavlink.MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS, 2, # param1 (compass0) @@ -7153,7 +7933,6 @@ def zero_mag_offset_parameters(self, compass_count=3): def forty_two_mag_dia_odi_parameters(self, compass_count=3): self.progress("Forty twoing Mag DIA and ODI parameters") - self.drain_mav() self.get_sim_time() params = [ [("SIM_MAG_DIA_X", "COMPASS_DIA_X", 42.0), @@ -7210,11 +7989,12 @@ def check_zeros_mag_orient(self, compass_count=3): for count in range(2, compass_count + 1): self.verify_parameter_values({"COMPASS_ORIENT%d" % count: 0}) - def test_mag_calibration(self, compass_count=3, timeout=1000): + # this autotest appears to interfere with FixedYawCalibration, no idea why. + def SITLCompassCalibration(self, compass_count=3, timeout=1000): + '''Test Fixed Yaw Calibration"''' def reset_pos_and_start_magcal(mavproxy, tmask): mavproxy.send("sitl_stop\n") mavproxy.send("sitl_attitude 0 0 0\n") - self.drain_mav() self.get_sim_time() self.run_cmd(mavutil.mavlink.MAV_CMD_DO_START_MAG_CAL, tmask, # p1: mag_mask @@ -7271,7 +8051,6 @@ def do_prep_mag_cal_test(mavproxy, params): if self.is_copter(): # set frame class to pass arming check on copter self.set_parameter("FRAME_CLASS", 1) - self.drain_mav() self.progress("Setting SITL Magnetometer model value") self.set_parameter("COMPASS_AUTO_ROT", 0) # MAG_ORIENT = 4 @@ -7325,6 +8104,7 @@ def do_test_mag_cal(mavproxy, params, compass_tnumber): else: continue if m is not None: + self.progress("Mag CAL progress: %s" % str(m)) cid = m.compass_id new_pct = int(m.completion_pct) if new_pct != reached_pct[cid]: @@ -7378,7 +8158,7 @@ def do_test_mag_cal(mavproxy, params, compass_tnumber): while True: if self.get_sim_time_cached() - tstart > timeout: raise NotAchievedException("Cannot receive enough MAG_CAL_PROGRESS") - m = self.mav.recv_match(type=["MAG_CAL_PROGRESS", "MAG_CAL_REPORT"], blocking=True, timeout=10) + m = self.assert_receive_message(["MAG_CAL_PROGRESS", "MAG_CAL_REPORT"], timeout=10) if m.get_type() == "MAG_CAL_REPORT": if report_get[m.compass_id] == 0: self.progress("Report: %s" % str(m)) @@ -7390,6 +8170,7 @@ def do_test_mag_cal(mavproxy, params, compass_tnumber): self.progress("All Mag report failure") break if m is not None and m.get_type() == "MAG_CAL_PROGRESS": + self.progress("Mag CAL progress: %s" % str(m)) cid = m.compass_id new_pct = int(m.completion_pct) if new_pct != reached_pct[cid]: @@ -7414,7 +8195,7 @@ def do_test_mag_cal(mavproxy, params, compass_tnumber): while True: if self.get_sim_time_cached() - tstart > timeout: raise NotAchievedException("Cannot receive enough MAG_CAL_PROGRESS") - m = self.mav.recv_match(type=["MAG_CAL_PROGRESS", "MAG_CAL_REPORT"], blocking=True, timeout=5) + m = self.assert_receive_message(["MAG_CAL_PROGRESS", "MAG_CAL_REPORT"], timeout=5) if m.get_type() == "MAG_CAL_REPORT": if report_get[m.compass_id] == 0: self.progress("Report: %s" % self.dump_message_verbose(m)) @@ -7588,7 +8369,8 @@ def test_mag_reordering_assert_mag_transform(self, values, transforms): raise NotAchievedException("%s has wrong value; want=%f got=%f transforms=%s (old parameter name=%s)" % (newkey, expected_value, current_value, str(transforms), key)) - def test_mag_reordering(self): + def CompassReordering(self): + '''Test Compass reordering when priorities are changed''' self.context_push() ex = None try: @@ -7690,7 +8472,10 @@ def test_mag_reordering(self): if ex is not None: raise ex - def test_fixed_yaw_calibration(self): + # something about SITLCompassCalibration appears to fail + # this one, so we put it first: + def FixedYawCalibration(self): + '''Test Fixed Yaw Calibration''' self.context_push() ex = None try: @@ -7757,10 +8542,7 @@ def test_fixed_yaw_calibration(self): # wait until we definitely know where we are: self.poll_home_position(timeout=120) - ss = self.mav.recv_match(type='SIMSTATE', blocking=True, timeout=1) - if ss is None: - raise NotAchievedException("Did not get SIMSTATE") - self.progress("Got SIMSTATE (%s)" % str(ss)) + ss = self.assert_receive_message('SIMSTATE', timeout=1, verbose=True) self.run_cmd(mavutil.mavlink.MAV_CMD_FIXED_MAG_CAL_YAW, math.degrees(ss.yaw), # param1 @@ -7786,7 +8568,8 @@ def test_fixed_yaw_calibration(self): if ex is not None: raise ex - def test_dataflash_over_mavlink(self): + def DataFlashOverMAVLink(self): + '''Test DataFlash over MAVLink''' self.context_push() ex = None mavproxy = self.start_mavproxy() @@ -7851,8 +8634,8 @@ def test_dataflash_over_mavlink(self): if ex is not None: raise ex - def test_dataflash_sitl(self): - """Test the basic functionality of block logging""" + def DataFlash(self): + """Test DataFlash SITL backend""" self.context_push() ex = None mavproxy = self.start_mavproxy() @@ -7948,7 +8731,7 @@ def __exit__(self, *args): if herrors > header_errors: raise NotAchievedException("Error parsing log file %s, %d header errors" % (logname, herrors)) - def test_dataflash_erase(self): + def DataFlashErase(self): """Test that erasing the dataflash chip and creating a new log is error free""" mavproxy = self.start_mavproxy() @@ -8030,8 +8813,8 @@ def test_dataflash_erase(self): if ex is not None: raise ex - def test_arm_feature(self): - """Common feature to test.""" + def ArmFeatures(self): + '''Arm features''' # TEST ARMING/DISARM if self.get_parameter("ARMING_CHECK") != 1.0 and not self.is_sub(): raise ValueError("Arming check should be 1") @@ -8054,15 +8837,14 @@ def test_arm_feature(self): if not self.arm_vehicle(): raise NotAchievedException("Failed to ARM") self.progress("default disarm_vehicle() call") - if not self.disarm_vehicle(): - raise NotAchievedException("Failed to DISARM") + self.disarm_vehicle() + self.progress("arm with mavproxy") mavproxy = self.start_mavproxy() if not self.mavproxy_arm_vehicle(mavproxy): raise NotAchievedException("Failed to ARM") self.progress("disarm with mavproxy") - if not self.mavproxy_disarm_vehicle(mavproxy): - raise NotAchievedException("Failed to DISARM") + self.mavproxy_disarm_vehicle(mavproxy) self.stop_mavproxy(mavproxy) if not self.is_sub(): @@ -8204,8 +8986,7 @@ def test_arm_feature(self): self.progress("Armable mode : %s" % mode) self.change_mode(mode) self.arm_vehicle() - if not self.disarm_vehicle(): - raise NotAchievedException("Failed to DISARM") + self.disarm_vehicle() self.progress("PASS arm mode : %s" % mode) if mode in self.get_not_armable_mode_list(): if mode in self.get_not_disarmed_settable_modes_list(): @@ -8236,8 +9017,7 @@ def test_arm_feature(self): self.change_mode(mode) self.arm_vehicle() self.wait_heartbeat() - if not self.disarm_vehicle(): - raise NotAchievedException("Failed to DISARM") + self.disarm_vehicle() self.progress("PASS arm mode : %s" % mode) self.progress("Not armable mode without Position : %s" % mode) self.wait_gps_disable() @@ -8271,48 +9051,60 @@ def test_arm_feature(self): self.set_parameter("FOLL_ENABLE", 0) self.change_mode(self.default_mode()) if self.armed(): - if not self.disarm_vehicle(): - raise NotAchievedException("Failed to DISARM") + self.disarm_vehicle() # we should find at least one Armed event and one disarmed # event, and at least one ARM message for arm and disarm - self.progress("Checking for an arm event") - dfreader = self.dfreader_for_current_onboard_log() - m = dfreader.recv_match(type="EV", condition="EV.Id==10") # armed - if m is None: - raise NotAchievedException("Did not find an Armed EV message") + wants = set([ + ("Armed EV message", "EV", lambda e : e.Id == 10), + ("Disarmed EV message", "EV", lambda e : e.Id == 11), + ("Armed ARM message", "ARM", lambda a : a.ArmState == 1), + ("Disarmed ARM message", "ARM", lambda a : a.ArmState == 0), + ]) - self.progress("Checking for a disarm event") dfreader = self.dfreader_for_current_onboard_log() - m = dfreader.recv_match(type="EV", condition="EV.Id==11") # disarmed - if m is None: - raise NotAchievedException("Did not find a disarmed EV message") + types = set() + for (name, msgtype, l) in wants: + types.add(msgtype) - self.progress("Checking for ARM.ArmState==1") - dfreader = self.dfreader_for_current_onboard_log() - m = dfreader.recv_match(type="ARM", condition="ARM.ArmState==1") - if m is None: - raise NotAchievedException("Did not find a armed ARM message") + while True: + m = dfreader.recv_match(type=types) + if m is None: + break + wantscopy = copy.copy(wants) + for want in wantscopy: + (name, msgtype, l) = want + if m.get_type() != msgtype: + continue + if l(m): + self.progress("Found %s" % name) + wants.discard(want) + if len(wants) == 0: + break - self.progress("Checking for ARM.ArmState==0") - dfreader = self.dfreader_for_current_onboard_log() - m = dfreader.recv_match(type="ARM", condition="ARM.ArmState==0") - if m is None: - raise NotAchievedException("Did not find a disarmed ARM message") + if len(wants): + msg = ", ".join([x[0] for x in wants]) + raise NotAchievedException("Did not find (%s)" % msg) self.progress("ALL PASS") # TODO : Test arming magic; - def get_message_rate(self, victim_message, timeout): + def get_message_rate(self, victim_message, timeout=10, mav=None): + if mav is None: + mav = self.mav tstart = self.get_sim_time() count = 0 while self.get_sim_time_cached() < tstart + timeout: - m = self.mav.recv_match(type=victim_message, - blocking=True, - timeout=0.1 - ) + m = mav.recv_match( + type=victim_message, + blocking=True, + timeout=0.1 + ) if m is not None: count += 1 + if mav != self.mav: + self.drain_mav(self.mav) + time_delta = self.get_sim_time_cached() - tstart self.progress("%s count after %f seconds: %u" % (victim_message, time_delta, count)) @@ -8321,7 +9113,7 @@ def get_message_rate(self, victim_message, timeout): def rate_to_interval_us(self, rate): return 1/float(rate)*1000000.0 - def set_message_rate_hz(self, id, rate_hz): + def set_message_rate_hz(self, id, rate_hz, mav=None): '''set a message rate in Hz; 0 for original, -1 to disable''' if type(id) == str: id = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % id) @@ -8336,15 +9128,20 @@ def set_message_rate_hz(self, id, rate_hz): 0, 0, 0, - 0) + 0, + mav=mav) - def send_get_message_interval(self, victim_message_id): - self.mav.mav.command_long_send( + def send_get_message_interval(self, victim_message, mav=None): + if mav is None: + mav = self.mav + if type(victim_message) == str: + victim_message = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % victim_message) + mav.mav.command_long_send( 1, 1, mavutil.mavlink.MAV_CMD_GET_MESSAGE_INTERVAL, 1, # confirmation - float(victim_message_id), + float(victim_message), 0, 0, 0, @@ -8352,23 +9149,39 @@ def send_get_message_interval(self, victim_message_id): 0, 0) - def test_rate(self, desc, in_rate, expected_rate): + def test_rate(self, + desc, + in_rate, + expected_rate + , mav=None, + victim_message="VFR_HUD", + ndigits=0, + message_rate_sample_period=10): + if mav is None: + mav = self.mav + self.progress("###### %s" % desc) - self.progress("Setting rate to %u" % in_rate) + self.progress("Setting rate to %f" % round(in_rate, ndigits=ndigits)) - self.set_message_rate_hz(self.victim_message_id, in_rate) + self.set_message_rate_hz(victim_message, in_rate, mav=mav) - new_measured_rate = self.get_message_rate(self.victim_message, 10) - self.progress("Measured rate: %f (want %u)" % - (new_measured_rate, expected_rate)) - if round(new_measured_rate) != expected_rate: - raise NotAchievedException("Rate not achieved (got %f want %u)" % - (new_measured_rate, expected_rate)) + new_measured_rate = self.get_message_rate(victim_message, timeout=message_rate_sample_period, mav=mav) + self.progress( + "Measured rate: %f (want %f)" % + (round(new_measured_rate, ndigits=ndigits), + round(expected_rate, ndigits=ndigits)) + ) + notachieved_ex = None + if round(new_measured_rate, ndigits=ndigits) != round(expected_rate, ndigits=ndigits): + notachieved_ex = NotAchievedException( + "Rate not achieved (got %f want %f)" % + (round(new_measured_rate, ndigits), + round(expected_rate, ndigits))) # make sure get_message_interval works: - self.send_get_message_interval(self.victim_message_id) + self.send_get_message_interval(victim_message, mav=mav) - m = self.mav.recv_match(type='MESSAGE_INTERVAL', blocking=True) + m = self.assert_receive_message('MESSAGE_INTERVAL', timeout=30, mav=mav) if in_rate == 0: want = self.rate_to_interval_us(expected_rate) @@ -8380,11 +9193,15 @@ def test_rate(self, desc, in_rate, expected_rate): if m.interval_us != want: raise NotAchievedException("Did not read same interval back from autopilot: want=%d got=%d)" % (want, m.interval_us)) - m = self.mav.recv_match(type='COMMAND_ACK', blocking=True) + m = self.assert_receive_message('COMMAND_ACK', mav=mav) if m.result != mavutil.mavlink.MAV_RESULT_ACCEPTED: raise NotAchievedException("Expected ACCEPTED for reading message interval") - def test_set_message_interval(self): + if notachieved_ex is not None: + raise notachieved_ex + + def SET_MESSAGE_INTERVAL(self): + '''Test MAV_CMD_SET_MESSAGE_INTERVAL''' self.start_subtest('Basic tests') self.test_set_message_interval_basic() self.start_subtest('Many-message tests') @@ -8414,22 +9231,22 @@ def test_set_message_interval_many(self): if ex is not None: raise ex - def assert_message_rate_hz(self, message, want_rate, sample_period=20): - self.drain_mav() - rate = round(self.get_message_rate(message, sample_period)) - self.progress("%s: Want=%u got=%u" % (message, want_rate, rate)) + def assert_message_rate_hz(self, message, want_rate, sample_period=20, ndigits=0, mav=None): + if mav is None: + mav = self.mav + self.drain_mav(mav) + rate = round(self.get_message_rate(message, sample_period, mav=mav), ndigits=ndigits) + self.progress("%s: Want=%f got=%f" % (message, round(want_rate, ndigits=ndigits), round(rate, ndigits=ndigits))) if rate != want_rate: - raise NotAchievedException("Did not get expected rate (want=%u got=%u" % (want_rate, rate)) + raise NotAchievedException("Did not get expected rate (want=%f got=%f)" % (want_rate, rate)) def test_set_message_interval_basic(self): - self.victim_message = 'VFR_HUD' - self.victim_message_id = mavutil.mavlink.MAVLINK_MSG_ID_VFR_HUD ex = None try: - rate = round(self.get_message_rate(self.victim_message, 20)) + rate = round(self.get_message_rate("VFR_HUD", 20)) self.progress("Initial rate: %u" % rate) - self.test_rate("Test set to %u" % (rate/2,), rate/2, rate/2) + self.test_rate("Test set to %u" % (rate/2,), rate/2, rate/2, victim_message="VFR_HUD") # this assumes the streamrates have not been played with: self.test_rate("Resetting original rate using 0-value", 0, rate) self.test_rate("Disabling using -1-value", -1, 0) @@ -8463,10 +9280,10 @@ def test_set_message_interval_basic(self): non_existant_id = 145 self.send_get_message_interval(non_existant_id) - m = self.mav.recv_match(type='MESSAGE_INTERVAL', blocking=True) + m = self.assert_receive_message('MESSAGE_INTERVAL') if m.interval_us != 0: raise NotAchievedException("Supposed to get 0 back for unsupported stream") - m = self.mav.recv_match(type='COMMAND_ACK', blocking=True) + m = self.assert_receive_message('COMMAND_ACK') if m.result != mavutil.mavlink.MAV_RESULT_FAILED: raise NotAchievedException("Getting rate of unsupported message is a failure") @@ -8497,7 +9314,6 @@ def send_poll_message(self, message_id, target_sysid=None, target_compid=None): def poll_message(self, message_id, timeout=10): if type(message_id) == str: message_id = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % message_id) - self.drain_mav() tstart = self.get_sim_time() # required for timeout in run_cmd_get_ack to work self.send_poll_message(message_id) self.run_cmd_get_ack( @@ -8539,7 +9355,8 @@ def get_msgs(mav, m): return msgs - def test_request_message(self, timeout=60): + def REQUEST_MESSAGE(self, timeout=60): + '''Test MAV_CMD_REQUEST_MESSAGE''' rate = round(self.get_message_rate("CAMERA_FEEDBACK", 10)) if rate != 0: raise PreconditionFailedException("Receiving camera feedback") @@ -8590,7 +9407,8 @@ def clear_fence_using_mavproxy(self, mavproxy, timeout=10): def clear_fence(self): self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE) - def test_config_error_loop(self): + # Sub does not instantiate AP_Stats. Also see https://github.com/ArduPilot/ardupilot/issues/10247 # noqa + def ConfigErrorLoop(self): '''test the sensor config error loop works and that parameter sets are persistent''' parameter_name = "SERVO8_MIN" old_parameter_value = self.get_parameter(parameter_name) @@ -8632,7 +9450,8 @@ def test_config_error_loop(self): if self.get_parameter(parameter_name) != new_parameter_value: raise NotAchievedException("Parameter value did not stick") - def test_initial_mode(self): + def InitialMode(self): + '''Test initial mode switching''' if self.is_copter(): init_mode = (9, "LAND") if self.is_rover(): @@ -8655,7 +9474,8 @@ def test_initial_mode(self): self.context_pop() self.reboot_sitl() - def test_gripper(self): + def Gripper(self): + '''Test gripper''' self.context_push() self.set_parameters({ "GRIP_ENABLE": 1, @@ -8751,7 +9571,62 @@ def test_gripper(self): self.context_pop() self.reboot_sitl() - def test_set_position_global_int(self, timeout=100): + def install_terrain_handlers_context(self): + '''install a message handler into the current context which will + listen for an fulfill terrain requests from ArduPilot. Will + die if the data is not available - but + self.terrain_in_offline_mode can be set to true in the + constructor to change this behaviour + ''' + + def check_terrain_requests(mav, m): + if m.get_type() != 'TERRAIN_REQUEST': + return + self.progress("Processing TERRAIN_REQUEST (%s)" % + self.dump_message_verbose(m)) + # swiped from mav_terrain.py + for bit in range(56): + if m.mask & (1 << bit) == 0: + continue + + lat = m.lat * 1.0e-7 + lon = m.lon * 1.0e-7 + bit_spacing = m.grid_spacing * 4 + (lat, lon) = mp_util.gps_offset(lat, lon, + east=bit_spacing * (bit % 8), + north=bit_spacing * (bit // 8)) + data = [] + for i in range(4*4): + y = i % 4 + x = i // 4 + (lat2, lon2) = mp_util.gps_offset(lat, lon, + east=m.grid_spacing * y, + north=m.grid_spacing * x) + # if we are in online mode then we'll try to fetch + # from the internet into the cache dir: + for i in range(120): + alt = self.elevationmodel.GetElevation(lat2, lon2) + if alt is not None: + break + if self.terrain_in_offline_mode: + break + self.progress("No elevation data for (%f %f); retry" % + (lat2, lon2)) + time.sleep(1) + if alt is None: + # no data - we can't send the packet + raise ValueError("No elevation data for (%f %f)" % (lat2, lon2)) + data.append(int(alt)) + self.terrain_data_messages_sent += 1 + self.mav.mav.terrain_data_send(m.lat, + m.lon, + m.grid_spacing, + bit, + data) + + self.install_message_hook_context(check_terrain_requests) + + def SetpointGlobalPos(self, timeout=100): """Test set position message in guided mode.""" # Disable heading and yaw test on rover type @@ -8764,10 +9639,7 @@ def test_set_position_global_int(self, timeout=100): test_heading = True test_yaw_rate = True - # we must start mavproxy here as otherwise we can't get the - # terrain database tiles - this leads to random failures in - # CI! - mavproxy = self.start_mavproxy() + self.install_terrain_handlers_context() self.set_parameter("FS_GCS_ENABLE", 0) self.change_mode("GUIDED") @@ -8973,13 +9845,11 @@ def send_yaw_rate(rate, target=None): called_function=lambda plop, empty: send_yaw_rate( target_rate, None), minimum_duration=5) - self.stop_mavproxy(mavproxy) - self.progress("Getting back to home and disarm") self.do_RTL(distance_min=0, distance_max=wp_accuracy) self.disarm_vehicle() - def test_set_velocity_global_int(self, timeout=30): + def SetpointGlobalVel(self, timeout=30): """Test set position message in guided mode.""" # Disable heading and yaw rate test on rover type if self.is_rover(): @@ -8991,10 +9861,7 @@ def test_set_velocity_global_int(self, timeout=30): test_heading = True test_yaw_rate = True - # we must start mavproxy here as otherwise we can't get the - # terrain database tiles - this leads to random failures in - # CI! - mavproxy = self.start_mavproxy() + self.install_terrain_handlers_context() self.set_parameter("FS_GCS_ENABLE", 0) self.change_mode("GUIDED") @@ -9340,8 +10207,6 @@ def send_yaw_rate_vel(rate, vector, mav_frame): minimum_duration=2 ) - self.stop_mavproxy(mavproxy) - self.progress("Getting back to home and disarm") self.do_RTL(distance_min=0, distance_max=wp_accuracy) self.disarm_vehicle() @@ -9468,10 +10333,6 @@ def end_subsubtest(self, description): '''TODO: sanity checks?''' pass - def test_skipped(self, test, reason): - self.progress("##### %s is skipped: %s" % (test, reason)) - self.skip_list.append((test, reason)) - def last_onboard_log(self): '''return number of last onboard log''' mavproxy = self.start_mavproxy() @@ -9514,13 +10375,17 @@ def current_onboard_log_contains_message(self, messagetype): print("m=%s" % str(m)) return m is not None + def assert_current_onboard_log_contains_message(self, messagetype): + if not self.current_onboard_log_contains_message(messagetype): + raise NotAchievedException("Current onboard log does not contain message %s" % messagetype) + def run_tests(self, tests): """Autotest vehicle in SITL.""" if self.run_tests_called: raise ValueError("run_tests called twice") self.run_tests_called = True - self.fail_list = [] + result_list = [] try: self.init() @@ -9537,11 +10402,14 @@ def run_tests(self, tests): for test in tests: self.drain_mav_unparsed() - self.run_one_test(test) + result_list.append(self.run_one_test(test)) except pexpect.TIMEOUT: self.progress("Failed with timeout") - self.fail_list.append(["Failed with timeout", None, None]) + result = Result(test) + result.passed = False + result.reason = "Failed with timeout" + result_list.append(result) if self.logs_dir: if glob.glob("core*") or glob.glob("ap-*.core"): self.check_logs("FRAMEWORK") @@ -9553,20 +10421,7 @@ def run_tests(self, tests): self.rc_thread = None self.close() - if len(self.skip_list): - self.progress("Skipped tests:") - for skipped in self.skip_list: - (test, reason) = skipped - print(" %s (see %s)" % (test.name, reason)) - - if len(self.fail_list): - self.progress("Failing tests:") - for failure in self.fail_list: - (desc, exception, debug_filename) = failure - print(" %s (%s) (see %s)" % (desc, exception, debug_filename)) - return False - - return True + return result_list def dictdiff(self, dict1, dict2): fred = copy.copy(dict1) @@ -9707,8 +10562,11 @@ def test_parameter_documentation(self): self.start_subsubtest("Check all parameters are documented") self.test_parameter_documentation_get_all_parameters() - def test_parameters(self): + def Parameters(self): '''general small tests for parameter system''' + if self.is_balancebot(): + # same binary and parameters as Rover + return self.test_parameter_documentation() self.test_parameters_mis_total() self.test_parameters_download() @@ -9743,13 +10601,16 @@ def test_parameter_checks_poscontrol(self, param_prefix): want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED) self.disarm_vehicle() - def assert_not_receiving_message(self, message, timeout=1): + def assert_not_receiving_message(self, message, timeout=1, mav=None): self.progress("making sure we're not getting %s messages" % message) - m = self.mav.recv_match(type=message, blocking=True, timeout=timeout) + if mav is None: + mav = self.mav + m = mav.recv_match(type=message, blocking=True, timeout=timeout) if m is not None: raise PreconditionFailedException("Receiving %s messags" % message) - def test_pid_tuning(self): + def PIDTuning(self): + '''Test PID Tuning''' self.assert_not_receiving_message('PID_TUNING', timeout=5) self.set_parameter("GCS_PID_MASK", 1) self.progress("making sure we are now getting PID_TUNING messages") @@ -9758,7 +10619,8 @@ def test_pid_tuning(self): def sample_mission_filename(self): return "flaps.txt" - def test_advanced_failsafe(self): + def AdvancedFailsafe(self): + '''Test Advanced Failsafe''' self.context_push() ex = None try: @@ -9843,14 +10705,15 @@ def wait_gps_fix_type_gte(self, fix_type, timeout=30, message_type="GPS_RAW_INT" if m.fix_type >= fix_type: break - def nmea_output(self): + def NMEAOutput(self): + '''Test AHRS NMEA Output can be read by out NMEA GPS''' self.set_parameter("SERIAL5_PROTOCOL", 20) # serial5 is NMEA output self.set_parameter("GPS_TYPE2", 5) # GPS2 is NMEA self.customise_SITL_commandline([ "--uartE=tcp:6735", # GPS2 is NMEA.... "--uartF=tcpclient:127.0.0.1:6735", # serial5 spews to localhost:6735 ]) - self.drain_mav_unparsed() + self.do_timesync_roundtrip() self.wait_gps_fix_type_gte(3) gps1 = self.mav.recv_match(type="GPS_RAW_INT", blocking=True, timeout=10) self.progress("gps1=(%s)" % str(gps1)) @@ -9881,7 +10744,8 @@ def mavproxy_unload_module(self, mavproxy, module): mavproxy.send("module unload %s\n" % module) mavproxy.expect("Unloaded module %s" % module) - def accelcal(self): + def AccelCal(self): + '''Accelerometer Calibration testing''' ex = None mavproxy = self.start_mavproxy() try: @@ -10030,19 +10894,21 @@ def ahrstrim_attitude_correctness(self): self.wait_attitude(desroll=0, despitch=0, timeout=120, tolerance=1.5) if ahrs_type != 0: # we don't get secondary msgs while DCM is primary self.wait_attitude(desroll=0, despitch=0, message_type='AHRS2', tolerance=1, timeout=120) - # self.send_debug_trap() self.wait_attitude_quaternion(desroll=0, despitch=0, tolerance=1, timeout=120) self.context_pop() self.reboot_sitl() - def ahrstrim(self): + def AHRSTrim(self): + '''AHRS trim testing''' self.start_subtest("Attitude Correctness") self.ahrstrim_attitude_correctness() + self.delay_sim_time(5) self.start_subtest("Preflight Calibration") self.ahrstrim_preflight_cal() - def test_button(self): + def Button(self): + '''Test Buttons''' self.set_parameter("SIM_PIN_MASK", 0) self.set_parameter("BTN_ENABLE", 1) self.drain_mav() @@ -10087,12 +10953,14 @@ def test_button(self): self.progress("Skipping arm/disarm tests for tracker") return + self.context_push() self.wait_ready_to_arm() self.set_parameter("BTN_FUNC%u" % btn, 153) # ARM/DISARM self.set_parameter("SIM_PIN_MASK", mask) self.wait_armed() self.set_parameter("SIM_PIN_MASK", 0) self.wait_disarmed() + self.context_pop() if self.is_rover(): self.context_push() @@ -10440,9 +11308,16 @@ def test_frsky_passthrough_do_wants(self, frsky, wants): self.progress(" Fulfilled") del wants[want] - def test_frsky_passthrough(self): - self.set_parameter("SERIAL5_PROTOCOL", 10) # serial5 is FRSky passthrough - self.set_parameter("RPM1_TYPE", 10) # enable RPM output + def FRSkyPassThroughStatustext(self): + '''test FRSKy protocol's telem-passthrough functionality''' + # we disable terrain here as RCTelemetry can queue a lot of + # statustexts if terrain tiles aren't available which can + # happen on the autotest server. + self.set_parameters({ + "SERIAL5_PROTOCOL": 10, # serial5 is FRSky passthrough + "RPM1_TYPE": 10, # enable RPM output + "TERRAIN_ENABLE": 0, + }) self.customise_SITL_commandline([ "--uartF=tcp:6735" # serial5 spews to localhost:6735 ]) @@ -10460,6 +11335,7 @@ def test_frsky_passthrough(self): tstart = self.get_sim_time() old_data = None text = "" + self.context_collect('STATUSTEXT') self.run_cmd(mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, 0, # p1 @@ -10472,10 +11348,11 @@ def test_frsky_passthrough(self): received_frsky_texts = [] last_len_received_statustexts = 0 + timeout = 7 * self.speedup # it can take a *long* time to get these messages down! while True: self.drain_mav() now = self.get_sim_time_cached() - if now - tstart > 60: # it can take a *long* time to get these messages down! + if now - tstart > timeout: raise NotAchievedException("Did not get statustext in time") frsky.update() data = frsky.get_data(0x5000) # no timestamping on this data, so we can't catch legitimate repeats. @@ -10501,7 +11378,8 @@ def test_frsky_passthrough(self): m = None text = text.rstrip("\0") self.progress("Received frsky text (%s)" % (text,)) - self.progress("context texts: %s" % str([x.text for x in self.context_collection('STATUSTEXT')])) + self.progress("context texts: %s" % + str([st.text for st in self.context_collection('STATUSTEXT')])) m = self.statustext_in_collections(text) if m is not None: want_sev = m.severity @@ -10514,21 +11392,31 @@ def test_frsky_passthrough(self): received_statustexts = self.context_collection('STATUSTEXT') if len(received_statustexts) != last_len_received_statustexts: last_len_received_statustexts = len(received_statustexts) - self.progress("received statustexts: %s" % str([x.text for x in received_statustexts])) + self.progress("received statustexts: %s" % str([st.text for st in received_statustexts])) self.progress("received frsky texts: %s" % str(received_frsky_texts)) - for (want_sev, text) in received_frsky_texts: + for (want_sev, received_text) in received_frsky_texts: for m in received_statustexts: - if m.text == text: + if m.text == received_text: if want_sev != m.severity: raise NotAchievedException("Incorrect severity; want=%u got=%u" % (want_sev, severity)) - self.progress("Got statustext (%s)" % text) + self.progress("Got statustext (%s)" % received_text) break - self.context_stop_collecting('STATUSTEXT') + + def FRSkyPassThroughSensorIDs(self): + '''test FRSKy protocol's telem-passthrough functionality (sensor IDs)''' + self.set_parameters({ + "SERIAL5_PROTOCOL": 10, # serial5 is FRSky passthrough + "RPM1_TYPE": 10, # enable RPM output + }) + self.customise_SITL_commandline([ + "--uartF=tcp:6735" # serial5 spews to localhost:6735 + ]) + frsky = FRSkyPassThrough(("127.0.0.1", 6735), + get_time=self.get_sim_time_cached) self.wait_ready_to_arm() # we need to start the engine to get some RPM readings, we do it for plane only - self.drain_mav_unparsed() # anything with a lambda in here needs a proper test written. # This, at least makes sure we're getting some of each # message. These are ordered according to the wfq scheduler @@ -10559,8 +11447,9 @@ def test_frsky_passthrough(self): } self.test_frsky_passthrough_do_wants(frsky, wants) self.zero_throttle() - if not self.disarm_vehicle(): - raise NotAchievedException("Failed to DISARM") + self.progress("Wait for vehicle to slow down") + self.wait_groundspeed(0, 0.3) + self.disarm_vehicle() self.progress("Counts of sensor_id polls sent:") frsky.dump_sensor_id_poll_counts_as_progress_messages() @@ -10581,14 +11470,13 @@ def decode_mavlite_command_ack(self, message): def read_message_via_mavlite(self, frsky, sport_to_mavlite): '''read bytes from frsky mavlite stream, trying to form up a mavlite message''' - self.drain_mav(quiet=True) tstart = self.get_sim_time() + timeout = 30 * self.speedup/10.0 + if self.valgrind or self.callgrind: + timeout *= 10 while True: self.drain_mav(quiet=True) tnow = self.get_sim_time_cached() - timeout = 30 - if self.valgrind or self.callgrind: - timeout *= 10 if tnow - tstart > timeout: raise NotAchievedException("Did not get parameter via mavlite") frsky.update() @@ -10599,11 +11487,10 @@ def read_message_via_mavlite(self, frsky, sport_to_mavlite): return message def read_parameter_via_mavlite(self, frsky, sport_to_mavlite, name): - self.drain_mav(quiet=True) tstart = self.get_sim_time() while True: tnow = self.get_sim_time_cached() - if tnow - tstart > 30: + if tnow - tstart > 30 * self.speedup / 10.0: raise NotAchievedException("Did not get parameter via mavlite") message = self.read_message_via_mavlite(frsky, sport_to_mavlite) if message.msgid != mavutil.mavlink.MAVLINK_MSG_ID_PARAM_VALUE: @@ -10672,7 +11559,8 @@ def run_cmd_via_mavlite_get_ack(self, frsky, sport_to_mavlite, command, want_res "Did not receive expected result in command_ack; want=%u got=%u" % (want_result, got_result)) - def test_frsky_mavlite(self): + def FRSkyMAVlite(self): + '''Test FrSky MAVlite serial output''' self.set_parameter("SERIAL5_PROTOCOL", 10) # serial5 is FRSky passthrough self.customise_SITL_commandline([ "--uartF=tcp:6735" # serial5 spews to localhost:6735 @@ -10929,7 +11817,7 @@ def wait_rpm1(self, min_rpm=None, timeout=10): tstart = self.get_sim_time() while True: t = self.get_sim_time_cached() - if t - tstart > 10: + if t - tstart > timeout: raise AutoTestTimeoutException("Failed to do get valid RPM") rpm = self.mav.recv_match( type='RPM', @@ -10944,7 +11832,8 @@ def wait_rpm1(self, min_rpm=None, timeout=10): if rpm.rpm1 >= min_rpm: return - def test_frsky_sport(self): + def FRSkySPort(self): + '''Test FrSky SPort mode''' self.set_parameter("SERIAL5_PROTOCOL", 4) # serial5 is FRSky sport self.set_parameter("RPM1_TYPE", 10) # enable SITL RPM sensor self.customise_SITL_commandline([ @@ -10961,7 +11850,9 @@ def test_frsky_sport(self): self.set_rc(3, 1050) self.wait_rpm1(timeout=10, min_rpm=200) - self.drain_mav_unparsed() + self.assert_current_onboard_log_contains_message("RPM") + + self.drain_mav() # anything with a lambda in here needs a proper test written. # This, at least makes sure we're getting some of each # message. @@ -11012,17 +11903,16 @@ def test_frsky_sport(self): # ok done, stop the engine if self.is_plane(): self.zero_throttle() - if not self.disarm_vehicle(): - raise NotAchievedException("Failed to DISARM") + self.disarm_vehicle(force=True) - def test_frsky_d(self): + def FRSkyD(self): + '''Test FrSkyD serial output''' self.set_parameter("SERIAL5_PROTOCOL", 3) # serial5 is FRSky output self.customise_SITL_commandline([ "--uartF=tcp:6735" # serial5 spews to localhost:6735 ]) frsky = FRSkyD(("127.0.0.1", 6735)) self.wait_ready_to_arm() - self.drain_mav_unparsed() m = self.assert_receive_message('GLOBAL_POSITION_INT', timeout=1) gpi_abs_alt = int((m.alt+500) / 1000) # mm -> m @@ -11064,8 +11954,7 @@ def test_frsky_d(self): if have_alt and have_battery: break - - self.drain_mav_unparsed() + self.drain_mav() def test_ltm_g(self, ltm): g = ltm.g() @@ -11109,7 +11998,7 @@ def test_ltm_a(self, ltm): a = ltm.a() if a is None: return - m = self.mav.recv_match(type='ATTITUDE', blocking=True) + m = self.assert_receive_message('ATTITUDE') pitch = a.pitch() print("pitch: %s" % str(pitch)) @@ -11138,14 +12027,14 @@ def test_ltm_s(self, ltm): # FIXME. Actually check the field values are correct :-) return True - def test_ltm(self): + def LTM(self): + '''Test LTM serial output''' self.set_parameter("SERIAL5_PROTOCOL", 25) # serial5 is LTM output self.customise_SITL_commandline([ "--uartF=tcp:6735" # serial5 spews to localhost:6735 ]) ltm = LTM(("127.0.0.1", 6735)) self.wait_ready_to_arm() - self.drain_mav_unparsed() wants = { "g": self.test_ltm_g, @@ -11153,7 +12042,7 @@ def test_ltm(self): "s": self.test_ltm_s, } - tstart = self.get_sim_time_cached() + tstart = self.get_sim_time() while True: self.progress("Still wanting (%s)" % ",".join([("%s" % x) for x in wants.keys()])) @@ -11180,6 +12069,7 @@ def convertDmsToDdFormat(self, dms): return math.trunc(dd * 1.0e7) def DEVO(self): + '''Test DEVO serial output''' self.context_push() self.set_parameter("SERIAL5_PROTOCOL", 17) # serial5 is DEVO output self.customise_SITL_commandline([ @@ -11187,7 +12077,6 @@ def DEVO(self): ]) devo = DEVO(("127.0.0.1", 6735)) self.wait_ready_to_arm() - self.drain_mav_unparsed() m = self.assert_receive_message('GLOBAL_POSITION_INT', timeout=1) tstart = self.get_sim_time_cached() @@ -11251,7 +12140,8 @@ def DEVO(self): self.context_pop() self.reboot_sitl() - def test_msp_dji(self): + def MSP_DJI(self): + '''Test MSP DJI serial output''' self.set_parameter("SERIAL5_PROTOCOL", 33) # serial5 is MSP DJI output self.set_parameter("MSP_OPTIONS", 1) # telemetry (unpolled) mode self.customise_SITL_commandline([ @@ -11259,15 +12149,13 @@ def test_msp_dji(self): ]) msp = MSP_DJI(("127.0.0.1", 6735)) self.wait_ready_to_arm() - self.drain_mav_unparsed() - tstart = self.get_sim_time_cached() + tstart = self.get_sim_time() while True: self.drain_mav() if self.get_sim_time_cached() - tstart > 10: raise NotAchievedException("Did not get location") msp.update() - self.drain_mav_unparsed(quiet=True) try: f = msp.get_frame(msp.FRAME_GPS_RAW) except KeyError: @@ -11277,7 +12165,8 @@ def test_msp_dji(self): if dist < 1: break - def test_crsf(self): + def CRSF(self): + '''Test RC CRSF''' self.context_push() ex = None try: @@ -11341,13 +12230,14 @@ def GPSTypes(self): (8, "NOVA", 15, "NOVA"), # no attempt to auto-detect this in AP_GPS # (9, "FILE"), ] + self.context_collect("STATUSTEXT") for (sim_gps_type, name, gps_type, detect_name) in sim_gps: self.start_subtest("Checking GPS type %s" % name) self.set_parameter("SIM_GPS_TYPE", sim_gps_type) if gps_type is None: gps_type = 1 # auto-detect self.set_parameter("GPS_TYPE", gps_type) - self.context_collect("STATUSTEXT") + self.context_clear_collection('STATUSTEXT') self.reboot_sitl() self.wait_statustext("detected as %s" % detect_name, check_context=True) n = self.poll_home_position(timeout=120) @@ -11441,11 +12331,15 @@ def fetch_file_via_ftp(self, path): try: mavproxy.send("module load ftp\n") mavproxy.expect(["Loaded module ftp", "module ftp already loaded"]) + mavproxy.send("ftp set debug 1\n") # so we get the "Terminated session" message mavproxy.send("ftp get %s %s\n" % (path, tmpfile.name)) mavproxy.expect("Getting") self.delay_sim_time(2) mavproxy.send("ftp status\n") mavproxy.expect("No transfer in progress") + # terminate the connection, or it may still be in progress the next time an FTP is attempted: + mavproxy.send("ftp cancel\n") + mavproxy.expect("Terminated session") except Exception as e: self.print_exception_caught(e) ex = e @@ -11485,43 +12379,16 @@ def MAVFTP(self): def tests(self): return [ - Test("PIDTuning", - "Test PID Tuning", - self.test_pid_tuning), - - Test("ArmFeatures", "Arm features", self.test_arm_feature), - - Test("SetHome", - "Test Set Home", - self.fly_test_set_home), - - Test("ConfigErrorLoop", - "Test Config Error Loop", - self.test_config_error_loop), - - Test("CPUFailsafe", - "Ensure we do something appropriate when the main loop stops", - self.CPUFailsafe), - - Test("Parameters", - "Test Parameter Set/Get", - self.test_parameters), - - Test("LoggerDocumentation", - "Test Onboard Logging Generation", - self.test_onboard_logging_generation), - - Test("Logging", - "Test Onboard Logging", - self.test_onboard_logging), - - Test("GetCapabilities", - "Get Capabilities", - self.test_get_autopilot_capabilities), - - Test("InitialMode", - "Test initial mode switching", - self.test_initial_mode), + self.PIDTuning, + self.ArmFeatures, + self.SetHome, + self.ConfigErrorLoop, + self.CPUFailsafe, + self.Parameters, + self.LoggerDocumentation, + self.Logging, + self.GetCapabilities, + self.InitialMode, ] def post_tests_announcements(self): @@ -11539,28 +12406,45 @@ def post_tests_announcements(self): print("Had to force-reset SITL %u times" % (self.forced_post_test_sitl_reboots,)) - def autotest(self): + def autotest(self, tests=None, allow_skips=True): """Autotest used by ArduPilot autotest CI.""" + if tests is None: + tests = self.tests() all_tests = [] - for test in self.tests(): - if type(test) == Test: - all_tests.append(test) - continue - (name, desc, func) = test - actual_test = Test(name, desc, func) - all_tests.append(actual_test) + for test in tests: + if type(test) != Test: + test = Test(test) + all_tests.append(test) disabled = self.disabled_tests() + if not allow_skips: + disabled = {} + skip_list = [] tests = [] for test in all_tests: if test.name in disabled: - self.test_skipped(test, disabled[test.name]) + self.progress("##### %s is skipped: %s" % (test, disabled[test.name])) + skip_list.append((test, disabled[test.name])) continue tests.append(test) - ret = self.run_tests(tests) + results = self.run_tests(tests) + + if len(skip_list): + self.progress("Skipped tests:") + for skipped in skip_list: + (test, reason) = skipped + print(" %s (see %s)" % (test.name, reason)) + + self.fail_list = list(filter(lambda x : not x.passed, results)) + if len(self.fail_list): + self.progress("Failing tests:") + for failure in self.fail_list: + print(str(failure)) + self.post_tests_announcements() - return ret + + return len(self.fail_list) == 0 def mavfft_fttd(self, sensor_type, sensor_instance, since, until): '''display fft for raw ACC data in current logfile''' @@ -11677,3 +12561,75 @@ def load_default_params_file(self, filename): '''load a file from Tools/autotest/default_params''' filepath = util.reltopdir(os.path.join("Tools", "autotest", "default_params", filename)) self.repeatedly_apply_parameter_file(filepath) + + def send_pause_command(self): + '''pause AUTO/GUIDED modes''' + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_PAUSE_CONTINUE, + 0, # 0: pause, 1: continue + 0, # param2 + 0, # param3 + 0, # param4 + 0, # param5 + 0, # param6 + 0) # param7 + + def send_resume_command(self): + '''resume AUTO/GUIDED modes''' + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_PAUSE_CONTINUE, + 1, # 0: pause, 1: continue + 0, # param2 + 0, # param3 + 0, # param4 + 0, # param5 + 0, # param6 + 0) # param7 + + def enum_state_name(self, enum_name, state, pretrim=None): + e = mavutil.mavlink.enums[enum_name] + e_value = e[state] + name = e_value.name + if pretrim is not None: + if not pretrim.startswith(pretrim): + raise NotAchievedException("Expected %s to pretrim" % (pretrim)) + name = name.replace(pretrim, "") + return name + + def vtol_state_name(self, state): + return self.enum_state_name("MAV_VTOL_STATE", state, pretrim="MAV_VTOL_STATE_") + + def landed_state_name(self, state): + return self.enum_state_name("MAV_LANDED_STATE", state, pretrim="MAV_LANDED_STATE_") + + def assert_extended_sys_state(self, vtol_state, landed_state): + m = self.assert_receive_message('EXTENDED_SYS_STATE', timeout=1) + if m.vtol_state != vtol_state: + raise ValueError("Bad MAV_VTOL_STATE. Want=%s got=%s" % + (self.vtol_state_name(vtol_state), + self.vtol_state_name(m.vtol_state))) + if m.landed_state != landed_state: + raise ValueError("Bad MAV_LANDED_STATE. Want=%s got=%s" % + (self.landed_state_name(landed_state), + self.landed_state_name(m.landed_state))) + + def wait_extended_sys_state(self, vtol_state, landed_state, timeout=10): + tstart = self.get_sim_time() + while True: + if self.get_sim_time() - tstart > timeout: + raise NotAchievedException("Did not achieve vol/landed states") + self.progress("Waiting for MAV_VTOL_STATE=%s MAV_LANDED_STATE=%s" % + (self.vtol_state_name(vtol_state), + self.landed_state_name(landed_state))) + m = self.assert_receive_message('EXTENDED_SYS_STATE', verbose=True) + if m.landed_state != landed_state: + self.progress("Wrong MAV_LANDED_STATE (want=%s got=%s)" % + (self.landed_state_name(landed_state), + self.landed_state_name(m.landed_state))) + continue + if m.vtol_state != vtol_state: + self.progress("Wrong MAV_VTOL_STATE (want=%s got=%s)" % + (self.vtol_state_name(vtol_state), + self.vtol_state_name(m.vtol_state))) + continue + + self.progress("vtol and landed states match") + return diff --git a/Tools/autotest/default_params/balancebot.parm b/Tools/autotest/default_params/balancebot.parm index c097bed73a5..f5b00eeda17 100644 --- a/Tools/autotest/default_params/balancebot.parm +++ b/Tools/autotest/default_params/balancebot.parm @@ -1,7 +1,6 @@ -ATC_BAL_P 18.0 -ATC_BAL_I 80.0 -ATC_BAL_D 0.005 -ATC_BAL_SPD_FF 0.000000 +ATC_BAL_P 3.5 +ATC_BAL_I 5.0 +ATC_BAL_D 0.06 ATC_SPEED_P 0.9 ATC_SPEED_I 0.5 AHRS_EKF_TYPE 10 diff --git a/Tools/autotest/default_params/blimp.parm b/Tools/autotest/default_params/blimp.parm index 9db84765738..192455b115c 100644 --- a/Tools/autotest/default_params/blimp.parm +++ b/Tools/autotest/default_params/blimp.parm @@ -1,3 +1,5 @@ +ARSPD_PIN 1 +ARSPD_BUS 2 EK2_ENABLE 1 FRAME_TYPE 0 FS_THR_ENABLE 1 diff --git a/Tools/autotest/default_params/copter-gimbal.parm b/Tools/autotest/default_params/copter-gimbal.parm new file mode 100644 index 00000000000..c6e2c50f136 --- /dev/null +++ b/Tools/autotest/default_params/copter-gimbal.parm @@ -0,0 +1,6 @@ +# copter with simulated 3-axis servo gimbal +MNT_TYPE 1 +RC6_OPTION 213 +SERVO5_FUNCTION 8 +SERVO6_FUNCTION 7 +SERVO7_FUNCTION 6 diff --git a/Tools/autotest/default_params/copter-wind-estimates.parm b/Tools/autotest/default_params/copter-wind-estimates.parm new file mode 100644 index 00000000000..0a79081f965 --- /dev/null +++ b/Tools/autotest/default_params/copter-wind-estimates.parm @@ -0,0 +1,5 @@ +# copter with wind speed estimates enabled +EK3_DRAG_BCOEF_X 9.5 +EK3_DRAG_BCOEF_Y 9.5 +EK3_DRAG_MCOEF 0.082 +SIM_WIND_SPD 3 diff --git a/Tools/autotest/default_params/copter.parm b/Tools/autotest/default_params/copter.parm index 07a8a376668..7f41498a4ec 100644 --- a/Tools/autotest/default_params/copter.parm +++ b/Tools/autotest/default_params/copter.parm @@ -1,5 +1,7 @@ FRAME_TYPE 0 FS_THR_ENABLE 1 +ARSPD_PIN 1 +ARSPD_BUS 2 ATC_RAT_YAW_P 0.09 ATC_RAT_YAW_I 0.009 BATT_MONITOR 4 diff --git a/Tools/autotest/default_params/quadplane.parm b/Tools/autotest/default_params/quadplane.parm index 08bc254b4fa..92a58bb015f 100644 --- a/Tools/autotest/default_params/quadplane.parm +++ b/Tools/autotest/default_params/quadplane.parm @@ -1,4 +1,3 @@ -AHRS_EKF_TYPE 2 ARMING_RUDDER 2 ARSPD_FBW_MAX 35 ARSPD_FBW_MIN 13 @@ -13,8 +12,6 @@ COMPASS_OFS3_Z 6.665476 COMPASS_OFS_X -0.453570 COMPASS_OFS_Y -0.585846 COMPASS_OFS_Z 6.815743 -EK2_ENABLE 1 -EK2_IMU_MASK 3 EK3_ENABLE 1 FBWB_CLIMB_RATE 10 FLTMODE1 10 diff --git a/Tools/autotest/default_params/rover.parm b/Tools/autotest/default_params/rover.parm index d26a8146f54..9095f40720d 100644 --- a/Tools/autotest/default_params/rover.parm +++ b/Tools/autotest/default_params/rover.parm @@ -1,3 +1,5 @@ +ARSPD_PIN 1 +ARSPD_BUS 2 ATC_SPEED_P 0.1 ATC_STR_RAT_FF 0.75 BATT_MONITOR 4 diff --git a/Tools/autotest/default_params/sailboat.parm b/Tools/autotest/default_params/sailboat.parm index be01673f04d..54fb607a1a2 100644 --- a/Tools/autotest/default_params/sailboat.parm +++ b/Tools/autotest/default_params/sailboat.parm @@ -1,4 +1,6 @@ ARSPD_OFFSET 2013 +ARSPD_PIN 1 +ARSPD_BUS 2 FRAME_CLASS 2 LOIT_TYPE 1 MOT_SLEWRATE 0 diff --git a/Tools/autotest/default_params/sub.parm b/Tools/autotest/default_params/sub.parm index ddb5c84c8df..3a173142cb7 100644 --- a/Tools/autotest/default_params/sub.parm +++ b/Tools/autotest/default_params/sub.parm @@ -1,3 +1,5 @@ +ARSPD_PIN 1 +ARSPD_BUS 2 BATT_MONITOR 4 BTN0_FUNCTION 0 BTN10_SFUNCTION 0 @@ -58,13 +60,12 @@ INS_ACC3OFFS_Z 0.000 INS_ACC3SCAL_X 1.000 INS_ACC3SCAL_Y 1.000 INS_ACC3SCAL_Z 1.000 -MNT_ANGMAX_TIL 4500 -MNT_ANGMIN_TIL -4500 -MNT_DEFLT_MODE 3 -MNT_JSTICK_SPD 100 -MNT_RC_IN_TILT 8 -MNT_STAB_TILT 0 -MNT_TYPE 1 +RC8_OPTION 213 +MNT1_PITCH_MAX 45 +MNT1_PITCH_MIN -45 +MNT1_DEFLT_MODE 3 +MNT1_RC_RATE 30 +MNT1_TYPE 7 PSC_ACCZ_P 2 PSC_ACCZ_I 4 PSC_ACCZ_FF 0.75 @@ -82,3 +83,6 @@ SERVO8_FUNCTION 7 SERVO8_MAX 1900 SERVO8_MIN 1100 BARO_EXT_BUS 1 +PILOT_ACCEL_Z 200 +PILOT_SPEED_UP 200 +PSC_JERK_Z 8 diff --git a/Tools/autotest/default_params/vee-gull 005.param b/Tools/autotest/default_params/vee-gull 005.param index 3fe8a3a2d92..113278a3eed 100644 --- a/Tools/autotest/default_params/vee-gull 005.param +++ b/Tools/autotest/default_params/vee-gull 005.param @@ -350,29 +350,6 @@ MIS_RESTART,0 MIS_TOTAL,7 MIXING_GAIN,0.5 MIXING_OFFSET,0 -MNT_ANGMAX_PAN,4500 -MNT_ANGMAX_ROL,4500 -MNT_ANGMAX_TIL,4500 -MNT_ANGMIN_PAN,-4500 -MNT_ANGMIN_ROL,-4500 -MNT_ANGMIN_TIL,-4500 -MNT_DEFLT_MODE,3 -MNT_JSTICK_SPD,0 -MNT_LEAD_PTCH,0 -MNT_LEAD_RLL,0 -MNT_NEUTRAL_X,0 -MNT_NEUTRAL_Y,0 -MNT_NEUTRAL_Z,0 -MNT_RC_IN_PAN,0 -MNT_RC_IN_ROLL,0 -MNT_RC_IN_TILT,0 -MNT_RETRACT_X,0 -MNT_RETRACT_Y,0 -MNT_RETRACT_Z,0 -MNT_STAB_PAN,0 -MNT_STAB_ROLL,0 -MNT_STAB_TILT,0 -MNT_TYPE,0 NAV_CONTROLLER,1 NAVL1_DAMPING,0.75 NAVL1_PERIOD,20 @@ -696,7 +673,6 @@ SIM_SONAR_RND,0 SIM_SONAR_SCALE,12.1212 SIM_SPEEDUP,-1 SIM_TERRAIN,1 -SIM_WIND_DELAY,0 SIM_WIND_DIR,180 SIM_WIND_SPD,0 SIM_WIND_TURB,0 diff --git a/Tools/autotest/examples.py b/Tools/autotest/examples.py index 934b336fc7f..590205b331c 100644 --- a/Tools/autotest/examples.py +++ b/Tools/autotest/examples.py @@ -1,5 +1,3 @@ -#!/usr/bin/env python - """ Contains functions used to test the ArduPilot examples diff --git a/Tools/autotest/fg_plane_view.bat b/Tools/autotest/fg_plane_view.bat old mode 100755 new mode 100644 diff --git a/Tools/autotest/fg_quad_view.bat b/Tools/autotest/fg_quad_view.bat old mode 100755 new mode 100644 diff --git a/Tools/autotest/helicopter.py b/Tools/autotest/helicopter.py index 6f5a9a0d4d5..c86286d1faf 100644 --- a/Tools/autotest/helicopter.py +++ b/Tools/autotest/helicopter.py @@ -1,5 +1,3 @@ -#!/usr/bin/env python - ''' Fly Helicopter in SITL @@ -59,7 +57,8 @@ def get_collective_out(self): chan_pwm = (servo.servo1_raw + servo.servo2_raw + servo.servo3_raw)/3.0 return chan_pwm - def rotor_runup_complete_checks(self): + def RotorRunup(self): + '''Test rotor runip''' # Takeoff and landing in Loiter TARGET_RUNUP_TIME = 10 self.zero_throttle() @@ -93,8 +92,8 @@ def rotor_runup_complete_checks(self): self.mav.wait_heartbeat() # fly_avc_test - fly AVC mission - def fly_avc_test(self): - # Arm + def AVCMission(self): + '''fly AVC mission''' self.change_mode('STABILIZE') self.wait_ready_to_arm() @@ -161,7 +160,8 @@ def takeoff(self, self.hover() self.progress("TAKEOFF COMPLETE") - def fly_each_frame(self): + def FlyEachFrame(self): + '''Fly each supported internal frame''' vinfo = vehicleinfo.VehicleInfo() vinfo_options = vinfo.options[self.vehicleinfo_key()] known_broken_frames = { @@ -198,7 +198,7 @@ def hover(self): self.progress("Setting hover collective") self.set_rc(3, 1500) - def fly_heli_poshold_takeoff(self): + def PosHoldTakeOff(self): """ensure vehicle stays put until it is ready to fly""" self.context_push() @@ -260,8 +260,8 @@ def fly_heli_poshold_takeoff(self): if ex is not None: raise ex - def fly_heli_stabilize_takeoff(self): - """""" + def StabilizeTakeOff(self): + """Fly stabilize takeoff""" self.context_push() ex = None @@ -298,7 +298,7 @@ def fly_heli_stabilize_takeoff(self): if ex is not None: raise ex - def fly_spline_waypoint(self, timeout=600): + def SplineWaypoint(self, timeout=600): """ensure basic spline functionality works""" self.load_mission("copter_spline_mission.txt", strict=False) self.change_mode("LOITER") @@ -319,8 +319,8 @@ def fly_spline_waypoint(self, timeout=600): self.progress("Lowering rotor speed") self.set_rc(8, 1000) - def fly_autorotation(self, timeout=600): - """ensure basic spline functionality works""" + def AutoRotation(self, timeout=600): + """Check engine-out behaviour""" self.set_parameter("AROT_ENABLE", 1) start_alt = 100 # metres self.set_parameter("PILOT_TKOFF_ALT", start_alt * 100) @@ -370,7 +370,8 @@ def fly_mission(self, filename, strict=True): self.set_rc(8, 1000) # Lower rotor speed # FIXME move this & plane's version to common - def test_airspeed_drivers(self, timeout=600): + def AirspeedDrivers(self, timeout=600): + '''Test AirSpeed drivers''' # set the start location to CMAC to use same test script as other vehicles self.sitl_start_loc = mavutil.location(-35.362881, 149.165222, 582.000000, 90.0) # CMAC @@ -430,39 +431,14 @@ def tests(self): '''return list of all tests''' ret = AutoTest.tests(self) ret.extend([ - ("AVCMission", "Fly AVC mission", self.fly_avc_test), - - ("RotorRunUp", - "Test rotor runup", - self.rotor_runup_complete_checks), - - ("PosHoldTakeOff", - "Fly POSHOLD takeoff", - self.fly_heli_poshold_takeoff), - - ("StabilizeTakeOff", - "Fly stabilize takeoff", - self.fly_heli_stabilize_takeoff), - - ("SplineWaypoint", - "Fly Spline Waypoints", - self.fly_spline_waypoint), - - ("AutoRotation", - "Fly AutoRotation", - self.fly_autorotation), - - ("FlyEachFrame", - "Fly each supported internal frame", - self.fly_each_frame), - - ("LogUpload", - "Log upload", - self.log_upload), - - ("AirspeedDrivers", - "Test AirSpeed drivers", - self.test_airspeed_drivers), + self.AVCMission, + self.RotorRunup, + self.PosHoldTakeOff, + self.StabilizeTakeOff, + self.SplineWaypoint, + self.AutoRotation, + self.FlyEachFrame, + self.AirspeedDrivers, ]) return ret diff --git a/Tools/autotest/locations.txt b/Tools/autotest/locations.txt index 1722ce3ed82..541a0996344 100644 --- a/Tools/autotest/locations.txt +++ b/Tools/autotest/locations.txt @@ -20,7 +20,7 @@ BMAC=-35.226343,149.132122,588,301 LGAT=37.889063,23.731863,21,330 BHV=53.547767,8.626440,0,324 QMAC=-35.363724,149.430011,740,312 -Karuizawa=36.324306,138.639282,938,0 +Karuizawa=36.323203,138.618215,926,0 Dalby=-27.274439,151.290064,343,8.7 RFRanch=37.118079,-2.773690,1297.88,180 KSFO=37.619373,-122.376637,5.3,118 @@ -92,3 +92,5 @@ RF_AirStadium=36.893328,-2.720371,1434,0 RF_BuenaVista=37.093686,-2.890969,2390,0 RF_Castle=37.090662,-3.074557,2736,0 RF_Garage=37.621798,-2.646596,788,0 +SFO_Bay=37.62561973,-122.33235387,0.0,0 + diff --git a/Tools/autotest/logger_metadata/emit_html.py b/Tools/autotest/logger_metadata/emit_html.py index 15ce6439c8a..197b9fa9c3d 100644 --- a/Tools/autotest/logger_metadata/emit_html.py +++ b/Tools/autotest/logger_metadata/emit_html.py @@ -1,5 +1,3 @@ -#!/usr/bin/env python - from __future__ import print_function import emitter diff --git a/Tools/autotest/logger_metadata/emit_rst.py b/Tools/autotest/logger_metadata/emit_rst.py index c29731524e0..433f2794cee 100644 --- a/Tools/autotest/logger_metadata/emit_rst.py +++ b/Tools/autotest/logger_metadata/emit_rst.py @@ -1,5 +1,3 @@ -#!/usr/bin/env python - from __future__ import print_function import emitter diff --git a/Tools/autotest/logger_metadata/emit_xml.py b/Tools/autotest/logger_metadata/emit_xml.py index 957ce280bad..05dd6a2ad80 100644 --- a/Tools/autotest/logger_metadata/emit_xml.py +++ b/Tools/autotest/logger_metadata/emit_xml.py @@ -1,5 +1,3 @@ -#!/usr/bin/env python - from __future__ import print_function from lxml import etree diff --git a/Tools/autotest/models/Callisto.json b/Tools/autotest/models/Callisto.json index 2a4d68476ec..100a994fcea 100644 --- a/Tools/autotest/models/Callisto.json +++ b/Tools/autotest/models/Callisto.json @@ -10,8 +10,8 @@ # the ref parameters should be taken from a test # with the copter flying at constant speed in zero wind. This is used # to estimate the drag coefficient - "refSpd" : 14.88, # m/s - "refAngle" : 8.91, # degrees + "refSpd" : 25.0, # m/s + "refAngle" : 30.0, # degrees "refVoltage" : 46.9, # volts "refCurrent" : 65.36, # Amps "refAlt" : 26, # meters AMSL @@ -54,5 +54,8 @@ # momentum drag coefficient # ratio of momentum drag relative to a ducted rotor of the same effective disc area - "mdrag_coef" : 0.10 + "mdrag_coef" : 0.10, + + # number of motors + "num_motors" : 8 } diff --git a/Tools/autotest/models/Callisto.param b/Tools/autotest/models/Callisto.param index 1454aff0912..4da6a413fb7 100644 --- a/Tools/autotest/models/Callisto.param +++ b/Tools/autotest/models/Callisto.param @@ -1,32 +1,36 @@ -ACRO_YAW_P,2 -ANGLE_MAX,3000 + + +ACRO_Y_RATE,90 ATC_ACCEL_P_MAX,30000 ATC_ACCEL_R_MAX,30000 ATC_ACCEL_Y_MAX,6000 -ATC_ANG_PIT_P,6 -ATC_ANG_RLL_P,6 +ATC_ANG_PIT_P,8 +ATC_ANG_RLL_P,8 ATC_ANG_YAW_P,5 ATC_INPUT_TC,0.25 -ATC_RAT_PIT_D,0.0080 +ATC_RAT_PIT_D,0.00375 ATC_RAT_PIT_FLTD,10 -ATC_RAT_PIT_I,0.1634 -ATC_RAT_PIT_IMAX,0.5 -ATC_RAT_PIT_P,0.1634 -ATC_RAT_RLL_D,0.0085 +ATC_RAT_PIT_I,0.455 +ATC_RAT_PIT_P,0.455 +ATC_RAT_RLL_D,0.00375 ATC_RAT_RLL_FLTD,10 -ATC_RAT_RLL_I,0.1671 -ATC_RAT_RLL_IMAX,0.5 -ATC_RAT_RLL_P,0.1671 +ATC_RAT_RLL_I,0.455 +ATC_RAT_RLL_P,0.455 +ATC_RAT_YAW_FLTE,10 ATC_RAT_YAW_I,0.05 ATC_RAT_YAW_P,0.5 ATC_SLEW_YAW,3000 ATC_THR_MIX_MAX,2 -AUTOTUNE_AGGR,0.1 -AUTOTUNE_MIN_D,0.001 +EK3_DRAG_BCOEF_X,91.2220 +EK3_DRAG_BCOEF_Y,91.2220 +EK3_DRAG_MCOEF,0.0760 +FOLL_ALT_TYPE,1 +FOLL_DIST_MAX,10000 +FOLL_ENABLE,1 +FOLL_OFS_TYPE,1 FRAME_CLASS,4 FRAME_TYPE,1 INS_ACCEL_FILTER,10 -LOIT_ACC_MAX,457.2916 LOIT_ANG_MAX,25 MOT_BAT_CURR_TC,2 MOT_BAT_VOLT_MAX,50.4 @@ -40,15 +44,17 @@ MOT_SPIN_MIN,0.2 MOT_THST_EXPO,0.5 MOT_THST_HOVER,0.52 MOT_YAW_HEADROOM,50 +PILOT_THR_BHV,3 +PILOT_Y_RATE,60 PSC_ACCZ_FLTD,10 PSC_ACCZ_FLTE,0 PSC_ACCZ_FLTT,10 -PSC_ACCZ_I,0.5 -PSC_ACCZ_P,0.25 +PSC_ACCZ_I,1.0 PSC_ANGLE_MAX,45 -PSC_POSXY_P,1 +PSC_JERK_Z,10 PSC_POSZ_P,0.5 PSC_VELZ_P,2.5 -WPNAV_ACCEL,250 +WP_YAW_BEHAVIOR,1 +WPNAV_RFND_USE,0 WPNAV_SPEED,1500 SIM_BATT_VOLTAGE 50 diff --git a/Tools/autotest/param_metadata/ednemit.py b/Tools/autotest/param_metadata/ednemit.py index 7523a038bd2..d024e13a5db 100644 --- a/Tools/autotest/param_metadata/ednemit.py +++ b/Tools/autotest/param_metadata/ednemit.py @@ -1,4 +1,3 @@ -#!/usr/bin/env python """ Emits parameters as an EDN file, does some small remapping of names """ diff --git a/Tools/autotest/param_metadata/emit.py b/Tools/autotest/param_metadata/emit.py index e88eaed0fcf..d2bee5092fd 100644 --- a/Tools/autotest/param_metadata/emit.py +++ b/Tools/autotest/param_metadata/emit.py @@ -1,4 +1,3 @@ -#!/usr/bin/env python """ The standard interface emitters must implement """ diff --git a/Tools/autotest/param_metadata/htmlemit.py b/Tools/autotest/param_metadata/htmlemit.py index 52b237d95f9..1d9e7653416 100644 --- a/Tools/autotest/param_metadata/htmlemit.py +++ b/Tools/autotest/param_metadata/htmlemit.py @@ -1,4 +1,3 @@ -#!/usr/bin/env python """ Emit docs in a form acceptable to the old Ardupilot wordpress docs site """ diff --git a/Tools/autotest/param_metadata/jsonemit.py b/Tools/autotest/param_metadata/jsonemit.py index 36212197e25..9d50c908db6 100644 --- a/Tools/autotest/param_metadata/jsonemit.py +++ b/Tools/autotest/param_metadata/jsonemit.py @@ -1,5 +1,3 @@ -#!/usr/bin/env python - import json import copy from emit import Emit diff --git a/Tools/autotest/param_metadata/mdemit.py b/Tools/autotest/param_metadata/mdemit.py index 09c9f49e191..d97ed1f3e69 100644 --- a/Tools/autotest/param_metadata/mdemit.py +++ b/Tools/autotest/param_metadata/mdemit.py @@ -1,4 +1,3 @@ -#!/usr/bin/env python """ Emit parameter documentation in markdown format """ diff --git a/Tools/autotest/param_metadata/param.py b/Tools/autotest/param_metadata/param.py index 41db301d2c2..1bb4a294bda 100644 --- a/Tools/autotest/param_metadata/param.py +++ b/Tools/autotest/param_metadata/param.py @@ -113,6 +113,7 @@ def set_name(self, name): 'octal' : 'octal' , 'RPM' : 'Revolutions Per Minute', 'kg/m/m' : 'kilograms per square meter', # metre is the SI unit name, meter is the american spelling of it + 'kg/m/m/m': 'kilograms per cubic meter', } required_param_fields = [ @@ -121,6 +122,11 @@ def set_name(self, name): 'User', ] +required_library_param_fields = [ + 'Description', + 'DisplayName', + ] + known_group_fields = [ 'Path', ] diff --git a/Tools/autotest/param_metadata/param_parse.py b/Tools/autotest/param_metadata/param_parse.py index 063f6ba12d0..36f3b0f781a 100755 --- a/Tools/autotest/param_metadata/param_parse.py +++ b/Tools/autotest/param_metadata/param_parse.py @@ -14,7 +14,7 @@ from argparse import ArgumentParser from param import (Library, Parameter, Vehicle, known_group_fields, - known_param_fields, required_param_fields, known_units) + known_param_fields, required_param_fields, required_library_param_fields, known_units) from htmlemit import HtmlEmit from rstemit import RSTEmit from rstlatexpdfemit import RSTLATEXPDFEmit @@ -250,7 +250,9 @@ def process_library(vehicle, library, pathprefix=None): global current_param current_param = p.name fields = prog_param_fields.findall(field_text) + field_list = [] for field in fields: + field_list.append(field[0]) if field[0] in known_param_fields: value = re.sub('@PREFIX@', library.name, field[1]) setattr(p, field[0], value) @@ -258,6 +260,10 @@ def process_library(vehicle, library, pathprefix=None): setattr(p, field[0], field[1]) else: error("param: unknown parameter metadata field %s" % field[0]) + for req_field in required_library_param_fields: + if req_field not in field_list: + error("missing parameter metadata field '%s' in %s" % (req_field, current_param)) + debug("matching %s" % field_text) fields = prog_param_tagged_fields.findall(field_text) # a parameter is considered to be vehicle-specific if diff --git a/Tools/autotest/param_metadata/rstemit.py b/Tools/autotest/param_metadata/rstemit.py old mode 100644 new mode 100755 index 7eecc7acd9c..752b769dee1 --- a/Tools/autotest/param_metadata/rstemit.py +++ b/Tools/autotest/param_metadata/rstemit.py @@ -263,7 +263,7 @@ def emit(self, g): ret += self.render_table_headings(ret, row, headings, field_table_info, field, param) elif field == "Range": (param_min, param_max) = (param.__dict__[field]).split(' ') - row.append("%s - %s" % (param_min, param_max,)) + row.append("%s to %s" % (param_min, param_max,)) elif field == 'Units': abbreviated_units = param.__dict__[field] if abbreviated_units != '': diff --git a/Tools/autotest/param_metadata/rstlatexpdfemit.py b/Tools/autotest/param_metadata/rstlatexpdfemit.py index 48cfdcecb23..535b4489b43 100644 --- a/Tools/autotest/param_metadata/rstlatexpdfemit.py +++ b/Tools/autotest/param_metadata/rstlatexpdfemit.py @@ -1,5 +1,3 @@ -#!/usr/bin/env python - from rstemit import RSTEmit diff --git a/Tools/autotest/param_metadata/xmlemit.py b/Tools/autotest/param_metadata/xmlemit.py index 4fefd991013..c9262590af0 100644 --- a/Tools/autotest/param_metadata/xmlemit.py +++ b/Tools/autotest/param_metadata/xmlemit.py @@ -1,5 +1,3 @@ -#!/usr/bin/env python - from lxml import etree from emit import Emit diff --git a/Tools/autotest/param_metadata/xmlemit_mp.py b/Tools/autotest/param_metadata/xmlemit_mp.py index aca0b5ce3f8..846993ee59e 100644 --- a/Tools/autotest/param_metadata/xmlemit_mp.py +++ b/Tools/autotest/param_metadata/xmlemit_mp.py @@ -1,5 +1,3 @@ -#!/usr/bin/env python - from xml.sax.saxutils import escape, quoteattr from emit import Emit diff --git a/Tools/autotest/pysim/iris_ros.py b/Tools/autotest/pysim/iris_ros.py deleted file mode 100644 index a8652b83412..00000000000 --- a/Tools/autotest/pysim/iris_ros.py +++ /dev/null @@ -1,114 +0,0 @@ -#!/usr/bin/env python -""" -Python interface to euroc ROS multirotor simulator -See https://pixhawk.org/dev/ros/sitl -""" - -import time - -import mav_msgs.msg as mav_msgs -import px4.msg as px4 -import rosgraph_msgs.msg as rosgraph_msgs -import rospy -import sensor_msgs.msg as sensor_msgs - -from aircraft import Aircraft -from pymavlink.rotmat import Vector3, Matrix3 - - -def quat_to_dcm(q1, q2, q3, q4): - """Convert quaternion to DCM.""" - q3q3 = q3 * q3 - q3q4 = q3 * q4 - q2q2 = q2 * q2 - q2q3 = q2 * q3 - q2q4 = q2 * q4 - q1q2 = q1 * q2 - q1q3 = q1 * q3 - q1q4 = q1 * q4 - q4q4 = q4 * q4 - - m = Matrix3() - m.a.x = 1.0-2.0*(q3q3 + q4q4) - m.a.y = 2.0*(q2q3 - q1q4) - m.a.z = 2.0*(q2q4 + q1q3) - m.b.x = 2.0*(q2q3 + q1q4) - m.b.y = 1.0-2.0*(q2q2 + q4q4) - m.b.z = 2.0*(q3q4 - q1q2) - m.c.x = 2.0*(q2q4 - q1q3) - m.c.y = 2.0*(q3q4 + q1q2) - m.c.z = 1.0-2.0*(q2q2 + q3q3) - return m - - -class IrisRos(Aircraft): - """A IRIS MultiCopter from ROS.""" - def __init__(self): - Aircraft.__init__(self) - self.max_rpm = 1200 - self.have_new_time = False - self.have_new_imu = False - self.have_new_pos = False - - topics = { - "/clock" : (self.clock_cb, rosgraph_msgs.Clock), - "/iris/imu" : (self.imu_cb, sensor_msgs.Imu), - "/iris/vehicle_local_position" : (self.pos_cb, px4.vehicle_local_position), - } - - rospy.init_node('ArduPilot', anonymous=True) - for topic in topics.keys(): - (callback, msgtype) = topics[topic] - rospy.Subscriber(topic, msgtype, callback) - - self.motor_pub = rospy.Publisher('/iris/command/motor_speed', - mav_msgs.CommandMotorSpeed, - queue_size=1) - self.last_time = 0 - - # spin() simply keeps python from exiting until this node is stopped - # rospy.spin() - - def clock_cb(self, msg): - self.time_now = self.time_base + msg.clock.secs + msg.clock.nsecs*1.0e-9 - self.have_new_time = True - - def imu_cb(self, msg): - self.gyro = Vector3(msg.angular_velocity.x, - -msg.angular_velocity.y, - -msg.angular_velocity.z) - self.accel_body = Vector3(msg.linear_acceleration.x, - -msg.linear_acceleration.y, - -msg.linear_acceleration.z) - self.dcm = quat_to_dcm(msg.orientation.w, - msg.orientation.x, - -msg.orientation.y, - -msg.orientation.z) - self.have_new_imu = True - - def pos_cb(self, msg): - self.velocity = Vector3(msg.vx, msg.vy, msg.vz) - self.position = Vector3(msg.x, msg.y, msg.z) - self.have_new_pos = True - - def update(self, actuators): - while self.last_time == self.time_now or not self.have_new_time or not self.have_new_imu or not self.have_new_pos: - time.sleep(0.001) - self.have_new_time = False - self.have_new_pos = False - self.have_new_imu = False - - # create motor speed message - msg = mav_msgs.CommandMotorSpeed() - msg.header.stamp = rospy.get_rostime() - motor_speed = [] - for i in range(len(actuators)): - motor_speed.append(actuators[i]*self.max_rpm) - msg.motor_speed = motor_speed - - self.last_time = self.time_now - - self.motor_pub.publish(msg) - - # update lat/lon/altitude - self.update_position() diff --git a/Tools/autotest/pysim/util.py b/Tools/autotest/pysim/util.py index a906a9096b8..7655ddae26c 100644 --- a/Tools/autotest/pysim/util.py +++ b/Tools/autotest/pysim/util.py @@ -1,5 +1,9 @@ from __future__ import print_function +''' +AP_FLAKE8_CLEAN +''' + import atexit import math import os @@ -17,17 +21,17 @@ from pymavlink.rotmat import Vector3, Matrix3 -if (sys.version_info[0] >= 3): +if sys.version_info[0] >= 3: ENCODING = 'ascii' else: ENCODING = None RADIUS_OF_EARTH = 6378100.0 # in meters - # List of open terminal windows for macosx windowID = [] + def m2ft(x): """Meters to feet.""" return float(x) / 0.3048 @@ -49,20 +53,22 @@ def mps2kt(x): def topdir(): """Return top of git tree where autotest is running from.""" d = os.path.dirname(os.path.realpath(__file__)) - assert(os.path.basename(d) == 'pysim') + assert os.path.basename(d) == 'pysim' d = os.path.dirname(d) - assert(os.path.basename(d) == 'autotest') + assert os.path.basename(d) == 'autotest' d = os.path.dirname(d) - assert(os.path.basename(d) == 'Tools') + assert os.path.basename(d) == 'Tools' d = os.path.dirname(d) return d + def relcurdir(path): """Return a path relative to current dir""" return os.path.relpath(path, os.getcwd()) + def reltopdir(path): - """Return a path relative to topdir().""" + """Returns the normalized ABSOLUTE path for 'path', where path is a path relative to topdir""" return os.path.normpath(os.path.join(topdir(), path)) @@ -86,7 +92,7 @@ def rmfile(path): """Remove a file if it exists.""" try: os.unlink(path) - except Exception: + except (OSError, FileNotFoundError): pass @@ -99,7 +105,19 @@ def relwaf(): return "./modules/waf/waf-light" -def waf_configure(board, j=None, debug=False, math_check_indexes=False, coverage=False, ekf_single=False, postype_single=False, sitl_32bit=False, extra_args=[], extra_hwdef=None): +def waf_configure(board, + j=None, + debug=False, + math_check_indexes=False, + coverage=False, + ekf_single=False, + postype_single=False, + sitl_32bit=False, + extra_args=[], + extra_hwdef=None, + ubsan=False, + ubsan_abort=False, + extra_defines={}): cmd_configure = [relwaf(), "configure", "--board", board] if debug: cmd_configure.append('--debug') @@ -113,8 +131,14 @@ def waf_configure(board, j=None, debug=False, math_check_indexes=False, coverage cmd_configure.append('--postype-single') if sitl_32bit: cmd_configure.append('--sitl-32bit') + if ubsan: + cmd_configure.append('--ubsan') + if ubsan_abort: + cmd_configure.append('--ubsan-abort') if extra_hwdef is not None: cmd_configure.extend(['--extra-hwdef', extra_hwdef]) + for nv in extra_defines.items(): + cmd_configure.extend(['--define', "%s=%s" % nv]) if j is not None: cmd_configure.extend(['-j', str(j)]) pieces = [shlex.split(x) for x in extra_args] @@ -133,8 +157,24 @@ def waf_build(target=None): cmd.append(target) run_cmd(cmd, directory=topdir(), checkfail=True) -def build_SITL(build_target, j=None, debug=False, board='sitl', clean=True, configure=True, math_check_indexes=False, coverage=False, - ekf_single=False, postype_single=False, sitl_32bit=False, extra_configure_args=[]): + +def build_SITL( + build_target, + board='sitl', + clean=True, + configure=True, + coverage=False, + debug=False, + ekf_single=False, + extra_configure_args=[], + extra_defines={}, + j=None, + math_check_indexes=False, + postype_single=False, + sitl_32bit=False, + ubsan=False, + ubsan_abort=False, +): # first configure if configure: @@ -146,6 +186,9 @@ def build_SITL(build_target, j=None, debug=False, board='sitl', clean=True, conf postype_single=postype_single, coverage=coverage, sitl_32bit=sitl_32bit, + ubsan=ubsan, + ubsan_abort=ubsan_abort, + extra_defines=extra_defines, extra_args=extra_configure_args) # then clean @@ -161,7 +204,7 @@ def build_SITL(build_target, j=None, debug=False, board='sitl', clean=True, conf def build_examples(board, j=None, debug=False, clean=False, configure=True, math_check_indexes=False, coverage=False, - ekf_single=False, postype_single=False, sitl_32bit=False, + ekf_single=False, postype_single=False, sitl_32bit=False, ubsan=False, ubsan_abort=False, extra_configure_args=[]): # first configure if configure: @@ -173,6 +216,8 @@ def build_examples(board, j=None, debug=False, clean=False, configure=True, math postype_single=postype_single, coverage=coverage, sitl_32bit=sitl_32bit, + ubsan=ubsan, + ubsan_abort=ubsan_abort, extra_args=extra_configure_args) # then clean @@ -184,6 +229,7 @@ def build_examples(board, j=None, debug=False, clean=False, configure=True, math run_cmd(cmd_make, directory=topdir(), checkfail=True, show=True) return True + def build_replay(board, j=None, debug=False, clean=False): # first configure waf_configure(board, j=j, debug=debug) @@ -197,8 +243,20 @@ def build_replay(board, j=None, debug=False, clean=False): run_cmd(cmd_make, directory=topdir(), checkfail=True, show=True) return True -def build_tests(board, j=None, debug=False, clean=False, configure=True, math_check_indexes=False, coverage=False, - ekf_single=False, postype_single=False, sitl_32bit=False, extra_configure_args=[]): + +def build_tests(board, + j=None, + debug=False, + clean=False, + configure=True, + math_check_indexes=False, + coverage=False, + ekf_single=False, + postype_single=False, + sitl_32bit=False, + ubsan=False, + ubsan_abort=False, + extra_configure_args=[]): # first configure if configure: @@ -210,6 +268,8 @@ def build_tests(board, j=None, debug=False, clean=False, configure=True, math_ch postype_single=postype_single, coverage=coverage, sitl_32bit=sitl_32bit, + ubsan=ubsan, + ubsan_abort=ubsan_abort, extra_args=extra_configure_args) # then clean @@ -220,6 +280,7 @@ def build_tests(board, j=None, debug=False, clean=False, configure=True, math_ch run_cmd([relwaf(), "tests"], directory=topdir(), checkfail=True, show=True) return True + # list of pexpect children to close on exit close_list = [] @@ -271,7 +332,6 @@ def pexpect_close_all(): def pexpect_drain(p): """Drain any pending input.""" - import pexpect try: p.read_nonblocking(1000, timeout=0) except Exception: @@ -298,13 +358,35 @@ def kill_screen_gdb(): cmd = ["screen", "-X", "-S", "ardupilot-gdb", "quit"] subprocess.Popen(cmd) + def kill_mac_terminal(): global windowID for window in windowID: cmd = ("osascript -e \'tell application \"Terminal\" to close " - "(window(get index of window id %s))\'" % window) + "(window(get index of window id %s))\'" % window) os.system(cmd) + +class FakeMacOSXSpawn(object): + """something that looks like a pspawn child so we can ignore attempts + to pause (and otherwise kill(1) SITL. MacOSX using osascript to + start/stop sitl + """ + def __init__(self): + pass + + def progress(self, message): + print(message) + + def kill(self, sig): + # self.progress("FakeMacOSXSpawn: ignoring kill(%s)" % str(sig)) + pass + + def isalive(self): + self.progress("FakeMacOSXSpawn: assuming process is alive") + return True + + def start_SITL(binary, valgrind=False, callgrind=False, @@ -353,8 +435,8 @@ def start_SITL(binary, # attach gdb to the gdbserver: f = open("/tmp/x.gdb", "w") f.write("target extended-remote localhost:3333\nc\n") - for breakpoint in breakpoints: - f.write("b %s\n" % (breakpoint,)) + for breakingpoint in breakpoints: + f.write("b %s\n" % (breakingpoint,)) if disable_breakpoints: f.write("disable\n") f.close() @@ -363,8 +445,8 @@ def start_SITL(binary, elif gdb: f = open("/tmp/x.gdb", "w") f.write("set pagination off\n") - for breakpoint in breakpoints: - f.write("b %s\n" % (breakpoint,)) + for breakingpoint in breakpoints: + f.write("b %s\n" % (breakingpoint,)) if disable_breakpoints: f.write("disable\n") if not gdb_no_tui: @@ -384,8 +466,8 @@ def start_SITL(binary, 'gdb', '-x', '/tmp/x.gdb', binary, '--args']) elif lldb: f = open("/tmp/x.lldb", "w") - for breakpoint in breakpoints: - f.write("b %s\n" % (breakpoint,)) + for breakingpoint in breakpoints: + f.write("b %s\n" % (breakingpoint,)) if disable_breakpoints: f.write("disable\n") f.write("settings set target.process.stop-on-exec false\n") @@ -394,7 +476,7 @@ def start_SITL(binary, if sys.platform == "darwin" and os.getenv('DISPLAY'): cmd.extend(['lldb', '-s', '/tmp/x.lldb', '--']) elif os.environ.get('DISPLAY'): - cmd.extend(['xterm', '-e', 'lldb', '-s','/tmp/x.lldb', '--']) + cmd.extend(['xterm', '-e', 'lldb', '-s', '/tmp/x.lldb', '--']) else: raise RuntimeError("DISPLAY was not set") @@ -421,7 +503,7 @@ def start_SITL(binary, # somewhere for MAVProxy to connect to: cmd.append('--uartC=tcp:2') if not enable_fgview_output: - cmd.append("--disable-fgview"); + cmd.append("--disable-fgview") cmd.extend(customisations) @@ -433,8 +515,7 @@ def start_SITL(binary, mydir = os.path.dirname(os.path.realpath(__file__)) autotest_dir = os.path.realpath(os.path.join(mydir, '..')) runme = [os.path.join(autotest_dir, "run_in_terminal_window.sh"), 'mactest'] - runme.extend(cmd) - print(runme) + runme.extend(cmd) print(cmd) out = subprocess.Popen(runme, stdout=subprocess.PIPE).communicate()[0] out = out.decode('utf-8') @@ -454,6 +535,7 @@ def start_SITL(binary, windowID.append(tabs[0]) else: print("Cannot find %s process terminal" % binary) + child = FakeMacOSXSpawn() elif gdb and not os.getenv('DISPLAY'): subprocess.Popen(cmd) atexit.register(kill_screen_gdb) @@ -468,7 +550,6 @@ def start_SITL(binary, else: print("Running: %s" % cmd_as_shell(cmd)) - first = cmd[0] rest = cmd[1:] child = pexpect.spawn(first, rest, logfile=sys.stdout, encoding=ENCODING, timeout=5) @@ -488,18 +569,20 @@ def start_SITL(binary, def mavproxy_cmd(): - '''return path to which mavproxy to use''' + """return path to which mavproxy to use""" return os.getenv('MAVPROXY_CMD', 'mavproxy.py') + def MAVProxy_version(): - '''return the current version of mavproxy as a tuple e.g. (1,8,8)''' + """return the current version of mavproxy as a tuple e.g. (1,8,8)""" command = "%s --version" % mavproxy_cmd() output = subprocess.Popen(command, shell=True, stdout=subprocess.PIPE).communicate()[0] output = output.decode('ascii') match = re.search("MAVProxy Version: ([0-9]+)[.]([0-9]+)[.]([0-9]+)", output) if match is None: raise ValueError("Unable to determine MAVProxy version from (%s)" % output) - return (int(match.group(1)), int(match.group(2)), int(match.group(3))) + return int(match.group(1)), int(match.group(2)), int(match.group(3)) + def start_MAVProxy_SITL(atype, aircraft=None, @@ -528,7 +611,7 @@ def start_MAVProxy_SITL(atype, aircraft = 'test.%s' % atype cmd.extend(['--aircraft', aircraft]) cmd.extend(options) - cmd.extend(['--default-modules', 'misc,terrain,wp,rally,fence,param,arm,mode,rc,cmdlong,output']) + cmd.extend(['--default-modules', 'misc,wp,rally,fence,param,arm,mode,rc,cmdlong,output']) print("PYTHONPATH: %s" % str(env['PYTHONPATH'])) print("Running: %s" % cmd_as_shell(cmd)) @@ -587,7 +670,7 @@ def lock_file(fname): f = open(fname, mode='w') try: fcntl.lockf(f, fcntl.LOCK_EX | fcntl.LOCK_NB) - except Exception: + except OSError: return None return f @@ -597,13 +680,13 @@ def check_parent(parent_pid=None): if parent_pid is None: try: parent_pid = os.getppid() - except Exception: + except OSError: pass if parent_pid is None: return try: os.kill(parent_pid, 0) - except Exception: + except OSError: print("Parent had finished - exiting") sys.exit(1) @@ -668,7 +751,7 @@ def gps_newpos(lat, lon, bearing, distance): cos(lat1) * sin(dr) * cos(brng)) lon2 = lon1 + atan2(sin(brng) * sin(dr) * cos(lat1), cos(dr) - sin(lat1) * sin(lat2)) - return (degrees(lat2), degrees(lon2)) + return degrees(lat2), degrees(lon2) def gps_distance(lat1, lon1, lat2, lon2): @@ -740,7 +823,7 @@ def current(self, deltat=None): w_delta -= (self.turbulance_mul - 1.0) * (deltat / self.turbulance_time_constant) self.turbulance_mul += w_delta speed = self.speed * math.fabs(self.turbulance_mul) - return (speed, self.direction) + return speed, self.direction # Calculate drag. def drag(self, velocity, deltat=None): @@ -794,7 +877,7 @@ def apparent_wind(wind_sp, obj_speed, alpha): else: beta = acos((delta + obj_speed) / rel_speed) - return (rel_speed, beta) + return rel_speed, beta def drag_force(wind, sp): @@ -837,8 +920,9 @@ def constrain(value, minv, maxv): value = maxv return value + def load_local_module(fname): - '''load a python module from within the ardupilot tree''' + """load a python module from within the ardupilot tree""" fname = os.path.join(topdir(), fname) if sys.version_info.major >= 3: import importlib.util diff --git a/Tools/autotest/pysim/vehicleinfo.py b/Tools/autotest/pysim/vehicleinfo.py index 684bd3ee0b8..db8715b1cfe 100644 --- a/Tools/autotest/pysim/vehicleinfo.py +++ b/Tools/autotest/pysim/vehicleinfo.py @@ -392,6 +392,14 @@ def __init__(self): }, }, }, + "sitl_periph_gps": { + "frames": { + "gps": { + "configure_target": "sitl_periph_gps", + "waf_target": "bin/AP_Periph", + }, + } + }, } diff --git a/Tools/autotest/quadplane.py b/Tools/autotest/quadplane.py index 999689a9ad2..50a38d00676 100644 --- a/Tools/autotest/quadplane.py +++ b/Tools/autotest/quadplane.py @@ -88,7 +88,7 @@ def get_disarm_delay(self): def set_autodisarm_delay(self, delay): self.set_parameter("LAND_DISARMDELAY", delay) - def test_airmode(self): + def AirMode(self): """Check that plane.air_mode turns on and off as required""" self.progress("########## Testing AirMode operation") self.set_parameter("AHRS_EKF_TYPE", 10) @@ -187,7 +187,6 @@ def test_airmode(self): 'LOITER', 'QHOVER', 'QLOITER', - 'RTL', 'STABILIZE', 'TRAINING', ): @@ -248,19 +247,18 @@ def test_airmode(self): self.progress("Waiting for Motor1 to speed up") self.wait_servo_channel_value(5, spin_min_pwm, comparator=operator.ge) - self.progress("Disarm/rearm with GCS") - self.disarm_vehicle() + self.disarm_vehicle_expect_fail() self.arm_vehicle() self.progress("Verify that airmode is still on") self.wait_servo_channel_value(5, spin_min_pwm, comparator=operator.ge) - self.disarm_vehicle() + self.disarm_vehicle(force=True) self.wait_ready_to_arm() - def test_motor_mask(self): + def TestMotorMask(self): """Check operation of output_motor_mask""" """copter tailsitters will add condition: or (int(self.get_parameter('Q_TAILSIT_MOTMX')) & 1)""" - if not(int(self.get_parameter('Q_TILT_MASK')) & 1): + if not (int(self.get_parameter('Q_TILT_MASK')) & 1): self.progress("output_motor_mask not in use") return self.progress("Testing output_motor_mask") @@ -268,7 +266,7 @@ def test_motor_mask(self): """Default channel for Motor1 is 5""" self.progress('Assert that SERVO5 is Motor1') - assert(33 == self.get_parameter('SERVO5_FUNCTION')) + assert 33 == self.get_parameter('SERVO5_FUNCTION') modes = ('MANUAL', 'FBWA', 'QHOVER') for mode in modes: @@ -284,7 +282,7 @@ def test_motor_mask(self): self.disarm_vehicle() self.wait_ready_to_arm() - def fly_mission(self, filename, fence=None, height_accuracy=-1): + def fly_mission(self, filename, fence=None, height_accuracy=-1, include_terrain_timeout=False): """Fly a mission from a file.""" self.progress("Flying mission %s" % filename) self.load_mission(filename) @@ -292,6 +290,7 @@ def fly_mission(self, filename, fence=None, height_accuracy=-1): self.load_fence(fence) if self.mavproxy is not None: self.mavproxy.send('wp list\n') + self.install_terrain_handlers_context() self.wait_ready_to_arm() self.arm_vehicle() self.change_mode('AUTO') @@ -307,56 +306,6 @@ def fly_mission(self, filename, fence=None, height_accuracy=-1): self.wait_disarmed(timeout=120) # give quadplane a long time to land self.progress("Mission OK") - def enum_state_name(self, enum_name, state, pretrim=None): - e = mavutil.mavlink.enums[enum_name] - e_value = e[state] - name = e_value.name - if pretrim is not None: - if not pretrim.startswith(pretrim): - raise NotAchievedException("Expected %s to pretrim" % (pretrim)) - name = name.replace(pretrim, "") - return name - - def vtol_state_name(self, state): - return self.enum_state_name("MAV_VTOL_STATE", state, pretrim="MAV_VTOL_STATE_") - - def landed_state_name(self, state): - return self.enum_state_name("MAV_LANDED_STATE", state, pretrim="MAV_LANDED_STATE_") - - def assert_extended_sys_state(self, vtol_state, landed_state): - m = self.assert_receive_message('EXTENDED_SYS_STATE', timeout=1) - if m.vtol_state != vtol_state: - raise ValueError("Bad MAV_VTOL_STATE. Want=%s got=%s" % - (self.vtol_state_name(vtol_state), - self.vtol_state_name(m.vtol_state))) - if m.landed_state != landed_state: - raise ValueError("Bad MAV_LANDED_STATE. Want=%s got=%s" % - (self.landed_state_name(landed_state), - self.landed_state_name(m.landed_state))) - - def wait_extended_sys_state(self, vtol_state, landed_state): - tstart = self.get_sim_time() - while True: - if self.get_sim_time() - tstart > 10: - raise NotAchievedException("Did not achieve vol/landed states") - self.progress("Waiting for MAV_VTOL_STATE=%s MAV_LANDED_STATE=%s" % - (self.vtol_state_name(vtol_state), - self.landed_state_name(landed_state))) - m = self.assert_receive_message('EXTENDED_SYS_STATE', verbose=True) - if m.landed_state != landed_state: - self.progress("Wrong MAV_LANDED_STATE (want=%s got=%s)" % - (self.landed_state_name(landed_state), - self.landed_state_name(m.landed_state))) - continue - if m.vtol_state != vtol_state: - self.progress("Wrong MAV_VTOL_STATE (want=%s got=%s)" % - (self.vtol_state_name(vtol_state), - self.vtol_state_name(m.vtol_state))) - continue - - self.progress("vtol and landed states match") - return - def EXTENDED_SYS_STATE_SLT(self): self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_EXTENDED_SYS_STATE, 10) self.change_mode("QHOVER") @@ -407,6 +356,7 @@ def EXTENDED_SYS_STATE_SLT(self): self.mav.motors_disarmed_wait() def EXTENDED_SYS_STATE(self): + '''Check extended sys state works''' self.EXTENDED_SYS_STATE_SLT() def fly_qautotune(self): @@ -447,6 +397,7 @@ def fly_qautotune(self): def takeoff(self, height, mode): """climb to specified height and set throttle to 1500""" + self.set_current_waypoint(0, check_afterwards=False) self.change_mode(mode) self.wait_ready_to_arm() self.arm_vehicle() @@ -471,6 +422,7 @@ def fly_home_land_and_disarm(self, timeout=30): self.change_mode("AUTO") self.set_current_waypoint(7) self.wait_disarmed(timeout=timeout) + self.set_current_waypoint(0, check_afterwards=False) def wait_level_flight(self, accuracy=5, timeout=30): """Wait for level flight.""" @@ -565,7 +517,7 @@ def hover_and_check_matched_frequency(self, dblevel=-15, minhz=200, maxhz=300, f return freq - def fly_gyro_fft(self): + def GyroFFT(self): """Use dynamic harmonic notch to control motor noise.""" # basic gyro sample rate test self.progress("Flying with gyro FFT - Gyro sample rate") @@ -676,11 +628,13 @@ def fly_gyro_fft(self): if ex is not None: raise ex - def test_pid_tuning(self): + def PIDTuning(self): + '''Test PID Tuning''' self.change_mode("FBWA") # we don't update PIDs in MANUAL - super(AutoTestQuadPlane, self).test_pid_tuning() + super(AutoTestQuadPlane, self).PIDTuning() - def test_parameter_checks(self): + def ParameterChecks(self): + '''basic parameter checks''' self.test_parameter_checks_poscontrol("Q_P") def rc_defaults(self): @@ -699,7 +653,31 @@ def disabled_tests(self): "ConfigErrorLoop": "failing because RC values not settable", } - def test_pilot_yaw(self): + def BootInAUTO(self): + '''Test behaviour when booting in auto''' + self.load_mission("mission.txt") + self.set_parameters({ + }) + self.set_rc(5, 1000) + self.wait_mode('AUTO') + self.reboot_sitl() + self.wait_ready_to_arm() + self.delay_sim_time(20) + self.assert_current_waypoint(1) + self.arm_vehicle() + self.wait_altitude(9, 11, relative=True) # value from mission file is 10 + distance = self.distance_to_home() + # this distance check is very, very loose. At time of writing + # the vehicle actually pitches ~6 degrees on trakeoff, + # wandering over 1m. + if distance > 2: + raise NotAchievedException("wandered from home (distance=%f)" % + (distance,)) + self.change_mode('QLAND') + self.wait_disarmed(timeout=60) + + def PilotYaw(self): + '''Test pilot yaw in various modes''' self.takeoff(10, mode="QLOITER") self.set_parameter("STICK_MIXING", 0) self.set_rc(4, 1700) @@ -711,7 +689,8 @@ def test_pilot_yaw(self): self.set_rc(4, 1500) self.do_RTL() - def weathervane_test(self): + def Weathervane(self): + '''test nose-into-wind functionality''' # We test nose into wind code paths and yaw direction in copter autotest, # so we shall test the side into wind yaw direction and plane code paths here. self.set_parameters({"SIM_WIND_SPD": 10, @@ -736,7 +715,8 @@ def CPUFailsafe(self): '''In lockup Plane should copy RC inputs to RC outputs''' self.plane_CPUFailsafe() - def test_qassist(self): + def QAssist(self): + '''QuadPlane Assist tests''' # find a motor peak self.takeoff(10, mode="QHOVER") self.set_rc(3, 1800) @@ -789,7 +769,7 @@ def test_qassist(self): self.change_mode("RTL") self.wait_disarmed(timeout=300) - def tailsitter(self): + def Tailsitter(self): '''tailsitter test''' self.set_parameter('Q_FRAME_CLASS', 10) self.set_parameter('Q_ENABLE', 1) @@ -811,52 +791,160 @@ def tailsitter(self): raise NotAchievedException("Changed throttle output on mode change to QHOVER") self.disarm_vehicle() - def tests(self): - '''return list of all tests''' - - ret = super(AutoTestQuadPlane, self).tests() - ret.extend([ - ("TestAirMode", "Test airmode", self.test_airmode), - - ("TestMotorMask", "Test output_motor_mask", self.test_motor_mask), - - ("PilotYaw", - "Test pilot yaw in various modes", - self.test_pilot_yaw), - - ("ParameterChecks", - "Test Arming Parameter Checks", - self.test_parameter_checks), + def ICEngine(self): + '''Test ICE Engine support''' + rc_engine_start_chan = 11 + self.set_parameters({ + 'SERVO13_FUNCTION': 67, # ignition + 'SERVO14_FUNCTION': 69, # starter + 'ICE_ENABLE': 1, + 'ICE_START_CHAN': rc_engine_start_chan, + 'ICE_RPM_CHAN': 1, + 'RPM1_TYPE': 10, + }) + self.reboot_sitl() + self.wait_ready_to_arm() + self.wait_rpm(1, 0, 0, minimum_duration=1) + self.arm_vehicle() + self.wait_rpm(1, 0, 0, minimum_duration=1) + self.context_collect("STATUSTEXT") + self.progress("Setting engine-start RC switch to HIGH") + self.set_rc(rc_engine_start_chan, 2000) + self.wait_statustext("Starting engine", check_context=True) + self.wait_rpm(1, 300, 400, minimum_duration=1) + self.progress("Setting engine-start RC switch to MID") + self.set_rc(rc_engine_start_chan, 1500) + self.progress("Setting full throttle") + self.set_rc(3, 2000) + self.wait_rpm(1, 6500, 7500, minimum_duration=30, timeout=40) + self.progress("Setting min-throttle") + self.set_rc(3, 1000) + self.wait_rpm(1, 300, 400, minimum_duration=1) + self.progress("Setting engine-start RC switch to LOW") + self.set_rc(rc_engine_start_chan, 1000) + self.wait_rpm(1, 0, 0, minimum_duration=1) + # ICE provides forward thrust, which can make us think we're flying: + self.disarm_vehicle(force=True) + self.reboot_sitl() - ("TestLogDownload", - "Test Onboard Log Download", - self.test_log_download), + def ICEngineMission(self): + '''Test ICE Engine Mission support''' + rc_engine_start_chan = 11 + self.set_parameters({ + 'SERVO13_FUNCTION': 67, # ignition + 'SERVO14_FUNCTION': 69, # starter + 'ICE_ENABLE': 1, + 'ICE_START_CHAN': rc_engine_start_chan, + 'ICE_RPM_CHAN': 1, + 'RPM1_TYPE': 10, + }) + self.load_mission("mission.txt") + self.wait_ready_to_arm() + self.set_rc(rc_engine_start_chan, 2000) + self.arm_vehicle() + self.change_mode('AUTO') + self.wait_disarmed(timeout=300) - ("EXTENDED_SYS_STATE", - "Check extended sys state works", - self.EXTENDED_SYS_STATE), + def Ship(self): + '''Ensure we can take off from simulated ship''' + self.context_push() + self.set_parameters({ + 'SIM_SHIP_ENABLE': 1, + 'SIM_SHIP_SPEED': 1, # the default of 3 will break this test + }) + self.change_mode('QLOITER') + self.wait_ready_to_arm() + self.arm_vehicle() + self.set_rc(3, 1700) + # self.delay_sim_time(1) + # self.send_debug_trap() + # output here is a bit weird as we also receive altitude from + # the simulated ship.... + self.wait_altitude(20, 30, relative=True) + self.disarm_vehicle(force=True) + self.context_pop() + self.reboot_sitl() - ("Mission", "Dalby Mission", - lambda: self.fly_mission("Dalby-OBC2016.txt", "Dalby-OBC2016-fence.txt")), + def MidAirDisarmDisallowed(self): + '''Check disarm behaviour in Q-mode''' + self.start_subtest("Basic arm in qloiter") + self.set_parameter("FLIGHT_OPTIONS", 0) + self.change_mode('QLOITER') + self.wait_ready_to_arm() + self.arm_vehicle() + self.disarm_vehicle() - ("Weathervane", - "Test Weathervane Functionality", - self.weathervane_test), + self.context_push() + self.start_subtest("Ensure disarming in q-modes on ground works") + self.set_parameter("FLIGHT_OPTIONS", 1 << 11) + self.arm_vehicle() + self.disarm_vehicle() # should be OK as we're not flying yet + self.context_pop() - ("QAssist", - "QuadPlane Assist tests", - self.test_qassist), + self.start_subtest("Ensure no disarming mid-air") + self.arm_vehicle() + self.set_rc(3, 2000) + self.wait_altitude(5, 50, relative=True) + self.set_rc(3, 1000) + disarmed = False + try: + self.disarm_vehicle() + disarmed = True + except ValueError as e: + self.progress("Got %s" % repr(e)) + if "Expected MAV_RESULT_ACCEPTED got MAV_RESULT_FAILED" not in str(e): + raise e + if disarmed: + raise NotAchievedException("Disarmed when we shouldn't have") + + self.change_mode('QLAND') + self.wait_disarmed() - ("GyroFFT", "Fly Gyro FFT", - self.fly_gyro_fft), + self.start_subtest("Check we can disarm after a short period on the ground") + self.takeoff(5, 'QHOVER') + self.change_mode('QLAND') + try: + self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_EXTENDED_SYS_STATE, 10) + self.wait_extended_sys_state( + landed_state=mavutil.mavlink.MAV_LANDED_STATE_ON_GROUND, + vtol_state=mavutil.mavlink.MAV_VTOL_STATE_MC, + timeout=60 + ) + except Exception: + self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_EXTENDED_SYS_STATE, 0) + raise + + self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_EXTENDED_SYS_STATE, -1) + self.disarm_vehicle() - ("Tailsitter", - "Test tailsitter support", - self.tailsitter), + def Mission(self): + '''fly the OBC 2016 mission in Dalby''' + self.fly_mission( + "Dalby-OBC2016.txt", + "Dalby-OBC2016-fence.txt", + include_terrain_timeout=True + ) + def tests(self): + '''return list of all tests''' - ("LogUpload", - "Log upload", - self.log_upload), + ret = super(AutoTestQuadPlane, self).tests() + ret.extend([ + self.AirMode, + self.TestMotorMask, + self.PilotYaw, + self.ParameterChecks, + self.LogDownload, + self.EXTENDED_SYS_STATE, + self.Mission, + self.Weathervane, + self.QAssist, + self.GyroFFT, + self.Tailsitter, + self.ICEngine, + self.ICEngineMission, + self.MidAirDisarmDisallowed, + self.BootInAUTO, + self.Ship, ]) return ret diff --git a/Tools/autotest/rover.py b/Tools/autotest/rover.py index fb10d75c032..42aefb375a4 100644 --- a/Tools/autotest/rover.py +++ b/Tools/autotest/rover.py @@ -1,5 +1,3 @@ -#!/usr/bin/env python - ''' Drive Rover in SITL @@ -72,6 +70,9 @@ def sitl_start_location(self): def default_frame(self): return "rover" + def default_speedup(self): + return 30 + def is_rover(self): return True @@ -82,15 +83,17 @@ def get_stick_arming_channel(self): # TESTS DRIVE ########################################################## # Drive a square in manual mode - def drive_square(self, side=50): - """Drive a square, Driving N then E .""" + def DriveSquare(self, side=50): + """Learn/Drive Square with Ch7 option""" self.context_push() ex = None try: self.progress("TEST SQUARE") - self.set_parameter("RC7_OPTION", 7) - self.set_parameter("RC9_OPTION", 58) + self.set_parameters({ + "RC7_OPTION": 7, + "RC9_OPTION": 58, + }) self.change_mode('MANUAL') @@ -232,7 +235,7 @@ def drive_left_circuit(self): # "timed out after %u seconds" % timeout) # return False - def test_sprayer(self): + def Sprayer(self): """Test sprayer functionality.""" self.context_push() ex = None @@ -310,7 +313,7 @@ def test_sprayer(self): self.change_mode("AUTO") # self.send_debug_trap() self.progress("Waiting for sprayer to start") - self.wait_servo_channel_value(pump_ch, 1300, timeout=60, comparator=operator.gt) + self.wait_servo_channel_value(pump_ch, 1250, timeout=60, comparator=operator.gt) self.progress("Waiting for sprayer to stop") self.wait_servo_channel_value(pump_ch, pump_ch_min, timeout=120) @@ -351,8 +354,8 @@ def test_sprayer(self): if ex: raise ex - def drive_max_rcin(self, timeout=30): - """Test max RC inputs""" + def DriveMaxRCIN(self, timeout=30): + """Drive rover at max RC inputs""" self.context_push() ex = None @@ -392,16 +395,21 @@ def drive_max_rcin(self, timeout=30): def drive_mission(self, filename, strict=True): """Drive a mission from a file.""" self.progress("Driving mission %s" % filename) - self.load_mission(filename, strict=strict) + wp_count = self.load_mission(filename, strict=strict) self.wait_ready_to_arm() self.arm_vehicle() self.change_mode('AUTO') - self.wait_waypoint(1, 4, max_dist=5) + self.wait_waypoint(1, wp_count-1, max_dist=5) self.wait_statustext("Mission Complete", timeout=600) self.disarm_vehicle() self.progress("Mission OK") - def test_gripper_mission(self): + def DriveMission(self): + '''Drive Mission rover1.txt''' + self.drive_mission("rover1.txt", strict=False) + + def GripperMission(self): + '''Test Gripper Mission Items''' self.load_mission("rover-gripper-mission.txt") self.change_mode('AUTO') self.wait_ready_to_arm() @@ -412,7 +420,8 @@ def test_gripper_mission(self): self.wait_statustext("Mission Complete", timeout=60, check_context=True) self.disarm_vehicle() - def do_get_banner(self): + def GetBanner(self): + '''Get Banner''' target_sysid = self.sysid_thismav() target_compid = 1 self.mav.mav.command_long_send( @@ -441,15 +450,17 @@ def do_get_banner(self): raise MsgRcvTimeoutException("banner not received") def drive_brake_get_stopping_distance(self, speed): - # measure our stopping distance: - old_cruise_speed = self.get_parameter('CRUISE_SPEED') - old_accel_max = self.get_parameter('ATC_ACCEL_MAX') + '''measure our stopping distance''' + + self.context_push() # controller tends not to meet cruise speed (max of ~14 when 15 # set), thus *1.2 - self.set_parameter('CRUISE_SPEED', speed*1.2) # at time of writing, the vehicle is only capable of 10m/s/s accel - self.set_parameter('ATC_ACCEL_MAX', 15) + self.set_parameters({ + 'CRUISE_SPEED': speed*1.2, + 'ATC_ACCEL_MAX': 15, + }) self.change_mode("STEERING") self.set_rc(3, 2000) self.wait_groundspeed(15, 100) @@ -471,17 +482,16 @@ def drive_brake_get_stopping_distance(self, speed): break delta = self.get_distance(start, stop) - self.set_parameter('CRUISE_SPEED', old_cruise_speed) - self.set_parameter('ATC_ACCEL_MAX', old_accel_max) + self.context_pop() return delta - def drive_brake(self): - old_using_brake = self.get_parameter('ATC_BRAKE') - old_cruise_speed = self.get_parameter('CRUISE_SPEED') - - self.set_parameter('CRUISE_SPEED', 15) - self.set_parameter('ATC_BRAKE', 0) + def DriveBrake(self): + '''Test braking''' + self.set_parameters({ + 'CRUISE_SPEED': 15, + 'ATC_BRAKE': 0, + }) self.arm_vehicle() @@ -490,13 +500,12 @@ def drive_brake(self): # brakes on: self.set_parameter('ATC_BRAKE', 1) distance_with_brakes = self.drive_brake_get_stopping_distance(15) - # revert state: - self.set_parameter('ATC_BRAKE', old_using_brake) - self.set_parameter('CRUISE_SPEED', old_cruise_speed) delta = distance_without_brakes - distance_with_brakes + + self.disarm_vehicle() + if delta < distance_without_brakes * 0.05: # 5% isn't asking for much - self.disarm_vehicle() raise NotAchievedException(""" Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) """ % @@ -504,8 +513,6 @@ def drive_brake(self): distance_without_brakes, delta)) - self.disarm_vehicle() - self.progress( "Brakes work (with=%0.2fm without=%0.2fm delta=%0.2fm)" % (distance_with_brakes, distance_without_brakes, delta)) @@ -514,7 +521,8 @@ def drive_rtl_mission_max_distance_from_home(self): '''maximum distance allowed from home at end''' return 6.5 - def drive_rtl_mission(self, timeout=120): + def DriveRTL(self, timeout=120): + '''Drive an RTL Mission''' self.wait_ready_to_arm() self.arm_vehicle() @@ -547,7 +555,7 @@ def drive_rtl_mission(self, timeout=120): (m.wp_dist, wp_dist_min,)) # wait for mission to complete - self.wait_statustext("Mission Complete", timeout=60) + self.wait_statustext("Mission Complete", timeout=70) # the EKF doesn't pull us down to 0 speed: self.wait_groundspeed(0, 0.5, timeout=600) @@ -564,14 +572,17 @@ def drive_rtl_mission(self, timeout=120): self.disarm_vehicle() self.progress("RTL Mission OK (%fm)" % home_distance) - def drive_fence_ac_avoidance(self): + def AC_Avoidance(self): + '''Test AC Avoidance switch''' self.context_push() ex = None try: self.load_fence("rover-fence-ac-avoid.txt") - self.set_parameter("FENCE_ENABLE", 0) - self.set_parameter("PRX_TYPE", 10) - self.set_parameter("RC10_OPTION", 40) # proximity-enable + self.set_parameters({ + "FENCE_ENABLE": 0, + "PRX1_TYPE": 10, + "RC10_OPTION": 40, # proximity-enable + }) self.reboot_sitl() # start = self.mav.location() self.wait_ready_to_arm() @@ -600,7 +611,8 @@ def drive_fence_ac_avoidance(self): if ex: raise ex - def test_servorelayevents(self): + def ServoRelayEvents(self): + '''Test ServoRelayEvents''' self.do_set_relay(0, 0) off = self.get_parameter("SIM_PIN_MASK") self.do_set_relay(0, 1) @@ -610,7 +622,8 @@ def test_servorelayevents(self): "Pin mask unchanged after relay cmd") self.progress("Pin mask changed after relay command") - def test_setting_modes_via_mavproxy_switch(self): + def MAVProxy_SetModeUsingSwitch(self): + """Set modes via mavproxy switch""" self.customise_SITL_commandline([ "--rc-in-port", "5502", ]) @@ -641,7 +654,8 @@ def test_setting_modes_via_mavproxy_switch(self): if ex is not None: raise ex - def test_setting_modes_via_mavproxy_mode_command(self): + def MAVProxy_SetModeUsingMode(self): + '''Set modes via mavproxy mode command''' fnoo = [(1, 'ACRO'), (3, 'STEERING'), (4, 'HOLD'), @@ -658,8 +672,8 @@ def test_setting_modes_via_mavproxy_mode_command(self): self.wait_mode(expected) self.stop_mavproxy(mavproxy) - def test_setting_modes_via_modeswitch(self): - # test setting of modes through mode switch + def ModeSwitch(self): + ''''Set modes via modeswitch''' self.context_push() ex = None try: @@ -686,7 +700,8 @@ def test_setting_modes_via_modeswitch(self): if ex is not None: raise ex - def test_setting_modes_via_auxswitches(self): + def AuxModeSwitch(self): + '''Set modes via auxswitches''' self.context_push() ex = None try: @@ -698,8 +713,10 @@ def test_setting_modes_via_auxswitches(self): self.set_rc(9, 1000) self.set_rc(10, 1000) - self.set_parameter("RC9_OPTION", 53) # steering - self.set_parameter("RC10_OPTION", 54) # hold + self.set_parameters({ + "RC9_OPTION": 53, # steering + "RC10_OPTION": 54, # hold + }) self.set_rc(9, 1900) self.wait_mode("STEERING") self.set_rc(10, 1900) @@ -727,7 +744,8 @@ def test_setting_modes_via_auxswitches(self): if ex is not None: raise ex - def test_rc_override_cancel(self): + def RCOverridesCancel(self): + '''Test RC overrides Cancel''' self.set_parameter("SYSID_MYGCS", self.mav.source_system) self.change_mode('MANUAL') self.wait_ready_to_arm() @@ -797,7 +815,8 @@ def test_rc_override_cancel(self): break self.disarm_vehicle() - def test_rc_overrides(self): + def RCOverrides(self): + '''Test RC overrides''' self.context_push() self.set_parameter("SYSID_MYGCS", self.mav.source_system) ex = None @@ -1040,7 +1059,8 @@ def test_rc_overrides(self): if ex is not None: raise ex - def test_manual_control(self): + def MANUAL_CONTROL(self): + '''Test mavlink MANUAL_CONTROL''' self.context_push() self.set_parameter("SYSID_MYGCS", self.mav.source_system) ex = None @@ -1130,6 +1150,7 @@ def test_manual_control(self): raise ex def CameraMission(self): + '''Test Camera Mission Items''' self.load_mission("rover-camera-mission.txt") self.wait_ready_to_arm() self.change_mode("AUTO") @@ -1166,17 +1187,20 @@ def CameraMission(self): self.disarm_vehicle() - def test_do_set_mode_via_command_long(self): + def DO_SET_MODE(self): + '''Set mode via MAV_COMMAND_DO_SET_MODE''' self.do_set_mode_via_command_long("HOLD") self.do_set_mode_via_command_long("MANUAL") - def test_mavproxy_do_set_mode_via_command_long(self): + def MAVProxy_DO_SET_MODE(self): + '''Set mode using MAVProxy commandline DO_SET_MODE''' mavproxy = self.start_mavproxy() self.mavproxy_do_set_mode_via_command_long(mavproxy, "HOLD") self.mavproxy_do_set_mode_via_command_long(mavproxy, "MANUAL") self.stop_mavproxy(mavproxy) - def test_sysid_enforce(self): + def SYSID_ENFORCE(self): + '''Test enforcement of SYSID_MYGCS''' '''Run the same arming code with correct then incorrect SYSID''' if self.mav.source_system != self.mav.mav.srcSystem: @@ -1235,11 +1259,9 @@ def test_sysid_enforce(self): if ex is not None: raise ex - def test_rally_points(self): - self.reboot_sitl() # to ensure starting point is as expected - + def Rally(self): + '''Test Rally Points''' self.load_rally("rover-test-rally.txt") - accuracy = self.get_parameter("WP_RADIUS") self.wait_ready_to_arm() self.arm_vehicle() @@ -1253,7 +1275,8 @@ def test_rally_points(self): -105.229401, 0, 0) - self.wait_location(loc, accuracy=accuracy) + accuracy = self.get_parameter("WP_RADIUS") + self.wait_location(loc, accuracy=accuracy, minimum_duration=10) self.disarm_vehicle() def fence_with_bad_frame(self, target_system=1, target_component=1): @@ -1982,7 +2005,8 @@ def test_gcs_fence_via_mavproxy(self, target_system=1, target_component=1): # MANUAL> usage: fence # noqa - def test_gcs_fence(self): + def GCSFence(self): + '''Upload and download of fence''' target_system = 1 target_component = 1 @@ -2152,8 +2176,8 @@ def test_gcs_fence(self): # exclusion zones) # FIXME: add test that a fence with edges that cross can't be uploaded # FIXME: add a test that fences enclose an area (e.g. all the points aren't the same value! - - def test_offboard(self, timeout=90): + def Offboard(self, timeout=90): + '''Test Offboard Control''' self.load_mission("rover-guided-mission.txt") self.wait_ready_to_arm(require_absolute=True) self.arm_vehicle() @@ -2387,7 +2411,7 @@ def check_rally_items_same(self, want, got, epsilon=None): def click_three_in(self, mavproxy, target_system=1, target_component=1): mavproxy.send('rally clear\n') - self.drain_mav_unparsed() + self.drain_mav() # there are race conditions in MAVProxy. Beware. mavproxy.send("click 1.0 1.0\n") mavproxy.send("rally add\n") @@ -2406,8 +2430,8 @@ def click_three_in(self, mavproxy, target_system=1, target_component=1): mavutil.mavlink.MAV_MISSION_TYPE_RALLY, ) - def test_gcs_rally(self, target_system=1, target_component=1): - + def GCSRally(self, target_system=1, target_component=1): + '''Upload and download of rally using MAVProxy''' self.start_subtest("Testing mavproxy CLI for rally points") if not self.mavproxy_can_do_mision_item_protocols(): return @@ -2423,7 +2447,7 @@ def test_gcs_rally(self, target_system=1, target_component=1): lat = float(lat_s) lng = float(lng_s) mavproxy.send('click %s %s\n' % (lat_s, lng_s)) - self.drain_mav_unparsed() + self.drain_mav() mavproxy.send('rally add\n') self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY, target_system=255, @@ -2630,9 +2654,9 @@ def test_gcs_rally(self, target_system=1, target_component=1): self.end_subsubtest("rally move") self.start_subsubtest("rally movemulti") - self.drain_mav_unparsed() + self.drain_mav() mavproxy.send('rally clear\n') - self.drain_mav_unparsed() + self.drain_mav() # there are race conditions in MAVProxy. Beware. mavproxy.send("click 1.0 1.0\n") mavproxy.send("rally add\n") @@ -2658,7 +2682,6 @@ def test_gcs_rally(self, target_system=1, target_component=1): # MAVProxy currently sends three separate items up. That's # not great and I don't want to lock that behaviour in here. self.delay_sim_time(10) - self.drain_mav_unparsed() expected_moved_items = copy.copy(unmoved_items) expected_moved_items[0].x = 1.0 * 1e7 expected_moved_items[0].y = 2.0 * 1e7 @@ -2677,7 +2700,6 @@ def test_gcs_rally(self, target_system=1, target_component=1): # MAVProxy currently sends three separate items up. That's # not great and I don't want to lock that behaviour in here. self.delay_sim_time(10) - self.drain_mav_unparsed() expected_moved_items = copy.copy(unmoved_items) expected_moved_items[0].x = 3.0 * 1e7 expected_moved_items[0].y = 1.0 * 1e7 @@ -2718,7 +2740,6 @@ def test_gcs_rally(self, target_system=1, target_component=1): self.progress("Removing first in list") mavproxy.send("rally remove 1\n") self.delay_sim_time(5) - self.drain_mav_unparsed() self.assert_mission_count_on_link( self.mav, 1, @@ -2735,7 +2756,6 @@ def test_gcs_rally(self, target_system=1, target_component=1): self.progress("Removing remaining item") mavproxy.send("rally remove 1\n") self.delay_sim_time(5) - self.drain_mav_unparsed() self.assert_mission_count_on_link( self.mav, 0, @@ -2777,7 +2797,6 @@ def test_gcs_rally(self, target_system=1, target_component=1): self.progress("Removing first in list") mavproxy.send("rally remove 1\n") self.delay_sim_time(5) - self.drain_mav_unparsed() self.assert_mission_count_on_link( self.mav, 2, @@ -2797,10 +2816,8 @@ def test_gcs_rally(self, target_system=1, target_component=1): mavproxy.send("rally move 1\n") # move has already been tested, assume it works... self.delay_sim_time(5) - self.drain_mav_unparsed() mavproxy.send("rally undo\n") self.delay_sim_time(5) - self.drain_mav_unparsed() undone_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY) self.check_rally_items_same(pure_items, undone_items) @@ -2847,8 +2864,8 @@ def test_gcs_rally(self, target_system=1, target_component=1): # MANUAL> usage: rally # noqa - def test_rally(self, target_system=1, target_component=1): - + def RallyUploadDownload(self, target_system=1, target_component=1): + '''Upload and download of rally''' old_srcSystem = self.mav.mav.srcSystem self.drain_mav() @@ -3433,7 +3450,7 @@ def test_rally(self, target_system=1, target_component=1): raise e self.reboot_sitl() - def test_gcs_mission(self): + def GCSMission(self): '''check MAVProxy's waypoint handling of missions''' target_system = 1 target_component = 1 @@ -3442,7 +3459,6 @@ def test_gcs_mission(self): self.delay_sim_time(1) if self.get_parameter("MIS_TOTAL") != 0: raise NotAchievedException("Failed to clear mission") - self.drain_mav_unparsed() m = self.assert_receive_message('MISSION_CURRENT', timeout=5) if m.seq != 0: raise NotAchievedException("Bad mission current") @@ -3590,7 +3606,7 @@ def wait_location_sending_target(self, loc, target_system=1, target_component=1, now = self.get_sim_time_cached() if now - tstart > timeout: raise AutoTestTimeoutException("Did not get to location") - if now - last_sent > 1: + if now - last_sent > 10: last_sent = now self.mav.mav.set_position_target_global_int_send( 0, @@ -3645,7 +3661,7 @@ def drive_somewhere_breach_boundary_and_rtl(self, loc, target_system=1, target_c now = self.get_sim_time_cached() if now - tstart > timeout: raise NotAchievedException("Did not breach boundary + RTL") - if now - last_sent > 1: + if now - last_sent > 10: last_sent = now self.mav.mav.set_position_target_global_int_send( 0, @@ -3710,7 +3726,7 @@ def drive_somewhere_stop_at_boundary(self, now = self.get_sim_time_cached() if now - tstart > timeout: raise NotAchievedException("Did not arrive and stop at boundary") - if now - last_sent > 1: + if now - last_sent > 10: last_sent = now self.mav.mav.set_position_target_global_int_send( 0, @@ -4347,7 +4363,7 @@ def test_poly_fence_reboot_survivability(self): raise NotAchievedException("Items did not survive reboot (want=%u got=%u)" % (8, downloaded_len)) - def test_poly_fence(self): + def PolyFence(self): '''test fence-related functions''' target_system = 1 target_component = 1 @@ -4356,8 +4372,10 @@ def test_poly_fence(self): self.wait_ready_to_arm() here = self.mav.location() self.progress("here: %f %f" % (here.lat, here.lng)) - self.set_parameter("FENCE_ENABLE", 1) - self.set_parameter("AVOID_ENABLE", 0) + self.set_parameters({ + "FENCE_ENABLE": 1, + "AVOID_ENABLE": 0, + }) # self.set_parameter("SIM_SPEEDUP", 1) @@ -4535,7 +4553,8 @@ def test_poly_fence_exclusion(self, here, target_system=1, target_component=1): target_system=target_system, target_component=target_component) - def drive_smartrtl(self): + def SmartRTL(self): + '''Test SmartRTL''' self.change_mode("STEERING") self.wait_ready_to_arm() self.arm_vehicle() @@ -4559,15 +4578,15 @@ def drive_smartrtl(self): self.change_mode("SMART_RTL") self.progress("Ensure we go via intermediate point") - self.wait_distance_to_location(loc, 0, 5) + self.wait_distance_to_location(loc, 0, 5, timeout=60) self.progress("Ensure we get home") self.wait_distance_to_home(3, 7, timeout=30) self.disarm_vehicle() - def test_motor_test(self): - '''AKA run-rover-run''' + def MotorTest(self): + '''Motor Test triggered via mavlink''' magic_throttle_value = 1812 self.wait_ready_to_arm() self.run_cmd( @@ -4605,9 +4624,11 @@ def test_poly_fence_object_avoidance_auto(self, target_system=1, target_componen self.context_push() ex = None try: - self.set_parameter("AVOID_ENABLE", 3) - self.set_parameter("OA_TYPE", 2) - self.set_parameter("FENCE_MARGIN", 0) # FIXME: https://github.com/ArduPilot/ardupilot/issues/11601 + self.set_parameters({ + "AVOID_ENABLE": 3, + "OA_TYPE": 2, + "FENCE_MARGIN": 0, # FIXME: https://github.com/ArduPilot/ardupilot/issues/11601 + }) self.reboot_sitl() self.change_mode('AUTO') self.wait_ready_to_arm() @@ -4652,9 +4673,11 @@ def test_poly_fence_object_avoidance_guided_pathfinding(self, target_system=1, t self.context_push() ex = None try: - self.set_parameter("AVOID_ENABLE", 3) - self.set_parameter("OA_TYPE", 2) - self.set_parameter("FENCE_MARGIN", 0) # FIXME: https://github.com/ArduPilot/ardupilot/issues/11601 + self.set_parameters({ + "AVOID_ENABLE": 3, + "OA_TYPE": 2, + "FENCE_MARGIN": 0, # FIXME: https://github.com/ArduPilot/ardupilot/issues/11601 + }) self.reboot_sitl() self.change_mode('GUIDED') self.wait_ready_to_arm() @@ -4677,13 +4700,15 @@ def test_poly_fence_object_avoidance_guided_pathfinding(self, target_system=1, t if ex is not None: raise ex - def test_wheelencoders(self): + def WheelEncoders(self): '''make sure wheel encoders are generally working''' ex = None try: - self.set_parameter("WENC_TYPE", 10) - self.set_parameter("EK3_ENABLE", 1) - self.set_parameter("AHRS_EKF_TYPE", 3) + self.set_parameters({ + "WENC_TYPE": 10, + "EK3_ENABLE": 1, + "AHRS_EKF_TYPE": 3, + }) self.reboot_sitl() self.change_mode("LOITER") self.wait_ready_to_arm() @@ -4737,8 +4762,10 @@ def test_poly_fence_object_avoidance_guided_two_squares(self, target_system=1, t self.context_push() ex = None try: - self.set_parameter("AVOID_ENABLE", 3) - self.set_parameter("OA_TYPE", 2) + self.set_parameters({ + "AVOID_ENABLE": 3, + "OA_TYPE": 2, + }) self.reboot_sitl() self.change_mode('GUIDED') self.wait_ready_to_arm() @@ -4786,8 +4813,10 @@ def test_poly_fence_avoidance_dont_breach_exclusion(self, target_system=1, targe ]) if self.mavproxy is not None: self.mavproxy.send("fence list\n") - self.set_parameter("FENCE_ENABLE", 1) - self.set_parameter("AVOID_ENABLE", 3) + self.set_parameters({ + "FENCE_ENABLE": 1, + "AVOID_ENABLE": 3, + }) fence_middle = self.offset_location_ne(here, 0, 30) # FIXME: this might be nowhere near "here"! expected_stopping_point = mavutil.location(40.0713376, -105.2295738, 0, 0) @@ -4804,7 +4833,8 @@ def do_RTL(self, distance_min=3, distance_max=7, timeout=60): self.change_mode("RTL") self.wait_distance_to_home(distance_min, distance_max, timeout=timeout) - def test_poly_fence_avoidance(self, target_system=1, target_component=1): + def PolyFenceAvoidance(self, target_system=1, target_component=1): + '''PolyFence avoidance tests''' self.change_mode("LOITER") self.wait_ready_to_arm() self.arm_vehicle() @@ -4823,15 +4853,19 @@ def test_poly_fence_object_avoidance_guided_bendy_ruler(self, target_system=1, t self.context_push() ex = None try: - self.set_parameter("AVOID_ENABLE", 3) - self.set_parameter("OA_TYPE", 1) - self.set_parameter("OA_LOOKAHEAD", 50) + self.set_parameters({ + "AVOID_ENABLE": 3, + "OA_TYPE": 1, + "OA_LOOKAHEAD": 50, + }) self.reboot_sitl() self.change_mode('GUIDED') self.wait_ready_to_arm() self.arm_vehicle() - self.set_parameter("FENCE_ENABLE", 1) - self.set_parameter("WP_RADIUS", 5) + self.set_parameters({ + "FENCE_ENABLE": 1, + "WP_RADIUS": 5, + }) if self.mavproxy is not None: self.mavproxy.send("fence list\n") target_loc = mavutil.location(40.071060, -105.227734, 0, 0) @@ -4851,7 +4885,8 @@ def test_poly_fence_object_avoidance_guided_bendy_ruler(self, target_system=1, t if ex is not None: raise ex - def test_poly_fence_object_avoidance_bendy_ruler_easier(self, target_system=1, target_component=1): + def PolyFenceObjectAvoidanceBendyRulerEasier(self, target_system=1, target_component=1): + '''PolyFence object avoidance tests - easier bendy ruler test''' if not self.mavproxy_can_do_mision_item_protocols(): return self.test_poly_fence_object_avoidance_auto_bendy_ruler_easier( @@ -4870,15 +4905,19 @@ def test_poly_fence_object_avoidance_guided_bendy_ruler_easier(self, target_syst self.context_push() ex = None try: - self.set_parameter("AVOID_ENABLE", 3) - self.set_parameter("OA_TYPE", 1) - self.set_parameter("OA_LOOKAHEAD", 50) + self.set_parameters({ + "AVOID_ENABLE": 3, + "OA_TYPE": 1, + "OA_LOOKAHEAD": 50, + }) self.reboot_sitl() self.change_mode('GUIDED') self.wait_ready_to_arm() self.arm_vehicle() - self.set_parameter("FENCE_ENABLE", 1) - self.set_parameter("WP_RADIUS", 5) + self.set_parameters({ + "FENCE_ENABLE": 1, + "WP_RADIUS": 5, + }) if self.mavproxy is not None: self.mavproxy.send("fence list\n") target_loc = mavutil.location(40.071260, -105.227000, 0, 0) @@ -4911,15 +4950,19 @@ def test_poly_fence_object_avoidance_auto_bendy_ruler_easier(self, target_system self.context_push() ex = None try: - self.set_parameter("AVOID_ENABLE", 3) - self.set_parameter("OA_TYPE", 1) - self.set_parameter("OA_LOOKAHEAD", 50) + self.set_parameters({ + "AVOID_ENABLE": 3, + "OA_TYPE": 1, + "OA_LOOKAHEAD": 50, + }) self.reboot_sitl() self.change_mode('AUTO') self.wait_ready_to_arm() self.arm_vehicle() - self.set_parameter("FENCE_ENABLE", 1) - self.set_parameter("WP_RADIUS", 5) + self.set_parameters({ + "FENCE_ENABLE": 1, + "WP_RADIUS": 5, + }) if self.mavproxy is not None: self.mavproxy.send("fence list\n") target_loc = mavutil.location(40.071260, -105.227000, 0, 0) @@ -4937,7 +4980,8 @@ def test_poly_fence_object_avoidance_auto_bendy_ruler_easier(self, target_system if ex is not None: raise ex - def test_poly_fence_object_avoidance(self, target_system=1, target_component=1): + def PolyFenceObjectAvoidance(self, target_system=1, target_component=1): + '''PolyFence object avoidance tests''' if not self.mavproxy_can_do_mision_item_protocols(): return @@ -4948,7 +4992,8 @@ def test_poly_fence_object_avoidance(self, target_system=1, target_component=1): target_system=target_system, target_component=target_component) - def test_poly_fence_object_avoidance_bendy_ruler(self, target_system=1, target_component=1): + def PolyFenceObjectAvoidanceBendyRuler(self, target_system=1, target_component=1): + '''PolyFence object avoidance tests - bendy ruler''' if not self.mavproxy_can_do_mision_item_protocols(): return # bendy Ruler isn't as flexible as Dijkstra for planning, so @@ -5008,9 +5053,11 @@ def my_message_hook(mav, message): messages.append(message) self.install_message_hook(my_message_hook) try: - self.set_parameter("SCR_ENABLE", 1) - self.set_parameter("SCR_HEAP_SIZE", 1024000) - self.set_parameter("SCR_VM_I_COUNT", 1000000) + self.set_parameters({ + "SCR_ENABLE": 1, + "SCR_HEAP_SIZE": 1024000, + "SCR_VM_I_COUNT": 1000000, + }) for script in test_scripts: self.install_test_script(script) @@ -5066,7 +5113,8 @@ def test_scripting_hello_world(self): if ex is not None: raise ex - def test_scripting_steering_and_throttle(self): + def ScriptingSteeringAndThrottle(self): + '''Scripting test - steering and throttle''' self.start_subtest("Scripting square") ex = None example_script = "rover-set-steering-and-throttle.lua" @@ -5177,7 +5225,8 @@ def test_scripting_set_home_to_vehicle_location(self): if ex is not None: raise ex - def test_scripting(self): + def Scripting(self): + '''Scripting test''' self.test_scripting_set_home_to_vehicle_location() self.test_scripting_print_home_and_origin() self.test_scripting_hello_world() @@ -5227,7 +5276,8 @@ def test_mission_frame(self, frame, target_system=1, target_component=1): self.check_mission_upload_download(items) - def test_mission_frames(self, target_system=1, target_component=1): + def MissionFrames(self, target_system=1, target_component=1): + '''Upload/Download of items in different frames''' for frame in (mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT_INT, mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, @@ -5310,13 +5360,16 @@ def send_obstacle_distances_expect_distance_sensor_messages(self, obstacle_dista self.progress("Have now seen all expected messages") break - def ap_proximity_mav(self): + def AP_Proximity_MAV(self): + '''Test MAV proximity backend''' self.context_push() ex = None try: - self.set_parameter("PRX_TYPE", 2) # AP_Proximity_MAV - self.set_parameter("OA_TYPE", 2) # dijkstra - self.set_parameter("OA_DB_OUTPUT", 3) # send all items + self.set_parameters({ + "PRX1_TYPE": 2, # AP_Proximity_MAV + "OA_TYPE": 2, # dijkstra + "OA_DB_OUTPUT": 3, # send all items + }) self.reboot_sitl() # 1 laser pointing straight forward: @@ -5369,7 +5422,8 @@ def ap_proximity_mav(self): if ex is not None: raise ex - def test_send_to_components(self): + def SendToComponents(self): + '''Test ArduPilot send_to_components function''' self.progress("Introducing ourselves to the autopilot as a component") old_srcSystem = self.mav.mav.srcSystem self.mav.mav.srcSystem = 1 @@ -5410,7 +5464,8 @@ def test_send_to_components(self): raise NotAchievedException("Did not get correct command_id") break - def test_skid_steer(self): + def SkidSteer(self): + '''Check skid-steering''' model = "rover-skid" self.customise_SITL_commandline([], @@ -5439,7 +5494,7 @@ def test_skid_steer(self): self.zero_throttle() self.disarm_vehicle() - def test_slew_rate(self): + def SlewRate(self): """Test Motor Slew Rate feature.""" self.context_push() self.change_mode("MANUAL") @@ -5516,6 +5571,7 @@ def test_slew_rate(self): self.context_pop() def SET_ATTITUDE_TARGET(self, target_sysid=None, target_compid=1): + '''Test handling of SET_ATTITUDE_TARGET''' if target_sysid is None: target_sysid = self.sysid_thismav() self.change_mode('GUIDED') @@ -5549,6 +5605,7 @@ def SET_ATTITUDE_TARGET(self, target_sysid=None, target_compid=1): self.disarm_vehicle() def SET_POSITION_TARGET_LOCAL_NED(self, target_sysid=None, target_compid=1): + '''Test handling of SET_POSITION_TARGET_LOCAL_NED''' if target_sysid is None: target_sysid = self.sysid_thismav() self.change_mode('GUIDED') @@ -5596,7 +5653,8 @@ def send_target(): self.do_RTL() self.disarm_vehicle() - def test_end_mission_behavior(self, timeout=60): + def EndMissionBehavior(self, timeout=60): + '''Test end mission behavior''' self.context_push() ex = None try: @@ -5642,16 +5700,23 @@ def test_end_mission_behavior(self, timeout=60): if self.get_sim_time_cached() - tstart > 15: self.progress("Got POSITION_TARGET_GLOBAL_INT, all good !") break - self.change_mode("GUIDED") self.start_subtest("Test End Mission Behavior ACRO") self.set_parameter("MIS_DONE_BEHAVE", 2) - self.change_mode("AUTO") + # race conditions here to do with get_sim_time() + # swallowing heartbeats means we have to be a little + # circuitous when testing here: + self.change_mode("GUIDED") + self.send_cmd_do_set_mode('AUTO') self.wait_mode("ACRO") self.start_subtest("Test End Mission Behavior MANUAL") self.set_parameter("MIS_DONE_BEHAVE", 3) - self.change_mode("AUTO") + # race conditions here to do with get_sim_time() + # swallowing heartbeats means we have to be a little + # circuitous when testing here: + self.change_mode("GUIDED") + self.send_cmd_do_set_mode("AUTO") self.wait_mode("MANUAL") self.disarm_vehicle() except Exception as e: @@ -5662,7 +5727,8 @@ def test_end_mission_behavior(self, timeout=60): if ex is not None: raise ex - def test_mavproxy_param(self): + def MAVProxyParam(self): + '''Test MAVProxy parameter handling''' mavproxy = self.start_mavproxy() mavproxy.send("param fetch\n") mavproxy.expect("Received [0-9]+ parameters") @@ -5721,6 +5787,7 @@ def MAV_CMD_DO_SET_MISSION_CURRENT_mission(self, target_system=1, target_compone ]) def MAV_CMD_DO_SET_MISSION_CURRENT(self, target_sysid=None, target_compid=1): + '''Test handling of CMD_DO_SET_MISSION_CURRENT''' if target_sysid is None: target_sysid = self.sysid_thismav() self.check_mission_upload_download(self.MAV_CMD_DO_SET_MISSION_CURRENT_mission()) @@ -5743,6 +5810,7 @@ def MAV_CMD_DO_SET_MISSION_CURRENT(self, target_sysid=None, target_compid=1): want_result=mavutil.mavlink.MAV_RESULT_FAILED) def FlashStorage(self): + '''Test flash storage (for parameters etc)''' self.set_parameter("LOG_BITMASK", 1) self.reboot_sitl() @@ -5764,6 +5832,7 @@ def FlashStorage(self): self.assert_parameter_value("LOG_BITMASK", 1) def FRAMStorage(self): + '''Test FRAM storage (for parameters etc)''' self.set_parameter("LOG_BITMASK", 1) self.reboot_sitl() @@ -5785,7 +5854,32 @@ def FRAMStorage(self): # make sure we're back at our original value: self.assert_parameter_value("LOG_BITMASK", 1) - def test_depthfinder(self): + def RangeFinder(self): + '''Test RangeFinder''' + # the following magic numbers correspond to the post locations in SITL + home_string = "%s,%s,%s,%s" % (51.8752066, 14.6487840, 54.15, 315) + + rangefinder_params = { + "SIM_SONAR_ROT": 6, + } + rangefinder_params.update(self.analog_rangefinder_parameters()) + + self.set_parameters(rangefinder_params) + self.customise_SITL_commandline([ + "--home", home_string, + ]) + self.wait_ready_to_arm() + if self.mavproxy is not None: + self.mavproxy.send('script /tmp/post-locations.scr\n') + m = self.assert_receive_message('RANGEFINDER', very_verbose=True) + if m.voltage == 0: + raise NotAchievedException("Did not get non-zero voltage") + want_range = 10 + if abs(m.distance - want_range) > 0.1: + raise NotAchievedException("Expected %fm got %fm" % (want_range, m.distance)) + + def DepthFinder(self): + '''Test mulitple depthfinders for boats''' # Setup rangefinders self.customise_SITL_commandline([ "--uartH=sim:nmea", # NMEA Rangefinder @@ -5859,6 +5953,7 @@ def check_rangefinder(mav, m): # self.context_pop() def EStopAtBoot(self): + '''Ensure EStop prevents arming when asserted at boot time''' self.context_push() self.set_parameters({ "RC9_OPTION": 31, @@ -5868,249 +5963,173 @@ def EStopAtBoot(self): self.delay_sim_time(10) self.assert_prearm_failure("Motors Emergency Stopped") self.context_pop() + self.reboot_sitl() - def tests(self): - '''return list of all tests''' - ret = super(AutoTestRover, self).tests() - - ret.extend([ - ("MAVProxy_SetModeUsingSwitch", - "Set modes via mavproxy switch", - self.test_setting_modes_via_mavproxy_switch), - - ("HIGH_LATENCY2", - "Set sending of HIGH_LATENCY2", - self.HIGH_LATENCY2), - - ("MAVProxy_SetModeUsingMode", - "Set modes via mavproxy mode command", - self.test_setting_modes_via_mavproxy_mode_command), - - ("ModeSwitch", - "Set modes via modeswitch", - self.test_setting_modes_via_modeswitch), - - ("AuxModeSwitch", - "Set modes via auxswitches", - self.test_setting_modes_via_auxswitches), - - ("DriveRTL", - "Drive an RTL Mission", self.drive_rtl_mission), - - ("SmartRTL", - "Test SmartRTL", - self.drive_smartrtl), - - ("DriveSquare", - "Learn/Drive Square with Ch7 option", - self.drive_square), - - ("DriveMaxRCIN", - "Drive rover at max RC inputs", - self.drive_max_rcin), - - ("DriveMission", - "Drive Mission %s" % "rover1.txt", - lambda: self.drive_mission("rover1.txt", strict=False)), - - # disabled due to frequent failures in travis. This test needs re-writing - # ("Drive Brake", self.drive_brake), - - ("GetBanner", "Get Banner", self.do_get_banner), - - ("DO_SET_MODE", - "Set mode via MAV_COMMAND_DO_SET_MODE", - self.test_do_set_mode_via_command_long), - - ("MAVProxy_DO_SET_MODE", - "Set mode via MAV_COMMAND_DO_SET_MODE with MAVProxy", - self.test_mavproxy_do_set_mode_via_command_long), - - ("ServoRelayEvents", - "Test ServoRelayEvents", - self.test_servorelayevents), - - ("RCOverrides", "Test RC overrides", self.test_rc_overrides), - - ("RCOverridesCancel", "Test RC overrides Cancel", self.test_rc_override_cancel), - - ("MANUAL_CONTROL", "Test mavlink MANUAL_CONTROL", self.test_manual_control), - - ("Sprayer", "Test Sprayer", self.test_sprayer), - - ("AC_Avoidance", - "Test AC Avoidance switch", - self.drive_fence_ac_avoidance), - - ("CameraMission", - "Test Camera Mission Items", - self.CameraMission), - - # Gripper test - ("Gripper", - "Test gripper", - self.test_gripper), - - ("GripperMission", - "Test Gripper Mission Items", - self.test_gripper_mission), - - ("SET_MESSAGE_INTERVAL", - "Test MAV_CMD_SET_MESSAGE_INTERVAL", - self.test_set_message_interval), - - ("REQUEST_MESSAGE", - "Test MAV_CMD_REQUEST_MESSAGE", - self.test_request_message), - - ("SYSID_ENFORCE", - "Test enforcement of SYSID_MYGCS", - self.test_sysid_enforce), - - ("SET_ATTITUDE_TARGET", - "Test handling of SET_ATTITUDE_TARGET", - self.SET_ATTITUDE_TARGET), - - ("SET_POSITION_TARGET_LOCAL_NED", - "Test handling of SET_POSITION_TARGET_LOCAL_NED", - self.SET_POSITION_TARGET_LOCAL_NED), - - ("MAV_CMD_DO_SET_MISSION_CURRENT", - "Test handling of CMD_DO_SET_MISSION_CURRENT", - self.MAV_CMD_DO_SET_MISSION_CURRENT), - - ("Button", - "Test Buttons", - self.test_button), - - ("Rally", - "Test Rally Points", - self.test_rally_points), - - ("Offboard", - "Test Offboard Control", - self.test_offboard), - - ("MAVProxyParam", - "Test MAVProxy parameter handling", - self.test_mavproxy_param), - - ("GCSFence", - "Upload and download of fence", - self.test_gcs_fence), - - ("Rally", - "Upload and download of rally", - self.test_rally), - - ("GCSMission", - "Upload and download of mission", - self.test_gcs_mission), - - ("GCSRally", - "Upload and download of rally using MAVProxy", - self.test_gcs_rally), - - ("MotorTest", - "Motor Test triggered via mavlink", - self.test_motor_test), - - ("WheelEncoders", - "Ensure SITL wheel encoders work", - self.test_wheelencoders), - - ("DataFlashOverMAVLink", - "Test DataFlash over MAVLink", - self.test_dataflash_over_mavlink), - - ("DataFlashSITL", - "Test DataFlash SITL backend", - self.test_dataflash_sitl), - - ("SkidSteer", - "Check skid-steering", - self.test_skid_steer), - - ("PolyFence", - "PolyFence tests", - self.test_poly_fence), - - ("PolyFenceAvoidance", - "PolyFence avoidance tests", - self.test_poly_fence_avoidance), - - ("PolyFenceObjectAvoidance", - "PolyFence object avoidance tests", - self.test_poly_fence_object_avoidance), - - ("PolyFenceObjectAvoidanceBendyRuler", - "PolyFence object avoidance tests - bendy ruler", - self.test_poly_fence_object_avoidance_bendy_ruler), - - ("SendToComponents", - "Test ArduPilot send_to_components function", - self.test_send_to_components), - - ("PolyFenceObjectAvoidanceBendyRulerEasier", - "PolyFence object avoidance tests - easier bendy ruler test", - self.test_poly_fence_object_avoidance_bendy_ruler_easier), - - ("SlewRate", - "Test output slew rate", - self.test_slew_rate), - - ("Scripting", - "Scripting test", - self.test_scripting), - - ("ScriptingSteeringAndThrottle", - "Scripting test - steering and throttle", - self.test_scripting_steering_and_throttle), - - ("MissionFrames", - "Upload/Download of items in different frames", - self.test_mission_frames), - - ("SetpointGlobalPos", - "Test setpoint global position", - lambda: self.test_set_position_global_int()), + def assert_mode(self, mode): + if not self.mode_is(mode): + raise NotAchievedException("Mode is not %s" % str(mode)) + + def ChangeModeByNumber(self): + '''ensure we can set a mode by number, handy when we don't have a + pymavlink number for it yet''' + for (x, want) in (0, 'MANUAL'), (1, 'ACRO'), (3, 3): + self.change_mode(x) + self.assert_mode(want) + + def StickMixingAuto(self): + '''Ensure Stick Mixing works in auto''' + items = [] + self.set_parameter('STICK_MIXING', 1) + # home + items.append((mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, 0, 0),) + # 1 waypoint a long way away + items.append((mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 2000, 0, 0),) + self.upload_simple_relhome_mission(items) + if self.mavproxy is not None: + # handy for getting pretty pictures + self.mavproxy.send("wp list\n") + self.change_mode('AUTO') + self.wait_ready_to_arm() + self.arm_vehicle() + self.set_rc(1, 1150) + self.wait_heading(45) + self.wait_heading(90) + self.disarm_vehicle() - ("SetpointGlobalVel", - "Test setpoint gloabl velocity", - lambda: self.test_set_velocity_global_int()), + def AutoDock(self): + '''Test automatic docking of rover for multiple FOVs of simulated beacon''' + self.context_push() - ("AccelCal", - "Accelerometer Calibration testing", - self.accelcal), + self.set_parameters({ + "PLND_ENABLED": 1, + "PLND_TYPE": 4, + "PLND_ORIENT": 0, + }) - ("AP_Proximity_MAV", - "Test MAV proximity backend", - self.ap_proximity_mav), + start = self.mav.location() + target = start + (target.lat, target.lng) = mavextra.gps_offset(start.lat, start.lng, 4, -4) + self.progress("Setting target to %f %f" % (start.lat, start.lng)) + stopping_dist = 0.5 - ("EndMissionBehavior", - "Test end mission behavior", - self.test_end_mission_behavior), + self.set_parameters({ + "SIM_PLD_ENABLE": 1, + "SIM_PLD_LAT": target.lat, + "SIM_PLD_LON": target.lng, + "SIM_PLD_HEIGHT": 0, + "SIM_PLD_ALT_LMT": 30, + "SIM_PLD_DIST_LMT": 30, + "SIM_PLD_ORIENT": 4, # emit beams towards south, vehicle's heading must be north to see it + "SIM_PLD_OPTIONS": 1, + "DOCK_SPEED": 2, + "DOCK_STOP_DIST": stopping_dist, + }) - ("FlashStorage", - "Test flash storage (for parameters etc)", - self.FlashStorage), + for type in range(0, 3): # CYLINDRICAL FOV, CONICAL FOV, SPHERICAL FOV + ex = None + try: + self.set_parameter("SIM_PLD_TYPE", type) + self.reboot_sitl() + self.wait_ready_to_arm() + self.arm_vehicle() + self.reach_heading_manual(0) + self.set_rc(3, 1400) + self.wait_distance(25) + self.set_rc_default() + self.change_mode(8) # DOCK mode + self.wait_groundspeed(0, 0.03, timeout=120) + self.disarm_vehicle() + self.assert_receive_message('GLOBAL_POSITION_INT') + new_pos = self.mav.location() + delta = abs(self.get_distance(target, new_pos) - stopping_dist) + self.progress("Docked %f metres from stopping point" % delta) + max_delta = 0.5 + if delta > max_delta: + raise NotAchievedException("Did not dock close enough to stopping point (%fm > %fm" % (delta, max_delta)) - ("FRAMStorage", - "Test FRAM storage (for parameters etc)", - self.FRAMStorage), + if not self.current_onboard_log_contains_message("PL"): + raise NotAchievedException("Did not see expected PL message") - ("LogUpload", - "Upload logs", - self.log_upload), + except Exception as e: + self.print_exception_caught(e) + ex = e + break + self.context_pop() + self.reboot_sitl() + self.progress("All done") - ("DepthFinder", - "Test mulitple depthfinders for boats", - self.test_depthfinder), + if ex is not None: + raise ex - ("EStopAtBoot", - "Ensure EStop prevents arming when asserted at boot time", - self.EStopAtBoot), + def tests(self): + '''return list of all tests''' + ret = super(AutoTestRover, self).tests() + ret.extend([ + self.MAVProxy_SetModeUsingSwitch, + self.HIGH_LATENCY2, + self.MAVProxy_SetModeUsingMode, + self.ModeSwitch, + self.AuxModeSwitch, + self.DriveRTL, + self.SmartRTL, + self.DriveSquare, + self.DriveMaxRCIN, + self.DriveMission, + # self.DriveBrake, # disabled due to frequent failures + self.GetBanner, + self.DO_SET_MODE, + self.MAVProxy_DO_SET_MODE, + self.ServoRelayEvents, + self.RCOverrides, + self.RCOverridesCancel, + self.MANUAL_CONTROL, + self.Sprayer, + self.AC_Avoidance, + self.CameraMission, + self.Gripper, + self.GripperMission, + self.SET_MESSAGE_INTERVAL, + self.REQUEST_MESSAGE, + self.SYSID_ENFORCE, + self.SET_ATTITUDE_TARGET, + self.SET_POSITION_TARGET_LOCAL_NED, + self.MAV_CMD_DO_SET_MISSION_CURRENT, + self.Button, + self.Rally, + self.Offboard, + self.MAVProxyParam, + self.GCSFence, + self.GCSMission, + self.GCSRally, + self.MotorTest, + self.WheelEncoders, + self.DataFlashOverMAVLink, + self.DataFlash, + self.SkidSteer, + self.PolyFence, + self.PolyFenceAvoidance, + self.PolyFenceObjectAvoidance, + self.PolyFenceObjectAvoidanceBendyRuler, + self.SendToComponents, + self.PolyFenceObjectAvoidanceBendyRulerEasier, + self.SlewRate, + self.Scripting, + self.ScriptingSteeringAndThrottle, + self.MissionFrames, + self.SetpointGlobalPos, + self.SetpointGlobalVel, + self.AccelCal, + self.RangeFinder, + self.AP_Proximity_MAV, + self.EndMissionBehavior, + self.FlashStorage, + self.FRAMStorage, + self.DepthFinder, + self.ChangeModeByNumber, + self.EStopAtBoot, + self.StickMixingAuto, + self.AutoDock, ]) return ret diff --git a/Tools/autotest/run_in_terminal_window.sh b/Tools/autotest/run_in_terminal_window.sh index 6044929477b..86bd86a2d16 100755 --- a/Tools/autotest/run_in_terminal_window.sh +++ b/Tools/autotest/run_in_terminal_window.sh @@ -31,7 +31,7 @@ if [ -n "$SITL_RITW_TERMINAL" ]; then elif [ "$TERM" = "screen" ] && [ -n "$TMUX" ]; then tmux new-window -dn "$name" "$*" elif [ -n "$DISPLAY" -a -n "$(which osascript)" ]; then - osascript -e 'tell application "Terminal" to do script "'"$* "'"' + osascript -e 'tell application "Terminal" to do script "'"cd $(pwd) && clear && $* "'"' elif [ -n "$DISPLAY" -a -n "$(which xterm)" ]; then if [ $SITL_RITW_MINIMIZE -eq 1 ]; then ICONIC=-iconic diff --git a/Tools/autotest/sailboat.py b/Tools/autotest/sailboat.py index 94672a1cc5b..a67fe0a5ad8 100644 --- a/Tools/autotest/sailboat.py +++ b/Tools/autotest/sailboat.py @@ -1,5 +1,3 @@ -#!/usr/bin/env python - ''' Drive a Sailboat in SITL @@ -13,6 +11,9 @@ from rover import AutoTestRover +from common import AutoTestTimeoutException +from common import PreconditionFailedException + # get location of scripts testdir = os.path.dirname(os.path.realpath(__file__)) @@ -31,19 +32,60 @@ def init(self): self.frame = 'sailboat' super(AutoTestSailboat, self).init() + def DriveRTL(self, timeout=120): + '''Drive an RTL Mission''' + self.wait_ready_to_arm() + self.arm_vehicle() + + self.load_mission("rtl.txt") + self.change_mode("AUTO") + + tstart = self.get_sim_time() + while True: + now = self.get_sim_time_cached() + if now - tstart > timeout: + raise AutoTestTimeoutException("Didn't see wp 3") + m = self.mav.recv_match(type='MISSION_CURRENT', + blocking=True, + timeout=1) + self.progress("MISSION_CURRENT: %s" % str(m)) + if m.seq == 3: + break + + self.drain_mav() + + m = self.assert_receive_message('NAV_CONTROLLER_OUTPUT', timeout=1) + + wp_dist_min = 5 + if m.wp_dist < wp_dist_min: + raise PreconditionFailedException( + "Did not start at least %f metres from destination (is=%f)" % + (wp_dist_min, m.wp_dist)) + + self.progress("NAV_CONTROLLER_OUTPUT.wp_dist looks good (%u >= %u)" % + (m.wp_dist, wp_dist_min,)) + + # wait for mission to complete + self.wait_statustext("Mission Complete", timeout=70) + + # sailboat loiters around RTL point indefinitely: + self.wait_groundspeed(0.5, 3, timeout=20, minimum_duration=10) + + self.disarm_vehicle() + + self.progress("RTL Mission OK") + + def DriveMission(self): + '''sail a simple mission''' + self.drive_mission("balancebot1.txt", strict=False) + def tests(self): '''return list of all tests''' ret = ([]) ret.extend([ - ("DriveRTL", - "Drive an RTL Mission", - self.drive_rtl_mission), - - ("DriveMission", - "Drive Mission %s" % "balancebot1.txt", - lambda: self.drive_mission("balancebot1.txt", strict=False)), - + self.DriveRTL, + self.DriveMission, ]) return ret diff --git a/Tools/autotest/sim_vehicle.py b/Tools/autotest/sim_vehicle.py index 14cb075f5d6..b0cfc0e63ae 100755 --- a/Tools/autotest/sim_vehicle.py +++ b/Tools/autotest/sim_vehicle.py @@ -319,7 +319,9 @@ def do_build(opts, frame_options): waf_light = os.path.join(root_dir, "modules/waf/waf-light") - cmd_configure = [waf_light, "configure", "--board", "sitl"] + configure_target = frame_options.get('configure_target', 'sitl') + + cmd_configure = [waf_light, "configure", "--board", configure_target] if opts.debug: cmd_configure.append("--debug") @@ -364,6 +366,15 @@ def do_build(opts, frame_options): if opts.sitl_32bit: cmd_configure.append("--sitl-32bit") + if opts.ubsan: + cmd_configure.append("--ubsan") + + if opts.ubsan_abort: + cmd_configure.append("--ubsan-abort") + + for nv in opts.define: + cmd_configure.append("--define=%s" % nv) + pieces = [shlex.split(x) for x in opts.waf_configure_args] for piece in pieces: cmd_configure.extend(piece) @@ -373,6 +384,7 @@ def do_build(opts, frame_options): if opts.clean: run_cmd_blocking("Building clean", [waf_light, "clean"]) + print(frame_options) cmd_build = [waf_light, "build", "--target", frame_options["waf_target"]] if opts.jobs is not None: cmd_build += ['-j', str(opts.jobs)] @@ -614,6 +626,18 @@ def start_antenna_tracker(opts): os.chdir(oldpwd) +def start_CAN_GPS(opts): + """Compile and run the sitl_periph_gps""" + + global can_uarta + progress("Preparing sitl_periph_gps") + options = vinfo.options["sitl_periph_gps"]['frames']['gps'] + do_build(opts, options) + exe = os.path.join(root_dir, 'build/sitl_periph_gps', 'bin/AP_Periph') + run_in_terminal_window("sitl_periph_gps", + ["nice", exe]) + + def start_vehicle(binary, opts, stuff, spawns=None): """Run the ArduPilot binary""" @@ -640,6 +664,7 @@ def start_vehicle(binary, opts, stuff, spawns=None): gdb_commands_file.write("b %s\n" % (breakpoint,)) if opts.disable_breakpoints: gdb_commands_file.write("disable\n") + gdb_commands_file.write("set pagination off\n") if not opts.gdb_stopped: gdb_commands_file.write("r\n") gdb_commands_file.close() @@ -690,6 +715,9 @@ def start_vehicle(binary, opts, stuff, spawns=None): print("The parameter file (%s) does not exist" % (x,)) sys.exit(1) path = ",".join(paths) + if cmd_opts.count > 1: + # we are in a subdirectory when using -n + path = os.path.join("..", path) progress("Using defaults from (%s)" % (path,)) if opts.flash_storage: cmd.append("--set-storage-flash-enabled 1") @@ -902,6 +930,7 @@ def generate_frame_help(): vehicle_choices.append("copter") # should change to ArduCopter at some stage vehicle_choices.append("plane") # should change to ArduPlane at some stage vehicle_choices.append("sub") # should change to Sub at some stage +vehicle_choices.append("blimp") # should change to Blimp at some stage parser.add_option("-v", "--vehicle", type='choice', @@ -959,6 +988,11 @@ def generate_frame_help(): action='store_true', dest="sitl_32bit", help="compile sitl using 32-bit") +group_build.add_option("", "--configure-define", + default=[], + action='append', + dest="define", + help="create a preprocessor define") group_build.add_option("", "--rebuild-on-failure", dest="rebuild_on_failure", action='store_true', @@ -980,6 +1014,16 @@ def generate_frame_help(): action='store_true', default=False, help="use coverage build") +group_build.add_option("", "--ubsan", + default=False, + action='store_true', + dest="ubsan", + help="compile sitl with undefined behaviour sanitiser") +group_build.add_option("", "--ubsan-abort", + default=False, + action='store_true', + dest="ubsan_abort", + help="compile sitl with undefined behaviour sanitiser and abort on error") parser.add_option_group(group_build) group_sim = optparse.OptionGroup(parser, "Simulation options") @@ -1010,6 +1054,10 @@ def generate_frame_help(): group_sim.add_option("", "--enable-onvif", action="store_true", help="enable onvif camera control sim using AntennaTracker") +group_sim.add_option("", "--can-gps", + action='store_true', + default=False, + help="start a DroneCAN GPS instance (use Tools/scripts/CAN/can_sitl_nodev.sh first)") group_sim.add_option("-A", "--sitl-instance-args", type='string', default=None, @@ -1305,6 +1353,7 @@ def generate_frame_help(): "copter": "ArduCopter", # will switch eventually "plane": "ArduPlane", # will switch eventually "sub": "ArduSub", # will switch eventually + "blimp" : "Blimp", # will switch eventually } if cmd_opts.vehicle in vehicle_map: progress("%s is now known as %s" % @@ -1351,6 +1400,9 @@ def generate_frame_help(): if cmd_opts.tracker: start_antenna_tracker(cmd_opts) +if cmd_opts.can_gps: + start_CAN_GPS(cmd_opts) + if cmd_opts.custom_location: location = [(float)(x) for x in cmd_opts.custom_location.split(",")] progress("Starting up at %s" % (location,)) diff --git a/Tools/autotest/test_build_options.py b/Tools/autotest/test_build_options.py index b659e3ef770..25e1c5b9e26 100755 --- a/Tools/autotest/test_build_options.py +++ b/Tools/autotest/test_build_options.py @@ -8,93 +8,250 @@ from __future__ import print_function - +import fnmatch +import optparse import os from pysim import util -# swiped from app.py: -def get_build_options_from_ardupilot_tree(): - '''return a list of build options''' - import importlib.util - spec = importlib.util.spec_from_file_location( - "build_options.py", - os.path.join(os.path.dirname(os.path.realpath(__file__)), - '..', 'scripts', 'build_options.py')) - mod = importlib.util.module_from_spec(spec) - spec.loader.exec_module(mod) - return mod.BUILD_OPTIONS - - -def write_defines_to_file(defines, filepath): - content = "\n".join(["define %s %s" % (a, b) for (a, b) in defines.items()]) - with open(filepath, "w") as f: - f.write(content) - - -def get_defines(feature, options): - '''returns a hash of (name, value) defines to turn feature off - - recursively gets dependencies''' - ret = { - feature.define: 0, - } - if feature.dependency is None: +class TestBuildOptions(object): + def __init__(self, + match_glob=None, + do_step_disable_all=True, + do_step_disable_none=False, + do_step_disable_defaults=True, + do_step_disable_in_turn=True, + build_targets=None, + board="DevEBoxH7v2", + extra_hwdef=None): + self.extra_hwdef = extra_hwdef + self.sizes_nothing_disabled = None + self.match_glob = match_glob + self.do_step_disable_all = do_step_disable_all + self.do_step_disable_none = do_step_disable_none + self.do_step_run_with_defaults = do_step_disable_defaults + self.do_step_disable_in_turn = do_step_disable_in_turn + self.build_targets = build_targets + if self.build_targets is None: + self.build_targets = self.all_targets() + self._board = board + + @staticmethod + def all_targets(): + return ['copter', 'plane', 'rover', 'antennatracker', 'sub', 'blimp'] + + def progress(self, message): + print("###### %s" % message) + + # swiped from app.py: + def get_build_options_from_ardupilot_tree(self): + '''return a list of build options''' + import importlib.util + spec = importlib.util.spec_from_file_location( + "build_options.py", + os.path.join(os.path.dirname(os.path.realpath(__file__)), + '..', 'scripts', 'build_options.py')) + mod = importlib.util.module_from_spec(spec) + spec.loader.exec_module(mod) + return mod.BUILD_OPTIONS + + def write_defines_to_file(self, defines, filepath): + lines = [] + lines.extend(["undef %s\n" % (a, ) for (a, b) in defines.items()]) + lines.extend(["define %s %s\n" % (a, b) for (a, b) in defines.items()]) + content = "".join(lines) + with open(filepath, "w") as f: + f.write(content) + + def get_defines(self, feature, options): + '''returns a hash of (name, value) defines to turn feature off - + recursively gets dependencies''' + ret = { + feature.define: 0, + } + added_one = True + while added_one: + added_one = False + for option in options: + if option.define in ret: + continue + if option.dependency is None: + continue + for dep in option.dependency.split(','): + f = self.get_option_by_label(dep, options) + if f.define not in ret: + continue + + print("%s requires %s" % (option.define, f.define)) + added_one = True + ret[option.define] = 0 + break return ret - for depname in feature.dependency.split(','): - dep = None - for f in options: - if f.label == depname: - dep = f - if dep is None: - raise ValueError("Invalid dep (%s)" % dep) - ret.update(get_defines(dep, options)) - return ret - - -def test_feature(feature, options): - defines = get_defines(feature, options) - test_compile_with_defines(defines) - - -def test_compile_with_defines(defines): - extra_hwdef_filepath = "/tmp/extra.hwdef" - write_defines_to_file(defines, extra_hwdef_filepath) - util.waf_configure( - "CubeOrange", - extra_hwdef=extra_hwdef_filepath, - ) - for t in 'copter', 'plane', 'rover', 'antennatracker', 'sub', 'blimp': - try: - util.waf_build(t) - except Exception: - print("Failed to build (%s) with everything disabled" % - (t,)) - raise + def test_feature(self, feature, options): + defines = self.get_defines(feature, options) + + if len(defines.keys()) > 1: + self.progress("Disabling %s disables (%s)" % ( + feature.define, + ",".join(defines.keys()))) -def run_disable_in_turn(): - options = get_build_options_from_ardupilot_tree() - count = 1 - for feature in options: - print("##### Disabling feature %s(%s) (%u/%u)" % - (feature.label, feature.define, count, len(options))) - test_feature(feature, options) - count += 1 + self.test_compile_with_defines(defines) + def board(self): + '''returns board to build for''' + return self._board -def run_disable_all(): - options = get_build_options_from_ardupilot_tree() - defines = {} - for feature in options: - defines[feature.define] = 0 - test_compile_with_defines(defines) + def test_compile_with_defines(self, defines): + extra_hwdef_filepath = "/tmp/extra.hwdef" + self.write_defines_to_file(defines, extra_hwdef_filepath) + if self.extra_hwdef is not None: + content = open(self.extra_hwdef, "r").read() + with open(extra_hwdef_filepath, "a") as f: + f.write(content) + util.waf_configure( + self.board(), + extra_hwdef=extra_hwdef_filepath, + ) + for t in self.build_targets: + try: + util.run_cmd([util.relwaf(), t]) + except Exception: + print("Failed to build (%s) with things disabled" % + (t,)) + raise + + def find_build_sizes(self): + '''returns a hash with size of all build targets''' + ret = {} + target_to_binpath = { + "copter": "arducopter", + "plane": "arduplane", + "rover": "ardurover", + "antennatracker": "antennatracker", + "sub": "ardusub", + "blimp": "blimp", + } + for target in self.build_targets: + path = os.path.join("build", self.board(), "bin", "%s.bin" % target_to_binpath[target]) + ret[target] = os.path.getsize(path) + return ret + def disable_in_turn_check_sizes(self, feature, sizes_nothing_disabled): + if not self.do_step_disable_none: + self.progress("disable-none skipped, size comparison not available") + return + current_sizes = self.find_build_sizes() + for (build, new_size) in current_sizes.items(): + old_size = sizes_nothing_disabled[build] + self.progress("Disabling %s(%s) on %s saves %u bytes" % + (feature.label, feature.define, build, old_size - new_size)) -def run(): - run_disable_all() - run_disable_in_turn() + def run_disable_in_turn(self): + options = self.get_build_options_from_ardupilot_tree() + if self.match_glob is not None: + options = list(filter(lambda x : fnmatch.fnmatch(x.define, self.match_glob), options)) + count = 1 + for feature in options: + self.progress("Disabling feature %s(%s) (%u/%u)" % + (feature.label, feature.define, count, len(options))) + self.test_feature(feature, options) + count += 1 + self.disable_in_turn_check_sizes(feature, self.sizes_nothing_disabled) + + def get_option_by_label(self, label, options): + for x in options: + if x.label == label: + return x + raise ValueError("No such") + + def run_disable_all(self): + options = self.get_build_options_from_ardupilot_tree() + defines = {} + for feature in options: + if self.match_glob is not None: + if not fnmatch.fnmatch(feature.define, self.match_glob): + continue + defines[feature.define] = 0 + self.test_compile_with_defines(defines) + + def run_disable_none(self): + self.test_compile_with_defines({}) + self.sizes_nothing_disabled = self.find_build_sizes() + + def run_with_defaults(self): + options = self.get_build_options_from_ardupilot_tree() + defines = {} + for feature in options: + defines[feature.define] = feature.default + self.test_compile_with_defines(defines) + + def check_deps_consistency(self): + # self.progress("Checking deps consistency") + options = self.get_build_options_from_ardupilot_tree() + for feature in options: + self.get_defines(feature, options) + + def run(self): + self.check_deps_consistency() + if self.do_step_run_with_defaults: + self.progress("Running run-with-defaults step") + self.run_with_defaults() + if self.do_step_disable_all: + self.progress("Running disable-all step") + self.run_disable_all() + if self.do_step_disable_none: + self.progress("Running disable-none step") + self.run_disable_none() + if self.do_step_disable_in_turn: + self.progress("Running disable-in-turn step") + self.run_disable_in_turn() if __name__ == '__main__': - run() + + parser = optparse.OptionParser() + parser.add_option("--define-match-glob", + type='string', + default=None, + help='feature define must match this glob to be tested') + parser.add_option("--no-run-with-defaults", + action='store_true', + help='Do not run the run-with-defaults step') + parser.add_option("--no-disable-all", + action='store_true', + help='Do not run the disable-all step') + parser.add_option("--no-disable-none", + action='store_true', + help='Do not run the disable-none step') + parser.add_option("--no-disable-in-turn", + action='store_true', + help='Do not run the disable-in-turn step') + parser.add_option("--build-targets", + type='choice', + choices=TestBuildOptions.all_targets(), + action='append', + help='vehicle targets to build') + parser.add_option("--extra-hwdef", + type='string', + default=None, + help="file containing extra hwdef information") + parser.add_option("--board", + type='string', + default="DevEBoxH7v2", + help='board to build for') + + opts, args = parser.parse_args() + + tbo = TestBuildOptions( + match_glob=opts.define_match_glob, + do_step_disable_all=not opts.no_disable_all, + do_step_disable_none=not opts.no_disable_none, + do_step_disable_defaults=not opts.no_run_with_defaults, + do_step_disable_in_turn=not opts.no_disable_in_turn, + build_targets=opts.build_targets, + board=opts.board, + extra_hwdef=opts.extra_hwdef, + ) + tbo.run() diff --git a/Tools/autotest/tilecache/srtm/S28E151.hgt.zip b/Tools/autotest/tilecache/srtm/S28E151.hgt.zip new file mode 100644 index 00000000000..d8775f6d1e0 Binary files /dev/null and b/Tools/autotest/tilecache/srtm/S28E151.hgt.zip differ diff --git a/Tools/autotest/tilecache/srtm/S36E149.hgt.zip b/Tools/autotest/tilecache/srtm/S36E149.hgt.zip new file mode 100644 index 00000000000..7571832de1e Binary files /dev/null and b/Tools/autotest/tilecache/srtm/S36E149.hgt.zip differ diff --git a/Tools/autotest/tilecache/srtm/filelist_python b/Tools/autotest/tilecache/srtm/filelist_python new file mode 100644 index 00000000000..125961aaae4 Binary files /dev/null and b/Tools/autotest/tilecache/srtm/filelist_python differ diff --git a/Tools/autotest/web-firmware/Tools/FilterTool/FileSaver.js b/Tools/autotest/web-firmware/Tools/FilterTool/FileSaver.js new file mode 100644 index 00000000000..5d204aee15a --- /dev/null +++ b/Tools/autotest/web-firmware/Tools/FilterTool/FileSaver.js @@ -0,0 +1,171 @@ +/* +* FileSaver.js +* A saveAs() FileSaver implementation. +* +* By Eli Grey, http://eligrey.com +* +* License : https://github.com/eligrey/FileSaver.js/blob/master/LICENSE.md (MIT) +* source : http://purl.eligrey.com/github/FileSaver.js +*/ + +// The one and only way of getting global scope in all environments +// https://stackoverflow.com/q/3277182/1008999 +var _global = typeof window === 'object' && window.window === window + ? window : typeof self === 'object' && self.self === self + ? self : typeof global === 'object' && global.global === global + ? global + : this + +function bom (blob, opts) { + if (typeof opts === 'undefined') opts = { autoBom: false } + else if (typeof opts !== 'object') { + console.warn('Deprecated: Expected third argument to be a object') + opts = { autoBom: !opts } + } + + // prepend BOM for UTF-8 XML and text/* types (including HTML) + // note: your browser will automatically convert UTF-16 U+FEFF to EF BB BF + if (opts.autoBom && /^\s*(?:text\/\S*|application\/xml|\S*\/\S*\+xml)\s*;.*charset\s*=\s*utf-8/i.test(blob.type)) { + return new Blob([String.fromCharCode(0xFEFF), blob], { type: blob.type }) + } + return blob +} + +function download (url, name, opts) { + var xhr = new XMLHttpRequest() + xhr.open('GET', url) + xhr.responseType = 'blob' + xhr.onload = function () { + saveAs(xhr.response, name, opts) + } + xhr.onerror = function () { + console.error('could not download file') + } + xhr.send() +} + +function corsEnabled (url) { + var xhr = new XMLHttpRequest() + // use sync to avoid popup blocker + xhr.open('HEAD', url, false) + try { + xhr.send() + } catch (e) {} + return xhr.status >= 200 && xhr.status <= 299 +} + +// `a.click()` doesn't work for all browsers (#465) +function click (node) { + try { + node.dispatchEvent(new MouseEvent('click')) + } catch (e) { + var evt = document.createEvent('MouseEvents') + evt.initMouseEvent('click', true, true, window, 0, 0, 0, 80, + 20, false, false, false, false, 0, null) + node.dispatchEvent(evt) + } +} + +// Detect WebView inside a native macOS app by ruling out all browsers +// We just need to check for 'Safari' because all other browsers (besides Firefox) include that too +// https://www.whatismybrowser.com/guides/the-latest-user-agent/macos +var isMacOSWebView = _global.navigator && /Macintosh/.test(navigator.userAgent) && /AppleWebKit/.test(navigator.userAgent) && !/Safari/.test(navigator.userAgent) + +var saveAs = _global.saveAs || ( + // probably in some web worker + (typeof window !== 'object' || window !== _global) + ? function saveAs () { /* noop */ } + + // Use download attribute first if possible (#193 Lumia mobile) unless this is a macOS WebView + : ('download' in HTMLAnchorElement.prototype && !isMacOSWebView) + ? function saveAs (blob, name, opts) { + var URL = _global.URL || _global.webkitURL + var a = document.createElement('a') + name = name || blob.name || 'download' + + a.download = name + a.rel = 'noopener' // tabnabbing + + // TODO: detect chrome extensions & packaged apps + // a.target = '_blank' + + if (typeof blob === 'string') { + // Support regular links + a.href = blob + if (a.origin !== location.origin) { + corsEnabled(a.href) + ? download(blob, name, opts) + : click(a, a.target = '_blank') + } else { + click(a) + } + } else { + // Support blobs + a.href = URL.createObjectURL(blob) + setTimeout(function () { URL.revokeObjectURL(a.href) }, 4E4) // 40s + setTimeout(function () { click(a) }, 0) + } + } + + // Use msSaveOrOpenBlob as a second approach + : 'msSaveOrOpenBlob' in navigator + ? function saveAs (blob, name, opts) { + name = name || blob.name || 'download' + + if (typeof blob === 'string') { + if (corsEnabled(blob)) { + download(blob, name, opts) + } else { + var a = document.createElement('a') + a.href = blob + a.target = '_blank' + setTimeout(function () { click(a) }) + } + } else { + navigator.msSaveOrOpenBlob(bom(blob, opts), name) + } + } + + // Fallback to using FileReader and a popup + : function saveAs (blob, name, opts, popup) { + // Open a popup immediately do go around popup blocker + // Mostly only available on user interaction and the fileReader is async so... + popup = popup || open('', '_blank') + if (popup) { + popup.document.title = + popup.document.body.innerText = 'downloading...' + } + + if (typeof blob === 'string') return download(blob, name, opts) + + var force = blob.type === 'application/octet-stream' + var isSafari = /constructor/i.test(_global.HTMLElement) || _global.safari + var isChromeIOS = /CriOS\/[\d]+/.test(navigator.userAgent) + + if ((isChromeIOS || (force && isSafari) || isMacOSWebView) && typeof FileReader !== 'undefined') { + // Safari doesn't allow downloading of blob URLs + var reader = new FileReader() + reader.onloadend = function () { + var url = reader.result + url = isChromeIOS ? url : url.replace(/^data:[^;]*;/, 'data:attachment/file;') + if (popup) popup.location.href = url + else location = url + popup = null // reverse-tabnabbing #460 + } + reader.readAsDataURL(blob) + } else { + var URL = _global.URL || _global.webkitURL + var url = URL.createObjectURL(blob) + if (popup) popup.location = url + else location.href = url + popup = null // reverse-tabnabbing #460 + setTimeout(function () { URL.revokeObjectURL(url) }, 4E4) // 40s + } + } +) + +_global.saveAs = saveAs.saveAs = saveAs + +if (typeof module !== 'undefined') { + module.exports = saveAs; +} diff --git a/Tools/autotest/web-firmware/Tools/FilterTool/app.py b/Tools/autotest/web-firmware/Tools/FilterTool/app.py new file mode 100644 index 00000000000..76ded1b765f --- /dev/null +++ b/Tools/autotest/web-firmware/Tools/FilterTool/app.py @@ -0,0 +1,16 @@ +import os +from flask import Flask +from flask import render_template + +# A flask app to allow hosting filter tool locally + +this_path = os.path.dirname(os.path.realpath(__file__)) + +app = Flask(__name__, template_folder=this_path, static_folder=this_path) + +@app.route('/') +def index(): + return render_template('index.html') + +if __name__ == "__main__": + app.run() diff --git a/Tools/autotest/web-firmware/Tools/FilterTool/filters.js b/Tools/autotest/web-firmware/Tools/FilterTool/filters.js new file mode 100644 index 00000000000..b68bc3b6737 --- /dev/null +++ b/Tools/autotest/web-firmware/Tools/FilterTool/filters.js @@ -0,0 +1,1196 @@ +function calc_lowpass_alpha_dt(dt, cutoff_freq) +{ + if (dt <= 0.0 || cutoff_freq <= 0.0) { + return 1.0; + } + var rc = 1.0/(Math.PI*2*cutoff_freq); + return dt/(dt+rc); +} + +function PID(sample_rate,kP,kI,kD,filtE,filtD) { + + this._kP = kP; + this._kI = kI; + this._kD = kD; + + this._dt = 1.0/sample_rate; + this.E_alpha = calc_lowpass_alpha_dt(this._dt,filtE) + this.D_alpha = calc_lowpass_alpha_dt(this._dt,filtD) + + this._error = 0.0; + this._derivative = 0.0; + this._integrator = 0.0; + + this.reset = function(sample) { + this._error = 0.0; + this._derivative = 0.0; + this._integrator = 0.0; + } + + this.apply = function(error) { + + var error_last = this._error; + this._error += this.E_alpha * (error - this._error); + + var derivative = (this._error - error_last) / this._dt; + this._derivative += this.D_alpha * (derivative - this._derivative) + + this._integrator += this._error * this._kI * this._dt; + + var P_out = this._error * this._kP; + var D_out = this._derivative * this._kD; + + return P_out + this._integrator + D_out; + } + return this; +} + +function LPF_1P(sample_rate,cutoff) { + this.reset = function(sample) { + this.value = sample; + } + if (cutoff <= 0) { + this.apply = function(sample) { + return sample; + } + return this; + } + this.alpha = calc_lowpass_alpha_dt(1.0/sample_rate,cutoff) + this.value = 0.0; + this.apply = function(sample) { + this.value += this.alpha * (sample - this.value); + return this.value; + } + return this; +} + +function DigitalBiquadFilter(sample_freq, cutoff_freq) { + this.delay_element_1 = 0; + this.delay_element_2 = 0; + this.cutoff_freq = cutoff_freq; + + if (cutoff_freq <= 0) { + // zero cutoff means pass-thru + this.reset = function(sample) { + } + this.apply = function(sample) { + return sample; + } + return this; + } + + var fr = sample_freq/cutoff_freq; + var ohm = Math.tan(Math.PI/fr); + var c = 1.0+2.0*Math.cos(Math.PI/4.0)*ohm + ohm*ohm; + + this.b0 = ohm*ohm/c; + this.b1 = 2.0*this.b0; + this.b2 = this.b0; + this.a1 = 2.0*(ohm*ohm-1.0)/c; + this.a2 = (1.0-2.0*Math.cos(Math.PI/4.0)*ohm+ohm*ohm)/c; + this.initialised = false; + + this.apply = function(sample) { + if (!this.initialised) { + this.reset(sample); + this.initialised = true; + } + var delay_element_0 = sample - this.delay_element_1 * this.a1 - this.delay_element_2 * this.a2; + var output = delay_element_0 * this.b0 + this.delay_element_1 * this.b1 + this.delay_element_2 * this.b2; + + this.delay_element_2 = this.delay_element_1; + this.delay_element_1 = delay_element_0; + return output; + } + + this.reset = function(sample) { + this.delay_element_1 = this.delay_element_2 = sample * (1.0 / (1 + this.a1 + this.a2)); + } + + return this; +} + +function sq(v) { + return v*v; +} + +function constrain_float(v,vmin,vmax) { + if (v < vmin) { + return vmin; + } + if (v > vmax) { + return vmax; + } + return v; +} + +function NotchFilter(sample_freq,center_freq_hz,bandwidth_hz,attenuation_dB) { + this.sample_freq = sample_freq; + this.center_freq_hz = center_freq_hz; + this.bandwidth_hz = bandwidth_hz; + this.attenuation_dB = attenuation_dB; + this.need_reset = true; + this.initialised = false; + + this.calculate_A_and_Q = function() { + this.A = Math.pow(10.0, -this.attenuation_dB / 40.0); + if (this.center_freq_hz > 0.5 * this.bandwidth_hz) { + var octaves = Math.log2(this.center_freq_hz / (this.center_freq_hz - this.bandwidth_hz / 2.0)) * 2.0; + this.Q = Math.sqrt(Math.pow(2.0, octaves)) / (Math.pow(2.0, octaves) - 1.0); + } else { + this.Q = 0.0; + } + } + + this.init_with_A_and_Q = function() { + if ((this.center_freq_hz > 0.0) && (this.center_freq_hz < 0.5 * this.sample_freq) && (this.Q > 0.0)) { + var omega = 2.0 * Math.PI * this.center_freq_hz / this.sample_freq; + var alpha = Math.sin(omega) / (2 * this.Q); + this.b0 = 1.0 + alpha*sq(this.A); + this.b1 = -2.0 * Math.cos(omega); + this.b2 = 1.0 - alpha*sq(this.A); + this.a0_inv = 1.0/(1.0 + alpha); + this.a1 = this.b1; + this.a2 = 1.0 - alpha; + this.initialised = true; + } else { + this.initialised = false; + } + } + + // check center frequency is in the allowable range + if ((center_freq_hz > 0.5 * bandwidth_hz) && (center_freq_hz < 0.5 * sample_freq)) { + this.calculate_A_and_Q(); + this.init_with_A_and_Q(); + } else { + this.initialised = false; + } + + this.apply = function(sample) { + if (!this.initialised || this.need_reset) { + // if we have not been initialised when return the input + // sample as output and update delayed samples + this.signal1 = sample; + this.signal2 = sample; + this.ntchsig = sample; + this.ntchsig1 = sample; + this.ntchsig2 = sample; + this.need_reset = false; + return sample; + } + this.ntchsig2 = this.ntchsig1; + this.ntchsig1 = this.ntchsig; + this.ntchsig = sample; + var output = (this.ntchsig*this.b0 + this.ntchsig1*this.b1 + this.ntchsig2*this.b2 - this.signal1*this.a1 - this.signal2*this.a2) * this.a0_inv; + this.signal2 = this.signal1; + this.signal1 = output; + return output; + } + + this.reset = function(sample) { + this.need_reset = true; + this.apply(sample); + } + + return this; +} + +function HarmonicNotchFilter(sample_freq,enable,mode,freq,bw,att,ref,fm_rat,hmncs,opts) { + this.notches = [] + var chained = 1; + var dbl = false; + var triple = false; + var composite_notches = 1; + if (opts & 1) { + dbl = true; + composite_notches = 2; + } else if (opts & 16) { + triple = true; + composite_notches = 3; + } + + this.reset = function(sample) { + for (n in this.notches) { + this.notches[n].reset(sample); + } + } + + if (enable <= 0) { + this.apply = function(sample) { + return sample; + } + return this; + } + + if (mode == 0) { + // fixed notch + } + if (mode == 1) { + var motors_throttle = Math.max(0,get_form("Throttle")); + var throttle_freq = freq * Math.max(fm_rat,Math.sqrt(motors_throttle / ref)); + freq = throttle_freq; + } + if (mode == 2) { + var rpm = get_form("RPM1"); + freq = Math.max(rpm/60.0,freq) * ref; + } + if (mode == 5) { + var rpm = get_form("RPM2"); + freq = Math.max(rpm/60.0,freq) * ref; + } + if (mode == 3) { + if (opts & 2) { + chained = get_form("NUM_MOTORS"); + } + var rpm = get_form("ESC_RPM"); + freq = Math.max(rpm/60.0,freq) * ref; + } + for (var n=0;n<8;n++) { + var fmul = n+1; + if (hmncs & (1< 1) { + var notch_center_double; + // only enable the filter if its center frequency is below the nyquist frequency + notch_center_double = notch_center * (1.0 - notch_spread); + if (notch_center_double < nyquist_limit) { + this.notches.push(new NotchFilter(sample_freq,notch_center_double,bandwidth_hz/composite_notches,att)); + } + // only enable the filter if its center frequency is below the nyquist frequency + notch_center_double = notch_center * (1.0 + notch_spread); + if (notch_center_double < nyquist_limit) { + this.notches.push(new NotchFilter(sample_freq,notch_center_double,bandwidth_hz/composite_notches,att)); + } + } + } + } + } + this.apply = function(sample) { + for (n in this.notches) { + sample = this.notches[n].apply(sample); + } + return sample; + } +} + +function get_form(vname) { + var v = parseFloat(document.getElementById(vname).value); + setCookie(vname, v); + return v; +} + +function run_filters(filters,freq,sample_rate,samples,fast_filters = null,fast_sample_rate = null) { + + for (var j=0;j= best_fit_offset) { + var index = i - best_fit_offset; + X.data[index][0] = Math.sin(t * kt); + X.data[index][1] = Math.cos(t * kt); + y.data[index][0] = output; + } + } + + // Z = a*sin(t*kt + p) + O + var ABO = ML.MatrixLib.solve(X, y); + + var amplitude = Math.sqrt(ABO.get(0,0)*ABO.get(0,0) + ABO.get(1,0)*ABO.get(1,0)); + var phase = Math.atan2(ABO.get(1,0),ABO.get(0,0)) * (-180.0 / Math.PI); + // var DC_offset = ABO.get(2,0); + + return [amplitude,phase]; +} + +var chart_attenuation; +var chart_phase; +var freq_log_scale; + +function get_filters(sample_rate) { + var filters = [] + filters.push(new HarmonicNotchFilter(sample_rate, + get_form("INS_HNTCH_ENABLE"), + get_form("INS_HNTCH_MODE"), + get_form("INS_HNTCH_FREQ"), + get_form("INS_HNTCH_BW"), + get_form("INS_HNTCH_ATT"), + get_form("INS_HNTCH_REF"), + get_form("INS_HNTCH_FM_RAT"), + get_form("INS_HNTCH_HMNCS"), + get_form("INS_HNTCH_OPTS"))); + filters.push(new HarmonicNotchFilter(sample_rate, + get_form("INS_HNTC2_ENABLE"), + get_form("INS_HNTC2_MODE"), + get_form("INS_HNTC2_FREQ"), + get_form("INS_HNTC2_BW"), + get_form("INS_HNTC2_ATT"), + get_form("INS_HNTC2_REF"), + get_form("INS_HNTC2_FM_RAT"), + get_form("INS_HNTC2_HMNCS"), + get_form("INS_HNTC2_OPTS"))); + filters.push(new DigitalBiquadFilter(sample_rate,get_form("INS_GYRO_FILTER"))); + + return filters; +} + +function calculate_filter() { + var sample_rate = get_form("GyroSampleRate"); + var freq_max = get_form("MaxFreq"); + var samples = 1000; + var freq_step = 0.1; + var filters = get_filters(sample_rate); + + var use_dB = document.getElementById("ScaleLog").checked; + setCookie("Scale", use_dB ? "Log" : "Linear"); + var use_RPM = document.getElementById("freq_Scale_RPM").checked; + setCookie("feq_unit", use_RPM ? "RPM" : "Hz"); + var unwrap_pahse = document.getElementById("ScaleUnWrap").checked; + setCookie("PhaseScale", unwrap_pahse ? "unwrap" : "wrap"); + var attenuation = [] + var phase_lag = [] + var min_phase_lag = 0.0; + var max_phase_lag = 0.0; + var phase_wrap = 0.0; + var min_atten = 0.0; + var max_atten = 1.0; + var last_phase = 0.0; + var atten_string = "Magnitude"; + if (use_dB) { + max_atten = 0; + min_atten = -10; + atten_string = "Magnitude (dB)"; + } + var freq_string = "Frequency (Hz)"; + if (use_RPM) { + freq_string = "Frequency (RPM)"; + } + + // start at zero + attenuation.push({x:0, y:1}); + phase_lag.push({x:0, y:0}); + + for (freq=freq_step; freq<=freq_max; freq+=freq_step) { + var v = run_filters(filters, freq, sample_rate, samples); + var aten = v[0]; + var phase = v[1] + phase_wrap; + if (use_dB) { + // show power in decibels + aten = 20 * Math.log10(aten); + } + var freq_value = freq; + if (use_RPM) { + freq_value *= 60; + } + if (unwrap_pahse) { + var phase_diff = phase - last_phase; + if (phase_diff > 180) { + phase_wrap -= 360.0; + phase -= 360.0; + } else if (phase_diff < -180) { + phase_wrap += 360.0; + phase += 360.0; + } + } + attenuation.push({x:freq_value, y:aten}); + phase_lag.push({x:freq_value, y:-phase}); + + min_atten = Math.min(min_atten, aten); + max_atten = Math.max(max_atten, aten); + min_phase_lag = Math.min(min_phase_lag, phase) + max_phase_lag = Math.max(max_phase_lag, phase) + last_phase = phase; + } + + if (unwrap_pahse) { + min_phase_lag = Math.floor((min_phase_lag-10)/10)*10; + min_phase_lag = Math.min(Math.max(-get_form("MaxPhaseLag"), min_phase_lag), 0); + max_phase_lag = Math.ceil((max_phase_lag+10)/10)*10; + max_phase_lag = Math.min(get_form("MaxPhaseLag"), max_phase_lag); + } else { + min_phase_lag = -180; + max_phase_lag = 180; + } + + if (use_RPM) { + freq_max *= 60.0; + } + + var freq_log = document.getElementById("freq_ScaleLog").checked; + setCookie("feq_scale", freq_log ? "Log" : "Linear"); + if ((freq_log_scale != null) && (freq_log_scale != freq_log)) { + // Scale changed, no easy way to update, delete chart and re-draw + chart_attenuation.clear(); + chart_attenuation.destroy(); + chart_attenuation = null; + chart_phase.clear(); + chart_phase.destroy(); + chart_phase = null; + } + freq_log_scale = freq_log; + + if (chart_attenuation) { + chart_attenuation.data.datasets[0].data = attenuation; + chart_attenuation.options.scales.xAxes[0].ticks.max = freq_max; + chart_attenuation.options.scales.xAxes[0].scaleLabel.labelString = freq_string + chart_attenuation.options.scales.yAxes[0].ticks.min = min_atten + chart_attenuation.options.scales.yAxes[0].ticks.max = max_atten; + chart_attenuation.options.scales.yAxes[0].scaleLabel.labelString = atten_string; + chart_attenuation.update(); + } else { + chart_attenuation = new Chart("Attenuation", { + type : "scatter", + data: { + datasets: [ + { + label: 'Magnitude', + yAxisID: 'Magnitude', + pointRadius: 0, + hitRadius: 8, + borderColor: "rgba(0,0,255,1.0)", + pointBackgroundColor: "rgba(0,0,255,1.0)", + data: attenuation, + showLine: true, + fill: false + }, + ] + }, + options: { + aspectRatio: 3, + legend: {display: false}, + scales: { + yAxes: [ + { + scaleLabel: { display: true, labelString: atten_string }, + id: 'Magnitude', + ticks: {min:min_atten, max:max_atten} + }, + ], + xAxes: [ + { + type: (freq_log ? "logarithmic" : "linear"), + scaleLabel: { display: true, labelString: freq_string }, + ticks: + { + min:0.0, + max:freq_max, + callback: function(value, index, ticks) { + return value; + }, + } + } + ], + }, + tooltips: { + callbacks: { + label: function(tooltipItem, data) { + // round tooltip to two decimal places + return tooltipItem.xLabel.toFixed(2) + ', ' + tooltipItem.yLabel.toFixed(2); + } + } + } + } + }); + } + + + if (chart_phase) { + chart_phase.data.datasets[0].data = phase_lag; + chart_phase.options.scales.xAxes[0].ticks.max = freq_max; + chart_phase.options.scales.xAxes[0].scaleLabel.labelString = freq_string + chart_phase.options.scales.yAxes[0].ticks.min = -max_phase_lag; + chart_phase.options.scales.yAxes[0].ticks.max = -min_phase_lag; + chart_phase.update(); + } else { + chart_phase = new Chart("Phase", { + type : "scatter", + data: { + datasets: [ + { + label: 'Phase', + yAxisID: 'Phase', + pointRadius: 0, + hitRadius: 8, + borderColor: "rgba(255,0,0,1.0)", + pointBackgroundColor: "rgba(255,0,0,1.0)", + data: phase_lag, + showLine: true, + fill: false + } + ] + }, + options: { + aspectRatio: 3, + legend: {display: false}, + scales: { + yAxes: [ + { + scaleLabel: { display: true, labelString: "Phase (deg)" }, + id: 'Phase', + ticks: {min:-max_phase_lag, max:-min_phase_lag} + } + ], + xAxes: [ + { + type: (freq_log ? "logarithmic" : "linear"), + scaleLabel: { display: true, labelString: freq_string }, + ticks: + { + min:0.0, + max:freq_max, + callback: function(value, index, ticks) { + return value; + }, + } + } + ], + }, + tooltips: { + callbacks: { + label: function(tooltipItem, data) { + // round tooltip to two decimal places + return tooltipItem.xLabel.toFixed(2) + ', ' + tooltipItem.yLabel.toFixed(2); + } + } + } + } + }); + } +} + +var PID_attenuation; +var PID_phase; +var PID_freq_log_scale; + +function calculate_pid(axis_id) { + //var sample_rate = get_form("GyroSampleRate"); + var PID_rate = get_form("SCHED_LOOP_RATE") + var filters = [] + var freq_max = get_form("PID_MaxFreq"); + var samples = 1000; + var freq_step = 0.1; + + // default to roll axis + var axis_prefix = "ATC_RAT_RLL_"; + if (axis_id == "CalculatePitch") { + var axis_prefix = "ATC_RAT_PIT_"; + document.getElementById("PID_title").innerHTML = "Pitch axis"; + } else if (axis_id == "CalculateYaw") { + var axis_prefix = "ATC_RAT_YAW_"; + document.getElementById("PID_title").innerHTML = "Yaw axis"; + } else { + document.getElementById("PID_title").innerHTML = "Roll axis"; + } + + filters.push(new PID(PID_rate, + get_form(axis_prefix + "P"), + get_form(axis_prefix + "I"), + get_form(axis_prefix + "D"), + get_form(axis_prefix + "FLTE"), + get_form(axis_prefix + "FLTD"))); + + var use_dB = document.getElementById("PID_ScaleLog").checked; + setCookie("PID_Scale", use_dB ? "Log" : "Linear"); + var use_RPM = document.getElementById("PID_freq_Scale_RPM").checked; + setCookie("PID_feq_unit", use_RPM ? "RPM" : "Hz"); + var unwrap_pahse = document.getElementById("PID_ScaleUnWrap").checked; + setCookie("PID_PhaseScale", unwrap_pahse ? "unwrap" : "wrap"); + var attenuation = [] + var phase_lag = [] + var min_phase_lag = 0.0; + var max_phase_lag = 0.0; + var phase_wrap = 0.0; + var min_atten = Infinity; + var max_atten = -Infinity; + var last_phase = 0.0; + var atten_string = "Gain"; + if (use_dB) { + max_atten = 0; + min_atten = -10; + atten_string = "Gain (dB)"; + } + var freq_string = "Frequency (Hz)"; + if (use_RPM) { + freq_string = "Frequency (RPM)"; + } + + var fast_filters = null; + var fast_sample_rate = null; + if (document.getElementById("PID_filtering_Post").checked) { + fast_sample_rate = get_form("GyroSampleRate"); + fast_filters = get_filters(fast_sample_rate); + } + setCookie("filtering", fast_filters == null ? "Pre" : "Post"); + + + for (freq=freq_step; freq<=freq_max; freq+=freq_step) { + var v = run_filters(filters, freq, PID_rate, samples, fast_filters, fast_sample_rate); + var aten = v[0]; + var phase = v[1] + phase_wrap; + if (use_dB) { + // show power in decibels + aten = 20 * Math.log10(aten); + } + var freq_value = freq; + if (use_RPM) { + freq_value *= 60; + } + if (unwrap_pahse) { + var phase_diff = phase - last_phase; + if (phase_diff > 180) { + phase_wrap -= 360.0; + phase -= 360.0; + } else if (phase_diff < -180) { + phase_wrap += 360.0; + phase += 360.0; + } + } + attenuation.push({x:freq_value, y:aten}); + phase_lag.push({x:freq_value, y:-phase}); + + min_atten = Math.min(min_atten, aten); + max_atten = Math.max(max_atten, aten); + min_phase_lag = Math.min(min_phase_lag, phase) + max_phase_lag = Math.max(max_phase_lag, phase) + last_phase = phase; + } + + if (use_RPM) { + freq_max *= 60.0; + } + + var mean_atten = (min_atten + max_atten) * 0.5; + var atten_range = Math.max((max_atten - min_atten) * 0.5 * 1.1, 1.0); + min_atten = mean_atten - atten_range; + max_atten = mean_atten + atten_range; + + if (unwrap_pahse) { + min_phase_lag = Math.floor((min_phase_lag-10)/10)*10; + min_phase_lag = Math.min(Math.max(-get_form("PID_MaxPhaseLag"), min_phase_lag), 0); + max_phase_lag = Math.ceil((max_phase_lag+10)/10)*10; + max_phase_lag = Math.min(get_form("PID_MaxPhaseLag"), max_phase_lag); + } else { + min_phase_lag = -180; + max_phase_lag = 180; + } + + var freq_log = document.getElementById("PID_freq_ScaleLog").checked; + setCookie("PID_feq_scale", use_dB ? "Log" : "Linear"); + if ((PID_freq_log_scale != null) && (PID_freq_log_scale != freq_log)) { + // Scale changed, no easy way to update, delete chart and re-draw + PID_attenuation.clear(); + PID_attenuation.destroy(); + PID_attenuation = null; + PID_phase.clear(); + PID_phase.destroy(); + PID_phase = null; + } + PID_freq_log_scale = freq_log; + + if (PID_attenuation) { + PID_attenuation.data.datasets[0].data = attenuation; + PID_attenuation.options.scales.xAxes[0].ticks.max = freq_max; + PID_attenuation.options.scales.xAxes[0].scaleLabel.labelString = freq_string + PID_attenuation.options.scales.yAxes[0].ticks.min = min_atten + PID_attenuation.options.scales.yAxes[0].ticks.max = max_atten; + PID_attenuation.options.scales.yAxes[0].scaleLabel.labelString = atten_string; + PID_attenuation.update(); + } else { + PID_attenuation = new Chart("PID_Attenuation", { + type : "scatter", + data: { + datasets: [ + { + label: 'Gain', + yAxisID: 'Gain', + pointRadius: 0, + hitRadius: 8, + borderColor: "rgba(0,0,255,1.0)", + pointBackgroundColor: "rgba(0,0,255,1.0)", + data: attenuation, + showLine: true, + fill: false + }, + ] + }, + options: { + aspectRatio: 3, + legend: {display: false}, + scales: { + yAxes: [ + { + scaleLabel: { display: true, labelString: atten_string }, + id: 'Gain', + position: 'left', + ticks: {min:min_atten, max:max_atten} + }, + ], + xAxes: [ + { + type: (freq_log ? "logarithmic" : "linear"), + scaleLabel: { display: true, labelString: freq_string }, + ticks: + { + min:0.0, + max:freq_max, + callback: function(value, index, ticks) { + return value; + }, + } + } + ], + }, + tooltips: { + callbacks: { + label: function(tooltipItem, data) { + // round tooltip to two decimal places + return tooltipItem.xLabel.toFixed(2) + ', ' + tooltipItem.yLabel.toFixed(2); + } + } + } + } + }); + } + + + if (PID_phase) { + PID_phase.data.datasets[0].data = phase_lag; + PID_phase.options.scales.xAxes[0].ticks.max = freq_max; + PID_phase.options.scales.xAxes[0].scaleLabel.labelString = freq_string + PID_phase.options.scales.yAxes[0].ticks.min = -max_phase_lag; + PID_phase.options.scales.yAxes[0].ticks.max = -min_phase_lag; + PID_phase.update(); + } else { + PID_phase = new Chart("PID_Phase", { + type : "scatter", + data: { + datasets: [ + { + label: 'PhaseLag', + yAxisID: 'PhaseLag', + pointRadius: 0, + hitRadius: 8, + borderColor: "rgba(255,0,0,1.0)", + pointBackgroundColor: "rgba(255,0,0,1.0)", + data: phase_lag, + showLine: true, + fill: false + } + ] + }, + options: { + aspectRatio: 3, + legend: {display: false}, + scales: { + yAxes: [ + { + scaleLabel: { display: true, labelString: "Phase (deg)" }, + id: 'PhaseLag', + ticks: {min:-max_phase_lag, max:-min_phase_lag} + } + ], + xAxes: [ + { + type: (freq_log ? "logarithmic" : "linear"), + scaleLabel: { display: true, labelString: freq_string }, + ticks: + { + min:0.0, + max:freq_max, + callback: function(value, index, ticks) { + return value; + }, + } + } + ], + }, + tooltips: { + callbacks: { + label: function(tooltipItem, data) { + // round tooltip to two decimal places + return tooltipItem.xLabel.toFixed(2) + ', ' + tooltipItem.yLabel.toFixed(2); + } + } + } + } + }); + } +} + +function load() { + var url_string = (window.location.href).toLowerCase(); + if (url_string.indexOf('?') == -1) { + // no query params, load from cookies + load_cookies(); + return; + } + + // populate from query's + var params = new URL(url_string).searchParams; + var sections = ["params", "PID_params"]; + for (var j = 0; j -1 ? cookie.substr(0, eqPos) : cookie; + document.cookie = name + "=;expires=Thu, 01 Jan 1970 00:00:00 GMT"; + } +} + +function save_parameters() { + var params = ""; + var inputs = document.forms["params"].getElementsByTagName("input"); + for (const v in inputs) { + var name = "" + inputs[v].name; + if (name.startsWith("INS_")) { + var value = inputs[v].value; + params += name + "," + value + "\n"; + } + } + var blob = new Blob([params], { type: "text/plain;charset=utf-8" }); + saveAs(blob, "filter.param"); +} + +async function load_parameters(file) { + var text = await file.text(); + var lines = text.split('\n'); + for (i in lines) { + var line = lines[i]; + line = line.replace("Q_A_RAT_","ATC_RAT_"); + v = line.split(/[\s,=\t]+/); + if (v.length >= 2) { + var vname = v[0]; + var value = v[1]; + var fvar = document.getElementById(vname); + if (fvar) { + fvar.value = value; + console.log("set " + vname + "=" + value); + } + } + } + fill_docs(); + update_all_hidden(); + calculate_filter(); +} + +function fill_docs() +{ + var inputs = document.forms["params"].getElementsByTagName("input"); + for (const v in inputs) { + var name = inputs[v].name; + var doc = document.getElementById(name + ".doc"); + if (!doc) { + continue; + } + if (inputs[v].onchange == null) { + inputs[v].onchange = fill_docs; + } + var value = parseFloat(inputs[v].value); + if (name.endsWith("_ENABLE")) { + if (value >= 1) { + doc.innerHTML = "Enabled"; + } else { + doc.innerHTML = "Disabled"; + } + } else if (name.endsWith("_MODE")) { + switch (Math.floor(value)) { + case 0: + doc.innerHTML = "Fixed notch"; + break; + case 1: + doc.innerHTML = "Throttle"; + break; + case 2: + doc.innerHTML = "RPM Sensor 1"; + break; + case 3: + doc.innerHTML = "ESC Telemetry"; + break; + case 4: + doc.innerHTML = "Dynamic FFT"; + break; + case 5: + doc.innerHTML = "RPM Sensor 2"; + break; + default: + doc.innerHTML = "INVALID"; + break; + } + } else if (name.endsWith("_OPTS")) { + var ival = Math.floor(value); + var bits = []; + if (ival & 1) { + bits.push("Double Notch"); + } + if (ival & 2) { + bits.push("Dynamic Harmonic"); + } + if (ival & 4) { + bits.push("Loop Rate"); + } + if (ival & 8) { + bits.push("All IMUs Rate"); + } + if ((ival & 16) && (ival & 1) == 0) { + bits.push("Triple Notch"); + } + doc.innerHTML = bits.join(", "); + } else if (name.endsWith("_HMNCS")) { + var ival = Math.floor(value); + var bits = []; + if (ival & 1) { + bits.push("Fundamental"); + } + if (ival & 2) { + bits.push("1st Harmonic"); + } + if (ival & 4) { + bits.push("2nd Harmonic"); + } + if (ival & 8) { + bits.push("3rd Harmonic"); + } + if (ival & 16) { + bits.push("4th Harmonic"); + } + if (ival & 32) { + bits.push("5th Harmonic"); + } + if (ival & 64) { + bits.push("6th Harmonic"); + } + doc.innerHTML = bits.join(", "); + } + + } +} + +// update all hidden params, to be called at init +function update_all_hidden() +{ + var enable_params = ["INS_HNTCH_ENABLE", "INS_HNTC2_ENABLE"]; + for (var i=-0;i +

ArduPilot Filter Analysis

+ +The following form will display the attenuation and phase lag for an +ArduPilot 4.2 filter setup. + + + +

+ + + + + + +

+
+ Graph Settings + + + + + + +
+
+ Magnitude scale + +
+ +
+
+
+
+ Phase scale + +
+ +
+
+
+
+ Frequency scale + + + + + +
+ +
+ +
+
+ +
+ +
+
+
+
+

+ + + +

+

+ + +

+
+
+ INS Settings +

+ + +

+

+ + +

+
+
+ First Notch Filter +

+ + + +

+

+ + + +

+

+ + +

+

+ + +

+

+ + +

+

+ + +

+

+ + +

+

+ + + +

+

+ + + +

+
+
+ Second Notch Filter +

+ + + +

+

+ + + +

+

+ + +

+

+ + +

+

+ + +

+

+ + +

+

+ + +

+

+ + + +

+

+ + + +

+
+
+ Throttle Based +

+ + +

+
+
+ ESC Telemetry +

+ + +

+

+ + +

+
+
+ RPM/EFI Based +

+ + +

+

+ + +

+
+
+ +

PIDs

+

+ + +

+ + + +

+
+
+ Graph Settings +

+ + + + + + + +
+
+ Gain scale + +
+ +
+
+
+
+ Phase scale + +
+ +
+
+
+
+ Frequency scale + + + + + +
+ +
+ +
+
+ +
+ +
+
+
+
+
+ Filtering + +
+ +
+
+
+

+

+ + + +

+

+ + +

+
+
+ Loop Rate +

+ + +

+
+
+ Roll +

+ + +

+

+ + +

+

+ + +

+

+ + +

+

+ + +

+
+
+ Pitch +

+ + +

+

+ + +

+

+ + +

+

+ + +

+

+ + +

+
+
+ Yaw +

+ + +

+

+ + +

+

+ + +

+

+ + +

+

+ + +

+
+
+ + + + + diff --git a/Tools/autotest/web-firmware/images/filter.png b/Tools/autotest/web-firmware/images/filter.png new file mode 100644 index 00000000000..bc541d07d59 Binary files /dev/null and b/Tools/autotest/web-firmware/images/filter.png differ diff --git a/Tools/autotest/web-firmware/index.html b/Tools/autotest/web-firmware/index.html index 42ccf9fe873..4ceef07a405 100644 --- a/Tools/autotest/web-firmware/index.html +++ b/Tools/autotest/web-firmware/index.html @@ -89,7 +89,7 @@

Firmwares

APM Planner 2.0APM Planner 2.0 - APM Planner 2.0 tool

RadioSiK - 3DR Radio Firmware

+ alt="Radio">SiK - SiK Radio Firmware

ToolsTools - Build and development tools

Firmwares alt="Companion">Companion - Companion Computer example code and Images

AP_PeriphAP_Periph - UAVCAN Peripheral Firmware

+FilterToolFilterTool - Filter Analysis Tool

Types of firmware available

diff --git a/Tools/bootloaders/ARK_GPS_bl.bin b/Tools/bootloaders/ARK_GPS_bl.bin index a2a0c61f4c8..e5e610d13b3 100755 Binary files a/Tools/bootloaders/ARK_GPS_bl.bin and b/Tools/bootloaders/ARK_GPS_bl.bin differ diff --git a/Tools/bootloaders/ARK_GPS_bl.hex b/Tools/bootloaders/ARK_GPS_bl.hex index 922a5cde93c..0ce07ba00bf 100644 --- a/Tools/bootloaders/ARK_GPS_bl.hex +++ b/Tools/bootloaders/ARK_GPS_bl.hex @@ -1,1024 +1,1024 @@ :020000040800F2 -:1000000000070020210500082D160008AD15000886 -:1000100005160008AD150008D915000823050008CD -:100020002305000823050008230500088137000880 -:100030002305000823050008230500082305000800 -:1000400023050008230500082305000823050008F0 -:100050002305000823050008B53B0008E13B000824 -:100060000D3C0008393C0008653C000823050008E9 -:1000700023050008230500082305000823050008C0 -:10008000230500082305000823050008A125000812 -:100090000D26000861260008B5260008913C0008DE -:1000A0002305000823050008230500082305000890 -:1000B000013A00082305000823050008230500086D -:1000C0002305000823050008230500082305000870 -:1000D00023050008230500084D2900082305000812 -:1000E000F93C000823050008230500082305000843 -:1000F0002305000823050008230500082305000840 -:10010000230500082305000823050008230500082F -:10011000230500082305000823050008230500081F -:10012000230500082305000823050008230500080F -:1001300023050008230500082305000823050008FF -:1001400023050008230500082305000823050008EF -:1001500023050008230500082305000823050008DF -:1001600023050008230500082305000823050008CF -:1001700023050008230500082305000823050008BF -:1001800023050008230500082305000823050008AF -:10019000230500082305000823050008230500089F -:1001A000230500082305000823050008230500088F -:1001B000230500082305000823050008230500087F -:1001C000230500082305000823050008230500086F -:1001D000230500082305000823050008230500085F -:1001E000D0400B1CD1409C46203AD3401843524289 -:1001F00063469340184370479140031C90409C46CF -:10020000203A9340194352426346D3401943704702 -:1002100053B94AB9002908BF00281CBF4FF0FF316D -:100220004FF0FF3000F07AB9ADF1080C6DE904CE63 -:1002300000F006F8DDF804E0DDE9022304B07047C1 -:100240002DE9F0478C460D460446089E002B51D1FF -:100250008A4217466DD9B2FA82FEBEF1000F0BD06A -:10026000CEF1200C01FA0EF520FA0CFC02FA0EF782 -:100270004CEA050C00FA0EF44FEA174A250CBCFBB9 -:10028000FAF81FFA87F90AFB18CC45EA0C4508FB77 -:1002900009F3AB420AD9ED1908F1FF3280F023814E -:1002A000AB4240F22081A8F102083D44ED1AA4B20D -:1002B000B5FBFAF00AFB105544EA054400FB09F9C6 -:1002C000A14509D9E41900F1FF3380F00A81A14565 -:1002D00040F2078102383C44A4EB090440EA08409C -:1002E0000021002E61D024FA0EF4002334607360E4 -:1002F000BDE8F0878B4207D9002E54D0002186E854 -:1003000021000846BDE8F087B3FA83F1002940F0E8 -:100310008E80AB4202D3824200F2FA80841A65EBEF -:1003200003050120AC46002E3FD086E81010BDE842 -:10033000F08712B90127B7FBF2F7B7FA87FEBEF1D3 -:10034000000F34D1EB1B3A0C1FFA87FC0121B3FBE1 -:10035000F2F8250C02FB183345EA03450CFB08F3C1 -:10036000AB4207D9ED1908F1FF3002D2AB4200F2DF -:10037000D1808046ED1AA3B2B5FBF2F002FB105516 -:1003800043EA05440CFB00FCA44507D9E41900F13D -:10039000FF3302D2A44500F2B8801846A4EB0C0447 -:1003A00040EA08409DE731463046BDE8F087CEF18F -:1003B000200405FA0EF307FA0EF720FA04F83A0CB7 -:1003C00025FA04F448EA0308B4FBF2F14FEA1845B1 -:1003D00002FB11441FFA87FC45EA044501FB0CF3BC -:1003E000AB4200FA0EF409D9ED1901F1FF3080F0AB -:1003F0008A80AB4240F2878002393D44EB1A1FFAF3 -:1004000088F5B3FBF2F002FB103345EA034500FB2D -:100410000CF3AB4207D9ED1900F1FF386FD2AB42B4 -:100420006DD902383D44EB1A40EA01418FE7C1F132 -:10043000200722FA07F88B4005FA01F448EA030383 -:1004400020FA07FE4FEA134CFD404EEA040EB5FBBE -:10045000FCF94FEA1E440CFB19551FFA83F844EAD5 -:10046000054509FB08F4AC4202FA01F200FA01FA70 -:1004700008D9ED1809F1FF3043D2AC4241D9A9F1B6 -:1004800002091D442D1B1FFA8EFEB5FBFCF00CFB70 -:1004900010554EEA054400FB08F8A04507D9E418BA -:1004A00000F1FF3529D2A04527D902381C4440EA83 -:1004B0000940A4EB0804A0FB02894C45C6464D4602 -:1004C00015D312D056B1BAEB0E0364EB050404FA4F -:1004D00007F7CB401F43CC40376074600021BDE874 -:1004E000F0871846F8E69046E0E6C245EAD2B8EB57 -:1004F000020E69EB03050138E4E72846D7E74046DA -:1005000091E78146BEE7014678E702383C4445E77B -:10051000084608E7A8F102083D442BE7704700BFF2 -:1005200002E000F000F8FEE772B63A4880F308886F -:10053000394880F3098839484EF60851CEF2000157 -:10054000086040F20000CCF200004EF63471CEF2AA -:1005500000010860BFF34F8FBFF36F8F40F20000C0 -:10056000C0F2F0004EF68851CEF200010860BFF3F1 -:100570004F8FBFF36F8F4FF00000E1EE100A4EF681 -:100580003C71CEF200010860062080F31488BFF3AE -:100590006F8F03F071F903F051F903F097F94FF001 -:1005A00055301F491B4A91423CBF41F8040BFAE702 -:1005B0001C49194A91423CBF41F8040BFAE71A4919 -:1005C0001A4A1B4B9A423EBF51F8040B42F8040BE7 -:1005D000F8E700201749184A91423CBF41F8040B44 -:1005E000FAE703F02FF903F0C5F9144C144DAC42AF -:1005F00003DA54F8041B8847F9E700F041F8114C7E -:10060000114DAC4203DA54F8041B8847F9E703F0B4 -:1006100017B9000000070020002300200000000898 -:100620000001002000070020604000080023002097 -:10063000242300202823002090390020E001000816 -:10064000E0010008E0010008E00100082DE9F04F9A -:100650002DED108AC1F80CD0C3689D46BDEC108A00 -:10066000BDE8F08F002383F311882846A0470020BF -:1006700002F086FDFEE702F0EDFC00DFFEE7000081 -:100680002DE9F04103F018F8804603F065F80546BF -:1006900000283DD12B4B98453AD0013398453AD0AC -:1006A000294B28F0FF029A4238D15FFA88F000F017 -:1006B00051FA2E4642F2107400F060FC08B100249A -:1006C000264600F04DFA074660B36CBB374635B19D -:1006D0001E4B984503D003F037F80024274600202E -:1006E00002F0F4FF1A4B1B691B0420D40FB100F079 -:1006F00031F800F09BFC00F08FFE00F099FF0546FA -:10070000BCB900F043FD4FF47A7002F03FFDF7E70B -:100710002E460024D0E704460126CDE706464FF4D6 -:100720007A74C9E70446D2E74FF47A74CFE700241D -:10073000DFE700F07DFF401BA042E2D900F00AF89D -:10074000DBE700BF010007B0000008B0263A09B09F -:100750000004024010B51E4B1E4953F8042F01320D -:1007600000D110BD8B42F8D11B4C1C4B22689A4221 -:100770002CD91B4B9B6803F1006303F580339A422D -:1007800024D202F0B5FF02F0C7FF002000F05EFEA9 -:10079000144B0220187000F095FE134B1A6C0022C7 -:1007A0001A64196E1A66196E596C5A64596E5A6633 -:1007B0005B6E72B60D4A0E4B13601B6822682021D7 -:1007C00081F311889D4683F30888104710BD00BF50 -:1007D000FCFF00081C00010804000108FFFF0008DE -:1007E00000230020282300200038024008ED00E00C -:1007F0000000010809490B6849F269009AB21B0C14 -:1008000000FB0233064A0B60136844F2506198B251 -:100810001B0C01FB0030106080B2704720230020C9 -:100820001C23002010B500211022044600F066FEB3 -:10083000034B03CB206061601868A06010BD00BF4F -:10084000107AFF1FF0B51F4CBBB000F0F1FEA3689B -:10085000C31AF92B30D906AD2346A0602822002107 -:10086000284601F0A3FB04F10E0000F03FFE002338 -:10087000C6B2591D5F1CDBB2B3424FEAC10107DAB1 -:100880000E3323440822284601F090FB3B46F0E754 -:10089000012303930823207B02930B4B0193C1F3A5 -:1008A000CF013023059100930146049503A3D3E9BA -:1008B0000023064801F0B4F93BB0F0BD78F6339F51 -:1008C00093CACD8D68330020753300204433002057 -:1008D00070B50D4614461E4601F04AF950B9022E75 -:1008E0000ED1012C0CD112A3D3E90023C5E90023BA -:1008F000012070BD052C14D003D8012C09D0002094 -:1009000070BD282C09D0302CF9D10BA3D3E90023DA -:10091000ECE70BA3D3E90023E8E70BA3D3E900231B -:10092000E4E70BA3D3E90023E0E700BFAFF30080C7 -:10093000401DA12026812A0B78F6339F93CACD8DC6 -:100940009E6AC421818A46EE26417272DF25D7B79E -:10095000F017304A39059E5638B504460D46034611 -:1009600020222846002101F021FB22792346032A78 -:1009700028BF032203F8042F28460222202101F079 -:1009800015FB62792346072A28BF072203F8052FA3 -:1009900028460322222101F009FBA2792346072AD7 -:1009A00028BF072203F8062F28460322252101F03D -:1009B000FDFA284604F108031022282101F0F6FA76 -:1009C000382038BD2DE9F04FFFB01FAE0CAD40F21E -:1009D000791280460F463046002100F08FFD4822F4 -:1009E0000021284600F08AFD00F022FE574B4FF40C -:1009F0007A72B0FBF2F0186093E80700002485E8F3 -:100A0000070001230DF152002B746C74FFF70AFFED -:100A1000512385F8213006AB18464D4985F8204012 -:100A200003F00EFA152228643146284685F83C204A -:100A3000FFF792FF10AB044601460822304601F052 -:100A4000B5FA0822A1180DF14103304601F0AEFAC3 -:100A50000DF14203082204F11001304601F0A6FA1C -:100A600011AB202204F11801304601F09FFA12ABBD -:100A7000402204F13801304601F098FA14AB082204 -:100A800004F17801304601F091FA0DF1510308228A -:100A900004F18001304601F089FA04F1880A0DF171 -:100AA000520904F5847B4B465146082230460AF130 -:100AB000080A01F07BFAD34509F10109F3D119AB1A -:100AC00008225946304601F071FA04F588744FF057 -:100AD000000995F834304B4510D84FF0000995F8CF -:100AE0003C304B4515D92B6C21464B4408223046EF -:100AF00001F05CFA083409F10109F0E7AB6B21461B -:100B00004B440822304601F051FA083409F101093A -:100B1000DFE7E31DC3F3CF03F97E059300230496BB -:100B20000393BB7E0293193701230093019705A31A -:100B3000D3E90023404601F073F87FB0BDE8F08FA1 -:100B4000AFF300809E6AC421818A46EE2C230020E8 -:100B5000EC3E0008014B1870704700BF382300209E -:100B6000F0B5324B1C7B85B034B1314B0E221A816B -:100B70000024204605B0F0BD2E4A1068516802AB33 -:100B800003C308230DEB03022B492C4803F03AF969 -:100B9000054630B9264B2A480A221A8100F002FD88 -:100BA000E6E70169B1F5E02F06D9214B25480B2274 -:100BB0001A8100F0F7FCDCE7438B512B08D01C4A6C -:100BC00021480C2111815122194600F0EBFCD0E79D -:100BD0001E4A024402F11003994204D2144B1C48ED -:100BE00010221A81E5E710398E1A2046134900F0C9 -:100BF00023FD3246074605F11801204600F01CFD92 -:100C0000AB689F4202D1EB6898420AD0084B0D2294 -:100C10001A8100903B46EA68A9680E4800F0C2FCC1 -:100C2000A6E70D4800F0BEFC0124A2E768330020CF -:100C30002C230020503E0008DCFF060000000108C5 -:100C4000583E0008643E0008763E00080800FFF7A2 -:100C5000943E0008B13E0008DA3E00082DE9F04F4E -:100C6000ADB006AF80460C4600F082FF0646002875 -:100C70005BD1237E022B19D1E38A012B16D100F020 -:100C8000D7FC0546FFF7B6FD4FF4C873B54AB0FB75 -:100C9000F3F105F5167501FB1300E37E15FA80F0FC -:100CA0001060914633B9B04B00221A709C37BD4694 -:100CB000BDE8F08FA38AF5B2013BAB4206F1010615 -:100CC0000CD93B1D691CC9001D4400950023082256 -:100CD00001F0F801204601F03BF8EBE707F11400C2 -:100CE000FFF7A0FD2A4607F11401381D03F07AF83A -:100CF00003460028D7D10F2D08D89B4B1D70D9F87B -:100D00000030A3F51673C9F80030CFE707F1980259 -:100D1000014602F8950D20460092072201F018F8CE -:100D2000F978404600F01CFFC0E7E38A052B00F08D -:100D3000068106D8012BB9D121464046FFF742FE75 -:100D4000B4E7282B3DD0302BB0D1637E874D0133E3 -:100D50006A7BDBB29342E94640F0EF80E27E2B7B78 -:100D60009A4240F0EA8007F19803002623F8846D48 -:100D70001022009331460123204600F0E9FFB4F829 -:100D80001480A8F102081FFA88F808F1030323F081 -:100D900003030A3323F00703ADEB030D0DF1180A2B -:100DA00033469BB2B11C98454FEAC10106F10106DA -:100DB0006CDD5344009308220023204600F0C8FF56 -:100DC000EEE7A38A013B9BB2C92B3FF66FAF674E9C -:100DD000357B4DBB06F10C03009308222B462946B8 -:100DE000204600F0B5FFA38A05F10109013BEDB2F1 -:100DF0009D424FEAC90109DA0E35354400950023BA -:100E00000822204600F0A4FF4D46ECE70023002214 -:100E1000C6E900230023B36086F8D730C6F8D8307F -:100E2000337B0BB9E37E3373002507F114063B1DBA -:100E30000822294630467D60BD60FD6001F0B6F8AD -:100E40003B7A05F10109AB424FEAC90107D9FB68BA -:100E500008222B44304601F0A9F84D46F0E7C1F3D3 -:100E6000CF010023E07E059104960393A37E0293B5 -:100E70001934282301460093019438A3D3E90023B1 -:100E8000404600F0CDFEFFF7DDFC0FE795F8D700F8 -:100E900000F0E6FAD5F8D83006461BB995F8D70029 -:100EA00000F0EEFAD5F8D83043449E4204D295F8CB -:100EB000D700013000F0E4FA4FEA980B0024A0B20A -:100EC000584504F1010408DA2B6880000AEB0001A0 -:100ED0000122184400F01AFBF1E7D5E90023D5F808 -:100EE000D84095F8D70012EB080243F100034444C0 -:100EF000C5E90023C5F8D84000F0B2FA844209D30E -:100F000095F8D730013385F8D730D5F8D8309E1B07 -:100F1000C5F8D860B8F1FF0F08DC00232B7300F090 -:100F2000C1FAFFF71DFE08B1FFF714FC2B68104A49 -:100F30009B0A013313810023AB60CD46B6E6BFF3B5 -:100F40004F8F0C490C4BCA6802F4E0621343CB602C -:100F5000BFF34F8F00BFFDE7AFF3008026417272F1 -:100F6000DF25D7B7403300203D3300206833002011 -:100F70002C23002000ED00E00400FA0537B54FF007 -:100F80000054214B22689A4229D1204B627D1A706D -:100F90001F48237D0373C9221E490E3000F09CFABE -:100FA000E0220021204600F0A9FA0125284603B0DE -:100FB00030BD0321184800F053FB8DE8030063683F -:100FC00083421ED1236899424FF0000319D1A360D8 -:100FD0000E4B22691A70114BE2681A60E6E702F0C4 -:100FE000C5FB054668B10E4A0E4C136C43F0007306 -:100FF0001364A2680C4B9A4203D12369013B7E2BF8 -:10100000D7D90025D2E700BF9AAD44C538230020C8 -:101010006833002016000020586600401823002086 -:1010200000380240506600405041A0B0F0B54B4A35 -:101030004B4CD2F800E085B002236371BEF57A7F95 -:101040004FF000030293ADF80C304AD3454B464DA8 -:10105000B5FBFEF19E4594BF102309235A1CB1FB3A -:10106000F2F702FB171222B1022B3ADD013BDBB291 -:10107000F4E77A1EB2F5806F33D2C3EBC306F21CDD -:10108000C2F3C702991A02F1010CC9B24FF47A7087 -:1010900000FB0CF08C44B0FBFCF080B2B0F5617F3B -:1010A00006D9721E082692FBF6F2D2B29B1AD9B26A -:1010B000531E0F2B50D84B1E072B8CBF0023012330 -:1010C000501800FB0770B5FBF0F5AE4509D143B1F0 -:1010D0000123ADF808708DF80C308DF80A208DF8DA -:1010E0000B109DF80B30214921485A1E9DF80A30FB -:1010F000013B1B0443EA0253BDF80820013A1343A5 -:101100004B6001F0E1FC002301931A4B00931A4954 -:101110001A4B1B484FF4805200F0FAFC194B197817 -:1011200011B1174800F01CFD00F082FA0546FFF7E8 -:1011300061FB4FF4C87305F51675B0FBF3F202FBC3 -:101140001300114B15FA80F0186002F005FB08B18E -:101150000F23238105B0F0BD0023B1E71823002041 -:101160002C2300203F420F0040787D0110230020F7 -:1011700080340020D10800083C2300205D0C0008CA -:101180004433002038230020403300202DE9F04F65 -:1011900096A7D7E900670FF25C29D9E900898F4C3F -:1011A00093B0DFF858B2DFF858A2204600F082FD75 -:1011B0000CAD079098B310220021284600F09EF94C -:1011C000079B197B4FF0000261F3030219468DF86B -:1011D000302051F8040F49680EAA03C21B680D9A0B -:1011E00063F31C029DF830300D9243F020038DF81C -:1011F000303000232A461946584601F075FC079006 -:1012000030B9204600F05AFD079B8AF80030CCE741 -:101210009AF80030072B40DC01338AF8003018229E -:101220000021284600F06AF9DFF8D0B1DFF8D4A138 -:10123000002319462A46584601F07EFC014680BB31 -:10124000102208A800F05AF9DAF8143083F4806309 -:10125000CAF8143000F0EEF90B4612A9024611E963 -:1012600003000DF1240E8EE803009DF83410C1F345 -:10127000030089064CBF0E99BDF838108DF82C007C -:1012800046BFC1F31C0141F00041C1F30A010891BE -:10129000204608A900F0D2FECAE7204600F00EFD65 -:1012A000BDE7204600F064FC824600284AD1DFF802 -:1012B00058B100F0BDF9DBF80030984242D300F09D -:1012C000B7F90790FFF796FA079A8DF820A04FF428 -:1012D000C87302F51672B0FBF3F101FB130012FAAA -:1012E00080F0CBF80000DFF824B19BF8001011B9B2 -:1012F00001238DF8203028460791FFF793FA0799CC -:10130000C1F1100A5FFA8AFABAF1060F28BF4FF04E -:10131000060A524629440DF1210000F0DDF80AF1D9 -:101320000103049308AB0393182302932C4B0193FE -:101330000123009332463B46204600F01BFC00236D -:101340008BF8003000F074F9264ADFF8C4A0136867 -:10135000C31AB3F57A7F32D3106000F06BF90246FE -:101360000B46204600F0B4FC204600F001FC30B3F0 -:101370009AF80C30DFF89CB0002B14BF0323022333 -:101380008BF8053000F054F94FF47A732946B0FB1E -:10139000F3F0CBF800005846FFF7DEFA18230730C9 -:1013A0000293114B0193C0F3CF0040F25513049008 -:1013B0000093039542464B46204600F0DBFB9AF82B -:1013C0000C300BB1FFF73EFA9AF80C30002B7FF48B -:1013D000E8AE13B0BDE8F08FAFF3008044330020D7 -:1013E0003C330020483400204C340020401DA12014 -:1013F00026812A0BF1C6A7C1D068080F80340020CF -:101400004D34002000000240403300203D330020D6 -:10141000683300202C23002070B502F01BF8094C23 -:10142000094E2080002530682388834208D902F0C5 -:101430000BF8336805440133B5F5803F3360F2D3D0 -:1014400070BD00BF7C3400205034002002F0B2B8E0 -:1014500000F10060920000F5803002F041B8000019 -:10146000054B1A68054B1B889B1A834202D910440E -:1014700001F0EABF00207047503400207C34002087 -:1014800038B5074D04462868204401F0E5FF28B927 -:1014900028682044BDE8384001F0F6BF38BD00BFE1 -:1014A00050340020064991F8243033B1002308223B -:1014B000086A81F82430FFF7CBBF0120704700BFD6 -:1014C00054340020022802BF024B4FF480629A611C -:1014D000704700BF0000024010B50023934203D0C4 -:1014E000CC5CC4540133F9E710BD0000024603464A -:1014F000981A13F9011B0029FAD1704702440346D8 -:10150000934202D003F8011BFAE770472DE9F04738 -:10151000234C94F8243005468846174683BB2E4654 -:10152000DFF87C90C7B394F824302BB92022FF2138 -:1015300048462662FFF7E2FF94F82400C0F1080550 -:10154000BD4228BF3D465FFA85FAAD0041462A46B6 -:1015500004EB8000FFF7C0FF94F82430A7EB0A07E4 -:101560009A445FFA8AFABAF1080F2E44A844FFB2EF -:1015700084F824A0D6D1FFF795FF0028D2D108E047 -:10158000266A06EB8306B042CAD0FFF78BFF00281D -:10159000C5D10020BDE8F0870120BDE8F08700BF7D -:1015A000543400200FB4002004B0704700B59BB045 -:1015B000EFF3098168226846FFF78EFFEFF305839A -:1015C000044B9A6BDA6A9A6A9A6A9A6A9A6A9A6A6F -:1015D0009B6AFEE700ED00E000B59BB0EFF30981E8 -:1015E00068226846FFF778FFEFF30583044B9A6B98 -:1015F0009A6A9A6A9A6A9A6A9A6A9B6AFEE700BF2E -:1016000000ED00E000B59BB0EFF309816822684669 -:10161000FFF762FFEFF30583034B5A6B9A6A9A6AEE -:101620009A6A9A6A9B6AFEE700ED00E0FEE7000016 -:1016300001F0FEBF01F0E8BF30B5084D0A44914209 -:101640000BD011F8013B09245840013CF7D040F37E -:1016500000032B4083EA5000F7E730BD2083B8ED4C -:101660002DE9F7431AA7D7E9006700EB81014FF096 -:10167000FF324FF0FF330DF1040C884223D050F8B5 -:1016800004EBCDF804E04FF0000E1EF80C800024AF -:101690004FEA086562406B404FF00908B8F1010855 -:1016A0000BD0002A73F1000904DA92185B417240F2 -:1016B0007B40F3E792185B41F0E70EF1010EBEF1BB -:1016C000040FE2D1D9E7D043D94303B0BDE8F0839A -:1016D0009336EAA9EBE1F0422DE9F047089E01F0CC -:1016E00007054FEAD60C2A4406F0070600EBD100A6 -:1016F0004FF47F49954201D1BDE8F08705F0070E10 -:1017000006F0070AD64577464FEAD50438BF574654 -:10171000C7F10807511B0CEBD6088F42045D28BFA8 -:101720000F4604FA0EF413F8081029FA07FE24FAFB -:101730000AF45FFA8EFE4C404EFA0AFE04EA0E04EA -:10174000614003F808103D443E44D3E70246006878 -:1017500048B103681360D388118901339BB2994261 -:10176000D38038BF1381704770B588B00D460446EA -:10177000202200216846FFF7C1FE20460495FFF7AE -:10178000E5FF054658B16B46044608AE1A4603CA43 -:10179000B24220606160134604F10804F6D1284685 -:1017A00008B070BD2DE9F041056885B90160BDE85C -:1017B000F081002B29DA930CB34229D1A54201D143 -:1017C0000D60F3E7C8F800100C60BDE8F0814B68CD -:1017D00023F06047BE0C4FEAD37EC3F3807C16EA49 -:1017E000230638BF3E46A8462C466368BEEBD37F2F -:1017F00023F06042DDD1974203D1C3F380739C454F -:101800000AD1974205E01C46EFE7B24206D01346E4 -:101810009E422CBF00230123002BCFD12368A0467A -:10182000002BF0D12160BDE8F08100002DE9F041EE -:1018300006460F4600254FF6FF7441F221082A465E -:1018400030463946FEF7CCFCC0B284EA00240823B7 -:1018500014F4004F4FEA4404A4B203F1FF3318BF5D -:1018600084EA080413F0FF03F2D10835402DE6D1D5 -:101870002046BDE8F081000010B54B6833B9CA8A34 -:1018800063F30902CA820020002110BDC4681A68EF -:101890001C60C360438A013B43824A60EDE700005D -:1018A00010B50A4441F22104914200D110BD11F853 -:1018B000013B80EA0320082310F4004F4FEA400068 -:1018C00080B203F1FF3318BF604013F0FF03F3D180 -:1018D000EAE700002DE9F04F85B081468DE80A0067 -:1018E000BDF83C409346002A00F0838024B10E9B53 -:1018F000002B7ED0072C2AD809F10C00FFF726FF19 -:10190000054628B96FF00205284605B0BDE8F08FFE -:1019100014220021FFF7F2FD22460E9905F108007E -:10192000FFF7DAFD631C2B749BF800302C4403F0A6 -:101930001F0363F03F032372009B43F000436B607F -:10194000294609F11C00FFF72DFF0125DCE7019B6B -:101950001B0A4FF00008029300F10C034FF0800ABD -:101960004646454603930398FFF7F0FE07460028D6 -:10197000C8D014220021FFF7C1FDC6BB9DF804307A -:101980003B729DF808307B7202220E9B711E194437 -:10199000B4420AD9B8180132D2B211F801EF80F876 -:1019A00008E00136072AB6B2F2D19BF8001001F028 -:1019B0001F01B44208BF4FF0400AB81841EA48116D -:1019C0004AEA01030372009B013243F000437B604B -:1019D0003A74394609F11C00FFF7E4FE0135B442C0 -:1019E0002DB288F001084FF0000ABCD18CE700222C -:1019F000CBE76FF0010587E72DE9F0471E46CB8A5C -:101A00009146C3F30902062A80460F4619D01346B1 -:101A10000021B0B28DB25A1992B2052A09D9A84252 -:101A200010D8FA8A034463F30902FA820120BDE860 -:101A3000F087A842F3D93A4419F80140947601316D -:101A4000E8E70025FB8A7C68C3F30900821F1C239A -:101A5000B2FBF3FA03FB1A2A1FFA8AF27CB30121C4 -:101A60002368002B39D1B31F03441C20B3FBF0F3D0 -:101A700001339BB299420CD2BAF1000F09D1404612 -:101A8000FFF764FE08B1C0F800A0206008B3044668 -:101A90000022B6B24FF0000AB54230D2691E494466 -:101AA0001346E01801339BB211F801EF80F804E00F -:101AB00001351C2BADB214D0AE42F2D8ECE7404653 -:101AC000FFF744FE044608B1002303607C60002C4D -:101AD000DED16FF00200BDE8F087013189B21C460B -:101AE000BEE7AE42D8D94046FFF730FE08B1C0F895 -:101AF00000A020600028ECD004460022CCE7FB8A3E -:101B0000C3F30902164466F30903FB828EE7000063 -:101B1000F8B5044615460E46242200211F46FFF75D -:101B2000EDFC069B6360079B23626A094FF6FF7317 -:101B30009A424FF0000028BF1A46A760207097B263 -:101B400004F10C0503469A4205D100232B6027823D -:101B50006382A382F8BD2E60013335462036F2E75A -:101B600003781BB94BB2002BC8BF0170704700004F -:101B7000007870472DE9F7430D9EBDF828900B9D26 -:101B80009DF83040BDF8388007461946104616B912 -:101B9000B8F1000F40D11F2C3ED83B78D3B9B8F133 -:101BA000070F36D839F0030336D1424631464FF697 -:101BB000FF70FFF775FE4FEA092920F0010009F4D4 -:101BC0004079400449EA0464400C44EA40244FF65A -:101BD000FF730DE043EA0923B8F1070F43EA0464F9 -:101BE000F5D9FFF723FE42463146FFF759FE03467B -:101BF0008DE840012A4621463846FFF76BFE2B78D8 -:101C00000133DBB21F2B88BF00232B7003B0BDE86C -:101C1000F0836FF00300F9E76FF00100F6E70000D2 -:101C20002DE9F7430E9F0B9D9DF83480BDF83C6075 -:101C300081469DF8300007B9AEBB1F2833D899F80C -:101C400000E0BEF1000F31D00C0244F080049DF89A -:101C5000281044EAC83444EA014444EA0E04072E3A -:101C600044EA00641CD919461046FFF7DFFD3246EE -:101C70003946FFF715FE0346019600972A4621468E -:101C80004846FFF727FEB8F1010F06D12B78013344 -:101C9000DBB21F2B88BF00232B7003B0BDE8F0839D -:101CA0004FF6FF73E8E76FF00100F6E76FF003000F -:101CB000F3E70000C06900B104307047C3691A68D7 -:101CC000C261C2681A60C360438A013B43827047A5 -:101CD0002DE9F047D0F818A0DFF8708005461646C9 -:101CE0001F4654464FF000090CB9BDE8F087D4E90F -:101CF0000223B21A67EB0303994508BF904523D22C -:101D0000AB699C42214628460FD1FFF7B5FDAB6970 -:101D10001B68AB61EB6823606B8AEC60AC69013BCC -:101D20006B822346A2461C46DEE7FFF7A5FD23682B -:101D3000CAF80030EB6823606B8AEC60013B6B8271 -:101D4000DAF800305446EDE72368EBE780841E00A4 -:101D50002DE9F04F8BB00E4614460793DDF8508006 -:101D60008346002800F01081B8F1000F00F00C81CC -:101D7000531E3F2B00F20881012A03D1079B002B41 -:101D800040F00281BBF81450ED000023AE420893EE -:101D9000099304D3002630460BB0BDE8F08F331909 -:101DA0009D42DBF80C303ABFAD1BEDB2254623B99E -:101DB000DBF81030002B00F093802F2E65D8C6F191 -:101DC0003007BD424FF000032CBFFFB22F460093F7 -:101DD000314608AB3A46DBF80800FFF77DFCA5EB7F -:101DE00007093E445FFA89F9BBF8143003F1005348 -:101DF000063BDB000493DBF80C3003933021039B9C -:101E000013B1B9F1000F43D1DBF8100040B1B9F1C3 -:101E1000000F05D0009708AB4A46711AFFF75CFC2B -:101E20002EB2002DB6D060070AD00AAB03EBD40166 -:101E3000624211F8083C02F00702134101F8083C25 -:101E4000082C54D9102C54D9202C8CBF08230423DF -:101E5000079A002A00F09E80B4EBC30F00F09D802B -:101E6000082C48D89DF82030621E23FA02F2D107D0 -:101E700006D54FF0FF3202FA04F423438DF82030E8 -:101E80009DF8203088F8003085E7A9460027ABE7A9 -:101E9000049BE02B28BFE02306930B44B342059339 -:101EA00015D9A3EB060AD145039800972CBF5FFA1A -:101EB0008AFACA46711A08AB52460430FFF70CFC86 -:101EC0005744A9EB0A095644FFB25FFA89F9049B0B -:101ED000069A05999B1A0493039B1B6803938EE74C -:101EE00000932A4608AB3146DBF8080096E7012349 -:101EF000AEE70223ACE7102C12D8BDF82030621EEA -:101F000023FA02F2D20706D54FF0FF3202FA04F4A8 -:101F10002343ADF82030BDF82030A8F800303AE770 -:101F2000202C0FD8089A631E22FA03F3DB0705D58D -:101F30004FF0FF3303FA04F414430894089BC8F8E5 -:101F4000003028E7402C22D0DDE908AB621E504665 -:101F50005946FEF745F9002100F0010050EA01035F -:101F60000DD0224601200021FEF746F9404261EBE8 -:101F7000410140EA0A0041EA0B01CDE90801DDE92F -:101F80000823C8E9002306E76FF0010603E76FF0B6 -:101F9000080600E7012C3FF473AF082C7FF670AF02 -:101FA000102CB8D9202CEAD8C8E7000030B5402A58 -:101FB00085B01FD8002A08BF01220024012A0294FC -:101FC000039419D11B788DF8083053070AD004AB5D -:101FD00003EBD205544215F8083C04F00704A34073 -:101FE00005F8083C00910346002102A8FFF774FBA6 -:101FF00005B030BD4022E0E7082AE3D9102A03D813 -:102000001B88ADF80830E0E7202A02D81B6802934D -:10201000DBE7D3E90045CDE90245D6E710B5CB684B -:102020001BB98B600B618B8210BDC4681A681C6081 -:10203000C360438A013B4382CA60F0E72DE9F04F59 -:10204000D1F800908FB0C9F3C01604460D46CDE913 -:102050000223002E50D0C9F3C03AC9F30626B9F1C5 -:10206000000F80F2CB8119F0C04F40F0C7812B7B6D -:10207000002B00F0C381BAF1020F03D02278B242E4 -:1020800040F0BF8109F07F02BAF1020F059236D10C -:1020900019F07F0FC9F30F2B01D10BF0030B2B4469 -:1020A0007606059A93F8038046EA0A4646EA82468F -:1020B0005FEAD81346EA0B06049300F0A1800022E1 -:1020C00000230EA961E90823059B00936768534626 -:1020D0005A462046B847002800F08F80A7698FB97C -:1020E000314604F10C00FFF73FFB0746D0B96FF013 -:1020F00002000FB0BDE8F08F4FF0020AAFE7C9F35E -:10210000074BCCE73B699E420DD03F68002FF9D1C9 -:10211000314604F10C00FFF727FB07460028E6D004 -:10212000A3693B60A761DDE90601FFF77FFBB88289 -:10213000F97D08F01F06C1F38401711A89B20FFA04 -:1021400081FED7E90223BEF1000FBCBF01F1200ED2 -:102150000FFA8EFE52EA0301C9F3046900F05D81B3 -:10216000DDE90201801A61EB030102460B46B64825 -:102170000021994208BF9042C0F04F81049B002B80 -:1021800048D0BEF1010F00F3488118F0400F41D054 -:10219000DDE902230021C7E9022306A82022FFF778 -:1021A000ADF9DDE90223CDE906232B1D08932B7B36 -:1021B000ADF82EB0013BDBB2ADF82C309DF81430F9 -:1021C0008DF833308DF830A0A3688DF831608DF82C -:1021D000329006A920469847FB7DC3F38402013262 -:1021E00062F38603FB75FB8A6FF30903FB821B0A0C -:1021F0006FF3C713FB7500207BE76FF00B0078E7E8 -:10220000A76917B96FF00C0073E73B699E428FD046 -:102210003F68F6E7FB7DC8F34012B2EBD31F40F0F6 -:10222000F380C3F38403B34240F0F18004992B7B25 -:102230004FEA981200293BD012F001085CD1032B21 -:1022400040F2E880DDE90223C7E902232B7BAE1DC3 -:10225000033BDBB23246394604F10C00FFF7CCFBFE -:10226000002814DA39462046FFF706FBFB7DC3F34E -:102270008402013262F38603FB75FB8A68F309036B -:10228000FB821B0A68F3C713FB75032031E7AB8899 -:102290003B832A7B033AD2B2B88A3146FFF700FB70 -:1022A000FB7DB882DA43C2F3C01262F3C713A1E721 -:1022B00012BB2E1D013BDBB23246394604F10C0045 -:1022C000FFF79AFB002814DA39462046FFF7D4FAC4 -:1022D000FB7DC3F38402013262F38603FB75049A2B -:1022E000FB8A62F30903FB82049A1B0A62F3C71399 -:1022F000CAE72A7B013ACEE7F98AC1F30901013B1B -:102300000529DAB25AD8281D00239A420AD907EBC8 -:10231000010E013110F801CB8EF81AC001330629E5 -:10232000DBB2F2D1DDE902019342CDE9060107F10A -:102330001A01089138BF04337968099134BF5B19D9 -:1023400000230A93FB8AADF82EB0C3F309031A44A5 -:102350009DF814308DF833300023ADF82C208DF823 -:1023600030A08DF831608DF832907B602A7BB88A7E -:10237000013A291DFFF794FA3B8BB882834203D1BF -:10238000A36806A920469847204606A9FFF746FEFF -:10239000FB7DB88AC3F38402013262F38603FB75C6 -:1023A000FB8A6FF30903FB821B0A6FF3C713FB75EC -:1023B0003B8B984214BF112000209AE6D7F804E026 -:1023C000BEF1000F18D00623DEF8000088B9C91A44 -:1023D00005F1040800EB010CBCF11B0FC3B2A1D83E -:1023E00093429FD2F44418F8013B8CF8043001303A -:1023F000F0E71C338646E7E7734693E76FF0090082 -:1024000077E66FF00A0074E66FF00D0071E66FF08A -:102410000E006EE66FF00F006BE6FB7D68F386033F -:102420006FF3C713FB7539462046FFF725FA049B67 -:10243000002B7FF4AAAEFB7DC3F38402013262F36A -:102440008603FB75DEE600BF80841E002DE9F041A7 -:10245000504EB04240F089804F4CDFF840E1256C8F -:1024600045F000752564256E45F000752566246EDF -:10247000846AD4F8007207EA0E0747F00107C4F82F -:102480000072D4F8005205EA0E0545F0010545EA50 -:102490000121C4F80012002A69D00021C4F81C12DE -:1024A0000F46C4F80412C4F80C12C4F8141204EB5A -:1024B000C10501311C29C5F84072C5F84472F6D136 -:1024C0004FF0000E4FF0010C964514D1826AD2F8FD -:1024D0000032B04223F00103C2F8003257D12E4B34 -:1024E0001A6C22F000721A641A6E22F000721A66D8 -:1024F0001B6EBDE8F0819F781D8817F0010F18BF93 -:10250000D4F804820CFA05F11CBF41EA0808C4F8AB -:10251000048217F0020F1EBFD4F80C8241EA0808AB -:10252000C4F80C827F0742BFD4F814720F43C4F87A -:10253000147204EBC5055F68C5F840729F68C5F862 -:102540004472D4F81C522943C4F81C120C330EF107 -:10255000010EB9E7846A0021C4F81C12C4F8041201 -:10256000C4F80C12C4F81412AAE7002AF2D1836A44 -:102570000022C3F84022C3F84422C3F80422C3F85F -:1025800014220122C3F80C22C3F81C229EE7BDE8E6 -:10259000F08100BF80340020003802400000FFFFBF -:1025A000184A916A08B58B688B6013F0010105D059 -:1025B00013F00C0F14BF4FF480310121D80506D55C -:1025C00013F4406F14BF41F4003141F00201D8030D -:1025D00006D513F4402F14BF41F4802141F00401CB -:1025E000D3690BB107489847202383F31188002152 -:1025F000054800F0F3FD002383F31188BDE808408F -:1026000001F0F2B8803400208834002038B5124C34 -:10261000A36ADD68AA0712D05A6922F002025A6141 -:10262000A36913B1012120469847202383F3118821 -:1026300000210A4800F0D2FD002383F31188EB0645 -:1026400006D5A36A1021D960236A0BB102489847C6 -:10265000BDE8384001F0C8B8803400209034002034 -:1026600038B5124CA36A1D69AA0712D05A6922F024 -:1026700010025A61A36913B1022120469847202312 -:1026800083F3118800210A4800F0A8FD002383F39A -:102690001188EB0606D5A36A10211961236A0BB1D4 -:1026A00002489847BDE8384001F09EB880340020C9 -:1026B0009034002038B50F4CA36A5D685D602A072E -:1026C0000AD5042222701A6822F002021A60636A94 -:1026D00013B10021204698476B0706D5A36A996974 -:1026E000236A13B1090403489847BDE8384001F054 -:1026F0007BB800BF8034002010B50F4C204600F09E -:10270000D1F90E4BA3620B21132000F0B3F90B217A -:10271000142000F0AFF90B21152000F0ABF90B21CC -:10272000162000F0A7F9002320461A460E21BDE826 -:102730001040FFF78BBE00BF8034002000640040D3 -:10274000114B984210B5044609D1104B1A6C42F057 -:1027500000721A641A6E42F000721A661B6EA36A47 -:1027600001221A60A36A5A68D20707D562685168C5 -:102770001268D9611A60064A5A6110BD0121082009 -:1027800000F022FCEEE700BF803400200038024059 -:102790005B87010003291AD8DFE801F0020A0F1451 -:1027A000836A9B6813F0E05F14BF0120002070472C -:1027B000836A9868C0F380607047836A9868C0F342 -:1027C000C0607047836A9868C0F30070704700204B -:1027D0007047000010B503291FD8DFE801F0021F81 -:1027E0002327816A8B68C3F30163183301EB03135A -:1027F000107881061ED55468C0F30011490041EAE3 -:10280000C40141F0040100F00F0058609068986026 -:10281000D268DA6041F00101196010BD836A03F5E6 -:10282000C073E5E7836A03F5C873E1E7836A03F5DC -:10283000D073DDE79488C0F30011490041EA4451A8 -:10284000E1E7000001290CD003D3022910D00020B9 -:102850007047836ADA68920701D1186903E00120A2 -:102860007047836AD86810F0030018BF01207047D2 -:10287000836AF2E710B539B9836AD96889071BD131 -:102880001B699B0704D110BD012915D0022948D12D -:10289000816AD1F8C031D1F8C401D1F8C8411461BE -:1028A000D1F8CC41546120240C610C69A40717D1E4 -:1028B0004C6944F0100412E0816AD1F8B031D1F8CB -:1028C000B401D1F8B8411461D1F8BC41546120245D -:1028D000CC60CC68A40703D14C6944F002044C617D -:1028E00011795C0864F304119C0864F345111171BB -:1028F00089064BBF91681189DB085B0D4CBF63F300 -:102900001C0163F30A01137948BF916060F303036C -:1029100013714FEA10234FEA104058BF1181137012 -:10292000508010BD024AD36843F0C003D3607047A3 -:1029300000440040044B5A6810439A6858600AB13A -:10294000181D1047704700BFAC3400202DE9F0413E -:102950003D4ED6F85C52EF682B68DA059CB20CD578 -:10296000202383F311884FF40070FFF7E3FF6FF427 -:1029700080732B60002383F31188202383F3118855 -:10298000DFF8C48014F02F0331D183F311883806A7 -:1029900013D5210611D5202383F311882B4800F08D -:1029A00005FA002844DA0820FFF7C4FF4FF67F73CA -:1029B0003B40EB60002383F311887A060DD5630654 -:1029C0000BD5202383F31188F26C336D9A4201D129 -:1029D000336C7BBB002383F31188D6F86422D36861 -:1029E0000BB110699847BDE8F04100F0FDBE230728 -:1029F00012D014F0080F0CBF00208020E10748BF60 -:102A000040F02000A20748BF40F04000630748BFE5 -:102A100040F48070FFF78EFFA4066B6805D596F82A -:102A200060124046194000F063FA2C68A4B2A9E78E -:102A30006860BFE727F040073F0410203F0CFFF716 -:102A400079FFEF60C6E700BFAC340020E43400201B -:102A500010B5054C054A0021204600F027FA044B2A -:102A6000C4F85C3210BD00BFAC340020252900083A -:102A70000044004000F1604300F01F02400903F5EC -:102A8000614309018000C9B200F1604083F800137E -:102A900000F5614001239340C0F880310360704726 -:102AA000FFF72ABE00F108020123037082600023B1 -:102AB000C26000F110024360026142618361C36140 -:102AC000036243627047000010B52023044683F37D -:102AD0001188022303704160FFF732FE0423237044 -:102AE000002383F3118810BD2DE9F0411F460446F1 -:102AF0000D461646202383F3118800F10808237839 -:102B0000052B0ED029462046FFF744FE48B120464B -:102B100032462946FFF75EFE002080F31188BDE8AB -:102B2000F0813946404600F03DFB0028E7D0002305 -:102B300083F31188BDE8F0812DE9F0411F4604467A -:102B40000D461646202383F3118800F110082378E0 -:102B5000052B0ED029462046FFF774FE48B12046CB -:102B600032462946FFF786FE002080F31188BDE833 -:102B7000F0813946404600F015FB0028E7D00023DD -:102B800083F31188BDE8F081F8B5154682680669BF -:102B9000AA420B46816938BF8568761AB542044659 -:102BA00007D218462A46FEF797FCA3692B44A36177 -:102BB0000DE011D932461846FEF78EFCAF1B3A469F -:102BC000E1683044FEF788FCE2683A44A261A368F9 -:102BD0005B1BA3602846F8BD18462A46FEF77CFC1E -:102BE000E368E4E783682DE9F04104469342154623 -:102BF000266938BF85684069361AB5420F4606D245 -:102C00002A46FEF769FC63692B4463610DE012D923 -:102C10003246A5EB0608FEF75FFC4246B919E068AC -:102C2000FEF75AFCE26842446261A3685B1BA36042 -:102C30002846BDE8F0812A46FEF74EFCE368E4E74B -:102C400010B50A440024C361029B006040608460A8 -:102C5000C160816141610261036210BD08B5826992 -:102C60004369934201D1826882B9826801328260ED -:102C70005A1C42611970426903699A4201D3C368C0 -:102C80004361002100F09EFA002008BD4FF0FF30A4 -:102C900008BD000070B5202304460E4683F311885A -:102CA000A568A5B1A368A269013BA360531CA361F9 -:102CB00015782269934224BFE368A361E3690BB1ED -:102CC00020469847002383F31188284670BD31467B -:102CD000204600F067FA0028E2DA85F3118870BD1B -:102CE0002DE9F74F05460F4690469A46D0F81C90BE -:102CF000202686F311884FF0000B144664B122465B -:102D000039462846FFF740FF034668B95146284632 -:102D100000F048FA0028F1D0002383F31188A8EBD3 -:102D2000040003B0BDE8F08FB9F1000F03D00190AB -:102D30002846C847019B8BF31188E41A1F4486F389 -:102D40001188DBE7C16081614161C3611144009B6F -:102D5000006040608260016103627047F8B504461C -:102D60000E461746202383F31188A568A5B1A368F2 -:102D7000013BA36063695A1C62611E70236962692A -:102D80009A4224BFE3686361E3690BB12046984728 -:102D9000002080F31188F8BD3946204600F002FA81 -:102DA0000028E2DA85F31188F8BD000083694269E2 -:102DB0009A4210B501D182687AB982680132826084 -:102DC0005A1C82611C7803699A4201D3C3688361EB -:102DD000002100F0F7F9204610BD4FF0FF3010BD84 -:102DE0002DE9F74F05460F4690469A46D0F81C90BD -:102DF000202686F311884FF0000B144664B122465A -:102E000039462846FFF7EEFE034668B95146284684 -:102E100000F0C8F90028F1D0002383F31188A8EB53 -:102E2000040003B0BDE8F08FB9F1000F03D00190AA -:102E30002846C847019B8BF31188E41A1F4486F388 -:102E40001188DBE7026843681143016003B118474A -:102E5000704700001430FFF743BF00004FF0FF330E -:102E60001430FFF73DBF00003830FFF7B9BF000056 -:102E70004FF0FF333830FFF7B3BF00001430FFF7D7 -:102E800009BF00004FF0FF311430FFF703BF00000F -:102E90003830FFF763BF00004FF0FF323830FFF7E4 -:102EA0005DBF000000207047FFF7D2BD37B50F4B64 -:102EB0000360002343608360C360012304460374FE -:102EC000154600900B464FF4807200F15C011430FF -:102ED000FFF7B6FE00942B464FF4807204F5AE71F6 -:102EE00004F13800FFF72EFF03B030BD043F0008A7 -:102EF00038B5C36904460D461BB904210844FFF7E1 -:102F0000A1FF294604F11400FFF7A8FE002806DA05 -:102F1000201D4FF48061BDE83840FFF793BF38BDF6 -:102F2000024B00221B605B609A60704714370020E0 -:102F3000002303748268054B1B6899689142FBD299 -:102F40005A68036042601060586070471437002070 -:102F500008B5202383F31188037C032B05D0042BB1 -:102F60000DD02BB983F3118808BD436900221A6084 -:102F70004FF0FF334361FFF7DBFF0023F2E790E8F8 -:102F80000C001A6002685360F2E70000002303742B -:102F90008268054B1B6899689142FBD85A680360A8 -:102FA000426010605860704714370020054B196963 -:102FB0000874186802681A6053601861012303746A -:102FC000FDF744BB1437002030B54B1C87B00546D5 -:102FD0000A4C10D023690A4A01A800F01BF92846C0 -:102FE000FFF7E4FF049B13B101A800F051F9236936 -:102FF000586907B030BDFFF7D9FFF8E71437002054 -:10300000512F000838B50C4D41612B6981689A68D1 -:103010009142044603D8BDE83840FFF789BF1846FF -:10302000FFF7B4FF01232C61014623742046BDE85D -:103030003840FDF70BBB00BF14370020044B1A6863 -:103040001B6990689B68984294BF002001207047DC -:103050001437002010B5084C236820691A682260D4 -:103060005460012223611A74FFF790FF0146206922 -:10307000BDE81040FDF7EABA1437002008B5FFF7A5 -:10308000DDFF18B1BDE80840FFF7E4BF08BD000050 -:10309000FEE7000010B50C4CFFF742FF00F0ACF863 -:1030A00080220A49204600F031F8012344F8180C28 -:1030B000037400F075FB002383F3118862B60448A3 -:1030C000BDE8104000F044B83C3700202C3F000819 -:1030D000343F000800F018B9EFF3118020B9EFF386 -:1030E0000583202282F311887047000010B558B97B -:1030F000EFF30584C4F3080414B180F3118810BD04 -:10310000FFF7BCFF84F3118810BD0000826002222B -:1031100002740022427470478368A3F17C0243F872 -:103120000C2C026943F83C2C426943F8382C074ABE -:1031300043F81C2CC26843F8102C022203F8082C18 -:10314000002203F8072CA3F1180070476506000859 -:1031500010B5202383F31188FFF7DEFF002104461A -:10316000FFF750FF002383F31188204610BD0000B5 -:10317000024B1B6958610F20FFF718BF143700205E -:10318000202383F31188FFF7F3BF000008B5014641 -:10319000202383F311880820FFF716FF002383F311 -:1031A000118808BD49B1064B42681B6918605A6016 -:1031B000136043600420FFF707BF4FF0FF307047F4 -:1031C000143700200368984206D01A6802605060E5 -:1031D00059611846FFF7ACBE7047000038B5044689 -:1031E0000D462068844200D138BD036823605C60CE -:1031F0004561FFF79DFEF4E7054B03F114025A61A8 -:103200009A614FF0FF32DA6100221A62704700BF04 -:1032100014370020F8B50361C2600E46054600F081 -:1032200041FB1A4B19461F4651F8142F8A420DD103 -:103230001862AE606A602A600A2E2CBF80190A30BC -:103240009D615D61BDE8F84000F01ABB1B6A9268A1 -:10325000C41A341928BF3446A24202D9181900F002 -:103260001DFB7B699A6894420CD8AC6098685A68D8 -:103270002B60041B6A6015605D609C604FF0FF333B -:10328000FB61F8BDA41A1B68ECE700BF14370020EF -:1032900038B51C4B01685A6990421D460DD04468F0 -:1032A0002160026800215460C16091688068014417 -:1032B00091604FF0FF32DA6138BD1A4642F8141FB0 -:1032C0004A605B6900219342C16003D1BDE8384088 -:1032D00000F0DEBA9A6881680A449A602C6A00F0AD -:1032E000E1FA6A699268001B82420AD9111A092917 -:1032F00098BF00F10A02286ABDE83840104400F087 -:10330000CDBA38BD143700202DE9F041184D002703 -:1033100005F114066C6900F0C5FA2A6AA368811ADF -:103320008B4216D813442B6294E80C001A60226872 -:10333000D4F80C8053606B69E760B34201D100F0B0 -:10334000A7FA87F311882069C047202383F31188E7 -:10335000E0E76A69B24208D05B1A0A2B2CBFC0189A -:103360000A30BDE8F04100F099BABDE8F08100BF35 -:103370001437002000207047FEE70000704700006F -:103380004FF0FF3070470000BFF34F8F024AD36801 -:10339000DB03FCD4704700BF003C024008B5094B7A -:1033A0001B7873B9FFF7F0FF074B1A69002ABFBFFC -:1033B000064A5A6002F188325A601A6822F4806222 -:1033C0001A6008BDD0380020003C02402301674548 -:1033D00008B50B4B1B7893B9FFF7D6FF094B1A6959 -:1033E00042F000421A611A6842F480521A601A6868 -:1033F00022F480521A601A6842F480621A6008BD92 -:10340000D0380020003C0240072870B513D80B4A82 -:103410000B4C137863B90B4E4FF0006144F8231046 -:1034200056F823500133082B2944F7D10123137098 -:1034300054F8200070BD002070BD00BFF43800209B -:10344000D4380020543F0008014B53F82000704747 -:10345000543F000808207047072810B5044601D9DA -:10346000002010BDFFF7D0FF064B53F8243018445E -:10347000C21A0BB9012010BD12680132F0D1043B11 -:10348000F6E700BF543F0008072810B5044621D8CE -:10349000FFF77AFFFFF782FF0F4AF323D360C300E1 -:1034A000DBB243F4007343F002031361136943F486 -:1034B00080331361FFF768FFFFF7A6FF074B53F850 -:1034C000241000F013F9FFF783FF2046BDE81040F9 -:1034D000FFF7C2BF002010BD003C0240543F00086F -:1034E0002DE9F84312F00103154640D184182E4A05 -:1034F00094423CD82D4B1B6813F0010337D02C4C61 -:10350000FFF74CFFF323E360FFF73EFF40F2012794 -:10351000032D01D9830713D0254C0F46401A40F2E2 -:103520000118EB1B0B44012B00EB0706236924D881 -:1035300023F001032361FFF74BFF0120BDE8F8836F -:10354000236923F44073236123693B43236151F8CA -:10355000046B0660BFF34F8FFFF716FF03689E42B0 -:1035600008D0236923F001032361FFF731FF002016 -:10357000BDE8F883043D0430CAE723F440732361B7 -:10358000236943EA08032361B94637F8023B3380D5 -:10359000BFF34F8FFFF7F8FE3688B9F80030B6B2A8 -:1035A000B342BED0DDE700BF00000808003802408B -:1035B000003C0240084908B50B7828B153B9FFF721 -:1035C000EDFE01230B7008BD23B1BDE80840087073 -:1035D000FFF7FEBE08BD00BFD038002038B500F0B0 -:1035E00061F9074B1A68824207D9064AD2E90045B9 -:1035F000003445F10105C2E90045186038BD00BF3F -:10360000F83800200039002070B5FFF765FD064648 -:10361000FFF7E4FF054BD3E90045241845F1000509 -:103620003046FFF763FD2046294670BD0039002073 -:1036300008B5FFF7E9FF4FF47A720023FCF7E8FDC5 -:1036400008BD00BF10B50244064B0439D2B2904207 -:1036500000D110BD441C00B253F8200041F8040F03 -:10366000E0B2F4E750280040104B30B51C6F240442 -:1036700007D41C6F44F400741C671C6F44F40044AE -:103680001C670B4C236843F4807323600244094B8E -:103690000439D2B2904200D130BD441C00B251F87E -:1036A000045F43F82050E0B2F4E700BF0038024066 -:1036B000007000405028004007B5012201A90020F9 -:1036C000FFF7C0FF019803B05DF804FB13B5044693 -:1036D000FFF7F2FFA04206D002A9012241F8044DF3 -:1036E0000020FFF7C1FF02B010BD000070470000CE -:1036F000074B45F255521A6002225A6040F6FF729B -:103700009A604CF6CC421A60024B01221A70704744 -:10371000003000400C390020034B1B781BB1034BD9 -:103720004AF6AA221A6070470C3900200030004087 -:10373000034B1A6812B9034A12681A60704700BF37 -:103740000839002074380240024B4FF080721A6032 -:10375000704700BF7438024008B5FFF7E9FF024B1D -:103760001868C0F3407008BD0839002008B5FFF79D -:10377000DFFF024B1868C0F3007008BD0839002055 -:10378000EFF3098305494A6822F001024A60683371 -:1037900083F30988002383F31188704730EF00E03A -:1037A000202080F3118862B60B4B0C4AD96821F4B3 -:1037B000E0610904090C0A430949DA60CA6842F069 -:1037C0008072CA6007490A6842F001020A6010224A -:1037D000DA7783F82200704700ED00E00003FA0575 -:1037E000F0ED00E0001000E010B5202383F3118815 -:1037F0000E4B5B6813F4006314D0F1EE103AEFF354 -:103800000984683C4FF08073E361094BDB682366F1 -:1038100084F30988FFF712FC10B1064BA36110BDB9 -:10382000054BFBE783F3118810BD00BF00ED00E0FE -:1038300030EF00E0770600087A06000870470000C5 -:10384000FEE70000084A094B09498B4204D3094AA4 -:103850000021934205D3704752F8040F43F8040B3C -:10386000F3E743F8041BF4E7804000089039002098 -:1038700090390020903900207047000000F086B891 -:103880004FF08043002258631A610222DA607047C9 -:103890004FF080430022DA60704700004FF0804311 -:1038A000586370474FF08043586A70474B684360D5 -:1038B0008B688360CB68C3600B6943614B690362AB -:1038C0008B6943620B6803607047000008B51F4BAB -:1038D0001F481A6942F0FF021A611A6922F0FF02BA -:1038E0001A611A691A6B42F0FF021A631A6D42F0EC -:1038F000FF021A65174A1B6D1146FFF7D7FF1648DE -:1039000002F11C01FFF7D2FF144802F13801FFF762 -:10391000CDFF134802F15401FFF7C8FF114802F12F -:103920007001FFF7C3FF104802F18C01FFF7BEFFE3 -:103930000E4802F1A801FFF7B9FF0D4802F1C401DA -:10394000FFF7B4FFBDE8084000F0A4B8003802401B -:1039500000000240743F00080004024000080240DA -:10396000000C024000100240001402400018024007 -:10397000001C024008B500F019FAFFF78BFBBDE808 -:103980000840FFF7D5BE000070470000104B1A6CCE -:1039900042F001021A641A6E42F001021A660D4AE0 -:1039A0001B6E936843F0010393604FF08043312214 -:1039B0009A624FF0FF32DA6200229A615A63DA604B -:1039C0005A6001225A6108211A601C20FFF752B880 -:1039D00000380240002004E04FF0804208B513692F -:1039E000D1680B40D9B2C9439B07116107D5202389 -:1039F00083F31188FFF76EFB002383F3118808BD62 -:103A000008B5FFF7E9FFBDE80840FFF7EDBE00008D -:103A10001E4B1A6962F0FF021A611A69D2B21A616A -:103A20004FF0FF301A695A69586100215A6959618B -:103A30005A691A6A62F080521A621A6A02F0805257 -:103A40001A621A6A5A6A58625A6A59625A6A1A6C2F -:103A500042F080521A641A6E42F080521A661A6E50 -:103A60000B4A106840F480701060186F00F44070CA -:103A7000B0F5007F1EBF4FF4803018671967536898 -:103A800023F40073536000F071B900BF00380240A6 -:103A9000007000403C4B3D4A1A643D4A4FF440419F -:103AA00011601A6842F001021A601A689207FCD588 -:103AB0009A6822F003029A60334B19469A6812F012 -:103AC0000C02FBD1186800F0F90018609A601A68BF -:103AD00042F480321A600B689803FCD54B6F43F0B8 -:103AE00001034B67284B5A6F9207FCD5294A5A604D -:103AF0001A6842F080721A60254A53685804FCD54F -:103B0000214B1A4619688901FCD52349C3F8841052 -:103B1000196841F08061196013681B01FCD51F4BC7 -:103B200093600323C2F88C304FF00063C2F89430E6 -:103B30001B4B1A681B4B9A421B4B21D11B4A116825 -:103B40001B4A91421CD140F203121A60164A1368B4 -:103B500003F00F03032BFAD10B4B9A6842F00202D9 -:103B60009A609A6802F00C02082AFAD15A6C42F460 -:103B700080425A645A6E42F480425A665B6E7047C5 -:103B800040F20372E1E700BF003802400004001079 -:103B90000070004004194002083000240094883866 -:103BA000002004E011640020003C024000ED00E031 -:103BB00041C20F41084A08B5536911680B4003F030 -:103BC0000103536123B1054A13680BB1506898474C -:103BD000BDE80840FFF708BE003C01401039002056 -:103BE000084A08B5536911680B4003F0020353619A -:103BF00023B1054A93680BB1D0689847BDE80840E7 -:103C0000FFF7F2BD003C014010390020084A08B51A -:103C1000536911680B4003F00403536123B1054A53 -:103C200013690BB150699847BDE80840FFF7DCBD48 -:103C3000003C014010390020084A08B5536911685A -:103C40000B4003F00803536123B1054A93690BB19C -:103C5000D0699847BDE80840FFF7C6BD003C014069 -:103C600010390020084A08B5536911680B4003F069 -:103C70001003536123B1054A136A0BB1506A984788 -:103C8000BDE80840FFF7B0BD003C014010390020FE -:103C9000174B10B55C691A68144004F478725A61C5 -:103CA000A30604D5134A936A0BB1D06A98476006FD -:103CB00004D5104A136B0BB1506B9847210604D5FD -:103CC0000C4A936B0BB1D06B9847E20504D5094AB7 -:103CD000136C0BB1506C9847A30504D5054A936C3F -:103CE0000BB1D06C9847BDE81040FFF77DBD00BF19 -:103CF000003C0140103900201A4B10B55C691A686D -:103D0000144004F47C425A61620504D5164A136DCE -:103D10000BB1506D9847230504D5134A936D0BB131 -:103D2000D06D9847E00404D50F4A136E0BB1506E66 -:103D30009847A10404D50C4A936E0BB1D06E9847F6 -:103D4000620404D5084A136F0BB1506F98472304DF -:103D500004D5054A936F0BB1D06F9847BDE810406A -:103D6000FFF742BD003C014010390020062108B594 -:103D70000846FEF77FFE06210720FEF77BFE0621A0 -:103D80000820FEF777FE06210920FEF773FE0621C4 -:103D90000A20FEF76FFE06211720FEF76BFE0621B4 -:103DA0002820BDE80840FEF765BE000008B5FFF713 -:103DB0002FFE00F00BF8FEF773FEFFF775F8FFF724 -:103DC000E3FDBDE80840FFF759BD000000230449AA -:103DD0001A465A50C8180833802B4260F9D17047F0 -:103DE0001039002010B501390244904201D1002061 -:103DF00010BD10F8013B11F8014FA342F5D0181B7C -:103E000010BD00002DE9F8430746884691461E463E -:103E10008BB10D46A8EB0500B54207EB000402D2BA -:103E20000020BDE8F883324649462046FFF7DAFF16 -:103E300018B1013DEEE7BDE8F8832046BDE8F88300 -:103E4000034611F8012B03F8012B002AF9D1704722 -:103E500040A2E4F1646891064E6F20617070207397 -:103E600069670A00426164206677206C656E67743A -:103E7000682025750A0042616420626F6172645F88 -:103E800069642025752073686F756C6420626520F5 -:103E900025750A0042616420667720646573637249 -:103EA0006970746F72206C656E6774682025750A7E -:103EB00000426164206170702043524320307825B5 -:103EC0003038783A307825303878203078253038D6 -:103ED000783A3078253038780A00476F6F6420666A -:103EE00069726D776172650A000000006F72672E5B -:103EF0006172647570696C6F742E41524B5F4750EC -:103F00005300000000000000712E00085D2E000824 -:103F1000992E0008852E0008912E00087D2E00089D -:103F2000692E0008552E0008A52E00086D61696EE7 -:103F3000000000004C3F000858370020D038002017 -:103F400001000000913000080000000069646C6509 -:103F500000000000004000000040000000400000A1 -:103F6000004000000000010000000200000002000C -:103F700000000200A000902A00000000AAAAAAAA3D -:103F800050000024FFFB00000077000000900900B3 -:103F90000100000500000000AAAAAAA501000080F7 -:103FA000FFEF000000000000000000000000000023 -:103FB00000000000AAAAAAAA00000000FFFF00005B +:1000000000070020E5040008B915000839150008AC +:10001000911500083915000865150008E704000867 +:10002000E7040008E7040008E7040008993700081F +:10003000E7040008E7040008E7040008E7040008F4 +:10004000E7040008E7040008E7040008E7040008E4 +:10005000E7040008E7040008C53B0008F13B00087E +:100060001D3C0008493C0008753C0008E7040008F6 +:10007000E7040008E7040008E7040008E7040008B4 +:10008000E7040008E7040008E704000871250008F9 +:10009000DD2500083126000885260008A13C00085F +:1000A000E7040008E7040008E7040008E704000884 +:1000B000153A0008E7040008E7040008E704000810 +:1000C000E7040008E7040008E7040008E704000864 +:1000D000E7040008E70400081D290008E7040008F9 +:1000E000093D0008E7040008E7040008E7040008E9 +:1000F000E7040008E7040008E7040008E704000834 +:10010000E7040008E7040008E7040008E704000823 +:10011000E7040008E7040008E7040008E704000813 +:10012000E7040008E7040008E7040008E704000803 +:10013000E7040008E7040008E7040008E7040008F3 +:10014000E7040008E7040008E7040008E7040008E3 +:10015000E7040008E7040008E7040008E7040008D3 +:10016000E7040008E7040008E7040008E7040008C3 +:10017000E7040008E7040008E7040008E7040008B3 +:10018000E7040008E7040008E7040008E7040008A3 +:10019000E7040008E7040008E7040008E704000893 +:1001A000E7040008E7040008E7040008E704000883 +:1001B000E7040008E7040008E7040008E704000873 +:1001C000E7040008E7040008E7040008E704000863 +:1001D000E7040008E7040008E7040008E704000853 +:1001E00053B94AB9002908BF00281CBF4FF0FF319E +:1001F0004FF0FF3000F074B9ADF1080C6DE904CE9A +:1002000000F006F8DDF804E0DDE9022304B07047F1 +:100210002DE9F047089D04468E46002B4DD18A42B9 +:10022000944669D9B2FA82F252B101FA02F3C2F1EC +:10023000200120FA01F10CFA02FC41EA030E94407D +:100240004FEA1C48210CBEFBF8F61FFA8CF708FB9E +:1002500016E341EA034306FB07F199420AD91CEB76 +:10026000030306F1FF3080F01F81994240F21C81A8 +:10027000023E63445B1AA4B2B3FBF8F008FB1033F0 +:1002800044EA034400FB07F7A7420AD91CEB040425 +:1002900000F1FF3380F00A81A74240F207816444F5 +:1002A000023840EA0640E41B00261DB1D44000237A +:1002B000C5E900433146BDE8F0878B4209D9002DDE +:1002C00000F0EF800026C5E9000130463146BDE868 +:1002D000F087B3FA83F6002E4AD18B4202D38242D2 +:1002E00000F2F980841A61EB030301209E46002D81 +:1002F000E0D0C5E9004EDDE702B9FFDEB2FA82F2D6 +:10030000002A40F09280A1EB0C014FEA1C471FFA33 +:100310008CFE0126200CB1FBF7F307FB131140EA1A +:1003200001410EFB03F0884208D91CEB010103F1E7 +:10033000FF3802D2884200F2CB804346091AA4B2A9 +:10034000B1FBF7F007FB101144EA01440EFB00FE7D +:10035000A64508D91CEB040400F1FF3102D2A645E2 +:1003600000F2BB800846A4EB0E0440EA03409CE781 +:10037000C6F12007B34022FA07FC4CEA030C20FA2E +:1003800007F401FA06F31C43F9404FEA1C4900FA4E +:1003900006F3B1FBF9F8200C1FFA8CFE09FB1811CB +:1003A00040EA014108FB0EF0884202FA06F20BD93E +:1003B0001CEB010108F1FF3A80F08880884240F28E +:1003C0008580A8F102086144091AA4B2B1FBF9F0D2 +:1003D00009FB101144EA014100FB0EFE8E4508D9CD +:1003E0001CEB010100F1FF346CD28E456AD9023852 +:1003F000614440EA0840A0FB0294A1EB0E01A14237 +:10040000C846A64656D353D05DB1B3EB080261EBA4 +:100410000E0101FA07F722FA06F3F1401F43C5E97E +:10042000007100263146BDE8F087C2F12003D840B4 +:100430000CFA02FC21FA03F3914001434FEA1C47F6 +:100440001FFA8CFEB3FBF7F007FB10360B0C43EAE8 +:10045000064300FB0EF69E4204FA02F408D91CEB98 +:10046000030300F1FF382FD29E422DD90238634496 +:100470009B1B89B2B3FBF7F607FB163341EA034136 +:1004800006FB0EF38B4208D91CEB010106F1FF3885 +:1004900016D28B4214D9023E6144C91A46EA00467C +:1004A00038E72E46284605E70646E3E61846F8E60E +:1004B0004B45A9D2B9EB020864EB0C0E0138A3E757 +:1004C0004646EAE7204694E74046D1E7D0467BE738 +:1004D000023B614432E7304609E76444023842E7B0 +:1004E000704700BF02E000F000F8FEE772B63A483D +:1004F00080F30888394880F3098839484EF6085156 +:10050000CEF20001086040F20000CCF200004EF68E +:100510003471CEF200010860BFF34F8FBFF36F8FCD +:1005200040F20000C0F2F0004EF68851CEF2000119 +:100530000860BFF34F8FBFF36F8F4FF00000E1EE05 +:10054000100A4EF63C71CEF200010860062080F3DE +:100550001488BFF36F8F03F09FF903F07BF903F06A +:10056000C5F94FF055301F491B4A91423CBF41F835 +:10057000040BFAE71C49194A91423CBF41F8040BAD +:10058000FAE71A491A4A1B4B9A423EBF51F8040B2C +:1005900042F8040BF8E700201749184A91423CBF83 +:1005A00041F8040BFAE703F059F903F0EDF9144CA4 +:1005B000144DAC4203DA54F8041B8847F9E700F005 +:1005C00041F8114C114DAC4203DA54F8041B884732 +:1005D000F9E703F041B900000007002000230020E4 +:1005E00000000008000100200007002078400008FB +:1005F00000230020242300202823002098390020F5 +:10060000E0010008E0010008E0010008E001000846 +:100610002DE9F04F2DED108AC1F80CD0C3689D462E +:10062000BDEC108ABDE8F08F002383F311882846C3 +:10063000A047002002F086FDFEE702F00BFD00DF80 +:10064000FEE700002DE9F04103F044F8074603F00F +:100650008FF8054600283DD12B4B9F423AD00133FD +:100660009F423AD0294B27F0FF029A4239D1F8B283 +:1006700000F052FAA84642F2107400F055FC08B19E +:100680000024A04600F04EFA064670B37CBB4646F6 +:1006900035B11F4B9F4203D003F062F80024264679 +:1006A000002003F021F81B4B1B691B0422D40EB160 +:1006B00000F032F800F096FC00F07CFE00F07EFFC7 +:1006C0000546CCB100F07AFF401BA04214D900F0DF +:1006D00023F8F3E7A8460024CFE704464FF00108CB +:1006E000CBE780464FF47A74C7E70446D0E74FF46F +:1006F0007A74CDE70024DDE700F026FD4FF47A7030 +:1007000002F026FDDDE700BF010007B0000008B0E1 +:10071000263A09B0000402401E4B1F4A10B51C4681 +:100720001968013134D004339342F9D162681B4B0C +:100730009A422DD91A4B9B6803F1006303F580336D +:100740009A4225D202F0E0FF02F0F2FF002000F012 +:100750004BFE144B0220187000F082FE124B1A6CF4 +:1007600000221A64196E1A66196E596C5A64596E11 +:100770005A665B6E72B64FF0E0232021C3F8084D35 +:10078000D4E9003281F311889D4683F3088810472D +:1007900010BD00BF0000010820000108FFFF000895 +:1007A000002300202823002000380240094A136853 +:1007B00049F2690099B21B0C00FB01331360064B30 +:1007C000186844F2506182B2000C01FB020018600C +:1007D00080B27047202300201C23002010B5002188 +:1007E0001022044600F058FE034B03CB20606160EA +:1007F0001868A06010BD00BF107AFF1F2DE9F043FC +:10080000224DBBB000F0DAFEAB6840F2ED22C31A15 +:10081000934232D906AFA8602B46282200213846E1 +:1008200001F0DAFB05F10E0000F02EFE0026044672 +:100830005FFA80F905F10E08F3B2F100994501F174 +:10084000280107D908EB06030822384601F0C4FB4B +:100850000136F1E708230122CDE9023205340C4BC1 +:100860000193A4B230230093CDE9047405A3D3E926 +:100870000023297B074801F0C7F93BB0BDE8F083AE +:10088000AFF3008078F6339F93CACD8D703300208C +:100890007D3300204433002070B50D4614461E46BB +:1008A00001F048F950B9022E10D1012C0ED112A33B +:1008B000D3E90023C5E90023012007E0282C10D04C +:1008C00005D8012C09D0052C0FD0002070BD302C8C +:1008D000FBD10BA3D3E90023ECE70BA3D3E900235F +:1008E000E8E70BA3D3E90023E4E70BA3D3E9002354 +:1008F000E0E700BFAFF30080401DA12026812A0B56 +:1009000078F6339F93CACD8D9E6AC421818A46EEC4 +:1009100026417272DF25D7B7F017304A39059E5647 +:1009200013B504462346084620220021019001F019 +:1009300053FB22790198032A234628BF032203F898 +:10094000042F2021022201F047FB62790198072A37 +:10095000234628BF072203F8052F2221032201F096 +:100960003BFBA2790198072A234628BF072203F8F8 +:10097000062F2521032201F02FFB019804F1080323 +:100980001022282101F028FB382002B010BD000001 +:100990002DE9F04FFFB01FAD0CAE40F2751280464E +:1009A0000F4620A80021296000F076FD4822002192 +:1009B000304600F071FD00F001FE554B4FF47A72A5 +:1009C000B0FBF2F0186093E80700012386E8070007 +:1009D0000DF152003382FFF701FF4FF4A24333843D +:1009E00006AB18464B4903F039FA15223064294604 +:1009F000304686F83C20FFF793FF10AB04460146D3 +:100A00000822284601F0E8FA0822A1180DF1410356 +:100A1000284601F0E1FA0DF14203082204F1100129 +:100A2000284601F0D9FA11AB202204F1180128461A +:100A300001F0D2FA12AB402204F13801284601F04D +:100A4000CBFA14AB082204F17801284601F0C4FA6D +:100A50000DF15103082204F18001284601F0BCFA8F +:100A600004F1880A0DF1520904F5847B4B46514686 +:100A7000082228460AF1080A01F0AEFAD34509F126 +:100A80000109F3D119AB08225946284601F0A4FA0E +:100A900004F588744FF0000996F834304B450AD9B4 +:100AA000B36B21464B440822284601F095FA0834DE +:100AB00009F10109F0E74FF0000996F83C304B4589 +:100AC00004EBC90108D9336C08224B44284601F0D5 +:100AD00083FA09F10109F0E700230393BB7E029337 +:100AE000073107F119030193C1F3CF010123CDE9C8 +:100AF00004510093F97E04A3D3E90023404601F09A +:100B000083F87FB0BDE8F08F9E6AC421818A46EEEB +:100B10002C2300206C3E0008014B1870704700BF6A +:100B200038230020F0B5324B1C7B85B034B1314BFB +:100B30000E221A810024204605B0F0BD2E4A10680E +:100B4000516802AB03C308232C492D480DEB030267 +:100B500003F062F9054630B9264B2A480A221A8169 +:100B600000F0E6FCE6E70169B1F5E02F06D9214B7C +:100B700025480B221A8100F0DBFCDCE7438B512B6C +:100B800008D01C4A21480C2111815122194600F03D +:100B9000CFFCD0E71E4A024402F11003994204D26E +:100BA000144B1C4810221A81E5E710398E1A204692 +:100BB000134900F007FD3246074605F118012046AB +:100BC00000F000FDAB689F4202D1EB6898420AD06A +:100BD000084B0D221A810090D5E902123B460E48BF +:100BE00000F0A6FCA6E70D4800F0A2FC0124A2E755 +:100BF000703300202C230020153F0008DCFF060086 +:100C000000000108843E0008903E0008A23E000853 +:100C10000800FFF7C03E0008DD3E0008063F000860 +:100C20002DE9F04FADB006AF80460C4600F082FFD4 +:100C3000054600285AD1237E022B1BD1E38A012BC3 +:100C400018D100F0BBFC0646FFF7B0FD03464FF499 +:100C5000C870DFF8D092B3FBF0F206F5167602FB0F +:100C6000103316FA83F3C9F80030E37E33B9A84B8A +:100C700000221A709C37BD46BDE8F08FA38AEEB201 +:100C8000013BB34205F101050BD93B1D1E44E900B0 +:100C900000960023082201F0F801204601F060F8D8 +:100CA000ECE707F11400FFF799FD324607F1140154 +:100CB000381D03F0A1F80028D9D10F2E08D8944B85 +:100CC0001E70D9F80030A3F51673C9F80030D1E7CB +:100CD000FB1CF8700146009307220346204601F0F2 +:100CE0003FF8F978404600F01DFFC3E7E38A282B60 +:100CF00026D010D8012B1ED0052BBBD1BFF34F8FB0 +:100D00008449854BCA6802F4E0621343CB60BFF3A9 +:100D10004F8F00BFFDE7302BACD1637E7F4D013399 +:100D20006A7BDBB29342E94603D1E27E2B7B9A4297 +:100D300065D0CD469EE721464046FFF729FE99E75C +:100D4000A38A013B9BB2C92B94D8744D2E7B26BB42 +:100D500005F10C030093082233463146204600F08B +:100D6000FFFF731CF2B2D9001E46A38A013B9A42D0 +:100D700005DA0E322A44009200230822EEE700230F +:100D80000022C5E900230023AB6085F8D730C5F801 +:100D9000D8302B7B0BB9E37E2B73002507F11409A8 +:100DA0003B1D082229464846C7E90155FD6001F070 +:100DB00013F93B7A05F1010AAB424FEACA0608D99A +:100DC000FB6808222B443146484601F005F9554698 +:100DD000EFE7C6F3CF06E17ECDE904960023039347 +:100DE000A37E0293193428230093019446A3D3E9E8 +:100DF0000023404600F008FFFFF700FD3AE74FF000 +:100E0000000807F11403A7F814801022009341464C +:100E10000123204600F0A4FFA68A023EB6B2F31CCE +:100E20009B109B000733DB08A9EBC3039D460DF124 +:100E3000180A1FFA88F34FEAC801B34201F1100102 +:100E40000AD20AEB0803009308220023204600F090 +:100E500087FF08F10108ECE795F8D70000F0CEFA1B +:100E6000D5F8D83004461BB995F8D70000F0D6FA6B +:100E7000D5F8D83033449C4204D295F8D7000130DD +:100E800000F0CCFA4FEA960B4FF000081FFA88F1F9 +:100E90008B45D5E9003209D90AEB880103EB8800BC +:100EA000012200F001FB08F10108EFE7F31842F11D +:100EB0000002C5E90032D5F8D83095F8D70006EB26 +:100EC0000308C5F8D88000F099FA804509D395F851 +:100ED000D730D5F8D8000133001B85F8D730C5F8D6 +:100EE000D800FF2E08D800232B7300F0A9FAFFF7D3 +:100EF00019FE08B1FFF710FC2B68094A9B0A013361 +:100F000013810023AB6014E726417272DF25D7B747 +:100F10003D33002000ED00E00400FA0570330020AE +:100F20002C2300204033002030B54FF00054244BD8 +:100F300022689A4285B007D002F024FC0446A8B982 +:100F40000024204605B030BD1E4B627D1A701E483D +:100F5000237D03731D49C9220E3000F08BFA204611 +:100F6000E022002100F098FA0124EAE7184A194D1E +:100F7000136C43F000731364AA6D174B9A42DFD1D0 +:100F80002B6E013B7E2BDBD8144A07CA01AB83E8EA +:100F900007001846032100F02BFB6B6D83424FF0D6 +:100FA0000003CDD12A6D8A4201BFAB65054B2A6E85 +:100FB0001A7003BF0A4BEA6D1A601C46C1E700BFF6 +:100FC0009AAD44C53823002070330020160000205D +:100FD00000380240006600405041A0B05866004012 +:100FE000182300202DE9FF474B4C02236371002397 +:100FF00002934A4BD3F800C0BCF57A7F12D3484B1A +:10100000484FB7FBFCF69C458CBF0A231123581EA2 +:10101000B6FBF3F503FB1562C1B2002A3ED00228ED +:101020000346F4D89DF80B303F4940485A1E9DF8BE +:101030000A30013B1B0443EA0253BDF80820013A81 +:1010400013434B6001F026FD00230193384B3949CF +:1010500000933948394B4FF4805200F03DFD384B36 +:10106000197811B1344800F05DFD00F0A7FA05468B +:10107000FFF79CFB4FF4C873B0FBF3F202FB1303C2 +:1010800005F5167010FA83F02E4B186002F070FB15 +:1010900008B10F23238104B0BDE8F0876B1EB3F5C0 +:1010A000806FBFD2C1EBC10E0EF103034FEAE3091B +:1010B000C3F3C703A1EB030809F1010A4FF47A70E7 +:1010C0005FFA88F609FB00005AFA88F8B0FBF8F0DE +:1010D000B0F5617F08D90EF1FF33C3F3C703C91A16 +:1010E000CEB2591E0F2914D8721E072A8CBF0022B7 +:1010F0000122991901FB0551B7FBF1F7BC4591D1CC +:10110000002A8FD0ADF808508DF80A308DF80B60AA +:1011100088E71346EDE700BF2C23002018230020AA +:101120003F420F0040787D011023002088340020CA +:10113000990800083C23002044330020210C0008BB +:1011400038230020403300202DE9F04F91A7D7E944 +:1011500000670FF24829D9E90089874D93B0DFF87D +:1011600044B2864C284600F0B3FD0DF1300A0790DA +:1011700070B310220021504600F08EF9079B197BB6 +:101180004FF0000261F303028DF83020586899682F +:101190000EAA03C21B680D9A63F31C029DF830303F +:1011A0000D9243F020038DF830300023524619464B +:1011B000584601F07FFC079028B9284600F08CFDC6 +:1011C000079B2370CEE72378072B3CD8013323708D +:1011D00018220021504600F05FF9DFF8C8B1684CD2 +:1011E000002319465246584601F08CFC014670BB5C +:1011F000102208A800F050F9636983F480636361EA +:1012000000F0DEF90B4612A9024611E903000DF1C8 +:10121000240C8CE803009DF83410C1F30300890608 +:101220004CBF0E99BDF838C08DF82C0046BFC1F3F5 +:101230001C0C4CF00041CCF30A010891284608A987 +:1012400000F012FFCCE7284600F046FDC0E7284634 +:1012500000F070FC0446002848D1DFF84CB100F0E3 +:10126000ADF9DBF80030984240D300F0A7F90790C1 +:10127000FFF79CFA079A8DF8204003464FF4C87098 +:1012800002F51672B3FBF0F101FB103312FA83F38F +:10129000CBF80030DFF814B19BF8001011B901232E +:1012A0008DF8203050460791FFF798FA0799C1F161 +:1012B0001004E4B2062C28BF0624224651440DF146 +:1012C000210000F0D7F808AB0393182302930134F0 +:1012D0002C4B0193E4B20123009304943B46324625 +:1012E000284600F029FC00238BF8003000F066F956 +:1012F000254A264C1368C31AB3F57A7F31D31060A0 +:1013000000F05EF902460B46284600F0EFFC284646 +:1013100000F010FC28B3237BDFF894B0002B14BF3F +:10132000032302238BF8053000F048F94FF47A7359 +:101330005146B0FBF3F0CBF800005846FFF7F0FA47 +:10134000182307300293124B0193C0F3CF0040F2F1 +:101350005513CDE903A0009342464B46284600F0C2 +:10136000EBFB237B2BB1FFF749FA237B002B7FF4A8 +:10137000F6AE13B0BDE8F08F4433002055340020A2 +:10138000000002403C330020503400207033002025 +:1013900054340020401DA12026812A0BF1C6A7C18C +:1013A000D068080F88340020403300203D330020EF +:1013B0002C23002070B502F02DF8094E094D308025 +:1013C000002428683388834208D902F01DF82B686E +:1013D00004440133B4F5803F2B60F2D370BD00BFED +:1013E000843400205834002002F0D8B800F10060A6 +:1013F000920000F5803002F05BB80000054B1A68DF +:10140000054B1B889B1A834202D9104401F0FCBF94 +:1014100000207047583400208434002038B5074D30 +:1014200004462868204401F0F7FF28B928682044C2 +:10143000BDE8384002F008B838BD00BF583400207D +:10144000064991F8243033B10023086A81F824302A +:101450000822FFF7CBBF0120704700BF5C3400209B +:10146000022802BF024B4FF480629A61704700BFAE +:101470000000024010B50023934203D0CC5CC4545A +:101480000133F9E710BD000003460246D01A12F9F5 +:10149000011B0029FAD1704702440346934202D04F +:1014A00003F8011BFAE770472DE9F8431F4D144676 +:1014B00095F824200746884652BBDFF870909CB30D +:1014C00095F824302BB92022FF2148462F62FFF7E0 +:1014D000E3FF95F82400C0F10802A24228BF22468B +:1014E000D6B24146920005EB8000FFF7C3FF95F8A6 +:1014F0002430A41B1E44F6B2082E17449044E4B2D4 +:1015000085F82460DBD1FFF79BFF0028D7D108E0E6 +:101510002B6A03EB82038342CFD0FFF791FF0028B1 +:10152000CBD10020BDE8F8830120FBE75C3400202C +:101530000FB4002004B0704700B59BB0EFF30981F1 +:1015400068226846FFF796FFEFF30583044B9A6B1A +:10155000DA6A9A6A9A6A9A6A9A6A9A6A9B6AFEE749 +:1015600000ED00E000B59BB0EFF30981682268460A +:10157000FFF780FFEFF30583044B9A6B9A6A9A6A30 +:101580009A6A9A6A9A6A9B6AFEE700BF00ED00E0D9 +:1015900000B59BB0EFF3098168226846FFF76AFF48 +:1015A000EFF30583034B5A6B9A6A9A6A9A6A9A6AAE +:1015B0009B6AFEE700ED00E0FEE7000002F028B8BD +:1015C00002F000B830B5094D0A4491420DD011F82F +:1015D000013B5840082340F30004013B2C4013F02A +:1015E000FF0384EA5000F6D1EFE730BD2083B8ED69 +:1015F000F7B54FF0FF33DFF854C0DFF854E000EBED +:1016000081011A4688421CD050F8044B019401AF66 +:10161000042417F8015B82EA05620825DB181646E8 +:1016200005F1FF355241002EBCBF83EA0C0382EA6C +:101630000E0215F0FF05F1D1013C14F0FF04E8D1D2 +:10164000E0E7D843D14303B0F0BD00BF9336EAA929 +:10165000EBE1F0422DE9F041C56915B9C161BDE882 +:10166000F0814B6823F06047C3F38A464FEAD37E8C +:10167000C3F3807816EA230638BF3E46AC462B46B5 +:101680005A68BEEBD27F22F060440AD0002A18DAF2 +:10169000A40CB44217D19D420FD10D60DEE7134672 +:1016A000EEE7A74207D102F08044C2F380724245C0 +:1016B0000BD054B1EFE708D2EDE7CCF800100B6087 +:1016C000CDE7B44201D0B442E5D81A689C46002A5E +:1016D000E5D11960C3E700002DE9F047089D01F04E +:1016E00007044FEAD508224405F0070500EBD100B6 +:1016F0004FF47F49944201D1BDE8F08704F0070719 +:1017000005F0070A57453E4638BF5646C6F108065B +:10171000111B8E4228BF0E46E10808EBD50E415C36 +:1017200013F80EC0B94029FA06F721FA0AF1FFB200 +:101730008CEA010147FA0AF739408CEA010C03F8F8 +:101740000EC034443544D5E780EA0120082341F235 +:10175000210201B24000002980B203F1FF33B8BF7B +:10176000504013F0FF03F4D17047000038B50C4629 +:101770008D18A54200D138BD14F8011BFFF7E4FF16 +:10178000F7E7000002684AB113680360C388018963 +:1017900001339BB29942C38038BF03811046704722 +:1017A00070B588B0202204460D4668460021FFF738 +:1017B00073FE20460495FFF7E5FF024658B16B46DD +:1017C000054608AE1C4603CCB44228606960234637 +:1017D00005F10805F6D1104608B070BD082817D9E4 +:1017E00009280CD00A280CD00B280CD00C280CD0BF +:1017F0000D280CD00E2814BF4020302070470C203C +:101800007047102070471420704718207047202020 +:1018100070470000082817D90C280CD910280CD9BB +:1018200014280CD918280CD920280CD930288CBFA2 +:101830000F200E207047092070470A2070470B20A8 +:1018400070470C2070470D207047000010B54B68A2 +:1018500023B9CA8A63F30902CA8210BDC4681A6830 +:101860001C60C360438A013B43824A60EFE700008B +:101870002DE9F84F1D46CB8A0F46C3F3090106290F +:10188000814692460B4630D00020AAB207F11904D7 +:101890009EB2052E1FFA80F80FD8904503F1010380 +:1018A00006D3FB8A0A4462F30903FB8201201AE093 +:1018B0001AF80060E6540130EAE79045F1D2A1F150 +:1018C000060B1C237C68BBFBF3F203FB12BB1FFA65 +:1018D0008BF6002C45D14846FFF754FF044638B933 +:1018E00078606FF00200BDE8F88F4FF00008E6E77F +:1018F000002606607860ADB24FF0000B454510D968 +:101900000AEB0803221D13F8011B9155B1B208F12F +:1019100001081B291FFA88F82BD0454506F101065E +:10192000F1D8FB8AC3F30902154465F30903BCE748 +:10193000013292B21C462368002BF9D1AB1F0B4435 +:101940001C21B3FBF1F301339BB29A42D3D2BBF11A +:10195000000FD0D14846FFF715FF20B9C4F800B0FA +:10196000BFE70122E7E7C0F800B05E46206004460A +:10197000C1E74545D5D94846FFF704FF08B92060BF +:10198000AFE7C0F800B0002620600446B6E70000CC +:101990002DE9F04F2DED028B83B0CDE90013BDF89A +:1019A0003C5007469146002A00F092802DB10E9BD4 +:1019B000002B00F08D80072D32D807F10C00FFF7C7 +:1019C000E1FE044638B96FF00204204603B0BDECD6 +:1019D000028BBDE8F08F14220021FFF75DFD0E9908 +:1019E0002A4604F10800FFF745FD681CC0B2FFF766 +:1019F00011FFFFF7F3FE207499F80030013814FA54 +:101A000080F003F01F0363F03F030372009B43F079 +:101A10000041616038462146FFF71CFE0124D4E7EF +:101A200000F10C034FF0000808EE103A4FF0800A66 +:101A30004646444618EE100AFFF7A4FE83460028E7 +:101A4000C1D014220021FFF727FDC6BB019BABF8D4 +:101A5000083002200E9B00F1080299195BFA82F20D +:101A60000130C0B2082801D0AE422AD3FFF7D2FE1F +:101A7000FFF7B4FE99F80020009B411E02F01F0200 +:101A800042EA4812AE4208BF4FF0400A5BFA81F1C9 +:101A90004AEA020A43F0004281F808A08BF81000DD +:101AA000CBF8042059463846FFF7D4FD0134AE4246 +:101AB00024B288F001084FF0000ABBD185E700206E +:101AC000C8E711F801CB02F801CB0136B6B2C7E77F +:101AD0006FF0010479E70000F8B515460E4628229C +:101AE000002104461F46FFF7D7FC069B6360B5F54F +:101AF000001F079BA76034BF6A094FF6FF7223627D +:101B000004F10C0097B200239A4205D80023036029 +:101B100027826382A382F8BD0660013330462036F7 +:101B2000F2E7000003781BB94BB2002BC8BF01706D +:101B300070470000007870472DE9F74FDDF83C90C2 +:101B4000BDF830500D9E9DF83840BDF8407080467D +:101B500092469B46B9F1000F01D1002F51D11F2CA5 +:101B60004FD898F80000B0B9072F47D835F00303D5 +:101B700047D13A4649464FF6FF70FFF7F7FD20F090 +:101B800001002D02400445EA0464400C44EA40246C +:101B90004FF6FF7321E040EA0520072F40EA046476 +:101BA000F6D900254FF6FF73C5F12000A5F12002FC +:101BB0002AFA05F10BFA00F001432BFA02F2114365 +:101BC0001846C9B2FFF7C0FD0835402D0346EBD1DA +:101BD0003A464946FFF7CAFD0346CDE9009732462B +:101BE00021464046FFF7D4FE33780133DBB21F2B8A +:101BF00088BF0023337003B0BDE8F08F6FF003009F +:101C0000F9E76FF00100F6E72DE9F04F85B0924655 +:101C1000DDF848800F9D9DF840209DF84490BDF868 +:101C20004C7006469B46B8F1000F01D1002F48D1F9 +:101C30001F2A46D83378002B46D00C0244EA0264AF +:101C40009DF8381044EAC93444EA01441C43072F84 +:101C500044F0800432D900234FF6FF72C3F1200C08 +:101C6000A3F120002AFA03F10BFA0CFC41EA0C0163 +:101C70002BFA00F00143C9B210460393FFF764FD4D +:101C8000039B0833402B0246E8D13A464146FFF712 +:101C90006DFD0346CDE900872A4621463046FFF711 +:101CA00077FEB9F1010F06D12B780133DBB21F2B80 +:101CB00088BF00232B7005B0BDE8F08F4FF6FF738F +:101CC000E8E76FF00100F6E76FF00300F3E70000CC +:101CD000C06900B104307047C3691A68C261C26844 +:101CE0001A60C360438A013B438270472DE9F0418B +:101CF000D0F81880194E14461D464146002709B9F0 +:101D0000BDE8F081D1E90223A21A65EB03039642F4 +:101D100077EB03031ED283698B420DD1FFF796FD4B +:101D200083691B688361C3680B60438AC1608169F2 +:101D3000013B43828846E2E7FFF788FD0B68C8F85D +:101D40000030C3680B60438AC160013B4382D8F80E +:101D50000010D4E788460968D1E700BF80841E00E0 +:101D60002DE9F04F8BB00D46DDF8509014469B46A0 +:101D70008046002800F01981B9F1000F00F01581AC +:101D8000531E3F2B00F21181012A03D1BBF1000F3A +:101D900040F00B810023CDE90833B8F81430B5EBDF +:101DA000C30F4FEAC30703D300200BB0BDE8F08F89 +:101DB0002B199F42D8F80C303ABF7F1BFFB2274641 +:101DC0001BB9D8F81030002B7AD02F2D4ED8C5F182 +:101DD0003006B7424FF000032CBFF6B23E460093E8 +:101DE0002946D8F8080008AB3246FFF775FCA7EB88 +:101DF000060A35445FFA8AFAB8F8143003F1005342 +:101E0000063BDB000493D8F80C3003933021039B8E +:101E100013B1BAF1000F2CD1D8F8100040B1BAF1CB +:101E2000000F05D0009608AB5246691AFFF754FC24 +:101E300038B2002FB8D066070AD00AAB03EBD40142 +:101E4000624211F8083C02F00702134101F8083C15 +:101E5000082C3CD9102C40F2B580202C40F2B780E1 +:101E6000BBF1000F00F09C80082334E0BA46002646 +:101E7000C2E7049BE02B28BFE02306930B44AB4250 +:101E8000059314D95A1B03980096924534BF5246C5 +:101E9000D2B2691A08AB04300792FFF71DFC079A0B +:101EA0001644AAEB020A1544F6B25FFA8AFA049BBA +:101EB000069A05999B1A0493039B1B680393A6E754 +:101EC0000093D8F8080008AB3A462946AEE7BBF1C4 +:101ED000000F13D00123B4EBC30F6CD0082C12D821 +:101EE0009DF82030621E23FA02F2D50706D54FF086 +:101EF000FF3202FA04F423438DF820309DF820309D +:101F000089F8003051E7102C12D8BDF82030621E3D +:101F100023FA02F2D10706D54FF0FF3202FA04F499 +:101F20002343ADF82030BDF82030A9F800303CE75D +:101F3000202C0FD80899631E21FA03F3DA0705D580 +:101F40004FF0FF3202FA04F40C430894089BC9F8DE +:101F500000302AE7402C2BD0DDE90865611EC4F172 +:101F60002102A4F1210326FA01F105FA02F225FA71 +:101F700003F311431943CB0712D50122A4F1200327 +:101F8000C4F1200102FA03F322FA01F1A240524205 +:101F900043EA010363EB430332432B43CDE90823B8 +:101FA000DDE90823C9E90023FFE66FF00100FCE644 +:101FB0006FF00800F9E6082CA0D9102CB3D9202C1A +:101FC000EED8C3E7BBF1000FADD0022383E7BBF12E +:101FD000000FBBD004237EE730B5012A144638BF7A +:101FE0000124402C85B028BF40240025012ACDE9DA +:101FF000025518D81B788DF8083063070AD004AB57 +:1020000003EBD405624215F8083C02F00702934046 +:1020100005F8083C009103462246002102A8FFF77C +:102020005BFB05B030BD082AE4D9102A03D81B8811 +:10203000ADF80830E1E7202A8DBFD3E900231B6803 +:102040000293CDE90223D8E710B5CB681BB98B60AA +:102050000B618B8210BDC4681A681C60C360438A20 +:10206000013B4382CA60F0E72DE9F04FD1F80080D0 +:1020700093B018F0800FCDE90323C8F3C01219BF45 +:10208000C8F3C03BC8F306264FF0020B1646B8F162 +:10209000000F04460D4680F2D18118F0C04305932D +:1020A00040F0CC810B7B002B00F0C881BBF1020F0C +:1020B00003D00178B14240F0C48108F07F0106915D +:1020C0006AB3C8F3074A2B44069A93F8039076063E +:1020D00046EA0B4646EA82465FEAD91346EA0A0612 +:1020E000079300F0908000220023CDE90A23069B8D +:1020F000009367685B4652460AA92046B847002805 +:102100007ED0A7699FB9314604F10C00FFF748FB68 +:102110000746E0B96FF0020013B0BDE8F08FC8F3D6 +:102120000F2A18F07F0F08BF0AF0030ACBE73B69BC +:102130009E420DD03F68002FF9D1314604F10C00CA +:10214000FFF72EFB07460028E4D0A3693B60A76198 +:10215000DDE90A2300264FF6FF70C6F1200E22FAB1 +:1021600006F103FA0EFEA6F1200C23FA0CFC41EA5C +:102170000E0141EA0C01C9B2083609920893FFF733 +:10218000E3FA402EDDE90832E7D1B882FB7D09F0A1 +:102190001F06C3F384039B1BD7E9022198B2002BCF +:1021A000BCBF00F120031BB252EA0100C8F304686F +:1021B0000FD00398821A049860EB0101A74890425F +:1021C0004FF000028A4104D3079A002A5BD0012B0A +:1021D00023DDFA7D4FEA890302F0030203F07C035A +:1021E0001343FB7539462046FFF730FB079BA3B925 +:1021F000FB7DC3F38402013262F38603FB7504E0C6 +:102200006FF00B0088E7A76917B96FF00C0083E740 +:102210003B699E42BAD03F68F6E719F0400F32D0D2 +:10222000039BBB60049BFB60142200210DA8FFF7F9 +:1022300033F9039B0A93049B0B932B1D0C932B7B6D +:10224000ADF83EA0013BDBB2ADF83C30069B8DF80B +:10225000433094F824308DF840B083F001038DF8BA +:1022600044308DF84160A3688DF842800AA9204669 +:102270009847FB7DC3F38403013303F01F039B02E4 +:10228000FB82002048E7FB7DC9F34012B2EBD31F6D +:1022900040F0DA80C3F38403B34240F0D88007995A +:1022A0002B7B4FEA9912002934D0D20741D4032B5B +:1022B00040F2D080039BBB60049BFB602B7BAE1D78 +:1022C000033BDBB23246394604F10C00FFF7D0FA8B +:1022D00000280DDA20463946FFF7B8FAFB7DC3F334 +:1022E0008403013303F01F039B02FB82032013E7E7 +:1022F000AB883B832A7B033AB88AD2B23146FFF7D8 +:1023000035FAFB7DB882DA43C2F3C01262F3C71319 +:10231000FB75B6E76AB92E1D013BDBB23246394682 +:1023200004F10C00FFF7A4FA0028D3DB2A7B013A62 +:10233000E2E7F98AC1F30901013B0529DAB259D86C +:10234000281D002307F11A0C9A4208D910F801EB56 +:102350000CF801E0013101330629DBB2F4D1039915 +:102360000A9104990B91934207F11A010C9138BF1D +:10237000043379680D9134BF55FA83F300230E932B +:10238000FB8AADF83EA0C3F309031A44069B8DF8FF +:10239000433094F82430ADF83C2083F001038DF8ED +:1023A000443000238DF840B08DF841608DF84280B4 +:1023B0007B602A7BB88A013A291DFFF7D7F93B8B4E +:1023C000B882834203D1A3680AA9204698472046D1 +:1023D0000AA9FFF739FEFB7DB88AC3F384030133F2 +:1023E00003F01F039B02FB823B8B984214BF11201A +:1023F000002091E67B68002BB1D0062001E01C3064 +:102400006346D3F800C0BCF1000FF8D1091A081DCB +:1024100005F1040C00EB030905989DF8143001EB5D +:10242000000EBEF11B0F9AD89A4298D91CF8013BB6 +:1024300009F8013B059B01330593EDE76FF00900B7 +:102440006AE66FF00A0067E66FF00D0064E66FF071 +:102450000E0061E66FF00F005EE600BF80841E0094 +:10246000404BF0B51C6C404E44F000741C641D6E73 +:1024700045F000751D661B6E3C4B9B6AD3F80052FD +:10248000354045F00105C3F80052D3F8004234400E +:1024900044EA002040F00100C3F80002002952D0B5 +:1024A0000020C3F81C020546C3F80402C3F80C025E +:1024B000C3F8140203EBC00401301C28C4F84052D6 +:1024C000C4F84452F6D100254FF0010C96781488D8 +:1024D000F70748BFD3F804720CFA04F044BF07436F +:1024E000C3F80472B70742BFD3F80C720743C3F8AE +:1024F0000C72760742BFD3F814620643C3F8146225 +:1025000003EBC4045668C4F840629668C4F8446299 +:10251000D3F81C4201352043A942C3F81C0202F142 +:102520000C02D3D1D3F8002222F00102C3F800221A +:102530000C4B1A6C22F000721A641A6E22F00072B0 +:102540001A661B6EF0BD0122C3F84012C3F8441294 +:10255000C3F80412C3F81412C3F80C22C3F81C22E7 +:10256000E0E700BF003802400000FFFF8834002091 +:10257000184A916A08B58B688B6013F0010104D08A +:1025800013F00C0F18BF4FF48031D80506D513F4A3 +:10259000406F14BF41F4003141F00201D80306D569 +:1025A00013F4402F14BF41F4802141F00401D3699A +:1025B0000BB108489847202383F31188064800216F +:1025C00000F0EEFD002383F31188BDE8084001F020 +:1025D00017B900BF883400209034002038B5124C61 +:1025E000A36ADD68AA0712D05A6922F002025A6172 +:1025F000A36913B1012120469847202383F3118852 +:102600000A48002100F0CCFD002383F31188EB067B +:1026100006D5A36A1021D960236A0BB102489847F6 +:10262000BDE8384001F0ECB8883400209834002030 +:1026300038B5124CA36A1D69AA0712D05A6922F054 +:1026400010025A61A36913B1022120469847202342 +:1026500083F311880A48002100F0A2FD002383F3D0 +:102660001188EB0606D5A36A10211961236A0BB104 +:1026700002489847BDE8384001F0C2B888340020CD +:102680009834002038B50F4CA36A5D685D602A0756 +:102690000AD5042222701A6822F002021A60636AC4 +:1026A00013B10021204698476B0706D5A36A9969A4 +:1026B000236A13B1034809049847BDE8384001F084 +:1026C0009FB800BF8834002010B50E4C204600F0A3 +:1026D000CFF90D4BA3620B21132000F0B1F90B21B0 +:1026E000142000F0ADF90B21152000F0A9F90B2101 +:1026F000162000F0A5F90022BDE8104011460E207A +:10270000FFF7AEBE8834002000640040114B9842B1 +:1027100010B5044609D1104B1A6C42F000721A64CD +:102720001A6E42F000721A661B6EA36A01221A60CA +:10273000A36A5A68D20707D5626851681268D961DE +:102740001A60064A5A6110BD0121082000F01EFCE3 +:10275000EEE700BF88340020003802405B870100AC +:1027600003291AD8DFE801F0020A0F14836A9B6874 +:1027700013F0E05F14BF012000207047836A98685F +:10278000C0F380607047836A9868C0F3C060704788 +:10279000836A9868C0F3007070470020704700009B +:1027A00010B5032925D8DFE801F00225292D836A19 +:1027B0009968C1F30161183103EB011310788406A5 +:1027C0004CBF54689488C0F300114FEA410148BFE0 +:1027D00041EAC40100F00F004CBF41F0040141EA9E +:1027E0004451586041F001019068D2689860DA6005 +:1027F000196010BD836A03F5C073DFE7836A03F5D0 +:10280000C873DBE7836A03F5D073D7E701290AD0E1 +:1028100002290FD081B9836ADA68920701D1186959 +:1028200003E001207047836AD86810F0030018BFE6 +:1028300001207047836AF2E70020704710B539B96C +:10284000836AD96889071BD11B699C0704D110BD15 +:10285000012915D00229FAD1816AD1F8C031D1F805 +:10286000C441D1F8C8011061D1F8CC0150612020D9 +:1028700008610869800717D1486940F0100012E02C +:10288000816AD1F8B031D1F8B441D1F8B801106102 +:10289000D1F8BC0150612020C860C868800703D10E +:1028A000486940F002004861C3F34000C3F380016F +:1028B000000140EA4111107920F03000014311710C +:1028C00089064BBF91681189DB085B0D4CBF63F330 +:1028D0001C0163F30A01137948BF916064F3030399 +:1028E00013714FEA14234FEA144458BF1181137037 +:1028F0005480ACE7024AD36843F0C003D36070470A +:1029000000440040044B5A6810439A6858600AB16A +:10291000181D1047704700BFB43400202DE9F04166 +:102920003C4ED6F85C52EF682B68DA059CB20CD5A9 +:10293000202383F311884FF40070FFF7E3FF6FF457 +:1029400080732B60002383F31188202383F3118885 +:10295000DFF8C08014F02F0339D183F311883806D3 +:1029600013D5210611D5202383F311882A4800F0BE +:1029700001FA00284CDA0820FFF7C4FF4FF67F73F6 +:102980003B40EB60002383F311887A0615D563067C +:1029900013D5202383F31188D6E913239A4209D152 +:1029A000336C3BB127F040073F0410203F0CFFF78A +:1029B000A9FFEF60002383F31188D6F86422D3685F +:1029C0000BB110699847BDE8F04100F019BF23072B +:1029D00012D014F0080F0CBF00208020E10748BF80 +:1029E00040F02000A20748BF40F04000630748BF06 +:1029F00040F48070FFF786FFA4066B6805D596F853 +:102A000060124046194000F057FA2C68A4B2A1E7C2 +:102A10006860B7E7B4340020EC34002010B5054CF2 +:102A2000054A0021204600F025FA044BC4F85C3228 +:102A300010BD00BFB4340020F52800080044004059 +:102A400000F1604303F561430901C9B283F8001343 +:102A5000012200F01F039A4043099B0003F16043E9 +:102A600003F56143C3F880211A607047FFF72CBE5D +:102A7000012300F10802C0E90222037000F11002F4 +:102A80000023C0E90422C0E90633C0E908334360EB +:102A90007047000010B52023044683F311880223F9 +:102AA00003704160FFF732FE04232370002383F399 +:102AB000118810BD2DE9F0411F4604460D4616460B +:102AC000202383F3118800F108082378052B0DD00B +:102AD00029462046FFF744FE40B1204632462946AB +:102AE000FFF75EFE002080F3118808E0394640467B +:102AF00000F03AFB0028E8D0002383F31188BDE8FA +:102B0000F08100002DE9F0411F4604460D461646AF +:102B1000202383F3118800F110082378052B0DD0B2 +:102B200029462046FFF772FE40B12046324629462C +:102B3000FFF784FE002080F3118808E03946404604 +:102B400000F012FB0028E8D0002383F31188BDE8D1 +:102B5000F0810000F8B5154682680669AA420B4666 +:102B6000816938BF8568761AB54204460BD218468B +:102B70002A46FEF77FFCA3692B44A361A3685B1B75 +:102B8000A3602846F8BD0CD918463246FEF772FC01 +:102B9000AF1BE1683A463044FEF76CFCE3683B4407 +:102BA000EBE718462A46FEF765FCE368E5E7000018 +:102BB00083689342F7B51546044638BF8568D0E967 +:102BC0000460361AB5420BD22A46FEF753FC6369FD +:102BD0002B446361A36828465B1BA36003B0F0BD70 +:102BE0000DD932460191FEF745FC0199E068AF1B13 +:102BF0003A463144FEF73EFCE3683B44E9E72A46A7 +:102C0000FEF738FCE368E4E710B50A440024C3612A +:102C1000029B8460C0E90000C0E90511C160026147 +:102C2000036210BD08B5D0E90532934201D1826834 +:102C300082B98268013282605A1C42611970D0E9FF +:102C400004329A4224BFC3684361002100F09CFA19 +:102C5000002008BD4FF0FF30FBE7000070B52023D7 +:102C600004460E4683F31188A568A5B1A368A2693E +:102C7000013BA360531CA36115782269934224BFD2 +:102C8000E368A361E3690BB120469847002383F30F +:102C90001188284607E03146204600F065FA0028F2 +:102CA000E2DA85F3118870BD2DE9F74F04460E4630 +:102CB00017469846D0F81C904FF0200A8AF31188E6 +:102CC0004FF0000B154665B12A4631462046FFF706 +:102CD00041FF034660B94146204600F045FA00280E +:102CE000F1D0002383F31188781B03B0BDE8F08F87 +:102CF000B9F1000F03D001902046C847019B8BF328 +:102D00001188ED1A1E448AF31188DCE7C0E9051129 +:102D1000C160C3611144009B8260C0E90000016191 +:102D200003627047F8B504460D461646202383F328 +:102D30001188A768A7B1A368013BA36063695A1C07 +:102D400062611D70D4E904329A4224BFE368636172 +:102D5000E3690BB120469847002080F3118807E013 +:102D60003146204600F000FA0028E2DA87F31188A5 +:102D7000F8BD0000D0E905239A4210B501D1826860 +:102D80007AB98268013282605A1C82611C780369B8 +:102D90009A4224BFC3688361002100F0F5F9204600 +:102DA00010BD4FF0FF30FBE72DE9F74F04460E460C +:102DB00017469846D0F81C904FF0200A8AF31188E5 +:102DC0004FF0000B154665B12A4631462046FFF705 +:102DD000EFFE034660B94146204600F0C5F90028E1 +:102DE000F1D0002383F31188781B03B0BDE8F08F86 +:102DF000B9F1000F03D001902046C847019B8BF327 +:102E00001188ED1A1E448AF31188DCE702684368D2 +:102E10001143016003B11847704700001430FFF7F9 +:102E200043BF00004FF0FF331430FFF73DBF0000F9 +:102E30003830FFF7B9BF00004FF0FF333830FFF7ED +:102E4000B3BF00001430FFF709BF00004FF0FF319F +:102E50001430FFF703BF00003830FFF763BF0000F6 +:102E60004FF0FF323830FFF75DBF000000207047A1 +:102E7000FFF7D4BD37B515460E4A02600022426006 +:102E8000C0E902220122044602740B46009000F1C0 +:102E90005C014FF480721430FFF7B6FE00942B46AD +:102EA0004FF4807204F5AE7104F13800FFF72EFF85 +:102EB00003B030BD203F000838B5C36904460D4655 +:102EC0001BB904210844FFF7A1FF294604F11400AF +:102ED000FFF7A8FE002806DA201D4FF48061BDE848 +:102EE0003840FFF793BF38BD024B0022C3E90033DF +:102EF0009A6070471C370020002303748268054BDA +:102F00001B6899689142FBD25A6803604260106066 +:102F1000586070471C37002008B5202383F31188C0 +:102F2000037C032B05D0042B0DD02BB983F3118820 +:102F300008BD436900221A604FF0FF334361FFF779 +:102F4000DBFF0023F2E7D0E9003213605A60F3E7B9 +:102F5000002303748268054B1B6899689142FBD873 +:102F60005A68036042601060586070471C37002048 +:102F7000054B19690874186802681A605360186173 +:102F800001230374FDF744BB1C37002030B54B1CF4 +:102F90000B4D87B0044610D02B690A4A01A800F0F7 +:102FA0001BF92046FFF7E4FF049B13B101A800F0D2 +:102FB0004FF92B69586907B030BDFFF7D9FFF8E723 +:102FC0001C370020192F000838B50C4D41612B69C2 +:102FD00081689A689142044603D8BDE83840FFF7FB +:102FE0008BBF1846FFF7B4FF01232C610146237401 +:102FF0002046BDE83840FDF70BBB00BF1C37002062 +:10300000044B1A681B6990689B68984294BF002023 +:10301000012070471C37002010B5084C2368206938 +:103020001A6822605460012223611A74FFF790FF2E +:1030300001462069BDE81040FDF7EABA1C370020C0 +:1030400008B5FFF7DDFF18B1BDE80840FFF7E4BFA2 +:1030500008BD0000FFF7E0BFFEE7000010B50C4C14 +:10306000FFF742FF00F0AAF80A498022204600F04C +:1030700031F8012344F8180C037400F09DFB002381 +:1030800083F3118862B60448BDE8104000F042B8EE +:1030900044370020483F0008583F000800F012B9AC +:1030A000EFF3118020B9EFF30583202282F311881A +:1030B0007047000010B530B9EFF30584C4F308047D +:1030C00014B180F3118810BDFFF7BAFF84F31188A3 +:1030D000F9E7000082600222028270478368A3F150 +:1030E0007C0243F80C2C026943F83C2C426943F8FB +:1030F000382C074A43F81C2CC26843F8102C0222D3 +:1031000003F8082C002203F8072CA3F118007047DD +:103110002906000810B5202383F31188FFF7DEFF8E +:1031200000210446FFF750FF002383F31188204657 +:1031300010BD0000024B1B6958610F20FFF718BF3C +:103140001C370020202383F31188FFF7F3BF000012 +:1031500008B50146202383F311880820FFF716FFE6 +:10316000002383F3118808BD49B1064B42681B69EF +:1031700018605A60136043600420FFF707BF4FF0E8 +:10318000FF3070471C3700200368984206D01A6849 +:103190000260506059611846FFF7AEBE70470000EC +:1031A00038B504460D462068844200D138BD036816 +:1031B00023605C604561FFF79FFEF4E7054B03F178 +:1031C0001402C3E905224FF0FF310022C3E90712C0 +:1031D000704700BF1C37002070B51C4EC0E90323A8 +:1031E00005460C4600F06EFB334653F8142F9A4206 +:1031F0000DD13062C5E901242A600A2C2CBF0019C8 +:103200000A30C6E90555BDE8704000F049BB316A97 +:10321000431AE31838BF1C469368A34202D9081921 +:1032200000F04CFB73699A6894420CD85A68AC6001 +:103230002B606A6015609A685D60121B9A604FF09F +:10324000FF33F36170BD1B68A41AECE71C37002044 +:1032500038B51B4C636998420DD0D0E90032136039 +:103260005A6000228168C2609A680A449A604FF0EE +:10327000FF33E36138BD2246036842F8143F002162 +:1032800093425A60C16003D1BDE8384000F010BBE2 +:103290009A688168256A0A449A6000F013FB6369A2 +:1032A0009A68411B8A42E5D9AB181D1A092D206A7C +:1032B00098BF01F10A02BDE83840104400F0FEBAA0 +:1032C0001C3700202DE9F041184C002704F11406AA +:1032D000656900F0F7FA236AAA68C11A8A4215D80C +:1032E00013442362D5E9003213605A606369D5F84C +:1032F0000C80EF60B34201D100F0DAFA87F3118855 +:103300002869C047202383F31188E1E76169B1424E +:1033100009D013441B1ABDE8F0410A2B2CBFC0187A +:103320000A3000F0CBBABDE8F08100BF1C370020A6 +:1033300000207047FEE70000704700004FF0FF30AC +:1033400070470000BFF34F8F024AD368DB03FCD401 +:10335000704700BF003C024008B5094B1B7873B9A9 +:10336000FFF7F0FF074B1A69002ABFBF064A5A60F1 +:1033700002F188325A601A6822F480621A6008BD2D +:10338000D8380020003C02402301674508B50B4BAC +:103390001B7893B9FFF7D6FF094B1A6942F0004238 +:1033A0001A611A6842F480521A601A6822F4805234 +:1033B0001A601A6842F480621A6008BDD83800208A +:1033C000003C02400728F0B516D80C4C0C49237875 +:1033D0007BB90C4D0E4608234FF0006255F8047B74 +:1033E00046F8042B013B13F0FF033A44F6D10123C6 +:1033F000237051F82000F0BD0020FCE7FC380020CD +:10340000DC380020703F0008014B53F82000704763 +:10341000703F000808207047072810B5044601D9FE +:10342000002010BDFFF7CEFF064B53F824301844A0 +:10343000C21A0BB90120F4E712680132F0D1043B43 +:10344000F6E700BF703F0008072838B5044628D8C3 +:10345000FFF726FEFFF776FFFFF77EFF124AF32302 +:10346000D360E300DBB243F4007343F00203136163 +:10347000136943F48033136105462046FFF762FF6A +:10348000FFF7A0FF094B53F8241000F03BF9284642 +:10349000FFF77CFFFFF70EFE2046BDE83840FFF740 +:1034A000BBBF002038BD00BF003C0240703F000899 +:1034B00012F001032DE9F04105460E4614464BD1AA +:1034C0008118334A914261D8324B1B6813F00103D3 +:1034D0005CD0314FFFF7E4FDFFF73EFFF323FB60C5 +:1034E000FFF730FF314640F20128032C18D824F0B2 +:1034F0000104294E0C446D1A40F20118A1423369AF +:1035000005EB01072AD123F001033361FFF73EFFEA +:10351000FFF7D0FD0120BDE8F081043C0435E4E76D +:10352000AB07E4D13B6923F440733B613B6943EA59 +:1035300008033B6151F8046B2E60BFF34F8FFFF718 +:1035400001FF2B689E42E8D03B6923F001033B61F9 +:10355000FFF71CFFFFF7AEFD0020DCE723F440730C +:103560003361336943EA080333610B883B80BFF35F +:103570004F8FFFF7E7FE3F8831F8023BBFB2BB42F7 +:10358000BCD0336923F001033361E1E71846C2E799 +:103590000000080800380240003C0240084908B515 +:1035A0000B7828B11BB9FFF7D7FE01230B7008BDBC +:1035B000002BFCD0BDE808400870FFF7E7BE00BF55 +:1035C000D838002070B582B0FFF76AFD0E4E054670 +:1035D00000F078F93268904237BF0C4A0B495168C5 +:1035E00014682EBFD1E9004101315160041903462E +:1035F00041F10001284601913360FFF75BFD01991D +:10360000204602B070BD00BF0039002008390020FC +:1036100070B582B0FFF744FD104E054600F052F938 +:103620003268904237BF0E4A0D49516814682EBF68 +:10363000D1E9004101315160041941F10001034613 +:10364000284601913360FFF735FD01994FF47A72F6 +:1036500000232046FCF7C4FD02B070BD00390020F5 +:103660000839002010B50244064BD2B2904200D176 +:1036700010BD441C00B253F8200041F8040BE0B226 +:10368000F4E700BF502800400F4B30B51C6F2404F6 +:1036900007D41C6F44F400741C671C6F44F400448E +:1036A0001C670A4C236843F4807323600244084B70 +:1036B000D2B2904200D130BD441C00B251F8045B3C +:1036C00043F82050E0B2F4E70038024000700040B8 +:1036D0005028004007B5012201A90020FFF7C2FFD2 +:1036E000019803B05DF804FB13B50446FFF7F2FF41 +:1036F000A04205D0012201A900200194FFF7C4FFD8 +:1037000002B010BD70470000074B45F255521A60D9 +:1037100002225A6040F6FF729A604CF6CC421A6060 +:10372000024B01221A70704700300040143900200B +:10373000034B1B781BB1034B4AF6AA221A60704751 +:103740001439002000300040034B1A681AB9034AAC +:10375000D2F874281A6070471039002000300240F7 +:10376000024B4FF08072C3F874287047003002405B +:1037700008B5FFF7E9FF024B1868C0F3407008BDB9 +:103780001039002008B5FFF7DFFF024B1868C0F3BF +:10379000007008BD10390020EFF3098305494A6B1A +:1037A00022F001024A63683383F30988002383F31C +:1037B0001188704700EF00E0202080F3118862B686 +:1037C0000C4B0D4AD96821F4E0610904090C0A4345 +:1037D000DA60D3F8FC20094942F08072C3F8FC207B +:1037E0000A6842F001020A601022DA7783F82200A8 +:1037F000704700BF00ED00E00003FA05001000E094 +:1038000010B5202383F311880E4B5B6813F400631B +:1038100014D0F1EE103AEFF30984683C4FF0807356 +:10382000E361094BDB6B236684F30988FFF7E8FB50 +:1038300010B1064BA36110BD054BFBE783F3118864 +:10384000F9E700BF00ED00E000EF00E03B060008F4 +:103850003E06000870470000FEE700000A4B0B48D8 +:103860000B4A90420BD30B4BDA1C121AC11E22F0EA +:1038700003028B4238BF00220021FDF70DBE53F832 +:10388000041B40F8041BECE79C400008983900201A +:1038900098390020983900207047000000F080B867 +:1038A0004FF08043002258631A610222DA607047A9 +:1038B0004FF080430022DA60704700004FF08043F1 +:1038C000586370474FF08043586A70474B684360B5 +:1038D0008B688360CB68C3600B6943614B6903628B +:1038E0008B6943620B6803607047000008B5234B87 +:1038F00023481A6942F0FF021A611A6922F0FF0296 +:103900001A611A691A6B42F0FF021A631A6D42F0CB +:10391000FF021A651B4A1B6D1146FFF7D7FF02F124 +:103920001C0100F58060FFF7D1FF02F1380100F5BE +:103930008060FFF7CBFF02F1540100F58060FFF7D4 +:10394000C5FF02F1700100F58060FFF7BFFF02F1D3 +:103950008C0100F58060FFF7B9FF02F1A80100F5C6 +:103960008060FFF7B3FF02F1C40100F58060FFF74C +:10397000ADFFBDE8084000F097B800BF0038024036 +:1039800000000240903F000808B500F017FAFFF76A +:1039900065FBBDE80840FFF7D7BE00007047000098 +:1039A000104B1A6C42F001021A641A6E42F00102C6 +:1039B0001A660D4A1B6E936843F0010393604FF043 +:1039C000804331229A624FF0FF32DA6200229A611C +:1039D0005A63DA605A6001225A6108211A601C2079 +:1039E000FFF72EB800380240002004E04FF080427C +:1039F00008B51169D3680B40D9B2C9439B0711615F +:103A000007D5202383F31188FFF748FB002383F3B6 +:103A1000118808BD08B5FFF7E9FFBDE80840FFF7CA +:103A2000EFBE00001E4B1A6962F0FF021A611A69AC +:103A3000D2B21A614FF0FF301A695A6958610021F9 +:103A40005A6959615A691A6A62F080521A621A6A8E +:103A500002F080521A621A6A5A6A58625A6A5962A5 +:103A60005A6A1A6C42F080521A641A6E42F08052FE +:103A70001A661A6E0B4A106840F480701060186F56 +:103A800000F44070B0F5007F1EBF4FF4803018671F +:103A90001967536823F40073536000F06FB900BFD7 +:103AA00000380240007000403B4B3C4A1A643C4ADC +:103AB0004FF4404111601A6842F001021A601A681E +:103AC0009007FCD59A6822F003029A60324B9A68FC +:103AD00012F00C02FBD1196801F0F90119609A602B +:103AE0001A6842F480321A601A689103FCD55A6F42 +:103AF00042F001025A67284B5A6F9207FCD5294AB7 +:103B00005A601A6842F080721A60254A5368580455 +:103B1000FCD5214B1A689101FCD5234AC3F88420B7 +:103B20001A6842F080621A601A681201FCD51F4AB6 +:103B30009A600322C3F88C204FF00062C3F89420EF +:103B40001B4B1A681B4B9A421B4B21D11B4A116815 +:103B50001B4A91421CD140F203121A60164A1368A4 +:103B600003F00F03032BFAD10B4B9A6842F00202C9 +:103B70009A609A6802F00C02082AFAD15A6C42F450 +:103B800080425A645A6E42F480425A665B6E7047B5 +:103B900040F20372E1E700BF003802400004001069 +:103BA0000070004004194002083000240094883856 +:103BB000002004E011640020003C024000ED00E021 +:103BC00041C20F41084A08B5516913680B4003F020 +:103BD0000103536123B1054A13680BB1506898473C +:103BE000BDE80840FFF70CBE003C0140183900203A +:103BF000084A08B5516913680B4003F0020353618A +:103C000023B1054A93680BB1D0689847BDE80840D6 +:103C1000FFF7F6BD003C014018390020084A08B5FE +:103C2000516913680B4003F00403536123B1054A43 +:103C300013690BB150699847BDE80840FFF7E0BD34 +:103C4000003C014018390020084A08B55169136842 +:103C50000B4003F00803536123B1054A93690BB18C +:103C6000D0699847BDE80840FFF7CABD003C014055 +:103C700018390020084A08B5516913680B4003F051 +:103C80001003536123B1054A136A0BB1506A984778 +:103C9000BDE80840FFF7B4BD003C014018390020E2 +:103CA000174B10B55A691C68144004F478725A61B5 +:103CB000A30604D5134A936A0BB1D06A98476006ED +:103CC00004D5104A136B0BB1506B9847210604D5ED +:103CD0000C4A936B0BB1D06B9847E20504D5094AA7 +:103CE000136C0BB1506C9847A30504D5054A936C2F +:103CF0000BB1D06C9847BDE81040FFF781BD00BF05 +:103D0000003C0140183900201A4B10B55A691C6854 +:103D1000144004F47C425A61620504D5164A136DBE +:103D20000BB1506D9847230504D5134A936D0BB121 +:103D3000D06D9847E00404D50F4A136E0BB1506E56 +:103D40009847A10404D50C4A936E0BB1D06E9847E6 +:103D5000620404D5084A136F0BB1506F98472304CF +:103D600004D5054A936F0BB1D06F9847BDE810405A +:103D7000FFF746BD003C014018390020062108B578 +:103D80000846FEF75DFE06210720FEF759FE0621D4 +:103D90000820FEF755FE06210920FEF751FE0621F8 +:103DA0000A20FEF74DFE06211720FEF749FEBDE86A +:103DB000084006212820FEF743BE000008B5FFF7A3 +:103DC00031FE00F00BF8FEF751FEFFF751F8FFF758 +:103DD000E5FDBDE80840FFF761BD00000023054A8E +:103DE00019460133102BC2E9001102F10802F8D183 +:103DF000704700BF1839002010B5013902449042C5 +:103E000001D1002005E0037811F8014FA34201D051 +:103E1000181B10BD0130F2E72DE9F041A3B1C91A1A +:103E200017780144044603F1FF3C8C42204601D937 +:103E3000002009E00578BD4204F10104F5D10CEB46 +:103E40000405D618A54201D1BDE8F08115F8018D11 +:103E500016F801EDF045F5D0E7E70000034611F84C +:103E6000012B03F8012B002AF9D170476F72672EDE +:103E70006172647570696C6F742E41524B5F47506C +:103E8000530000004E6F20617070207369670A0054 +:103E9000426164206677206C656E677468202575C2 +:103EA0000A0042616420626F6172645F6964202568 +:103EB000752073686F756C642062652025750A0033 +:103EC0004261642066772064657363726970746F01 +:103ED00072206C656E6774682025750A0042616403 +:103EE0002061707020435243203078253038783A72 +:103EF000307825303878203078253038783A307866 +:103F0000253038780A00476F6F64206669726D77D4 +:103F10006172650A0040A2E4F16468910600000045 +:103F200000000000392E0008252E0008612E000830 +:103F30004D2E0008592E0008452E0008312E00088D +:103F40001D2E00086D2E00086D61696E00000000D6 +:103F500069646C6500000000503F00086037002075 +:103F6000D83800200100000059300008000000008F +:103F70000040000000400000004000000040000041 +:103F8000000001000000020000000200000002002A +:103F9000A000902A00000000AAAAAAAA50000024AB +:103FA000FFFB000000770000009009000100000501 +:103FB00000000000AAAAAAA501000080FFEF0000EF :103FC00000000000000000000000000000000000F1 :103FD000AAAAAAAA00000000FFFF0000000000003B :103FE000000000000000000000000000AAAAAAAA29 @@ -1027,9 +1027,10 @@ :10401000FFFF0000000000000000000000000000A2 :1040200000000000AAAAAAAA00000000FFFF0000EA :104030000000000000000000000000000000000080 -:104040000A00000000000000030000000000000063 -:1040500000000000ECC1FF7F010000000000000034 -:1040600051000000000000000000070000000000F8 -:10407000640000000000000040420F00FE2A010022 -:04408000D204000066 +:10404000AAAAAAAA00000000FFFF000000000000CA +:104050000000000000000000000000000A00000056 +:10406000000000000300000000000000000000004D +:10407000A0C1FF7F0100000051000000000000000F +:1040800000000700000000006400000000000000C5 +:0C40900040420F00FE2A0100D204000094 :00000001FF diff --git a/Tools/bootloaders/AtomRCF405NAVI_bl.bin b/Tools/bootloaders/AtomRCF405NAVI_bl.bin new file mode 100755 index 00000000000..03e238812d8 Binary files /dev/null and b/Tools/bootloaders/AtomRCF405NAVI_bl.bin differ diff --git a/Tools/bootloaders/BeastF7v2_bl.bin b/Tools/bootloaders/BeastF7v2_bl.bin old mode 100644 new mode 100755 index fd00cc6e10e..eb985db537d Binary files a/Tools/bootloaders/BeastF7v2_bl.bin and b/Tools/bootloaders/BeastF7v2_bl.bin differ diff --git a/Tools/bootloaders/BeastF7v2_bl.hex b/Tools/bootloaders/BeastF7v2_bl.hex index 06471d3e5ff..b619f76da71 100644 --- a/Tools/bootloaders/BeastF7v2_bl.hex +++ b/Tools/bootloaders/BeastF7v2_bl.hex @@ -1,25 +1,25 @@ :020000040800F2 -:1000000000060120010200083D0F0008BD0E000897 -:10001000150F0008BD0E0008E90E000803020008D5 -:100020000302000803020008030200086527000815 +:100000000006012001020008A90F0008290F0008BE +:10001000810F0008290F0008550F0008030200088F +:100020000302000803020008030200084928000830 :10003000030200080302000803020008030200088C :10004000030200080302000803020008030200087C -:100050000302000803020008D9380008013900082B -:1000600029390008513900087939000803020008CD +:100050000302000803020008BD390008E539000862 +:100060000D3A0008353A00085D3A0008030200081E :10007000030200080302000803020008030200084C :10008000030200080302000803020008030200083C -:10009000030200080302000803020008A139000857 +:10009000030200080302000803020008853A000872 :1000A000030200080302000803020008030200081C -:1000B000893A00080302000803020008030200084E +:1000B0006D3B000803020008030200080302000869 :1000C00003020008030200080302000803020008FC -:1000D00003020008753A0008030200080302000842 -:1000E000053A0008030200080302000803020008A2 +:1000D00003020008593B000803020008030200085D +:1000E000E93A0008030200080302000803020008BE :1000F00003020008030200080302000803020008CC :1001000003020008030200080302000803020008BB :1001100003020008030200080302000803020008AB :10012000030200080302000803020008030200089B :10013000030200080302000803020008030200088B -:10014000030200080302000803020008252F00082C +:100140000302000803020008030200080930000847 :10015000030200080302000803020008030200086B :10016000030200080302000803020008030200085B :10017000030200080302000803020008030200084B @@ -38,974 +38,988 @@ :10024000C0F2F0004EF68851CEF200010860BFF314 :100250004F8FBFF36F8F4FF00000E1EE100A4EF6A4 :100260003C71CEF200010860062080F31488BFF3D1 -:100270006F8F02F037FB02F0D9FA03F0CFF94FF09D +:100270006F8F02F0A9FB02F04BFB03F041FA4FF045 :1002800055301F491B4A91423CBF41F8040BFAE725 :100290001C49194A91423CBF41F8040BFAE71A493C :1002A0001A4A1B4B9A423EBF51F8040B42F8040B0A :1002B000F8E700201749184A91423CBF41F8040B67 -:1002C000FAE702F0F1FA03F009FA144C144DAC42CB +:1002C000FAE702F063FB03F07BFA144C144DAC42E6 :1002D00003DA54F8041B8847F9E700F041F8114CA1 :1002E000114DAC4203DA54F8041B8847F9E702F0D9 -:1002F000D9BA0000000601200022012000000008F9 -:100300000000012000060120A03E0008002201207C -:1003100068220120682201205430012000020008D8 +:1002F0004BBB000000060120002201200000000886 +:100300000000012000060120803F0008002201209B +:1003100068220120682201205830012000020008D4 :100320000002000800020008000200082DE9F04F5A :100330002DED108AC1F80CD0D0F80CD0BDEC108A8D :10034000BDE8F08F002383F311882846A0470020E2 -:1003500001F024FEFEE701F0B5FD00DFFEE700003E -:1003600038B502F0C1F9054602F0F6F90446D8B9ED +:1003500001F080FEFEE701F0F5FD00DFFEE70000A2 +:1003600038B502F031FA054602F064FA0446D8B90D :100370000F4B9D421AD001339D4218BF044641F2F3 -:10038000883504BF01240025002002F0B7F90CB124 -:1003900000F058F800F03AFD00F0DEFB284600F0CF -:1003A000E1F800F04FF8F9E70025EDE70546EBE747 -:1003B000010007B008B500F09BFBA0F120035842F4 +:10038000883504BF01240025002002F027FA0CB1B3 +:1003900000F078F800F070FD00F012FC284600F044 +:1003A000FDF800F06FF8F9E70025EDE70546EBE70B +:1003B000010007B008B500F0CFFBA0F120035842C0 :1003C000584108BD07B541F21203022101A8ADF85A -:1003D000043000F0ABFB03B05DF804FB10B572B65F -:1003E000202383F3118862B61248C3680BB101F071 -:1003F0005DFE114A0F4800234FF47A7101F01AFE96 -:10040000002383F311880D4C236813B12368013B4B -:100410002360636813B16368013B6360084B1B781A -:1004200033B9636823B9022000F06AFC32236360A9 -:1004300010BD00BF68220120DD03000884230120D5 -:100440007C220120F8B5414B414A1C461968013114 -:100450007BD004339342F9D16268A24275D33D4BFD -:100460009B6803F1006303F5C0339A426DD200200C -:1004700000F08CFB384B0220187000F037FC374B33 -:1004800000211A6C19641A6E19661A6E5A6C596436 -:100490005A6E59665A6E5A6942F080025A615A6918 -:1004A00022F080025A615A691A6942F000521A61B8 -:1004B0001A6922F000521A611B6972B64FF0E023EC -:1004C000C3F8084DD4E90004BFF34F8FBFF36F8F1B -:1004D000234AC2F88410BFF34F8F536923F480334B -:1004E0005361BFF34F8FD2F88030C3F3C905C3F314 -:1004F0004E335B0143F6E07603EA060C29464CEAEC -:1005000081770139C2F87472F9D2203B13F1200FC0 -:10051000F2D1BFF34F8FBFF36F8FBFF34F8FBFF396 -:100520006F8F536923F4003353610023C2F85032B4 -:10053000BFF34F8FBFF36F8F72B6202383F3118801 -:1005400062B6854680F308882047F8BD0080010820 -:1005500020800108002201207C2201200038024076 -:1005600000ED00E02DE9F04F93B0AA4B009020225F -:10057000FF210AA89D6800F0F3FBA74A1378B3B9DE -:10058000A64801211170C36072B6202383F311883D -:1005900062B6C3680BB101F089FDA14A9F480023F0 -:1005A0004FF47A7101F046FD002383F31188009B1C -:1005B0009C4A03B113609C49009C00230B7053605C -:1005C00098469B461E469A46012000F08FFB24B1B8 -:1005D000944B1B68002B00F01682002000F088FA74 -:1005E0000390039B002BF2DB012000F075FB039BC3 -:1005F000213B162BE8D801A252F823F05906000837 -:100600008106000815070008C9050008C90500088B -:10061000C9050008A90700087B090008950800081B -:10062000F70800081F09000845090008C905000867 -:1006300057090008C9050008C9090008F90600089B -:10064000C90500080D0A000865060008F90600083B -:10065000C9050008F70800080220FFF7ABFE0028D4 -:1006600040F0FB81009B0221B8F1000F08BF1C463F -:1006700005A841F21233ADF8143000F057FAA3E7A1 -:100680004FF47A7000F034FA071EEBDB0220FFF71C -:1006900091FE0028E6D0013F052F00F2E081DFE85F -:1006A00007F0030A0D10133605230593042105A84E -:1006B00000F03CFA17E057480421F9E75B480421B1 -:1006C000F6E75B480421F3E74FF01C09484600F0C9 -:1006D0005FFA09F104090590042105A800F026FA43 -:1006E000B9F12C0FF2D1012000FA07F747EA0B0B02 -:1006F0005FFA8BFB4FF0000A00F07EFB26B10BF097 -:100700000B030B2B08BF0024FFF75CFE5CE7494896 -:100710000421CDE7002EA5D00BF00B030B2BA1D1AC -:100720000220FFF747FE074600289BD001203E4EDF -:1007300000F02CFA0220307000F0D8FA4FF00008D8 -:100740005FFA88F9484600F031FA044690B148460D -:1007500000F03CFA08F101080028F1D1B84604463F -:1007600041F21213022105A8ADF814303E4600F004 -:10077000DDF929E701230220337000F0ADFA2546A8 -:10078000244B9B68AB4207D9284600F001FA0130A0 -:1007900040F068810435F3E7234B00251D70214BA1 -:1007A000B8465D603E46A7E7002E3FF45BAF0BF016 -:1007B0000B030B2B7FF456AF1B4B0220187000F07D -:1007C00095FA322000F094F9B0F10009FFF64AAF33 -:1007D00019F003077FF446AF0E4A926809EB050350 -:1007E00093423FF63FAFB9F5807F3FF73BAF124BE7 -:1007F0000193B94522DD4FF47A7000F079F9039046 -:10080000039A002AFFF62EAF019B039A03F8012BEF -:100810000137EDE70022012080230120682201201A -:10082000DD030008842301207C2201200422012012 -:10083000082201200C22012080220120C820FFF77D -:10084000B9FD074600283FF40DAF1F2D11D8C5F1A3 -:1008500020024A450AAB25F0030028BF4A468349D7 -:100860000192184400F056FA019A8048FF2100F0E6 -:1008700077FA4FEAA9037D490193C9F38702284615 -:1008800000F076FA064600283FF46AAF019B05EBBC -:10089000830531E70220FFF78DFD00283FF4E2AE2B -:1008A00000F0BEF900283FF4DDAE0027B946704BDA -:1008B0009B68BB4218D91F2F11D80A9B01330ED059 -:1008C00027F0030312AA134453F8203C059348462B -:1008D000042205A900F034FB04378146E7E73846D7 -:1008E00000F056F90590F2E7CDF81490042105A820 -:1008F00000F01CF900E70023642104A8049300F031 -:100900000BF900287FF4AEAE0220FFF753FD00285C -:100910003FF4A8AE049800F06BF90590E6E70023D9 -:10092000642104A8049300F0F7F800287FF49AAE3D -:100930000220FFF73FFD00283FF494AE049800F03A -:1009400067F9EAE70220FFF735FD00283FF48AAE99 -:1009500000F076F9E1E70220FFF72CFD00283FF4D4 -:1009600081AE05A9142000F071F904210746049016 -:1009700004A800F0DBF83946B9E7322000F0B8F8F7 -:10098000071EFFF66FAEBB077FF46CAE384A926865 -:1009900007EB0A0393423FF665AE0220FFF70AFD1C -:1009A00000283FF45FAE27F003075744BA453FF4F1 -:1009B000A3AE504600F0ECF80421059005A800F025 -:1009C000B5F80AF1040AF1E74FF47A70FFF7F2FC88 -:1009D00000283FF447AE00F023F9002844D00A9BDA -:1009E00001330BD008220AA9002000F0C1F9002829 -:1009F0003AD02022FF210AA800F0B2F9FFF7E2FC6A -:100A00001C4801F0D3FA13B0BDE8F08F002E3FF47C -:100A100029AE0BF00B030B2B7FF424AE00236421D3 -:100A200005A8059300F078F8074600287FF41AAE71 -:100A30000220FFF7BFFC814600283FF413AEFFF70A -:100A4000C1FC41F2883001F0B1FA059800F016FAC5 -:100A50004E4600F0D1F93C46B6E506464CE64FF06E -:100A6000000AFFE5B8467BE6374679E6802201209A -:100A700000220120A0860100F7B5194E0C464FF464 -:100A80007A7102FB01F396F900200546501C0BD148 -:100A90001448019302682946176A2246B8478442DF -:100AA000019B03D1002310E0002AF1D096F9002029 -:100AB000511C01D0012A0DD10B4802682946166A43 -:100AC0002246B047844205D10123084A0120137011 -:100AD00003B0F0BD4FF4FA7001F068FA0020F7E7B8 -:100AE00010220120F8270120D4230120D023012047 -:100AF00007B50023024601210DF107008DF80730EC -:100B0000FFF7BAFF20B19DF8070003B05DF804FBC2 -:100B10004FF0FF30F9E700000A4608B50421FFF75F -:100B2000ABFF80F00100C0B2404208BD30B4074BBB -:100B30000A461978064B53F821402368DD69054BB6 -:100B40000146AC46204630BC604700BFD0230120A0 -:100B5000643B0008A086010070B501F0CBFC094E93 -:100B6000094D3080002428683388834208D901F079 -:100B7000BBFC2B6804440133B4F5C03F2B60F2D3B7 -:100B800070BD00BFD22301208C23012001F060BD85 -:100B900000F1006000F5C0300068704700F10060AF -:100BA000920000F5C03001F0EBBC0000054B1A6864 -:100BB000054B1B889B1A834202D9104401F094BC58 -:100BC000002070478C230120D223012038B5074D27 -:100BD00004462868204401F08FFC28B92868204486 -:100BE000BDE8384001F0A0BC38BD00BF8C23012017 -:100BF00010F0030309D1B0F5846F04D200F1005066 -:100C0000A0F571200368184670470023FBE7000039 -:100C100000F10050A0F57120D0F8200470470000CA -:100C2000064991F8243033B10023086A81F8243052 -:100C30000822FFF7B3BF0120704700BF90230120B7 -:100C4000014B1868704700BF002004E0F0B5204B4E -:100C5000024618681F4B1F885D6893F90840C0F36F -:100C60000B06BE424FEA104022D09F89BE4221D0DF -:100C70001F8BBE4206D102240C2505FB04335D68A0 -:100C800093F90840B0F5805F16D041F20103984215 -:100C900008BF5A24013A0A44013D0B4693420DD243 -:100CA00015F9016F581C5EB100F8016C0346F5E7B9 -:100CB0000024E1E70124DFE74124EBE7184605E0E3 -:100CC0002C2590421D7001D2981C5C70401AF0BD1A -:100CD000002004E014220120022802BF024B4FF042 -:100CE00000529A61704700BF00080240022802BF0C -:100CF000024B4FF400529A61704700BF0008024057 -:100D0000022801BF024A536983F4005353617047BC -:100D10000008024010B50023934203D0CC5CC454B9 -:100D20000133F9E710BD000010B5013810F9013F9B -:100D30003BB191F900409C4203D11AB10131013A13 -:100D4000F4E71AB191F90020981A10BD1046FCE79B -:100D500003460246D01A12F9011B0029FAD1704746 -:100D600002440346934202D003F8011BFAE770479E -:100D70002DE9F8431F4D144695F824200746884670 -:100D800052BBDFF870909CB395F824302BB9202229 -:100D9000FF2148462F62FFF7E3FF95F82400C0F1DA -:100DA0000802A24228BF2246D6B24146920005EB75 -:100DB0008000FFF7AFFF95F82430A41B1E44F6B265 -:100DC000082E17449044E4B285F82460DBD1FFF785 -:100DD00027FF0028D7D108E02B6A03EB8203834268 -:100DE000CFD0FFF71DFF0028CBD10020BDE8F8834E -:100DF0000120FBE790230120024B1A78024B1A7066 -:100E0000704700BFD02301201022012038B5154CB7 -:100E1000154D204600F0F4FB2946204600F01CFC4E -:100E20002D681248EA6ED2F8043843F00203C2F883 -:100E3000043801F0BBF80E49284600F01BFDEA6EAD -:100E40000C48D2F804380C4923F00203C2F80438E5 -:100E5000A0424FF4E1330B6003D0BDE8384000F00E -:100E60002BBB38BDF8270120703C000840420F0022 -:100E7000783C0008D4230120B823012038B50B4B5F -:100E80001A780B4B53F822500A4B9D4204460CD063 -:100E9000094B002118461822FFF762FF0460014643 -:100EA0002846BDE8384000F007BB38BDD0230120FC -:100EB000643B0008F8270120B823012000B59BB04F -:100EC000EFF3098168226846FFF724FFEFF30583FB -:100ED000044B9A6BDA6A9A6A9A6A9A6A9A6A9A6A66 -:100EE0009B6AFEE700ED00E000B59BB0EFF30981DF -:100EF00068226846FFF70EFFEFF30583044B9A6BF9 -:100F00009A6A9A6A9A6A9A6A9A6A9B6AFEE700BF24 -:100F100000ED00E000B59BB0EFF309816822684660 -:100F2000FFF7F8FEEFF30583034B5A6B9A6A9A6A50 -:100F30009A6A9A6A9B6AFEE700ED00E0FEE700000D -:100F400030B5094D0A4491420DD011F8013B58408B -:100F5000082340F30004013B2C4013F0FF0384EA14 -:100F60005000F6D1EFE730BD2083B8ED72B62023F4 -:100F700083F3118862B670470268436811430160C9 -:100F800003B1184770470000024A136843F0C003DA -:100F9000136070470010014013B50E4C204600F05E -:100FA0007FFA04F114000C49009400234FF480727E -:100FB00000F044F9094B0A4900944FF4807204F19F -:100FC000380000F0B9F9074A074BC4E9172302B00B -:100FD00010BD00BFD423012040240120890F000848 -:100FE000402501200010014000F36F0630B5037C5E -:100FF000214C002918BF0C46012B0CD11F4B9842E5 -:1010000009D11F4B5A6C42F010025A645A6E42F0DA -:1010100010025A665B6E2268036EC16D846603EB34 -:101020005203B3FBF2F36268150442BF23F00705D5 -:1010300003F0070343EA4503CB60A36843F0400392 -:101040004B60E36843F001038B6042F4967343F016 -:1010500001030B604FF0FF330B62510505D512F011 -:10106000102205D0B2F1805F04D080F8643030BD2A -:101070007F23FAE73F23F8E76C3B0008D4230120E5 -:10108000003802402DE9F047C66D3768F4693462D4 -:101090002107054617D014F0080118BF8021E20788 -:1010A00048BF41F02001A30748BF41F0400160075D -:1010B00048BF41F48071281DFFF758FFFFF75CFF20 -:1010C000002383F31188E20509D54FF40071281D30 -:1010D000FFF74CFFFFF750FF002383F311884FF019 -:1010E000000914F0200835D13B0614D505F1380964 -:1010F000200610D54846FFF739FF00F04FF90028C9 -:1011000035DA0821281DFFF737FF27F08003336009 -:10111000002383F31188790613D5620611D5FFF7F2 -:1011200025FFD5E913239A4208D12B6C33B1102146 -:10113000281D27F04007FFF71FFF3760002383F3C8 -:101140001188E30618D5AA6E1369ABB1BDE8F04764 -:1011500050691847FFF70AFF736A95F8641028462C -:10116000194000F0B5F989F31188F469B9E7B06264 -:1011700088F31188F469BBE7BDE8F08772B62023D5 -:1011800083F3118862B67047F8B515468268066920 -:10119000AA420B46816938BF8568761AB542044673 -:1011A0000BD218462A46FFF7B5FDA3692B44A3616D -:1011B000A3685B1BA3602846F8BD0CD918463246CD -:1011C000FFF7A8FDAF1BE1683A463044FFF7A2FDE8 -:1011D000E3683B44EBE718462A46FFF79BFDE368CC -:1011E000E5E7000083689342F7B51546044638BF2B -:1011F0008568D0E90460361AB5420BD22A46FFF75B -:1012000089FD63692B446361A36828465B1BA36067 -:1012100003B0F0BD0DD932460191FFF77BFD019976 -:10122000E068AF1B3A463144FFF774FDE3683B4486 -:10123000E9E72A46FFF76EFDE368E4E710B50A44E4 -:101240000024C361029B8460C0E90000C0E905116D -:10125000C1600261036210BD08B5D0E90532934256 -:1012600001D1826882B98268013282605A1C42616F -:101270001970D0E904329A4224BFC3684361002147 -:1012800000F0B0FE002008BD4FF0FF30FBE700008B -:1012900070B504460D46FFF771FFA668A6B1A368B6 -:1012A000A269013BA360531CA36115782269934294 -:1012B00024BFE368A361E3690BB12046984700238C -:1012C00083F31188284607E02946204600F07AFE7D -:1012D0000028E2DA86F3118870BD00002DE9F84F8E -:1012E000D0F81CA09946FFF749FF04460E469046E9 -:1012F00015464FF0000B65B12A4631462046FFF7F0 -:1013000043FF074660B94946204600F05BFE0028CF -:10131000F1D0002383F31188A8EB0500BDE8F88F16 -:10132000BAF1000F01D02046D0478BF31188ED1B96 -:101330003E44FFF723FFDEE7C0E90511C160C3614A -:101340001144009B8260C0E90000016103627047A4 -:10135000F8B504460D461646FFF710FFA768A7B17B -:10136000A368013BA36063695A1C62611D70D4E9E4 -:1013700004329A4224BFE3686361E3690BB12046FB -:101380009847002080F3118807E03146204600F09E -:1013900019FE0028E2DA87F31188F8BDD0E90523A9 -:1013A0009A4210B501D182687AB9826801328260AE -:1013B0005A1C82611C7803699A4224BFC368836106 -:1013C000002100F00FFE204610BD4FF0FF30FBE77C -:1013D0002DE9F84FD0F81CA09946FFF7CFFE044640 -:1013E0000E46904615464FF0000B65B12A46314631 -:1013F0002046FFF7F7FE074660B94946204600F051 -:10140000E1FD0028F1D0002383F31188A8EB05004B -:10141000BDE8F88FBAF1000F01D02046D0478BF31A -:101420001188ED1B3E44FFF7A9FEDEE772B62023CC -:1014300083F3118862B67047026843681143016004 -:1014400003B11847704700001430FFF747BF000092 -:101450004FF0FF331430FFF741BF00003830FFF783 -:10146000B7BF00004FF0FF333830FFF7B1BF0000C7 -:101470001430FFF70DBF00004FF0FF311430FFF7BD -:1014800007BF00003830FFF763BF00004FF0FF32A6 -:101490003830FFF75DBF000000207047FFF77CBDCC -:1014A000044B03600023C0E902334360012303744B -:1014B000704700BF843B000810B50446FFF7B6FF35 -:1014C000FFF794FD02232374002383F3118810BDDA -:1014D00038B5C36904460D461BB904210844FFF71B -:1014E000ABFF294604F11400FFF7B6FE002806DA28 -:1014F000201D4FF48061BDE83840FFF79DBF38BD27 -:1015000072B6202383F3118862B67047026843687D -:101510001143016003B118477047000013B5446BD5 -:10152000D4F894341A681178042915D1217C022941 -:1015300012D11979128901238B4013420CD101A9D0 -:1015400004F14C0001F072FFD4F89444019B21791E -:101550000246206800F0DAF902B010BD143001F044 -:10156000F7BE00004FF0FF33143001F0F1BE000071 -:101570004C3001F0C7BF00004FF0FF334C3001F09A -:10158000C1BF0000143001F0C7BE00004FF0FF31B2 -:10159000143001F0C1BE00004C3001F093BF0000D8 -:1015A0004FF0FF324C3001F08DBF0000002070473B -:1015B00010B5D0F894341A6811780429044617D16C -:1015C000017C022914D15979528901238B4013429D -:1015D0000ED1143001F05AFE024648B1D4F89444BA -:1015E0004FF4807361792068BDE8104000F07CB949 -:1015F00010BD0000406BFFF7DBBF0000704700002C -:101600007FB5124B036000234360C0E9023301251C -:1016100002260F4B057404460290019300F18402E8 -:10162000294600964FF48073143001F00BFE094BED -:101630000294CDE9006304F523724FF480732946C8 -:1016400004F14C0001F0CEFE04B070BDAC3B0008CC -:10165000F51500081D15000808B50A68FFF750FFCA -:101660000B7902EB830318624B790D3342F82300A8 -:101670008B7913B102EB8302106202230374C0F86A -:101680009414002383F3118808BD000038B5037F4C -:10169000044613B190F85430ABB9201D0125022146 -:1016A000FFF734FF04F1140025776FF0010100F01B -:1016B000A5FC84F8545004F14C006FF00101BDE822 -:1016C000384000F09BBC38BD10B501210446043001 -:1016D000FFF71CFF0023237784F8543010BD00006F -:1016E00038B504460025143001F0C4FD04F14C0067 -:1016F000257701F08FFE201D84F854500121FFF75B -:1017000005FF2046BDE83840FFF752BF90F85C3037 -:1017100003F06003202B07D190F85D20212A4FF0C1 -:10172000000303D81F2A06D800207047222AFBD1C5 -:10173000C0E9143303E0034A02650722426583656A -:10174000012070473822012037B5D0F894341A6848 -:101750001178042904461AD1017C022917D119797C -:10176000128901238B40134211D100F14C05284608 -:1017700001F00EFF58B101A9284601F057FED4F838 -:101780009444019B21790246206800F0BFF803B021 -:1017900030BD0000F0B500EB810385B01E6A044641 -:1017A0000D46F6B104EB8507301D0821FFF7A8FEB2 -:1017B000FFF7ACFEFB685B691B6806F14C001BB1D0 -:1017C000019001F041FE019803A901F02FFE0246AD -:1017D00048B1039B2946204600F098F8002383F384 -:1017E000118805B0F0BDFB685A691268002AF5D06F -:1017F0001B8A013B1340F1D104F15C02EAE70000CF -:101800000D3138B550F82140D4B1FFF779FED4F846 -:1018100094241368527903EB8203DB689B695D684B -:1018200045B104216018FFF771FE294604F1140048 -:1018300001F036FD2046FFF7BBFE002383F311883D -:1018400038BD00007047000072B6202383F3118872 -:1018500062B6704701F0BCB810B5012304462822D7 -:1018600000F8243B0021FFF77BFA0023C4E9013391 -:1018700010BD000038B50025FFF7E6FF0446C0E9BB -:101880000355C0E90555C0E90755416001F0B0F8BE -:101890000223237085F3118838BD000070B500EB7A -:1018A000810305465069DA600E46144618B11022CD -:1018B0000021FFF755FAA06918B110220021FFF7A7 -:1018C0004FFA31462846BDE8704001F05BB9000090 -:1018D000826802F0011282600022C0E90422C0E99D -:1018E0000622026201F0DAB9F0B400EB8104478904 -:1018F000E4680125A4698D403D43458123600023B0 -:10190000A2606360F0BC01F0F5B90000F0B400EB38 -:1019100081040789E468012564698D403D430581A0 -:1019200023600023A2606360F0BC01F071BA000084 -:1019300070B50223002504460370C0E90255C0E9D2 -:101940000455C0E906554566056280F84C5001F023 -:10195000B5F863681B6823B129462046BDE870408E -:10196000184770BD037880F868300523037043681A -:101970001B6810B504460BB1042198470023A360EF -:1019800010BD000090F86820436802701B680BB11E -:10199000052118477047000070B590F84C30044698 -:1019A00013B1002380F84C3004F15C02204601F0B2 -:1019B00097F963689B68B3B994F85C3013F06005DD -:1019C00033D00021204601F003FC0021204601F025 -:1019D000F5FB63681B6813B1062120469847062370 -:1019E00084F84C3070BD204698470028E4D0B4F805 -:1019F0006230626D9A4288BF636594F95C30656DB0 -:101A0000002B80F20281002D00F0F180092384F880 -:101A10004C30FFF719FF0021D4E914232046FFF7CB -:101A200075FF002383F31188DCE794F85D2003F051 -:101A30007F0343EA022340F20232934200F0C48063 -:101A400021D8B3F5807F48D00DD8012B3FD0022B91 -:101A500000F09280002BB4D104F1640222650222CE -:101A60006265A365C3E7B3F5817F00F09A80B3F5A3 -:101A7000407FA6D194F85E30012BA2D1B4F8643037 -:101A800043F0020332E0B3F5006F4DD017D8B3F541 -:101A9000A06F31D0A3F5C063012B92D8636894F88E -:101AA0005E205E6894F85F10B4F860302046B0475E -:101AB000002886D043682365036863651AE0B3F5A0 -:101AC000106F36D040F6024293427FF47AAF5B4B00 -:101AD0002365022363650023C3E794F85E30012B7E -:101AE0007FF46FAFB4F8643023F00203C4E91455F7 -:101AF000A4F86430A5657AE7B4F85C30B3F5A06F5C -:101B00000ED194F85E3084F86630204601F02EF84D -:101B100063681B6813B10121204698470323237093 -:101B20000023C4E914339CE704F167032365012310 -:101B3000C3E72378042B0FD12046FFF785FEFFF77C -:101B4000C7FE85F311880321636884F8675021700C -:101B50001B680BB12046984794F85E30002BDFD00D -:101B600084F867300423237063681B68002BD7D088 -:101B7000022120469847D3E794F860301D0603F011 -:101B80000F0120460AD501F09DF8012804D0022853 -:101B90007FF417AF2A4B9BE72A4B99E701F084F8B3 -:101BA000F3E794F85E30002B7FF40BAF94F86030CD -:101BB00013F00F01B4D01A06204602D501F01CFB29 -:101BC000AEE701F00FFBABE794F85E30002B7FF43B -:101BD000F8AE94F8603013F00F01A1D01B06204638 -:101BE00002D501F0F5FA9BE701F0E8FA98E7142333 -:101BF00084F84C30FFF728FE2A462B46294620461B -:101C0000FFF772FE85F31188ECE65DB1152384F8C9 -:101C10004C30FFF719FE0021D4E914232046FFF7CA -:101C200063FEFEE60B2384F84C30FFF70DFE2A46D8 -:101C30002B4629462046FFF769FEE3E7DC3B000818 -:101C4000D43B0008D83B000838B590F84C30044627 -:101C5000002B3CD0063BDAB20F2A32D80F2B30D8FB -:101C6000DFE803F0352F2F0821302F2F2F2F2F2FB4 -:101C70002F2F3535456DB0F862309D4213D2C368C1 -:101C80001B8AB5FBF3F203FB125565B9FFF7DCFDC8 -:101C90002A462B462946FFF739FE85F311880A2389 -:101CA00084F84C300DE0142384F84C30FFF7CCFD61 -:101CB00000231A4619462046FFF716FE002383F339 -:101CC000118838BD836D03B198470023E8E70021F0 -:101CD000204601F07DFA0021204601F06FFA63688A -:101CE0001B6813B10621204698470623D8E7000059 -:101CF00010B590F84C30142B044628D017D8062B7A -:101D000005D001D81BB110BD093B022BFBD8002127 -:101D1000204601F05DFA0021204601F04FFA636889 -:101D20001B6813B1062120469847062318E0152B9F -:101D3000E9D10B2380F84C30FFF786FD00231A46CB -:101D40001946FFF7E3FD002383F31188DBE7C3683F -:101D50009B695B68002BD6D1836D03B19847002344 -:101D600084F84C30CFE70000024B0022C3E9003377 -:101D70009A60704740260120002303748268054B57 -:101D80001B6899689142FBD25A68036042601060F8 -:101D9000586070474026012008B572B6202383F3AF -:101DA000118862B6037C032B05D0042B0DD02BB910 -:101DB00083F3118808BD436900221A604FF0FF3396 -:101DC0004361FFF7D9FF0023F2E7D0E90032136047 -:101DD0005A60F3E7002303748268054B1B68996817 -:101DE0009142FBD85A6803604260106058607047A7 -:101DF00040260120054B19690874186802681A60AA -:101E00005360186101230374FEF790BA4026012045 -:101E100030B54B1C0B4D87B0044610D02B690A4AD5 -:101E200001A800F007F92046FFF7E4FF049B13B177 -:101E300001A800F03BF92B69586907B030BDFFF7E6 -:101E4000D9FFF8E740260120991D000838B50C4D50 -:101E500041612B6981689A689142044603D8BDE8C4 -:101E60003840FFF789BF1846FFF7B4FF01232C6104 -:101E7000014623742046BDE83840FEF757BA00BF3C -:101E800040260120044B1A681B6990689B689842A1 -:101E900094BF0020012070474026012010B5084C57 -:101EA000236820691A6822605460012223611A7431 -:101EB000FFF790FF01462069BDE81040FEF736BAF3 -:101EC00040260120FFF7EABFFEE7000010B50C4CEA -:101ED000FFF74AFF00F0A0F80A498022204600F0F0 -:101EE00027F8012344F8180C037400F04BFC00237E -:101EF00083F3118862B60448BDE8104000F038B89A -:101F000068260120E03B0008F03B000800F008B91B -:101F1000034A516853685B1A9842FBD8704700BF68 -:101F2000001000E072B6202383F3118862B6704778 -:101F300082600222028270478368A3F17C0243F828 -:101F40000C2C026943F83C2C426943F8382C074AB0 -:101F500043F81C2CC26843F8102C022203F8082C0A -:101F6000002203F8072CA3F118007047450300086E -:101F700010B5FFF7D7FFFFF7DFFF00210446FFF79B -:101F800065FF002383F31188204610BD024B1B69B7 -:101F900058610F20FFF72EBF4026012008B5FFF73C -:101FA000C1FFBDE80840FFF7F1BF000008B50146DA -:101FB0000820FFF7B7FFFFF72BFF002383F31188FB -:101FC00008BD000049B1064B42681B6918605A60A1 -:101FD000136043600420FFF71BBF4FF0FF307047D2 -:101FE000402601200368984206D01A6802605060BB -:101FF00059611846FFF7C0BE7047000038B5044667 -:102000000D462068844200D138BD036823605C60BF -:102010004561FFF7B1FEF4E7054B03F11402C3E994 -:1020200005224FF0FF310022C3E90712704700BFBD -:102030004026012070B51C4EC0E9032305460C461E -:1020400001F0D8FA334653F8142F9A420DD130627A -:10205000C5E901242A600A2C2CBF00190A30C6E900 -:102060000555BDE8704001F0B3BA316A431AE31870 -:1020700038BF1C469368A34202D9081901F0B6FA8A -:1020800073699A6894420CD85A68AC602B606A6095 -:1020900015609A685D60121B9A604FF0FF33F36120 -:1020A00070BD1B68A41AECE74026012038B51B4C14 -:1020B000636998420DD0D0E9003213605A60002263 -:1020C0008168C2609A680A449A604FF0FF33E36106 -:1020D00038BD2246036842F8143F002193425A60FB -:1020E000C16003D1BDE8384001F07ABA9A688168CE -:1020F000256A0A449A6001F07DFA63699A68411B77 -:102100008A42E5D9AB181D1A092D206A98BF01F142 -:102110000A02BDE83840104401F068BA40260120A8 -:102120002DE9F041194C002704F11406656901F00E -:1021300061FA236AAA68C11A8A4217D81344236233 -:10214000D5E9003213605A606369D5F80C80EF60FE -:10215000B34201D101F044FA87F311882869C047DE -:1021600072B6202383F3118862B6DFE76169B1425A -:1021700009D013441B1ABDE8F0410A2B2CBFC0182C -:102180000A3001F033BABDE8F08100BF40260120DB -:1021900000207047FEE70000704700004FF0FF305E -:1021A0007047000072B6202383F3118862B670472F -:1021B00002290CD0032904D00129074818BF0020A8 -:1021C0007047032A05D8054800EBC2007047044851 -:1021D00070470020704700BFD43C0008482201200F -:1021E000883C000870B59AB00546084601A9144617 -:1021F00000F0BEF801A8FEF7ABFD431C5B00C5E98B -:1022000000340022237003236370C6B201AB023492 -:102210001046D1B28E4204F1020401D81AB070BD4A -:1022200013F8011B04F8021C04F8010C0132F0E75A -:1022300008B50448FFF7B6FFFFF786FA002383F3DB -:10224000118808BDF827012090F85C3003F01F02C8 -:10225000012A07D190F85D200B2A03D10023C0E9A1 -:10226000143315E003F06003202B08D1B0F8603080 -:102270002BB990F85D20212A03D81F2A04D8FFF734 -:1022800045BA222AEBD0FAE7034A026507224265E3 -:1022900083650120704700BF3F22012007B5052953 -:1022A00016D8DFE801F018150318181E104A01218E -:1022B000FFF778FF0190FFF7F1FA01980D4A02212C -:1022C000FFF7ECFA0C48FFF70BFA002383F31188B1 -:1022D00003B05DF804FB0848FFF764FFFFF7D6F989 -:1022E000F3E70548FFF75EFFFFF7EEF9EDE700BF04 -:1022F000283C00084C3C0008F827012038B50C4D5C -:102300000C4C0D492A4604F10800FFF76BFF05F15C -:10231000CA0204F110000949FFF764FF05F5CA720B -:1023200004F118000649BDE83840FFF75BBF00BF65 -:10233000C02C012048220120083C0008123C000863 -:102340001D3C000870B5044608460D46FEF700FD2A -:10235000C6B22046013403780BB9184670BD324628 -:102360002946FEF7E1FC0028F3D10120F6E7000042 -:102370002DE9F84F05460C46FEF7EAFC2B49C6B29C -:102380002846FFF7DFFF08B10236F6B22849284693 -:10239000FFF7D8FF08B11036F6B2632E0DD8DFF87C -:1023A0008C80DFF88C90234FDFF890A0DFF890B09E -:1023B0002E7846B92670BDE8F88F29462046BDE83C -:1023C000F84F01F0B1BB252E2BD1072241462846FC -:1023D000FEF7AAFC58B9DBF800302360DBF80430C4 -:1023E00063609BF80830237207350934E0E7082260 -:1023F00049462846FEF798FC98B90F4BA21C19785D -:1024000009090232C95D02F8041C13F8011B01F02E -:102410000F015345C95D02F8031CF0D1183408358B -:10242000C6E704F8016B0135C2E700BFF43C0008C1 -:102430001D3C0008063D000820F4F01F2CF4F01F9E -:10244000FC3C0008BFF34F8F024AD368DB03FCD487 -:10245000704700BF003C024008B5074B1B7853B9DA -:10246000FFF7F0FF054B1A69002ABFBF044A5A6004 -:1024700002F188325A6008BD1E2F0120003C024044 -:102480002301674508B5054B1B7833B9FFF7DAFF21 -:10249000034A136943F00043136108BD1E2F012056 -:1024A000003C02400728F0B516D80C4C0C492378A4 -:1024B0007BB90C4D0E4608234FF0006255F8047BA3 -:1024C00046F8042B013B13F0FF033A44F6D10123F5 -:1024D000237051F82000F0BD0020FCE7402F0120C0 -:1024E000202F0120183D0008014B53F820007047B1 -:1024F000183D000808207047072810B5044601D988 -:10250000002010BDFFF7CEFF064B53F824301844CF -:10251000C21A0BB90120F4E712680132F0D1043B72 -:10252000F6E700BF183D0008072810B5044621D87B -:10253000FFF788FFFFF790FF0F4AF323D360C30034 -:10254000DBB243F4007343F002031361136943F4F5 -:1025500080331361FFF776FFFFF7A4FF074B53F8B3 -:10256000241000F0D9F8FFF78DFF2046BDE8104099 -:10257000FFF7C2BF002010BD003C0240183D00081C -:10258000F8B512F00103144642D18218B2F1016F7E -:1025900057D82D4B1B6813F0010352D02B4DFFF77A -:1025A0005BFFF323EB60FFF74DFF40F20127032CA5 -:1025B00015D824F001046618244C401A40F2011783 -:1025C000B142236900EB010524D123F0010323610B -:1025D000FFF758FF0120F8BD043C0430E7E783070C -:1025E000E7D12B6923F440732B612B693B432B61AB -:1025F00051F8046B0660BFF34F8FFFF723FF0368AA -:102600009E42E9D02B6923F001032B61FFF73AFFCB -:102610000020E0E723F44073236123693B432361F7 -:102620000B882B80BFF34F8FFFF70CFF2D8831F8FD -:10263000023BADB2AB42C3D0236923F00103236157 -:10264000E4E71846C7E700BF00380240003C0240FC -:10265000084908B50B7828B11BB9FFF7FDFE012327 -:102660000B7008BD002BFCD0BDE808400870FFF7D8 -:1026700009BF00BF1E2F012010B50244064BD2B285 -:10268000904200D110BD441C00B253F8200041F824 -:10269000040BE0B2F4E700BF502800400F4B30B508 -:1026A0001C6F240407D41C6F44F400741C671C6F57 -:1026B00044F400441C670A4C236843F4807323608D -:1026C0000244084BD2B2904200D130BD441C00B24B -:1026D00051F8045B43F82050E0B2F4E700380240C0 -:1026E000007000405028004007B5012201A90020D9 -:1026F000FFF7C2FF019803B05DF804FB13B5044671 -:10270000FFF7F2FFA04205D0012201A900200194A9 -:10271000FFF7C4FF02B010BD0144BFF34F8F064B5B -:10272000884204D3BFF34F8FBFF36F8F7047C3F856 -:102730005C022030F4E700BF00ED00E0044BD3F86A -:1027400074389B0042BF034B01221A70704700BFD0 -:1027500000300240412F0120014B1878704700BF24 -:10276000412F0120EFF3098305494A6B22F0010252 -:102770004A63683383F30988002383F31188704721 -:1027800000EF00E0202080F3118862B60D4B0E4A66 -:10279000D96821F4E0610904090C0A43DA60D3F82E -:1027A000FC200A4942F08072C3F8FC20084AC2F8B3 -:1027B000B01F116841F0010111601022DA7783F82F -:1027C0002200704700ED00E00003FA0555CEACC5CD -:1027D000001000E010B572B6202383F3118862B6B2 -:1027E0000E4B5B6813F4006314D0F1EE103AEFF374 -:1027F0000984683C4FF08073E361094BDB6B23660F -:1028000084F30988FFF73EFB10B1064BA36110BDAE -:10281000054BFBE783F31188F9E700BF00ED00E00B -:1028200000EF00E0570300085A03000870B5BFF33B -:102830004F8FBFF36F8F1A4A0021C2F85012BFF3B7 -:102840004F8FBFF36F8F536943F400335361BFF36E -:102850004F8FBFF36F8FC2F88410BFF34F8FD2F842 -:102860008030C3F3C900C3F34E335B0143F6E07419 -:1028700003EA0406014646EA81750139C2F860524E -:10288000F9D2203B13F1200FF2D1BFF34F8F5369E0 -:1028900043F480335361BFF34F8FBFF36F8F70BD2D -:1028A00000ED00E0FEE700000A4B0B480B4A9042A7 -:1028B0000BD30B4BDA1C121AC11E22F003028B42FF -:1028C00038BF00220021FEF74BBA53F8041B40F832 -:1028D000041BECE7083F000854300120543001206D -:1028E000543001207047000070B5D0E91B439E684A -:1028F00000224FF0FF3504EB42135101D3F80009D9 -:102900000028BEBFD3F8000940F08040C3F800099A -:10291000D3F8000B0028BEBFD3F8000B40F0804076 -:10292000C3F8000B013263189642C3F80859C3F884 -:10293000085BE0D24FF00113C4F81C3870BD0000F2 -:102940001D4B03EB80022DE9F043D2F80CC0DD6E85 -:10295000DCF81420461CD2F800E005EB063605EB47 -:102960004018516871450AD3D5F83438012202FA6B -:1029700000F023EA0000C5F83408BDE8F083BCF895 -:102980001040AEEB0103A34228BF2346D8F81849F4 -:10299000A4B2B3EB840FF0D89468A4F1040959F8F9 -:1029A000047F3760A4EB09071F44042FF7D81C44A9 -:1029B0000B4494605360D4E7442F0120890141F017 -:1029C0002001016103699B06FCD41220FFF7A0BA25 -:1029D00010B5054C2046FEF73FFF4FF0A043E366DD -:1029E000024B236710BD00BF442F01205C3D00084F -:1029F00070B50378012B054650D12A4BC46E98421E -:102A00001BD1294B5A6B42F080025A635A6D42F037 -:102A100080025A655A6D5A6942F080025A615A69B9 -:102A200022F080025A610E2143205B6900F0EEFB28 -:102A30001E4BE3601E4BC4F800380023C4F8003E70 -:102A4000C0232360EE6E4FF40413A3633369002B9D -:102A5000FCDA012333610C20FFF75AFA3369DB07F4 -:102A6000FCD41220FFF754FA3369002BFCDA00265D -:102A7000A6602846FFF738FF6B68C4F81068DB686B -:102A8000C4F81468C4F81C684BB90A4BA3614FF032 -:102A9000FF336361A36843F00103A36070BD064B7D -:102AA000F4E700BF442F01200038024040140040EA -:102AB00003002002003C30C0083C30C0F8B5C46EB2 -:102AC000054600212046FFF779FF296F00234FF0CC -:102AD00001128F68C4F834384FF00066C4F81C281F -:102AE0004FF0FF3004EB431201339F42C2F80069FC -:102AF000C2F8006BC2F80809C2F8080BF2D20B68E2 -:102B0000EA6E6B67636210231361166916F0100694 -:102B1000FBD11220FFF7FCF9D4F8003823F4FE6350 -:102B2000C4F80038A36943F4402343F01003A361C1 -:102B30000923C4F81038C4F814380A4BEB604FF07E -:102B4000C043C4F8103B084BC4F8003BC4F81069FC -:102B5000C4F800396B6F03F1100243F480136A6705 -:102B6000A362F8BD383D000840800010C26E90F8A6 -:102B70006610D2F8003823F4FE6343EA0113C2F86A -:102B8000003870472DE9F84300EB8103C56EDA6821 -:102B9000166806F00306731E022B05EB41130C4664 -:102BA00080460FFA81F94FEA41104FF00001C3F857 -:102BB000101B4FF0010104F1100398BFB60401FA95 -:102BC00003F391698EBF334E06F1805606F5004639 -:102BD00000293AD0578A04F15801490137436F5010 -:102BE000D5F81C180B43C5F81C382B180021C3F866 -:102BF000101953690127611EA7409BB3138A928B5A -:102C00009B08012A88BF5343D8F87420981842EAD9 -:102C1000034301F1400205EB8202C8F8740021462B -:102C200053602846FFF7CAFE08EB8900C3681B8A79 -:102C300043EA8453483464011E432E51D5F81C38AE -:102C40001F43C5F81C78BDE8F88305EB4917D7F892 -:102C5000001B21F40041C7F8001BD5F81C1821EA1D -:102C60000303C0E704F13F0305EB83030A4A5A60FC -:102C700028462146FFF7A2FE05EB4910D0F800399F -:102C800023F40043C0F80039D5F81C3823EA0707BD -:102C9000D7E700BF0080001000040002026F126836 -:102CA0004267FFF721BE00005831C36E49015B58EF -:102CB00013F4004004D013F4001F0CBF02200120C5 -:102CC000704700004831C36E49015B5813F400405F -:102CD00004D013F4001F0CBF022001207047000035 -:102CE00000EB8101CB68196A0B6813604B68536075 -:102CF0007047000000EB810330B5DD68AA691368F6 -:102D0000D36019B9402B84BF402313606B8A1468C9 -:102D1000C26E1C44013CB4FBF3F46343033323F061 -:102D2000030302EB411043EAC44343F0C043C0F83D -:102D3000103B2B6803F00303012B09B20ED1D2F82C -:102D4000083802EB411013F4807FD0F8003B14BF29 -:102D500043F0805343F00053C0F8003B02EB4112B4 -:102D6000D2F8003B43F00443C2F8003B30BD000002 -:102D70002DE9F041254DEE6E06EB40130446D3F8E5 -:102D8000087BC3F8087B38070AD5D6F8143819072A -:102D900006D505EB84032146DB6828465B68984727 -:102DA000FA0721D5D6F81438DB071DD505EB8403C7 -:102DB000D968DCB98B69488A5A68B2FBF0F600FB27 -:102DC00016229AB91868DA6890420FD2121AC3E92B -:102DD000002472B6202383F3118862B60B48214683 -:102DE000FFF788FF84F31188BDE8F081012303FA1F -:102DF00004F26B8923EA02036B81CB68002BF3D0CA -:102E000021460248BDE8F041184700BF442F012089 -:102E100000EB810370B5DD68C36E6C692668E660FF -:102E20004A0156BB1A444FF40020C2F810092A6820 -:102E300002F00302012A0AB20ED1D3F8080803EB0C -:102E4000421410F4807FD4F8000914BF40F0805081 -:102E500040F00050C4F8000903EB4212D2F8000918 -:102E600040F00440C2F80009D3F83408012202FA05 -:102E700001F10143C3F8341870BD19B9402E84BF65 -:102E80004020206020682E8A8419013CB4FBF6F4AF -:102E900040EAC44040F000501A44C6E7F8B5044682 -:102EA0001F48C56E05EB4413D3F80869C3F80869D9 -:102EB000F10719D5D5F81038DA0715D500EB8403DA -:102EC000D9684B691F68DA6897421AD2D21B00276B -:102ED0001A605F6072B6202383F3118862B62146C0 -:102EE000FFF796FF87F31188330617D5D5F83428F6 -:102EF0000123A340134211D02046BDE8F840FFF75C -:102F00001FBD012303FA04F2038923EA02030381AC -:102F10008B68002BE8D021469847E5E7F8BD00BF55 -:102F2000442F01202DE9F74FA34CE66E7569B36974 -:102F30001D4015F48058756107D02046FEF7F8FC57 -:102F400003B0BDE8F04FFFF745BC002D12DAD6F80C -:102F5000003E99489F071EBFD6F8003E23F00303AA -:102F6000C6F8003ED6F8043823F00103C6F804384A -:102F7000FEF708FD280505D58F48FFF7B5FC8E48FC -:102F8000FEF7F0FCA9040CD5D6F8083813F0060FAC -:102F9000F36823F470530CBF43F4105343F4A0536D -:102FA000F3602A0704D56368DB680BB18248984751 -:102FB000EB0200F18A80AF0227D5D4F86C90DFF8DD -:102FC000F8B100274FF0010A09EB4712D2F8003B95 -:102FD00003F44023B3F5802F11D1D2F8003B002B2E -:102FE0000DDA62890AFA07F322EA0303638104EB2C -:102FF0008703DB68DB6813B1394658469847236F6F -:1030000001379B68FFB29F42DED9E80618D5E76E0C -:103010003A6AC2F30A1002F00F0302F4F012B2F59A -:10302000802F00F09D80B2F5402F09D104EB83037F -:103030000022DB681B6A07F58057904240F08280CF -:103040002B03D6F818481DD5E70302D50020FFF75B -:103050008FFEA60302D50120FFF78AFE600302D58A -:103060000220FFF785FE210302D50320FFF780FE33 -:10307000E20202D50420FFF77BFEA30202D5052061 -:10308000FFF776FE6F037FF55BAFE60702D5002002 -:10309000FFF704FFA50702D50120FFF7FFFE600739 -:1030A00002D50220FFF7FAFE210702D50320FFF721 -:1030B000F5FEE20602D50420FFF7F0FEA3067FF539 -:1030C0003FAF0520FFF7EAFE3AE7E36EDFF8E8B02E -:1030D000019300274FF0010A236F9B685FFA87F97D -:1030E00099453FF668AF019B03EB4913D3F80029DC -:1030F00002F44022B2F5802F22D1D3F80029002A11 -:103100001EDAD3F8002942F09042C3F80029D3F820 -:103110000029002AFBDBE06E4946FFF74FFC2289BD -:103120000AFA09F322EA0303238104EB8903DB682B -:103130009B6813B14946584698474846FFF700FC3C -:103140000137C9E7910708BFD7F80080072A98BF61 -:1031500003F8018B02F1010298BF4FEA18286CE7CF -:10316000023304EB830207F580575268D2F818C087 -:10317000DCF80820DCE9001CA1EB0C0C00218842E3 -:103180000AD104EB830463689B699A6802449A60DD -:103190005A6802445A6053E711F0030F08BFD7F88A -:1031A00000808C4588BF02F8018B01F1010188BFC6 -:1031B0004FEA1828E3E700BF442F0120C36E03EB5A -:1031C0004111D1F8003B43F40013C1F8003B7047B4 -:1031D000C36E03EB4111D1F8003943F40013C1F879 -:1031E00000397047C36E03EB4111D1F8003B23F463 -:1031F0000013C1F8003B7047C36E03EB4111D1F8D7 -:10320000003923F40013C1F80039704700F160431E -:1032100003F561430901C9B283F80013012200F0EC -:103220001F039A4043099B0003F1604303F5614388 -:10323000C3F880211A60704772B6202383F3118887 -:1032400062B6704730B5039C0172043304FB03255A -:10325000C0E90653049B03630021059BC160C0E9DC -:103260000000C0E90422C0E90842C0E90A11436332 -:1032700030BD0000416A0022C0E90411C0E90A2201 -:10328000C2606FF00101FEF7B9BE0000D0E9043260 -:10329000934201D1C2680AB9181D704700207047D7 -:1032A00003691960C2680132C260C269134482694D -:1032B0000361934224BF436A03610021FEF792BE7B -:1032C00038B504460D46E3683BB16269131D1268C8 -:1032D000A3621344E362002007E0237A33B929464E -:1032E0002046FEF76FFE0028EDDA38BD6FF00100D2 -:1032F000FBE70000C368C269013BC3604369134434 -:1033000082694361934224BF436A4361002383621D -:10331000036B03B11847704770B5FFF78DFF866ADE -:1033200004463EB9FFF7CCFF054618B186F3118875 -:10333000284670BDA36AE26A13F8015BA362934258 -:1033400002D32046FFF7D6FF002383F31188EFE76F -:103350002DE9F0479846FFF76FFF002504460E461B -:103360001746A946D4F828A0BAF1000F09D1414662 -:103370002046FFF7A5FF20B18AF311882846BDE853 -:10338000F087D4E90A12A7EB050A521A924528BF22 -:103390009246BAF1400F1BD9334601F1400251F871 -:1033A000040B43F8040B9142F9D1A36A4033403631 -:1033B000A3624035D4E90A239A4202D32046FFF79C -:1033C00099FF89F31188BD42D8D2FFF735FFC9E7CD -:1033D00030465246FDF79EFCA36A53445644A3620E -:1033E0005544E7E710B5029C0172043304FB032146 -:1033F000C0E906130023C0E90A33039B0363049B5F -:10340000C460C0E90000C0E90422C0E90842436387 -:1034100010BD0000026AC260426AC0E904220022B4 -:10342000C0E90A226FF00101FEF7E8BDD0E90423EC -:103430009A4201D1C26822B9184650F8043B0B6089 -:103440007047002070470000C368C2690133C36041 -:103450004369134482694361934224BF436A4361D1 -:103460000021FEF7BFBD000038B504460D46E368F5 -:103470003BB123691A1DA262E2691344E362002092 -:1034800007E0237A33B929462046FEF79BFD002842 -:10349000EDDA38BD6FF00100FBE700000369196049 -:1034A000C268013AC260C2691344826903619342EF -:1034B00024BF436A036100238362036B03B118478F -:1034C0007047000070B5FFF7B7FE866A0D460446E8 -:1034D00011462EB9FFF7C8FF10B186F3118870BDF1 -:1034E000A36A1D70A36AE26A01339342A36204D304 -:1034F000E16920460439FFF7D1FF002080F31188ED -:10350000EDE700002DE9F0479946FFF795FE00260C -:1035100004460D469046B246A76A4FB94946204632 -:10352000FFF7A2FF20B187F311883046BDE8F0878E -:10353000D4E90A073A1AA8EB0607974228BF1746AC -:10354000402F1BD905F1400355F8042B40F8042BFC -:103550009D42F9D1A36A4033A3624036D4E90A23DD -:103560009A4204D3E16920460439FFF797FF8AF3B2 -:1035700011884645D9D2FFF75FFECDE729463A4686 -:10358000FDF7C8FBA36A3B443D44A3623E44E5E724 -:10359000D0E904239A4217D1C3689BB1836A8BB1E7 -:1035A000043B9B1A0ED01360C368013BC360C36920 -:1035B0001A44836902619A4224BF436A036100236B -:1035C00083620123184670470023FBE700F094B89C -:1035D0004FF08043002258631A610222DA6070477C -:1035E0004FF080430022DA60704700004FF08043C4 -:1035F000586370474FF08043586A70474B68436088 -:103600008B688360CB68C3600B6943614B6903625D -:103610008B6943620B6803607047000008B52C4B50 -:103620002C481A6940F2FF710A431A611A6922F4A0 -:10363000FF6222F007021A611A691A6B0A431A63C1 -:103640001A6D0A431A65244A1B6D1146FFF7D6FF0F -:1036500002F11C0100F58060FFF7D0FF02F1380194 -:1036600000F58060FFF7CAFF02F1540100F58060A9 -:10367000FFF7C4FF02F1700100F58060FFF7BEFFA5 -:1036800002F18C0100F58060FFF7B8FF02F1A8019C -:1036900000F58060FFF7B2FF02F1C40100F5806021 -:1036A000FFF7ACFF02F1E00100F58060FFF7A6FF35 -:1036B00002F1FC0100F58060FFF7A0FF02F58C71BC -:1036C00000F58060FFF79AFFBDE8084000F08AB877 -:1036D0000038024000000240683D000808B500F0D4 -:1036E00003FAFEF7F3FBFFF729F8BDE80840FEF701 -:1036F00005BE0000704700000F4B1A6C42F001023B -:103700001A641A6E42F001021A660C4A1B6E936824 -:1037100043F0010393604FF080436B229A624FF0B5 -:10372000FF32DA6200229A615A63DA605A6001223B -:103730005A611A60704700BF00380240002004E060 -:103740004FF0804208B51169D3680B40D9B2C94324 -:103750009B07116109D572B6202383F3118862B6E5 -:10376000FEF7D4FB002383F3118808BD1B4B1A69B5 -:103770006FEA42526FEA52521A611A69C2F30A02A0 -:103780001A614FF0FF301A695A69586100215A696D -:1037900059615A691A6A62F080521A621A6A02F012 -:1037A00080521A621A6A5A6A58625A6A59625A6A86 -:1037B0000B4A106840F480701060186F00F440707D -:1037C000B0F5007F1EBF4FF480301867196753684B -:1037D00023F40073536000F05FB900BF003802406B -:1037E00000700040374B4FF080521A64364A4FF455 -:1037F000404111601A6842F001021A601A6892078B -:10380000FCD59A6822F003029A602E4B9A6812F057 -:103810000C02FBD1196801F0F90119609A601A686D -:1038200042F480321A601A689003FCD55A6F42F055 -:1038300001025A67234B5A6F9107FCD5234A5A60FD -:103840001A6842F080721A601F4B5A685204FCD505 -:103850001A6842F480321A605A68D003FCD51A689C -:1038600042F400321A60184A53689903FCD5154B8C -:103870001A689201FCD5164A9A6040F20112C3F808 -:103880008C200022C3F89020124A40F207331360C4 -:10389000136803F00F03072BFAD10A4B9A6842F022 -:1038A00002029A609A6802F00C02082AFAD15A6C55 -:1038B00042F480425A645A6E42F480425A665B6E09 -:1038C000704700BF0038024000700040086C40099B -:1038D00000948838003C0240074A08B5536903F059 -:1038E0000103536123B1054A13680BB1506898472F -:1038F000BDE80840FEF76EBF003C0140D42F012018 -:10390000074A08B5536903F00203536123B1054A1E -:1039100093680BB1D0689847BDE80840FEF75ABFDE -:10392000003C0140D42F0120074A08B5536903F039 -:103930000403536123B1054A13690BB150699847D9 -:10394000BDE80840FEF746BF003C0140D42F0120EF -:10395000074A08B5536903F00803536123B1054AC8 -:1039600093690BB1D0699847BDE80840FEF732BFB4 -:10397000003C0140D42F0120074A08B5536903F0E9 -:103980001003536123B1054A136A0BB1506A98477B -:10399000BDE80840FEF71EBF003C0140D42F0120C7 -:1039A000164B10B55C6904F478725A61A30604D50D -:1039B000134A936A0BB1D06A9847600604D5104A3F -:1039C000136B0BB1506B9847210604D50C4A936BCF -:1039D0000BB1D06B9847E20504D5094A136C0BB1C3 -:1039E000506C9847A30504D5054A936C0BB1D06C75 -:1039F0009847BDE81040FEF7EDBE00BF003C014017 -:103A0000D42F0120194B10B55C6904F47C425A6133 -:103A1000620504D5164A136D0BB1506D9847230506 -:103A200004D5134A936D0BB1D06D9847E00404D5CB -:103A30000F4A136E0BB1506E9847A10404D50C4A7F -:103A4000936E0BB1D06E9847620404D5084A136F89 -:103A50000BB1506F9847230404D5054A936F0BB1FF -:103A6000D06F9847BDE81040FEF7B4BE003C01405F -:103A7000D42F012008B50348FDF704FBBDE808403A -:103A8000FEF7A8BED423012008B5FFF759FEBDE814 -:103A90000840FEF79FBE0000062108B50846FFF764 -:103AA000B5FB06210720FFF7B1FB06210820FFF731 -:103AB000ADFB06210920FFF7A9FB06210A20FFF72D -:103AC000A5FB06211720FFF7A1FB06212820FFF701 -:103AD0009DFB07211C20FFF799FBBDE808400C2146 -:103AE0002520FFF793BB000008B5FFF73FFE00F06D -:103AF0000DF8FDF7D3FCFDF7ADFEFDF77FFDFFF7F9 -:103B0000F9FDBDE80840FFF761BD00000023054A4C -:103B100019460133102BC2E9001102F10802F8D155 -:103B2000704700BFD42F0120034611F8012B03F882 -:103B3000012B002AF9D1704753544D3332463F3F91 -:103B40003F3F3F3F0053544D333246375B347C3563 -:103B50005D780053544D333246375B367C375D78A1 -:103B600000000000F8270120D42301200096000067 -:103B70000000000000000000000000000000000045 -:103B80000000000000000000651400085114000847 -:103B90008D140008791400088514000871140008B9 -:103BA0005D14000849140008991400080000000082 -:103BB0007915000865150008A11500088D15000885 -:103BC0009915000885150008711500085D15000895 -:103BD000AD1500080000000001000000000000001A -:103BE0006D61696E0000000069646C650000000092 -:103BF000E83B000880260120F82701200100000092 -:103C0000C91E0008000000004172647550696C6FA5 -:103C1000740025424F415244252D424C0025534506 -:103C20005249414C25000000020000000000000045 -:103C3000951700080118000840004000902C012052 -:103C4000A02C012002000000000000000300000082 -:103C500000000000451800080000000010000000EF -:103C6000B02C012000000000010000000000000056 -:103C7000442F0120010102009D220008B12100080B -:103C8000492200083122000843000000903C00084F -:103C900009024300020100C03209040000010202CF -:103CA0000100052400100105240100010424020282 -:103CB0000524060001070582030800FF090401002E -:103CC000020A00000007050102400000070581020A -:103CD0004000000012000000DC3C0008120110014E -:103CE00002000040091241570002010203010000D6 -:103CF0000403090425424F41524425004265617383 -:103D0000744637763200303132333435363738390D -:103D1000414243444546000000800000008000000E -:103D2000008000000080000000000200000004008D -:103D300000000400000004000000000099190008C1 -:103D4000491C0008F11C000840004000BC2F012065 -:103D5000BC2F012001000000CC2F012080000000BA -:103D600040010000050000000001A86A00000000FA -:103D7000AAAAAAAA00011464FFFF00000000000024 -:103D800070A70A000000000000000000AAAAAAAA6A -:103D900000000000FFFF0000000000000000000025 -:103DA0000000000400000000AAAAAAAA0000000067 -:103DB000FFDF000000000000000000000000000025 -:103DC00000000000AAAAAAAA00000000FFFF00004D -:103DD00000000000000000000001000000000000E2 -:103DE000AAAAAAAA00010000FFFF0000000000002C -:103DF000000000000000000000000000AAAAAAAA1B -:103E000000000000FFFF00000000000000000000B4 -:103E10000000000000000000AAAAAAAA00000000FA -:103E2000FFFF000000000000000000000000000094 -:103E3000000000000A000000000000000300000075 -:103E40000000000000000000000000000000000072 -:103E50000000000000000000000000000000000062 -:103E60000000000000000000000000000000000052 -:103E70000000000000000000000000000000000042 -:103E80000000000000000000000000000000000032 -:103E90000000000000000000000000000000000022 -:103EA000210400000000000000800E00000000005F -:103EB000FF00000000000000383B00083F00000049 -:103EC00049040000453B00083F0000005104000089 -:103ED000533B00083F00000000960000000008006F -:103EE000960000000008000004000000F03C0008FC -:103EF00000000000000000000000000000000000C2 -:083F00000000000000000000B9 +:1003D000043000F0DFFB03B05DF804FB38B572B603 +:1003E000202383F3118862B61748C3680BB101F06C +:1003F000B9FE164A144800234FF47A7101F076FED4 +:10040000002383F31188124C236813B12368013B46 +:100410002360636813B16368013B63600D4D2B7803 +:1004200033B963687BB9022000F0A0FC322363601B +:100430002B78032B07D163682BB9022000F096FCC0 +:100440004FF47A73636038BD68220120DD03000831 +:10045000842301207C220120084B187003280CD82B +:10046000DFE800F008050208022000F075BC022059 +:1004700000F068BC024B00225A6070477C220120C9 +:1004800084230120F8B5404B404A1C4619680131CD +:1004900079D004339342F9D16268A24273D33C4BC2 +:1004A0009B6803F1006303F5C0339A426BD20020CE +:1004B00000F0A0FB0220FFF7CFFF364B00211A6CA3 +:1004C00019641A6E19661A6E5A6C59645A6E596616 +:1004D0005A6E5A6942F080025A615A6922F08002CB +:1004E0005A615A691A6942F000521A611A6922F077 +:1004F00000521A611B6972B64FF0E023C3F8084D31 +:10050000D4E90004BFF34F8FBFF36F8F224AC2F8C4 +:100510008410BFF34F8F536923F480335361BFF3CB +:100520004F8FD2F88030C3F3C905C3F34E335B015C +:1005300043F6E07603EA060C29464CEA8177013956 +:10054000C2F87472F9D2203B13F1200FF2D1BFF33D +:100550004F8FBFF36F8FBFF34F8FBFF36F8F536911 +:1005600023F4003353610023C2F85032BFF34F8F9E +:10057000BFF36F8F72B6202383F3118862B685466E +:1005800080F308882047F8BD00800108208001081A +:10059000002201200038024000ED00E02DE9F04F7C +:1005A00093B0B64B00902022FF210AA89D6800F06E +:1005B0000DFCB34A1378B3B9B24801211170C3607E +:1005C00072B6202383F3118862B6C3680BB101F0C1 +:1005D000C9FDAD4AAB4800234FF47A7101F086FDA6 +:1005E000002383F31188009B13B1A84B009A1A6073 +:1005F000A74A009C1378032B1EBF00231370A34A45 +:100600004FF0000A18BF5360D3465646D14601202A +:1006100000F0A2FB24B19D4B1B68002B00F0278249 +:10062000002000F099FA0390039B002BF2DB0120DD +:1006300000F088FB039B213B1F2BE8D801A252F856 +:1006400023F000BFC5060008ED060008810700087A +:100650000F0600080F0600080F0600081308000820 +:10066000E3090008FD0800085F0900088709000881 +:10067000AD0900080F060008BF0900080F060008B2 +:10068000310A0008650700080F060008750A00080F +:10069000D1060008650700080F0600085F0900087A +:1006A0000F0600080F0600080F0600080F060008D6 +:1006B0000F0600080F0600080F0600080F060008C6 +:1006C000810700080220FFF775FE002840F0F9813D +:1006D000009B0221BAF1000F08BF1C4605A841F299 +:1006E0001233ADF8143000F055FA90E74FF47A70F9 +:1006F00000F032FA071EEBDB0220FFF75BFE00285A +:10070000E6D0013F052F00F2DE81DFE807F0030AA3 +:100710000D10133605230593042105A800F03AFABD +:1007200017E056480421F9E75A480421F6E75A48E9 +:100730000421F3E74FF01C08404600F05DFA08F191 +:1007400004080590042105A800F024FAB8F12C0F44 +:10075000F2D1012000FA07F747EA0B0B5FFA8BFB97 +:100760004FF0000900F07EFB26B10BF00B030B2BC2 +:1007700008BF0024FFF726FE49E748480421CDE7DB +:10078000002EA5D00BF00B030B2BA1D10220FFF7FD +:1007900011FE074600289BD0012000F02BFA022012 +:1007A000FFF75AFE00265FFA86F8404600F032FA5C +:1007B0000446B0B10399A1F1400251425141404673 +:1007C00000F038FA01360028EDD1BA46044641F26D +:1007D0001213022105A8ADF814303E4600F0DAF9F4 +:1007E00015E70120FFF738FE2546244B9B68AB42F6 +:1007F00007D9284600F000FA013040F0678104353F +:10080000F3E7234B00251D70204BBA465D603E4642 +:10081000A8E7002E3FF45CAF0BF00B030B2B7FF42B +:1008200057AF0220FFF718FE322000F095F9B0F123 +:100830000008FFF64DAF18F003077FF449AF0F4AE9 +:10084000926808EB050393423FF642AFB8F5807F0C +:100850003FF73EAF124B0193B84523DD4FF47A705A +:1008600000F07AF90390039A002AFFF631AF019B5A +:10087000039A03F8012B0137EDE700BF00220120A6 +:100880008023012068220120DD0300088423012049 +:100890007C22012004220120082201200C220120B8 +:1008A00080220120C820FFF785FD074600283FF47D +:1008B0000FAF1F2D11D8C5F1200242450AAB25F01C +:1008C000030028BF424683490192184400F058FAB9 +:1008D000019A8048FF2100F079FA4FEAA8037D4988 +:1008E0000193C8F38702284600F078FA06460028EC +:1008F0003FF46DAF019B05EB830533E70220FFF763 +:1009000059FD00283FF4E4AE00F0C0F900283FF4A0 +:10091000DFAE0027B846704B9B68BB4218D91F2F2B +:1009200011D80A9B01330ED027F0030312AA1344F7 +:1009300053F8203C05934046042205A900F036FBFD +:1009400004378046E7E7384600F056F90590F2E7AD +:10095000CDF81480042105A800F01CF902E700235B +:10096000642104A8049300F00BF900287FF4B0AED2 +:100970000220FFF71FFD00283FF4AAAE049800F004 +:100980006DF90590E6E70023642104A8049300F0C4 +:10099000F7F800287FF49CAE0220FFF70BFD00283B +:1009A0003FF496AE049800F069F9EAE70220FFF7F9 +:1009B00001FD00283FF48CAE00F078F9E1E7022059 +:1009C000FFF7F8FC00283FF483AE05A9142000F0DF +:1009D00073F904210746049004A800F0DBF83946B7 +:1009E000B9E7322000F0B8F8071EFFF671AEBB077A +:1009F0007FF46EAE384A926807EB090393423FF6E4 +:100A000067AE0220FFF7D6FC00283FF461AE27F066 +:100A100003074F44B9453FF4A5AE484600F0ECF853 +:100A20000421059005A800F0B5F809F10409F1E7E3 +:100A30004FF47A70FFF7BEFC00283FF449AE00F097 +:100A400025F9002844D00A9B01330BD008220AA9BB +:100A5000002000F0C3F900283AD02022FF210AA884 +:100A600000F0B4F9FFF7AEFC1C4801F0FBFA13B03C +:100A7000BDE8F08F002E3FF42BAE0BF00B030B2BD9 +:100A80007FF426AE0023642105A8059300F078F8D2 +:100A9000074600287FF41CAE0220FFF78BFC80463F +:100AA00000283FF415AEFFF78DFC41F2883001F0CD +:100AB000D9FA059800F018FA464600F0D3F93C46FA +:100AC000A5E506464EE64FF0000901E6BA467EE689 +:100AD00037467CE68022012000220120A08601000A +:100AE000F7B5194E0C464FF47A7102FB01F396F9F3 +:100AF00000200546501C0BD114480193026829467A +:100B0000176A2246B8478442019B03D1002310E0B4 +:100B1000002AF1D096F90020511C01D0012A0DD1F4 +:100B20000B4802682946166A2246B047844205D11E +:100B30000123084A0120137003B0F0BD4FF4FA708E +:100B400001F090FA0020F7E710220120F827012099 +:100B5000D4230120D023012007B500230246012120 +:100B60000DF107008DF80730FFF7BAFF20B19DF8AF +:100B7000070003B05DF804FB4FF0FF30F9E7000019 +:100B80000A4608B50421FFF7ABFF80F00100C0B2B0 +:100B9000404208BD30B4074B0A461978064B53F85B +:100BA00021402368DD69054B0146AC46204630BC38 +:100BB000604700BFD0230120483C0008A086010008 +:100BC00070B501F0F3FC094E094D3080002428680F +:100BD0003388834208D901F0E3FC2B6804440133D5 +:100BE000B4F5C03F2B60F2D370BD00BFD22301200B +:100BF0008C23012001F09CBD00F1006000F5C030A5 +:100C00000068704700F10060920000F5C03001F00C +:100C10001BBD0000054B1A68054B1B889B1A8342BD +:100C200002D9104401F0BCBC002070478C23012085 +:100C3000D223012038B5084D044629B12868204444 +:100C4000BDE8384001F0CCBC2868204401F0B0FC7D +:100C50000028F3D038BD00BF8C23012010F003031F +:100C600009D1B0F5846F04D200F10050A0F57120D5 +:100C70000368184670470023FBE7000000F10050AE +:100C8000A0F57120D0F8200470470000064991F8C3 +:100C9000243033B10023086A81F824300822FFF79A +:100CA000B1BF0120704700BF90230120014B18689D +:100CB000704700BF002004E0F0B5204B02461868E2 +:100CC0001F4B1F885D6893F90840C0F30B06BE42B6 +:100CD0004FEA104022D09F89BE4221D01F8BBE42D6 +:100CE00006D102240C2505FB04335D6893F9084006 +:100CF000B0F5805F16D041F20103984208BF5A2434 +:100D0000013A0A44013D0B4693420DD215F9016F99 +:100D1000581C5EB100F8016C0346F5E70024E1E7DA +:100D20000124DFE74124EBE7184605E02C2590423B +:100D30001D7001D2981C5C70401AF0BD002004E0C8 +:100D400014220120022802BF024B4FF000529A6188 +:100D5000704700BF00080240022802BF024B4FF458 +:100D600000529A61704700BF00080240022801BF8C +:100D7000024A536983F400535361704700080240EC +:100D800010B50023934203D0CC5CC4540133F9E77F +:100D900010BD000010B5013810F9013F3BB191F9C9 +:100DA00000409C4203D11AB10131013AF4E71AB173 +:100DB00091F90020981A10BD1046FCE70346024640 +:100DC000D01A12F9011B0029FAD1704702440346D8 +:100DD000934202D003F8011BFAE770472DE9F8436C +:100DE0001F4D144695F824200746884652BBDFF86D +:100DF00070909CB395F824302BB92022FF214846EF +:100E00002F62FFF7E3FF95F82400C0F10802A24229 +:100E100028BF2246D6B24146920005EB8000FFF77C +:100E2000AFFF95F82430A41B1E44F6B2082E1744D9 +:100E30009044E4B285F82460DBD1FFF727FF002857 +:100E4000D7D108E02B6A03EB82038342CFD0FFF7B0 +:100E50001DFF0028CBD10020BDE8F8830120FBE76F +:100E600090230120024B1A78024B1A70704700BF82 +:100E7000D02301201022012038B5154C154D2046F5 +:100E800000F0F4FB2946204600F01CFC2D681248B7 +:100E9000EA6ED2F8043843F00203C2F8043801F0D5 +:100EA000E1F80E49284600F01BFDEA6E0C48D2F826 +:100EB00004380C4923F00203C2F80438A0424FF46E +:100EC000E1330B6003D0BDE8384000F02BBB38BDE8 +:100ED000F8270120543D000840420F005C3D000807 +:100EE000D4230120B823012038B50B4B1A780B4BC3 +:100EF00053F822500A4B9D4204460CD0094B002166 +:100F000018461822FFF762FF046001462846BDE834 +:100F1000384000F007BB38BDD0230120483C000812 +:100F2000F8270120B823012000B59BB0EFF3098119 +:100F300068226846FFF724FFEFF30583044B9A6BA2 +:100F4000DA6A9A6A9A6A9A6A9A6A9A6A9B6AFEE75F +:100F500000ED00E000B59BB0EFF309816822684620 +:100F6000FFF70EFFEFF30583044B9A6B9A6A9A6AB8 +:100F70009A6A9A6A9A6A9B6AFEE700BF00ED00E0EF +:100F800000B59BB0EFF3098168226846FFF7F8FED1 +:100F9000EFF30583034B5A6B9A6A9A6A9A6A9A6AC4 +:100FA0009B6AFEE700ED00E0FEE7000030B5094D6A +:100FB0000A4491420DD011F8013B5840082340F3F8 +:100FC0000004013B2C4013F0FF0384EA5000F6D1EB +:100FD000EFE730BD2083B8ED72B6202383F311888C +:100FE00062B67047026843681143016003B1184755 +:100FF00070470000024A136843F0C0031360704753 +:101000000010014013B50E4C204600F07FFA04F1A9 +:1010100014000C49009400234FF4807200F044F94E +:10102000094B0A4900944FF4807204F1380000F033 +:10103000B9F9074A074BC4E9172302B010BD00BF36 +:10104000D423012040240120F50F00084025012071 +:101050000010014000F36F0630B5037C214C0029DD +:1010600018BF0C46012B0CD11F4B984209D11F4BC6 +:101070005A6C42F010025A645A6E42F010025A66DC +:101080005B6E2268036EC16D846603EB5203B3FB93 +:10109000F2F36268150442BF23F0070503F007036B +:1010A00043EA4503CB60A36843F040034B60E36829 +:1010B00043F001038B6042F4967343F001030B602D +:1010C0004FF0FF330B62510505D512F0102205D009 +:1010D000B2F1805F04D080F8643030BD7F23FAE73E +:1010E0003F23F8E7503C0008D42301200038024099 +:1010F0002DE9F047C66D3768F4693462210705466B +:1011000017D014F0080118BF8021E20748BF41F052 +:101110002001A30748BF41F04001600748BF41F4E8 +:101120008071281DFFF758FFFFF75CFF002383F352 +:101130001188E20509D54FF40071281DFFF74CFF17 +:10114000FFF750FF002383F311884FF0000914F0DC +:10115000200835D13B0614D505F13809200610D5F5 +:101160004846FFF739FF00F04FF9002835DA08212B +:10117000281DFFF737FF27F080033360002383F338 +:101180001188790613D5620611D5FFF725FFD5E939 +:1011900013239A4208D12B6C33B11021281D27F05C +:1011A0004007FFF71FFF3760002383F31188E30632 +:1011B00018D5AA6E1369ABB1BDE8F047506918475E +:1011C000FFF70AFF736A95F864102846194000F08B +:1011D000B5F989F31188F469B9E7B06288F3118829 +:1011E000F469BBE7BDE8F08772B6202383F311886A +:1011F00062B67047F8B5154682680669AA420B4682 +:10120000816938BF8568761AB54204460BD2184604 +:101210002A46FFF7B5FDA3692B44A361A3685B1BB6 +:10122000A3602846F8BD0CD918463246FFF7A8FD42 +:10123000AF1BE1683A463044FFF7A2FDE3683B4448 +:10124000EBE718462A46FFF79BFDE368E5E7000059 +:1012500083689342F7B51546044638BF8568D0E9E0 +:101260000460361AB5420BD22A46FFF789FD63693E +:101270002B446361A36828465B1BA36003B0F0BDE9 +:101280000DD932460191FFF77BFD0199E068AF1B54 +:101290003A463144FFF774FDE3683B44E9E72A46E8 +:1012A000FFF76EFDE368E4E710B50A440024C3616C +:1012B000029B8460C0E90000C0E90511C1600261C1 +:1012C000036210BD08B5D0E90532934201D18268AE +:1012D00082B98268013282605A1C42611970D0E979 +:1012E00004329A4224BFC3684361002100F0D6FE55 +:1012F000002008BD4FF0FF30FBE7000070B504464A +:101300000D46FFF771FFA668A6B1A368A269013B6D +:10131000A360531CA36115782269934224BFE3683C +:10132000A361E3690BB120469847002383F311883A +:10133000284607E02946204600F0A0FE0028E2DA11 +:1013400086F3118870BD00002DE9F84FD0F81CA07D +:101350009946FFF749FF04460E46904615464FF062 +:10136000000B65B12A4631462046FFF743FF07468A +:1013700060B94946204600F081FE0028F1D00023E4 +:1013800083F31188A8EB0500BDE8F88FBAF1000FD0 +:1013900001D02046D0478BF31188ED1B3E44FFF768 +:1013A00023FFDEE7C0E90511C160C3611144009B62 +:1013B0008260C0E90000016103627047F8B504462D +:1013C0000D461646FFF710FFA768A7B1A368013BBB +:1013D000A36063695A1C62611D70D4E904329A42A9 +:1013E00024BFE3686361E3690BB12046984700209E +:1013F00080F3118807E03146204600F03FFE0028C8 +:10140000E2DA87F31188F8BDD0E905239A4210B5D6 +:1014100001D182687AB98268013282605A1C826185 +:101420001C7803699A4224BFC3688361002100F0DD +:1014300035FE204610BD4FF0FF30FBE72DE9F84F99 +:10144000D0F81CA09946FFF7CFFE04460E46904602 +:1014500015464FF0000B65B12A4631462046FFF78E +:10146000F7FE074660B94946204600F007FE00280F +:10147000F1D0002383F31188A8EB0500BDE8F88FB5 +:10148000BAF1000F01D02046D0478BF31188ED1B35 +:101490003E44FFF7A9FEDEE772B6202383F31188EE +:1014A00062B67047026843681143016003B1184790 +:1014B000704700001430FFF747BF00004FF0FF33C4 +:1014C0001430FFF741BF00003830FFF7B7BF00000E +:1014D0004FF0FF333830FFF7B1BF00001430FFF793 +:1014E0000DBF00004FF0FF311430FFF707BF0000C1 +:1014F0003830FFF763BF00004FF0FF323830FFF79E +:101500005DBF000000207047FFF77CBD044B036007 +:101510000023C0E90233436001230374704700BF16 +:10152000683C000810B50446FFF7B6FFFFF794FDCE +:1015300002232374002383F3118810BD38B5C369D7 +:1015400004460D461BB904210844FFF7ABFF2946AA +:1015500004F11400FFF7B6FE002806DA201D4FF450 +:101560008061BDE83840FFF79DBF38BD72B62023CB +:1015700083F3118862B670470268436811430160C3 +:1015800003B118477047000013B5446BD4F8943486 +:101590001A681178042915D1217C022912D11979F0 +:1015A000128901238B4013420CD101A904F14C0094 +:1015B00001F0AEFFD4F89444019B217902462068E3 +:1015C00000F0DAF902B010BD143001F033BF0000B2 +:1015D0004FF0FF33143001F02DBF00004C3002F00B +:1015E00003B800004FF0FF334C3001F0FDBF0000A6 +:1015F000143001F003BF00004FF0FF31143001F050 +:10160000FDBE00004C3001F0CFBF00004FF0FF32B4 +:101610004C3001F0C9BF00000020704710B5D0F871 +:1016200094341A6811780429044617D1017C0229E0 +:1016300014D15979528901238B4013420ED11430B1 +:1016400001F096FE024648B1D4F894444FF48073FA +:1016500061792068BDE8104000F07CB910BD000041 +:10166000406BFFF7DBBF0000704700007FB5124BF7 +:10167000036000234360C0E90233012502260F4BBB +:10168000057404460290019300F1840229460096F5 +:101690004FF48073143001F047FE094B0294CDE9FA +:1016A000006304F523724FF48073294604F14C0063 +:1016B00001F00AFF04B070BD903C000861160008FC +:1016C0008915000808B50A68FFF750FF0B7902EB8F +:1016D000830318624B790D3342F823008B7913B1E1 +:1016E00002EB8302106202230374C0F894140023F7 +:1016F00083F3118808BD000038B5037F044613B199 +:1017000090F85430ABB9201D01250221FFF734FFBA +:1017100004F1140025776FF0010100F0CBFC84F890 +:10172000545004F14C006FF00101BDE8384000F066 +:10173000C1BC38BD10B5012104460430FFF71CFFC1 +:101740000023237784F8543010BD000038B50446D8 +:101750000025143001F000FE04F14C00257701F063 +:10176000CBFE201D84F854500121FFF705FF2046D1 +:10177000BDE83840FFF752BF90F85C3003F06003DB +:10178000202B07D190F85D20212A4FF0000303D8C9 +:101790001F2A06D800207047222AFBD1C0E9143343 +:1017A00003E0034A02650722426583650120704712 +:1017B0003822012037B5D0F894341A6811780429FA +:1017C00004461AD1017C022917D119791289012303 +:1017D0008B40134211D100F14C05284601F04AFF1D +:1017E00058B101A9284601F093FED4F89444019B16 +:1017F00021790246206800F0BFF803B030BD000038 +:10180000F0B500EB810385B01E6A04460D46F6B1C3 +:1018100004EB8507301D0821FFF7A8FEFFF7ACFE9B +:10182000FB685B691B6806F14C001BB1019001F07D +:101830007DFE019803A901F06BFE024648B1039BAF +:101840002946204600F098F8002383F3118805B05C +:10185000F0BDFB685A691268002AF5D01B8A013B6B +:101860001340F1D104F15C02EAE700000D3138B514 +:1018700050F82140D4B1FFF779FED4F894241368CE +:10188000527903EB8203DB689B695D6845B10421F3 +:101890006018FFF771FE294604F1140001F072FD93 +:1018A0002046FFF7BBFE002383F3118838BD0000FC +:1018B0007047000072B6202383F3118862B6704728 +:1018C00001F0F8B810B501230446282200F8243BA3 +:1018D0000021FFF77BFA0023C4E9013310BD0000AB +:1018E00038B50025FFF7E6FF0446C0E90355C0E917 +:1018F0000555C0E90755416001F0ECF8022323705B +:1019000085F3118838BD000070B500EB81030546F2 +:101910005069DA600E46144618B110220021FFF714 +:1019200055FAA06918B110220021FFF74FFA31468D +:101930002846BDE8704001F097B90000826802F0C7 +:10194000011282600022C0E90422C0E9062202627C +:1019500001F016BAF0B400EB81044789E468012570 +:10196000A4698D403D43458123600023A2606360EC +:10197000F0BC01F031BA0000F0B400EB810407893B +:10198000E468012564698D403D430581236000239F +:10199000A2606360F0BC01F0ADBA000070B5022334 +:1019A000002504460370C0E90255C0E90455C0E9AA +:1019B00006554566056280F84C5001F0F1F8636801 +:1019C0001B6823B129462046BDE87040184770BD0A +:1019D000037880F868300523037043681B6810B5EE +:1019E00004460BB1042198470023A36010BD0000FA +:1019F00090F86820436802701B680BB105211847F6 +:101A00007047000070B590F84C30044613B10023C5 +:101A100080F84C3004F15C02204601F0D3F9636891 +:101A20009B68B3B994F85C3013F0600533D00021A3 +:101A3000204601F03FFC0021204601F031FC6368A4 +:101A40001B6813B1062120469847062384F84C30C2 +:101A500070BD204698470028E4D0B4F86230626D2B +:101A60009A4288BF636594F95C30656D002B80F203 +:101A70000281002D00F0F180092384F84C30FFF73B +:101A800019FF0021D4E914232046FFF775FF002336 +:101A900083F31188DCE794F85D2003F07F0343EAC9 +:101AA000022340F20232934200F0C48021D8B3F501 +:101AB000807F48D00DD8012B3FD0022B00F09280C0 +:101AC000002BB4D104F16402226502226265A36591 +:101AD000C3E7B3F5817F00F09A80B3F5407FA6D1CC +:101AE00094F85E30012BA2D1B4F8643043F00203C5 +:101AF00032E0B3F5006F4DD017D8B3F5A06F31D0F9 +:101B0000A3F5C063012B92D8636894F85E205E68E9 +:101B100094F85F10B4F860302046B047002886D0B3 +:101B200043682365036863651AE0B3F5106F36D028 +:101B300040F6024293427FF47AAF5B4B2365022367 +:101B400063650023C3E794F85E30012B7FF46FAF29 +:101B5000B4F8643023F00203C4E91455A4F86430E7 +:101B6000A5657AE7B4F85C30B3F5A06F0ED194F8B0 +:101B70005E3084F86630204601F06AF863681B68BE +:101B800013B1012120469847032323700023C4E9A1 +:101B900014339CE704F1670323650123C3E723782B +:101BA000042B0FD12046FFF785FEFFF7C7FE85F314 +:101BB00011880321636884F8675021701B680BB19A +:101BC0002046984794F85E30002BDFD084F86730C9 +:101BD0000423237063681B68002BD7D002212046A2 +:101BE0009847D3E794F860301D0603F00F012046B4 +:101BF0000AD501F0D9F8012804D002287FF417AFE4 +:101C00002A4B9BE72A4B99E701F0C0F8F3E794F8D9 +:101C10005E30002B7FF40BAF94F8603013F00F01AF +:101C2000B4D01A06204602D501F058FBAEE701F009 +:101C30004BFBABE794F85E30002B7FF4F8AE94F8E2 +:101C4000603013F00F01A1D01B06204602D501F031 +:101C500031FB9BE701F024FB98E7142384F84C3018 +:101C6000FFF728FE2A462B4629462046FFF772FE3C +:101C700085F31188ECE65DB1152384F84C30FFF74D +:101C800019FE0021D4E914232046FFF763FEFEE687 +:101C90000B2384F84C30FFF70DFE2A462B462946CD +:101CA0002046FFF769FEE3E7C03C0008B83C0008A7 +:101CB000BC3C000838B590F84C300446002B3CD0B2 +:101CC000063BDAB20F2A32D80F2B30D8DFE803F008 +:101CD000352F2F0821302F2F2F2F2F2F2F2F353536 +:101CE000456DB0F862309D4213D2C3681B8AB5FBC4 +:101CF000F3F203FB125565B9FFF7DCFD2A462B46CC +:101D00002946FFF739FE85F311880A2384F84C3001 +:101D10000DE0142384F84C30FFF7CCFD00231A4665 +:101D200019462046FFF716FE002383F3118838BDBD +:101D3000836D03B198470023E8E70021204601F0B6 +:101D4000B9FA0021204601F0ABFA63681B6813B1B1 +:101D50000621204698470623D8E7000010B590F8E2 +:101D60004C30142B044628D017D8062B05D001D8A8 +:101D70001BB110BD093B022BFBD80021204601F00E +:101D800099FA0021204601F08BFA63681B6813B1B1 +:101D9000062120469847062318E0152BE9D10B238E +:101DA00080F84C30FFF786FD00231A461946FFF7EE +:101DB000E3FD002383F31188DBE7C3689B695B685D +:101DC000002BD6D1836D03B19847002384F84C30A3 +:101DD000CFE70000024B0022C3E900339A6070474E +:101DE00040260120002303748268054B1B68996814 +:101DF0009142FBD25A68036042601060586070479D +:101E00004026012008B572B6202383F3118862B6FC +:101E1000037C032B05D0042B0DD02BB983F3118841 +:101E200008BD436900221A604FF0FF334361FFF79A +:101E3000D9FF0023F2E7D0E9003213605A60F3E7DC +:101E4000002303748268054B1B6899689142FBD894 +:101E50005A68036042601060586070474026012055 +:101E6000054B19690874186802681A605360186194 +:101E700001230374FEF75ABA4026012030B54B1CEB +:101E80000B4D87B0044610D02B690A4A01A800F018 +:101E90002DF92046FFF7E4FF049B13B101A800F0E1 +:101EA00061F92B69586907B030BDFFF7D9FFF8E732 +:101EB00040260120051E000838B50C4D41612B69F4 +:101EC00081689A689142044603D8BDE83840FFF71C +:101ED00089BF1846FFF7B4FF01232C610146237424 +:101EE0002046BDE83840FEF721BA00BF4026012059 +:101EF000044B1A681B6990689B68984294BF002045 +:101F0000012070474026012010B5084C2368206945 +:101F10001A6822605460012223611A74FFF790FF4F +:101F200001462069BDE81040FEF700BA40260120B6 +:101F300008B5FFF7DDFF18B1BDE80840FFF7E4BFC3 +:101F400008BD0000FFF7E0BFFEE7000010B50C4C35 +:101F5000FFF740FF00F0BCF80A498022204600F05D +:101F600043F8012344F8180C037400F07DFC0023AF +:101F700083F3118862B60448BDE8104000F054B8FD +:101F800068260120C43C0008D43C000800F024B9B5 +:101F9000EFF3118030B9EFF30583202272B682F39C +:101FA000118862B67047000010B530B9EFF30584B0 +:101FB000C4F3080414B180F3118810BDFFF7B8FF13 +:101FC00084F31188F9E70000034A516853685B1AEB +:101FD0009842FBD8704700BF001000E072B6202383 +:101FE00083F3118862B670478260022202827047D2 +:101FF0008368A3F17C0243F80C2C026943F83C2C63 +:10200000426943F8382C074A43F81C2CC26843F84D +:10201000102C022203F8082C002203F8072CA3F14D +:10202000180070474503000810B5FFF7D7FFFFF70A +:10203000DFFF00210446FFF73FFF002383F31188F1 +:10204000204610BD024B1B6958610F20FFF708BFE7 +:102050004026012008B5FFF7C1FFBDE80840FFF7A3 +:10206000F1BF000008B501460820FFF7B7FFFFF7F2 +:1020700005FF002383F3118808BD000049B1064B1A +:1020800042681B6918605A60136043600420FFF7C0 +:10209000F5BE4FF0FF30704740260120036898429C +:1020A00006D01A680260506059611846FFF79ABE60 +:1020B0007047000038B504460D462068844200D1C0 +:1020C00038BD036823605C604561FFF78BFEF4E771 +:1020D000054B03F11402C3E905224FF0FF31002242 +:1020E000C3E90712704700BF4026012070B51C4E9F +:1020F000C0E9032305460C4601F0EEFA334653F8D7 +:10210000142F9A420DD13062C5E901242A600A2CAD +:102110002CBF00190A30C6E90555BDE8704001F032 +:10212000C9BA316A431AE31838BF1C469368A34200 +:1021300002D9081901F0CCFA73699A6894420CD854 +:102140005A68AC602B606A6015609A685D60121B0B +:102150009A604FF0FF33F36170BD1B68A41AECE77F +:102160004026012038B51B4C636998420DD0D0E958 +:10217000003213605A6000228168C2609A680A4483 +:102180009A604FF0FF33E36138BD2246036842F89E +:10219000143F002193425A60C16003D1BDE838402A +:1021A00001F090BA9A688168256A0A449A6001F041 +:1021B00093FA63699A68411B8A42E5D9AB181D1AE4 +:1021C000092D206A98BF01F10A02BDE83840104489 +:1021D00001F07EBA402601202DE9F041194C00277C +:1021E00004F11406656901F077FA236AAA68C11A36 +:1021F0008A4217D813442362D5E9003213605A602B +:102200006369D5F80C80EF60B34201D101F05AFA4E +:1022100087F311882869C04772B6202383F3118899 +:1022200062B6DFE76169B14209D013441B1ABDE809 +:10223000F0410A2B2CBFC0180A3001F049BABDE8A2 +:10224000F08100BF4026012000207047FEE700001B +:10225000704700004FF0FF307047000072B6202337 +:1022600083F3118862B6704702290CD0032904D089 +:102270000129074818BF00207047032A05D80548E0 +:1022800000EBC2007047044870470020704700BF51 +:10229000B83D0008482201206C3D000870B59AB096 +:1022A0000546084601A9144600F0BEF801A8FEF74D +:1022B00085FD431C5B00C5E9003400222370032325 +:1022C0006370C6B201AB02341046D1B28E4204F143 +:1022D000020401D81AB070BD13F8011B04F8021CE7 +:1022E00004F8010C0132F0E708B50448FFF7B6FF27 +:1022F000FFF760FA002383F3118808BDF827012057 +:1023000090F85C3003F01F02012A07D190F85D209D +:102310000B2A03D10023C0E9143315E003F0600356 +:10232000202B08D1B0F860302BB990F85D20212A1D +:1023300003D81F2A04D8FFF71FBA222AEBD0FAE7E6 +:10234000034A02650722426583650120704700BF8A +:102350003F22012007B5052916D8DFE801F018153E +:102360000318181E104A0121FFF778FF0190FFF7AC +:10237000CBFA01980D4A0221FFF7C6FA0C48FFF785 +:10238000E5F9002383F3118803B05DF804FB0848E6 +:10239000FFF764FFFFF7B0F9F3E70548FFF75EFFCB +:1023A000FFF7C8F9EDE700BF0C3D0008303D00081D +:1023B000F827012038B50C4D0C4C0D492A4604F184 +:1023C0000800FFF76BFF05F1CA0204F1100009498C +:1023D000FFF764FF05F5CA7204F118000649BDE86D +:1023E0003840FFF75BBF00BFC02C0120482201200E +:1023F000EC3C0008F63C0008013D000870B50446BE +:1024000008460D46FEF7DAFCC6B2204601340378D2 +:102410000BB9184670BD32462946FEF7BBFC0028B2 +:10242000F3D10120F6E700002DE9F84F05460C46F0 +:10243000FEF7C4FC2B49C6B22846FFF7DFFF08B100 +:102440000236F6B228492846FFF7D8FF08B1103601 +:10245000F6B2632E0DD8DFF88C80DFF88C90234F16 +:10246000DFF890A0DFF890B02E7846B92670BDE86E +:10247000F88F29462046BDE8F84F01F0C7BB252E4E +:102480002BD1072241462846FEF784FC58B9DBF8D9 +:1024900000302360DBF8043063609BF8083023725F +:1024A00007350934E0E7082249462846FEF772FC62 +:1024B00098B90F4BA21C197809090232C95D02F8BC +:1024C000041C13F8011B01F00F015345C95D02F80C +:1024D000031CF0D118340835C6E704F8016B013548 +:1024E000C2E700BFD83D0008013D0008EA3D0008F2 +:1024F00020F4F01F2CF4F01FE03D0008BFF34F8FD5 +:10250000024AD368DB03FCD4704700BF003C0240A2 +:1025100008B5074B1B7853B9FFF7F0FF054B1A6955 +:10252000002ABFBF044A5A6002F188325A6008BDCF +:102530001E2F0120003C02402301674508B5054BD2 +:102540001B7833B9FFF7DAFF034A136943F00043FE +:10255000136108BD1E2F0120003C02400728F0B582 +:1025600016D80C4C0C4923787BB90C4D0E46082329 +:102570004FF0006255F8047B46F8042B013B13F042 +:10258000FF033A44F6D10123237051F82000F0BD37 +:102590000020FCE7402F0120202F0120FC3D0008F7 +:1025A000014B53F820007047FC3D0008082070479D +:1025B000072810B5044601D9002010BDFFF7CEFF53 +:1025C000064B53F824301844C21A0BB90120F4E723 +:1025D00012680132F0D1043BF6E700BFFC3D000871 +:1025E000072838B5044628D8FFF7D2FCFFF786FF46 +:1025F000FFF78EFF124AF323D360E300DBB243F40C +:10260000007343F002031361136943F480331361D1 +:1026100005462046FFF772FFFFF7A0FF094B53F86E +:10262000241000F0E9F82846FFF788FFFFF7BCFC0C +:102630002046BDE83840FFF7BBBF002038BD00BFD3 +:10264000003C0240FC3D000812F001032DE9F0417E +:1026500005460E4614464BD18218B2F1016F61D87F +:10266000314B1B6813F001035CD0304FFFF790FC37 +:10267000FFF74EFFF323FB60FFF740FF314640F2C8 +:102680000128032C18D824F00104284E0C446D1A9C +:1026900040F20118A142336905EB01072AD123F06A +:1026A00001033361FFF74AFFFFF77EFC0120BDE81D +:1026B000F081043C0435E4E7AB07E4D13B6923F443 +:1026C00040733B613B6943EA08033B6151F8046B8B +:1026D0002E60BFF34F8FFFF711FF2B689E42E8D0AB +:1026E0003B6923F001033B61FFF728FFFFF75CFC28 +:1026F0000020DCE723F440733361336943EA0803C5 +:1027000033610B883B80BFF34F8FFFF7F7FE3F88A5 +:1027100031F8023BBFB2BB42BCD0336923F00103A6 +:102720003361E1E71846C2E700380240003C02404E +:10273000084908B50B7828B11BB9FFF7E9FE01235A +:102740000B7008BD002BFCD0BDE808400870FFF7F7 +:10275000F5BE00BF1E2F012010B50244064BD2B2B9 +:10276000904200D110BD441C00B253F8200041F843 +:10277000040BE0B2F4E700BF502800400F4B30B527 +:102780001C6F240407D41C6F44F400741C671C6F76 +:1027900044F400441C670A4C236843F480732360AC +:1027A0000244084BD2B2904200D130BD441C00B26A +:1027B00051F8045B43F82050E0B2F4E700380240DF +:1027C000007000405028004007B5012201A90020F8 +:1027D000FFF7C2FF019803B05DF804FB13B5044690 +:1027E000FFF7F2FFA04205D0012201A900200194C9 +:1027F000FFF7C4FF02B010BD0144BFF34F8F064B7B +:10280000884204D3BFF34F8FBFF36F8F7047C3F875 +:102810005C022030F4E700BF00ED00E0034B1A68D3 +:102820001AB9034AD2F874281A607047442F01205D +:102830000030024008B5FFF7F1FF024B1868C0F303 +:10284000407008BD442F0120EFF3098305494A6B0E +:1028500022F001024A63683383F30988002383F37B +:102860001188704700EF00E0202080F3118862B6E5 +:102870000D4B0E4AD96821F4E0610904090C0A43A2 +:10288000DA60D3F8FC200A4942F08072C3F8FC20D9 +:10289000084AC2F8B01F116841F00101116010220E +:1028A000DA7783F82200704700ED00E00003FA05B4 +:1028B00055CEACC5001000E010B572B6202383F3EE +:1028C000118862B60E4B5B6813F4006314D0F1EE0E +:1028D000103AEFF30984683C4FF08073E361094BD1 +:1028E000DB6B236684F30988FFF702FB10B1064B0C +:1028F000A36110BD054BFBE783F31188F9E700BF27 +:1029000000ED00E000EF00E0570300085A03000864 +:1029100070B5BFF34F8FBFF36F8F1A4A0021C2F813 +:102920005012BFF34F8FBFF36F8F536943F40033DF +:102930005361BFF34F8FBFF36F8FC2F88410BFF3A3 +:102940004F8FD2F88030C3F3C900C3F34E335B011D +:1029500043F6E07403EA0406014646EA817501394C +:10296000C2F86052F9D2203B13F1200FF2D1BFF32D +:102970004F8F536943F480335361BFF34F8FBFF3DD +:102980006F8F70BD00ED00E0FEE700000A4B0B48C2 +:102990000B4A90420BD30B4BDA1C121AC11E22F0C9 +:1029A00003028B4238BF00220021FEF70FBA53F812 +:1029B000041B40F8041BECE7E83F000858300120F6 +:1029C00058300120583001207047000070B5D0E920 +:1029D0001B439E6800224FF0FF3504EB4213510168 +:1029E000D3F800090028BEBFD3F8000940F08040AA +:1029F000C3F80009D3F8000B0028BEBFD3F8000BC2 +:102A000040F08040C3F8000B013263189642C3F8CF +:102A10000859C3F8085BE0D24FF00113C4F81C3822 +:102A200070BD00001D4B03EB80022DE9F043D2F88E +:102A30000CC0DD6EDCF81420461CD2F800E005EB7B +:102A4000063605EB4018516871450AD3D5F834387D +:102A5000012202FA00F023EA0000C5F83408BDE8BC +:102A6000F083BCF81040AEEB0103A34228BF23461D +:102A7000D8F81849A4B2B3EB840FF0D89468A4F145 +:102A8000040959F8047F3760A4EB09071F44042F99 +:102A9000F7D81C440B4494605360D4E7482F0120BE +:102AA000890141F02001016103699B06FCD41220D9 +:102AB000FFF78ABA10B5054C2046FEF703FF4FF02A +:102AC000A043E366024B236710BD00BF482F0120DF +:102AD000403E000870B50378012B054650D12A4BC3 +:102AE000C46E98421BD1294B5A6B42F080025A6344 +:102AF0005A6D42F080025A655A6D5A6942F080025E +:102B00005A615A6922F080025A610E2143205B69A2 +:102B100000F0EEFB1E4BE3601E4BC4F800380023B0 +:102B2000C4F8003EC0232360EE6E4FF40413A36389 +:102B30003369002BFCDA012333610C20FFF744FAE0 +:102B40003369DB07FCD41220FFF73EFA3369002B10 +:102B5000FCDA0026A6602846FFF738FF6B68C4F849 +:102B60001068DB68C4F81468C4F81C684BB90A4BD9 +:102B7000A3614FF0FF336361A36843F00103A360D7 +:102B800070BD064BF4E700BF482F0120003802401B +:102B90004014004003002002003C30C0083C30C01C +:102BA000F8B5C46E054600212046FFF779FF296F6E +:102BB00000234FF001128F68C4F834384FF00066DC +:102BC000C4F81C284FF0FF3004EB431201339F423E +:102BD000C2F80069C2F8006BC2F80809C2F8080B15 +:102BE000F2D20B68EA6E6B67636210231361166999 +:102BF00016F01006FBD11220FFF7E6F9D4F80038E2 +:102C000023F4FE63C4F80038A36943F4402343F07F +:102C10001003A3610923C4F81038C4F814380A4B10 +:102C2000EB604FF0C043C4F8103B084BC4F8003BC6 +:102C3000C4F81069C4F800396B6F03F1100243F453 +:102C400080136A67A362F8BD1C3E00084080001034 +:102C5000C26E90F86610D2F8003823F4FE6343EA9F +:102C60000113C2F8003870472DE9F84300EB8103E7 +:102C7000C56EDA68166806F00306731E022B05EBB4 +:102C800041130C4680460FFA81F94FEA41104FF08C +:102C90000001C3F8101B4FF0010104F1100398BFAD +:102CA000B60401FA03F391698EBF334E06F18056E4 +:102CB00006F5004600293AD0578A04F15801490127 +:102CC00037436F50D5F81C180B43C5F81C382B1828 +:102CD0000021C3F8101953690127611EA7409BB357 +:102CE000138A928B9B08012A88BF5343D8F874201B +:102CF000981842EA034301F1400205EB8202C8F84A +:102D00007400214653602846FFF7CAFE08EB89008D +:102D1000C3681B8A43EA8453483464011E432E511E +:102D2000D5F81C381F43C5F81C78BDE8F88305EBBF +:102D30004917D7F8001B21F40041C7F8001BD5F84C +:102D40001C1821EA0303C0E704F13F0305EB8303EA +:102D50000A4A5A6028462146FFF7A2FE05EB4910B1 +:102D6000D0F8003923F40043C0F80039D5F81C38F6 +:102D700023EA0707D7E700BF008000100004000225 +:102D8000026F12684267FFF721BE00005831C36E20 +:102D900049015B5813F4004004D013F4001F0CBF2A +:102DA00002200120704700004831C36E49015B5882 +:102DB00013F4004004D013F4001F0CBF02200120C4 +:102DC0007047000000EB8101CB68196A0B68136043 +:102DD0004B6853607047000000EB810330B5DD683D +:102DE000AA691368D36019B9402B84BF40231360CC +:102DF0006B8A1468C26E1C44013CB4FBF3F4634359 +:102E0000033323F0030302EB411043EAC44343F0CE +:102E1000C043C0F8103B2B6803F00303012B09B239 +:102E20000ED1D2F8083802EB411013F4807FD0F8AD +:102E3000003B14BF43F0805343F00053C0F8003B05 +:102E400002EB4112D2F8003B43F00443C2F8003BCE +:102E500030BD00002DE9F041254DEE6E06EB40132C +:102E60000446D3F8087BC3F8087B38070AD5D6F8A0 +:102E70001438190706D505EB84032146DB6828467C +:102E80005B689847FA0721D5D6F81438DB071DD5BB +:102E900005EB8403D968DCB98B69488A5A68B2FBB0 +:102EA000F0F600FB16229AB91868DA6890420FD241 +:102EB000121AC3E9002472B6202383F3118862B684 +:102EC0000B482146FFF788FF84F31188BDE8F081A5 +:102ED000012303FA04F26B8923EA02036B81CB68B6 +:102EE000002BF3D021460248BDE8F041184700BF4F +:102EF000482F012000EB810370B5DD68C36E6C695B +:102F00002668E6604A0156BB1A444FF40020C2F816 +:102F100010092A6802F00302012A0AB20ED1D3F87E +:102F2000080803EB421410F4807FD4F8000914BFA2 +:102F300040F0805040F00050C4F8000903EB42120A +:102F4000D2F8000940F00440C2F80009D3F8340870 +:102F5000012202FA01F10143C3F8341870BD19B916 +:102F6000402E84BF4020206020682E8A8419013CB6 +:102F7000B4FBF6F440EAC44040F000501A44C6E7FF +:102F8000F8B504461F48C56E05EB4413D3F808692D +:102F9000C3F80869F10719D5D5F81038DA0715D53F +:102FA00000EB8403D9684B691F68DA6897421AD22C +:102FB000D21B00271A605F6072B6202383F311884A +:102FC00062B62146FFF796FF87F31188330617D5BF +:102FD000D5F834280123A340134211D02046BDE880 +:102FE000F840FFF71FBD012303FA04F2038923EA27 +:102FF000020303818B68002BE8D021469847E5E760 +:10300000F8BD00BF482F01202DE9F74FA34CE66E15 +:103010007569B3691D4015F48058756107D0204665 +:10302000FEF7BCFC03B0BDE8F04FFFF745BC002D38 +:1030300012DAD6F8003E99489F071EBFD6F8003E28 +:1030400023F00303C6F8003ED6F8043823F001034A +:10305000C6F80438FEF7CCFC280505D58F48FFF7E5 +:10306000B5FC8E48FEF7B4FCA9040CD5D6F8083898 +:1030700013F0060FF36823F470530CBF43F410539E +:1030800043F4A053F3602A0704D56368DB680BB1EF +:1030900082489847EB0200F18A80AF0227D5D4F826 +:1030A0006C90DFF8F8B100274FF0010A09EB4712E6 +:1030B000D2F8003B03F44023B3F5802F11D1D2F8AE +:1030C000003B002B0DDA62890AFA07F322EA0303B8 +:1030D000638104EB8703DB68DB6813B1394658462C +:1030E0009847236F01379B68FFB29F42DED9E806FD +:1030F00018D5E76E3A6AC2F30A1002F00F0302F421 +:10310000F012B2F5802F00F09D80B2F5402F09D16A +:1031100004EB83030022DB681B6A07F580579042AB +:1031200040F082802B03D6F818481DD5E70302D55E +:103130000020FFF78FFEA60302D50120FFF78AFECD +:10314000600302D50220FFF785FE210302D503208C +:10315000FFF780FEE20202D50420FFF77BFEA30208 +:1031600002D50520FFF776FE6F037FF55BAFE6071C +:1031700002D50020FFF704FFA50702D50120FFF7C5 +:10318000FFFE600702D50220FFF7FAFE210702D5F5 +:103190000320FFF7F5FEE20602D50420FFF7F0FE5C +:1031A000A3067FF53FAF0520FFF7EAFE3AE7E36E9F +:1031B000DFF8E8B0019300274FF0010A236F9B6806 +:1031C0005FFA87F999453FF668AF019B03EB491316 +:1031D000D3F8002902F44022B2F5802F22D1D3F88F +:1031E0000029002A1EDAD3F8002942F09042C3F8E1 +:1031F0000029D3F80029002AFBDBE06E4946FFF7DF +:103200004FFC22890AFA09F322EA0303238104EB23 +:103210008903DB689B6813B149465846984748467E +:10322000FFF700FC0137C9E7910708BFD7F8008016 +:10323000072A98BF03F8018B02F1010298BF4FEAF9 +:1032400018286CE7023304EB830207F580575268B5 +:10325000D2F818C0DCF80820DCE9001CA1EB0C0C4B +:10326000002188420AD104EB830463689B699A6851 +:1032700002449A605A6802445A6053E711F0030FFF +:1032800008BFD7F800808C4588BF02F8018B01F198 +:10329000010188BF4FEA1828E3E700BF482F01204B +:1032A000C36E03EB4111D1F8003B43F40013C1F8A6 +:1032B000003B7047C36E03EB4111D1F8003943F472 +:1032C0000013C1F800397047C36E03EB4111D1F808 +:1032D000003B23F40013C1F8003B7047C36E03EBBF +:1032E0004111D1F8003923F40013C1F800397047B7 +:1032F00000F1604303F561430901C9B283F800138B +:10330000012200F01F039A4043099B0003F1604330 +:1033100003F56143C3F880211A60704772B6202319 +:1033200083F3118862B6704730B5039C0172043391 +:1033300004FB0325C0E90653049B03630021059B9E +:10334000C160C0E90000C0E90422C0E90842C0E948 +:103350000A11436330BD0000416A0022C0E9041134 +:10336000C0E90A22C2606FF00101FEF7A3BE0000AF +:10337000D0E90432934201D1C2680AB9181D7047DE +:103380000020704703691960C2680132C260C269D7 +:10339000134482690361934224BF436A036100219D +:1033A000FEF77CBE38B504460D46E3683BB1626962 +:1033B000131D1268A3621344E362002007E0237A1E +:1033C00033B929462046FEF759FE0028EDDA38BD0C +:1033D0006FF00100FBE70000C368C269013BC360F6 +:1033E0004369134482694361934224BF436A436142 +:1033F00000238362036B03B11847704770B5FFF772 +:103400008DFF866A04463EB9FFF7CCFF054618B12A +:1034100086F31188284670BDA36AE26A13F8015B3F +:10342000A362934202D32046FFF7D6FF002383F323 +:103430001188EFE72DE9F0479846FFF76FFF002569 +:1034400004460E461746A946D4F828A0BAF1000F44 +:1034500009D141462046FFF7A5FF20B18AF3118824 +:103460002846BDE8F087D4E90A12A7EB050A521AEC +:10347000924528BF9246BAF1400F1BD9334601F15D +:10348000400251F8040B43F8040B9142F9D1A36AAE +:1034900040334036A3624035D4E90A239A4202D32E +:1034A0002046FFF799FF89F31188BD42D8D2FFF774 +:1034B00035FFC9E730465246FDF762FCA36A534424 +:1034C0005644A3625544E7E710B5029C01720433E9 +:1034D00004FB0321C0E906130023C0E90A33039B60 +:1034E0000363049BC460C0E90000C0E90422C0E992 +:1034F0000842436310BD0000026AC260426AC0E92C +:1035000004220022C0E90A226FF00101FEF7D2BDB9 +:10351000D0E904239A4201D1C26822B9184650F872 +:10352000043B0B607047002070470000C368C2690D +:103530000133C3604369134482694361934224BFEA +:10354000436A43610021FEF7A9BD000038B5044677 +:103550000D46E3683BB123691A1DA262E269134478 +:10356000E362002007E0237A33B929462046FEF7BC +:1035700085FD0028EDDA38BD6FF00100FBE70000A3 +:1035800003691960C268013AC260C2691344826962 +:103590000361934224BF436A036100238362036B88 +:1035A00003B118477047000070B5FFF7B7FE866A91 +:1035B0000D46044611462EB9FFF7C8FF10B186F339 +:1035C000118870BDA36A1D70A36AE26A0133934239 +:1035D000A36204D3E16920460439FFF7D1FF00203C +:1035E00080F31188EDE700002DE9F0479946FFF7D9 +:1035F00095FE002604460D469046B246A76A4FB98E +:1036000049462046FFF7A2FF20B187F311883046D4 +:10361000BDE8F087D4E90A073A1AA8EB06079742F3 +:1036200028BF1746402F1BD905F1400355F8042B3E +:1036300040F8042B9D42F9D1A36A4033A36240367F +:10364000D4E90A239A4204D3E16920460439FFF7FA +:1036500097FF8AF311884645D9D2FFF75FFECDE781 +:1036600029463A46FDF78CFBA36A3B443D44A362DE +:103670003E44E5E7D0E904239A4217D1C3689BB1E1 +:10368000836A8BB1043B9B1A0ED01360C368013B65 +:10369000C360C3691A44836902619A4224BF436AC2 +:1036A0000361002383620123184670470023FBE770 +:1036B00000F094B84FF08043002258631A61022250 +:1036C000DA6070474FF080430022DA6070470000F4 +:1036D0004FF08043586370474FF08043586A7047FB +:1036E0004B6843608B688360CB68C3600B69436140 +:1036F0004B6903628B6943620B680360704700008B +:1037000008B52C4B2C481A6940F2FF710A431A6124 +:103710001A6922F4FF6222F007021A611A691A6B11 +:103720000A431A631A6D0A431A65244A1B6D11462F +:10373000FFF7D6FF02F11C0100F58060FFF7D0FF14 +:1037400002F1380100F58060FFF7CAFF02F1540171 +:1037500000F58060FFF7C4FF02F1700100F58060A2 +:10376000FFF7BEFF02F18C0100F58060FFF7B8FFA4 +:1037700002F1A80100F58060FFF7B2FF02F1C40179 +:1037800000F58060FFF7ACFF02F1E00100F580601A +:10379000FFF7A6FF02F1FC0100F58060FFF7A0FF34 +:1037A00002F58C7100F58060FFF79AFFBDE80840D4 +:1037B00000F08AB800380240000002404C3E000889 +:1037C00008B500F003FAFEF7C1FBFFF727F8BDE8E4 +:1037D0000840FEF7EFBD0000704700000F4B1A6C69 +:1037E00042F001021A641A6E42F001021A660C4A93 +:1037F0001B6E936843F0010393604FF080436B228C +:103800009A624FF0FF32DA6200229A615A63DA60FC +:103810005A6001225A611A60704700BF00380240A6 +:10382000002004E04FF0804208B51169D3680B40D6 +:10383000D9B2C9439B07116109D572B6202383F31E +:10384000118862B6FEF7A2FB002383F3118808BD3E +:103850001B4B1A696FEA42526FEA52521A611A6997 +:10386000C2F30A021A614FF0FF301A695A695861AF +:1038700000215A6959615A691A6A62F080521A62C3 +:103880001A6A02F080521A621A6A5A6A58625A6AAE +:1038900059625A6A0B4A106840F480701060186FC1 +:1038A00000F44070B0F5007F1EBF4FF48030186701 +:1038B0001967536823F40073536000F05FB900BFC9 +:1038C0000038024000700040374B4FF080521A64BD +:1038D000364A4FF4404111601A6842F001021A6002 +:1038E0001A689207FCD59A6822F003029A602E4B60 +:1038F0009A6812F00C02FBD1196801F0F901196005 +:103900009A601A6842F480321A601A689003FCD5F3 +:103910005A6F42F001025A67234B5A6F9107FCD548 +:10392000234A5A601A6842F080721A601F4B5A6824 +:103930005204FCD51A6842F480321A605A68D003E7 +:10394000FCD51A6842F400321A60184A5368990389 +:10395000FCD5154B1A689201FCD5164A9A6040F2C4 +:103960000112C3F88C200022C3F89020124A40F2C2 +:1039700007331360136803F00F03072BFAD10A4BC8 +:103980009A6842F002029A609A6802F00C02082AD1 +:10399000FAD15A6C42F480425A645A6E42F4804220 +:1039A0005A665B6E704700BF0038024000700040EE +:1039B000086C400900948838003C0240074A08B56A +:1039C000536903F00103536123B1054A13680BB136 +:1039D00050689847BDE80840FEF76EBF003C0140C4 +:1039E000D82F0120074A08B5536903F00203536139 +:1039F00023B1054A93680BB1D0689847BDE80840E9 +:103A0000FEF75ABF003C0140D82F0120074A08B5F5 +:103A1000536903F00403536123B1054A13690BB1E1 +:103A200050699847BDE80840FEF746BF003C01409A +:103A3000D82F0120074A08B5536903F008035361E2 +:103A400023B1054A93690BB1D0699847BDE8084096 +:103A5000FEF732BF003C0140D82F0120074A08B5CD +:103A6000536903F01003536123B1054A136A0BB184 +:103A7000506A9847BDE80840FEF71EBF003C014071 +:103A8000D82F0120164B10B55C6904F478725A6186 +:103A9000A30604D5134A936A0BB1D06A984760060F +:103AA00004D5104A136B0BB1506B9847210604D50F +:103AB0000C4A936B0BB1D06B9847E20504D5094AC9 +:103AC000136C0BB1506C9847A30504D5054A936C51 +:103AD0000BB1D06C9847BDE81040FEF7EDBE00BFBB +:103AE000003C0140D82F0120194B10B55C6904F44B +:103AF0007C425A61620504D5164A136D0BB1506DB4 +:103B00009847230504D5134A936D0BB1D06D9847A0 +:103B1000E00404D50F4A136E0BB1506E9847A10410 +:103B200004D50C4A936E0BB1D06E9847620404D54D +:103B3000084A136F0BB1506F9847230404D5054A08 +:103B4000936F0BB1D06F9847BDE81040FEF7B4BE3D +:103B5000003C0140D82F012008B50348FDF7C8FA02 +:103B6000BDE80840FEF7A8BED423012008B5FFF742 +:103B700059FEBDE80840FEF79FBE0000062108B5CB +:103B80000846FFF7B5FB06210720FFF7B1FB06212A +:103B90000820FFF7ADFB06210920FFF7A9FB06214E +:103BA0000A20FFF7A5FB06211720FFF7A1FB06213E +:103BB0002820FFF79DFB07211C20FFF799FBBDE89C +:103BC00008400C212520FFF793BB000008B5FFF744 +:103BD0003FFE00F00DF8FDF797FCFDF771FEFDF7D5 +:103BE00043FDFFF7F9FDBDE80840FFF761BD0000A8 +:103BF0000023054A19460133102BC2E9001102F1D6 +:103C00000802F8D1704700BFD82F0120034611F8F1 +:103C1000012B03F8012B002AF9D1704753544D337F +:103C200032463F3F3F3F3F3F0053544D33324637CC +:103C30005B347C355D780053544D333246375B3608 +:103C40007C375D7800000000F8270120D423012094 +:103C500000960000000000000000000000000000CE +:103C6000000000000000000000000000D114000867 +:103C7000BD140008F9140008E5140008F114000848 +:103C8000DD140008C9140008B51400080515000863 +:103C900000000000E5150008D11500080D16000809 +:103CA000F915000805160008F1150008DD150008D3 +:103CB000C9150008191600080000000001000000E6 +:103CC000000000006D61696E0000000069646C65B1 +:103CD00000000000CC3C000880260120F8270120CD +:103CE00001000000491F00080000000041726475D7 +:103CF00050696C6F740025424F415244252D424C4F +:103D0000002553455249414C2500000002000000A7 +:103D100000000000011800086D1800084000400075 +:103D2000902C0120A02C01200200000000000000C7 +:103D30000300000000000000B118000800000000AF +:103D400010000000B02C0120000000000100000065 +:103D500000000000482F0120010102005523000847 +:103D60006922000801230008E9220008430000003E +:103D7000743D000809024300020100C0320904003A +:103D800000010202010005240010010524010001C8 +:103D9000042402020524060001070582030800FF2F +:103DA00009040100020A00000007050102400000AA +:103DB000070581024000000012000000C03D00081D +:103DC00012011001020000400912415700020102D5 +:103DD000030100000403090425424F415244250019 +:103DE0004265617374463776320030313233343590 +:103DF00036373839414243444546000000800000D0 +:103E00000080000000800000008000000000020030 +:103E10000000040000000400000004000000000096 +:103E2000051A0008B51C00085D1D00084000400090 +:103E3000C02F0120C02F012001000000D02F012041 +:103E40008000000040010000050000000001A86A99 +:103E500000000000AAAAAAAA00011464FFFF000043 +:103E60000000000070A70A00000000000000000031 +:103E7000AAAAAAAA00000000FFFF0000000000009C +:103E8000000000000000000400000000AAAAAAAA86 +:103E900000000000FFDF0000000000000000000044 +:103EA0000000000000000000AAAAAAAA000000006A +:103EB000FFFF000000000000000000000001000003 +:103EC00000000000AAAAAAAA00010000FFFF00004B +:103ED00000000000000000000000000000000000E2 +:103EE000AAAAAAAA00000000FFFF0000000000002C +:103EF000000000000000000000000000AAAAAAAA1A +:103F000000000000FFFF00000000000000000000B3 +:103F100000000000000000000A0000000000000097 +:103F2000030000000000000000000000000000008E +:103F30000000000000000000000000000000000081 +:103F40000000000000000000000000000000000071 +:103F50000000000000000000000000000000000061 +:103F60000000000000000000000000000000000051 +:103F70000000000000000000000000000000000041 +:103F8000210400000000000000800E00000000007E +:103F9000FF000000000000001C3C00083F00000083 +:103FA00049040000293C00083F00000051040000C3 +:103FB000373C00083F0000000096000000000800A9 +:103FC000960000000008000004000000D43D000836 +:103FD00000000000000000000000000000000000E1 +:083FE0000000000000000000D9 :00000001FF diff --git a/Tools/bootloaders/BeastH7_bl.bin b/Tools/bootloaders/BeastH7_bl.bin old mode 100644 new mode 100755 index 74ff9557445..eac65a1fa69 Binary files a/Tools/bootloaders/BeastH7_bl.bin and b/Tools/bootloaders/BeastH7_bl.bin differ diff --git a/Tools/bootloaders/BeastH7_bl.hex b/Tools/bootloaders/BeastH7_bl.hex index eef22214e3e..6debad981f8 100644 --- a/Tools/bootloaders/BeastH7_bl.hex +++ b/Tools/bootloaders/BeastH7_bl.hex @@ -1,34 +1,34 @@ :020000040800F2 -:1000000000060020A1020008791000087D100008F9 -:10001000D11000087D100008A5100008A3020008F8 -:10002000A3020008A3020008A3020008292A00086E +:1000000000060020A102000845100008C50F0008E6 +:100010001D100008C50F0008F10F0008A30200081A +:10002000A3020008A3020008A30200083529000863 :10003000A3020008A3020008A3020008A30200080C :10004000A3020008A3020008A3020008A3020008FC -:10005000A3020008A3020008353E0008613E000824 -:100060008D3E0008B93E0008E53E0008A3020008E6 +:10005000A3020008A3020008BD3D0008E93D000816 +:10006000153E0008413E00086D3E0008A30200084E :10007000A3020008A3020008A3020008A3020008CC :10008000A3020008A3020008A3020008A3020008BC -:10009000A3020008A3020008A3020008113F000801 +:10009000A3020008A3020008A3020008993E00087A :1000A000A3020008A3020008A3020008A30200089C :1000B000A3020008A3020008A3020008A30200088C :1000C000A3020008A3020008A3020008A30200087C -:1000D000A302000861110008A3020008A30200089F -:1000E000793F0008A3020008A3020008A302000849 +:1000D000A3020008713F0008A3020008A302000861 +:1000E000FD3E0008A3020008A3020008A3020008C6 :1000F000A3020008A3020008A3020008A30200084C -:10010000A3020008A3020008C13A0008A3020008E5 +:10010000A3020008A3020008853F0008A30200081C :10011000A3020008A3020008A3020008A30200082B :10012000A3020008A3020008A3020008A30200081B :10013000A3020008A3020008A3020008A30200080B :10014000A3020008A3020008A3020008A3020008FB :10015000A3020008A3020008A3020008A3020008EB :10016000A3020008A3020008A3020008A3020008DB -:10017000A302000861350008A3020008A3020008DA +:10017000A3020008A1340008A3020008A30200089B :10018000A3020008A3020008A3020008A3020008BB :10019000A3020008A3020008A3020008A3020008AB :1001A000A3020008A3020008A3020008A30200089B :1001B000A3020008A3020008A3020008A30200088B :1001C000A3020008A3020008A3020008A30200087B -:1001D000A30200084D350008A3020008A30200088E +:1001D000A30200088D340008A3020008A30200084F :1001E000A3020008A3020008A3020008A30200085B :1001F000A3020008A3020008A3020008A30200084B :10020000A3020008A3020008A3020008A30200083A @@ -41,1052 +41,1050 @@ :10027000A3020008A3020008A3020008A3020008CA :10028000A3020008A3020008A3020008A3020008BA :10029000A3020008A3020008A3020008A3020008AA -:1002A00002E000F000F8FEE772B6394880F30888F3 -:1002B000384880F3098838484EF60851CEF20001DC +:1002A00002E000F000F8FEE772B63A4880F30888F2 +:1002B000394880F3098839484EF60851CEF20001DA :1002C000086040F20000CCF200004EF63471CEF22D :1002D00000010860BFF34F8FBFF36F8F40F2000043 :1002E000C0F2F0004EF68851CEF200010860BFF374 :1002F0004F8FBFF36F8F4FF00000E1EE100A4EF604 :100300003C71CEF200010860062080F31488BFF330 -:100310006F8F02F0C7FB03F051FB4FF055301F49C0 -:100320001B4A91423CBF41F8040BFAE71C49194AA9 -:1003300091423CBF41F8040BFAE71A491A4A1B4B99 -:100340009A423EBF51F8040B42F8040BF8E7002034 -:100350001749184A91423CBF41F8040BFAE702F0F2 -:10036000E5FB03F09FFB144C144DAC4203DA54F848 -:10037000041B8847F9E700F03FF8114C114DAC42DF -:1003800003DA54F8041B8847F9E702F0CDBB0000FC -:1003900000060020002200200000000800000020CD -:1003A00000060020D843000800220020442200203C -:1003B0004822002060330020A0020008A0020008AC -:1003C000A0020008A00200082DE9F04F2DED108AD0 -:1003D000C1F80CD0D0F80CD0BDEC108ABDE8F08F7D -:1003E000002383F311882846A047002001F078FFFE -:1003F00001F094FE00DFFEE738B51F4C0123002515 -:1004000023700423A57063701A23E570257165714C -:10041000A571E57125726572A372E57200F008FDA1 -:1004200020B10E2325726572A372E57202F0BEFA46 -:10043000044602F0F3FA0546D0B9104B9C4219D09D -:1004400001339C4241F2883412BF05460024012545 -:10045000002002F0B5FA0DB100F05AF800F0B2FD3C -:1004600000F020FC204600F013F900F051F8F9E705 -:100470000024EDE70446EBE748220020010007B026 -:1004800008B500F08DFBA0F120035842584108BD8B -:10049000054B07B51B88022101A8ADF8043000F018 -:1004A000EBFB03B05DF804FB8040000810B520238F -:1004B00083F311881248C3680BB101F097FF002342 -:1004C000104A4FF47A710E4801F054FF002383F371 -:1004D00011880D4C236813B12368013B23606368C6 -:1004E00013B16368013B6360084B1B7833B96368E1 -:1004F00023B9022000F0D6FC3223636010BD00BF98 -:1005000054220020AD04000870230020682200203F -:10051000554B56492DE9F04153F8042F013201D1D2 -:10052000BDE8F0818B42F7D1514C524B22689A4280 -:1005300040F29880504B9B6803F1006303F5003351 -:100540009A4280F08F80002000F0D6FB02204B4BB7 -:10055000187000F09DFC4A4BD3F8E8200022C3F845 -:10056000E820D3F81011C3F81021D3F81011D3F8F4 -:10057000EC10C3F8EC20D3F81411C3F81421D3F80D -:100580001411D3F8F010C3F8F020D3F81811C3F801 -:100590001821D3F81811D3F8801041F00061C3F886 -:1005A0008010D3F8801021F00061C3F88010D3F8D8 -:1005B0008010D3F8801041F00071C3F88010D3F898 -:1005C000801021F00071C3F88010D3F8803072B62B -:1005D0002C4B2D490B601D682468BFF34F8FBFF370 -:1005E0006F8F2A4BC3F88420BFF34F8F5A6922F4D0 -:1005F00080325A61BFF34F8FD3F8802043F6E07EFC -:10060000C2F3C906C2F34E32B707520102EA0E081E -:1006100038463146013948EA000C00F14040B1F15A -:10062000FF3FC3F874C2F5D1203A12F1200FEDD18B -:10063000BFF34F8FBFF36F8FBFF34F8FBFF36F8F3A -:100640005A6922F400325A610022C3F85022BFF3E3 -:100650004F8FBFF36F8F202383F31188AD4685F34F -:1006600008882047BDE8F081FCFF01081C00020853 -:1006700004000208FFFF0108482200206822002031 -:10068000004402580000020808ED00E000ED00E020 -:100690002DE9F04F99B0B34C2022FF21019010A812 -:1006A000A66800F031FCB04AA3461378A3B9012133 -:1006B000AE481170C360202383F31188C3680BB167 -:1006C00001F094FE0023AA4A4FF47A71A74801F082 -:1006D00051FE002383F31188019B13B1A54B019AAE -:1006E0001A600023A44AA349019F99461C461D464F -:1006F000984613704B600292012000F0C9FB002F56 -:1007000000F012829B4B1B68002B40F00D8219B049 -:10071000BDE8F08F0220FFF7B3FE002840F0FB8118 -:10072000019BB9F1000F08BF1F46944B1B880221A3 -:100730000BA8ADF82C3000F09FFADDE74FF47A708B -:1007400000F02EFA031E0393EADB0220FFF798FE67 -:1007500082460028E4D0039B581E042800F2DD8165 -:10076000DFE800F0030E1114170018A80523042178 -:1007700040F8343D00F080FA54464FF0000856E04F -:1007800004217848F6E704217D48F3E704217D48F9 -:10079000F0E71C242046043400F0B0FA04210B904A -:1007A0000BA800F069FA2C2CF4D1E5E7002DB7D0A6 -:1007B000002CB5D00220FFF763FE0546002800F0AC -:1007C000AF8101206C4C00F097FA4FF00009022035 -:1007D000207000F05DFB5FFA89FA504600F09CFA49 -:1007E000074658B1504609F1010900F0A5FA002862 -:1007F000F1D12C46A9460027634B97E701233E46DB -:100800000220237000F03AFBDBF808309E4206D24B -:10081000304600F073FA0130EBD10436F4E70026DD -:10082000029BA9462C461E703746524B5E6000F074 -:10083000BFFB15B1002C18BF0027FFF729FE5BE7AF -:10084000002D3FF46DAF002C3FF46AAF0220029BF5 -:10085000187000F01DFB322000F0A2F9B0F1000A80 -:10086000C0F25E811AF0030540F05A8106EB0A03DC -:10087000DBF80820934200F25381BAF5807F00F242 -:100880004F8155450DDA4FF47A7000F089F90490E4 -:10089000049B002BC0F24481049B3C4AAB540135BD -:1008A000EFE7C820FFF7ECFD0546002800F038818F -:1008B0001F2E11D8C6F1200410AB26F003003349D7 -:1008C0005445184428BF5446224600F0F5FA224603 -:1008D000FF212E4800F018FB4FEAAA0A2B493046A8 -:1008E0005FFA8AF200F018FB0446002800F01A8133 -:1008F00006EB8A0605469AE70220FFF7C1FD0028AD -:100900003FF40EAF00F032FA00283FF409AF4FF089 -:10091000000A5346DBF8082092451CD2BAF11F0F9B -:1009200012D8109A01320FD02AF0030218A90A44F3 -:1009300052F8202C0B92184604220BA90AF1040A43 -:1009400000F0DAFB0346E5E75046039300F0D6F9E2 -:10095000039B0B90EFE718A8042140F84C3D00F0F2 -:100960008BF964E7482200206C23002054220020E9 -:10097000AD04000870230020682200208240000897 -:100980004C22002050220020844000086C220020CD -:1009900018A80023642140F8343D00F039F90028FC -:1009A0007FF4BEAE0220FFF76BFD00283FF4B8AE27 -:1009B0000B9800F0D3F918AB43F8480D0421184602 -:1009C000CDE718A80023642140F8343D00F020F959 -:1009D00000287FF4A5AE0220FFF752FD00283FF467 -:1009E0009FAE0B9800F0BCF918AB43F8440DE5E757 -:1009F0000220FFF745FD00283FF492AE00F0C6F953 -:100A000018AB43F8400DD9E70220FFF739FD002865 -:100A10003FF486AE0BA9142000F0BEF9824618A858 -:100A2000042140F83CAD00F027F951460BA896E7A9 -:100A3000322000F0B5F8B0F1000AFFF671AE1AF0FE -:100A4000030F7FF46DAE0AEB0803DBF80820934236 -:100A50003FF666AE0220FFF713FD00283FF460AEBC -:100A60002AF0030AC244D0453FF4E1AE404608F103 -:100A7000040800F043F904210A900AA800F0FCF8E9 -:100A8000F1E74FF47A70FFF7FBFC00283FF448AE23 -:100A900000F06CF900283FF4AFAE109B01330CD08E -:100AA000082210A9002000F037FA00283FF4A4AE75 -:100AB0002022FF2110A800F027FAFFF7E9FC3748B1 -:100AC00001F014FC23E6002D3FF42AAE002C3FF485 -:100AD00027AE18A80023642140F8343D00F098F8B0 -:100AE000824600287FF41CAE0220FFF7C9FC0028D4 -:100AF0003FF416AE0390FFF7CBFC41F28830574627 -:100B000001F0F4FB0B9800F097FA00F051FA039B08 -:100B10001C461D46F0E5054689E64FF00008FFE556 -:100B20002546FDE52C4667E6002000F039F80490E4 -:100B3000049B002BFFF6E3AD012000F09FF9049B1E -:100B4000213B122B3FF6D8AD01A252F823F000BF93 -:100B5000150700083D070008AD070008F906000862 -:100B6000F9060008F906000841080008310A0008E3 -:100B7000F908000891090008C3090008F1090008F4 -:100B8000F9060008090A0008F9060008830A0008A7 -:100B90002F080008F9060008C70A0008A08601000F -:100BA0002DE9F3474FF47A75002402AE154F454303 -:100BB000DFF8588006F8014D97F900305FFA84F9A4 -:100BC0005A1C01D0A34212D158F824000122314608 -:100BD0000368D3F820A02B46D047012807D10A4B41 -:100BE0009DF8070083F8009002B0BDE8F08701345B -:100BF000022CE1D14FF4FA7001F078FB4FF0FF3096 -:100C0000F2E700BF00220020BC230020984000082B -:100C10002DE9F0474FF47A7506460024134F4D43F3 -:100C2000DFF8508097F900305FFA84F95A1C01D040 -:100C3000A34210D158F82400042231460368D3F8A7 -:100C400020A02B46D047042805D1094B002083F86B -:100C50000090BDE8F0870134022CE3D14FF4FA7024 -:100C600001F044FB4FF0FF30BDE8F0870022002088 -:100C7000BC23002098400008074B30B41A78074B7B -:100C800053F822400A46014623682046DD69044B9A -:100C9000AC4630BC604700BFBC2300209840000831 -:100CA000A0860100F8B5104C0025104E01F066FD3D -:100CB0000F4F20703068237883420CD800250D4EEA -:100CC0002078013801F056FD23780544013BB542F8 -:100CD0002370F5D9F8BD01F04DFD336805440133AB -:100CE000BD423360E6D9E9E7BD2300207823002028 -:100CF000FFFF0100FFFF030001F00CBE00F10060E8 -:100D000000F500300068704700F10060920000F5C7 -:100D1000003001F08FBD0000054B1A68054B1B78B1 -:100D20009B1A834202D9104401F024BD0020704771 -:100D300078230020BD23002038B5074D04462868DD -:100D4000204401F01DFD28B928682044BDE8384042 -:100D500001F028BD38BD00BF782300200020704777 -:100D6000014BC058704700BF00E8F11F064991F8D9 -:100D7000243033B100230822086A81F82430FFF7B9 -:100D8000C3BF0120704700BF7C230020014B1868BF -:100D9000704700BF0010005C234BF0B5234C1B686C -:100DA0002788C3F30B0665681B0C94F90820BE4224 -:100DB00028D0A789BE4206D101220C2505FB02449A -:100DC000656894F9082041F20104A3421CD041F265 -:100DD0000304A3421AD042F20104A34218D042F203 -:100DE0000304A34208BF5622441E013D0B460C4497 -:100DF000A34217D215F9016F581C5EB1034600F8E3 -:100E0000016CF5E70022D8E75A22EDE75922EBE71B -:100E10005822E9E72C2584421D7001D9981C5A708C -:100E2000401AF0BD1846FBE70010005C04220020C9 -:100E3000104B41F201015B888B429AB211D041F212 -:100E400003018B420FD042F201039A420DD042F2CD -:100E500003039A420BD10323074A02EB8303D8789A -:100E600070470023F8E70123F6E70223F4E70020A8 -:100E7000704700BF0010005C88400008022803D1C2 -:100E80004FF00052014B9A61704700BF00080258B2 -:100E9000022803D14FF40052014B9A61704700BF02 -:100EA00000080258022804D1024A536983F400530F -:100EB0005361704700080258002310B5934203D0D5 -:100EC000CC5CC4540133F9E710BD000030B5441EBA -:100ED00014F9010F0B4658B193F9005001318542C6 -:100EE00006D11AB993F90020801A30BD013AEFE714 -:100EF000002AF7D1104630BD02460346981A13F96E -:100F0000011B0029FAD1704702440346934202D0E4 -:100F100003F8011BFAE770472DE9F047234C05461B -:100F20008846174694F8243083BB2E46DFF87C9021 -:100F3000C7B394F824302BB92022FF2148462662FB -:100F4000FFF7E2FF94F824004146C0F1080504EBE6 -:100F50008000BD4228BF3D465FFA85FAAD00A7EB91 -:100F60000A072A462E44FFF7A7FF94F82430A84426 -:100F7000FFB29A445FFA8AFABAF1080F84F824A003 -:100F8000D6D1FFF7F3FE0028D2D108E0266A06EB9F -:100F90008306B042CAD0FFF7E9FE0028C5D1002081 -:100FA000BDE8F0870120BDE8F08700BF7C2300206A -:100FB000024B1A78024B1A70704700BFBC23002006 -:100FC0000022002038B5164C164D204600F02CFCAF -:100FD0002946204600F054FC2D681348D5F890208F -:100FE000D2F8043843F00203C2F8043801F07EF965 -:100FF0000E49284600F054FDD5F890200C48D2F850 -:1010000004380C49A04223F00203C2F804384FF41C -:10101000E1330B6003D0BDE8384000F063BB38BD5E -:10102000E82A0020A041000840420F00C841000803 -:1010300040240020A423002038B50B4B05461A7825 -:101040000A4B53F822400A4B9C420CD0094B00211A -:1010500018221846FFF758FF056001462046BDE8F4 -:10106000384000F03FBB38BDBC230020984000084A -:10107000E82A0020A4230020FEE7000000B59BB072 -:10108000EFF3098168226846FFF716FFEFF3058347 -:10109000034B9A6B9A6A9A6A9A6A9A6A9B6AFEE703 -:1010A00000ED00E000B59BB0EFF3098168226846CF -:1010B000FFF702FFEFF30583044B9A6B9A6A9A6A73 -:1010C0009A6A9A6A9A6A9B6AFEE700BF00ED00E09E -:1010D00000B59BB0EFF3098168226846FFF7ECFE8C -:1010E000EFF30583034B5A6B9A6A9A6A9A6A9A6A73 -:1010F0009B6AFEE700ED00E030B50A44074D9142DF -:101100000BD011F8013B09245840013CF7D040F3C3 -:1011100000032B4083EA5000F7E730BD2083B8ED91 -:10112000002304491A465A50C81808334260802BDD -:10113000F9D17047C0230020024A136843F0C0036E -:101140001360704700100140044B5A6810439A68BE -:1011500058600AB1181D1047704700BF4024002096 -:101160002DE9F84F414EF56D2F68EC6921072C628F -:1011700019D014F0080F0CBF00208020E20748BFF0 -:1011800040F02000A3074FF0200348BF40F040008C -:10119000610748BF40F4807083F31188FFF7D4FFE4 -:1011A000002383F31188E20509D5202383F31188F6 -:1011B0004FF40070FFF7C8FF002383F311884FF04E -:1011C0002009DFF8A8A04FF0000B14F0200832D15E -:1011D0003B0615D54FF02009DFF894A020060FD567 -:1011E00089F31188504600F0F1F9002830DA082020 -:1011F000FFF7AAFF27F080032B60002383F31188F9 -:1012000079060DD562060BD5202383F31188F26C85 -:10121000336D9A4201D1336C03BB002383F31188F1 -:10122000E30604D5B26E13690BB150699847BDE867 -:10123000F84F01F009BC89F31188AB8C504696F841 -:101240006410194000F05CFA8BF31188EC69BCE77C -:1012500080B2288588F31188EC69BFE727F0400742 -:101260001020FFF771FF2F60D7E700BF4024002058 -:101270007824002013B5104C204600F027FA04F122 -:101280001400009400234FF400720C4900F0E8F8B9 -:1012900004F1380000944FF40072094B094900F042 -:1012A00061F9094B0C212520E365084B236602B048 -:1012B000BDE8104000F05EB840240020AC240020BF -:1012C00039110008AC2600200010014000E1F505AE -:1012D000254B002908BF1946037C012B816630B5D8 -:1012E00011D1224B98420ED1214BD3F8F02042F07D -:1012F0001002C3F8F020D3F8182142F01002C3F80E -:101300001821D3F818310A68036EC46D03EB520339 -:10131000B3FBF2F34A68150442BF23F0070503F05C -:10132000070343EA4503E3608B6843F040036360CF -:10133000CB68510543F00103A36042F4967343F078 -:10134000010323604FF0FF33236205D512F0102212 -:1013500005D0B2F1805F04D080F8643030BD7F23C7 -:10136000FAE73F23F8E700BFBC4000084024002014 -:101370000044025800F1604300F01F0209014009D7 -:1013800003F56143C9B2800083F80013012300F123 -:101390006040934000F56140C0F8803103607047C1 -:1013A000F8B51546826804460B46AA4200D2856805 -:1013B000A1692669761AB54207D218462A46FFF770 -:1013C0007BFDA3692B44A3610DE011D9AF1B32460D -:1013D0001846FFF771FD3A46E1683044FFF76CFDAF -:1013E000E2683A44A261A36828465B1BA360F8BD8B -:1013F00018462A46FFF760FDE368E4E783689342F6 -:101400002DE9F04104460F46154600D28568606913 -:101410002669361AB54207D22A463946FFF74CFDEF -:1014200063692B4463610EE013D9A5EB06083246CD -:101430003946FFF741FD4246B919E068FFF73CFD28 -:10144000E26842446261A36828465B1BA360BDE872 -:10145000F0812A463946FFF72FFDE368E2E70000F6 -:1014600010B50A440024C361029B006040608460A0 -:10147000C160816141610261036210BD08B582698A -:101480004369934201D1826882B9826801328260E5 -:101490005A1C42611970426903699A4201D3C368B8 -:1014A0004361002100F03EFF002008BD4FF0FF30F7 -:1014B00008BD000070B5202304460E4683F3118852 -:1014C000A568A5B1A368A269013BA360531CA361F1 -:1014D00015782269934224BFE368A361E3690BB1E5 -:1014E00020469847002383F31188284670BD314673 -:1014F000204600F007FF0028E2DA85F3118870BD6E -:101500002DE9F74F05460F4690469A46D0F81C90B5 -:10151000202686F311884FF0000B144664B1224652 -:1015200039462846FFF73CFF034668B9514628462E -:1015300000F0E8FE0028F1D0002383F31188A8EB27 -:10154000040003B0BDE8F08FB9F1000F03D00190A3 -:101550002846C847019B8BF31188E41A1F4486F381 -:101560001188DBE7C160816141611144C361009B67 -:10157000006040608260016103627047F8B5044614 -:101580000E461746202383F31188A568A5B1A368EA -:10159000013BA36063695A1C62611E702369626922 -:1015A0009A4224BFE3686361E3690BB12046984720 -:1015B000002080F31188F8BD3946204600F0A2FED5 -:1015C0000028E2DA85F31188F8BD000083694269DA -:1015D0009A4210B501D182687AB98268013282607C -:1015E0005A1C82611C7803699A4201D3C3688361E3 -:1015F000002100F097FE204610BD4FF0FF3010BDD7 -:101600002DE9F74F05460F4690469A46D0F81C90B4 -:10161000202686F311884FF0000B144664B1224651 -:1016200039462846FFF7EAFE034668B95146284680 -:1016300000F068FE0028F1D0002383F31188A8EBA6 -:10164000040003B0BDE8F08FB9F1000F03D00190A2 -:101650002846C847019B8BF31188E41A1F4486F380 -:101660001188DBE7026843681143016003B1184742 -:10167000704700001430FFF743BF00004FF0FF3306 -:101680001430FFF73DBF00003830FFF7B9BF00004E -:101690004FF0FF333830FFF7B3BF00001430FFF7CF -:1016A00009BF00004FF0FF311430FFF703BF000007 -:1016B0003830FFF763BF00004FF0FF323830FFF7DC -:1016C0005DBF000000207047FFF7D4BD044B0360EE -:1016D000002343608360C36001230374704700BF2D -:1016E000D440000810B52023044683F31188FFF787 -:1016F000EFFD02232374002383F3118810BD000043 -:1017000038B5C36904460D461BB904210844FFF7E8 -:10171000A9FF294604F11400FFF7B0FE002806DAFD -:10172000201D4FF48061BDE83840FFF79BBF38BDF6 -:10173000026843681143016003B118477047000015 -:1017400013B5446BD4F894341A681178042915D170 -:10175000217C022912D11979012312898B4013426D -:101760000CD101A904F14C0002F02CF8D4F89444F7 -:101770000246019B2179206800F0EAF902B010BD11 -:10178000143001F0AFBF00004FF0FF33143001F010 -:10179000A9BF00004C3002F081B800004FF0FF33C9 -:1017A0004C3002F07BB80000143001F07DBF000027 -:1017B0004FF0FF31143001F077BF00004C3002F0E1 -:1017C0004DB800004FF0FF324C3002F047B8000037 -:1017D000D0F8942438B5136805461978042901D047 -:1017E000012038BD017C0229FAD1127901205C89DF -:1017F00090400440F4D105F1140001F00FFF0246BF -:101800000028EDD0D5F894544FF480732868697996 -:1018100000F08CF9204638BD406BFFF7D9BF0000BF -:1018200000207047704700007FB5124B012502264B -:10183000044603600023057400F1840243602946D6 -:101840008360C3600C4B0290143001934FF480739B -:10185000009601F0BFFE094B04F52372294601935F -:1018600004F14C004FF480730294009601F086FF5F -:1018700004B070BDFC4000081918000841170008AA -:101880000A68202383F311880B790B3342F8230075 -:101890004B79133342F823008B7913B10B3342F8A1 -:1018A00023000223C0F894140374002383F31188E7 -:1018B0007047000038B5037F044613B190F85430E8 -:1018C000ABB90125201D0221FFF732FF04F11400FE -:1018D00025776FF0010100F031FD84F8545004F1D8 -:1018E0004C006FF00101BDE8384000F027BD38BD65 -:1018F00010B5012104460430FFF71AFF00232377B7 -:1019000084F8543010BD000038B50446002514306A -:1019100001F078FE04F14C00257701F047FF201D0F -:1019200084F854500121FFF703FF2046BDE83840FA -:10193000FFF74EBF90F8803003F06003202B19D1E1 -:1019400090F88120212A0AD0222A4FF000030ED0DD -:10195000202A0FD1084A42670722826704E0064B1B -:101960004367072383670023C367012070474367EA -:101970008367F9E7002070471C220020D0F89434D8 -:1019800037B51A680446117804291AD1017C022956 -:1019900017D11979012312898B40134211D100F11B -:1019A0004C05284601F0C2FF58B101A9284601F0B4 -:1019B00009FFD4F894440246019B2179206800F085 -:1019C000C7F803B030BD000001F10B03F7B550F8C4 -:1019D000234005460E46F4B1202383F3118805EB1E -:1019E0008607201D08214C34FFF7A2FEFB685B69C7 -:1019F0001B6813B1204601F0F3FE01A9204601F057 -:101A0000E1FE024648B1019B3146284600F0A0F8AD -:101A1000002383F3118803B0F0BDFB685A69126894 -:101A2000002AF5D01B8A013B1340F1D105F1800259 -:101A3000EAE70000133138B550F82140DCB120232B -:101A400083F31188D4F894241368527903EB82034A -:101A5000DB689B695D6845B104216018FFF768FE8B -:101A6000294604F1140001F0E3FD2046FFF7B0FE23 -:101A7000002383F3118838BD7047000001F0DEB801 -:101A8000012300F1300200F1500103700023436094 -:101A900042F8043B8A42D361FAD103814381704703 -:101AA00038B50446202383F31188002500F10C0388 -:101AB00000F13002416043F8045B9342FBD12046C1 -:101AC00001F0DEF80223237085F3118838BD000091 -:101AD00070B500EB8103054650690E461446DA6086 -:101AE00018B110220021FFF70FFAA06918B11022D7 -:101AF0000021FFF709FA31462846BDE8704001F0A1 -:101B0000D1B90000038900F13002002103F0010384 -:101B10000381438903F00103438100F1100343F87B -:101B2000041B9342FBD101F055BA0000F0B401252B -:101B300000EB810447898D40E4683D43A4694581F9 -:101B400023600023A2606360F0BC01F071BA000062 -:101B5000F0B4012500EB810407898D40E4683D4322 -:101B60006469058123600023A2606360F0BC01F01A -:101B7000E9BA0000022300F10C0200F1300110B5B7 -:101B8000037004460023A0F8883080F88A3080F87B -:101B90008B300381438142F8043B8A42FBD184F8B5 -:101BA0007030204601F012F963681B6823B12046AB -:101BB0000021BDE81040184710BD000002784368BE -:101BC00080F88C2005221B6802700BB10421184795 -:101BD00070470000436890F88C201B6802700BB1BE -:101BE000052118477047000090F8703070B5044622 -:101BF00013B1002380F8703004F18002204601F018 -:101C00000DFA63689B6863BB94F8805015F060061A -:101C100015D194F8813005F07F0545EA032540F29F -:101C200002339D4200F00E815BD8022D00F0DC8073 -:101C30003FD8002D00F08780012D00F0CF800021DB -:101C4000204601F0A3FC0021204601F093FC6368CC -:101C50001B6813B1062120469847062384F870308C -:101C600070BD204698470028CED094F8872094F87D -:101C7000863043EA0223A26F934238BFA36794F9E8 -:101C80008030A56F002B4FF0200380F2FD80002DE7 -:101C900000F0EC80092284F8702083F31188002181 -:101CA000A36F626F2046FFF753FF002383F3118871 -:101CB00070BDB5F5817F00F0B180B5F5407F49D0AA -:101CC000B5F5807FBBD194F88230012BB7D1B4F841 -:101CD000883023F00203A4F888306667A667E667B9 -:101CE000C3E740F201639D421ED8B5F5C06F3BD2F9 -:101CF000B5F5A06FA3D1B4F88030B3F5A06F0ED1C5 -:101D000094F88230204684F88A3001F0BDF8636888 -:101D10001B6813B101212046984703232370002339 -:101D20006367A367E367A0E7B5F5106F32D040F6AD -:101D300002439D4252D0B5F5006F80D104F18B0370 -:101D40006367012324E004F18803E56763670223E6 -:101D5000A3678AE794F88230012B7FF470AFB4F860 -:101D6000883043F00203B6E794F885202046616886 -:101D700094F884304D6843EA022394F8831094F871 -:101D80008220A84700283FF45AAF4368636703687E -:101D9000A367A4E72378042B10D1202383F31188B1 -:101DA0002046FFF7AFFE86F311886368032184F8AD -:101DB0008B601B6821700BB12046984794F88230E5 -:101DC000002BACD084F88B300423237063681B682D -:101DD000002BA4D0022120469847A0E7374B636729 -:101DE0000223A36700239DE794F88410204611F096 -:101DF000800F01F00F010ED001F002F9012806D08A -:101E000002287FF41CAF2E4BA067636767E72D4B5A -:101E1000A567636763E701F0E5F8EFE794F88230C0 -:101E2000002B7FF40CAF94F8843013F00F013FF4D3 -:101E300076AF1A06204602D501F0C0FB6FE701F02D -:101E4000B1FB6CE794F88230002B7FF4F8AE94F885 -:101E5000843013F00F013FF462AF1B06204602D519 -:101E600001F094FB5BE701F085FB58E7142284F84E -:101E7000702083F311882B462A4629462046FFF717 -:101E800055FE85F3118870BD5DB1152284F8702070 -:101E900083F311880021A36F626F2046FFF746FE8F -:101EA00003E70B2284F8702083F311882B462A461F -:101EB00029462046FFF74CFEE3E700BF2C4100080F -:101EC000244100082841000838B590F870300446D5 -:101ED000152B29D8DFE803F03E28282828283E289B -:101EE000280B293928282828282828283E3E90F819 -:101EF000871090F88620836F42EA01229A4214D913 -:101F0000C268128AB3FBF2F502FB15356DB92023C6 -:101F100083F311882B462A462946FFF719FE85F3DD -:101F200011880A2384F8703038BD142384F8703087 -:101F3000202383F31188002320461A461946FFF711 -:101F4000F5FD002383F3118838BDC36F03B19847B3 -:101F50000023E7E7002101F019FB0021204601F0F2 -:101F600009FB63681B6813B10621204698470623C6 -:101F7000D8E7000090F87020152A38B5044622D81A -:101F80000123934040F6416213421DD113F48015A2 -:101F90000FD19B0217D50B2380F87030202383F3D9 -:101FA00011882B462A462946FFF7D2FD85F3118872 -:101FB00038BDC3689B695B682BB9C36F03B1984791 -:101FC000002384F8703038BD002101F0DFFA0021D1 -:101FD000204601F0CFFA63681B6813B10621204642 -:101FE00098470623EDE70000024B00221B605B6070 -:101FF0009A607047AC280020002382680374054B68 -:102000001B6899689142FBD25A6803604260106075 -:1020100058607047AC28002008B5202383F311884E -:10202000037C032B05D0042B0DD02BB983F311882F -:1020300008BD436900221A604FF0FF334361FFF788 -:10204000DBFF0023F2E790E80C001A60026853609F -:10205000F2E70000002382680374054B1B6899684F -:102060009142FBD85A680360426010605860704724 -:10207000AC280020054B1969087418680268536081 -:102080001A60186101230374FEF79EB9AC28002082 -:102090004B1C30B5054687B00A4C10D0236901A807 -:1020A000094A00F067F92846FFF7E4FF049B13B1E3 -:1020B00001A800F09BF92369586907B030BDFFF70C -:1020C000D9FFF8E7AC2800201920000838B50C4DDE -:1020D000044641612B6981689A68914203D8BDE842 -:1020E0003840FFF789BF1846FFF786FF01232C61B0 -:1020F000014623742046BDE83840FEF765B900BFAD -:10210000AC280020044B1A681B6990689B689842B1 -:1021100094BF002001207047AC28002010B5084C67 -:10212000236820691A6854602260012223611A74AE -:10213000FFF790FF01462069BDE81040FEF744B963 -:10214000AC280020FEE7000010B5194CFFF74CFF4B -:1021500000F002F980221749204600F087F8012399 -:1021600044F8180C0374144B144AD96821F4E06144 -:102170000904090C0A431249DA60CA6842F0807205 -:10218000CA60104A1049C2F8B01F116841F001013D -:1021900011601022DA77202283F82220002383F3B3 -:1021A000118862B60948BDE8104000F081B800BF50 -:1021B000D42800203041000800ED00E00003FA05BB -:1021C000F0ED00E0001000E055CEACC5384100084D -:1021D0002DE9F84F1E4C4FF00008DFF87890656944 -:1021E00004F11407D9F82430266AAA689E1B964287 -:1021F0001CD34FF0200AAA68236AD5F80CB0B61A8F -:10220000134423622B68BB425F606361C5F80C8096 -:1022100001D101F0B7FB88F311882869D8478AF308 -:1022200011886569AB689E42E5D2DBE76269BA4214 -:102230000CD0916823628E1B9660A86802282CBF80 -:102240001818981CBDE8F84F01F0A2BBBDE8F88F44 -:10225000AC280020000C0040034B59685A68521A01 -:102260009042FBD8704700BF001000E0826002225D -:1022700002740022427470478368A3F17C0243F821 -:102280000C2C026943F83C2C426943F8382C074A6D -:1022900043F81C2CC268A3F1180043F8102C02224A -:1022A00003F8082C002203F8072C7047E10300080C -:1022B00010B5202383F31188FFF7DEFF00210446C9 -:1022C000FFF704FF002383F31188204610BD0000B0 -:1022D000024B1B6958610F20FFF7CCBEAC280020D1 -:1022E000202383F31188FFF7F3BF000008B50146F0 -:1022F000202383F311880820FFF7CAFE002383F30D -:10230000118808BD49B1064B42681B6918605A60C4 -:10231000136043600420FFF7BBBE4FF0FF307047EF -:10232000AC2800200368984206D01A68026050600A -:1023300018465961FFF760BE7047000038B5044683 -:102340000D462068844200D138BD036823605C607C -:102350004561FFF751FEF4E7054B03F114025A61A2 -:102360009A614FF0FF32DA6100221A62704700BFB3 -:10237000AC280020F8B5036102291A4B0646C2605A -:1023800038BF02215C6A184B1A461F4652F8145F88 -:1023900095420AD1586198611C6205604560816070 -:1023A0000819BDE8F84001F0E3BA186AAB68241ACE -:1023B0000C1902D3E41A2D6804E09C4202D2204496 -:1023C00001F0E6FAAB689C42F4D86B683560736044 -:1023D0001E604FF0FF336E60B460A968091BA960EE -:1023E000FB61F8BD000C0040AC28002010B41A4C72 -:1023F000234653F8141F814210D0416802680A60D6 -:10240000026851609A424FF00001C16003D09368A6 -:1024100081680B4493605DF8044B70470A680020A4 -:102420009A4262615360C86003D15DF8044B01F0C9 -:10243000A9BA936888680344206A9360074A526A7D -:10244000121A9342E7D9991A5DF8044B012998BFF3 -:10245000931C184401F09CBAAC280020000C0040EA -:1024600000207047FEE70000704700004FF0FF308B -:1024700070470000022906D0032906D0012906482A -:1024800018BF0020704705487047032A9ABF0448C8 -:1024900000EBC2000020704724420008D841000829 -:1024A0002422002070B59AB006460846144601ADB5 -:1024B000294600F095F82846FEF71EFDC0B2431CE1 -:1024C0005B0086E8180023700323023404F8013C03 -:1024D00000231946DAB20234904201D81AB070BD16 -:1024E000EA5C013304F8011C04F8022CF2E7000056 -:1024F00008B5202383F311880348FFF73FFA002330 -:1025000083F3118808BD00BFE82A002010B50446F7 -:10251000052916D8DFE801F016150316161D20232D -:1025200083F311880E4A0121FFF7D2FA20460D4AA3 -:102530000221FFF7CDFA0C48FFF7E6F9002383F3F9 -:10254000118810BD202383F311880748FFF7B2F9E3 -:10255000F4E7202383F311880348FFF7C9F9EDE777 -:10256000584100087C410008E82A002038B50C4D8D -:102570000C4C2A460C4904F10800FFF793FF05F1C3 -:10258000CA0204F110000949FFF78CFF05F5CA7271 -:1025900004F118000649BDE83840FFF783BF00BFCB -:1025A000B02F002024220020A8410008B2410008DA -:1025B000BD41000870B5044608460D46FEF79CFC78 -:1025C000C6B22046013403780BB9184670BD3246B6 -:1025D0002946FEF77BFC0028F3D1012070BD0000E6 -:1025E0002DE9F84F05460C46FEF786FC2B49C6B28E -:1025F0002846FFF7DFFF2A492846FFF7DBFF08B12F -:102600001036F6B2632E0DD8DFF89080DFF8909088 -:10261000244FDFF898A0DFF898B02E7846B92670DE -:10262000BDE8F88F29462046BDE8F84F01F020BDEF -:10263000252E2ED1072241462846FEF747FC70B9C9 -:10264000DBF800300735073444F8073CBBF80430AA -:1026500024F8033C9BF8063004F8013CDDE708222F -:1026600049462846FEF732FC98B9A21C0E4B13F8D7 -:10267000011F023209095345C95D02F8041C19788B -:1026800001F00F01C95D02F8031CF0D118340835C0 -:10269000C3E7267001350134BFE700BF444200089C -:1026A000BD41000854420008FFE7F11F0BE8F11F8D -:1026B0004C420008BFF34F8F044B1A695107FCD1FD -:1026C000D3F810215207F8D1704700BF0020005204 -:1026D00008B50D4B1B78ABB9FFF7ECFF0B4BDA6875 -:1026E000D10704D50A4A5A6002F188325A60D3F8F9 -:1026F0000C21D20706D5064AC3F8042102F188321C -:10270000C3F8042108BD00BF0E3200200020005293 -:102710002301674508B5114B1B78F3B9104B1A69B3 -:10272000510703D5DA6842F04002DA60D3F810218D -:10273000520705D5D3F80C2142F04002C3F80C2112 -:10274000FFF7B8FF064BDA6842F00102DA60D3F80F -:102750000C2142F00102C3F80C2108BD0E3200200A -:10276000002000520F289ABF00F58060400400202E -:10277000704700004FF40030704700001020704791 -:102780000F2808B50BD8FFF7EDFF00F500330268FE -:10279000013204D104308342F9D1012008BD002068 -:1027A00008BD00000F2810B504463FD8FFF782FF90 -:1027B000FFF78EFF1E484FF0FF33072C4361C0F830 -:1027C00014311DD80361FFF775FF230243F0240382 -:1027D000C360C36843F08003C36003695A07FCD435 -:1027E000FFF768FF2046FFF7BDFF4FF4003100F010 -:1027F000F7F8FFF78FFF2046BDE81040FFF7C0BF96 -:10280000C0F81031FFF756FFA4F108031B0243F094 -:102810002403C0F80C31D0F80C3143F08003C0F829 -:102820000C31D0F810315B07FBD4D9E7002010BD84 -:10283000002000522DE9F84F40EA020305460E46FB -:102840001746DB0656D13446DFF8C090DFF8C0A04B -:10285000FFF73EFF3B1B33441F2B04D8FFF75AFF03 -:102860000120BDE8F88F20222146284601F0F0FB28 -:10287000002837D005F17843214A22489342224B61 -:1028800098BF984603F5827392BFD346C8469B46CD -:10289000A3F1080388BF1846FFF70CFF4FF0FF3382 -:1028A00004F11C01A5EB040ECBF80030036843F0E3 -:1028B00002030360231FD8F8002012F0050FFAD19D -:1028C00053F8042F99424EF80320F4D1BFF34F8FF1 -:1028D000FFF7F0FE4FF0FF33CBF80030036823F032 -:1028E0000203036020222146284601F0B1FB20B1FB -:1028F000FFF710FF0020BDE8F88F20352034A9E74E -:10290000FFFF0F000C200052102000521021005237 -:102910001420005210B5084C237828B153B9FFF7A2 -:10292000D7FE0123237010BD23B12070BDE81040F5 -:10293000FFF7F0BE10BD00BF0E3200200244043984 -:10294000064BD2B210B5904200D110BD441C00B26B -:1029500053F8200041F8040FE0B2F4E7504000586B -:102960000F4B30B51C6F240405D41C6F1C671C6F03 -:1029700044F400441C670B4C024404392368D2B26F -:1029800043F480732360084B904200D130BD441C57 -:1029900051F8045F00B243F82050E0B2F4E700BF02 -:1029A00000440258004802585040005807B5012220 -:1029B00001A90020FFF7C2FF019803B05DF804FBF6 -:1029C00013B50446FFF7F2FFA04206D002A9012288 -:1029D000002041F8044DFFF7C3FF02B010BD000016 -:1029E0000144BFF34F8F064B884204D3BFF34F8F90 -:1029F000BFF36F8F7047C3F85C022030F4E700BF6D -:102A000000ED00E0034B1B685B0142BF0122024B5B -:102A10001A707047D04402580F320020014B1878CA -:102A2000704700BF0F320020064A536823F00103AD -:102A30005360EFF30983683383F30988002383F33A -:102A40001188704730EF00E010B5202383F3118820 -:102A5000104B5B6813F4006318D0F1EE103AEFF3FB -:102A600009844FF0807344F84C3C0B4BDB6844F80E -:102A7000083CA4F1680383F30988FFF743FB18B10E -:102A8000064B44F8503C10BD054BFAE783F3118820 -:102A900010BD00BF00ED00E030EF00E0F1030008E2 -:102AA000F4030008F0B5BFF34F8FBFF36F8F1D4BDA -:102AB0000021C3F85012BFF34F8FBFF36F8F5A69D5 -:102AC00042F400325A61BFF34F8FBFF36F8FC3F8E8 -:102AD0008410BFF34F8FD3F8802043F6E076C2F323 -:102AE000C904C2F34E32A507520102EA060E284677 -:102AF00021464EEA0007013900F14040C3F86072F8 -:102B00004F1CF6D1203A12F1200FEED1BFF34F8FB8 -:102B10005A6942F480325A61BFF34F8FBFF36F8F0F -:102B2000F0BD00BF00ED00E0FEE70000084A094BE1 -:102B300009498B4204D3094A0021934205D37047C7 -:102B400052F8040F43F8040BF3E743F8041BF4E7CF -:102B500018440008603300206033002060330020F8 -:102B6000D0F89430002230B51146D0F890409D68DE -:102B70004FF0FF3004EB421301329542C3F80019C5 -:102B8000C3F81019C3F80809C3F8001BC3F8101BD9 -:102B9000C3F8080BEED24FF00113C4F81C3830BD57 -:102BA00000EB81032DE9F04FD3F80CE04F1C4FEA06 -:102BB0004118DEF814403F03D4F800C06568D0F82F -:102BC000902065450AD30120D2F8343800FA01F18B -:102BD00023EA0101C2F83418BDE8F08FACEB05031D -:102BE000BEF81060B34228BF334602EB0806D6F8A1 -:102BF0001869B6B2B3EB860F13D8A6683A44994663 -:102C0000A6F1040A5AF804BFB9F1040FC2F800B0E3 -:102C100002D9A9F10409F5E71E442B44A6606360BC -:102C2000CCE70020BDE8F08F890141F0200101616F -:102C300003699B06FCD41220FFF70EBB10B50A4CAB -:102C40002046FEF71DFF094BC4F89030084BC4F82E -:102C50009430084C2046FEF713FF074BC4F8903021 -:102C6000064BC4F8943010BD10320020000008401C -:102C70008C420008AC32002000000440984200085A -:102C80000378012B70B505465DD1494BD0F89040D3 -:102C9000984259D1474B0E216520D3F8D82042F0F5 -:102CA0000062C3F8D820D3F8002142F00062C3F8D4 -:102CB0000021D3F80021D3F8802042F00062C3F84D -:102CC0008020D3F8802022F00062C3F88020D3F85F -:102CD0008030FEF74FFB384BE360384BC4F80038C8 -:102CE0000023D5F89060C4F8003EC02323604FF461 -:102CF0000413A3633369002BFCDA01230C20336136 -:102D0000FFF7AAFA3369DB07FCD41220FFF7A4FA15 -:102D10003369002BFCDA00262846A660FFF720FF67 -:102D20006B68C4F81068DB68C4F81468C4F81C68E1 -:102D3000002B3AD1224BA3614FF0FF336361A368AC -:102D400043F00103A36070BD1E4B9842C8D1194BDC -:102D50000E214D20D3F8D82042F00072C3F8D820BD -:102D6000D3F8002142F00072C3F80021D3F800210B -:102D7000D3F8802042F00072C3F88020D3F880207E -:102D800022F00072C3F88020D3F88020D3F8D82036 -:102D900022F08062C3F8D820D3F8002122F08062AC -:102DA000C3F80021D3F8003193E7074BC3E700BF16 -:102DB000103200200044025840140040030020025A -:102DC000003C30C0AC320020083C30C0F8B5D0F830 -:102DD0009040054600214FF000662046FFF724FF93 -:102DE000D5F8941000234FF001128F684FF0FF3098 -:102DF000C4F83438C4F81C2804EB431201339F4252 -:102E0000C2F80069C2F8006BC2F80809C2F8080BE2 -:102E1000F2D20B68D5F89020C5F898306362102381 -:102E20001361166916F01006FBD11220FFF714FA91 -:102E3000D4F8003823F4FE63C4F80038A36943F4DF -:102E4000402343F01003A3610923C4F81038C4F8E9 -:102E500014380B4BEB604FF0C043C4F8103B094BE8 -:102E6000C4F8003BC4F81069C4F80039D5F89830AC -:102E700003F1100243F48013C5F89820A362F8BD53 -:102E80006842000840800010D0F8902090F88A1026 -:102E9000D2F8003823F4FE6343EA0113C2F8003885 -:102EA000704700002DE9F0410EB20D4600EB860898 -:102EB000D8F80C100F6807F00303022B53D0032B34 -:102EC00053D03F4A3F4F012B18BF1746D0F89040D0 -:102ED0004FEA451E002205F1100C04EB0E03C3F867 -:102EE000102B8A69002A42D04A8A05F158033A43D6 -:102EF0005B01E2500123D4F81C2803FA0CF31343BE -:102F0000C4F81C38A64400234A69CEF8103905F1EC -:102F10003F03002A3BD00A8A04EB8303898B920883 -:102F2000012988BF4A43D0F89810561841EA024256 -:102F30002946C0F8986020465A60FFF775FED8F819 -:102F40000C301B8A43EA85531F4305F148035B019C -:102F5000E7500123D4F81C2803FA05F51543C4F8FB -:102F60001C58BDE8F081184FB0E7184FAEE704EBEE -:102F70004613D3F8002B22F40042C3F8002B0123A0 -:102F8000D4F81C2803FA0CF322EA0303B8E704EB95 -:102F900083030F4A04EB461629465A602046FFF782 -:102FA00043FED6F80039012223F4004302FA05F566 -:102FB000C6F80039D4F81C3823EA0505CFE700BF6E -:102FC00000800010008004100080081000800C10A9 -:102FD00000040002D0F894201268C0F89820FFF78F -:102FE000BFBD00005831D0F8903049015B5813F450 -:102FF000004004D013F4001F14BF012002207047CA -:103000004831D0F8903049015B5813F4004004D0A7 -:1030100013F4001F14BF01200220704700EB810150 -:10302000CB68196A0B6813604B68536070470000E7 -:1030300000EB810330B5DD68AA691368D36019B964 -:10304000402B84BF402313606B8A1468D0F8902013 -:103050001C4402EB4110013C09B2B4FBF3F463439E -:10306000033323F0030343EAC44343F0C043C0F8EF -:10307000103B2B6803F00303012B0ED1D2F8083864 -:1030800002EB411013F4807FD0F8003B14BF43F0F3 -:10309000805343F00053C0F8003B02EB4112D2F8DA -:1030A000003B43F00443C2F8003B30BD2DE9F04142 -:1030B000D0F8906005460C4606EB4113D3F8087B28 -:1030C0003A07C3F8087B08D5D6F814381B0704D58F -:1030D00000EB8103DB685B689847FA072FD5D6F8C9 -:1030E0001438DB072BD505EB8403D968CCB98B6981 -:1030F000488A5E68B6FBF0F200FB12628AB9186873 -:10310000DA6890420DD2121A83E81400202383F368 -:10311000118821462846FFF78BFF84F31188BDE80C -:10312000F081012303FA04F26B8923EA02036B8125 -:10313000CB6823B121462846BDE8F0411847BDE8D9 -:10314000F081000000EB81034A0170B5DD68D0F822 -:1031500090306C692668E66056BB1A444FF4002034 -:10316000C2F810092A6802F00302012A0AB20ED13D -:10317000D3F8080803EB421410F4807FD4F8000958 -:1031800014BF40F0805040F00050C4F8000903EB39 -:103190004212D2F8000940F00440C2F800090122AE -:1031A000D3F8340802FA01F10143C3F8341870BDB2 -:1031B00019B9402E84BF4020206020681A442E8A0E -:1031C000841940F00050013CB4FBF6F440EAC440DE -:1031D000C6E700002DE9F041D0F8906004460D46A6 -:1031E00006EB4113D3F80879C3F80879FB071CD51F -:1031F000D6F81038DA0718D500EB8103D3F80CE0C5 -:10320000DEF81430D3F800C0DA6894451BD2A2EB84 -:103210000C024FF000081A60C3F80480202383F3E7 -:103220001188FFF78FFF88F311883B0618D501231B -:10323000D6F83428AB40134212D029462046BDE8C8 -:10324000F041FFF7ADBC012303FA01F2038923EA41 -:1032500002030381DEF80830002BE6D09847E4E74C -:10326000BDE8F0812DE9F047D0F8905004466E6932 -:10327000AB691E40F1046E6103D5BDE8F047FEF76F -:1032800079BC002E12DAD5F8003E9A0705D0D5F8A1 -:10329000003E23F00303C5F8003ED5F8043820466D -:1032A00023F00103C5F80438FEF794FC330502D57A -:1032B0002046FEF783FCB7040CD5D5F8083813F088 -:1032C000060FEB6823F470530CBF43F4105343F420 -:1032D000A053EB60300704D56368DB680BB1204670 -:1032E0009847F10200F1A180B2020BD5D4F890808A -:1032F00000274FF00109D4F89430F9B29B688B4253 -:1033000080F0D280F3061AD5D4F890100A6AC2F37E -:103310000A1702F00F0302F4F012B2F5802F00F04A -:10332000EB80B2F5402F0AD104EB830301F5805105 -:10333000DB68186A00231A469F4240F0D1803003B0 -:10334000D5F8185835D5E90303D500212046FFF7F5 -:10335000ADFEAA0303D501212046FFF7A7FE6B03AC -:1033600003D502212046FFF7A1FE2F0303D5032139 -:103370002046FFF79BFEE80203D504212046FFF715 -:1033800095FEA90203D505212046FFF78FFE6A02AC -:1033900003D506212046FFF789FE2B0203D507211E -:1033A0002046FFF783FEEF0103D508212046FFF7F3 -:1033B0007DFE700340F1C780E90703D50021204658 -:1033C000FFF708FFAA0703D501212046FFF702FFF8 -:1033D0006B0703D502212046FFF7FCFE2F0703D51C -:1033E00003212046FFF7F6FEEE0603D50421204612 -:1033F000FFF7F0FEA80603D505212046FFF7EAFEF9 -:10340000690603D506212046FFF7E4FE2A0603D508 -:1034100007212046FFF7DEFEEB0540F194802046B1 -:103420000821BDE8F047FFF7D5BED4F890904FF0E3 -:1034300000084FF0010AD4F894305FFA88F79B68CF -:10344000BB42FFF451AF09EB4713D3F8002902F454 -:103450004022B2F5802F24D1D3F80029002A20DAA7 -:10346000D3F8002942F09042C3F80029D3F800298C -:10347000002AFBDB3946D4F89000FFF7D5FB228900 -:103480000AFA07F322EA0303238104EB8703DB68CC -:103490009B6813B139462046984739462046FFF7C6 -:1034A0007FFB08F10108C6E708EB4112D2F8003BA8 -:1034B00003F44023B3F5802F10D1D2F8003B002B4A -:1034C0000CDA628909FA01F322EA0303638104EB4F -:1034D0008103DB68DB680BB12046984701370AE7B8 -:1034E00013F0030F00D10A68072B03F101039EBFFD -:1034F0000270120A01301FE704EB830301F58051CB -:10350000DA6890690268D0F808C04068A2EB000E43 -:1035100000221046974208D1DB689B699A683A44BA -:103520009A605A6817445F6009E712F0030F00D1F0 -:103530000868964502F1010282BF8CF80000000A7B -:103540000CF1010CE6E7BDE8F087000008B5034880 -:10355000FFF788FEBDE80840FFF776BA103200207A -:1035600008B50348FFF77EFEBDE80840FFF76CBAD8 -:10357000AC320020D0F8903003EB4111D1F8003B81 -:1035800043F40013C1F8003B70470000D0F89030BE -:1035900003EB4111D1F8003943F40013C1F80039AD -:1035A00070470000D0F8903003EB4111D1F8003B98 -:1035B00023F40013C1F8003B70470000D0F89030AE -:1035C00003EB4111D1F8003923F40013C1F800399D -:1035D0007047000030B50433039C0172002104FBE6 -:1035E0000325C361049B00600363059B4060C160C9 -:1035F000426102618561046242628162C162436329 -:1036000030BD00000022416AC260416101616FF07B -:1036100001018262C262FEF791BE00000369426945 -:10362000934203D1C2680AB100207047181D704749 -:10363000036919600021C2680132C260C269134483 -:1036400082699342036124BF436A0361FEF76ABE45 -:1036500038B504460D46E3683BB162690020131D8E -:103660001268A3621344E36238BD237A33B9294652 -:103670002046FEF747FE0028EDDA38BD6FF0010066 -:10368000FBE70000C368C269013BC36043691344A0 -:1036900082699342436124BF436A4361002383628A -:1036A000036B03B11847704770B52023044683F3BA -:1036B0001188866A3EB9FFF7CBFF054618B186F33D -:1036C0001188284670BDA36AE26A13F8015B934231 -:1036D000A36202D32046FFF7D5FF002383F31188AE -:1036E000EFE700002DE9F84F04460E469046994654 -:1036F000202787F311880025AA46D4F828B0BBF10B -:10370000000F09D149462046FFF7A2FF20B18BF3F5 -:1037100011882846BDE8F88FA16AA8EB050BE36A7B -:103720005B1A9B4528BF9B46BBF1400F1BD9334614 -:1037300001F1400251F8040B914243F8040BF9D116 -:10374000A36A403640354033A362A26AE36A9A42D4 -:1037500002D32046FFF796FF8AF311884545D8D259 -:1037600087F31188C9E730465A46FDF7A5FBA36ADF -:103770005E445D445B44A362E7E7000010B5029C31 -:1037800004330172C36103FB0421002300608362E0 -:10379000C362039B40600363049BC4604261026197 -:1037A000816104624262436310BD0000026A6FF0EF -:1037B0000101C260426A4261026100228262C26209 -:1037C000FEF7BCBD436902699A4203D1C2680AB1DF -:1037D00000207047184650F8043B0B60704700000B -:1037E000C3680021C2690133C3604369134482691D -:1037F0009342436124BF436A4361FEF793BD0000D7 -:1038000038B504460D46E3683BB1236900201A1D14 -:10381000A262E2691344E36238BD237A33B92946D0 -:103820002046FEF76FFD0028EDDA38BD6FF001008D -:10383000FBE7000003691960C268013AC260C2690F -:10384000134482699342036124BF436A03610023E6 -:103850008362036B03B118477047000070B52023E3 -:1038600004460E4683F31188856A35B91146FFF781 -:10387000C7FF10B185F3118870BDA36A1E70A36ADB -:10388000E26A01339342A36204D3E169204604391A -:10389000FFF7D0FF002080F3118870BD2DE9F84FAD -:1038A00004460D4691469A464FF0200888F3118849 -:1038B0000026B346A76A4FB951462046FFF7A0FF3E -:1038C00020B187F311883046BDE8F88FA06AA9EBD4 -:1038D0000603E76A3F1A9F4228BF1F46402F1BD9A5 -:1038E00005F1400355F8042B9D4240F8042BF9D113 -:1038F000A36A40364033A362A26AE36A9A4204D3C1 -:10390000E16920460439FFF795FF8BF311884E4596 -:10391000D9D288F31188CDE729463A46FDF7CCFA8B -:10392000A36A3D443E443B44A362E5E70269436920 -:103930009A4203D1C3681BB9184670470023FBE7BE -:10394000836A002BF8D0043B9B1AF5D01360C36840 -:10395000013BC360C3691A4483699A42026124BF70 -:10396000436A0361002383620123E5E700F0BCB8EA -:10397000034B002258631A610222DA60704700BFCD -:10398000000C00400022014BDA607047000C004040 -:10399000014B5863704700BF000C00404B68436008 -:1039A0008B688360CB68C3600B6943614B690362BA -:1039B0008B6943620B6803607047000008B52C4BAD -:1039C00040F2FF712B48D3F888200A43C3F88820BF -:1039D000D3F8882022F4FF6222F00702C3F888207F -:1039E000D3F88820D3F8E0200A43C3F8E020D3F8C6 -:1039F00008210A43C3F808211F4AD3F808311146A9 -:103A0000FFF7CCFF1D4802F11C01FFF7C7FF1C4860 -:103A100002F13801FFF7C2FF1A4802F15401FFF723 -:103A2000BDFF194802F17001FFF7B8FF174802F116 -:103A30008C01FFF7B3FF164802F1A801FFF7AEFFB4 -:103A4000144802F1C401FFF7A9FF134802F1E00195 -:103A5000FFF7A4FF114802F1FC01FFF79FFF104898 -:103A600002F58C71FFF79AFFBDE8084000F016B927 -:103A70000044025800000258A44200080004025802 -:103A800000080258000C0258001002580014025896 -:103A900000180258001C0258002002580024025846 -:103AA0000028025808B500F0C1FAFEF74DFBFEF7FA -:103AB000A9FFBDE80840FEF759BD000070470000AF -:103AC000084B1A69920710B508D500241C61202301 -:103AD00083F31188FEF77CFB84F31188BDE8104066 -:103AE000FEF7B2BF000C0040124B08213220D3F881 -:103AF000E82042F00802C3F8E820D3F8102142F091 -:103B00000802C3F810210C4AD3F81031D36B43F0EC -:103B10000803D363C722094B9A624FF0FF32DA627F -:103B200000229A615A63DA605A6001225A611A606F -:103B3000FDF720BC004402580010005C000C00405F -:103B4000F8B5514B0024D3F880204FF0FF32C3F872 -:103B50008020D3F88010C3F88040D3F88010D3F8C9 -:103B60008410C3F88420D3F88410C3F88440D3F8B9 -:103B70008410D96F41F0FF4141F4FF0141F4DF416E -:103B800041F07F01D967D96F21F0FF4121F4FF0196 -:103B900021F4DF4121F07F01D967D96FD3F8881074 -:103BA0006FEA41516FEA5151C3F88810D3F8881079 -:103BB000C1F30A01C3F88810D3F88810D3F8901025 -:103BC000C3F89020D3F89010C3F89040D3F8901029 -:103BD000D3F89410C3F89420D3F89410C3F8944009 -:103BE000D3F89410D3F89810C3F89820D3F898100D -:103BF000C3F89840D3F89810D3F88C10C3F88C20F1 -:103C0000D3F88C10C3F88C40D3F88C10D3F89C10E8 -:103C1000C3F89C20D3F89C20C3F89C40D3F89C3078 -:103C200000F0E4F9194B07229A60194ADA60194A40 -:103C30001A6105225A60184A536A43F4803353626A -:103C4000C2F88440BFF34F8FD2F8803043F6E0765D -:103C5000C3F3C904C3F34E33A5075B0103EA060EA1 -:103C6000284621464EEA0007013900F14040C2F8DB -:103C700074724F1CF6D1203B13F1200FEED1BFF32D -:103C80004F8FBFF36F8FF8BD0044025890ED00E0F6 -:103C9000000004301B00080300ED00E00122574B38 -:103CA00057491A60574B19609A60574ADA600022E8 -:103CB0001A614FF440429A619A699004FCD51A68DF -:103CC00042F480721A60514B1A6F12F4407F04D094 -:103CD0004FF480321A6700221A671A6842F0010214 -:103CE0001A604A4A134611684907FCD50021116140 -:103CF0001A6912F03802FBD1012119604FF080419E -:103D000059605A67424ADA62424A1A611A6842F4B2 -:103D100080321A603D4B1A689203FCD53E4A3F49F7 -:103D20009A6200225A631963A1F58021DA634B3944 -:103D300099635A643A4A1A643A4ADA621A6842F053 -:103D4000A8521A60314B1A6802F02852B2F1285F6B -:103D5000F9D1482222219A614FF48862DA61402227 -:103D60001A624FF00052DA641A652F4A5A652F4AD8 -:103D70009A652F4A11601A6942F003021A61234BB7 -:103D80001A6902F03802182AFAD1D3F8DC2042F07E -:103D90000052C3F8DC20D3F8042142F00052C3F8EB -:103DA0000421D3F80421D3F8DC2042F08042C3F888 -:103DB000DC20D3F8042142F08042C3F80421D3F878 -:103DC0000421D3F8DC2042F00042C3F8DC20D3F811 -:103DD000042142F00042C3F80421D3F80421D3F8AF -:103DE000F42042F00202C3F8F420D3F81C2142F080 -:103DF0000202C3F81C21D3F81C317047088100511E -:103E000000C000F0004802580200000100440258BF -:103E10000000FF01008890081210200063020701D3 -:103E200047040508FD0BFF010010E0000001010040 -:103E300000200052084A08B5936811680B4003F04F -:103E40000103936023B1054A13680BB1506898478A -:103E5000BDE80840FEF7F8BD80000058C0230020F0 -:103E6000084A08B5936811680B4003F00203936099 -:103E700023B1054A93680BB1D0689847BDE8084064 -:103E8000FEF7E2BD80000058C0230020084A08B5B4 -:103E9000936811680B4003F00403936023B1054A53 -:103EA00013690BB150699847BDE80840FEF7CCBDD7 -:103EB00080000058C0230020084A08B593681168A4 -:103EC0000B4003F00803936023B1054A93690BB1DB -:103ED000D0699847BDE80840FEF7B6BD800000589D -:103EE000C0230020084A08B5936811680B4003F00E -:103EF0001003936023B1054A136A0BB1506A9847C7 -:103F0000BDE80840FEF7A0BD80000058C023002097 -:103F1000174B10B59C681A68144004F478729A60C4 -:103F2000A30604D5134A936A0BB1D06A984760067A -:103F300004D5104A136B0BB1506B9847210604D57A -:103F40000C4A936B0BB1D06B9847E20504D5094A34 -:103F5000136C0BB1506C9847A30504D5054A936CBC -:103F60000BB1D06C9847BDE81040FEF76DBD00BFA7 -:103F700080000058C02300201A4B10B59C681A68B6 -:103F8000144004F47C429A60620504D5164A136D0D -:103F90000BB1506D9847230504D5134A936D0BB1AF -:103FA000D06D9847E00404D50F4A136E0BB1506EE4 -:103FB0009847A10404D50C4A936E0BB1D06E984774 -:103FC000620404D5084A136F0BB1506F984723045D -:103FD00004D5054A936F0BB1D06F9847BDE81040E8 -:103FE000FEF732BD80000058C0230020062108B52E -:103FF0000846FDF7BFF906210720FDF7BBF90621AA -:104000000820FDF7B7F906210920FDF7B3F90621CD -:104010000A20FDF7AFF906211720FDF7ABF90621BD -:104020002820BDE80840FDF7A5B9000008B5FFF756 -:1040300087FDFDF775F8FDF747FBFDF71FFDFDF761 -:10404000F1FBFFF73BFDBDE80840FFF78FBC000028 -:1040500010B501390244904201D1002010BD10F882 -:10406000013B11F8014FA342F5D0181B10BD000011 -:10407000034611F8012B03F8012B002AF9D17047F0 -:10408000121012131211000001105A0003105900EF -:104090000120580003205600E82A00204024002078 -:1040A00053544D333248373F3F3F0053544D333222 -:1040B000483734332F3735330000000000960000B6 -:1040C00000000000000000000000000000000000F0 -:1040D0000000000000000000911600087D16000896 -:1040E000B9160008A5160008B11600089D160008AC -:1040F0008916000875160008C516000800000000A3 -:104100009D17000889170008C5170008B117000897 -:10411000BD170008A91700089517000881170008A7 -:10412000211800080000000001000000000000004D -:104130006D61696E0000000050410008F028002009 -:10414000E82A0020010000004521000800000000CE -:1041500069646C65000000000200000000000000BF -:10416000C9190008351A000840004000802F0020BF -:10417000902F00200200000000000000030000005B -:1041800000000000791A0008000000001000000084 -:10419000A02F00200000000001000000000000002F -:1041A00010320020010102004172647550696C6F89 -:1041B000740025424F415244252D424C0025534561 -:1041C0005249414C250000000D25000875240008C7 -:1041D00035190008F124000843000000E041000800 -:1041E00009024300020100C032090400000102027A -:1041F000010005240010010524010001042402022D -:104200000524060001070582030800FF09040100D8 -:10421000020A0000000705010240000007058102B4 -:1042200040000000120000002C42000812011001A2 -:104230000200004009124157000201020301000080 -:104240000403090425424F4152442500426561732D -:1042500074483700303132333435363738394142DB -:10426000434445460000000000000000E91B000830 -:10427000C91E0008751F0008400040004833002098 -:104280004833002001000000583300208000000067 -:1042900040010000080000000001000000040000D0 -:1042A000080000000001A86A00000000AAAAAAAA4B -:1042B00000011440FFFF00000000000070A70A008A -:1042C0000000000000000000AAAAAAAA0000000046 -:1042D000FFFF0000000000000000000000000004DC -:1042E00000000000AAAAAAAA00000000FFDF000048 -:1042F00000000000000000000000000000000000BE -:10430000AAAAAAAA00000000FFFF00000000000007 -:10431000000000000001000000000000AAAAAAAAF4 -:1043200000010000FFFF000000000000000000008E -:104330000000000000000000AAAAAAAA00000000D5 -:10434000FFFF00000000000000000000000000006F -:1043500000000000AAAAAAAA00000000FFFF0000B7 -:10436000000000000000000000000000000000004D -:10437000AAAAAAAA00000000FFFF00000000000097 -:10438000000000000000000000000000AAAAAAAA85 -:1043900000000000FFFF000000000000000000001F -:1043A0000000000000000000AAAAAAAA0000000065 -:1043B000FFFF0000000000000000000000000000FF -:1043C00000000000AAAAAAAA00000000FFFF000047 -:1043D0000000000000000000FF00000000000000DE -:1043E000A04000083F00000050040000AB4000085F -:1043F0003F000000009600000000080004000000DC -:104400004042000800000000000000000000000022 -:0C441000000000000000000000000000A0 +:100310006F8F02F0CDFB02F06FFB03F009FB4FF093 +:1003200055301F491B4A91423CBF41F8040BFAE784 +:100330001C49194A91423CBF41F8040BFAE71A499B +:100340001A4A1B4B9A423EBF51F8040B42F8040B69 +:10035000F8E700201749184A91423CBF41F8040BC6 +:10036000FAE702F087FB03F067FB144C144DAC4234 +:1003700003DA54F8041B8847F9E700F041F8114C00 +:10038000114DAC4203DA54F8041B8847F9E702F038 +:100390006FBB0000000600200022002000000008C3 +:1003A0000000002000060020A043000800220020DA +:1003B0005C22002060220020FC460020A0020008F1 +:1003C000A0020008A0020008A00200082DE9F04FDA +:1003D0002DED108AC1F80CD0D0F80CD0BDEC108AED +:1003E000BDE8F08F002383F311882846A047002042 +:1003F00001F086FEFEE701F001FE00DFFEE70000EF +:1004000038B500F0E9FC30B1164B00220E211A720B +:100410005A729972DA7202F04DFA054602F080FAC9 +:100420000446D0B9104B9D4219D001339D4241F290 +:10043000883512BF044600250124002002F044FA4A +:100440000CB100F059F800F063FD00F0FFFB284606 +:1004500000F004F900F050F8F9E70025EDE7054653 +:10046000EBE700BF00220020010007B008B500F054 +:10047000B9FBA0F120035842584108BD07B541F22D +:100480001203022101A8ADF8043000F0C9FB03B04B +:100490005DF804FB202310B583F311881248C3686C +:1004A0000BB101F0B3FE0023104A4FF47A710E48ED +:1004B00001F070FE002383F311880D4C236813B103 +:1004C0002368013B2360636813B16368013B636089 +:1004D000084B1B7833B9636823B9022000F092FC03 +:1004E0003223636010BD00BF602200209504000825 +:1004F0007C23002074220020F8B5514B514A1C4641 +:100500001968013100F09B8004339342F8D162688E +:100510004D4B9A4240F293804C4B9B6803F1006331 +:1005200003F500339A4280F08A80002000F0B4FB8B +:100530000220474B187000F05BFC464B0021D3F8BB +:10054000E820C3F8E810D3F81021C3F81011D3F84D +:100550001021D3F8EC20C3F8EC10D3F81421C3F821 +:100560001411D3F81421D3F8F020C3F8F010D3F805 +:100570001821C3F81811D3F81821D3F8802042F0BD +:100580000062C3F88020D3F8802022F00062C3F814 +:100590008020D3F88020D3F8802042F00072C3F886 +:1005A0008020D3F8802022F00072C3F88020D3F896 +:1005B000803072B64FF0E023C3F8084DD4E9000450 +:1005C000BFF34F8FBFF36F8F234AC2F88410BFF37E +:1005D0004F8F536923F480335361BFF34F8FD2F8A9 +:1005E000803043F6E076C3F3C905C3F34E335B01B5 +:1005F00003EA060C29464CEA81770139C2F8747285 +:10060000F9D2203B13F1200FF2D1BFF34F8FBFF38C +:100610006F8FBFF34F8FBFF36F8F536923F4003396 +:1006200053610023C2F85032BFF34F8FBFF36F8F77 +:10063000202383F31188854680F308882047F8BD7E +:100640000000020820000208FFFF0108002200202D +:10065000742200200044025800ED00E02DE9F04F24 +:1006600093B0A94B2022FF2100900AA89D6800F0BA +:10067000F9FBA64A1378A3B90121A5481170C360FC +:10068000202383F31188C3680BB101F0BFFD002361 +:10069000A04A4FF47A719E4801F07CFD002383F359 +:1006A0001188009B9C4A03B1136000239B49009C66 +:1006B00098469B461E469A460B705360012000F0F8 +:1006C00097FB24B1944B1B68002B00F0168200208E +:1006D00000F088FA0390039B002BF2DB012000F06E +:1006E0007DFB039B213B162BE8D801A252F823F097 +:1006F0004D0700087507000809080008BD06000836 +:10070000BD060008BD0600089D0800086F0A000825 +:1007100089090008EB090008130A0008390A0008D3 +:10072000BD0600084B0A0008BD060008BD0A000807 +:10073000ED070008BD060008010B00085907000876 +:10074000ED070008BD060008EB0900080220FFF7CE +:100750008DFE002840F0FB81009B022105A8B8F126 +:10076000000F08BF1C4641F21233ADF8143000F000 +:1007700057FAA3E74FF47A7000F034FA071EEBDB68 +:100780000220FFF773FE0028E6D0013F052F00F29C +:10079000E081DFE807F0030A0D101336052304217A +:1007A00005A8059300F03CFA17E004215648F9E744 +:1007B00004215B48F6E704215A48F3E74FF01C098F +:1007C000484609F1040900F069FA0421059005A8DA +:1007D00000F026FAB9F12C0FF2D101204FF0000AF7 +:1007E00000FA07F747EA0B0B5FFA8BFB00F086FB7A +:1007F00026B10BF00B030B2B08BF0024FFF73EFEC6 +:100800005CE704214848CDE7002EA5D00BF00B0390 +:100810000B2BA1D10220FFF729FE074600289BD011 +:1008200001203E4E00F038FA4FF0000802203070F0 +:1008300000F0DEFA5FFA88F9484600F03DFA044617 +:1008400090B1484608F1010800F046FA0028F1D1BD +:10085000B846044641F21213022105A83E46ADF8FF +:10086000143000F0DDF929E701232546022033701A +:1008700000F0B4FA244B9B68AB4207D9284600F03D +:100880000DFA013040F068810435F3E70025234B71 +:10089000B8463E461D70204B5D60A7E7002E3FF432 +:1008A0005BAF0BF00B030B2B7FF456AF02201B4BFF +:1008B000187000F09DFA322000F094F9B0F10009B0 +:1008C000FFF64AAF19F003077FF446AF0E4A09EB73 +:1008D0000503926893423FF63FAFB9F5807F3FF73B +:1008E0003BAF124BB945019322DD4FF47A7000F013 +:1008F00079F90390039A002AFFF62EAF039A013785 +:10090000019B03F8012BEDE7002200207823002053 +:1009100060220020950400087C230020742200201F +:1009200004220020082200200C220020782200202F +:10093000C820FFF79BFD074600283FF40DAF1F2D91 +:1009400011D8C5F120020AAB25F0030084494A45BD +:10095000184428BF4A46019200F05EFA019AFF212E +:100960007F4800F07FFA4FEAA903C9F387027C4968 +:100970002846019300F07EFA064600283FF46AAF4D +:10098000019B05EB830531E70220FFF76FFD00288F +:100990003FF4E2AE00F0BCF900283FF4DDAE0027E2 +:1009A000B946704B9B68BB4218D91F2F11D80A9BC0 +:1009B00001330ED027F0030312AA134453F8203C4E +:1009C00005934846042205A9043700F03DFB814603 +:1009D000E7E7384600F062F90590F2E7CDF81490A9 +:1009E000042105A800F01CF900E70023642104A8F5 +:1009F000049300F00BF900287FF4AEAE0220FFF75D +:100A000035FD00283FF4A8AE049800F077F9059072 +:100A1000E6E70023642104A8049300F0F7F8002817 +:100A20007FF49AAE0220FFF721FD00283FF494AE38 +:100A3000049800F065F9EAE70220FFF717FD0028A7 +:100A40003FF48AAE00F074F9E1E70220FFF70EFDF3 +:100A500000283FF481AE05A9142000F06FF9074685 +:100A60000421049004A800F0DBF83946B9E73220ED +:100A700000F0B8F8071EFFF66FAEBB077FF46CAE50 +:100A8000384A07EB0A03926893423FF665AE0220AC +:100A9000FFF7ECFC00283FF45FAE27F00307574454 +:100AA000BA453FF4A3AE50460AF1040A00F0F6F846 +:100AB0000421059005A800F0B3F8F1E74FF47A702F +:100AC000FFF7D4FC00283FF447AE00F021F90028DE +:100AD00044D00A9B01330BD008220AA9002000F061 +:100AE000C9F900283AD02022FF210AA800F0BAF95B +:100AF000FFF7C4FC1C4801F009FB13B0BDE8F08F00 +:100B0000002E3FF429AE0BF00B030B2B7FF424AE29 +:100B10000023642105A8059300F078F80746002813 +:100B20007FF41AAE0220FFF7A1FC814600283FF4B3 +:100B300013AEFFF7A3FC41F2883001F0E7FA059805 +:100B400000F020FA4E463C4600F0D8F9B6E50646DD +:100B50004CE64FF0000AFFE5B8467BE6374679E6FB +:100B60007822002000220020A0860100F7B50C4664 +:100B7000184E4FF47A71054602FB01F396F90020F6 +:100B8000501C0BD11448294601930268176A22466B +:100B9000B8478442019B03D1002310E0002AF1D022 +:100BA00096F90020511C01D0012A0DD10B4829468D +:100BB0000268166A2246B047844205D10123084ADA +:100BC0000120137003B0F0BD4FF4FA7001F09EFAEB +:100BD0000020F7E710220020F0290020CC2300207D +:100BE000C8230020002307B5024601210DF10700AC +:100BF0008DF80730FFF7BAFF20B19DF8070003B06A +:100C00005DF804FB4FF0FF30F9E700000A460421CD +:100C100008B5FFF7ABFF80F00100C0B2404208BD4D +:100C2000074B0A4630B41978064B53F82140014669 +:100C300023682046DD69044BAC4630BC604700BFEA +:100C4000C823002078400008A086010070B5104C31 +:100C50000025104E01F006FD208030682388834275 +:100C60000CD800252088013801F0F8FC23880544C1 +:100C7000013BB5F5802F2380F4D370BD01F0EEFC6D +:100C8000336805440133B5F5003F3360E5D3E8E749 +:100C9000CA2300208423002001F0C2BD00F10060BF +:100CA00000F500300068704700F10060920000F528 +:100CB000003001F039BD0000054B1A68054B1B8858 +:100CC0009B1A834202D9104401F0C8BC002070472F +:100CD00084230020CA23002038B5074D0446286825 +:100CE000204401F0C1FC28B928682044BDE8384000 +:100CF00001F0CCBC38BD00BF842300200020704729 +:100D000000F1FF5000F58F10D0F800087047000088 +:100D1000064991F8243033B100230822086A81F88B +:100D20002430FFF7C1BF0120704700BF8823002097 +:100D3000014B1868704700BF0010005C244BF0B5F1 +:100D40001A680446234BC2F30B06120C1F8858681E +:100D5000BE4293F9085028D09F89BE4206D1012097 +:100D60000C2505FB0033586893F9085041F2010344 +:100D70009A421CD041F203039A421AD042F2010374 +:100D80009A4218D042F203039A4208BF5625621EC7 +:100D90000B46441E0A4493420FD214F9016F581CAB +:100DA0006EB1034600F8016CF5E70020D8E75A253C +:100DB000EDE75925EBE75825E9E7184605E02C242F +:100DC00082421C7001D9981C5D70401AF0BD00BFB2 +:100DD0000010005C1422002000207047022803D17C +:100DE000024B4FF000529A61704700BF0008025852 +:100DF000022803D1024B4FF400529A61704700BFA2 +:100E000000080258022804D1024A536983F40053AF +:100E10005361704700080258002310B5934203D075 +:100E2000CC5CC4540133F9E710BD0000013810B5A3 +:100E300010F9013F3BB191F900409C4203D11AB136 +:100E40000131013AF4E71AB191F90020981A10BD66 +:100E50001046FCE703460246D01A12F9011B00298E +:100E6000FAD1704702440346934202D003F8011BB3 +:100E7000FAE770472DE9F8431F4D144607468846A8 +:100E800095F8242052BBDFF870909CB395F824307D +:100E90002BB92022FF2148462F62FFF7E3FF95F888 +:100EA00024004146C0F1080205EB8000A24228BFA1 +:100EB0002246D6B29200FFF7AFFF95F82430A41B6C +:100EC00017441E449044E4B2F6B2082E85F824601C +:100ED000DBD1FFF71DFF0028D7D108E02B6A03EB19 +:100EE00082038342CFD0FFF713FF0028CBD100202D +:100EF000BDE8F8830120FBE788230020024B1A7825 +:100F0000024B1A70704700BFC82300201022002037 +:100F100038B5164C164D204600F0FAFB29462046FF +:100F200000F022FC2D681348D5F89020D2F8043840 +:100F300043F00203C2F8043801F0E8F80E492846ED +:100F400000F020FDD5F890200C48D2F804380C4968 +:100F5000A04223F00203C2F804384FF4E1330B60DF +:100F600003D0BDE8384000F031BB38BDF029002087 +:100F70008441000840420F008C410008CC2300202F +:100F8000B023002038B50B4B04461A780A4B53F8AF +:100F900022500A4B9D420CD0094B002118221846C2 +:100FA000FFF760FF046001462846BDE8384000F0C6 +:100FB0000DBB38BDC823002078400008F029002070 +:100FC000B023002000B59BB0EFF30981682268468A +:100FD000FFF722FFEFF30583044B9A6BDA6A9A6AF4 +:100FE0009A6A9A6A9A6A9A6A9B6AFEE700ED00E03A +:100FF00000B59BB0EFF3098168226846FFF70CFF4C +:10100000EFF30583044B9A6B9A6A9A6A9A6A9A6A12 +:101010009A6A9B6AFEE700BF00ED00E000B59BB056 +:10102000EFF3098168226846FFF7F6FEEFF30583C8 +:10103000034B5A6B9A6A9A6A9A6A9A6A9B6AFEE7A3 +:1010400000ED00E0FEE7000030B50A44084D914293 +:101050000DD011F8013B5840082340F30004013B38 +:101060002C4013F0FF0384EA5000F6D1EFE730BDC7 +:101070002083B8ED026843681143016003B118474B +:1010800070470000024A136843F0C00313607047C2 +:101090000010014013B50E4C204600F08BFA04F10D +:1010A000140000234FF400720A49009400F04CF938 +:1010B000094B4FF40072094904F13800009400F024 +:1010C000C5F9074A074BC4E9172302B010BD00BF9A +:1010D000CC2300203824002085100008382600206A +:1010E0000010014000E1F505037C30B5244C0029D7 +:1010F00018BF0C46012B11D1224B98420ED1224B26 +:10110000D3F8F02042F01002C3F8F020D3F81821F1 +:1011100042F01002C3F81821D3F818312268036E88 +:10112000C16D03EB52038466B3FBF2F362681504EE +:1011300042BF23F0070503F0070343EA4503CB60F2 +:10114000A36843F040034B60E36843F001038B6006 +:1011500042F4967343F001030B604FF0FF330B62D0 +:10116000510505D512F0102205D0B2F1805F04D0F0 +:1011700080F8643030BD7F23FAE73F23F8E700BFF3 +:1011800080400008CC230020004402582DE9F0479D +:10119000C66D05463768F4692107346219D014F02A +:1011A000080118BF8021E20748BF41F02001A307D2 +:1011B0004FF0200348BF41F04001600748BF41F4B1 +:1011C000807183F31188281DFFF754FF002383F3F8 +:1011D0001188E2050AD5202383F311884FF40071AA +:1011E000281DFFF747FF002383F311884FF02009E4 +:1011F0004FF0000A14F0200838D13B0616D54FF006 +:10120000200905F1380A200610D589F311885046C7 +:1012100000F050F9002836DA0821281DFFF72AFFD0 +:1012200027F080033360002383F31188790614D5F7 +:10123000620612D5202383F31188D5E913239A423D +:1012400008D12B6C33B127F040071021281DFFF780 +:1012500011FF3760002383F31188E30618D5AA6EC7 +:101260001369ABB15069BDE8F047184789F311889D +:10127000736A284695F86410194000F0B5F98AF3AE +:101280001188F469B6E7B06288F31188F469BAE7A7 +:10129000BDE8F087F8B51546826804460B46AA42B9 +:1012A00000D28568A1692669761AB5420BD2184624 +:1012B0002A46FFF7B1FDA3692B44A3612846A36822 +:1012C0005B1BA360F8BD0CD9AF1B18463246FFF775 +:1012D000A3FD3A46E1683044FFF79EFDE3683B44D6 +:1012E000EBE718462A46FFF797FDE368E5E70000BD +:1012F00083689342F7B50446154600D28568D4E961 +:101300000460361AB5420BD22A46FFF785FD6369A1 +:101310002B4463612846A3685B1BA36003B0F0BD48 +:101320000DD93246AF1B0191FFF776FD01993A4680 +:10133000E0683144FFF770FDE3683B44E9E72A4683 +:10134000FFF76AFDE368E4E710B50A440024C361CF +:10135000029B8460C16002610362C0E90000C0E9D1 +:10136000051110BD08B5D0E90532934201D182685C +:1013700082B98268013282605A1C42611970002170 +:10138000D0E904329A4224BFC368436100F0DAFE18 +:10139000002008BD4FF0FF30FBE7000070B52023B0 +:1013A00004460E4683F31188A568A5B1A368A26917 +:1013B000013BA360531CA36115782269934224BFAB +:1013C000E368A361E3690BB120469847002383F3E8 +:1013D0001188284607E03146204600F0A3FE002889 +:1013E000E2DA85F3118870BD2DE9F74F04460E4609 +:1013F00017469846D0F81C904FF0200A8AF31188BF +:101400004FF0000B154665B12A4631462046FFF7DE +:1014100041FF034660B94146204600F083FE0028A4 +:10142000F1D0002383F31188781B03B0BDE8F08F5F +:10143000B9F1000F03D001902046C847019B8BF300 +:101440001188ED1A1E448AF31188DCE7C160C3617C +:10145000009B82600362C0E905111144C0E90000ED +:1014600001617047F8B504460D461646202383F304 +:101470001188A768A7B1A368013BA36063695A1CE0 +:1014800062611D70D4E904329A4224BFE36863614B +:10149000E3690BB120469847002080F3118807E0EC +:1014A0003146204600F03EFE0028E2DA87F311883C +:1014B000F8BD0000D0E9052310B59A4201D1826839 +:1014C0007AB982680021013282605A1C82611C78DC +:1014D00003699A4224BFC368836100F033FE20464B +:1014E00010BD4FF0FF30FBE72DE9F74F04460E46E5 +:1014F00017469846D0F81C904FF0200A8AF31188BE +:101500004FF0000B154665B12A4631462046FFF7DD +:10151000EFFE034660B94146204600F003FE002876 +:10152000F1D0002383F31188781B03B0BDE8F08F5E +:10153000B9F1000F03D001902046C847019B8BF3FF +:101540001188ED1A1E448AF31188DCE702684368AB +:101550001143016003B11847704700001430FFF7D2 +:1015600043BF00004FF0FF331430FFF73DBF0000D2 +:101570003830FFF7B9BF00004FF0FF333830FFF7C6 +:10158000B3BF00001430FFF709BF00004FF0FF3178 +:101590001430FFF703BF00003830FFF763BF0000CF +:1015A0004FF0FF323830FFF75DBF0000002070477A +:1015B000FFF770BD044B036000234360C0E90233B2 +:1015C00001230374704700BF9840000810B5202322 +:1015D000044683F31188FFF787FD02232374002359 +:1015E00083F3118810BD000038B5C36904460D4669 +:1015F0001BB904210844FFF7A9FF294604F1140090 +:10160000FFF7B0FE002806DA201D4FF48061BDE828 +:101610003840FFF79BBF38BD026843681143016043 +:1016200003B118477047000013B5406B00F58054B4 +:10163000D4F8A4381A681178042914D1017C02293D +:1016400011D11979012312898B4013420BD101A9C1 +:101650004C3002F06DF8D4F8A4480246019B217981 +:10166000206800F0DFF902B010BD0000143001F076 +:10167000EFBF00004FF0FF33143001F0E9BF00006E +:101680004C3002F0C1B800004FF0FF334C3002F094 +:10169000BBB80000143001F0BDBF00004FF0FF31B7 +:1016A000143001F0B7BF00004C3002F08DB80000DC +:1016B0004FF0FF324C3002F087B800000020704736 +:1016C00010B500F58054D4F8A4381A6811780429AC +:1016D00017D1017C022914D15979012352898B40F9 +:1016E00013420ED1143001F04FFF024648B1D4F836 +:1016F000A4484FF4407361792068BDE8104000F0C1 +:101700007FB910BD406BFFF7DBBF000070470000E2 +:101710007FB5124B0125042604460360002305749F +:1017200000F1840243602946C0E902330C4B029069 +:10173000143001934FF44073009601F001FF094B00 +:1017400004F69442294604F14C000294CDE900636A +:101750004FF4407301F0C8FF04B070BDC0400008F2 +:1017600005170008291600080A68202383F311884A +:101770000B790B3342F823004B79133342F82300E3 +:101780008B7913B10B3342F8230000F58053C3F873 +:10179000A41802230374002383F311887047000008 +:1017A00038B5037F044613B190F85430ABB9012526 +:1017B000201D0221FFF730FF04F114006FF001013A +:1017C000257700F0CBFC04F14C0084F854506FF006 +:1017D0000101BDE8384000F0C1BC38BD10B50121A1 +:1017E00004460430FFF718FF0023237784F85430B1 +:1017F00010BD000038B504460025143001F0B8FED5 +:1018000004F14C00257701F087FF201D84F8545027 +:101810000121FFF701FF2046BDE83840FFF750BF28 +:1018200090F8803003F06003202B06D190F88120DF +:101830000023212A03D81F2A06D800207047222A15 +:10184000FBD1C0E91D3303E0034A426707228267E8 +:10185000C3670120704700BF2C22002037B500F578 +:101860008055D5F8A4381A68117804291AD1017C5A +:10187000022917D11979012312898B40134211D102 +:1018800000F14C04204602F007F858B101A92046A7 +:1018900001F04EFFD5F8A4480246019B217920684B +:1018A00000F0C0F803B030BD01F10B03F0B550F803 +:1018B000236085B004460D46FEB1202383F31188D2 +:1018C00004EB8507301D0821FFF7A6FEFB6806F133 +:1018D0004C005B691B681BB1019001F037FF019858 +:1018E00003A901F025FF024648B1039B2946204683 +:1018F00000F098F8002383F3118805B0F0BDFB6871 +:101900005A691268002AF5D01B8A013B1340F1D1B5 +:1019100004F18002EAE70000133138B550F82140A5 +:10192000ECB1202383F3118804F58053D3F8A42865 +:101930001368527903EB8203DB689B695D6845B1EC +:1019400004216018FFF768FE294604F1140001F035 +:1019500025FE2046FFF7B4FE002383F3118838BD2F +:101960007047000001F018B901234022002110B592 +:10197000044600F8303BFFF775FA0023C4E9013351 +:1019800010BD000010B52023044683F311882422E3 +:10199000416000210C30FFF765FA204601F01EF986 +:1019A00002232370002383F3118810BD70B500EB70 +:1019B0008103054650690E461446DA6018B11022BC +:1019C0000021FFF74FFAA06918B110220021FFF79C +:1019D00049FA31462846BDE8704001F011BA0000CE +:1019E00083682022002103F0011310B504468360B0 +:1019F0001030FFF737FA2046BDE8104001F08CBAEE +:101A0000F0B4012500EB810447898D40E4683D4333 +:101A1000A469458123600023A2606360F0BC01F0EB +:101A2000A9BA0000F0B4012500EB810407898D40BC +:101A3000E4683D436469058123600023A26063601C +:101A4000F0BC01F01FBB000070B502230025044666 +:101A5000242203702946C0F888500C3040F8045CFA +:101A6000FFF700FA204684F8705001F05DF96368D2 +:101A70001B6823B129462046BDE87040184770BD59 +:101A8000037880F88C300523037043681B6810B519 +:101A900004460BB1042198470023A36010BD000049 +:101AA00090F88C20436802701B680BB10521184721 +:101AB0007047000070B590F87030044613B10023F1 +:101AC00080F8703004F18002204601F049FA636822 +:101AD0009B68B3B994F8803013F0600535D00021CD +:101AE000204601F0F3FC0021204601F0E3FC63688E +:101AF0001B6813B1062120469847062384F87030EE +:101B000070BD204698470028E4D0B4F88630A26F14 +:101B10009A4288BFA36794F98030A56F002B4FF0DD +:101B2000200380F20381002D00F0F280092284F866 +:101B3000702083F3118800212046D4E91D23FFF78C +:101B400071FF002383F31188DAE794F8812003F012 +:101B50007F0343EA022340F20232934200F0C58041 +:101B600021D8B3F5807F48D00DD8012B3FD0022B70 +:101B700000F09380002BB2D104F188026267022248 +:101B8000A267E367C1E7B3F5817F00F09B80B3F5FF +:101B9000407FA4D194F88230012BA0D1B4F88830D2 +:101BA00043F0020332E0B3F5006F4DD017D8B3F520 +:101BB000A06F31D0A3F5C063012B90D86368204695 +:101BC00094F882205E6894F88310B4F88430B047AB +:101BD000002884D0436863670368A3671AE0B3F5FD +:101BE000106F36D040F6024293427FF478AF5C4BE0 +:101BF00063670223A3670023C3E794F88230012BB5 +:101C00007FF46DAFB4F8883023F00203A4F8883075 +:101C1000C4E91D55E56778E7B4F88030B3F5A06FE7 +:101C20000ED194F88230204684F88A3001F0DAF838 +:101C300063681B6813B10121204698470323237072 +:101C40000023C4E91D339CE704F18B036367012380 +:101C5000C3E72378042B10D1202383F31188204677 +:101C6000FFF7BEFE85F311880321636884F88B506B +:101C700021701B680BB12046984794F88230002BE6 +:101C8000DED084F88B300423237063681B68002B3C +:101C9000D6D0022120469847D2E794F884302046D7 +:101CA0001D0603F00F010AD501F04CF9012804D0FC +:101CB00002287FF414AF2B4B9AE72B4B98E701F0E7 +:101CC00033F9F3E794F88230002B7FF408AF94F8EF +:101CD000843013F00F01B3D01A06204602D501F06C +:101CE0000DFCADE701F0FEFBAAE794F88230002B73 +:101CF0007FF4F5AE94F8843013F00F01A0D01B06EA +:101D0000204602D501F0E2FB9AE701F0D3FB97E70A +:101D1000142284F8702083F311882B462A46294622 +:101D20002046FFF76DFE85F31188E9E65DB11522C7 +:101D300084F8702083F3118800212046D4E91D2304 +:101D4000FFF75EFEFDE60B2284F8702083F3118816 +:101D50002B462A4629462046FFF764FEE3E700BFEC +:101D6000F0400008E8400008EC40000838B590F862 +:101D700070300446002B3ED0063BDAB20F2A34D82E +:101D80000F2B32D8DFE803F03731310822323131FE +:101D90003131313131313737856FB0F886309D427E +:101DA00014D2C3681B8AB5FBF3F203FB12556DB95D +:101DB000202383F311882B462A462946FFF732FE5B +:101DC00085F311880A2384F870300EE0142384F818 +:101DD0007030202383F31188002320461A461946C9 +:101DE000FFF70EFE002383F3118838BDC36F03B1E4 +:101DF00098470023E7E70021204601F067FB002118 +:101E0000204601F057FB63681B6813B1062120468A +:101E100098470623D7E7000010B590F870300446C5 +:101E2000142B29D017D8062B05D001D81BB110BD13 +:101E3000093B022BFBD80021204601F047FB002183 +:101E4000204601F037FB63681B6813B1062120466A +:101E50009847062319E0152BE9D10B2380F8703041 +:101E6000202383F3118800231A461946FFF7DAFD71 +:101E7000002383F31188DAE7C3689B695B68002B52 +:101E8000D5D1C36F03B19847002384F87030CEE7F3 +:101E9000024B0022C3E900339A60704738280020C3 +:101EA000002382680374054B1B6899689142FBD23A +:101EB0005A680360426010605860704738280020FC +:101EC00008B5202383F31188037C032B05D0042B52 +:101ED0000DD02BB983F3118808BD436900221A6025 +:101EE0004FF0FF334361FFF7DBFF0023F2E7D0E958 +:101EF000003213605A60F3E7002382680374054BD5 +:101F00001B6899689142FBD85A6803604260106070 +:101F10005860704738280020054B19690874186804 +:101F2000026853601A60186101230374FEF74EBA09 +:101F3000382800204B1C30B5044687B00A4D10D01D +:101F40002B6901A8094A00F025F92046FFF7E4FFB4 +:101F5000049B13B101A800F059F92B69586907B027 +:101F600030BDFFF7D9FFF8E738280020C11E000870 +:101F700038B50C4D044641612B6981689A689142DD +:101F800003D8BDE83840FFF78BBF1846FFF7B4FF12 +:101F900001232C61014623742046BDE83840FEF73A +:101FA00015BA00BF38280020044B1A681B699068D6 +:101FB0009B68984294BF0020012070473828002079 +:101FC00010B5084C236820691A6854602260012209 +:101FD00023611A74FFF790FF01462069BDE81040A5 +:101FE000FEF7F4B93828002008B5FFF7DDFF18B177 +:101FF000BDE80840FFF7E4BF08BD0000FFF7E0BF01 +:10200000FEE7000010B50C4CFFF742FF00F0B4F8FB +:1020100080220A49204600F03BF8012344F8180CBE +:10202000037400F097FC002383F3118862B6044820 +:10203000BDE8104000F04CB860280020F4400008D3 +:102040000441000800F01CB9EFF3118020B9EFF350 +:102050000583202282F311887047000010B530B943 +:10206000EFF30584C4F3080414B180F3118810BDA4 +:10207000FFF7BAFF84F31188F9E70000034A5168BB +:1020800053685B1A9842FBD8704700BF001000E00D +:1020900082600222028270478368A3F17C0243F8C7 +:1020A0000C2C026943F83C2C426943F8382C074A4F +:1020B00043F81C2CC268A3F1180043F8102C02222C +:1020C00003F8082C002203F8072C7047E5030008EA +:1020D00010B5202383F31188FFF7DEFF00210446AB +:1020E000FFF746FF002383F31188204610BD000050 +:1020F000024B1B6958610F20FFF70EBF38280020E4 +:10210000202383F31188FFF7F3BF000008B50146D1 +:10211000202383F311880820FFF70CFF002383F3AB +:10212000118808BD49B1064B42681B6918605A60A6 +:10213000136043600420FFF7FDBE4FF0FF3070478F +:10214000382800200368984206D01A680260506060 +:1021500018465961FFF7A4BE7047000038B5044621 +:102160000D462068844200D138BD036823605C605E +:102170004561FFF795FEF4E7054B4FF0FF3103F1A2 +:102180001402C3E905220022C3E90712704700BF09 +:102190003828002070B51C4E05460C46C0E90323C4 +:1021A00001F0B0FB334653F8142F9A420DD1306240 +:1021B0000A2C2CBF00190A302A60C5E90124C6E99F +:1021C0000555BDE8704001F087BB316A431AE3183A +:1021D00038BF1C469368A34202D9081901F08CFB52 +:1021E00073699A6894420CD85A68AC602B606A6034 +:1021F00015609A685D60121B9A604FF0FF33F361BF +:1022000070BDA41A1B68ECE73828002038B51B4CB9 +:10221000636998420DD08168D0E9003213605A603A +:102220000022C2609A680A449A604FF0FF33E3616B +:1022300038BD03682246002142F8143F93425A6099 +:10224000C16003D1BDE8384001F050BB9A68816895 +:10225000256A0A449A6001F055FB6369411B9A683C +:102260008A42E5D9AB181D1A206A092D98BF01F1E1 +:102270000A02BDE83840104401F03EBB3828002077 +:102280002DE9F041184C002704F11406656901F0AE +:1022900039FB236AAA68C11A8A4215D81344D5F8B3 +:1022A0000C802362D5E9003213605A606369EF60E5 +:1022B000B34201D101F01AFB87F311882869C047A6 +:1022C000202383F31188E1E76169B14209D0134407 +:1022D0001B1ABDE8F0410A2B2CBFC0180A3001F0D0 +:1022E0000BBBBDE8F08100BF3828002000207047FC +:1022F000FEE70000704700004FF0FF30704700001D +:1023000002290CD0032904D00129074818BF002056 +:102310007047032A05D8054800EBC20070470448FF +:1023200070470020704700BFE84100083C220020B1 +:102330009C41000870B59AB005460846144601A9AC +:1023400000F0C2F801A8FEF785FD431C0022C6B2CA +:102350005B001046C5E9003423700323023404F8FF +:10236000013C01ABD1B202348E4201D81AB070BD2B +:1023700013F8011B013204F8010C04F8021CF1E708 +:1023800008B5202383F311880348FFF767FA002379 +:1023900083F3118808BD00BFF029002090F8803039 +:1023A00003F01F02012A07D190F881200B2A03D1E4 +:1023B0000023C0E91D3315E003F06003202B08D192 +:1023C000B0F884302BB990F88120212A03D81F2A35 +:1023D00004D8FFF725BA222AEBD0FAE7034A42676E +:1023E00007228267C3670120704700BF33220020A5 +:1023F00007B5052917D8DFE801F0191603191920C8 +:10240000202383F31188104A01210190FFF7CEFAAF +:10241000019802210D4AFFF7C9FA0D48FFF7EAF9C2 +:10242000002383F3118803B05DF804FB202383F3BA +:1024300011880748FFF7B4F9F2E7202383F31188E6 +:102440000348FFF7CBF9EBE73C4100086041000887 +:10245000F029002038B50C4D0C4C2A460C4904F1EB +:102460000800FFF767FF05F1CA0204F110000949EF +:10247000FFF760FF05F5CA7204F118000649BDE8D0 +:102480003840FFF757BF00BFC84200203C22002061 +:102490001C410008264100083141000870B504467F +:1024A00008460D46FEF7D6FCC6B220460134037836 +:1024B0000BB9184670BD32462946FEF7B7FC002816 +:1024C000F3D10120F6E700002DE9F84F05460C4650 +:1024D000FEF7C0FC2B49C6B22846FFF7DFFF2A49AA +:1024E0002846FFF7DBFF08B11036F6B2632E0DD891 +:1024F000DFF89080DFF89090244FDFF898A0DFF8A5 +:1025000098B02E7846B92670BDE8F88F2946204647 +:10251000BDE8F84F01F09ABD252E2ED10722414685 +:102520002846FEF783FC70B9DBF800300735073426 +:1025300044F8073CBBF8043024F8033C9BF8063011 +:1025400004F8013CDDE7082249462846FEF76EFC08 +:1025500098B9A21C0E4B197802320909C95D02F81C +:10256000041C13F8011B01F00F015345C95D02F86B +:10257000031CF0D118340835C3E7013504F8016BAA +:10258000BFE700BF084200083141000818420008B8 +:1025900000E8F11F0CE8F11F10420008BFF34F8F55 +:1025A000044B1A695107FCD1D3F810215207F8D116 +:1025B000704700BF0020005208B50D4B1B78ABB927 +:1025C000FFF7ECFF0B4BDA68D10704D50A4A5A60D3 +:1025D00002F188325A60D3F80C21D20706D5064A98 +:1025E000C3F8042102F18832C3F8042108BD00BFFA +:1025F00026450020002000522301674508B5114BF5 +:102600001B78F3B9104B1A69510703D5DA6842F009 +:102610004002DA60D3F81021520705D5D3F80C2117 +:1026200042F04002C3F80C21FFF7B8FF064BDA680E +:1026300042F00102DA60D3F80C2142F00102C3F843 +:102640000C2108BD26450020002000520F289ABF0B +:1026500000F5806040040020704700004FF4003017 +:1026600070470000102070470F2808B50BD8FFF7FF +:10267000EDFF00F500330268013204D104308342DB +:10268000F9D1012008BD0020FCE700000F2870B53B +:10269000054645D8FFF7D8FC224CFFF77FFF0646DA +:1026A000FFF78AFF4FF0FF33072D6361C4F8143141 +:1026B00020D82361FFF772FF2B0243F02403E3606D +:1026C000E36843F08003E36023695A07FCD428469B +:1026D000FFF764FF4FF40031FFF7B8FF00F002F995 +:1026E0003046FFF78BFFFFF7B9FC2846BDE8704086 +:1026F000FFF7BABFC4F81031FFF750FFA5F1080388 +:102700001B0243F02403C4F80C31D4F80C3143F01D +:102710008003C4F80C31D4F810315B07FBD4D6E742 +:10272000002070BD002000522DE9F84F40EA02035E +:1027300005460C461746D80602D00020BDE8F88FA3 +:1027400027F01F07DFF8D4B0FFF736FF2744BC425D +:1027500003D10120FFF752FFF0E72022294620464F +:1027600001F064FC10B920352034F0E72B4605F168 +:1027700020021E68711CE0D104339A42F9D1FFF7A0 +:1027800063FC05F17843234AB3F5801F224B28BF31 +:102790009A4603F1040338BF9046A2F1080228BF0D +:1027A0009846A3F108033ABF9146DA469946FFF7E7 +:1027B000F5FEC8F80060A5EB040CD9F8002004F180 +:1027C0001C0142F00202C9F80020221FDAF8006062 +:1027D00016F00506FAD152F8043F8A424CF802304E +:1027E000F4D1BFF34F8FFFF7D9FE4FF0FF32C8F897 +:1027F0000020D9F8002022F00202C9F80020FFF7DB +:102800002DFC20222146284601F010FC0028AAD0E9 +:1028100030469FE714200052102100521020005231 +:1028200010B5084C237828B11BB9FFF7C5FE01236A +:10283000237010BD002BFCD02070BDE81040FFF7C6 +:10284000DDBE00BF264500200244074BD2B210B5C2 +:10285000904200D110BD441C00B253F8200041F852 +:10286000040BE0B2F4E700BF504000580E4B30B507 +:102870001C6F240405D41C6F1C671C6F44F40044B7 +:102880001C670A4C02442368D2B243F4807323606D +:10289000074B904200D130BD441C51F8045B00B29C +:1028A00043F82050E0B2F4E70044025800480258D0 +:1028B0005040005807B5012201A90020FFF7C4FFCE +:1028C000019803B05DF804FB13B50446FFF7F2FF6F +:1028D000A04205D0012201A900200194FFF7C6FF04 +:1028E00002B010BD0144BFF34F8F064B884204D3A2 +:1028F000BFF34F8FBFF36F8F7047C3F85C02203078 +:10290000F4E700BF00ED00E0034B1A681AB9034A70 +:10291000D2F8D0241A6070472845002000400258A1 +:1029200008B5FFF7F1FF024B1868C0F3806008BDDF +:1029300028450020EFF30983054968334A6B22F0EC +:1029400001024A6383F30988002383F311887047E7 +:1029500000EF00E0202080F3118862B60D4B0E4A94 +:10296000D96821F4E0610904090C0A430B49DA60D3 +:10297000D3F8FC2042F08072C3F8FC20084AC2F869 +:10298000B01F116841F0010111601022DA7783F85D +:102990002200704700ED00E00003FA0555CEACC5FB +:1029A000001000E0202310B583F311880E4B5B6804 +:1029B00013F4006314D0F1EE103AEFF309844FF0F2 +:1029C0008073683CE361094BDB6B236684F3098801 +:1029D000FFF7EAFA10B1064BA36110BD054BFBE708 +:1029E00083F31188F9E700BF00ED00E000EF00E09D +:1029F000F7030008FA03000870B5BFF34F8FBFF369 +:102A00006F8F1A4A0021C2F85012BFF34F8FBFF3E5 +:102A10006F8F536943F400335361BFF34F8FBFF39C +:102A20006F8FC2F88410BFF34F8FD2F8803043F617 +:102A3000E074C3F3C900C3F34E335B0103EA040639 +:102A4000014646EA81750139C2F86052F9D2203B4D +:102A500013F1200FF2D1BFF34F8F536943F480334A +:102A60005361BFF34F8FBFF36F8F70BD00ED00E078 +:102A7000FEE700000A4B0B480B4A90420BD30B4B6E +:102A8000C11EDA1C121A22F003028B4238BF002248 +:102A90000021FEF7E7B953F8041B40F8041BECE7EC +:102AA000FC430008FC460020FC460020FC460020B9 +:102AB0007047000070B5D0E9244300224FF0FF3585 +:102AC0009E6804EB42135101D3F80009002805DA8F +:102AD000D3F8000940F08040C3F80009D3F8000B98 +:102AE000002805DAD3F8000B40F08040C3F8000B53 +:102AF000013263189642C3F80859C3F8085BE0D264 +:102B00004FF00113C4F81C3870BD000000EB8103C6 +:102B1000D3F80CC02DE9F043DCF814204E1CD0F89B +:102B20009050D2F800E005EB063605EB41185068EE +:102B300070450AD30122D5F8343802FA01F123EAAC +:102B40000101C5F83418BDE8F083AEEB0003BCF812 +:102B50001040A34228BF2346D8F81849A4B2B3EBCB +:102B6000840FF0D89468A4F1040959F8047F376001 +:102B7000A4EB09071F44042FF7D81C4403449460B6 +:102B80005360D4E7890141F02001016103699B068C +:102B9000FCD41220FFF772BA10B50A4C2046FEF79B +:102BA000E3FE094BC4F89030084BC4F89430084C4D +:102BB0002046FEF7D9FE074BC4F89030064BC4F808 +:102BC000943010BD2C450020000008405042000801 +:102BD000C8450020000004405C42000870B503783E +:102BE0000546012B5DD1494BD0F89040984259D110 +:102BF000474B0E216520D3F8D82042F00062C3F87D +:102C0000D820D3F8002142F00062C3F80021D3F8A5 +:102C10000021D3F8802042F00062C3F88020D3F86E +:102C2000802022F00062C3F88020D3F8803000F0CA +:102C300071FC384BE360384BC4F800380023D5F8FA +:102C40009060C4F8003EC02323604FF40413A363D4 +:102C50003369002BFCDA01230C203361FFF70EFAF5 +:102C60003369DB07FCD41220FFF708FA3369002B25 +:102C7000FCDA00262846A660FFF71CFF6B68C4F844 +:102C80001068DB68C4F81468C4F81C68002B3AD1DB +:102C9000224BA3614FF0FF336361A36843F001034C +:102CA000A36070BD1E4B9842C8D1194B0E214D2018 +:102CB000D3F8D82042F00072C3F8D820D3F800210E +:102CC00042F00072C3F80021D3F80021D3F880202D +:102CD00042F00072C3F88020D3F8802022F0007206 +:102CE000C3F88020D3F88020D3F8D82022F0806267 +:102CF000C3F8D820D3F8002122F08062C3F8002165 +:102D0000D3F8003193E7074BC3E700BF2C45002001 +:102D1000004402584014004003002002003C30C030 +:102D2000C8450020083C30C0F8B5D0F890400546B2 +:102D300000214FF000662046FFF724FFD5F89410DD +:102D400000234FF001128F684FF0FF30C4F8343881 +:102D5000C4F81C2804EB431201339F42C2F80069F7 +:102D6000C2F8006BC2F80809C2F8080BF2D20B686F +:102D7000D5F89020C5F89830636210231361166966 +:102D800016F01006FBD11220FFF778F9D4F80038BE +:102D900023F4FE63C4F80038A36943F4402343F0EE +:102DA0001003A3610923C4F81038C4F814380B4B7E +:102DB000EB604FF0C043C4F8103B094BC4F8003B34 +:102DC000C4F81069C4F80039D5F8983003F110023E +:102DD00043F48013C5F89820A362F8BD2C42000884 +:102DE00040800010D0F8902090F88A10D2F8003877 +:102DF00023F4FE6343EA0113C2F800387047000071 +:102E00002DE9F84300EB8103D0F890500C46804642 +:102E1000DA680FFA81F94801166806F00306731E96 +:102E2000022B05EB41134FF0000194BFB604384E5E +:102E3000C3F8101B4FF0010104F1100398BF06F115 +:102E4000805601FA03F3916998BF06F50046002900 +:102E50003AD0578A04F15801374349016F50D5F8E9 +:102E60001C180B430021C5F81C382B180127C3F888 +:102E70001019A7405369611E9BB3138A928B9B085C +:102E8000012A88BF5343D8F89820981842EA034390 +:102E900001F140022146C8F89800284605EB82025D +:102EA0005360FFF76FFE08EB8900C3681B8A43EA93 +:102EB000845348341E4364012E51D5F81C381F43F7 +:102EC000C5F81C78BDE8F88305EB4917D7F8001B57 +:102ED00021F40041C7F8001BD5F81C1821EA0303B0 +:102EE000C0E704F13F030B4A2846214605EB830364 +:102EF0005A60FFF747FE05EB4910D0F8003923F47C +:102F00000043C0F80039D5F81C3823EA0707D7E793 +:102F10000080001000040002D0F894201268C0F86D +:102F20009820FFF7C7BD00005831D0F89030490114 +:102F30005B5813F4004004D013F4001F0CBF0220B0 +:102F4000012070474831D0F8903049015B5813F4A4 +:102F5000004004D013F4001F0CBF02200120704772 +:102F600000EB8101CB68196A0B6813604B685360F2 +:102F70007047000000EB810330B5DD68AA69136873 +:102F8000D36019B9402B84BF402313606B8A146847 +:102F9000D0F890201C4402EB4110013C09B2B4FB74 +:102FA000F3F46343033323F0030343EAC44343F0DE +:102FB000C043C0F8103B2B6803F00303012B0ED174 +:102FC000D2F8083802EB411013F4807FD0F8003BB0 +:102FD00014BF43F0805343F00053C0F8003B02EBB2 +:102FE0004112D2F8003B43F00443C2F8003B30BD2D +:102FF0002DE9F041D0F8906005460C4606EB4113F0 +:10300000D3F8087B3A07C3F8087B08D5D6F81438FC +:103010001B0704D500EB8103DB685B689847FA0760 +:103020001FD5D6F81438DB071BD505EB8403D96808 +:10303000CCB98B69488A5A68B2FBF0F600FB1622BD +:103040008AB91868DA6890420DD2121AC3E90024CE +:10305000202383F3118821462846FFF78BFF84F352 +:103060001188BDE8F081012303FA04F26B8923EA99 +:1030700002036B81CB68002BF3D021462846BDE8C4 +:10308000F041184700EB81034A0170B5DD68D0F8C4 +:1030900090306C692668E66056BB1A444FF40020F5 +:1030A000C2F810092A6802F00302012A0AB20ED1FE +:1030B000D3F8080803EB421410F4807FD4F8000919 +:1030C00014BF40F0805040F00050C4F8000903EBFA +:1030D0004212D2F8000940F00440C2F8000901226F +:1030E000D3F8340802FA01F10143C3F8341870BD73 +:1030F00019B9402E84BF4020206020681A442E8ACF +:103100008419013CB4FBF6F440EAC44040F000509E +:10311000C6E700002DE9F041D0F8906004460D4666 +:1031200006EB4113D3F80879C3F80879FB071CD5DF +:10313000D6F81038DA0718D500EB8103D3F80CC0A5 +:10314000DCF81430D3F800E0DA6896451BD2A2EB25 +:103150000E024FF000081A60C3F80480202383F3A6 +:103160001188FFF78FFF88F311883B0618D50123DC +:10317000D6F83428AB40134212D029462046BDE889 +:10318000F041FFF7C3BC012303FA01F2038923EAEC +:1031900002030381DCF80830002BE6D09847E4E70F +:1031A000BDE8F0812DE9F84FD0F8905004466E69E3 +:1031B000AB691E4016F480586E6103D0BDE8F84F2D +:1031C000FEF742BC002E12DAD5F8003E9F0705D06C +:1031D000D5F8003E23F00303C5F8003ED5F80438C7 +:1031E000204623F00103C5F80438FEF759FC3005EA +:1031F00005D52046FFF75EFC2046FEF741FCB104F2 +:103200000CD5D5F8083813F0060FEB6823F470538B +:103210000CBF43F4105343F4A053EB60320704D5C2 +:103220006368DB680BB120469847F30200F1BA806F +:10323000B70226D5D4F8909000274FF0010A09EB89 +:103240004712D2F8003B03F44023B3F5802F11D18D +:10325000D2F8003B002B0DDA62890AFA07F322EA62 +:103260000303638104EB8703DB68DB6813B1394632 +:10327000204698470137D4F89430FFB29B689F42AC +:10328000DDD9F00619D5D4F89000026AC2F30A1706 +:1032900002F00F0302F4F012B2F5802F00F0CC80A0 +:1032A000B2F5402F09D104EB8303002200F58050D2 +:1032B000DB681B6A974240F0B2803003D5F818589B +:1032C00035D5E90303D500212046FFF791FEAA0377 +:1032D00003D501212046FFF78BFE6B0303D50221A6 +:1032E0002046FFF785FE2F0303D503212046FFF775 +:1032F0007FFEE80203D504212046FFF779FEA902EC +:1033000003D505212046FFF773FE6A0203D5062187 +:103310002046FFF76DFE2B0203D507212046FFF75D +:1033200067FEEF0103D508212046FFF761FE700319 +:1033300040F1A980E90703D500212046FFF7EAFE06 +:10334000AA0703D501212046FFF7E4FE6B0703D54A +:1033500002212046FFF7DEFE2F0703D5032120467A +:10336000FFF7D8FEEE0603D504212046FFF7D2FE74 +:10337000A80603D505212046FFF7CCFE690603D534 +:1033800006212046FFF7C6FE2A0603D50721204660 +:10339000FFF7C0FEEB0576D520460821BDE8F84FC3 +:1033A000FFF7B8BED4F8909000274FF0010AD4F888 +:1033B00094305FFA87FB9B689B453FF639AF09EB7A +:1033C0004B13D3F8002902F44022B2F5802F24D108 +:1033D000D3F80029002A20DAD3F8002942F09042DD +:1033E000C3F80029D3F80029002AFBDB5946D4F89A +:1033F0009000FFF7C7FB22890AFA0BF322EA0303C6 +:10340000238104EB8B03DB689B6813B1594620468C +:10341000984759462046FFF779FB0137C7E79107E0 +:1034200001D1D0F80080072A02F101029CBF03F805 +:10343000018B4FEA18283DE704EB830300F5805029 +:10344000DA68D2F818C0DCF80820DCE9001CA1EB2F +:103450000C0C00218F4208D1DB689B699A683A44C2 +:103460009A605A683A445A6027E711F0030F01D175 +:10347000D0F800808C4501F1010184BF02F8018B76 +:103480004FEA1828E6E7BDE8F88F000008B50348C2 +:10349000FFF788FEBDE80840FFF784BA2C450020FE +:1034A00008B50348FFF77EFEBDE80840FFF77ABA8B +:1034B000C8450020D0F8903003EB4111D1F8003B13 +:1034C00043F40013C1F8003B70470000D0F890307F +:1034D00003EB4111D1F8003943F40013C1F800396E +:1034E00070470000D0F8903003EB4111D1F8003B59 +:1034F00023F40013C1F8003B70470000D0F890306F +:1035000003EB4111D1F8003923F40013C1F800395D +:1035100070470000090100F16043012203F5614397 +:10352000C9B283F8001300F01F039A4043099B00BF +:1035300003F1604303F56143C3F880211A607047CB +:1035400030B50433039C0172002104FB0325C160E4 +:10355000C0E90653049B0363059BC0E90000C0E972 +:103560000422C0E90842C0E90A11436330BD0000EB +:103570000022416AC260C0E90411C0E90A226FF06A +:103580000101FEF7EBBD0000D0E90432934201D106 +:10359000C2680AB9181D7047002070470369196096 +:1035A0000021C2680132C260C26913448269934239 +:1035B000036124BF436A0361FEF7C4BD38B5044606 +:1035C0000D46E3683BB162690020131D1268A362D7 +:1035D0001344E36207E0237A33B929462046FEF715 +:1035E000A1FD0028EDDA38BD6FF00100FBE7000017 +:1035F000C368C269013BC360436913448269934253 +:10360000436124BF436A436100238362036B03B1B8 +:103610001847704770B52023044683F31188866AE3 +:103620003EB9FFF7CBFF054618B186F3118828464F +:1036300070BDA36AE26A13F8015B9342A36202D3EE +:103640002046FFF7D5FF002383F31188EFE7000042 +:103650002DE9F84F04460E46174698464FF02009CC +:1036600089F311880025AA46D4F828B0BBF1000FD1 +:1036700009D141462046FFF7A1FF20B18BF3118805 +:103680002846BDE8F88FD4E90A12A7EB050B521AB9 +:10369000934528BF9346BBF1400F1BD9334601F138 +:1036A000400251F8040B914243F8040BF9D1A36A8C +:1036B000403640354033A362D4E90A239A4202D30C +:1036C0002046FFF795FF8AF31188BD42D8D289F3CF +:1036D0001188C9E730465A46FDF79EFBA36A5E444F +:1036E0005D445B44A362E7E710B5029C04330172BA +:1036F00004FB0321C460C0E906130023C0E90A33B8 +:10370000039B0363049BC0E90000C0E90422C0E9F5 +:103710000842436310BD0000026A6FF00101C260FD +:10372000426AC0E904220022C0E90A22FEF716BD5F +:10373000D0E904239A4201D1C26822B9184650F850 +:10374000043B0B607047002070470000C3680021F5 +:10375000C2690133C3604369134482699342436180 +:1037600024BF436A4361FEF7EDBC000038B5044650 +:103770000D46E3683BB1236900201A1DA262E2698D +:103780001344E36207E0237A33B929462046FEF763 +:10379000C9FC0028EDDA38BD6FF00100FBE700003E +:1037A00003691960C268013AC260C2691344826940 +:1037B0009342036124BF436A036100238362036B66 +:1037C00003B118477047000070B520230D4604462A +:1037D000114683F31188866A2EB9FFF7C7FF10B12F +:1037E00086F3118870BDA36A1D70A36AE26A013373 +:1037F0009342A36204D3E16920460439FFF7D0FF66 +:10380000002080F31188EDE72DE9F84F04460D46BE +:10381000904699464FF0200A8AF311880026B34655 +:10382000A76A4FB949462046FFF7A0FF20B187F3AA +:1038300011883046BDE8F88FD4E90A073A1AA8EB98 +:103840000607974228BF1746402F1BD905F14003B2 +:1038500055F8042B9D4240F8042BF9D1A36A403659 +:103860004033A362D4E90A239A4204D3E169204693 +:103870000439FFF795FF8BF311884645D9D28AF3B7 +:103880001188CDE729463A46FDF7C6FAA36A3D44BA +:103890003E443B44A362E5E7D0E904239A4217D1B2 +:1038A000C3689BB1836A8BB1043B9B1A0ED0136033 +:1038B000C368013BC360C3691A4483699A420261C9 +:1038C00024BF436A036100238362012318467047C3 +:1038D0000023FBE700F0DAB8034B002258631A61BB +:1038E0000222DA60704700BF000C0040014B00224A +:1038F000DA607047000C0040014B5863704700BF0E +:10390000000C0040014B586A704700BF000C00409B +:103910004B6843608B688360CB68C3600B6943610D +:103920004B6903628B6943620B6803607047000058 +:1039300008B53C4B40F2FF713B48D3F888200A435E +:10394000C3F88820D3F8882022F4FF6222F007020F +:10395000C3F88820D3F88820D3F8E0200A43C3F8BE +:10396000E020D3F808210A43C3F808212F4AD3F8EE +:1039700008311146FFF7CCFF00F5806002F11C0111 +:10398000FFF7C6FF00F5806002F13801FFF7C0FFC6 +:1039900000F5806002F15401FFF7BAFF00F5806086 +:1039A00002F17001FFF7B4FF00F5806002F18C01B5 +:1039B000FFF7AEFF00F5806002F1A801FFF7A8FF56 +:1039C00000F5806002F1C401FFF7A2FF00F58060FE +:1039D00002F1E001FFF79CFF00F5806002F1FC01BD +:1039E000FFF796FF02F58C7100F58060FFF790FFFE +:1039F00000F000F90E4BD3F8902242F00102C3F818 +:103A00009022D3F8942242F00102C3F894220522B6 +:103A1000C3F898204FF06052C3F89C20054AC3F8C1 +:103A2000A02008BD00440258000002586842000867 +:103A300000ED00E01F00080308B500F0D7FAFEF71C +:103A4000E1FA0F4BD3F8DC2042F04002C3F8DC204F +:103A5000D3F8042122F04002C3F80421D3F8043142 +:103A6000084B1A6842F008021A601A6842F0040211 +:103A70001A60FEF749FFBDE80840FEF7EBBC00BF47 +:103A8000004402580018024870470000114BD3F858 +:103A9000E82042F00802C3F8E820D3F8102142F0F1 +:103AA0000802C3F810210C4AD3F81031D36B43F04D +:103AB0000803D363C722094B9A624FF0FF32DA62E0 +:103AC00000229A615A63DA605A6001225A611A60D0 +:103AD000704700BF004402580010005C000C00401A +:103AE000094A08B51169D3680B40D9B29B076FEA40 +:103AF0000101116107D5202383F31188FEF7A2FA93 +:103B0000002383F3118808BD000C0040384B4FF0B0 +:103B1000FF31D3F88020C3F88010D3F88020002232 +:103B2000C3F88020D3F88000D3F88400C3F8841051 +:103B3000D3F88400C3F88420D3F88400D86F40F011 +:103B4000FF4040F4FF0040F43F5040F03F00D86792 +:103B5000D86F20F0FF4020F4FF0020F43F5020F009 +:103B60003F00D867D86FD3F888006FEA40506FEAFB +:103B70005050C3F88800D3F88800C0F30A00C3F897 +:103B80008800D3F88800D3F89000C3F89010D3F8D9 +:103B90009000C3F89020D3F89000D3F89400C3F8B5 +:103BA0009410D3F89400C3F89420D3F89400D3F879 +:103BB0009800C3F89810D3F89800C3F89820D3F869 +:103BC0009800D3F88C00C3F88C10D3F88C00C3F89D +:103BD0008C20D3F88C00D3F89C00C3F89C10D3F849 +:103BE0009C10C3F89C20D3F89C3000F0D3B900BFE0 +:103BF00000440258614B0122C3F80821604BD3F8FE +:103C0000F42042F00202C3F8F420D3F81C2142F061 +:103C10000202C3F81C210222D3F81C31594BDA608E +:103C20005A689104FCD5584A1A6001229A60574A92 +:103C3000DA6000221A614FF440429A61514B9A694E +:103C40009204FCD51A6842F480721A604C4B1A6FC9 +:103C500012F4407F04D04FF480321A6700221A67B2 +:103C60001A6842F001021A60454B1A685007FCD5E9 +:103C700000221A611A6912F03802FBD10121196081 +:103C80004FF0804159605A67414ADA62414A1A61ED +:103C90001A6842F480321A60394B1A689103FCD5D5 +:103CA0001A6842F480521A601A689204FCD53A4AA3 +:103CB0003A499A6200225A6319633949DA6399636F +:103CC0005A64384A1A64384ADA621A6842F0A852CA +:103CD0001A602B4B1A6802F02852B2F1285FF9D112 +:103CE00048229A614FF48862DA6140221A622F4AB0 +:103CF000DA644FF080521A652D4A5A652D4A9A654A +:103D000032232D4A1360136803F00F03022BFAD1FC +:103D10001B4B1A6942F003021A611A6902F0380259 +:103D2000182AFAD1D3F8DC2042F00052C3F8DC2084 +:103D3000D3F8042142F00052C3F80421D3F804213F +:103D4000D3F8DC2042F08042C3F8DC20D3F8042111 +:103D500042F08042C3F80421D3F80421D3F8DC20D8 +:103D600042F00042C3F8DC20D3F8042142F00042C4 +:103D7000C3F80421D3F80431704700BF008000511C +:103D8000004402580048025800C000F00200000140 +:103D90000000FF0100889008121020006302090152 +:103DA0002C02040047040508FD0BFF012000002041 +:103DB0000010E00000010100002000524FF0B0426E +:103DC00008B5D2F8883003F00103C2F8883023B177 +:103DD000044A13680BB150689847BDE80840FEF7E5 +:103DE000E1BD00BF7C4600204FF0B04208B5D2F8DC +:103DF000883003F00203C2F8883023B1044A936884 +:103E00000BB1D0689847BDE80840FEF7CBBD00BFB6 +:103E10007C4600204FF0B04208B5D2F8883003F05D +:103E20000403C2F8883023B1044A13690BB1506906 +:103E30009847BDE80840FEF7B5BD00BF7C460020AE +:103E40004FF0B04208B5D2F8883003F00803C2F84A +:103E5000883023B1044A93690BB1D0699847BDE813 +:103E60000840FEF79FBD00BF7C4600204FF0B042E7 +:103E700008B5D2F8883003F01003C2F8883023B1B7 +:103E8000044A136A0BB1506A9847BDE80840FEF730 +:103E900089BD00BF7C4600204FF0B04310B5D3F879 +:103EA000884004F47872C3F88820A30604D5124A27 +:103EB000936A0BB1D06A9847600604D50E4A136B1B +:103EC0000BB1506B9847210604D50B4A936B0BB18D +:103ED000D06B9847E20504D5074A136C0BB1506CC0 +:103EE0009847A30504D5044A936C0BB1D06C98474E +:103EF000BDE81040FEF756BD7C4600204FF0B043B1 +:103F000010B5D3F8884004F47C42C3F888206205D9 +:103F100004D5164A136D0BB1506D9847230504D58F +:103F2000124A936D0BB1D06D9847E00404D50F4A47 +:103F3000136E0BB1506E9847A10404D50B4A936ED3 +:103F40000BB1D06E9847620404D5084A136F0BB1C9 +:103F5000506F9847230404D5044A936F0BB1D06F78 +:103F60009847BDE81040FEF71DBD00BF7C4600200D +:103F700008B50348FDF70AF9BDE80840FEF712BD91 +:103F8000CC23002008B5FFF7ABFDBDE80840FEF7E5 +:103F900009BD0000062108B50846FFF7BBFA062157 +:103FA0000720FFF7B7FA06210820FFF7B3FA06212A +:103FB0000920FFF7AFFA06210A20FFF7ABFA062126 +:103FC0001720FFF7A7FA06212820FFF7A3FA0921F7 +:103FD0007A20FFF79FFA07213220FFF79BFA0C2186 +:103FE0002520BDE80840FFF795BA000008B5FFF7A7 +:103FF0008DFD00F00DF8FDF7DBFAFDF7B3FCFDF7E2 +:1040000085FBFFF741FDBDE80840FFF763BC0000FA +:104010000023054A19460133102BC2E9001102F1B1 +:104020000802F8D1704700BF7C46002010B5013966 +:104030000244904201D1002005E0037811F8014FBD +:10404000A34201D0181B10BD0130F2E7034611F85E +:10405000012B03F8012B002AF9D1704753544D333B +:104060003248373F3F3F0053544D333248373433A3 +:104070002F37353300000000F0290020CC2300202A +:10408000009600000000000000000000000000009A +:10409000000000000000000000000000791500088A +:1040A00065150008A11500088D1500089915000870 +:1040B00085150008711500085D150008AD1500088C +:1040C000000000008916000875160008B1160008E7 +:1040D0009D160008A916000895160008811600080C +:1040E0006D160008BD160008000000000100000069 +:1040F000000000006D61696E0000000069646C657D +:1041000000000000FC40000878280020F029002072 +:1041100001000000012000080000000041726475E9 +:1041200050696C6F740025424F415244252D424C1A +:10413000002553455249414C250000000200000073 +:1041400000000000A91800081919000840004000EC +:1041500098420020A8420020020000000000000059 +:1041600003000000000000006119000800000000CA +:1041700010000000B8420020000000000100000014 +:10418000000000002C45002001010200F12300087E +:10419000012300089D23000881230008430000003C +:1041A000A441000809024300020100C032090400D2 +:1041B0000001020201000524001001052401000194 +:1041C000042402020524060001070582030800FFFB +:1041D00009040100020A0000000705010240000076 +:1041E000070581024000000012000000F0410008B5 +:1041F00012011001020000400912415700020102A1 +:10420000030100000403090425424F4152442500E4 +:104210004265617374483700303132333435363794 +:104220003839414243444546000000000000000088 +:10423000B51A00086D1D0008191E00084000400056 +:1042400064460020644600200100000074460020FF +:104250008000000040010000080000000001000094 +:1042600000040000080000000001A86A000000002F +:10427000AAAAAAAA00011464FFFF0000000000001F +:1042800070A70A000000000000000000AAAAAAAA65 +:1042900000000000FFFF0000000000000000000020 +:1042A0000000000400000000AAAAAAAA0000000062 +:1042B000FFDF000000000000000000000000000020 +:1042C00000000000AAAAAAAA00000000FFFF000048 +:1042D00000000000000000000001000000000000DD +:1042E000AAAAAAAA00010000FFFF00000000000027 +:1042F000000000000000000000000000AAAAAAAA16 +:1043000000000000FFFF00000000000000000000AF +:104310000000000000000000AAAAAAAA00000000F5 +:10432000FFFF00000000000000000000000000008F +:1043300000000000AAAAAAAA00000000FFFF0000D7 +:10434000000000000000000000000000000000006D +:10435000AAAAAAAA00000000FFFF000000000000B7 +:10436000000000000000000000000000AAAAAAAAA5 +:1043700000000000FFFF000000000000000000003F +:104380000000000000000000AAAAAAAA0000000085 +:10439000FFFF00000000000000000000000000001F +:1043A000010400000000000000001A0000000000EE +:1043B000FF000000000000005C4000083F0000001B +:1043C00050040000674000083F0000000096000015 +:1043D0000000080096000000000800000400000033 +:1043E000044200080000000000000000000000007F +:0C43F000000000000000000000000000C1 :00000001FF diff --git a/Tools/bootloaders/BeastH7v2_bl.bin b/Tools/bootloaders/BeastH7v2_bl.bin new file mode 100755 index 00000000000..534dd4f85c7 Binary files /dev/null and b/Tools/bootloaders/BeastH7v2_bl.bin differ diff --git a/Tools/bootloaders/BeastH7v2_bl.hex b/Tools/bootloaders/BeastH7v2_bl.hex new file mode 100644 index 00000000000..b4515e95f9a --- /dev/null +++ b/Tools/bootloaders/BeastH7v2_bl.hex @@ -0,0 +1,1081 @@ +:020000040800F2 +:1000000000060020A10200082D100008AD0F000816 +:1000100005100008AD0F0008D90F0008A302000862 +:10002000A3020008A3020008A3020008BD280008DC +:10003000A3020008A3020008A3020008A30200080C +:10004000A3020008A3020008A3020008A3020008FC +:10005000A3020008A30200082D3D0008593D000836 +:10006000853D0008B13D0008DD3D0008A302000801 +:10007000A3020008A3020008A3020008A3020008CC +:10008000A3020008A3020008A3020008A3020008BC +:10009000A3020008A3020008A3020008093E00080A +:1000A000A3020008A3020008A3020008A30200089C +:1000B000A3020008A3020008A3020008A30200088C +:1000C000A3020008A3020008A3020008A30200087C +:1000D000A3020008E13E0008A3020008A3020008F2 +:1000E0006D3E0008A3020008A3020008A302000856 +:1000F000A3020008A3020008A3020008A30200084C +:10010000A3020008A3020008F53E0008A3020008AD +:10011000A3020008A3020008A3020008A30200082B +:10012000A3020008A3020008A3020008A30200081B +:10013000A3020008A3020008A3020008A30200080B +:10014000A3020008A3020008A3020008A3020008FB +:10015000A3020008A3020008A3020008A3020008EB +:10016000A3020008A3020008A3020008A3020008DB +:10017000A302000829340008A3020008A302000813 +:10018000A3020008A3020008A3020008A3020008BB +:10019000A3020008A3020008A3020008A3020008AB +:1001A000A3020008A3020008A3020008A30200089B +:1001B000A3020008A3020008A3020008A30200088B +:1001C000A3020008A3020008A3020008A30200087B +:1001D000A302000815340008A3020008A3020008C7 +:1001E000A3020008A3020008A3020008A30200085B +:1001F000A3020008A3020008A3020008A30200084B +:10020000A3020008A3020008A3020008A30200083A +:10021000A3020008A3020008A3020008A30200082A +:10022000A3020008A3020008A3020008A30200081A +:10023000A3020008A3020008A3020008A30200080A +:10024000A3020008A3020008A3020008A3020008FA +:10025000A3020008A3020008A3020008A3020008EA +:10026000A3020008A3020008A3020008A3020008DA +:10027000A3020008A3020008A3020008A3020008CA +:10028000A3020008A3020008A3020008A3020008BA +:10029000A3020008A3020008A3020008A3020008AA +:1002A00002E000F000F8FEE772B63A4880F30888F2 +:1002B000394880F3098839484EF60851CEF20001DA +:1002C000086040F20000CCF200004EF63471CEF22D +:1002D00000010860BFF34F8FBFF36F8F40F2000043 +:1002E000C0F2F0004EF68851CEF200010860BFF374 +:1002F0004F8FBFF36F8F4FF00000E1EE100A4EF604 +:100300003C71CEF200010860062080F31488BFF330 +:100310006F8F02F091FB02F033FB03F0CDFA4FF048 +:1003200055301F491B4A91423CBF41F8040BFAE784 +:100330001C49194A91423CBF41F8040BFAE71A499B +:100340001A4A1B4B9A423EBF51F8040B42F8040B69 +:10035000F8E700201749184A91423CBF41F8040BC6 +:10036000FAE702F04BFB03F01FFB144C144DAC42B8 +:1003700003DA54F8041B8847F9E700F041F8114C00 +:10038000114DAC4203DA54F8041B8847F9E702F038 +:1003900033BB0000000600200022002000000008FF +:1003A000000000200006002010430008002200206A +:1003B0005C22002060220020FC460020A0020008F1 +:1003C000A0020008A0020008A00200082DE9F04FDA +:1003D0002DED108AC1F80CD0D0F80CD0BDEC108AED +:1003E000BDE8F08F002383F311882846A047002042 +:1003F00001F056FEFEE701F0EBFD00DFFEE7000036 +:1004000038B500F0DDFC30B1164B00220E211A7217 +:100410005A729972DA7202F011FA054602F044FA41 +:100420000446D0B9104B9D4219D001339D4241F290 +:10043000883512BF044600250124002002F008FA86 +:100440000CB100F059F800F057FD00F0FFFB284612 +:1004500000F004F900F050F8F9E70025EDE7054653 +:10046000EBE700BF00220020010007B008B500F054 +:10047000B9FBA0F120035842584108BD07B541F22D +:100480001203022101A8ADF8043000F0C9FB03B04B +:100490005DF804FB202310B583F311881248C3686C +:1004A0000BB101F083FE0023104A4FF47A710E481D +:1004B00001F040FE002383F311880D4C236813B133 +:1004C0002368013B2360636813B16368013B636089 +:1004D000084B1B7833B9636823B9022000F086FC0F +:1004E0003223636010BD00BF602200209504000825 +:1004F0007C23002074220020F8B5514B514A1C4641 +:100500001968013100F09B8004339342F8D162688E +:100510004D4B9A4240F293804C4B9B6803F1006331 +:1005200003F500339A4280F08A80002000F0A8FB97 +:100530000220474B187000F04FFC464B0021D3F8C7 +:10054000E820C3F8E810D3F81021C3F81011D3F84D +:100550001021D3F8EC20C3F8EC10D3F81421C3F821 +:100560001411D3F81421D3F8F020C3F8F010D3F805 +:100570001821C3F81811D3F81821D3F8802042F0BD +:100580000062C3F88020D3F8802022F00062C3F814 +:100590008020D3F88020D3F8802042F00072C3F886 +:1005A0008020D3F8802022F00072C3F88020D3F896 +:1005B000803072B64FF0E023C3F8084DD4E9000450 +:1005C000BFF34F8FBFF36F8F234AC2F88410BFF37E +:1005D0004F8F536923F480335361BFF34F8FD2F8A9 +:1005E000803043F6E076C3F3C905C3F34E335B01B5 +:1005F00003EA060C29464CEA81770139C2F8747285 +:10060000F9D2203B13F1200FF2D1BFF34F8FBFF38C +:100610006F8FBFF34F8FBFF36F8F536923F4003396 +:1006200053610023C2F85032BFF34F8FBFF36F8F77 +:10063000202383F31188854680F308882047F8BD7E +:100640000000020820000208FFFF0108002200202D +:10065000742200200044025800ED00E02DE9F04F24 +:1006600093B0A94B2022FF2100900AA89D6800F0BA +:10067000EDFBA64A1378A3B90121A5481170C36008 +:10068000202383F31188C3680BB101F08FFD002391 +:10069000A04A4FF47A719E4801F04CFD002383F389 +:1006A0001188009B9C4A03B1136000239B49009C66 +:1006B00098469B461E469A460B705360012000F0F8 +:1006C0008BFB24B1944B1B68002B00F0168200209A +:1006D00000F088FA0390039B002BF2DB012000F06E +:1006E00071FB039B213B162BE8D801A252F823F0A3 +:1006F0004D0700087507000809080008BD06000836 +:10070000BD060008BD0600089D0800086F0A000825 +:1007100089090008EB090008130A0008390A0008D3 +:10072000BD0600084B0A0008BD060008BD0A000807 +:10073000ED070008BD060008010B00085907000876 +:10074000ED070008BD060008EB0900080220FFF7CE +:100750008DFE002840F0FB81009B022105A8B8F126 +:10076000000F08BF1C4641F21233ADF8143000F000 +:1007700057FAA3E74FF47A7000F034FA071EEBDB68 +:100780000220FFF773FE0028E6D0013F052F00F29C +:10079000E081DFE807F0030A0D101336052304217A +:1007A00005A8059300F03CFA17E004215648F9E744 +:1007B00004215B48F6E704215A48F3E74FF01C098F +:1007C000484609F1040900F05DFA0421059005A8E6 +:1007D00000F026FAB9F12C0FF2D101204FF0000AF7 +:1007E00000FA07F747EA0B0B5FFA8BFB00F07AFB86 +:1007F00026B10BF00B030B2B08BF0024FFF73EFEC6 +:100800005CE704214848CDE7002EA5D00BF00B0390 +:100810000B2BA1D10220FFF729FE074600289BD011 +:1008200001203E4E00F02CFA4FF0000802203070FC +:1008300000F0D2FA5FFA88F9484600F031FA04462F +:1008400090B1484608F1010800F03AFA0028F1D1C9 +:10085000B846044641F21213022105A83E46ADF8FF +:10086000143000F0DDF929E701232546022033701A +:1008700000F0A8FA244B9B68AB4207D9284600F049 +:1008800001FA013040F068810435F3E70025234B7D +:10089000B8463E461D70204B5D60A7E7002E3FF432 +:1008A0005BAF0BF00B030B2B7FF456AF02201B4BFF +:1008B000187000F091FA322000F094F9B0F10009BC +:1008C000FFF64AAF19F003077FF446AF0E4A09EB73 +:1008D0000503926893423FF63FAFB9F5807F3FF73B +:1008E0003BAF124BB945019322DD4FF47A7000F013 +:1008F00079F90390039A002AFFF62EAF039A013785 +:10090000019B03F8012BEDE7002200207823002053 +:1009100060220020950400087C230020742200201F +:1009200004220020082200200C220020782200202F +:10093000C820FFF79BFD074600283FF40DAF1F2D91 +:1009400011D8C5F120020AAB25F0030084494A45BD +:10095000184428BF4A46019200F052FA019AFF213A +:100960007F4800F073FA4FEAA903C9F387027C4974 +:100970002846019300F072FA064600283FF46AAF59 +:10098000019B05EB830531E70220FFF76FFD00288F +:100990003FF4E2AE00F0B0F900283FF4DDAE0027EE +:1009A000B946704B9B68BB4218D91F2F11D80A9BC0 +:1009B00001330ED027F0030312AA134453F8203C4E +:1009C00005934846042205A9043700F031FB81460F +:1009D000E7E7384600F056F90590F2E7CDF81490B5 +:1009E000042105A800F01CF900E70023642104A8F5 +:1009F000049300F00BF900287FF4AEAE0220FFF75D +:100A000035FD00283FF4A8AE049800F06BF905907E +:100A1000E6E70023642104A8049300F0F7F8002817 +:100A20007FF49AAE0220FFF721FD00283FF494AE38 +:100A3000049800F059F9EAE70220FFF717FD0028B3 +:100A40003FF48AAE00F068F9E1E70220FFF70EFDFF +:100A500000283FF481AE05A9142000F063F9074691 +:100A60000421049004A800F0DBF83946B9E73220ED +:100A700000F0B8F8071EFFF66FAEBB077FF46CAE50 +:100A8000384A07EB0A03926893423FF665AE0220AC +:100A9000FFF7ECFC00283FF45FAE27F00307574454 +:100AA000BA453FF4A3AE50460AF1040A00F0EAF852 +:100AB0000421059005A800F0B3F8F1E74FF47A702F +:100AC000FFF7D4FC00283FF447AE00F015F90028EA +:100AD00044D00A9B01330BD008220AA9002000F061 +:100AE000BDF900283AD02022FF210AA800F0AEF973 +:100AF000FFF7C4FC1C4801F0D9FA13B0BDE8F08F31 +:100B0000002E3FF429AE0BF00B030B2B7FF424AE29 +:100B10000023642105A8059300F078F80746002813 +:100B20007FF41AAE0220FFF7A1FC814600283FF4B3 +:100B300013AEFFF7A3FC41F2883001F0B7FA059835 +:100B400000F014FA4E463C4600F0CCF9B6E50646F5 +:100B50004CE64FF0000AFFE5B8467BE6374679E6FB +:100B60007822002000220020A0860100F7B50C4664 +:100B7000184E4FF47A71054602FB01F396F90020F6 +:100B8000501C0BD11448294601930268176A22466B +:100B9000B8478442019B03D1002310E0002AF1D022 +:100BA00096F90020511C01D0012A0DD10B4829468D +:100BB0000268166A2246B047844205D10123084ADA +:100BC0000120137003B0F0BD4FF4FA7001F06EFA1B +:100BD0000020F7E710220020F0290020CC2300207D +:100BE000C8230020002307B5024601210DF10700AC +:100BF0008DF80730FFF7BAFF20B19DF8070003B06A +:100C00005DF804FB4FF0FF30F9E700000A460421CD +:100C100008B5FFF7ABFF80F00100C0B2404208BD4D +:100C2000074B0A4630B41978064B53F82140014669 +:100C300023682046DD69044BAC4630BC604700BFEA +:100C4000C8230020E83F0008A086010070B50A4EC6 +:100C500000240A4D01F0D8FC308028683388834294 +:100C600008D901F0CDFC2B6804440133B4F5003FF2 +:100C70002B60F2D370BD00BFCA2300208423002064 +:100C800001F092BD00F1006000F50030006870478F +:100C900000F10060920000F5003001F011BD00008D +:100CA000054B1A68054B1B889B1A834202D91044D6 +:100CB00001F0A6BC0020704784230020CA23002036 +:100CC00038B5074D04462868204401F09FFC28B938 +:100CD00028682044BDE8384001F0AABC38BD00BFF8 +:100CE000842300200020704700F1FF5000F58F1092 +:100CF000D0F8000870470000064991F8243033B15D +:100D000000230822086A81F82430FFF7C1BF0120C0 +:100D1000704700BF88230020014B1868704700BF50 +:100D20000010005C244BF0B51A680446234BC2F354 +:100D30000B06120C1F885868BE4293F9085028D041 +:100D40009F89BE4206D101200C2505FB003358685F +:100D500093F9085041F201039A421CD041F2030377 +:100D60009A421AD042F201039A4218D042F2030387 +:100D70009A4208BF5625621E0B46441E0A449342FF +:100D80000FD214F9016F581C6EB1034600F8016CC4 +:100D9000F5E70020D8E75A25EDE75925EBE7582578 +:100DA000E9E7184605E02C2482421C7001D9981C02 +:100DB0005D70401AF0BD00BF0010005C14220020DE +:100DC00000207047022803D1024B4FF000529A6175 +:100DD000704700BF00080258022803D1024B4FF4AD +:100DE00000529A61704700BF00080258022804D1DF +:100DF000024A536983F40053536170470008025854 +:100E0000002310B5934203D0CC5CC4540133F9E7FE +:100E100010BD0000013810B510F9013F3BB191F948 +:100E200000409C4203D11AB10131013AF4E71AB1F2 +:100E300091F90020981A10BD1046FCE703460246BF +:100E4000D01A12F9011B0029FAD170470244034657 +:100E5000934202D003F8011BFAE770472DE9F843EB +:100E60001F4D14460746884695F8242052BBDFF8EC +:100E700070909CB395F824302BB92022FF2148466E +:100E80002F62FFF7E3FF95F824004146C0F1080206 +:100E900005EB8000A24228BF2246D6B29200FFF79F +:100EA000AFFF95F82430A41B17441E449044E4B2CD +:100EB000F6B2082E85F82460DBD1FFF71DFF00286D +:100EC000D7D108E02B6A03EB82038342CFD0FFF730 +:100ED00013FF0028CBD10020BDE8F8830120FBE7F9 +:100EE00088230020024B1A78024B1A70704700BF0B +:100EF000C82300201022002038B5164C164D20467D +:100F000000F0FAFB2946204600F022FC2D68134829 +:100F1000D5F89020D2F8043843F00203C2F8043820 +:100F200001F0C4F80E49284600F020FDD5F89020C5 +:100F30000C48D2F804380C49A04223F00203C2F84E +:100F400004384FF4E1330B6003D0BDE8384000F0C3 +:100F500031BB38BDF0290020F440000840420F00AA +:100F6000FC400008CC230020B023002038B50B4BF8 +:100F700004461A780A4B53F822500A4B9D420CD073 +:100F8000094B002118221846FFF760FF0460014654 +:100F90002846BDE8384000F00DBB38BDC82300200E +:100FA000E83F0008F0290020B023002000B59BB0E6 +:100FB000EFF3098168226846FFF722FFEFF305830C +:100FC000044B9A6BDA6A9A6A9A6A9A6A9A6A9A6A75 +:100FD0009B6AFEE700ED00E000B59BB0EFF30981EE +:100FE00068226846FFF70CFFEFF30583044B9A6B0A +:100FF0009A6A9A6A9A6A9A6A9A6A9B6AFEE700BF34 +:1010000000ED00E000B59BB0EFF30981682268466F +:10101000FFF7F6FEEFF30583034B5A6B9A6A9A6A61 +:101020009A6A9A6A9B6AFEE700ED00E0FEE700001C +:1010300030B50A44084D91420DD011F8013B58409B +:10104000082340F30004013B2C4013F0FF0384EA23 +:101050005000F6D1EFE730BD2083B8ED0268436859 +:101060001143016003B1184770470000024A13683A +:1010700043F0C003136070470010014013B50E4CDD +:10108000204600F08BFA04F1140000234FF40072A4 +:101090000A49009400F04CF9094B4FF400720949D9 +:1010A00004F13800009400F0C5F9074A074BC4E981 +:1010B000172302B010BD00BFCC230020382400202D +:1010C0006D100008382600200010014000E1F505F1 +:1010D000037C30B5244C002918BF0C46012B11D1DC +:1010E000224B98420ED1224BD3F8F02042F010024E +:1010F000C3F8F020D3F8182142F01002C3F81821E9 +:10110000D3F818312268036EC16D03EB5203846675 +:10111000B3FBF2F36268150442BF23F0070503F046 +:10112000070343EA4503CB60A36843F040034B60E9 +:10113000E36843F001038B6042F4967343F00103CC +:101140000B604FF0FF330B62510505D512F01022F2 +:1011500005D0B2F1805F04D080F8643030BD7F23C9 +:10116000FAE73F23F8E700BFF03F0008CC23002058 +:10117000004402582DE9F047C66D05463768F4690A +:101180002107346219D014F0080118BF8021E2074A +:1011900048BF41F02001A3074FF0200348BF41F0B2 +:1011A0004001600748BF41F4807183F31188281D16 +:1011B000FFF754FF002383F31188E2050AD52023AB +:1011C00083F311884FF40071281DFFF747FF0023B8 +:1011D00083F311884FF020094FF0000A14F0200823 +:1011E00038D13B0616D54FF0200905F1380A200604 +:1011F00010D589F31188504600F050F9002836DAEE +:101200000821281DFFF72AFF27F080033360002301 +:1012100083F31188790614D5620612D5202383F34F +:101220001188D5E913239A4208D12B6C33B127F0EA +:1012300040071021281DFFF711FF3760002383F3BB +:101240001188E30618D5AA6E1369ABB15069BDE8E1 +:10125000F047184789F31188736A284695F8641097 +:10126000194000F0B5F98AF31188F469B6E7B06265 +:1012700088F31188F469BAE7BDE8F087F8B5154638 +:10128000826804460B46AA4200D28568A169266995 +:10129000761AB5420BD218462A46FFF7B1FDA3696C +:1012A0002B44A3612846A3685B1BA360F8BD0CD93F +:1012B000AF1B18463246FFF7A3FD3A46E1683044BB +:1012C000FFF79EFDE3683B44EBE718462A46FFF72D +:1012D00097FDE368E5E7000083689342F7B50446AD +:1012E000154600D28568D4E90460361AB5420BD29F +:1012F0002A46FFF785FD63692B4463612846A3688E +:101300005B1BA36003B0F0BD0DD93246AF1B01914A +:10131000FFF776FD01993A46E0683144FFF770FD2A +:10132000E3683B44E9E72A46FFF76AFDE368E4E740 +:1013300010B50A440024C361029B8460C16002614D +:101340000362C0E90000C0E9051110BD08B5D0E98D +:101350000532934201D1826882B98268013282608B +:101360005A1C426119700021D0E904329A4224BF0C +:10137000C368436100F0B6FE002008BD4FF0FF30A7 +:10138000FBE7000070B5202304460E4683F3118866 +:10139000A568A5B1A368A269013BA360531CA36122 +:1013A00015782269934224BFE368A361E3690BB116 +:1013B00020469847002383F31188284607E03146EA +:1013C000204600F07FFE0028E2DA85F3118870BD28 +:1013D0002DE9F74F04460E4617469846D0F81C9064 +:1013E0004FF0200A8AF311884FF0000B154665B1C3 +:1013F0002A4631462046FFF741FF034660B9414681 +:10140000204600F05FFE0028F1D0002383F311880E +:10141000781B03B0BDE8F08FB9F1000F03D0019045 +:101420002046C847019B8BF31188ED1A1E448AF3AE +:101430001188DCE7C160C361009B82600362C0E980 +:1014400005111144C0E9000001617047F8B5044678 +:101450000D461646202383F31188A768A7B1A36819 +:10146000013BA36063695A1C62611D70D4E90432B8 +:101470009A4224BFE3686361E3690BB12046984751 +:10148000002080F3118807E03146204600F01AFE64 +:101490000028E2DA87F31188F8BD0000D0E90523BF +:1014A00010B59A4201D182687AB98268002101326E +:1014B00082605A1C82611C7803699A4224BFC36807 +:1014C000836100F00FFE204610BD4FF0FF30FBE7B8 +:1014D0002DE9F74F04460E4617469846D0F81C9063 +:1014E0004FF0200A8AF311884FF0000B154665B1C2 +:1014F0002A4631462046FFF7EFFE034660B94146D3 +:10150000204600F0DFFD0028F1D0002383F311888E +:10151000781B03B0BDE8F08FB9F1000F03D0019044 +:101520002046C847019B8BF31188ED1A1E448AF3AD +:101530001188DCE7026843681143016003B1184772 +:10154000704700001430FFF743BF00004FF0FF3337 +:101550001430FFF73DBF00003830FFF7B9BF00007F +:101560004FF0FF333830FFF7B3BF00001430FFF700 +:1015700009BF00004FF0FF311430FFF703BF000038 +:101580003830FFF763BF00004FF0FF323830FFF70D +:101590005DBF000000207047FFF770BD044B036083 +:1015A00000234360C0E9023301230374704700BF86 +:1015B0000840000810B52023044683F31188FFF784 +:1015C00087FD02232374002383F3118810BD0000DC +:1015D00038B5C36904460D461BB904210844FFF71A +:1015E000A9FF294604F11400FFF7B0FE002806DA2F +:1015F000201D4FF48061BDE83840FFF79BBF38BD28 +:10160000026843681143016003B118477047000046 +:1016100013B5406B00F58054D4F8A4381A681178DB +:10162000042914D1017C022911D1197901231289CD +:101630008B4013420BD101A94C3002F03DF8D4F895 +:10164000A4480246019B2179206800F0DFF902B02E +:1016500010BD0000143001F0BFBF00004FF0FF3399 +:10166000143001F0B9BF00004C3002F091B8000016 +:101670004FF0FF334C3002F08BB80000143001F013 +:101680008DBF00004FF0FF31143001F087BF000024 +:101690004C3002F05DB800004FF0FF324C3002F0E9 +:1016A00057B800000020704710B500F58054D4F8FA +:1016B000A4381A681178042917D1017C022914D1A1 +:1016C0005979012352898B4013420ED1143001F015 +:1016D0001FFF024648B1D4F8A4484FF44073617923 +:1016E0002068BDE8104000F07FB910BD406BFFF7E7 +:1016F000DBBF0000704700007FB5124B01250426B8 +:10170000044603600023057400F184024360294607 +:10171000C0E902330C4B0290143001934FF4407334 +:10172000009601F0D1FE094B04F69442294604F1DB +:101730004C000294CDE900634FF4407301F098FF30 +:1017400004B070BD30400008ED1600081116000806 +:101750000A68202383F311880B790B3342F82300A6 +:101760004B79133342F823008B7913B10B3342F8D2 +:10177000230000F58053C3F8A41802230374002348 +:1017800083F311887047000038B5037F044613B116 +:1017900090F85430ABB90125201D0221FFF730FF2E +:1017A00004F114006FF00101257700F0A7FC04F1AB +:1017B0004C0084F854506FF00101BDE8384000F04F +:1017C0009DBC38BD10B5012104460430FFF718FF59 +:1017D0000023237784F8543010BD000038B5044648 +:1017E0000025143001F088FE04F14C00257701F04B +:1017F00057FF201D84F854500121FFF701FF2046B8 +:10180000BDE83840FFF750BF90F8803003F0600328 +:10181000202B06D190F881200023212A03D81F2AEB +:1018200006D800207047222AFBD1C0E91D3303E00F +:10183000034A426707228267C3670120704700BFDF +:101840002C22002037B500F58055D5F8A4381A6849 +:10185000117804291AD1017C022917D119790123A1 +:1018600012898B40134211D100F14C04204601F043 +:10187000D7FF58B101A9204601F01EFFD5F8A448B2 +:101880000246019B2179206800F0C0F803B030BD0A +:1018900001F10B03F0B550F8236085B004460D4606 +:1018A000FEB1202383F3118804EB8507301D082146 +:1018B000FFF7A6FEFB6806F14C005B691B681BB1D5 +:1018C000019001F007FF019803A901F0F5FE02461F +:1018D00048B1039B2946204600F098F8002383F383 +:1018E000118805B0F0BDFB685A691268002AF5D06E +:1018F0001B8A013B1340F1D104F18002EAE70000AA +:10190000133138B550F82140ECB1202383F311880E +:1019100004F58053D3F8A4281368527903EB8203AB +:10192000DB689B695D6845B104216018FFF768FEBC +:10193000294604F1140001F0F5FD2046FFF7B4FE3E +:10194000002383F3118838BD7047000001F0E8B828 +:1019500001234022002110B5044600F8303BFFF778 +:1019600075FA0023C4E9013310BD000010B520232F +:10197000044683F311882422416000210C30FFF7D4 +:1019800065FA204601F0EEF802232370002383F36A +:10199000118810BD70B500EB8103054650690E46F5 +:1019A0001446DA6018B110220021FFF74FFAA0693F +:1019B00018B110220021FFF749FA31462846BDE848 +:1019C000704001F0E1B9000083682022002103F09B +:1019D000011310B5044683601030FFF737FA204634 +:1019E000BDE8104001F05CBAF0B4012500EB8104C1 +:1019F00047898D40E4683D43A46945812360002305 +:101A0000A2606360F0BC01F079BA0000F0B4012577 +:101A100000EB810407898D40E4683D4364690581DA +:101A200023600023A2606360F0BC01F0EFBA000005 +:101A300070B5022300250446242203702946C0F80D +:101A400088500C3040F8045CFFF700FA204684F818 +:101A5000705001F02DF963681B6823B129462046B8 +:101A6000BDE87040184770BD037880F88C300523BE +:101A7000037043681B6810B504460BB104219847F6 +:101A80000023A36010BD000090F88C204368027012 +:101A90001B680BB1052118477047000070B590F81E +:101AA0007030044613B1002380F8703004F18002D6 +:101AB000204601F019FA63689B68B3B994F8803046 +:101AC00013F0600535D00021204601F0C3FC002151 +:101AD000204601F0B3FC63681B6813B10621204661 +:101AE0009847062384F8703070BD20469847002838 +:101AF000E4D0B4F88630A26F9A4288BFA36794F905 +:101B00008030A56F002B4FF0200380F20381002D61 +:101B100000F0F280092284F8702083F311880021FC +:101B20002046D4E91D23FFF771FF002383F31188BA +:101B3000DAE794F8812003F07F0343EA022340F2BE +:101B40000232934200F0C58021D8B3F5807F48D09F +:101B50000DD8012B3FD0022B00F09380002BB2D187 +:101B600004F1880262670222A267E367C1E7B3F566 +:101B7000817F00F09B80B3F5407FA4D194F8823040 +:101B8000012BA0D1B4F8883043F0020332E0B3F562 +:101B9000006F4DD017D8B3F5A06F31D0A3F5C06357 +:101BA000012B90D86368204694F882205E6894F8F0 +:101BB0008310B4F88430B047002884D0436863674A +:101BC0000368A3671AE0B3F5106F36D040F60242FF +:101BD00093427FF478AF5C4B63670223A3670023D3 +:101BE000C3E794F88230012B7FF46DAFB4F88830EE +:101BF00023F00203A4F88830C4E91D55E56778E7AF +:101C0000B4F88030B3F5A06F0ED194F8823020463E +:101C100084F88A3001F0AAF863681B6813B10121C7 +:101C200020469847032323700023C4E91D339CE713 +:101C300004F18B0363670123C3E72378042B10D1DE +:101C4000202383F311882046FFF7BEFE85F3118819 +:101C50000321636884F88B5021701B680BB1204608 +:101C6000984794F88230002BDED084F88B30042320 +:101C7000237063681B68002BD6D00221204698474A +:101C8000D2E794F8843020461D0603F00F010AD5F0 +:101C900001F01CF9012804D002287FF414AF2B4B6B +:101CA0009AE72B4B98E701F003F9F3E794F88230B9 +:101CB000002B7FF408AF94F8843013F00F01B3D0F9 +:101CC0001A06204602D501F0DDFBADE701F0CEFBA0 +:101CD000AAE794F88230002B7FF4F5AE94F88430B4 +:101CE00013F00F01A0D01B06204602D501F0B2FB75 +:101CF0009AE701F0A3FB97E7142284F8702083F39E +:101D000011882B462A4629462046FFF76DFE85F3AB +:101D10001188E9E65DB1152284F8702083F31188FB +:101D200000212046D4E91D23FFF75EFEFDE60B22CD +:101D300084F8702083F311882B462A4629462046D2 +:101D4000FFF764FEE3E700BF60400008584000086A +:101D50005C40000838B590F870300446002B3ED047 +:101D6000063BDAB20F2A34D80F2B32D8DFE803F063 +:101D70003731310822323131313131313131373778 +:101D8000856FB0F886309D4214D2C3681B8AB5FBBC +:101D9000F3F203FB12556DB9202383F311882B4610 +:101DA0002A462946FFF732FE85F311880A2384F874 +:101DB00070300EE0142384F87030202383F31188F0 +:101DC000002320461A461946FFF70EFE002383F330 +:101DD000118838BDC36F03B198470023E7E700219E +:101DE000204601F037FB0021204601F027FB636805 +:101DF0001B6813B10621204698470623D7E7000049 +:101E000010B590F870300446142B29D017D8062B43 +:101E100005D001D81BB110BD093B022BFBD8002116 +:101E2000204601F017FB0021204601F007FB636804 +:101E30001B6813B1062120469847062319E0152B8D +:101E4000E9D10B2380F87030202383F3118800231D +:101E50001A461946FFF7DAFD002383F31188DAE703 +:101E6000C3689B695B68002BD5D1C36F03B19847EA +:101E7000002384F87030CEE7024B0022C3E9003320 +:101E80009A60704738280020002382680374054B4D +:101E90001B6899689142FBD25A68036042601060E7 +:101EA000586070473828002008B5202383F3118834 +:101EB000037C032B05D0042B0DD02BB983F31188A1 +:101EC00008BD436900221A604FF0FF334361FFF7FA +:101ED000DBFF0023F2E7D0E9003213605A60F3E73A +:101EE000002382680374054B1B6899689142FBD8F4 +:101EF0005A680360426010605860704738280020BC +:101F0000054B196908741868026853601A601861F3 +:101F100001230374FEF75ABA382800204B1C30B551 +:101F2000044687B00A4D10D02B6901A8094A00F079 +:101F300001F92046FFF7E4FF049B13B101A800F06C +:101F400035F92B69586907B030BDFFF7D9FFF8E7BD +:101F500038280020A91E000838B50C4D0446416100 +:101F60002B6981689A68914203D8BDE83840FFF731 +:101F70008BBF1846FFF7B4FF01232C610146237481 +:101F80002046BDE83840FEF721BA00BF38280020BF +:101F9000044B1A681B6990689B68984294BF0020A4 +:101FA000012070473828002010B5084C23682069AC +:101FB0001A6854602260012223611A74FFF790FFAF +:101FC00001462069BDE81040FEF700BA382800201D +:101FD000FFF7EABFFEE7000010B50C4CFFF74CFF1F +:101FE00000F09AF880220A49204600F021F80123E7 +:101FF00044F8180C037400F071FC002383F311887B +:1020000062B60448BDE8104000F032B860280020F5 +:10201000644000087440000800F002B9034A5168A7 +:1020200053685B1A9842FBD8704700BF001000E06D +:1020300082600222028270478368A3F17C0243F827 +:102040000C2C026943F83C2C426943F8382C074AAF +:1020500043F81C2CC268A3F1180043F8102C02228C +:1020600003F8082C002203F8072C7047E50300084A +:1020700010B5202383F31188FFF7DEFF002104460B +:10208000FFF76AFF002383F31188204610BD00008C +:10209000024B1B6958610F20FFF732BF3828002020 +:1020A000202383F31188FFF7F3BF000008B5014632 +:1020B000202383F311880820FFF730FF002383F3E8 +:1020C000118808BD49B1064B42681B6918605A6007 +:1020D000136043600420FFF721BF4FF0FF307047CB +:1020E000382800200368984206D01A6802605060C1 +:1020F00018465961FFF7C8BE7047000038B504465E +:102100000D462068844200D138BD036823605C60BE +:102110004561FFF7B9FEF4E7054B4FF0FF3103F1DE +:102120001402C3E905220022C3E90712704700BF69 +:102130003828002070B51C4E05460C46C0E9032324 +:1021400001F0A4FB334653F8142F9A420DD13062AC +:102150000A2C2CBF00190A302A60C5E90124C6E9FF +:102160000555BDE8704001F07BBB316A431AE318A6 +:1021700038BF1C469368A34202D9081901F080FBBE +:1021800073699A6894420CD85A68AC602B606A6094 +:1021900015609A685D60121B9A604FF0FF33F3611F +:1021A00070BDA41A1B68ECE73828002038B51B4C1A +:1021B000636998420DD08168D0E9003213605A609B +:1021C0000022C2609A680A449A604FF0FF33E361CC +:1021D00038BD03682246002142F8143F93425A60FA +:1021E000C16003D1BDE8384001F044BB9A68816802 +:1021F000256A0A449A6001F049FB6369411B9A68A9 +:102200008A42E5D9AB181D1A206A092D98BF01F141 +:102210000A02BDE83840104401F032BB38280020E3 +:102220002DE9F041184C002704F11406656901F00E +:102230002DFB236AAA68C11A8A4215D81344D5F81F +:102240000C802362D5E9003213605A606369EF6045 +:10225000B34201D101F00EFB87F311882869C04712 +:10226000202383F31188E1E76169B14209D0134467 +:102270001B1ABDE8F0410A2B2CBFC0180A3001F030 +:10228000FFBABDE8F08100BF382800200020704769 +:10229000FEE70000704700004FF0FF30704700007D +:1022A00002290CD0032904D00129074818BF0020B7 +:1022B0007047032A05D8054800EBC2007047044860 +:1022C00070470020704700BF584100083C220020A2 +:1022D0000C41000870B59AB005460846144601A99D +:1022E00000F0C2F801A8FEF7A9FD431C0022C6B207 +:1022F0005B001046C5E9003423700323023404F860 +:10230000013C01ABD1B202348E4201D81AB070BD8B +:1023100013F8011B013204F8010C04F8021CF1E768 +:1023200008B5202383F311880348FFF78BFA0023B5 +:1023300083F3118808BD00BFF029002090F8803099 +:1023400003F01F02012A07D190F881200B2A03D144 +:102350000023C0E91D3315E003F06003202B08D1F2 +:10236000B0F884302BB990F88120212A03D81F2A95 +:1023700004D8FFF749BA222AEBD0FAE7034A4267AA +:1023800007228267C3670120704700BF3322002005 +:1023900007B5052917D8DFE801F019160319192028 +:1023A000202383F31188104A01210190FFF7F2FAEC +:1023B000019802210D4AFFF7EDFA0D48FFF70EFADA +:1023C000002383F3118803B05DF804FB202383F31B +:1023D00011880748FFF7D8F9F2E7202383F3118823 +:1023E0000348FFF7EFF9EBE7AC400008D0400008E6 +:1023F000F029002038B50C4D0C4C2A460C4904F14C +:102400000800FFF767FF05F1CA0204F1100009494F +:10241000FFF760FF05F5CA7204F118000649BDE830 +:102420003840FFF757BF00BFC84200203C220020C1 +:102430008C40000896400008A140000870B5044692 +:1024400008460D46FEF7FAFCC6B220460134037872 +:102450000BB9184670BD32462946FEF7DBFC002852 +:10246000F3D10120F6E700002DE9F84F05460C46B0 +:10247000FEF7E4FC2C49C6B22846FFF7DFFF08B19F +:102480000236F6B229492846FFF7D8FF08B11036C0 +:10249000F6B2632E0DD8DFF89080DFF89090244FCD +:1024A000DFF894A0DFF894B02E7846B92670BDE826 +:1024B000F88F29462046BDE8F84F01F07FBD252E54 +:1024C0002ED1072241462846FEF7A4FC70B9DBF85E +:1024D00000300735093444F8093CDBF8043044F88F +:1024E000053C9BF8083004F8013CDDE7082249462A +:1024F0002846FEF78FFC98B9A21C0E4B19780232C1 +:102500000909C95D02F8041C13F8011B01F00F0151 +:102510005345C95D02F8031CF0D118340835C3E7F0 +:10252000013504F8016BBFE778410008A1400008BD +:102530008A41000800E8F11F0CE8F11F8041000803 +:10254000BFF34F8F044B1A695107FCD1D3F8102108 +:102550005207F8D1704700BF0020005208B50D4B5C +:102560001B78ABB9FFF7ECFF0B4BDA68D10704D54A +:102570000A4A5A6002F188325A60D3F80C21D20715 +:1025800006D5064AC3F8042102F18832C3F80421B3 +:1025900008BD00BF264500200020005223016745EA +:1025A00008B5114B1B78F3B9104B1A69510703D5C5 +:1025B000DA6842F04002DA60D3F81021520705D5FC +:1025C000D3F80C2142F04002C3F80C21FFF7B8FF0A +:1025D000064BDA6842F00102DA60D3F80C2142F0CF +:1025E0000102C3F80C2108BD26450020002000523E +:1025F0000F289ABF00F5806040040020704700005B +:102600004FF4003070470000102070470F2808B5C5 +:102610000BD8FFF7EDFF00F500330268013204D15B +:1026200004308342F9D1012008BD0020FCE70000FE +:102630000F2838B505463FD8FFF782FF1F4CFFF73C +:102640008DFF4FF0FF3307286361C4F814311DD8A4 +:102650002361FFF775FF030243F02403E360E3689F +:1026600043F08003E36023695A07FCD42846FFF750 +:1026700067FFFFF7BDFF4FF4003100F0F7F8284681 +:10268000FFF78EFFBDE83840FFF7C0BFC4F8103138 +:10269000FFF756FFA0F108031B0243F02403C4F820 +:1026A0000C31D4F80C3143F08003C4F80C31D4F869 +:1026B00010315B07FBD4D9E7002038BD0020005261 +:1026C0002DE9F84F05460C46104645EA0203DB06A5 +:1026D0005DD122F003022B462A44934209D120F017 +:1026E0001F00DFF8BCB0DFF8BCA0FFF737FF2718EA +:1026F00044E0196801314AD10433EEE705F178432B +:1027000024492548B3F5801F244B38BF184603F1F0 +:10271000F80339BF8846D9469846D146FFF710FFDF +:102720004FF0FF33A5EB040C04F11C010360D8F853 +:10273000003043F00203C8F80030231FD9F80060CE +:1027400016F00506FAD153F8042F99424CF80320ED +:10275000F4D1BFF34F8FFFF7F3FE4FF0FF3320228A +:10276000214603602846D8F8003023F00203C8F859 +:10277000003001F013FC40B920352034BC42BDD1FB +:102780000120FFF70DFFBDE8F88F3046F9E7002084 +:10279000F9E700BF0C20005214210052142000520F +:1027A000102000521021005210B5084C237828B197 +:1027B0001BB9FFF7D3FE0123237010BD002BFCD003 +:1027C0002070BDE81040FFF7EBBE00BF264500209B +:1027D0000244074BD2B210B5904200D110BD441C48 +:1027E00000B253F8200041F8040BE0B2F4E700BF58 +:1027F000504000580E4B30B51C6F240405D41C6F9C +:102800001C671C6F44F400441C670A4C0244236894 +:10281000D2B243F480732360074B904200D130BDA5 +:10282000441C51F8045B00B243F82050E0B2F4E7D6 +:1028300000440258004802585040005807B5012291 +:1028400001A90020FFF7C4FF019803B05DF804FB65 +:1028500013B50446FFF7F2FFA04205D0012201A9FB +:1028600000200194FFF7C6FF02B010BD0144BFF382 +:102870004F8F064B884204D3BFF34F8FBFF36F8F48 +:102880007047C3F85C022030F4E700BF00ED00E0C1 +:10289000034B1A681AB9034AD2F8D0241A60704759 +:1028A000284500200040025808B5FFF7F1FF024B11 +:1028B0001868C0F3806008BD28450020EFF3098345 +:1028C000054968334A6B22F001024A6383F30988A1 +:1028D000002383F31188704700EF00E0202080F38D +:1028E000118862B60D4B0E4AD96821F4E0610904E3 +:1028F000090C0A430B49DA60D3F8FC2042F08072DD +:10290000C3F8FC20084AC2F8B01F116841F0010169 +:1029100011601022DA7783F82200704700ED00E0A2 +:102920000003FA0555CEACC5001000E0202310B519 +:1029300083F311880E4B5B6813F4006314D0F1EE3F +:10294000103AEFF309844FF08073683CE361094B60 +:10295000DB6B236684F30988FFF71AFB10B1064B83 +:10296000A36110BD054BFBE783F31188F9E700BFB6 +:1029700000ED00E000EF00E0F7030008FA030008B4 +:1029800070B5BFF34F8FBFF36F8F1A4A0021C2F8A3 +:102990005012BFF34F8FBFF36F8F536943F400336F +:1029A0005361BFF34F8FBFF36F8FC2F88410BFF333 +:1029B0004F8FD2F8803043F6E074C3F3C900C3F3FD +:1029C0004E335B0103EA0406014646EA817501398C +:1029D000C2F86052F9D2203B13F1200FF2D1BFF3BD +:1029E0004F8F536943F480335361BFF34F8FBFF36D +:1029F0006F8F70BD00ED00E0FEE700000A4B0B4852 +:102A00000B4A90420BD30B4BC11EDA1C121A22F058 +:102A100003028B4238BF00220021FEF717BA53F899 +:102A2000041B40F8041BECE76C430008FC46002044 +:102A3000FC460020FC4600207047000070B5D0E93D +:102A4000244300224FF0FF359E6804EB42135101EE +:102A5000D3F80009002805DAD3F8000940F08040D7 +:102A6000C3F80009D3F8000B002805DAD3F8000BEF +:102A700040F08040C3F8000B013263189642C3F85F +:102A80000859C3F8085BE0D24FF00113C4F81C38B2 +:102A900070BD000000EB8103D3F80CC02DE9F043BA +:102AA000DCF814204E1CD0F89050D2F800E005EB72 +:102AB000063605EB4118506870450AD30122D5F857 +:102AC000343802FA01F123EA0101C5F83418BDE8EF +:102AD000F083AEEB0003BCF81040A34228BF2346AE +:102AE000D8F81849A4B2B3EB840FF0D89468A4F1D5 +:102AF000040959F8047F3760A4EB09071F44042F29 +:102B0000F7D81C44034494605360D4E7890141F032 +:102B10002001016103699B06FCD41220FFF77EBAF5 +:102B200010B50A4C2046FEF713FF094BC4F890304D +:102B3000084BC4F89430084C2046FEF709FF074BB9 +:102B4000C4F89030064BC4F8943010BD2C450020DA +:102B500000000840C0410008C845002000000440B3 +:102B6000CC41000870B503780546012B5DD1494B77 +:102B7000D0F89040984259D1474B0E216520D3F8A8 +:102B8000D82042F00062C3F8D820D3F8002142F0E8 +:102B90000062C3F80021D3F80021D3F8802042F06E +:102BA0000062C3F88020D3F8802022F00062C3F8CE +:102BB0008020D3F8803000F071FC384BE360384B54 +:102BC000C4F800380023D5F89060C4F8003EC02354 +:102BD00023604FF40413A3633369002BFCDA012351 +:102BE0000C203361FFF71AFA3369DB07FCD412209B +:102BF000FFF714FA3369002BFCDA00262846A6609A +:102C0000FFF71CFF6B68C4F81068DB68C4F8146831 +:102C1000C4F81C68002B3AD1224BA3614FF0FF335C +:102C20006361A36843F00103A36070BD1E4B98422B +:102C3000C8D1194B0E214D20D3F8D82042F0007294 +:102C4000C3F8D820D3F8002142F00072C3F8002165 +:102C5000D3F80021D3F8802042F00072C3F880201E +:102C6000D3F8802022F00072C3F88020D3F88020AF +:102C7000D3F8D82022F08062C3F8D820D3F80021FE +:102C800022F08062C3F80021D3F8003193E7074BAC +:102C9000C3E700BF2C450020004402584014004008 +:102CA00003002002003C30C0C8450020083C30C072 +:102CB000F8B5D0F89040054600214FF00066204658 +:102CC000FFF724FFD5F8941000234FF001128F680E +:102CD0004FF0FF30C4F83438C4F81C2804EB43121A +:102CE00001339F42C2F80069C2F8006BC2F80809BC +:102CF000C2F8080BF2D20B68D5F89020C5F89830CE +:102D0000636210231361166916F01006FBD11220BE +:102D1000FFF784F9D4F8003823F4FE63C4F80038D0 +:102D2000A36943F4402343F01003A3610923C4F8CB +:102D30001038C4F814380B4BEB604FF0C043C4F8A4 +:102D4000103B094BC4F8003BC4F81069C4F80039C3 +:102D5000D5F8983003F1100243F48013C5F8982099 +:102D6000A362F8BD9C41000840800010D0F890207C +:102D700090F88A10D2F8003823F4FE6343EA011376 +:102D8000C2F80038704700002DE9F84300EB8103DA +:102D9000D0F890500C468046DA680FFA81F9480165 +:102DA000166806F00306731E022B05EB41134FF065 +:102DB000000194BFB604384EC3F8101B4FF0010158 +:102DC00004F1100398BF06F1805601FA03F39169EC +:102DD00098BF06F5004600293AD0578A04F15801F9 +:102DE000374349016F50D5F81C180B430021C5F833 +:102DF0001C382B180127C3F81019A7405369611E0E +:102E00009BB3138A928B9B08012A88BF5343D8F83F +:102E10009820981842EA034301F140022146C8F87D +:102E20009800284605EB82025360FFF76FFE08EB1F +:102E30008900C3681B8A43EA845348341E436401F3 +:102E40002E51D5F81C381F43C5F81C78BDE8F8830F +:102E500005EB4917D7F8001B21F40041C7F8001B08 +:102E6000D5F81C1821EA0303C0E704F13F030B4A1D +:102E70002846214605EB83035A60FFF747FE05EB22 +:102E80004910D0F8003923F40043C0F80039D5F8D0 +:102E90001C3823EA0707D7E700800010000400026F +:102EA000D0F894201268C0F89820FFF7C7BD000042 +:102EB0005831D0F8903049015B5813F4004004D0E9 +:102EC00013F4001F0CBF0220012070474831D0F8D6 +:102ED000903049015B5813F4004004D013F4001FF4 +:102EE0000CBF02200120704700EB8101CB68196AFA +:102EF0000B6813604B6853607047000000EB810360 +:102F000030B5DD68AA691368D36019B9402B84BF56 +:102F1000402313606B8A1468D0F890201C4402EBA5 +:102F20004110013C09B2B4FBF3F46343033323F0D3 +:102F3000030343EAC44343F0C043C0F8103B2B688B +:102F400003F00303012B0ED1D2F8083802EB411035 +:102F500013F4807FD0F8003B14BF43F0805343F05C +:102F60000053C0F8003B02EB4112D2F8003B43F0A3 +:102F70000443C2F8003B30BD2DE9F041D0F8906029 +:102F800005460C4606EB4113D3F8087B3A07C3F815 +:102F9000087B08D5D6F814381B0704D500EB81034D +:102FA000DB685B689847FA071FD5D6F81438DB074B +:102FB0001BD505EB8403D968CCB98B69488A5A685C +:102FC000B2FBF0F600FB16228AB91868DA68904264 +:102FD0000DD2121AC3E90024202383F3118821465D +:102FE0002846FFF78BFF84F31188BDE8F0810123A9 +:102FF00003FA04F26B8923EA02036B81CB68002B8E +:10300000F3D021462846BDE8F041184700EB810384 +:103010004A0170B5DD68D0F890306C692668E660CA +:1030200056BB1A444FF40020C2F810092A6802F077 +:103030000302012A0AB20ED1D3F8080803EB4214A6 +:1030400010F4807FD4F8000914BF40F0805040F0A5 +:103050000050C4F8000903EB4212D2F8000940F016 +:103060000440C2F800090122D3F8340802FA01F141 +:103070000143C3F8341870BD19B9402E84BF4020F5 +:10308000206020681A442E8A8419013CB4FBF6F4AF +:1030900040EAC44040F00050C6E700002DE9F0418E +:1030A000D0F8906004460D4606EB4113D3F808793A +:1030B000C3F80879FB071CD5D6F81038DA0718D5FD +:1030C00000EB8103D3F80CC0DCF81430D3F800E037 +:1030D000DA6896451BD2A2EB0E024FF000081A6088 +:1030E000C3F80480202383F31188FFF78FFF88F350 +:1030F00011883B0618D50123D6F83428AB4013427B +:1031000012D029462046BDE8F041FFF7C3BC012399 +:1031100003FA01F2038923EA02030381DCF8083091 +:10312000002BE6D09847E4E7BDE8F0812DE9F84FA1 +:10313000D0F8905004466E69AB691E4016F4805872 +:103140006E6103D0BDE8F84FFEF772BC002E12DAB4 +:10315000D5F8003E9F0705D0D5F8003E23F00303C5 +:10316000C5F8003ED5F80438204623F00103C5F821 +:103170000438FEF789FC300505D52046FFF75EFCD4 +:103180002046FEF771FCB1040CD5D5F8083813F0D1 +:10319000060FEB6823F470530CBF43F4105343F451 +:1031A000A053EB60320704D56368DB680BB120469F +:1031B0009847F30200F1BA80B70226D5D4F8909070 +:1031C00000274FF0010A09EB4712D2F8003B03F445 +:1031D0004023B3F5802F11D1D2F8003B002B0DDA3C +:1031E00062890AFA07F322EA0303638104EB870387 +:1031F000DB68DB6813B13946204698470137D4F8BD +:103200009430FFB29B689F42DDD9F00619D5D4F8FF +:103210009000026AC2F30A1702F00F0302F4F012E0 +:10322000B2F5802F00F0CC80B2F5402F09D104EB2D +:103230008303002200F58050DB681B6A974240F050 +:10324000B2803003D5F8185835D5E90303D50021ED +:103250002046FFF791FEAA0303D501212046FFF780 +:103260008BFE6B0303D502212046FFF785FE2F035B +:1032700003D503212046FFF77FFEE80203D5042192 +:103280002046FFF779FEA90203D505212046FFF766 +:1032900073FE6A0203D506212046FFF76DFE2B025E +:1032A00003D507212046FFF767FEEF0103D508216C +:1032B0002046FFF761FE700340F1A980E90703D5BE +:1032C00000212046FFF7EAFEAA0703D50121204688 +:1032D000FFF7E4FE6B0703D502212046FFF7DEFE71 +:1032E0002F0703D503212046FFF7D8FEEE0603D5AE +:1032F00004212046FFF7D2FEA80603D5052120466B +:10330000FFF7CCFE690603D506212046FFF7C6FE6F +:103310002A0603D507212046FFF7C0FEEB0576D528 +:1033200020460821BDE8F84FFFF7B8BED4F89090CA +:1033300000274FF0010AD4F894305FFA87FB9B68AE +:103340009B453FF639AF09EB4B13D3F8002902F444 +:103350004022B2F5802F24D1D3F80029002A20DAA8 +:10336000D3F8002942F09042C3F80029D3F800298D +:10337000002AFBDB5946D4F89000FFF7C7FB2289EF +:103380000AFA0BF322EA0303238104EB8B03DB68C5 +:103390009B6813B159462046984759462046FFF787 +:1033A00079FB0137C7E7910701D1D0F80080072AE0 +:1033B00002F101029CBF03F8018B4FEA18283DE798 +:1033C00004EB830300F58050DA68D2F818C0DCF80B +:1033D0000820DCE9001CA1EB0C0C00218F4208D175 +:1033E000DB689B699A683A449A605A683A445A6022 +:1033F00027E711F0030F01D1D0F800808C4501F1CF +:10340000010184BF02F8018B4FEA1828E6E7BDE806 +:10341000F88F000008B50348FFF788FEBDE80840B4 +:10342000FFF784BA2C45002008B50348FFF77EFE5D +:10343000BDE80840FFF77ABAC8450020D0F89030C0 +:1034400003EB4111D1F8003B43F40013C1F8003BFA +:1034500070470000D0F8903003EB4111D1F80039EB +:1034600043F40013C1F8003970470000D0F89030E1 +:1034700003EB4111D1F8003B23F40013C1F8003BEA +:1034800070470000D0F8903003EB4111D1F80039BB +:1034900023F40013C1F8003970470000090100F15E +:1034A0006043012203F56143C9B283F8001300F0C1 +:1034B0001F039A4043099B0003F1604303F56143F6 +:1034C000C3F880211A60704730B50433039C017241 +:1034D000002104FB0325C160C0E90653049B03637C +:1034E000059BC0E90000C0E90422C0E90842C0E928 +:1034F0000A11436330BD00000022416AC260C0E986 +:103500000411C0E90A226FF00101FEF7F7BD0000C7 +:10351000D0E90432934201D1C2680AB9181D70473C +:1035200000207047036919600021C2680132C2603F +:10353000C269134482699342036124BF436A0361F1 +:10354000FEF7D0BD38B504460D46E3683BB162696D +:103550000020131D1268A3621344E36207E0237A7C +:1035600033B929462046FEF7ADFD0028EDDA38BD17 +:103570006FF00100FBE70000C368C269013BC36054 +:103580004369134482699342436124BF436A4361A0 +:1035900000238362036B03B11847704770B5202383 +:1035A000044683F31188866A3EB9FFF7CBFF0546D0 +:1035B00018B186F31188284670BDA36AE26A13F831 +:1035C000015B9342A36202D32046FFF7D5FF00239D +:1035D00083F31188EFE700002DE9F84F04460E460B +:1035E000174698464FF0200989F311880025AA460E +:1035F000D4F828B0BBF1000F09D141462046FFF7AF +:10360000A1FF20B18BF311882846BDE8F88FD4E9DB +:103610000A12A7EB050B521A934528BF9346BBF13C +:10362000400F1BD9334601F1400251F8040B91427F +:1036300043F8040BF9D1A36A403640354033A36206 +:10364000D4E90A239A4202D32046FFF795FF8AF372 +:103650001188BD42D8D289F31188C9E730465A464D +:10366000FDF7CEFBA36A5E445D445B44A362E7E7DB +:1036700010B5029C0433017204FB0321C460C0E94D +:1036800006130023C0E90A33039B0363049BC0E9CC +:103690000000C0E90422C0E90842436310BD0000F5 +:1036A000026A6FF00101C260426AC0E9042200228E +:1036B000C0E90A22FEF722BDD0E904239A4201D1D3 +:1036C000C26822B9184650F8043B0B6070470020CE +:1036D00070470000C3680021C2690133C3604369B9 +:1036E000134482699342436124BF436A4361FEF7F6 +:1036F000F9BC000038B504460D46E3683BB12369C8 +:1037000000201A1DA262E2691344E36207E0237AF3 +:1037100033B929462046FEF7D5FC0028EDDA38BD3E +:103720006FF00100FBE7000003691960C268013A0D +:10373000C260C269134482699342036124BF436A31 +:10374000036100238362036B03B1184770470000D5 +:1037500070B520230D460446114683F31188866A0E +:103760002EB9FFF7C7FF10B186F3118870BDA36AA9 +:103770001D70A36AE26A01339342A36204D3E16934 +:1037800020460439FFF7D0FF002080F31188EDE7D1 +:103790002DE9F84F04460D46904699464FF0200A11 +:1037A0008AF311880026B346A76A4FB949462046D6 +:1037B000FFF7A0FF20B187F311883046BDE8F88FEE +:1037C000D4E90A073A1AA8EB0607974228BF17461A +:1037D000402F1BD905F1400355F8042B9D4240F8BA +:1037E000042BF9D1A36A40364033A362D4E90A23FB +:1037F0009A4204D3E16920460439FFF795FF8BF321 +:1038000011884645D9D28AF31188CDE729463A4630 +:10381000FDF7F6FAA36A3D443E443B44A362E5E764 +:10382000D0E904239A4217D1C3689BB1836A8BB154 +:10383000043B9B1A0ED01360C368013BC360C3698D +:103840001A4483699A42026124BF436A03610023D8 +:1038500083620123184670470023FBE700F0CEB8CF +:10386000034B002258631A610222DA60704700BFDE +:10387000000C0040014B0022DA607047000C004051 +:10388000014B5863704700BF000C0040014B586A61 +:10389000704700BF000C00404B6843608B6883603A +:1038A000CB68C3600B6943614B6903628B694362F8 +:1038B0000B6803607047000008B5364B40F2FF719B +:1038C0003548D3F888200A43C3F88820D3F88820E5 +:1038D00022F4FF6222F00702C3F88820D3F8882080 +:1038E000D3F8E0200A43C3F8E020D3F808210A43C4 +:1038F000C3F80821294AD3F808311146FFF7CCFF55 +:1039000000F5806002F11C01FFF7C6FF00F5806042 +:1039100002F13801FFF7C0FF00F5806002F15401A9 +:10392000FFF7BAFF00F5806002F17001FFF7B4FF06 +:1039300000F5806002F18C01FFF7AEFF00F58060BA +:1039400002F1A801FFF7A8FF00F5806002F1C401B1 +:10395000FFF7A2FF00F5806002F1E001FFF79CFF96 +:1039600000F5806002F1FC01FFF796FF02F58C7113 +:1039700000F58060FFF790FF00F0F4F8084B052297 +:10398000C3F898204FF06052C3F89C20054AC3F852 +:10399000A02008BD0044025800000258D841000889 +:1039A00000ED00E01F00080308B500F0D7FAFEF7AD +:1039B00013FB0F4BD3F8DC2042F04002C3F8DC20AD +:1039C000D3F8042122F04002C3F80421D3F80431D3 +:1039D000084B1A6842F008021A601A6842F00402A2 +:1039E0001A60FEF755FFBDE80840FEF703BD00BFB3 +:1039F000004402580018024870470000114BD3F8E9 +:103A0000E82042F00802C3F8E820D3F8102142F081 +:103A10000802C3F810210C4AD3F81031D36B43F0DD +:103A20000803D363C722094B9A624FF0FF32DA6270 +:103A300000229A615A63DA605A6001225A611A6060 +:103A4000704700BF004402580010005C000C0040AA +:103A5000094A08B51169D3680B40D9B29B076FEAD0 +:103A60000101116107D5202383F31188FEF7D4FAF1 +:103A7000002383F3118808BD000C0040384B4FF041 +:103A8000FF31D3F88020C3F88010D3F880200022C3 +:103A9000C3F88020D3F88000D3F88400C3F88410E2 +:103AA000D3F88400C3F88420D3F88400D86F40F0A2 +:103AB000FF4040F4FF0040F43F5040F03F00D86723 +:103AC000D86F20F0FF4020F4FF0020F43F5020F09A +:103AD0003F00D867D86FD3F888006FEA40506FEA8C +:103AE0005050C3F88800D3F88800C0F30A00C3F828 +:103AF0008800D3F88800D3F89000C3F89010D3F86A +:103B00009000C3F89020D3F89000D3F89400C3F845 +:103B10009410D3F89400C3F89420D3F89400D3F809 +:103B20009800C3F89810D3F89800C3F89820D3F8F9 +:103B30009800D3F88C00C3F88C10D3F88C00C3F82D +:103B40008C20D3F88C00D3F89C00C3F89C10D3F8D9 +:103B50009C10C3F89C20D3F89C3000F0D3B900BF70 +:103B600000440258614B0122C3F80821604BD3F88E +:103B7000F42042F00202C3F8F420D3F81C2142F0F2 +:103B80000202C3F81C210222D3F81C31594BDA601F +:103B90005A689104FCD5584A1A6001229A60574A23 +:103BA000DA6000221A614FF440429A61514B9A69DF +:103BB0009204FCD51A6842F480721A604C4B1A6F5A +:103BC00012F4407F04D04FF480321A6700221A6743 +:103BD0001A6842F001021A60454B1A685007FCD57A +:103BE00000221A611A6912F03802FBD10121196012 +:103BF0004FF0804159605A67414ADA62414A1A617E +:103C00001A6842F480321A60394B1A689103FCD565 +:103C10001A6842F480521A601A689204FCD53A4A33 +:103C20003A499A6200225A6319633949DA639963FF +:103C30005A64384A1A64384ADA621A6842F0A8525A +:103C40001A602B4B1A6802F02852B2F1285FF9D1A2 +:103C500048229A614FF48862DA6140221A622F4A40 +:103C6000DA644FF000521A652D4A5A652D4A9A655A +:103C700032232D4A1360136803F00F03022BFAD18D +:103C80001B4B1A6942F003021A611A6902F03802EA +:103C9000182AFAD1D3F8DC2042F00052C3F8DC2015 +:103CA000D3F8042142F00052C3F80421D3F80421D0 +:103CB000D3F8DC2042F08042C3F8DC20D3F80421A2 +:103CC00042F08042C3F80421D3F80421D3F8DC2069 +:103CD00042F00042C3F8DC20D3F8042142F0004255 +:103CE000C3F80421D3F80431704700BF00800051AD +:103CF000004402580048025800C000F002000001D1 +:103D00000000FF01008890081210200063020701E4 +:103D10002C02040047040508FD0BFF0120000020D1 +:103D20000010E00000010100002000524FF0B042FE +:103D300008B5D2F8883003F00103C2F8883023B107 +:103D4000044A13680BB150689847BDE80840FEF775 +:103D5000EDBD00BF7C4600204FF0B04208B5D2F860 +:103D6000883003F00203C2F8883023B1044A936814 +:103D70000BB1D0689847BDE80840FEF7D7BD00BF3B +:103D80007C4600204FF0B04208B5D2F8883003F0EE +:103D90000403C2F8883023B1044A13690BB1506997 +:103DA0009847BDE80840FEF7C1BD00BF7C46002033 +:103DB0004FF0B04208B5D2F8883003F00803C2F8DB +:103DC000883023B1044A93690BB1D0699847BDE8A4 +:103DD0000840FEF7ABBD00BF7C4600204FF0B0426C +:103DE00008B5D2F8883003F01003C2F8883023B148 +:103DF000044A136A0BB1506A9847BDE80840FEF7C1 +:103E000095BD00BF7C4600204FF0B04310B5D3F8FD +:103E1000884004F47872C3F88820A30604D5124AB7 +:103E2000936A0BB1D06A9847600604D50E4A136BAB +:103E30000BB1506B9847210604D50B4A936B0BB11D +:103E4000D06B9847E20504D5074A136C0BB1506C50 +:103E50009847A30504D5044A936C0BB1D06C9847DE +:103E6000BDE81040FEF762BD7C4600204FF0B04335 +:103E700010B5D3F8884004F47C42C3F8882062056A +:103E800004D5164A136D0BB1506D9847230504D520 +:103E9000124A936D0BB1D06D9847E00404D50F4AD8 +:103EA000136E0BB1506E9847A10404D50B4A936E64 +:103EB0000BB1D06E9847620404D5084A136F0BB15A +:103EC000506F9847230404D5044A936F0BB1D06F09 +:103ED0009847BDE81040FEF729BD00BF7C46002092 +:103EE00008B50348FDF746F9BDE80840FEF71EBDDA +:103EF000CC23002008B5FFF7ABFDBDE80840FEF776 +:103F000015BD0000062108B50846FFF7C7FA0621CF +:103F10000720FFF7C3FA06210820FFF7BFFA0621A2 +:103F20000920FFF7BBFA06210A20FFF7B7FA06219E +:103F30001720FFF7B3FA06212820FFF7AFFA09216F +:103F40007A20FFF7ABFA07213220FFF7A7FA0C21FE +:103F50002520BDE80840FFF7A1BA000008B5FFF72B +:103F60008DFD00F00DF8FDF717FBFDF7EFFCFDF7F9 +:103F7000C1FBFFF741FDBDE80840FFF76FBC000043 +:103F80000023054A19460133102BC2E9001102F142 +:103F90000802F8D1704700BF7C46002010B50139F7 +:103FA0000244904201D1002005E0037811F8014F4E +:103FB000A34201D0181B10BD0130F2E7034611F8EF +:103FC000012B03F8012B002AF9D1704753544D33CC +:103FD0003248373F3F3F0053544D33324837343334 +:103FE0002F37353300000000F0290020CC230020BB +:103FF000009600000000000000000000000000002B +:104000000000000000000000000000006115000832 +:104010004D15000889150008751500088115000860 +:104020006D1500085915000845150008951500087C +:1040300000000000711600085D16000899160008BF +:1040400085160008911600087D16000869160008FC +:1040500055160008A5160008000000000100000029 +:10406000000000006D61696E0000000069646C650D +:10407000000000006C40000878280020F029002093 +:1040800001000000D51F00080000000041726475A7 +:1040900050696C6F740025424F415244252D424CAB +:1040A000002553455249414C250000000200000004 +:1040B00000000000911800080119000840004000AD +:1040C00098420020A84200200200000000000000EA +:1040D0000300000000000000491900080000000073 +:1040E00010000000B84200200000000001000000A5 +:1040F000000000002C45002001010200912300086F +:10410000A12200083D2300082123000843000000ED +:104110001441000809024300020100C032090400F2 +:104120000001020201000524001001052401000124 +:10413000042402020524060001070582030800FF8B +:1041400009040100020A0000000705010240000006 +:1041500007058102400000001200000060410008D5 +:104160001201100102000040091241570002010231 +:10417000030100000403090425424F415244250075 +:1041800042656173744837763200303132333435EA +:1041900036373839414243444546000000000000AC +:1041A0009D1A0008551D0008011E0008400040002F +:1041B0006446002064460020010000007446002090 +:1041C0008000000040010000080000000001000025 +:1041D00000040000080000000001A86A00000000C0 +:1041E000AAAAAAAA00011464FFFF000000000000B0 +:1041F00070A70A000000000000000000AAAAAAAAF6 +:1042000000000000FFFF00000000000000000000B0 +:104210000000000400000000AAAAAAAA00000000F2 +:10422000FFDF0000000000000000000000000000B0 +:1042300000000000AAAAAAAA00000000FFFF0000D8 +:10424000000000000000000000010000000000006D +:10425000AAAAAAAA00010000FFFF000000000000B7 +:10426000000000000000000000000000AAAAAAAAA6 +:1042700000000000FFFF0000000000000000000040 +:104280000000000000000000AAAAAAAA0000000086 +:10429000FFFF000000000000000000000000000020 +:1042A00000000000AAAAAAAA00000000FFFF000068 +:1042B00000000000000000000000000000000000FE +:1042C000AAAAAAAA00000000FFFF00000000000048 +:1042D000000000000000000000000000AAAAAAAA36 +:1042E00000000000FFFF00000000000000000000D0 +:1042F0000000000000000000AAAAAAAA0000000016 +:10430000FFFF0000000000000000000000000000AF +:10431000200400000000000000001E00000000005B +:10432000FF00000000000000CC3F00083F0000003C +:1043300050040000D73F00083F0000000096000036 +:1043400000000800960000000008000004000000C3 +:1043500074410008000000000000000000000000A0 +:0C43600000000000000000000000000051 +:00000001FF diff --git a/Tools/bootloaders/BirdCANdy_bl.bin b/Tools/bootloaders/BirdCANdy_bl.bin index d99f6c5a275..4c3fd6689d9 100755 Binary files a/Tools/bootloaders/BirdCANdy_bl.bin and b/Tools/bootloaders/BirdCANdy_bl.bin differ diff --git a/Tools/bootloaders/BirdCANdy_bl.elf b/Tools/bootloaders/BirdCANdy_bl.elf index 45a9c7c3aba..5b1c66aa0b9 100755 Binary files a/Tools/bootloaders/BirdCANdy_bl.elf and b/Tools/bootloaders/BirdCANdy_bl.elf differ diff --git a/Tools/bootloaders/BirdCANdy_bl.hex b/Tools/bootloaders/BirdCANdy_bl.hex index a60538ae8a5..515351a6fb5 100644 --- a/Tools/bootloaders/BirdCANdy_bl.hex +++ b/Tools/bootloaders/BirdCANdy_bl.hex @@ -1,26 +1,26 @@ :020000040800F2 -:1000000000070020E504000881140008851400089A -:10001000DD14000885140008B1140008E704000886 -:10002000E7040008E7040008E70400089D3500081D +:1000000000070020E5040008A915000829150008CC +:10001000811500082915000855150008E704000897 +:10002000E7040008E7040008E7040008893700082F :10003000E7040008E7040008E7040008E7040008F4 :10004000E7040008E7040008E7040008E7040008E4 -:10005000E7040008E7040008AD390008D9390008B2 -:10006000053A0008313A00085D3A0008E704000844 +:10005000E7040008E7040008B53B0008E13B00089E +:100060000D3C0008393C0008653C0008E704000826 :10007000E7040008E7040008E7040008E7040008B4 -:10008000E7040008E7040008E7040008B5230008B7 -:100090002124000875240008C9240008893A0008B2 +:10008000E7040008E7040008E70400086125000809 +:10009000CD2500082126000875260008913C00089F :1000A000E7040008E7040008E7040008E704000884 -:1000B00019380008E7040008E7040008E70400080E +:1000B000053A0008E7040008E7040008E704000820 :1000C000E7040008E7040008E7040008E704000864 :1000D000E7040008E7040008E7040008E704000854 -:1000E000F13A0008E7040008E7040008E704000804 +:1000E000F93C0008E7040008E7040008E7040008FA :1000F000E7040008E7040008E7040008E704000834 :10010000E7040008E7040008E7040008E704000823 :10011000E7040008E7040008E7040008E704000813 :10012000E7040008E7040008E7040008E704000803 :10013000E7040008E7040008E7040008E7040008F3 :10014000E7040008E7040008E7040008E7040008E3 -:10015000E7040008E7040008E70400086127000836 +:10015000E7040008E7040008E70400080D29000888 :10016000E7040008E7040008E7040008E7040008C3 :10017000E7040008E7040008E7040008E7040008B3 :10018000E7040008E7040008E7040008E7040008A3 @@ -84,919 +84,952 @@ :1005200040F20000C0F2F0004EF68851CEF2000119 :100530000860BFF34F8FBFF36F8F4FF00000E1EE05 :10054000100A4EF63C71CEF200010860062080F3DE -:100550001488BFF36F8F03F0A1F803F07DF803F068 -:10056000C7F84FF055301F491B4A91423CBF41F834 +:100550001488BFF36F8F03F097F903F073F903F07A +:10056000BDF94FF055301F491B4A91423CBF41F83D :10057000040BFAE71C49194A91423CBF41F8040BAD :10058000FAE71A491A4A1B4B9A423EBF51F8040B2C :1005900042F8040BF8E700201749184A91423CBF83 -:1005A00041F8040BFAE703F05BF803F0EFF8144CA2 +:1005A00041F8040BFAE703F051F903F0E5F9144CB4 :1005B000144DAC4203DA54F8041B8847F9E700F005 :1005C00041F8114C114DAC4203DA54F8041B884732 -:1005D000F9E703F043B800000007002000230020E3 -:1005E000000000080001002000070020603E000815 -:1005F000002300201C230020202300208439002019 +:1005D000F9E703F039B900000007002000230020EC +:1005E000000000080001002000070020684000080B +:1005F00000230020242300202823002098390020F5 :10060000E0010008E0010008E0010008E001000846 :100610002DE9F04F2DED108AC1F80CD0C3689D462E :10062000BDEC108ABDE8F08F002383F311882846C3 -:10063000A047002002F0A8FCFEE702F02DFC00DF3E -:10064000FEE700002DE9F04102F052FF074602F0FC -:100650009FFF0546A8BB274B9F4232D001339F42E4 -:1006600032D0254B27F0FF029A4231D1F8B200F088 -:1006700043FAA84642F2107400F048FC00F042FA37 -:10068000064648B354BB464635B11C4B9F4203D087 -:1006900002F076FF00242646002002F033FF0EB160 -:1006A00000F02EF800F054FC00F028FE00F02AFFC5 -:1006B0000546B4B900F0ECFC4FF47A7002F06AFC25 -:1006C000F7E7A8460024D7E704464FF00108D3E730 -:1006D00080464FF47A74CFE70446D5E74FF47A7436 -:1006E000D2E700F00FFF431BA342E3D900F008F864 -:1006F000DCE700BF010007B0000008B0263A09B0EF -:100700001E4B1F4A10B51C461968013134D0043302 -:100710009342F9D162681B4B9A422DD91A4B9B68C0 -:1007200003F1006303F580339A4225D202F0FAFE0A -:1007300002F00CFF002000F0FBFD144B02201870AB -:1007400000F032FE124B1A6C00221A64196E1A66FF -:10075000196E596C5A64596E5A665B6E72B64FF0D8 -:10076000E0232021C3F8084DD4E9003281F3118839 -:100770009D4683F30888104710BD00BF00000108A4 -:1007800020000108FFFF0008002300202023002094 -:1007900000380240094A136849F2690099B21B0CFB -:1007A00000FB01331360064B186844F2506182B2BB -:1007B000000C01FB0200186080B270471823002073 -:1007C0001423002010B500211022044600F008FE7A -:1007D000034B03CB206061601868A06010BD00BFB0 -:1007E000107AFF1F2DE9F043204DBBB000F08AFEC8 -:1007F000AB68C31AF92B32D906AFA8602B46282262 -:100800000021384601F016FB05F10E0000F0E0FD76 -:10081000002604465FFA80F905F10E08F3B2F100F4 -:10082000994501F1280107D908EB0603082238464B -:1008300001F000FB0136F1E708230122CDE9023285 -:1008400005340B4B0193A4B230230093CDE904741B -:1008500004A3D3E90023297B064801F003F93BB048 -:10086000BDE8F08378F6339F93CACD8D60330020C6 -:100870006D3300203C33002070B50D4614461E46F3 -:1008800001F086F850B9022E10D1012C0ED112A31E -:10089000D3E90023C5E90023012007E0282C10D06C -:1008A00005D8012C09D0052C0FD0002070BD302CAC -:1008B000FBD10BA3D3E90023ECE70BA3D3E900237F -:1008C000E8E70BA3D3E90023E4E70BA3D3E9002374 -:1008D000E0E700BFAFF30080401DA12026812A0B76 -:1008E00078F6339F93CACD8D9E6AC421818A46EEE5 -:1008F00026417272DF25D7B7F017304A39059E5668 -:1009000013B504462346084620220021019001F039 -:1009100091FA22790198032A234628BF032203F87B -:10092000042F2021022201F085FA62790198072A1A -:10093000234628BF072203F8052F2221032201F0B6 -:1009400079FAA2790198072A234628BF072203F8DB -:10095000062F2521032201F06DFA019804F1080306 -:100960001022282101F066FA382002B010BD0000E4 -:100970002DE9F04FFFB01FAD0CAE40F2751280466E -:100980000F4620A80021296000F02AFD48220021FE -:10099000304600F025FD00F0B5FD554B4FF47A725E -:1009A000B0FBF2F0186093E80700012386E8070027 -:1009B0000DF152003382FFF705FF41F20443338407 -:1009C00006AB18464B4903F03DF91722306429461F -:1009D000304686F83C20FFF793FF10AB04460146F3 -:1009E0000822284601F026FA0822A1180DF1410339 -:1009F000284601F01FFA0DF14203082204F110010C -:100A0000284601F017FA11AB202204F118012846FC -:100A100001F010FA12AB402204F13801284601F02F -:100A200009FA14AB082204F17801284601F002FA11 -:100A30000DF15103082204F18001284601F0FAF972 -:100A400004F1880A0DF1520904F5847B4B465146A6 -:100A5000082228460AF1080A01F0ECF9D34509F109 -:100A60000109F3D119AB08225946284601F0E2F9F1 -:100A700004F588744FF0000996F834304B450AD9D4 -:100A8000B36B21464B440822284601F0D3F90834C1 -:100A900009F10109F0E74FF0000996F83C304B45A9 -:100AA00004EBC90108D9336C08224B44284601F0F5 -:100AB000C1F909F10109F0E700230393BB7E02931A -:100AC000073107F119030193C1F3CF010123CDE9E8 -:100AD00004510093F97E04A3D3E90023404600F0BB -:100AE000C1FF7FB0BDE8F08F9E6AC421818A46EEC7 -:100AF00024230020543C0008014B1870704700BFAD -:100B000030230020F0B5334B1C7B85B034B1324B21 -:100B10000E221A810024204605B0F0BD2F4A10682D -:100B2000516802AB03C308232D492E480DEB030285 -:100B300003F066F8054630B9274B2B480A221A8184 -:100B400000F09AFCE6E70169B1F5E02F06D9224BE7 -:100B500026480B221A8100F08FFCDCE7438B40F221 -:100B60001442934207D01C490C20088119462048A2 -:100B700000F082FCCFE71F4A024402F110039942C1 -:100B800004D2154B1C4810221A81E4E710398E1A42 -:100B90002046144900F0BAFC3246074605F1180118 -:100BA000204600F0B3FCAB689F4202D1EB6898424C -:100BB0000AD0094B0D221A810090D5E902123B465A -:100BC0000E4800F059FCA5E70D4800F055FC012443 -:100BD000A1E700BF6033002024230020FD3C000873 -:100BE000DCFF0600000001086C3C0008783C0008AF -:100BF0008A3C00080800FFF7A83C0008C53C000834 -:100C0000EE3C00082DE9F04FADB006AF80460C4633 -:100C100000F0BEFE054600285AD1237E022B1BD1D0 -:100C2000E38A012B18D100F06DFC0646FFF7B2FDF8 -:100C300003464FF4C870DFF8D092B3FBF0F206F52C -:100C4000167602FB103316FA83F3C9F80030E37E00 -:100C500033B9A84B00221A709C37BD46BDE8F08F0F -:100C6000A38AEEB2013BB34205F101050BD93B1D4E -:100C70001E44E90000960023082201F0F8012046F6 -:100C800000F09CFFECE707F11400FFF79BFD3246F4 -:100C900007F11401381D02F0A3FF0028D9D10F2E4F -:100CA00008D8944B1E70D9F80030A3F51673C9F814 -:100CB0000030D1E7FB1CF870014600930722034681 -:100CC000204600F07BFFF978404600F059FEC3E76C -:100CD000E38A282B26D010D8012B1ED0052BBBD1A0 -:100CE000BFF34F8F8449854BCA6802F4E062134317 -:100CF000CB60BFF34F8F00BFFDE7302BACD1637EDD -:100D00007F4D01336A7BDBB29342E94603D1E27E39 -:100D10002B7B9A4265D0CD469EE721464046FFF7A1 -:100D200027FE99E7A38A013B9BB2C92B94D8744D47 -:100D30002E7B26BB05F10C03009308223346314677 -:100D4000204600F03BFF731CF2B2D9001E46A38A76 -:100D5000013B9A4205DA0E322A440092002308220F -:100D6000EEE700230022C5E900230023AB6085F8ED -:100D7000D730C5F8D8302B7B0BB9E37E2B73002519 -:100D800007F114093B1D082229464846C7E90155C9 -:100D9000FD6001F04FF83B7A05F1010AAB424FEAE2 -:100DA000CA0608D9FB6808222B443146484601F0A0 -:100DB00041F85546EFE7C6F3CF06E17ECDE904964C -:100DC00000230393A37E02931934282300930194F4 -:100DD00046A3D3E90023404600F044FEFFF702FD9E -:100DE0003AE74FF0000807F11403A7F81480102227 -:100DF000009341460123204600F0E0FEA68A023E11 -:100E0000B6B2F31C9B109B000733DB08A9EBC303AE -:100E10009D460DF1180A1FFA88F34FEAC801B34244 -:100E200001F110010AD20AEB080300930822002303 -:100E3000204600F0C3FE08F10108ECE795F8D70062 -:100E400000F080FAD5F8D83004461BB995F8D700E1 -:100E500000F088FAD5F8D83033449C4204D295F893 -:100E6000D700013000F07EFA4FEA960B4FF00008F1 -:100E70001FFA88F18B45D5E9003209D90AEB8801C0 -:100E800003EB8800012200F0B3FA08F10108EFE754 -:100E9000F31842F10002C5E90032D5F8D83095F8D0 -:100EA000D70006EB0308C5F8D88000F04BFA804560 -:100EB00009D395F8D730D5F8D8000133001B85F851 -:100EC000D730C5F8D800FF2E08D800232B7300F0C8 -:100ED0005BFAFFF717FE08B1FFF712FC2B68094A0F -:100EE0009B0A013313810023AB6014E72641727221 -:100EF000DF25D7B73533002000ED00E00400FA0508 -:100F000060330020242300203833002008B54FF040 -:100F100000530B4A196891420AD10A4A597D11704F -:100F200009481B7D03730949C9220E3000F046FAB7 -:100F3000BDE80840E02200214FF0005000F050BA18 -:100F40009AAD44C5302300206033002016000020F5 -:100F50002DE9FF41434C02236371002302931825BE -:100F60000A23581EB5FBF3F67343D3F11802C1B23E -:100F70003ED002280346F4D19DF80B303A493B4855 -:100F80005A1E9DF80A30013B1B0443EA0253BDF888 -:100F90000820013A13434B6001F09EFC00230193AB -:100FA000334B344900933448344B4FF4805200F0B3 -:100FB000C1FC334B197811B12F4800F0E1FC00F06F -:100FC000A1FA0546FFF7E6FB4FF4C873B0FBF3F256 -:100FD00002FB130305F5167010FA83F0294B186015 -:100FE00002F0D6FA08B10F23238104B0BDE8F081E6 -:100FF000C1EBC107FB1C4FEAE30EC3F3C703A1EB30 -:10100000030C0EF101084FF47A705FFA8CF50EFBB9 -:10101000000058FA8CFCB0FBFCF0B0F5617F07D9FA -:101020007B1EC3F3C703C91ACDB2591E0F2916D8A8 -:101030006A1E072A8CBF00220122591901FB066093 -:101040001149B1FBF0F11148814295D1002A93D0AA -:10105000ADF808608DF80A308DF80B508CE7134618 -:10106000EBE700BF242300200C230020783400206D -:1010700079080008342300203C330020050C0008C8 -:10108000302300203833002000366E0140420F002C -:101090002DE9F04F91A7D7E900670FF24829D9E968 -:1010A0000089874D93B0DFF844B2864C284600F0A3 -:1010B0003DFD0DF1300A079070B31022002150461B -:1010C00000F08EF9079B197B4FF0000261F30302D9 -:1010D0008DF83020586899680EAA03C21B680D9AD3 -:1010E00063F31C029DF830300D9243F020038DF81D -:1010F0003030002352461946584601F0FDFB079058 -:1011000028B9284600F016FD079B2370CEE7237808 -:10111000072B3CD80133237018220021504600F0E1 -:101120005FF9DFF8C8B1684C0023194652465846AB -:1011300001F00AFC014670BB102208A800F050F92B -:10114000636983F02003636100F0DEF90B4612A9A6 -:10115000024611E903000DF1240C8CE803009DF810 -:101160003410C1F3030089064CBF0E99BDF838C096 -:101170008DF82C0046BFC1F31C0C4CF00041CCF3A1 -:101180000A010891284608A900F09CFECCE72846F1 -:1011900000F0D0FCC0E7284600F0FAFB0446002827 -:1011A00048D1DFF84CB100F0ADF9DBF800309842DF -:1011B00040D300F0A7F90790FFF7ECFA079A8DF8F3 -:1011C000204003464FF4C87002F51672B3FBF0F1ED -:1011D00001FB103312FA83F3CBF80030DFF814B1BF -:1011E0009BF8001011B901238DF82030504607916B -:1011F000FFF7E8FA0799C1F11004E4B2062C28BF02 -:101200000624224651440DF1210000F0D7F808AB26 -:1012100003931823029301342C4B0193E4B201236E -:10122000009304943B463246284600F0B3FB00236B -:101230008BF8003000F066F9254A264C1368C31A73 -:10124000B3F57A7F31D3106000F05EF902460B46A9 -:10125000284600F079FC284600F09AFB28B3237B4F -:10126000DFF894B0002B14BF032302238BF8053062 -:1012700000F048F94FF47A735146B0FBF3F0CBF825 -:1012800000005846FFF73CFB182307300293124B2F -:101290000193C0F3CF0040F25513CDE903A00093B2 -:1012A00042464B46284600F075FB237B2BB1FFF7E7 -:1012B00099FA237B002B7FF4F6AE13B0BDE8F08FD4 -:1012C0003C3300204534002000000240343300202D -:1012D000403400206033002044340020401DA12011 -:1012E00026812A0BF1C6A7C1D068080F78340020E8 -:1012F00038330020353300202423002070B501F05E -:10130000ABFF094E094D30800024286833888342A2 -:1013100008D901F09BFF2B6804440133B4F5803FEA -:101320002B60F2D370BD00BF74340020483400201D -:1013300002F042B800F10060920000F5803001F048 -:10134000D1BF0000054B1A68054B1B889B1A8342CE -:1013500002D9104401F07ABF0020704748340020C1 -:101360007434002038B5074D04462868204401F045 -:1013700075FF28B928682044BDE8384001F086BFD1 -:1013800038BD00BF48340020064991F8243033B1FD -:101390000023086A81F824300822FFF7CBBF012020 -:1013A000704700BF4C340020022802BF024B4FF4AC -:1013B00000129A61704700BF0000024010B5002380 -:1013C000934203D0CC5CC4540133F9E710BD000054 -:1013D00003460246D01A12F9011B0029FAD17047C0 -:1013E00002440346934202D003F8011BFAE7704718 -:1013F0002DE9F8431F4D144695F8242007468846EA -:1014000052BBDFF870909CB395F824302BB92022A2 -:10141000FF2148462F62FFF7E3FF95F82400C0F153 -:101420000802A24228BF2246D6B24146920005EBEE -:101430008000FFF7C3FF95F82430A41B1E44F6B2CA -:10144000082E17449044E4B285F82460DBD1FFF7FE -:101450009BFF0028D7D108E02B6A03EB820383426D -:10146000CFD0FFF791FF0028CBD10020BDE8F88353 -:101470000120FBE74C3400200FB4002004B070477B -:10148000FEE7000000B59BB0EFF3098168226846D3 -:10149000FFF794FFEFF30583044B9A6BDA6A9A6ABD -:1014A0009A6A9A6A9A6A9A6A9B6AFEE700ED00E075 -:1014B00000B59BB0EFF3098168226846FFF77EFF15 -:1014C000EFF30583044B9A6B9A6A9A6A9A6A9A6A4E -:1014D0009A6A9B6AFEE700BF00ED00E000B59BB092 -:1014E000EFF3098168226846FFF768FFEFF3058391 -:1014F000034B5A6B9A6A9A6A9A6A9A6A9B6AFEE7DF -:1015000000ED00E001F092BF01F06ABF30B5094D77 -:101510000A4491420DD011F8013B5840082340F392 -:101520000004013B2C4013F0FF0384EA5000F6D185 -:10153000EFE730BD2083B8ED2DE9F041C56915B95D -:10154000C161BDE8F0814B6823F06047C3F38A4670 -:101550004FEAD37EC3F3807816EA230638BF3E46AF -:10156000AC462B465A68BEEBD27F22F060440AD0CC -:10157000002A18DAA40CB44217D19D420FD10D6095 -:10158000DEE71346EEE7A74207D102F08044C2F33C -:10159000807242450BD054B1EFE708D2EDE7CCF8AA -:1015A00000100B60CDE7B44201D0B442E5D81A6810 -:1015B0009C46002AE5D11960C3E700002DE9F047F9 -:1015C000089D01F007044FEAD508224405F00705FD -:1015D00000EBD1004FF47F49944201D1BDE8F08780 -:1015E00004F0070705F0070A57453E4638BF564640 -:1015F000C6F10806111B8E4228BF0E46E10808EB13 -:10160000D50E415C13F80EC0B94029FA06F721FA4D -:101610000AF1FFB28CEA010147FA0AF739408CEA75 -:10162000010C03F80EC034443544D5E780EA0120AC -:10163000082341F2210201B24000002980B203F1E7 -:10164000FF33B8BF504013F0FF03F4D170470000E0 -:1016500038B50C468D18A54200D138BD14F8011BD1 -:10166000FFF7E4FFF7E7000002684AB11368036080 -:10167000C388018901339BB29942C38038BF03817B -:101680001046704770B588B0202204460D46684663 -:101690000021FFF7A5FE20460495FFF7E5FF02466F -:1016A00058B16B46054608AE1C4603CCB4422860D0 -:1016B0006960234605F10805F6D1104608B070BDF3 -:1016C00010B54B6823B9CA8A63F30902CA8210BDF8 -:1016D000C4681A681C60C360438A013B43824A6045 -:1016E000EFE700002DE9F84F1D46CB8A0F46C3F304 -:1016F00009010629814692460B4630D00020AAB245 -:1017000007F119049EB2052E1FFA80F80FD89045F4 -:1017100003F1010306D3FB8A0A4462F30903FB8247 -:1017200001201AE01AF80060E6540130EAE790451B -:10173000F1D2A1F1060B1C237C68BBFBF3F203FB87 -:1017400012BB1FFA8BF6002C45D14846FFF78CFFE1 -:10175000044638B978606FF00200BDE8F88F4FF0AA -:101760000008E6E7002606607860ADB24FF0000B97 -:10177000454510D90AEB0803221D13F8011B9155AA -:10178000B1B208F101081B291FFA88F82BD0454592 -:1017900006F10106F1D8FB8AC3F30902154465F38B -:1017A0000903BCE7013292B21C462368002BF9D131 -:1017B000AB1F0B441C21B3FBF1F301339BB29A42E4 -:1017C000D3D2BBF1000FD0D14846FFF74DFF20B96F -:1017D000C4F800B0BFE70122E7E7C0F800B05E46FA -:1017E00020600446C1E74545D5D94846FFF73CFF90 -:1017F00008B92060AFE7C0F800B0002620600446BA -:10180000B6E700002DE9F04F2DED028B83B0CDE956 -:101810000013BDF83C4080469246002A00F08780C5 -:101820002CB10E9B002B00F08280072C2BD808F1E6 -:101830000C00FFF719FF054638B96FF0020528467E -:1018400003B0BDEC028BBDE8F08F14220021FFF73E -:10185000C7FD22460E9905F10800FFF7AFFD631C96 -:101860002B749AF800302C4403F01F0363F03F03FD -:101870002372009B43F00041696040462946FFF710 -:101880005BFE0125DBE700F10C034FF0000908EED9 -:10189000103A4FF0800B4E464D4618EE100AFFF7F7 -:1018A000E3FE07460028C8D014220021FFF798FD68 -:1018B000002E3AD1019B3B8102220E9B02F10801CE -:1018C00003EB060C57FA81F11046B44202F1010213 -:1018D000D2B201D8024607E01CF8010B01F8010B57 -:1018E0000136062AB6B2EFD99AF8001001F01F01AE -:1018F000B44208BF4FF0400BB81841EA49114BEA17 -:1019000001030372009B013243F000437B603A7491 -:1019100039464046FFF710FE0135B4422DB289F03A -:1019200001094FF0000BB8D189E70022C5E76FF03D -:10193000010584E7F8B515460E4624220021044629 -:101940001F46FFF74DFD069B6360B5F5001F079B23 -:10195000A76034BF6A094FF6FF72236204F10C00DE -:1019600097B200239A4205D800230360278263823E -:10197000A382F8BD0660013330462036F2E700004E -:1019800003781BB94BB2002BC8BF01707047000031 -:10199000007870472DE9F74FDDF83C90BDF83050E6 -:1019A0000D9E9DF83840BDF84070804692469B469B -:1019B000B9F1000F01D1002F51D11F2C4FD898F849 -:1019C0000000B0B9072F47D835F0030347D13A4696 -:1019D00049464FF6FF70FFF73BFE20F001002D0255 -:1019E000400445EA0464400C44EA40244FF6FF7387 -:1019F00021E040EA0520072F40EA0464F6D90025DB -:101A00004FF6FF73C5F12000A5F120022AFA05F177 -:101A10000BFA00F001432BFA02F211431846C9B247 -:101A2000FFF704FE0835402D0346EBD13A46494600 -:101A3000FFF70EFE0346CDE90097324621464046A9 -:101A4000FFF7E0FE33780133DBB21F2B88BF0023A2 -:101A5000337003B0BDE8F08F6FF00300F9E76FF06B -:101A60000100F6E72DE9F04F85B09246DDF8488099 -:101A70000F9D9DF840209DF84490BDF84C7006469F -:101A80009B46B8F1000F01D1002F48D11F2A46D83C -:101A90003378002B46D00C0244EA02649DF83810DB -:101AA00044EAC93444EA01441C43072F44F080044B -:101AB00032D900234FF6FF72C3F1200CA3F12000AE -:101AC0002AFA03F10BFA0CFC41EA0C012BFA00F0A4 -:101AD0000143C9B210460393FFF7A8FD039B0833E7 -:101AE000402B0246E8D13A464146FFF7B1FD034696 -:101AF000CDE900872A4621463046FFF783FEB9F13B -:101B0000010F06D12B780133DBB21F2B88BF0023D6 -:101B10002B7005B0BDE8F08F4FF6FF73E8E76FF06C -:101B20000100F6E76FF00300F3E70000C06900B1C1 -:101B300004307047C3691A68C261C2681A60C36022 -:101B4000438A013B438270472DE9F041D0F8188069 -:101B5000194E14461D464146002709B9BDE8F081DB -:101B6000D1E90223A21A65EB0303964277EB030344 -:101B70001ED283698B420DD1FFF7A2FD83691B68DA -:101B80008361C3680B60438AC1608169013B438202 -:101B90008846E2E7FFF794FD0B68C8F80030C36899 -:101BA0000B60438AC160013B4382D8F80010D4E740 -:101BB00088460968D1E700BF80841E002DE9F04FF8 -:101BC0008BB00D46DDF8509014469B4680460028A9 -:101BD00000F01981B9F1000F00F01581531E3F2B61 -:101BE00000F21181012A03D1BBF1000F40F00B81FB -:101BF0000023CDE90833B8F81430B5EBC30F4FEA32 -:101C0000C30703D300200BB0BDE8F08F2B199F4210 -:101C1000D8F80C303ABF7F1BFFB227461BB9D8F863 -:101C20001030002B7AD02F2D4ED8C5F13006B74298 -:101C30004FF000032CBFF6B23E4600932946D8F879 -:101C4000080008AB3246FFF7B9FCA7EB060A35449B -:101C50005FFA8AFAB8F8143003F10053063BDB0050 -:101C60000493D8F80C3003933021039B13B1BAF1DD -:101C7000000F2CD1D8F8100040B1BAF1000F05D0F8 -:101C8000009608AB5246691AFFF798FC38B2002F4D -:101C9000B8D066070AD00AAB03EBD401624211F850 -:101CA000083C02F00702134101F8083C082C3CD91B -:101CB000102C40F2B580202C40F2B780BBF1000F11 -:101CC00000F09C80082334E0BA460026C2E7049B5B -:101CD000E02B28BFE02306930B44AB42059314D9B5 -:101CE0005A1B03980096924534BF5246D2B2691AE5 -:101CF00008AB04300792FFF761FC079A1644AAEB81 -:101D0000020A1544F6B25FFA8AFA049B069A05990C -:101D10009B1A0493039B1B680393A6E70093D8F8D0 -:101D2000080008AB3A462946AEE7BBF1000F13D0D6 -:101D30000123B4EBC30F6CD0082C12D89DF82030CF -:101D4000621E23FA02F2D50706D54FF0FF3202FADF -:101D500004F423438DF820309DF8203089F80030BA -:101D600051E7102C12D8BDF82030621E23FA02F27F -:101D7000D10706D54FF0FF3202FA04F42343ADF841 -:101D80002030BDF82030A9F800303CE7202C0FD8D7 -:101D90000899631E21FA03F3DA0705D54FF0FF32E5 -:101DA00002FA04F40C430894089BC9F800302AE7AF -:101DB000402C2BD0DDE90865611EC4F12102A4F19D -:101DC000210326FA01F105FA02F225FA03F3114381 -:101DD0001943CB0712D50122A4F12003C4F120013D -:101DE00002FA03F322FA01F1A240524243EA01034C -:101DF00063EB430332432B43CDE90823DDE908239A -:101E0000C9E90023FFE66FF00100FCE66FF008006F -:101E1000F9E6082CA0D9102CB3D9202CEED8C3E7B2 -:101E2000BBF1000FADD0022383E7BBF1000FBBD0A5 -:101E300004237EE730B5012A144638BF0124402C24 -:101E400085B028BF40240025012ACDE9025518D8C5 -:101E50001B788DF8083063070AD004AB03EBD40578 -:101E6000624215F8083C02F00702934005F8083C6E -:101E7000009103462246002102A8FFF79FFB05B010 -:101E800030BD082AE4D9102A03D81B88ADF80830E1 -:101E9000E1E7202A8DBFD3E900231B680293CDE937 -:101EA0000223D8E710B5CB681BB98B600B618B821E -:101EB00010BDC4681A681C60C360438A013B43823A -:101EC000CA60F0E72DE9F04FD1F8008093B018F028 -:101ED000800FCDE90323C8F3C01219BFC8F3C03B7C -:101EE000C8F306264FF0020B1646B8F1000F044661 -:101EF0000D4680F2C58118F0C043059340F0C081C3 -:101F00000B7B002B00F0BC81BBF1020F03D00178EA -:101F1000B14240F0B88108F07F0106916AB3C8F37E -:101F2000074A2B44069A93F80390760646EA0B4636 -:101F300046EA82465FEAD91346EA0A06079300F0AA -:101F4000908000220023CDE90A23069B0093676856 -:101F50005B4652460AA92046B84700287ED0A769AA -:101F60009FB9314604F10C00FFF78CFB0746E0B93E -:101F70006FF0020013B0BDE8F08FC8F30F2A18F01D -:101F80007F0F08BF0AF0030ACBE73B699E420DD0E2 -:101F90003F68002FF9D1314604F10C00FFF772FBC6 -:101FA00007460028E4D0A3693B60A761DDE90A2366 -:101FB00000264FF6FF70C6F1200E22FA06F103FA52 -:101FC0000EFEA6F1200C23FA0CFC41EA0E0141EAB8 -:101FD0000C01C9B2083609920893FFF727FB402E7F -:101FE000DDE90832E7D1B882FB7D09F01F06C3F3B3 -:101FF00084039B1BD7E9022198B2002BBCBF00F1E0 -:1020000020031BB252EA0100C8F304680FD0039802 -:10201000821A049860EB0101A14890424FF000023F -:102020008A4104D3079A002A55D0012B23DDFA7D7B -:102030004FEA890302F0030203F07C031343FB75AC -:1020400039462046FFF73CFB079BA3B9FB7DC3F352 -:102050008402013262F38603FB7504E06FF00B002B -:1020600088E7A76917B96FF00C0083E73B699E42C8 -:10207000BAD03F68F6E719F0400F2CD0039BBB6045 -:10208000049BFB60142200210DA8FFF7A9F9039B14 -:102090000A93049B0B932B1D0C932B7BADF83EA056 -:1020A000013BDBB2ADF83C30069B8DF843308DF838 -:1020B00040B0A3688DF841608DF842800AA920469F -:1020C0009847FB7DC3F38403013303F01F039B0296 -:1020D000FB8200204EE7FB7DC9F34012B2EBD31F19 -:1020E00040F0D480C3F38403B34240F0D280079918 -:1020F0002B7B4FEA9912002934D0D20741D4032B0D -:1021000040F2CA80039BBB60049BFB602B7BAE1D2F -:10211000033BDBB23246394604F10C00FFF7E2FA2A -:1021200000280DDA20463946FFF7CAFAFB7DC3F3D3 -:102130008403013303F01F039B02FB82032019E792 -:10214000AB883B832A7B033AB88AD2B23146FFF789 -:102150007FFAFB7DB882DA43C2F3C01262F3C71381 -:10216000FB75B6E76AB92E1D013BDBB23246394634 -:1021700004F10C00FFF7B6FA0028D3DB2A7B013A02 -:10218000E2E7F98AC1F30901013B0529DAB253D824 -:10219000281D002307F11A0C9A4208D910F801EB08 -:1021A0000CF801E0013101330629DBB2F4D10399C7 -:1021B0000A9104990B91934207F11A010C9138BFCF -:1021C000043379680D9134BF55FA83F300230E93DD -:1021D000FB8AADF83EA0C3F309031A44069B8DF8B1 -:1021E00043300023ADF83C208DF840B08DF84160BD -:1021F0008DF842807B602A7BB88A013A291DFFF75F -:1022000027FA3B8BB882834203D1A3680AA92046F0 -:10221000984720460AA9FFF745FEFB7DB88AC3F31D -:102220008403013303F01F039B02FB823B8B984224 -:1022300014BF112000209DE67B68002BB7D006203C -:1022400001E01C306346D3F800C0BCF1000FF8D1A8 -:10225000091A081D05F1040C00EB030905989DF807 -:10226000143001EB000EBEF11B0FA0D89A429ED98C -:102270001CF8013B09F8013B059B01330593EDE791 -:102280006FF0090076E66FF00A0073E66FF00D005C -:1022900070E66FF00E006DE66FF00F006AE600BFAB -:1022A00080841E00404BF0B51C6C404E44F000741E -:1022B0001C641D6E45F000751D661B6E3C4B9B6AD1 -:1022C000D3F80052354045F00105C3F80052D3F869 -:1022D0000042344044EA002040F00100C3F800020C -:1022E000002952D00020C3F81C020546C3F804029E -:1022F000C3F80C02C3F8140203EBC00401301C281D -:10230000C4F84052C4F84452F6D100254FF0010CF5 -:1023100096781488F70748BFD3F804720CFA04F0D3 -:1023200044BF0743C3F80472B70742BFD3F80C7227 -:102330000743C3F80C72760742BFD3F81462064312 -:10234000C3F8146203EBC4045668C4F8406296688C -:10235000C4F84462D3F81C4201352043A942C3F8B3 -:102360001C0202F10C02D3D1D3F8002222F00102A8 -:10237000C3F800220C4B1A6C22F000721A641A6E19 -:1023800022F000721A661B6EF0BD0122C3F84012E3 -:10239000C3F84412C3F80412C3F81412C3F80C2291 -:1023A000C3F81C22E0E700BF003802400000FFFF36 -:1023B00078340020184A916A08B58B688B6013F056 -:1023C000010104D013F00C0F18BF4FF48031D80571 -:1023D00006D513F4406F14BF41F4003141F00201FF -:1023E000D80306D513F4402F14BF41F4802141F0E7 -:1023F0000401D3690BB108489847202383F311885F -:102400000648002100F0EEFD002383F31188BDE8AB -:10241000084001F0F7B800BF783400208034002075 -:1024200038B5124CA36ADD68AA0712D05A6922F0A7 -:1024300002025A61A36913B1012120469847202363 -:1024400083F311880A48002100F0CCFD002383F3B8 -:102450001188EB0606D5A36A1021D960236A0BB157 -:1024600002489847BDE8384001F0CCB878340020E5 -:102470008834002038B5124CA36A1D69AA0712D00F -:102480005A6922F010025A61A36913B10221204651 -:102490009847202383F311880A48002100F0A2FD09 -:1024A000002383F31188EB0606D5A36A1021196176 -:1024B000236A0BB102489847BDE8384001F0A2B842 -:1024C000783400208834002038B50F4CA36A5D684A -:1024D0005D602A070AD5042222701A6822F00202DF -:1024E0001A60636A13B10021204698476B0706D52E -:1024F000A36A9969236A13B1034809049847BDE8A0 -:10250000384001F07FB800BF7834002010B50E4C81 -:10251000204600F0CFF90D4BA3620B21132000F0F1 -:10252000B1F90B21142000F0ADF90B21152000F0BA -:10253000A9F90B21162000F0A5F90022BDE81040F2 -:1025400011460E20FFF7AEBE783400200064004034 -:10255000114B984210B5044609D1104B1A6C42F049 -:1025600000721A641A6E42F000721A661B6EA36A39 -:1025700001221A60A36A5A68D20707D562685168B7 -:102580001268D9611A60064A5A6110BD01210820FB -:1025900000F01EFCEEE700BF783400200038024057 -:1025A0005B87010003291AD8DFE801F0020A0F1443 -:1025B000836A9B6813F0E05F14BF0120002070471E -:1025C000836A9868C0F380607047836A9868C0F334 -:1025D000C0607047836A9868C0F30070704700203D -:1025E0007047000010B5032925D8DFE801F0022567 -:1025F000292D836A9968C1F30161183103EB011336 -:10260000107884064CBF54689488C0F300114FEAD8 -:10261000410148BF41EAC40100F00F004CBF41F046 -:10262000040141EA4451586041F001019068D268C8 -:102630009860DA60196010BD836A03F5C073DFE744 -:10264000836A03F5C873DBE7836A03F5D073D7E7C2 -:1026500001290AD002290FD081B9836ADA6892076A -:1026600001D1186903E001207047836AD86810F02F -:10267000030018BF01207047836AF2E7002070470B -:1026800010B539B9836AD96889071BD11B699C07C2 -:1026900004D110BD012915D00229FAD1816AD1F8DF -:1026A000C031D1F8C441D1F8C8011061D1F8CC01D2 -:1026B0005061202008610869800717D1486940F0FF -:1026C000100012E0816AD1F8B031D1F8B441D1F8EC -:1026D000B8011061D1F8BC0150612020C860C86801 -:1026E000800703D1486940F002004861C3F340000D -:1026F000C3F38001000140EA4111107920F030005D -:102700000143117189064BBF91681189DB085B0D8C -:102710004CBF63F31C0163F30A01137948BF916056 -:1027200064F3030313714FEA14234FEA144458BFB0 -:10273000118113705480ACE7024AD36843F0C003A0 -:10274000D360704700140140044B5A6810439A68E4 -:1027500058600AB1181D1047704700BFA43400200C -:102760002DE9F0413C4ED6F85C52EF682B68DA0553 -:102770009CB20CD5202383F311884FF40070FFF72F -:10278000E3FF6FF480732B60002383F31188202311 -:1027900083F31188DFF8C08014F02F0339D183F35D -:1027A0001188380613D5210611D5202383F311880B -:1027B0002A4800F001FA00284CDA0820FFF7C4FF8D -:1027C0004FF67F733B40EB60002383F311887A065A -:1027D00015D5630613D5202383F31188D6E9132377 -:1027E0009A4209D1336C3BB127F040073F041020D7 -:1027F0003F0CFFF7A9FFEF60002383F31188D6F8A1 -:102800006422D3680BB110699847BDE8F04100F02D -:10281000F9BE230712D014F0080F0CBF002080204F -:10282000E10748BF40F02000A20748BF40F0400049 -:10283000630748BF40F48070FFF786FFA4066B680B -:1028400005D596F860124046194000F057FA2C68FA -:10285000A4B2A1E76860B7E7A4340020DC3400200C -:1028600010B5054C054A0021204600F025FA044B1E -:10287000C4F85C3210BD00BFA43400203927000822 -:102880000014014000F1604303F561430901C9B23E -:1028900083F80013012200F01F039A4043099B00B4 -:1028A00003F1604303F56143C3F880211A60704768 -:1028B000FFF72CBE012300F10802C0E902220370D9 -:1028C00000F110020023C0E90422C0E90633C0E988 -:1028D000083343607047000010B52023044683F39B -:1028E0001188022303704160FFF732FE0423237036 -:1028F000002383F3118810BD2DE9F0411F460446E3 -:102900000D461646202383F3118800F1080823782A -:10291000052B0DD029462046FFF744FE40B1204646 -:1029200032462946FFF75EFE002080F3118808E05A -:102930003946404600F03AFB0028E8D0002383F3F4 -:102940001188BDE8F08100002DE9F0411F460446E2 -:102950000D461646202383F3118800F110082378D2 -:10296000052B0DD029462046FFF772FE40B12046C8 -:1029700032462946FFF784FE002080F3118808E0E4 -:102980003946404600F012FB0028E8D0002383F3CC -:102990001188BDE8F0810000F8B515468268066927 -:1029A000AA420B46816938BF8568761AB54204464B -:1029B0000BD218462A46FEF701FDA3692B44A361FA -:1029C000A3685B1BA3602846F8BD0CD918463246A5 -:1029D000FEF7F4FCAF1BE1683A463044FEF7EEFC2C -:1029E000E3683B44EBE718462A46FEF7E7FCE3685A -:1029F000E5E7000083689342F7B51546044638BF03 -:102A00008568D0E90460361AB5420BD22A46FEF733 -:102A1000D5FC63692B446361A36828465B1BA360F4 -:102A200003B0F0BD0DD932460191FEF7C7FC019904 -:102A3000E068AF1B3A463144FEF7C0FCE3683B4414 -:102A4000E9E72A46FEF7BAFCE368E4E710B50A4472 -:102A50000024C361029B8460C0E90000C0E9051145 -:102A6000C1600261036210BD08B5D0E9053293422E -:102A700001D1826882B98268013282605A1C426147 -:102A80001970D0E904329A4224BFC368436100211F -:102A900000F09CFA002008BD4FF0FF30FBE700007B -:102AA00070B5202304460E4683F31188A568A5B1AE -:102AB000A368A269013BA360531CA3611578226936 -:102AC000934224BFE368A361E3690BB120469847B2 -:102AD000002383F31188284607E03146204600F0A2 -:102AE00065FA0028E2DA85F3118870BD2DE9F74F09 -:102AF00004460E4617469846D0F81C904FF0200A20 -:102B00008AF311884FF0000B154665B12A4631460D -:102B10002046FFF741FF034660B94146204600F0DA -:102B200045FA0028F1D0002383F31188781B03B005 -:102B3000BDE8F08FB9F1000F03D001902046C847DF -:102B4000019B8BF31188ED1A1E448AF31188DCE790 -:102B5000C0E90511C160C3611144009B8260C0E9F6 -:102B60000000016103627047F8B504460D46164641 -:102B7000202383F31188A768A7B1A368013BA36052 -:102B800063695A1C62611D70D4E904329A4224BF01 -:102B9000E3686361E3690BB120469847002080F346 -:102BA000118807E03146204600F000FA0028E2DAFA -:102BB00087F31188F8BD0000D0E905239A4210B5CB -:102BC00001D182687AB98268013282605A1C8261BE -:102BD0001C7803699A4224BFC3688361002100F016 -:102BE000F5F9204610BD4FF0FF30FBE72DE9F74F18 -:102BF00004460E4617469846D0F81C904FF0200A1F -:102C00008AF311884FF0000B154665B12A4631460C -:102C10002046FFF7EFFE034660B94146204600F02C -:102C2000C5F90028F1D0002383F31188781B03B085 -:102C3000BDE8F08FB9F1000F03D001902046C847DE -:102C4000019B8BF31188ED1A1E448AF31188DCE78F -:102C5000026843681143016003B1184770470000E0 -:102C60001430FFF743BF00004FF0FF331430FFF77D -:102C70003DBF00003830FFF7B9BF00004FF0FF3311 -:102C80003830FFF7B3BF00001430FFF709BF000072 -:102C90004FF0FF311430FFF703BF00003830FFF76B -:102CA00063BF00004FF0FF323830FFF75DBF000018 -:102CB00000207047FFF7D4BD37B515460E4A0260B5 -:102CC00000224260C0E902220122044602740B463F -:102CD000009000F15C014FF480721430FFF7B6FEF3 -:102CE00000942B464FF4807204F5AE7104F1380065 -:102CF000FFF72EFF03B030BD083D000838B5C369AB -:102D000004460D461BB904210844FFF7A1FF2946DC -:102D100004F11400FFF7A8FE002806DA201D4FF486 -:102D20008061BDE83840FFF793BF38BD024B0022F9 -:102D3000C3E900339A6070470C3700200023037406 -:102D40008268054B1B6899689142FBD25A68036000 -:102D500042601060586070470C37002008B520238F -:102D600083F31188037C032B05D0042B0DD02BB9E2 -:102D700083F3118808BD436900221A604FF0FF33C6 -:102D80004361FFF7DBFF0023F2E7D0E90032136075 -:102D90005A60F3E7002303748268054B1B68996847 -:102DA0009142FBD85A6803604260106058607047D7 -:102DB0000C370020054B19690874186802681A60FE -:102DC0005360186101230374FDF722BC0C37002007 -:102DD00030B54B1C0B4D87B0044610D02B690A4A06 -:102DE00001A800F01BF92046FFF7E4FF049B13B194 -:102DF00001A800F04FF92B69586907B030BDFFF703 -:102E0000D9FFF8E70C3700205D2D000838B50C4DD0 -:102E100041612B6981689A689142044603D8BDE8F4 -:102E20003840FFF78BBF1846FFF7B4FF01232C6132 -:102E3000014623742046BDE83840FDF7E9BB00BFDA -:102E40000C370020044B1A681B6990689B689842F5 -:102E500094BF0020012070470C37002010B5084CAB -:102E6000236820691A6822605460012223611A7461 -:102E7000FFF790FF01462069BDE81040FDF7C8BB91 -:102E80000C37002008B5FFF7DDFF18B1BDE808409A -:102E9000FFF7E4BF08BD0000FFF7E0BFFEE700005A -:102EA00010B50C4CFFF742FF00F0AAF80A49802247 -:102EB000204600F031F8012344F8180C037400F0A8 -:102EC0007DFB002383F3118862B60448BDE81040FF -:102ED00000F042B834370020303D0008403D000883 -:102EE00000F012B9EFF3118020B9EFF3058320222F -:102EF00082F311887047000010B530B9EFF30584F4 -:102F0000C4F3080414B180F3118810BDFFF7BAFFB1 -:102F100084F31188F9E70000826002220282704780 -:102F20008368A3F17C0243F80C2C026943F83C2C23 -:102F3000426943F8382C074A43F81C2CC26843F80E -:102F4000102C022203F8082C002203F8072CA3F10E -:102F5000180070472906000810B5202383F3118854 -:102F6000FFF7DEFF00210446FFF750FF002383F345 -:102F70001188204610BD0000024B1B6958610F20CC -:102F8000FFF718BF0C370020202383F31188FFF7C9 -:102F9000F3BF000008B50146202383F31188082001 -:102FA000FFF716FF002383F3118808BD49B1064BD4 -:102FB00042681B6918605A60136043600420FFF781 -:102FC00007BF4FF0FF3070470C370020036898426E -:102FD00006D01A680260506059611846FFF7AEBE0D -:102FE0007047000038B504460D462068844200D181 -:102FF00038BD036823605C604561FFF79FFEF4E71E -:10300000054B03F11402C3E905224FF0FF31002202 -:10301000C3E90712704700BF0C37002070B51C4E83 -:10302000C0E9032305460C4600F04EFB334653F837 -:10303000142F9A420DD13062C5E901242A600A2C6E -:103040002CBF00190A30C6E90555BDE8704000F0F4 -:1030500029BB316A431AE31838BF1C469368A34260 -:1030600002D9081900F02CFB73699A6894420CD8B5 -:103070005A68AC602B606A6015609A685D60121BCC -:103080009A604FF0FF33F36170BD1B68A41AECE740 -:103090000C37002038B51B4C636998420DD0D0E93D -:1030A000003213605A6000228168C2609A680A4444 -:1030B0009A604FF0FF33E36138BD2246036842F85F -:1030C000143F002193425A60C16003D1BDE83840EB -:1030D00000F0F0BA9A688168256A0A449A6000F0A4 -:1030E000F3FA63699A68411B8A42E5D9AB181D1A45 -:1030F000092D206A98BF01F10A02BDE8384010444A -:1031000000F0DEBA0C3700202DE9F041184C002702 -:1031100004F11406656900F0D7FA236AAA68C11A97 -:103120008A4215D813442362D5E9003213605A60ED -:103130006369D5F80C80EF60B34201D100F0BAFAB0 -:1031400087F311882869C047202383F31188E1E7BA -:103150006169B14209D013441B1ABDE8F0410A2B42 -:103160002CBFC0180A3000F0ABBABDE8F08100BF38 -:103170000C37002000207047FEE700007047000079 -:103180004FF0FF3070470000BFF34F8F024AD36803 -:10319000DB03FCD4704700BF003C024008B5094B7C -:1031A0001B7873B9FFF7F0FF074B1A69002ABFBFFE -:1031B000064A5A6002F188325A601A6822F4806224 -:1031C0001A6008BDC8380020003C02402301674552 -:1031D00008B50B4B1B7893B9FFF7D6FF094B1A695B -:1031E00042F000421A611A6842F480521A601A686A -:1031F00022F480521A601A6842F480621A6008BD94 -:10320000C8380020003C02400728F0B516D80C4C06 -:103210000C4923787BB90C4D0E4608234FF0006211 -:1032200055F8047B46F8042B013B13F0FF033A44A6 -:10323000F6D10123237051F82000F0BD0020FCE7F7 -:10324000EC380020CC380020583D0008014B53F8E2 -:1032500020007047583D000808207047072810B527 -:10326000044601D9002010BDFFF7CEFF064B53F8EE -:1032700024301844C21A0BB90120F4E71268013255 -:10328000F0D1043BF6E700BF583D0008072810B511 -:10329000044621D8FFF778FFFFF780FF0F4AF3239A -:1032A000D360C300DBB243F4007343F00203136145 -:1032B000136943F480331361FFF766FFFFF7A4FF40 -:1032C000074B53F8241000F02BF9FFF781FF20463D -:1032D000BDE81040FFF7C2BF002010BD003C024017 -:1032E000583D0008F8B512F00103144642D1851884 -:1032F0002E4A954257D82E4B1B6813F0010352D02B -:103300002C4DFFF74BFFF323EB60FFF73DFF40F23F -:103310000127032C15D824F001046618254C401A07 -:1033200040F20117B142236900EB010524D123F0DB -:1033300001032361FFF74CFF0120F8BD043C04307A -:10334000E7E78307E7D12B6923F440732B612B69EF -:103350003B432B6151F8046B0660BFF34F8FFFF7BF -:1033600013FF03689E42E9D02B6923F001032B6110 -:10337000FFF72EFF0020E0E723F440732361236969 -:103380003B4323610B882B80BFF34F8FFFF7FCFE7D -:103390002D8831F8023BADB2AB42C3D0236923F094 -:1033A00001032361E4E71846C7E700BFFFFF0708F2 -:1033B00000380240003C0240084908B50B7828B1AB -:1033C0001BB9FFF7EBFE01230B7008BD002BFCD0EF -:1033D000BDE808400870FFF7FBBE00BFC8380020FA -:1033E00070B582B0FFF77EFD0E4E054600F06CF919 -:1033F0003268904237BF0C4A0B49516814682EBF9F -:10340000D1E90041013151600419034641F1000145 -:10341000284601913360FFF76FFD0199204602B005 -:1034200070BD00BFF0380020F838002070B582B0C1 -:10343000FFF758FD104E054600F046F932689042FD -:1034400037BF0E4A0D49516814682EBFD1E90041BB -:1034500001315160041941F10001034628460191F0 -:103460003360FFF749FD01994FF47A72002320463B -:10347000FCF7B6FE02B070BDF0380020F83800202E -:1034800010B50244064BD2B2904200D110BD441C8C -:1034900000B253F8200041F8040BE0B2F4E700BF9B -:1034A000502800400F4B30B51C6F240407D41C6F0C -:1034B00044F400741C671C6F44F400441C670A4CFD -:1034C000236843F4807323600244084BD2B29042D5 -:1034D00000D130BD441C00B251F8045B43F82050C9 -:1034E000E0B2F4E70038024000700040502800408D -:1034F00007B5012201A90020FFF7C2FF019803B020 -:103500005DF804FB13B50446FFF7F2FFA04205D0B7 -:10351000012201A900200194FFF7C4FF02B010BDF1 -:1035200070470000074B45F255521A6002225A605C -:1035300040F6FF729A604CF6CC421A60024B0122B0 -:103540001A7070470030004001390020034B1B788F -:103550001BB1034B4AF6AA221A60704701390020BA -:1035600000300040044BD3F874389B0042BF034B3B -:1035700001221A70704700BF00300240003900205D -:10358000024B4FF08072C3F874287047003002403D -:10359000014B1878704700BF00390020EFF3098312 -:1035A00005494A6B22F001024A63683383F30988B4 -:1035B000002383F31188704700EF00E0202080F3A0 -:1035C000118862B60C4B0D4AD96821F4E0610904F8 -:1035D000090C0A43DA60D3F8FC20094942F08072F2 -:1035E000C3F8FC200A6842F001020A601022DA7770 -:1035F00083F82200704700BF00ED00E00003FA05E9 -:10360000001000E010B5202383F311880E4B5B6897 -:1036100013F4006314D0F1EE103AEFF30984683C20 -:103620004FF08073E361094BDB6B236684F30988F9 -:10363000FFF708FC10B1064BA36110BD054BFBE77B -:1036400083F31188F9E700BF00ED00E000EF00E030 -:103650003B0600083E06000870470000FEE7000039 -:103660000A4B0B480B4A90420BD30B4BDA1C121A35 -:10367000C11E22F003028B4238BF00220021FDF759 -:10368000AFBE53F8041B40F8041BECE77C3E000877 -:1036900084390020843900208439002070470000DC -:1036A00000F080B84FF08043002258631A61022274 -:1036B000DA6070474FF080430022DA607047000004 -:1036C0004FF08043586370474FF08043586A70470B -:1036D0004B6843608B688360CB68C3600B69436150 -:1036E0004B6903628B6943620B680360704700009B -:1036F00008B5234B23481A6942F0FF021A611A6980 -:1037000022F0FF021A611A691A6B42F0FF021A6373 -:103710001A6D42F0FF021A651B4A1B6D1146FFF736 -:10372000D7FF02F11C0100F58060FFF7D1FF02F125 -:10373000380100F58060FFF7CBFF02F1540100F57E -:103740008060FFF7C5FF02F1700100F58060FFF7B0 -:10375000BFFF02F18C0100F58060FFF7B9FF02F1B5 -:10376000A80100F58060FFF7B3FF02F1C40100F586 -:103770008060FFF7ADFFBDE8084000F097B800BFDC -:103780000038024000000240783D000808B500F013 -:1037900009FAFFF785FBBDE80840FFF7E3BE00002C -:1037A00070470000104B1A6C42F001021A641A6E46 -:1037B00042F001021A660D4A1B6E936843F0010342 -:1037C00093604FF080432F229A624FF0FF32DA620B -:1037D00000229A615A63DA605A6001225A61082114 -:1037E0001A601C20FFF74EB800380240002004E0A9 -:1037F0004FF0804208B51169D3680B40D9B2C94374 -:103800009B07116107D5202383F31188FFF768FB1D -:10381000002383F3118808BD08B5FFF7E9FFBDE871 -:103820000840FFF7EFBE00001E4B1A6962F0FF026E -:103830001A611A69D2B21A614FF0FF301A695A69D7 -:10384000586100215A6959615A691A6A62F08052B6 -:103850001A621A6A02F080521A621A6A5A6A586226 -:103860005A6A59625A6A1A6C42F080521A641A6E85 -:1038700042F080521A661A6E0B4A106840F480704B -:103880001060186F00F44070B0F5007F1EBF4FF459 -:10389000803018671967536823F40073536000F091 -:1038A00061B900BF0038024000700040354B364A15 -:1038B0001A64364A4FF4404111601A6842F001021E -:1038C0001A601A689107FCD59A6822F003029A6080 -:1038D0002C4B9A6812F00C02FBD1196801F0F90127 -:1038E00019609A601A6842F480321A601A6892036A -:1038F000FCD55A6F42F001025A67224B5A6F90076B -:10390000FCD5234A5A601A6842F080721A601F4A36 -:1039100053685904FCD51B4B1A689201FCD51D4A0B -:103920009A600322C3F88C200022C3F894201A4B1B -:103930001A681A4B9A421A4B21D11A4A11681A4A2C -:1039400091421CD140F203121A60154A136803F029 -:103950000F03032BFAD10B4B9A6842F002029A60D4 -:103960009A6802F00C02082AFAD15A6C42F480429A -:103970005A645A6E42F480425A665B6E704740F257 -:103980000372E1E7003802400004001000700040BC -:103990001060410800948838002004E01164002081 -:1039A000003C024000ED00E041C20F41084A08B56A -:1039B000516913680B4003F00103536123B1054AB9 -:1039C00013680BB150689847BDE80840FFF71ABE6E -:1039D000003C014004390020084A08B551691368C9 -:1039E0000B4003F00203536123B1054A93680BB106 -:1039F000D0689847BDE80840FFF704BE003C01408E -:103A000004390020084A08B5516913680B4003F0D7 -:103A10000403536123B1054A13690BB150699847F8 -:103A2000BDE80840FFF7EEBD003C0140043900202E -:103A3000084A08B5516913680B4003F00803536145 -:103A400023B1054A93690BB1D0699847BDE8084096 -:103A5000FFF7D8BD003C014004390020084A08B5F2 -:103A6000516913680B4003F01003536123B1054AF9 -:103A7000136A0BB1506A9847BDE80840FFF7C2BD12 -:103A8000003C014004390020174B10B55A691C68EE -:103A9000144004F478725A61A30604D5134A936A59 -:103AA0000BB1D06A9847600604D5104A136B0BB16E -:103AB000506B9847210604D50C4A936B0BB1D06B21 -:103AC0009847E20504D5094A136C0BB1506C98472E -:103AD000A30504D5054A936C0BB1D06C9847BDE89B -:103AE0001040FFF78FBD00BF003C014004390020AB -:103AF0001A4B10B55A691C68144004F47C425A6190 -:103B0000620504D5164A136D0BB1506D9847230515 -:103B100004D5134A936D0BB1D06D9847E00404D5DA -:103B20000F4A136E0BB1506E9847A10404D50C4A8E -:103B3000936E0BB1D06E9847620404D5084A136F98 -:103B40000BB1506F9847230404D5054A936F0BB10E -:103B5000D06F9847BDE81040FFF754BD003C0140CE -:103B600004390020062108B50846FEF78BFE062121 -:103B70000720FEF787FE06210820FEF783FE0621B8 -:103B80000920FEF77FFE06210A20FEF77BFE0621B4 -:103B90001720FEF777FEBDE8084006212820FEF733 -:103BA00071BE000008B5FFF73FFE00F00BF8FEF70E -:103BB0007FFEFFF77FF8FFF7F3FDBDE80840FFF752 -:103BC0006FBD00000023054A19460133102BC2E9DE -:103BD000001102F10802F8D1704700BF043900203B -:103BE00010B501390244904201D1002005E003786C -:103BF00011F8014FA34201D0181B10BD0130F2E7AC -:103C00002DE9F041A3B1C91A17780144044603F124 -:103C1000FF3C8C42204601D9002009E00578BD42D6 -:103C200004F10104F5D10CEB0405D618A54201D12D -:103C3000BDE8F08115F8018D16F801EDF045F5D0DD -:103C4000E7E70000034611F8012B03F8012B002AD7 -:103C5000F9D170476F72672E6172647570696C6F0D -:103C6000742E6269726463616E6479004E6F2061C4 -:103C70007070207369670A00426164206677206C67 -:103C8000656E6774682025750A0042616420626F62 -:103C90006172645F69642025752073686F756C6458 -:103CA0002062652025750A004261642066772064E1 -:103CB000657363726970746F72206C656E67746887 -:103CC0002025750A004261642061707020435243D0 -:103CD000203078253038783A3078253038782030E0 -:103CE00078253038783A3078253038780A00476FB0 -:103CF0006F64206669726D776172650A0040A2E4A4 -:103D0000F164689106000000000000007D2C0008AE -:103D1000692C0008A52C0008912C00089D2C000897 -:103D2000892C0008752C0008612C0008B12C0008B3 -:103D30006D61696E0000000069646C650000000040 -:103D4000383D000850370020C8380020010000002E -:103D50009D2E000800000000004000000040000010 -:103D600000400000004000000000010000000200D0 -:103D700000000200000002000004802A0000000091 -:103D8000AAAAAAAA00004001DFFF0000000000006C -:103D90000080080010000A00000000009AAAAAAAE9 -:103DA00000000000FBFF0000000000008800000091 -:103DB0000000000000000000AAAAAAAA000000005B -:103DC000FFFF0000000000000000000000000000F5 -:103DD00000000000AAAAAAAA00000000FFFF00003D -:103DE00000000000000000000000000000000000D3 -:103DF000AAAAAAAA00000000FFFF0000000000001D -:103E0000000000000000000000000000AAAAAAAA0A -:103E100000000000FFFF00000000000000000000A4 -:103E20000000000000000000AAAAAAAA00000000EA -:103E3000FFFF000000000000000000000000000084 -:103E4000000000000A000000000000000300000065 -:103E50000000000000000000B8C3FF7F0100000068 -:103E600014040000000000000000070064000000CF -:0C3E700000000000FE2A0100D204000047 +:10063000A047002002F07EFDFEE702F003FD00DF90 +:10064000FEE700002DE9F04103F03CF8074603F017 +:1006500087F80546C0BB284B9F4235D001339F42E7 +:1006600035D0264B27F0FF029A4234D1F8B200F081 +:1006700049FAA84642F2107400F04EFC08B100247A +:10068000A04600F045FA064648B354BB464635B18D +:100690001B4B9F4203D003F05BF80024264600204A +:1006A00003F01AF80EB100F02DF800F093FC00F002 +:1006B00079FE00F07BFF0546B4B900F03DFD4FF434 +:1006C0007A7002F03DFDF7E7A8460024D4E704461F +:1006D0004FF00108D0E780464FF47A74CCE7044627 +:1006E000D5E74FF47A74D2E700F060FF431BA342D2 +:1006F000E3D900F007F8DCE7010007B0000008B01C +:10070000263A09B01E4B1F4A10B51C461968013124 +:1007100034D004339342F9D162681B4B9A422DD9ED +:100720001A4B9B6803F1006303F580339A4225D28C +:1007300002F0E2FF02F0F4FF002000F04DFE144B47 +:100740000220187000F084FE124B1A6C00221A640A +:10075000196E1A66196E596C5A64596E5A665B6E38 +:1007600072B64FF0E0232021C3F8084DD4E90032DF +:1007700081F311889D4683F30888104710BD00BFA0 +:100780000000010820000108FFFF000800230020EE +:100790002823002000380240094A136849F2690002 +:1007A00099B21B0C00FB01331360064B186844F22E +:1007B000506182B2000C01FB0200186080B27047E9 +:1007C000202300201C23002010B500211022044605 +:1007D00000F05AFE034B03CB206061601868A060F4 +:1007E00010BD00BF107AFF1F2DE9F043224DBBB0B2 +:1007F00000F0DCFEAB6840F2ED22C31A934232D91E +:1008000006AFA8602B4628220021384601F0DCFB09 +:1008100005F10E0000F030FE002604465FFA80F974 +:1008200005F10E08F3B2F100994501F1280107D94D +:1008300008EB06030822384601F0C6FB0136F1E753 +:1008400008230122CDE9023205340C4B0193A4B2F6 +:1008500030230093CDE9047405A3D3E90023297B59 +:10086000074801F0C9F93BB0BDE8F083AFF3008061 +:1008700078F6339F93CACD8D703300207D330020EE +:100880004433002070B50D4614461E4601F04AF967 +:1008900050B9022E10D1012C0ED112A3D3E900239E +:1008A000C5E90023012007E0282C10D005D8012C31 +:1008B00009D0052C0FD0002070BD302CFBD10BA32C +:1008C000D3E90023ECE70BA3D3E90023E8E70BA36C +:1008D000D3E90023E4E70BA3D3E90023E0E700BF5B +:1008E000AFF30080401DA12026812A0B78F6339FAC +:1008F00093CACD8D9E6AC421818A46EE26417272CA +:10090000DF25D7B7F017304A39059E5613B5044690 +:100910002346084620220021019001F055FB227950 +:100920000198032A234628BF032203F8042F20211D +:10093000022201F049FB62790198072A234628BF69 +:10094000072203F8052F2221032201F03DFBA279A3 +:100950000198072A234628BF072203F8062F2521DE +:10096000032201F031FB019804F108031022282131 +:1009700001F02AFB382002B010BD00002DE9F04F35 +:10098000FFB01FAD0CAE40F2751280460F4620A896 +:100990000021296000F078FD48220021304600F057 +:1009A00073FD00F003FE554B4FF47A72B0FBF2F08A +:1009B000186093E80700012386E807000DF1520054 +:1009C0003382FFF701FF41F20443338406AB18463C +:1009D0004B4903F03BFA172230642946304686F82B +:1009E0003C20FFF793FF10AB04460146082228463F +:1009F00001F0EAFA0822A1180DF14103284601F09E +:100A0000E3FA0DF14203082204F11001284601F037 +:100A1000DBFA11AB202204F11801284601F0D4FAC8 +:100A200012AB402204F13801284601F0CDFA14AB94 +:100A3000082204F17801284601F0C6FA0DF15103AD +:100A4000082204F18001284601F0BEFA04F1880A68 +:100A50000DF1520904F5847B4B4651460822284685 +:100A60000AF1080A01F0B0FAD34509F10109F3D1FE +:100A700019AB08225946284601F0A6FA04F58874F5 +:100A80004FF0000996F834304B450AD9B36B214634 +:100A90004B440822284601F097FA083409F101096D +:100AA000F0E74FF0000996F83C304B4504EBC901E4 +:100AB00008D9336C08224B44284601F085FA09F125 +:100AC0000109F0E700230393BB7E0293073107F18E +:100AD00019030193C1F3CF010123CDE90451009320 +:100AE000F97E04A3D3E90023404601F085F87FB0E6 +:100AF000BDE8F08F9E6AC421818A46EE2C23002037 +:100B00005C3E0008014B1870704700BF382300207E +:100B1000F0B5334B1C7B85B034B1324B0E221A81B9 +:100B20000024204605B0F0BD2F4A1068516802AB82 +:100B300003C308232D492E480DEB030203F064F98B +:100B4000054630B9274B2B480A221A8100F0E8FCF1 +:100B5000E6E70169B1F5E02F06D9224B26480B22C2 +:100B60001A8100F0DDFCDCE7438B40F21442934233 +:100B700007D01C490C2008811946204800F0D0FC01 +:100B8000CFE71F4A024402F11003994204D2154BE9 +:100B90001C4810221A81E4E710398E1A20461449A5 +:100BA00000F008FD3246074605F11801204600F026 +:100BB00001FDAB689F4202D1EB6898420AD0094B15 +:100BC0000D221A810090D5E902123B460E4800F032 +:100BD000A7FCA5E70D4800F0A3FC0124A1E700BF96 +:100BE000703300202C230020053F0008DCFF0600A6 +:100BF00000000108743E0008803E0008923E000894 +:100C00000800FFF7B03E0008CD3E0008F63E0008A1 +:100C10002DE9F04FADB006AF80460C4600F082FFE4 +:100C2000054600285AD1237E022B1BD1E38A012BD3 +:100C300018D100F0BBFC0646FFF7AEFD03464FF4AB +:100C4000C870DFF8D092B3FBF0F206F5167602FB1F +:100C5000103316FA83F3C9F80030E37E33B9A84B9A +:100C600000221A709C37BD46BDE8F08FA38AEEB211 +:100C7000013BB34205F101050BD93B1D1E44E900C0 +:100C800000960023082201F0F801204601F060F8E8 +:100C9000ECE707F11400FFF797FD324607F1140166 +:100CA000381D03F0A1F80028D9D10F2E08D8944B95 +:100CB0001E70D9F80030A3F51673C9F80030D1E7DB +:100CC000FB1CF8700146009307220346204601F002 +:100CD0003FF8F978404600F01DFFC3E7E38A282B70 +:100CE00026D010D8012B1ED0052BBBD1BFF34F8FC0 +:100CF0008449854BCA6802F4E0621343CB60BFF3BA +:100D00004F8F00BFFDE7302BACD1637E7F4D0133A9 +:100D10006A7BDBB29342E94603D1E27E2B7B9A42A7 +:100D200065D0CD469EE721464046FFF727FE99E76E +:100D3000A38A013B9BB2C92B94D8744D2E7B26BB52 +:100D400005F10C030093082233463146204600F09B +:100D5000FFFF731CF2B2D9001E46A38A013B9A42E0 +:100D600005DA0E322A44009200230822EEE700231F +:100D70000022C5E900230023AB6085F8D730C5F811 +:100D8000D8302B7B0BB9E37E2B73002507F11409B8 +:100D90003B1D082229464846C7E90155FD6001F080 +:100DA00013F93B7A05F1010AAB424FEACA0608D9AA +:100DB000FB6808222B443146484601F005F95546A8 +:100DC000EFE7C6F3CF06E17ECDE904960023039357 +:100DD000A37E0293193428230093019446A3D3E9F8 +:100DE0000023404600F008FFFFF7FEFC3AE74FF013 +:100DF000000807F11403A7F814801022009341465D +:100E00000123204600F0A4FFA68A023EB6B2F31CDE +:100E10009B109B000733DB08A9EBC3039D460DF134 +:100E2000180A1FFA88F34FEAC801B34201F1100112 +:100E30000AD20AEB0803009308220023204600F0A0 +:100E400087FF08F10108ECE795F8D70000F0CEFA2B +:100E5000D5F8D83004461BB995F8D70000F0D6FA7B +:100E6000D5F8D83033449C4204D295F8D7000130ED +:100E700000F0CCFA4FEA960B4FF000081FFA88F109 +:100E80008B45D5E9003209D90AEB880103EB8800CC +:100E9000012200F001FB08F10108EFE7F31842F12D +:100EA0000002C5E90032D5F8D83095F8D70006EB36 +:100EB0000308C5F8D88000F099FA804509D395F861 +:100EC000D730D5F8D8000133001B85F8D730C5F8E6 +:100ED000D800FF2E08D800232B7300F0A9FAFFF7E3 +:100EE00017FE08B1FFF70EFC2B68094A9B0A013375 +:100EF00013810023AB6014E726417272DF25D7B758 +:100F00003D33002000ED00E00400FA0570330020BE +:100F10002C2300204033002030B54FF00054244BE8 +:100F200022689A4285B007D002F024FC0446A8B992 +:100F30000024204605B030BD1E4B627D1A701E484D +:100F4000237D03731D49C9220E3000F08BFA204621 +:100F5000E022002100F098FA0124EAE7184A194D2E +:100F6000136C43F000731364AA6D174B9A42DFD1E0 +:100F70002B6E013B7E2BDBD8144A07CA01AB83E8FA +:100F800007001846032100F02BFB6B6D83424FF0E6 +:100F90000003CDD12A6D8A4201BFAB65054B2A6E95 +:100FA0001A7003BF0A4BEA6D1A601C46C1E700BF06 +:100FB0009AAD44C53823002070330020160000206D +:100FC00000380240006600405041A0B05866004022 +:100FD000182300202DE9FF474B4C022363710023A7 +:100FE00002934A4BD3F800C0BCF57A7F12D3484B2A +:100FF000484FB7FBFCF69C458CBF0A231123581EB3 +:10100000B6FBF3F503FB1562C1B2002A3ED00228FD +:101010000346F4D89DF80B303F4940485A1E9DF8CE +:101020000A30013B1B0443EA0253BDF80820013A91 +:1010300013434B6001F026FD00230193384B3949DF +:1010400000933948394B4FF4805200F03DFD384B46 +:10105000197811B1344800F05DFD00F0A7FA05469B +:10106000FFF79AFB4FF4C873B0FBF3F202FB1303D4 +:1010700005F5167010FA83F02E4B186002F070FB25 +:1010800008B10F23238104B0BDE8F0876B1EB3F5D0 +:10109000806FBFD2C1EBC10E0EF103034FEAE3092B +:1010A000C3F3C703A1EB030809F1010A4FF47A70F7 +:1010B0005FFA88F609FB00005AFA88F8B0FBF8F0EE +:1010C000B0F5617F08D90EF1FF33C3F3C703C91A26 +:1010D000CEB2591E0F2914D8721E072A8CBF0022C7 +:1010E0000122991901FB0551B7FBF1F7BC4591D1DC +:1010F000002A8FD0ADF808508DF80A308DF80B60BB +:1011000088E71346EDE700BF2C23002018230020BA +:101110003F420F0040787D011023002088340020DA +:10112000850800083C23002044330020110C0008EF +:1011300038230020403300202DE9F04F91A7D7E954 +:1011400000670FF24829D9E90089874D93B0DFF88D +:1011500044B2864C284600F0B3FD0DF1300A0790EA +:1011600070B310220021504600F08EF9079B197BC6 +:101170004FF0000261F303028DF83020586899683F +:101180000EAA03C21B680D9A63F31C029DF830304F +:101190000D9243F020038DF830300023524619465B +:1011A000584601F07FFC079028B9284600F08CFDD6 +:1011B000079B2370CEE72378072B3CD8013323709D +:1011C00018220021504600F05FF9DFF8C8B1684CE2 +:1011D000002319465246584601F08CFC014670BB6C +:1011E000102208A800F050F9636983F020036361BE +:1011F00000F0DEF90B4612A9024611E903000DF1D9 +:10120000240C8CE803009DF83410C1F30300890618 +:101210004CBF0E99BDF838C08DF82C0046BFC1F305 +:101220001C0C4CF00041CCF30A010891284608A997 +:1012300000F012FFCCE7284600F046FDC0E7284644 +:1012400000F070FC0446002848D1DFF84CB100F0F3 +:10125000ADF9DBF80030984240D300F0A7F90790D1 +:10126000FFF79AFA079A8DF8204003464FF4C870AA +:1012700002F51672B3FBF0F101FB103312FA83F39F +:10128000CBF80030DFF814B19BF8001011B901233E +:101290008DF8203050460791FFF796FA0799C1F173 +:1012A0001004E4B2062C28BF0624224651440DF156 +:1012B000210000F0D7F808AB039318230293013400 +:1012C0002C4B0193E4B20123009304943B46324635 +:1012D000284600F029FC00238BF8003000F066F966 +:1012E000254A264C1368C31AB3F57A7F31D31060B0 +:1012F00000F05EF902460B46284600F0EFFC284657 +:1013000000F010FC28B3237BDFF894B0002B14BF4F +:10131000032302238BF8053000F048F94FF47A7369 +:101320005146B0FBF3F0CBF800005846FFF7EEFA59 +:10133000182307300293124B0193C0F3CF0040F201 +:101340005513CDE903A0009342464B46284600F0D2 +:10135000EBFB237B2BB1FFF747FA237B002B7FF4BA +:10136000F6AE13B0BDE8F08F4433002055340020B2 +:10137000000002403C330020503400207033002035 +:1013800054340020401DA12026812A0BF1C6A7C19C +:10139000D068080F88340020403300203D330020FF +:1013A0002C23002070B502F02DF8094E094D308035 +:1013B000002428683388834208D902F01DF82B687E +:1013C00004440133B4F5803F2B60F2D370BD00BFFD +:1013D000843400205834002002F0D8B800F10060B6 +:1013E000920000F5803002F05BB80000054B1A68EF +:1013F000054B1B889B1A834202D9104401F0FCBFA5 +:1014000000207047583400208434002038B5074D40 +:1014100004462868204401F0F7FF28B928682044D2 +:10142000BDE8384002F008B838BD00BF583400208D +:10143000064991F8243033B10023086A81F824303A +:101440000822FFF7CBBF0120704700BF5C340020AB +:10145000022802BF024B4FF400129A61704700BF8E +:101460000000024010B50023934203D0CC5CC4546A +:101470000133F9E710BD000003460246D01A12F905 +:10148000011B0029FAD1704702440346934202D05F +:1014900003F8011BFAE770472DE9F8431F4D144686 +:1014A00095F824200746884652BBDFF870909CB31D +:1014B00095F824302BB92022FF2148462F62FFF7F0 +:1014C000E3FF95F82400C0F10802A24228BF22469B +:1014D000D6B24146920005EB8000FFF7C3FF95F8B6 +:1014E0002430A41B1E44F6B2082E17449044E4B2E4 +:1014F00085F82460DBD1FFF79BFF0028D7D108E0F7 +:101500002B6A03EB82038342CFD0FFF791FF0028C1 +:10151000CBD10020BDE8F8830120FBE75C3400203C +:101520000FB4002004B0704700B59BB0EFF3098101 +:1015300068226846FFF796FFEFF30583044B9A6B2A +:10154000DA6A9A6A9A6A9A6A9A6A9A6A9B6AFEE759 +:1015500000ED00E000B59BB0EFF30981682268461A +:10156000FFF780FFEFF30583044B9A6B9A6A9A6A40 +:101570009A6A9A6A9A6A9B6AFEE700BF00ED00E0E9 +:1015800000B59BB0EFF3098168226846FFF76AFF58 +:10159000EFF30583034B5A6B9A6A9A6A9A6A9A6ABE +:1015A0009B6AFEE700ED00E0FEE7000002F028B8CD +:1015B00002F000B830B5094D0A4491420DD011F83F +:1015C000013B5840082340F30004013B2C4013F03A +:1015D000FF0384EA5000F6D1EFE730BD2083B8ED79 +:1015E000F7B54FF0FF33DFF854C0DFF854E000EBFD +:1015F00081011A4688421CD050F8044B019401AF77 +:10160000042417F8015B82EA05620825DB181646F8 +:1016100005F1FF355241002EBCBF83EA0C0382EA7C +:101620000E0215F0FF05F1D1013C14F0FF04E8D1E2 +:10163000E0E7D843D14303B0F0BD00BF9336EAA939 +:10164000EBE1F0422DE9F041C56915B9C161BDE892 +:10165000F0814B6823F06047C3F38A464FEAD37E9C +:10166000C3F3807816EA230638BF3E46AC462B46C5 +:101670005A68BEEBD27F22F060440AD0002A18DA02 +:10168000A40CB44217D19D420FD10D60DEE7134682 +:10169000EEE7A74207D102F08044C2F380724245D0 +:1016A0000BD054B1EFE708D2EDE7CCF800100B6097 +:1016B000CDE7B44201D0B442E5D81A689C46002A6E +:1016C000E5D11960C3E700002DE9F047089D01F05E +:1016D00007044FEAD508224405F0070500EBD100C6 +:1016E0004FF47F49944201D1BDE8F08704F0070729 +:1016F00005F0070A57453E4638BF5646C6F108066C +:10170000111B8E4228BF0E46E10808EBD50E415C46 +:1017100013F80EC0B94029FA06F721FA0AF1FFB210 +:101720008CEA010147FA0AF739408CEA010C03F808 +:101730000EC034443544D5E780EA0120082341F245 +:10174000210201B24000002980B203F1FF33B8BF8B +:10175000504013F0FF03F4D17047000038B50C4639 +:101760008D18A54200D138BD14F8011BFFF7E4FF26 +:10177000F7E7000002684AB113680360C388018973 +:1017800001339BB29942C38038BF03811046704732 +:1017900070B588B0202204460D4668460021FFF748 +:1017A00073FE20460495FFF7E5FF024658B16B46ED +:1017B000054608AE1C4603CCB44228606960234647 +:1017C00005F10805F6D1104608B070BD082817D9F4 +:1017D00009280CD00A280CD00B280CD00C280CD0CF +:1017E0000D280CD00E2814BF4020302070470C204C +:1017F0007047102070471420704718207047202031 +:1018000070470000082817D90C280CD910280CD9CB +:1018100014280CD918280CD920280CD930288CBFB2 +:101820000F200E207047092070470A2070470B20B8 +:1018300070470C2070470D207047000010B54B68B2 +:1018400023B9CA8A63F30902CA8210BDC4681A6840 +:101850001C60C360438A013B43824A60EFE700009B +:101860002DE9F84F1D46CB8A0F46C3F3090106291F +:10187000814692460B4630D00020AAB207F11904E7 +:101880009EB2052E1FFA80F80FD8904503F1010390 +:1018900006D3FB8A0A4462F30903FB8201201AE0A3 +:1018A0001AF80060E6540130EAE79045F1D2A1F160 +:1018B000060B1C237C68BBFBF3F203FB12BB1FFA75 +:1018C0008BF6002C45D14846FFF754FF044638B943 +:1018D00078606FF00200BDE8F88F4FF00008E6E78F +:1018E000002606607860ADB24FF0000B454510D978 +:1018F0000AEB0803221D13F8011B9155B1B208F140 +:1019000001081B291FFA88F82BD0454506F101066E +:10191000F1D8FB8AC3F30902154465F30903BCE758 +:10192000013292B21C462368002BF9D1AB1F0B4445 +:101930001C21B3FBF1F301339BB29A42D3D2BBF12A +:10194000000FD0D14846FFF715FF20B9C4F800B00A +:10195000BFE70122E7E7C0F800B05E46206004461A +:10196000C1E74545D5D94846FFF704FF08B92060CF +:10197000AFE7C0F800B0002620600446B6E70000DC +:101980002DE9F04F2DED028B83B0CDE90013BDF8AA +:101990003C5007469146002A00F092802DB10E9BE4 +:1019A000002B00F08D80072D32D807F10C00FFF7D7 +:1019B000E1FE044638B96FF00204204603B0BDECE6 +:1019C000028BBDE8F08F14220021FFF75DFD0E9918 +:1019D0002A4604F10800FFF745FD681CC0B2FFF776 +:1019E00011FFFFF7F3FE207499F80030013814FA64 +:1019F00080F003F01F0363F03F030372009B43F08A +:101A00000041616038462146FFF71CFE0124D4E7FF +:101A100000F10C034FF0000808EE103A4FF0800A76 +:101A20004646444618EE100AFFF7A4FE83460028F7 +:101A3000C1D014220021FFF727FDC6BB019BABF8E4 +:101A4000083002200E9B00F1080299195BFA82F21D +:101A50000130C0B2082801D0AE422AD3FFF7D2FE2F +:101A6000FFF7B4FE99F80020009B411E02F01F0210 +:101A700042EA4812AE4208BF4FF0400A5BFA81F1D9 +:101A80004AEA020A43F0004281F808A08BF81000ED +:101A9000CBF8042059463846FFF7D4FD0134AE4256 +:101AA00024B288F001084FF0000ABBD185E700207E +:101AB000C8E711F801CB02F801CB0136B6B2C7E78F +:101AC0006FF0010479E70000F8B515460E462822AC +:101AD000002104461F46FFF7D7FC069B6360B5F55F +:101AE000001F079BA76034BF6A094FF6FF7223628D +:101AF00004F10C0097B200239A4205D8002303603A +:101B000027826382A382F8BD066001333046203607 +:101B1000F2E7000003781BB94BB2002BC8BF01707D +:101B200070470000007870472DE9F74FDDF83C90D2 +:101B3000BDF830500D9E9DF83840BDF8407080468D +:101B400092469B46B9F1000F01D1002F51D11F2CB5 +:101B50004FD898F80000B0B9072F47D835F00303E5 +:101B600047D13A4649464FF6FF70FFF7F7FD20F0A0 +:101B700001002D02400445EA0464400C44EA40247C +:101B80004FF6FF7321E040EA0520072F40EA046486 +:101B9000F6D900254FF6FF73C5F12000A5F120020C +:101BA0002AFA05F10BFA00F001432BFA02F2114375 +:101BB0001846C9B2FFF7C0FD0835402D0346EBD1EA +:101BC0003A464946FFF7CAFD0346CDE9009732463B +:101BD00021464046FFF7D4FE33780133DBB21F2B9A +:101BE00088BF0023337003B0BDE8F08F6FF00300AF +:101BF000F9E76FF00100F6E72DE9F04F85B0924666 +:101C0000DDF848800F9D9DF840209DF84490BDF878 +:101C10004C7006469B46B8F1000F01D1002F48D109 +:101C20001F2A46D83378002B46D00C0244EA0264BF +:101C30009DF8381044EAC93444EA01441C43072F94 +:101C400044F0800432D900234FF6FF72C3F1200C18 +:101C5000A3F120002AFA03F10BFA0CFC41EA0C0173 +:101C60002BFA00F00143C9B210460393FFF764FD5D +:101C7000039B0833402B0246E8D13A464146FFF722 +:101C80006DFD0346CDE900872A4621463046FFF721 +:101C900077FEB9F1010F06D12B780133DBB21F2B90 +:101CA00088BF00232B7005B0BDE8F08F4FF6FF739F +:101CB000E8E76FF00100F6E76FF00300F3E70000DC +:101CC000C06900B104307047C3691A68C261C26854 +:101CD0001A60C360438A013B438270472DE9F0419B +:101CE000D0F81880194E14461D464146002709B900 +:101CF000BDE8F081D1E90223A21A65EB0303964205 +:101D000077EB03031ED283698B420DD1FFF796FD5B +:101D100083691B688361C3680B60438AC160816902 +:101D2000013B43828846E2E7FFF788FD0B68C8F86D +:101D30000030C3680B60438AC160013B4382D8F81E +:101D40000010D4E788460968D1E700BF80841E00F0 +:101D50002DE9F04F8BB00D46DDF8509014469B46B0 +:101D60008046002800F01981B9F1000F00F01581BC +:101D7000531E3F2B00F21181012A03D1BBF1000F4A +:101D800040F00B810023CDE90833B8F81430B5EBEF +:101D9000C30F4FEAC30703D300200BB0BDE8F08F99 +:101DA0002B199F42D8F80C303ABF7F1BFFB2274651 +:101DB0001BB9D8F81030002B7AD02F2D4ED8C5F192 +:101DC0003006B7424FF000032CBFF6B23E460093F8 +:101DD0002946D8F8080008AB3246FFF775FCA7EB98 +:101DE000060A35445FFA8AFAB8F8143003F1005352 +:101DF000063BDB000493D8F80C3003933021039B9F +:101E000013B1BAF1000F2CD1D8F8100040B1BAF1DB +:101E1000000F05D0009608AB5246691AFFF754FC34 +:101E200038B2002FB8D066070AD00AAB03EBD40152 +:101E3000624211F8083C02F00702134101F8083C25 +:101E4000082C3CD9102C40F2B580202C40F2B780F1 +:101E5000BBF1000F00F09C80082334E0BA46002656 +:101E6000C2E7049BE02B28BFE02306930B44AB4260 +:101E7000059314D95A1B03980096924534BF5246D5 +:101E8000D2B2691A08AB04300792FFF71DFC079A1B +:101E90001644AAEB020A1544F6B25FFA8AFA049BCA +:101EA000069A05999B1A0493039B1B680393A6E764 +:101EB0000093D8F8080008AB3A462946AEE7BBF1D4 +:101EC000000F13D00123B4EBC30F6CD0082C12D831 +:101ED0009DF82030621E23FA02F2D50706D54FF096 +:101EE000FF3202FA04F423438DF820309DF82030AD +:101EF00089F8003051E7102C12D8BDF82030621E4E +:101F000023FA02F2D10706D54FF0FF3202FA04F4A9 +:101F10002343ADF82030BDF82030A9F800303CE76D +:101F2000202C0FD80899631E21FA03F3DA0705D590 +:101F30004FF0FF3202FA04F40C430894089BC9F8EE +:101F400000302AE7402C2BD0DDE90865611EC4F182 +:101F50002102A4F1210326FA01F105FA02F225FA81 +:101F600003F311431943CB0712D50122A4F1200337 +:101F7000C4F1200102FA03F322FA01F1A240524215 +:101F800043EA010363EB430332432B43CDE90823C8 +:101F9000DDE90823C9E90023FFE66FF00100FCE654 +:101FA0006FF00800F9E6082CA0D9102CB3D9202C2A +:101FB000EED8C3E7BBF1000FADD0022383E7BBF13E +:101FC000000FBBD004237EE730B5012A144638BF8A +:101FD0000124402C85B028BF40240025012ACDE9EA +:101FE000025518D81B788DF8083063070AD004AB67 +:101FF00003EBD405624215F8083C02F00702934057 +:1020000005F8083C009103462246002102A8FFF78C +:102010005BFB05B030BD082AE4D9102A03D81B8821 +:10202000ADF80830E1E7202A8DBFD3E900231B6813 +:102030000293CDE90223D8E710B5CB681BB98B60BA +:102040000B618B8210BDC4681A681C60C360438A30 +:10205000013B4382CA60F0E72DE9F04FD1F80080E0 +:1020600093B018F0800FCDE90323C8F3C01219BF55 +:10207000C8F3C03BC8F306264FF0020B1646B8F172 +:10208000000F04460D4680F2D18118F0C04305933D +:1020900040F0CC810B7B002B00F0C881BBF1020F1C +:1020A00003D00178B14240F0C48108F07F0106916D +:1020B0006AB3C8F3074A2B44069A93F8039076064E +:1020C00046EA0B4646EA82465FEAD91346EA0A0622 +:1020D000079300F0908000220023CDE90A23069B9D +:1020E000009367685B4652460AA92046B847002815 +:1020F0007ED0A7699FB9314604F10C00FFF748FB79 +:102100000746E0B96FF0020013B0BDE8F08FC8F3E6 +:102110000F2A18F07F0F08BF0AF0030ACBE73B69CC +:102120009E420DD03F68002FF9D1314604F10C00DA +:10213000FFF72EFB07460028E4D0A3693B60A761A8 +:10214000DDE90A2300264FF6FF70C6F1200E22FAC1 +:1021500006F103FA0EFEA6F1200C23FA0CFC41EA6C +:102160000E0141EA0C01C9B2083609920893FFF743 +:10217000E3FA402EDDE90832E7D1B882FB7D09F0B1 +:102180001F06C3F384039B1BD7E9022198B2002BDF +:10219000BCBF00F120031BB252EA0100C8F304687F +:1021A0000FD00398821A049860EB0101A74890426F +:1021B0004FF000028A4104D3079A002A5BD0012B1A +:1021C00023DDFA7D4FEA890302F0030203F07C036A +:1021D0001343FB7539462046FFF730FB079BA3B935 +:1021E000FB7DC3F38402013262F38603FB7504E0D6 +:1021F0006FF00B0088E7A76917B96FF00C0083E751 +:102200003B699E42BAD03F68F6E719F0400F32D0E2 +:10221000039BBB60049BFB60142200210DA8FFF709 +:1022200033F9039B0A93049B0B932B1D0C932B7B7D +:10223000ADF83EA0013BDBB2ADF83C30069B8DF81B +:10224000433094F824308DF840B083F001038DF8CA +:1022500044308DF84160A3688DF842800AA9204679 +:102260009847FB7DC3F38403013303F01F039B02F4 +:10227000FB82002048E7FB7DC9F34012B2EBD31F7D +:1022800040F0DA80C3F38403B34240F0D88007996A +:102290002B7B4FEA9912002934D0D20741D4032B6B +:1022A00040F2D080039BBB60049BFB602B7BAE1D88 +:1022B000033BDBB23246394604F10C00FFF7D0FA9B +:1022C00000280DDA20463946FFF7B8FAFB7DC3F344 +:1022D0008403013303F01F039B02FB82032013E7F7 +:1022E000AB883B832A7B033AB88AD2B23146FFF7E8 +:1022F00035FAFB7DB882DA43C2F3C01262F3C7132A +:10230000FB75B6E76AB92E1D013BDBB23246394692 +:1023100004F10C00FFF7A4FA0028D3DB2A7B013A72 +:10232000E2E7F98AC1F30901013B0529DAB259D87C +:10233000281D002307F11A0C9A4208D910F801EB66 +:102340000CF801E0013101330629DBB2F4D1039925 +:102350000A9104990B91934207F11A010C9138BF2D +:10236000043379680D9134BF55FA83F300230E933B +:10237000FB8AADF83EA0C3F309031A44069B8DF80F +:10238000433094F82430ADF83C2083F001038DF8FD +:10239000443000238DF840B08DF841608DF84280C4 +:1023A0007B602A7BB88A013A291DFFF7D7F93B8B5E +:1023B000B882834203D1A3680AA9204698472046E1 +:1023C0000AA9FFF739FEFB7DB88AC3F38403013302 +:1023D00003F01F039B02FB823B8B984214BF11202A +:1023E000002091E67B68002BB1D0062001E01C3074 +:1023F0006346D3F800C0BCF1000FF8D1091A081DDC +:1024000005F1040C00EB030905989DF8143001EB6D +:10241000000EBEF11B0F9AD89A4298D91CF8013BC6 +:1024200009F8013B059B01330593EDE76FF00900C7 +:102430006AE66FF00A0067E66FF00D0064E66FF081 +:102440000E0061E66FF00F005EE600BF80841E00A4 +:10245000404BF0B51C6C404E44F000741C641D6E83 +:1024600045F000751D661B6E3C4B9B6AD3F800520D +:10247000354045F00105C3F80052D3F8004234401E +:1024800044EA002040F00100C3F80002002952D0C5 +:102490000020C3F81C020546C3F80402C3F80C026E +:1024A000C3F8140203EBC00401301C28C4F84052E6 +:1024B000C4F84452F6D100254FF0010C96781488E8 +:1024C000F70748BFD3F804720CFA04F044BF07437F +:1024D000C3F80472B70742BFD3F80C720743C3F8BE +:1024E0000C72760742BFD3F814620643C3F8146235 +:1024F00003EBC4045668C4F840629668C4F84462AA +:10250000D3F81C4201352043A942C3F81C0202F152 +:102510000C02D3D1D3F8002222F00102C3F800222A +:102520000C4B1A6C22F000721A641A6E22F00072C0 +:102530001A661B6EF0BD0122C3F84012C3F84412A4 +:10254000C3F80412C3F81412C3F80C22C3F81C22F7 +:10255000E0E700BF003802400000FFFF88340020A1 +:10256000184A916A08B58B688B6013F0010104D09A +:1025700013F00C0F18BF4FF48031D80506D513F4B3 +:10258000406F14BF41F4003141F00201D80306D579 +:1025900013F4402F14BF41F4802141F00401D369AA +:1025A0000BB108489847202383F31188064800217F +:1025B00000F0EEFD002383F31188BDE8084001F030 +:1025C00017B900BF883400209034002038B5124C71 +:1025D000A36ADD68AA0712D05A6922F002025A6182 +:1025E000A36913B1012120469847202383F3118862 +:1025F0000A48002100F0CCFD002383F31188EB068C +:1026000006D5A36A1021D960236A0BB10248984706 +:10261000BDE8384001F0ECB8883400209834002040 +:1026200038B5124CA36A1D69AA0712D05A6922F064 +:1026300010025A61A36913B1022120469847202352 +:1026400083F311880A48002100F0A2FD002383F3E0 +:102650001188EB0606D5A36A10211961236A0BB114 +:1026600002489847BDE8384001F0C2B888340020DD +:102670009834002038B50F4CA36A5D685D602A0766 +:102680000AD5042222701A6822F002021A60636AD4 +:1026900013B10021204698476B0706D5A36A9969B4 +:1026A000236A13B1034809049847BDE8384001F094 +:1026B0009FB800BF8834002010B50E4C204600F0B3 +:1026C000CFF90D4BA3620B21132000F0B1F90B21C0 +:1026D000142000F0ADF90B21152000F0A9F90B2111 +:1026E000162000F0A5F90022BDE8104011460E208A +:1026F000FFF7AEBE8834002000640040114B9842C2 +:1027000010B5044609D1104B1A6C42F000721A64DD +:102710001A6E42F000721A661B6EA36A01221A60DA +:10272000A36A5A68D20707D5626851681268D961EE +:102730001A60064A5A6110BD0121082000F01EFCF3 +:10274000EEE700BF88340020003802405B870100BC +:1027500003291AD8DFE801F0020A0F14836A9B6884 +:1027600013F0E05F14BF012000207047836A98686F +:10277000C0F380607047836A9868C0F3C060704798 +:10278000836A9868C0F300707047002070470000AB +:1027900010B5032925D8DFE801F00225292D836A29 +:1027A0009968C1F30161183103EB011310788406B5 +:1027B0004CBF54689488C0F300114FEA410148BFF0 +:1027C00041EAC40100F00F004CBF41F0040141EAAE +:1027D0004451586041F001019068D2689860DA6015 +:1027E000196010BD836A03F5C073DFE7836A03F5E0 +:1027F000C873DBE7836A03F5D073D7E701290AD0F2 +:1028000002290FD081B9836ADA68920701D1186969 +:1028100003E001207047836AD86810F0030018BFF6 +:1028200001207047836AF2E70020704710B539B97C +:10283000836AD96889071BD11B699C0704D110BD25 +:10284000012915D00229FAD1816AD1F8C031D1F815 +:10285000C441D1F8C8011061D1F8CC0150612020E9 +:1028600008610869800717D1486940F0100012E03C +:10287000816AD1F8B031D1F8B441D1F8B801106112 +:10288000D1F8BC0150612020C860C868800703D11E +:10289000486940F002004861C3F34000C3F380017F +:1028A000000140EA4111107920F03000014311711C +:1028B00089064BBF91681189DB085B0D4CBF63F340 +:1028C0001C0163F30A01137948BF916064F30303A9 +:1028D00013714FEA14234FEA144458BF1181137047 +:1028E0005480ACE7024AD36843F0C003D36070471A +:1028F00000140140044B5A6810439A6858600AB1AA +:10290000181D1047704700BFB43400202DE9F04176 +:102910003C4ED6F85C52EF682B68DA059CB20CD5B9 +:10292000202383F311884FF40070FFF7E3FF6FF467 +:1029300080732B60002383F31188202383F3118895 +:10294000DFF8C08014F02F0339D183F311883806E3 +:1029500013D5210611D5202383F311882A4800F0CE +:1029600001FA00284CDA0820FFF7C4FF4FF67F7306 +:102970003B40EB60002383F311887A0615D563068C +:1029800013D5202383F31188D6E913239A4209D162 +:10299000336C3BB127F040073F0410203F0CFFF79A +:1029A000A9FFEF60002383F31188D6F86422D3686F +:1029B0000BB110699847BDE8F04100F019BF23073B +:1029C00012D014F0080F0CBF00208020E10748BF90 +:1029D00040F02000A20748BF40F04000630748BF16 +:1029E00040F48070FFF786FFA4066B6805D596F863 +:1029F00060124046194000F057FA2C68A4B2A1E7D3 +:102A00006860B7E7B4340020EC34002010B5054C02 +:102A1000054A0021204600F025FA044BC4F85C3238 +:102A200010BD00BFB4340020E528000800140140A8 +:102A300000F1604303F561430901C9B283F8001353 +:102A4000012200F01F039A4043099B0003F16043F9 +:102A500003F56143C3F880211A607047FFF72CBE6D +:102A6000012300F10802C0E90222037000F1100204 +:102A70000023C0E90422C0E90633C0E908334360FB +:102A80007047000010B52023044683F31188022309 +:102A900003704160FFF732FE04232370002383F3A9 +:102AA000118810BD2DE9F0411F4604460D4616461B +:102AB000202383F3118800F108082378052B0DD01B +:102AC00029462046FFF744FE40B1204632462946BB +:102AD000FFF75EFE002080F3118808E0394640468B +:102AE00000F03AFB0028E8D0002383F31188BDE80A +:102AF000F08100002DE9F0411F4604460D461646C0 +:102B0000202383F3118800F110082378052B0DD0C2 +:102B100029462046FFF772FE40B12046324629463C +:102B2000FFF784FE002080F3118808E03946404614 +:102B300000F012FB0028E8D0002383F31188BDE8E1 +:102B4000F0810000F8B5154682680669AA420B4676 +:102B5000816938BF8568761AB54204460BD218469B +:102B60002A46FEF77FFCA3692B44A361A3685B1B85 +:102B7000A3602846F8BD0CD918463246FEF772FC11 +:102B8000AF1BE1683A463044FEF76CFCE3683B4417 +:102B9000EBE718462A46FEF765FCE368E5E7000028 +:102BA00083689342F7B51546044638BF8568D0E977 +:102BB0000460361AB5420BD22A46FEF753FC63690D +:102BC0002B446361A36828465B1BA36003B0F0BD80 +:102BD0000DD932460191FEF745FC0199E068AF1B23 +:102BE0003A463144FEF73EFCE3683B44E9E72A46B7 +:102BF000FEF738FCE368E4E710B50A440024C3613B +:102C0000029B8460C0E90000C0E90511C160026157 +:102C1000036210BD08B5D0E90532934201D1826844 +:102C200082B98268013282605A1C42611970D0E90F +:102C300004329A4224BFC3684361002100F09CFA29 +:102C4000002008BD4FF0FF30FBE7000070B52023E7 +:102C500004460E4683F31188A568A5B1A368A2694E +:102C6000013BA360531CA36115782269934224BFE2 +:102C7000E368A361E3690BB120469847002383F31F +:102C80001188284607E03146204600F065FA002802 +:102C9000E2DA85F3118870BD2DE9F74F04460E4640 +:102CA00017469846D0F81C904FF0200A8AF31188F6 +:102CB0004FF0000B154665B12A4631462046FFF716 +:102CC00041FF034660B94146204600F045FA00281E +:102CD000F1D0002383F31188781B03B0BDE8F08F97 +:102CE000B9F1000F03D001902046C847019B8BF338 +:102CF0001188ED1A1E448AF31188DCE7C0E905113A +:102D0000C160C3611144009B8260C0E900000161A1 +:102D100003627047F8B504460D461646202383F338 +:102D20001188A768A7B1A368013BA36063695A1C17 +:102D300062611D70D4E904329A4224BFE368636182 +:102D4000E3690BB120469847002080F3118807E023 +:102D50003146204600F000FA0028E2DA87F31188B5 +:102D6000F8BD0000D0E905239A4210B501D1826870 +:102D70007AB98268013282605A1C82611C780369C8 +:102D80009A4224BFC3688361002100F0F5F9204610 +:102D900010BD4FF0FF30FBE72DE9F74F04460E461C +:102DA00017469846D0F81C904FF0200A8AF31188F5 +:102DB0004FF0000B154665B12A4631462046FFF715 +:102DC000EFFE034660B94146204600F0C5F90028F1 +:102DD000F1D0002383F31188781B03B0BDE8F08F96 +:102DE000B9F1000F03D001902046C847019B8BF337 +:102DF0001188ED1A1E448AF31188DCE702684368E3 +:102E00001143016003B11847704700001430FFF709 +:102E100043BF00004FF0FF331430FFF73DBF000009 +:102E20003830FFF7B9BF00004FF0FF333830FFF7FD +:102E3000B3BF00001430FFF709BF00004FF0FF31AF +:102E40001430FFF703BF00003830FFF763BF000006 +:102E50004FF0FF323830FFF75DBF000000207047B1 +:102E6000FFF7D4BD37B515460E4A02600022426016 +:102E7000C0E902220122044602740B46009000F1D0 +:102E80005C014FF480721430FFF7B6FE00942B46BD +:102E90004FF4807204F5AE7104F13800FFF72EFF95 +:102EA00003B030BD103F000838B5C36904460D4675 +:102EB0001BB904210844FFF7A1FF294604F11400BF +:102EC000FFF7A8FE002806DA201D4FF48061BDE858 +:102ED0003840FFF793BF38BD024B0022C3E90033EF +:102EE0009A6070471C370020002303748268054BEA +:102EF0001B6899689142FBD25A6803604260106077 +:102F0000586070471C37002008B5202383F31188D0 +:102F1000037C032B05D0042B0DD02BB983F3118830 +:102F200008BD436900221A604FF0FF334361FFF789 +:102F3000DBFF0023F2E7D0E9003213605A60F3E7C9 +:102F4000002303748268054B1B6899689142FBD883 +:102F50005A68036042601060586070471C37002058 +:102F6000054B19690874186802681A605360186183 +:102F700001230374FDF74CBB1C37002030B54B1CFC +:102F80000B4D87B0044610D02B690A4A01A800F007 +:102F90001BF92046FFF7E4FF049B13B101A800F0E2 +:102FA0004FF92B69586907B030BDFFF7D9FFF8E733 +:102FB0001C370020092F000838B50C4D41612B69E2 +:102FC00081689A689142044603D8BDE83840FFF70B +:102FD0008BBF1846FFF7B4FF01232C610146237411 +:102FE0002046BDE83840FDF713BB00BF1C3700206A +:102FF000044B1A681B6990689B68984294BF002034 +:10300000012070471C37002010B5084C2368206948 +:103010001A6822605460012223611A74FFF790FF3E +:1030200001462069BDE81040FDF7F2BA1C370020C8 +:1030300008B5FFF7DDFF18B1BDE80840FFF7E4BFB2 +:1030400008BD0000FFF7E0BFFEE7000010B50C4C24 +:10305000FFF742FF00F0AAF80A498022204600F05C +:1030600031F8012344F8180C037400F09DFB002391 +:1030700083F3118862B60448BDE8104000F042B8FE +:1030800044370020383F0008483F000800F012B9DC +:10309000EFF3118020B9EFF30583202282F311882A +:1030A0007047000010B530B9EFF30584C4F308048D +:1030B00014B180F3118810BDFFF7BAFF84F31188B3 +:1030C000F9E7000082600222028270478368A3F160 +:1030D0007C0243F80C2C026943F83C2C426943F80B +:1030E000382C074A43F81C2CC26843F8102C0222E3 +:1030F00003F8082C002203F8072CA3F118007047EE +:103100002906000810B5202383F31188FFF7DEFF9E +:1031100000210446FFF750FF002383F31188204667 +:1031200010BD0000024B1B6958610F20FFF718BF4C +:103130001C370020202383F31188FFF7F3BF000022 +:1031400008B50146202383F311880820FFF716FFF6 +:10315000002383F3118808BD49B1064B42681B69FF +:1031600018605A60136043600420FFF707BF4FF0F8 +:10317000FF3070471C3700200368984206D01A6859 +:103180000260506059611846FFF7AEBE70470000FC +:1031900038B504460D462068844200D138BD036826 +:1031A00023605C604561FFF79FFEF4E7054B03F188 +:1031B0001402C3E905224FF0FF310022C3E90712D0 +:1031C000704700BF1C37002070B51C4EC0E90323B8 +:1031D00005460C4600F06EFB334653F8142F9A4216 +:1031E0000DD13062C5E901242A600A2C2CBF0019D8 +:1031F0000A30C6E90555BDE8704000F049BB316AA8 +:10320000431AE31838BF1C469368A34202D9081931 +:1032100000F04CFB73699A6894420CD85A68AC6011 +:103220002B606A6015609A685D60121B9A604FF0AF +:10323000FF33F36170BD1B68A41AECE71C37002054 +:1032400038B51B4C636998420DD0D0E90032136049 +:103250005A6000228168C2609A680A449A604FF0FE +:10326000FF33E36138BD2246036842F8143F002172 +:1032700093425A60C16003D1BDE8384000F010BBF2 +:103280009A688168256A0A449A6000F013FB6369B2 +:103290009A68411B8A42E5D9AB181D1A092D206A8C +:1032A00098BF01F10A02BDE83840104400F0FEBAB0 +:1032B0001C3700202DE9F041184C002704F11406BA +:1032C000656900F0F7FA236AAA68C11A8A4215D81C +:1032D00013442362D5E9003213605A606369D5F85C +:1032E0000C80EF60B34201D100F0DAFA87F3118865 +:1032F0002869C047202383F31188E1E76169B1425F +:1033000009D013441B1ABDE8F0410A2B2CBFC0188A +:103310000A3000F0CBBABDE8F08100BF1C370020B6 +:1033200000207047FEE70000704700004FF0FF30BC +:1033300070470000BFF34F8F024AD368DB03FCD411 +:10334000704700BF003C024008B5094B1B7873B9B9 +:10335000FFF7F0FF074B1A69002ABFBF064A5A6001 +:1033600002F188325A601A6822F480621A6008BD3D +:10337000D8380020003C02402301674508B50B4BBC +:103380001B7893B9FFF7D6FF094B1A6942F0004248 +:103390001A611A6842F480521A601A6822F4805244 +:1033A0001A601A6842F480621A6008BDD83800209A +:1033B000003C02400728F0B516D80C4C0C49237885 +:1033C0007BB90C4D0E4608234FF0006255F8047B84 +:1033D00046F8042B013B13F0FF033A44F6D10123D6 +:1033E000237051F82000F0BD0020FCE7FC380020DD +:1033F000DC380020603F0008014B53F82000704784 +:10340000603F000808207047072810B5044601D91E +:10341000002010BDFFF7CEFF064B53F824301844B0 +:10342000C21A0BB90120F4E712680132F0D1043B53 +:10343000F6E700BF603F0008072838B5044628D8E3 +:10344000FFF726FEFFF776FFFFF77EFF124AF32312 +:10345000D360E300DBB243F4007343F00203136173 +:10346000136943F48033136105462046FFF762FF7A +:10347000FFF7A0FF094B53F8241000F03BF9284652 +:10348000FFF77CFFFFF70EFE2046BDE83840FFF750 +:10349000BBBF002038BD00BF003C0240603F0008B9 +:1034A00012F001032DE9F04105460E4614464BD1BA +:1034B0008118334A914261D8324B1B6813F00103E3 +:1034C0005CD0314FFFF7E4FDFFF73EFFF323FB60D5 +:1034D000FFF730FF314640F20128032C18D824F0C2 +:1034E0000104294E0C446D1A40F20118A1423369BF +:1034F00005EB01072AD123F001033361FFF73EFFFB +:10350000FFF7D0FD0120BDE8F081043C0435E4E77D +:10351000AB07E4D13B6923F440733B613B6943EA69 +:1035200008033B6151F8046B2E60BFF34F8FFFF728 +:1035300001FF2B689E42E8D03B6923F001033B6109 +:10354000FFF71CFFFFF7AEFD0020DCE723F440731C +:103550003361336943EA080333610B883B80BFF36F +:103560004F8FFFF7E7FE3F8831F8023BBFB2BB4207 +:10357000BCD0336923F001033361E1E71846C2E7A9 +:103580000000080800380240003C0240084908B525 +:103590000B7828B11BB9FFF7D7FE01230B7008BDCC +:1035A000002BFCD0BDE808400870FFF7E7BE00BF65 +:1035B000D838002070B582B0FFF76AFD0E4E054680 +:1035C00000F078F93268904237BF0C4A0B495168D5 +:1035D00014682EBFD1E9004101315160041903463E +:1035E00041F10001284601913360FFF75BFD01992D +:1035F000204602B070BD00BF00390020083900200D +:1036000070B582B0FFF744FD104E054600F052F948 +:103610003268904237BF0E4A0D49516814682EBF78 +:10362000D1E9004101315160041941F10001034623 +:10363000284601913360FFF735FD01994FF47A7206 +:1036400000232046FCF7CCFD02B070BD00390020FD +:103650000839002010B50244064BD2B2904200D186 +:1036600010BD441C00B253F8200041F8040BE0B236 +:10367000F4E700BF502800400F4B30B51C6F240406 +:1036800007D41C6F44F400741C671C6F44F400449E +:103690001C670A4C236843F4807323600244084B80 +:1036A000D2B2904200D130BD441C00B251F8045B4C +:1036B00043F82050E0B2F4E70038024000700040C8 +:1036C0005028004007B5012201A90020FFF7C2FFE2 +:1036D000019803B05DF804FB13B50446FFF7F2FF51 +:1036E000A04205D0012201A900200194FFF7C4FFE8 +:1036F00002B010BD70470000074B45F255521A60EA +:1037000002225A6040F6FF729A604CF6CC421A6070 +:10371000024B01221A70704700300040143900201B +:10372000034B1B781BB1034B4AF6AA221A60704761 +:103730001439002000300040034B1A681AB9034ABC +:10374000D2F874281A607047103900200030024007 +:10375000024B4FF08072C3F874287047003002406B +:1037600008B5FFF7E9FF024B1868C0F3407008BDC9 +:103770001039002008B5FFF7DFFF024B1868C0F3CF +:10378000007008BD10390020EFF3098305494A6B2A +:1037900022F001024A63683383F30988002383F32C +:1037A0001188704700EF00E0202080F3118862B696 +:1037B0000C4B0D4AD96821F4E0610904090C0A4355 +:1037C000DA60D3F8FC20094942F08072C3F8FC208B +:1037D0000A6842F001020A601022DA7783F82200B8 +:1037E000704700BF00ED00E00003FA05001000E0A4 +:1037F00010B5202383F311880E4B5B6813F400632C +:1038000014D0F1EE103AEFF30984683C4FF0807366 +:10381000E361094BDB6B236684F30988FFF7E8FB60 +:1038200010B1064BA36110BD054BFBE783F3118874 +:10383000F9E700BF00ED00E000EF00E03B06000804 +:103840003E06000870470000FEE700000A4B0B48E8 +:103850000B4A90420BD30B4BDA1C121AC11E22F0FA +:1038600003028B4238BF00220021FDF70DBE53F842 +:10387000041B40F8041BECE78C400008983900203A +:1038800098390020983900207047000000F080B877 +:103890004FF08043002258631A610222DA607047B9 +:1038A0004FF080430022DA60704700004FF0804301 +:1038B000586370474FF08043586A70474B684360C5 +:1038C0008B688360CB68C3600B6943614B6903629B +:1038D0008B6943620B6803607047000008B5234B97 +:1038E00023481A6942F0FF021A611A6922F0FF02A6 +:1038F0001A611A691A6B42F0FF021A631A6D42F0DC +:10390000FF021A651B4A1B6D1146FFF7D7FF02F134 +:103910001C0100F58060FFF7D1FF02F1380100F5CE +:103920008060FFF7CBFF02F1540100F58060FFF7E4 +:10393000C5FF02F1700100F58060FFF7BFFF02F1E3 +:103940008C0100F58060FFF7B9FF02F1A80100F5D6 +:103950008060FFF7B3FF02F1C40100F58060FFF75C +:10396000ADFFBDE8084000F097B800BF0038024046 +:1039700000000240803F000808B500F017FAFFF78A +:1039800065FBBDE80840FFF7D7BE000070470000A8 +:10399000104B1A6C42F001021A641A6E42F00102D6 +:1039A0001A660D4A1B6E936843F0010393604FF053 +:1039B000804331229A624FF0FF32DA6200229A612C +:1039C0005A63DA605A6001225A6108211A601C2089 +:1039D000FFF72EB800380240002004E04FF080428C +:1039E00008B51169D3680B40D9B2C9439B0711616F +:1039F00007D5202383F31188FFF748FB002383F3C7 +:103A0000118808BD08B5FFF7E9FFBDE80840FFF7DA +:103A1000EFBE00001E4B1A6962F0FF021A611A69BC +:103A2000D2B21A614FF0FF301A695A695861002109 +:103A30005A6959615A691A6A62F080521A621A6A9E +:103A400002F080521A621A6A5A6A58625A6A5962B5 +:103A50005A6A1A6C42F080521A641A6E42F080520E +:103A60001A661A6E0B4A106840F480701060186F66 +:103A700000F44070B0F5007F1EBF4FF4803018672F +:103A80001967536823F40073536000F06FB900BFE7 +:103A900000380240007000403B4B3C4A1A643C4AEC +:103AA0004FF4404111601A6842F001021A601A682E +:103AB0009007FCD59A6822F003029A60324B9A680C +:103AC00012F00C02FBD1196801F0F90119609A603B +:103AD0001A6842F480321A601A689103FCD55A6F52 +:103AE00042F001025A67284B5A6F9207FCD5294AC7 +:103AF0005A601A6842F080721A60254A5368580466 +:103B0000FCD5214B1A689101FCD5234AC3F88420C7 +:103B10001A6842F080621A601A681201FCD51F4AC6 +:103B20009A600322C3F88C204FF00062C3F89420FF +:103B30001B4B1A681B4B9A421B4B21D11B4A116825 +:103B40001B4A91421CD140F203121A60164A1368B4 +:103B500003F00F03032BFAD10B4B9A6842F00202D9 +:103B60009A609A6802F00C02082AFAD15A6C42F460 +:103B700080425A645A6E42F480425A665B6E7047C5 +:103B800040F20372E1E700BF003802400004001079 +:103B9000007000400819400210300024009488385A +:103BA000002004E011640020003C024000ED00E031 +:103BB00041C20F41084A08B5516913680B4003F030 +:103BC0000103536123B1054A13680BB1506898474C +:103BD000BDE80840FFF70CBE003C0140183900204A +:103BE000084A08B5516913680B4003F0020353619A +:103BF00023B1054A93680BB1D0689847BDE80840E7 +:103C0000FFF7F6BD003C014018390020084A08B50E +:103C1000516913680B4003F00403536123B1054A53 +:103C200013690BB150699847BDE80840FFF7E0BD44 +:103C3000003C014018390020084A08B55169136852 +:103C40000B4003F00803536123B1054A93690BB19C +:103C5000D0699847BDE80840FFF7CABD003C014065 +:103C600018390020084A08B5516913680B4003F061 +:103C70001003536123B1054A136A0BB1506A984788 +:103C8000BDE80840FFF7B4BD003C014018390020F2 +:103C9000174B10B55A691C68144004F478725A61C5 +:103CA000A30604D5134A936A0BB1D06A98476006FD +:103CB00004D5104A136B0BB1506B9847210604D5FD +:103CC0000C4A936B0BB1D06B9847E20504D5094AB7 +:103CD000136C0BB1506C9847A30504D5054A936C3F +:103CE0000BB1D06C9847BDE81040FFF781BD00BF15 +:103CF000003C0140183900201A4B10B55A691C6865 +:103D0000144004F47C425A61620504D5164A136DCE +:103D10000BB1506D9847230504D5134A936D0BB131 +:103D2000D06D9847E00404D50F4A136E0BB1506E66 +:103D30009847A10404D50C4A936E0BB1D06E9847F6 +:103D4000620404D5084A136F0BB1506F98472304DF +:103D500004D5054A936F0BB1D06F9847BDE810406A +:103D6000FFF746BD003C014018390020062108B588 +:103D70000846FEF75DFE06210720FEF759FE0621E4 +:103D80000820FEF755FE06210920FEF751FE062108 +:103D90000A20FEF74DFE06211720FEF749FEBDE87A +:103DA000084006212820FEF743BE000008B5FFF7B3 +:103DB00031FE00F00BF8FEF751FEFFF751F8FFF768 +:103DC000E5FDBDE80840FFF761BD00000023054A9E +:103DD00019460133102BC2E9001102F10802F8D193 +:103DE000704700BF1839002010B5013902449042D5 +:103DF00001D1002005E0037811F8014FA34201D062 +:103E0000181B10BD0130F2E72DE9F041A3B1C91A2A +:103E100017780144044603F1FF3C8C42204601D947 +:103E2000002009E00578BD4204F10104F5D10CEB56 +:103E30000405D618A54201D1BDE8F08115F8018D21 +:103E400016F801EDF045F5D0E7E70000034611F85C +:103E5000012B03F8012B002AF9D170476F72672EEE +:103E60006172647570696C6F742E626972646361EB +:103E70006E6479004E6F20617070207369670A006C +:103E8000426164206677206C656E677468202575D2 +:103E90000A0042616420626F6172645F6964202578 +:103EA000752073686F756C642062652025750A0043 +:103EB0004261642066772064657363726970746F11 +:103EC00072206C656E6774682025750A0042616413 +:103ED0002061707020435243203078253038783A82 +:103EE000307825303878203078253038783A307876 +:103EF000253038780A00476F6F64206669726D77E5 +:103F00006172650A0040A2E4F16468910600000055 +:103F100000000000292E0008152E0008512E000870 +:103F20003D2E0008492E0008352E0008212E0008DD +:103F30000D2E00085D2E00086D61696E0000000006 +:103F400069646C6500000000403F00086037002095 +:103F5000D8380020010000004930000800000000AF +:103F60000040000000400000004000000040000051 +:103F7000000001000000020000000200000002003A +:103F80000004802A00000000AAAAAAAA0000402576 +:103F9000DFFF0000000000000080080010000A00A1 +:103FA000000000009AAAAAAA00000000FBFF00007F +:103FB0000000000088000000000000000000000079 +:103FC000AAAAAAAA00000000FFFF0000000000004B +:103FD000000000000000000000000000AAAAAAAA39 +:103FE00000000000FFFF00000000000000000000D3 +:103FF0000000000000000000AAAAAAAA0000000019 +:10400000FFFF0000000000000000000000000000B2 +:1040100000000000AAAAAAAA00000000FFFF0000FA +:104020000000000000000000000000000000000090 +:10403000AAAAAAAA00000000FFFF000000000000DA +:104040000000000000000000000000000A00000066 +:10405000000000000300000000000000000000005D +:10406000B0C1FF7F01000000140400000000000048 +:1040700000000700000000006400000000000000D5 +:0C40800040420F00FE2A0100D2040000A4 :00000001FF diff --git a/Tools/bootloaders/CUAV-Nora-bdshot_bl.bin b/Tools/bootloaders/CUAV-Nora-bdshot_bl.bin new file mode 100644 index 00000000000..86d649994d7 Binary files /dev/null and b/Tools/bootloaders/CUAV-Nora-bdshot_bl.bin differ diff --git a/Tools/bootloaders/CUAV-Nora-bdshot_bl.hex b/Tools/bootloaders/CUAV-Nora-bdshot_bl.hex new file mode 100644 index 00000000000..13e9d96dbaf --- /dev/null +++ b/Tools/bootloaders/CUAV-Nora-bdshot_bl.hex @@ -0,0 +1,1093 @@ +:020000040800F2 +:1000000000060020A1020008851000080510000865 +:100010005D1000080510000831100008A302000858 +:10002000A3020008A3020008A30200087129000827 +:10003000A3020008A3020008A3020008A30200080C +:10004000A3020008A3020008A3020008A3020008FC +:10005000A3020008A3020008E93D0008153E0008BD +:10006000413E00086D3E0008993E0008A3020008CA +:10007000A3020008A3020008A3020008A3020008CC +:10008000A3020008A3020008A3020008A3020008BC +:10009000A3020008A3020008A3020008C53E00084E +:1000A000A3020008A3020008A3020008A30200089C +:1000B000B13F0008A3020008A3020008A302000841 +:1000C000A3020008A3020008A3020008A30200087C +:1000D000A3020008A3020008A3020008A30200086C +:1000E000293F0008A3020008A3020008A302000899 +:1000F000A3020008A3020008A3020008A30200084C +:10010000A3020008A3020008A3020008A30200083B +:10011000A3020008A3020008A3020008A30200082B +:10012000A3020008A3020008A3020008A30200081B +:10013000A3020008A3020008A3020008A30200080B +:10014000A3020008A3020008A3020008A3020008FB +:10015000A3020008A3020008A3020008A3020008EB +:10016000A3020008A3020008A3020008A3020008DB +:10017000A3020008DD340008A3020008A30200085F +:10018000A3020008A30200089D3F0008A302000884 +:10019000A3020008A3020008A3020008A3020008AB +:1001A000A3020008A3020008A3020008A30200089B +:1001B000A3020008A3020008A3020008A30200088B +:1001C000A3020008A3020008A3020008A30200087B +:1001D000A3020008C9340008A3020008A302000813 +:1001E000A3020008A3020008A3020008A30200085B +:1001F000A3020008A3020008A3020008A30200084B +:10020000A3020008A3020008A3020008A30200083A +:10021000A3020008A3020008A3020008A30200082A +:10022000A3020008A3020008A3020008A30200081A +:10023000A3020008A3020008A3020008A30200080A +:10024000A3020008A3020008A3020008A3020008FA +:10025000A3020008A3020008A3020008A3020008EA +:10026000A3020008A3020008A3020008A3020008DA +:10027000A3020008A3020008A3020008A3020008CA +:10028000A3020008A3020008A3020008A3020008BA +:10029000A3020008A3020008A3020008A3020008AA +:1002A00002E000F000F8FEE772B63A4880F30888F2 +:1002B000394880F3098839484EF60851CEF20001DA +:1002C000086040F20000CCF200004EF63471CEF22D +:1002D00000010860BFF34F8FBFF36F8F40F2000043 +:1002E000C0F2F0004EF68851CEF200010860BFF374 +:1002F0004F8FBFF36F8F4FF00000E1EE100A4EF604 +:100300003C71CEF200010860062080F31488BFF330 +:100310006F8F02F0EBFB02F08DFB03F021FB4FF03F +:1003200055301F491B4A91423CBF41F8040BFAE784 +:100330001C49194A91423CBF41F8040BFAE71A499B +:100340001A4A1B4B9A423EBF51F8040B42F8040B69 +:10035000F8E700201749184A91423CBF41F8040BC6 +:10036000FAE702F0A5FB03F07FFB144C144DAC42FE +:1003700003DA54F8041B8847F9E700F041F8114C00 +:10038000114DAC4203DA54F8041B8847F9E702F038 +:100390008DBB0000000600200022002000000008A5 +:1003A0000000002000060020D043000800220020AA +:1003B0005C22002060220020FC460020A0020008F1 +:1003C000A0020008A0020008A00200082DE9F04FDA +:1003D0002DED108AC1F80CD0D0F80CD0BDEC108AED +:1003E000BDE8F08F002383F311882846A047002042 +:1003F00001F0A6FEFEE701F021FE00DFFEE70000AF +:1004000038B500F0F7FC30B1164B00220E211A72FD +:100410005A729972DA7202F06BFA054602F09EFA8D +:100420000446D0B9104B9D4219D001339D4241F290 +:10043000883512BF044600250124002002F062FA2C +:100440000CB100F079F800F083FD00F019FC2846AB +:1004500000F020F900F070F8F9E70025EDE7054617 +:10046000EBE700BF00220020010007B008B500F054 +:10047000D3FBA0F120035842584108BD07B541F213 +:100480001203022101A8ADF8043000F0E3FB03B031 +:100490005DF804FB38B5202383F311881748C3683F +:1004A0000BB101F0D3FE0023154A4FF47A711348C3 +:1004B00001F090FE002383F31188124C236813B1DE +:1004C0002368013B2360636813B16368013B636089 +:1004D0000D4D2B7833B963687BB9022000F0AAFC7C +:1004E000322363602B78032B07D163682BB902207A +:1004F00000F0A0FC4FF47A73636038BD60220020E6 +:10050000950400087C23002074220020084B1870FA +:1005100003280CD8DFE800F008050208022000F0EC +:100520007BBC022000F068BC024B00225A6070477E +:10053000742200207C230020F8B5504B504A1C4602 +:100540001968013100F0998004339342F8D1626850 +:100550004C4B9A4240F291804B4B9B6803F10063F5 +:1005600003F500339A4280F08880002000F0A2FB5F +:100570000220FFF7CBFF454B0021D3F8E820C3F85A +:10058000E810D3F81021C3F81011D3F81021D3F8D4 +:10059000EC20C3F8EC10D3F81421C3F81411D3F8ED +:1005A0001421D3F8F020C3F8F010D3F81821C3F8C1 +:1005B0001811D3F81821D3F8802042F00062C3F854 +:1005C0008020D3F8802022F00062C3F88020D3F886 +:1005D0008020D3F8802042F00072C3F88020D3F846 +:1005E000802022F00072C3F88020D3F8803072B6E9 +:1005F0004FF0E023C3F8084DD4E90004BFF34F8F58 +:10060000BFF36F8F224AC2F88410BFF34F8F536934 +:1006100023F480335361BFF34F8FD2F8803043F619 +:10062000E076C3F3C905C3F34E335B0103EA060C5E +:1006300029464CEA81770139C2F87472F9D2203B1D +:1006400013F1200FF2D1BFF34F8FBFF36F8FBFF3C2 +:100650004F8FBFF36F8F536923F40033536100232F +:10066000C2F85032BFF34F8FBFF36F8F202383F355 +:100670001188854680F308882047F8BD00000208ED +:1006800020000208FFFF0108002200200044025859 +:1006900000ED00E02DE9F04F93B0A84B2022FF21A0 +:1006A00000900AA89D6800F0FDFBA54A1378A3B945 +:1006B0000121A4481170C360202383F31188C3680B +:1006C0000BB101F0C3FD00239F4A4FF47A719D489E +:1006D00001F080FD002383F31188009B13B19B4B35 +:1006E000009A1A609A4A1378032B03D000231370E0 +:1006F000964A53604FF0000A009CD3465646D146B6 +:10070000012000F089FB24B1904B1B68002B00F006 +:100710000E82002000F080FA0390039B002BF2DB96 +:10072000012000F069FB039B213B162BE8D801A2B6 +:1007300052F823F091070008B90700084D08000897 +:10074000010700080107000801070008D508000894 +:10075000A30A0008BD0900081F0A0008470A00088C +:100760006D0A0008010700087F0A00080107000859 +:10077000F10A00083108000801070008350B0008DD +:100780009D07000831080008010700081F0A00083B +:100790000220FFF76BFE002840F0F381009B02214E +:1007A00005A8BAF1000F08BF1C4641F21233ADF89C +:1007B000143000F04FFAA3E74FF47A7000F02CFAEF +:1007C000071EEBDB0220FFF751FE0028E6D0013FB9 +:1007D000052F00F2D881DFE807F0030A0D10133669 +:1007E0000523042105A8059300F034FA17E004213D +:1007F0005248F9E704215748F6E704215648F3E741 +:100800004FF01C08404608F1040800F055FA042196 +:10081000059005A800F01EFAB8F12C0FF2D10120C6 +:100820004FF0000900FA07F747EA0B0B5FFA8BFB62 +:1008300000F084FB26B10BF00B030B2B08BF002448 +:10084000FFF71CFE5CE704214448CDE7002EA5D04D +:100850000BF00B030B2BA1D10220FFF707FE07467D +:1008600000289BD00120002600F024FA0220FFF788 +:100870004DFE5FFA86F8404600F02CFA044688B137 +:100880004046013600F036FA0028F2D1BA46044656 +:1008900041F21213022105A83E46ADF8143000F0D3 +:1008A000D9F92DE725460120FFF730FE234B9B6841 +:1008B000AB4207D9284600F0FFF9013040F06681CD +:1008C0000435F3E70025224BBA463E461D701F4B08 +:1008D0005D60ADE7002E3FF461AF0BF00B030B2B17 +:1008E0007FF45CAF0220FFF711FE322000F094F994 +:1008F000B0F10008FFF652AF18F003077FF44EAFD7 +:100900000E4A08EB0503926893423FF647AFB8F5ED +:10091000807F3FF743AF124BB845019322DD4FF480 +:100920007A7000F079F90390039A002AFFF636AF47 +:10093000039A0137019B03F8012BEDE70022002009 +:100940007823002060220020950400087C230020EA +:100950007422002004220020082200200C22002003 +:1009600078220020C820FFF781FD074600283FF4C9 +:1009700015AF1F2D11D8C5F120020AAB25F00300D9 +:1009800084494245184428BF4246019200F064FA67 +:10099000019AFF217F4800F085FA4FEAA803C8F3C7 +:1009A00087027C492846019300F084FA0646002815 +:1009B0003FF46EAF019B05EB830539E70220FFF79B +:1009C00055FD00283FF4EAAE00F0B0F900283FF4EE +:1009D000E5AE0027B846704B9B68BB4218D91F2F65 +:1009E00011D80A9B01330ED027F0030312AA134437 +:1009F00053F8203C05934046042205A9043700F033 +:100A000043FB8046E7E7384600F056F90590F2E7E9 +:100A1000CDF81480042105A800F01CF908E7002394 +:100A2000642104A8049300F00BF900287FF4B6AE0B +:100A30000220FFF71BFD00283FF4B0AE049800F041 +:100A40006BF90590E6E70023642104A8049300F005 +:100A5000F7F800287FF4A2AE0220FFF707FD002878 +:100A60003FF49CAE049800F059F9EAE70220FFF742 +:100A7000FDFC00283FF492AE00F068F9E1E70220A7 +:100A8000FFF7F4FC00283FF489AE05A9142000F01C +:100A900063F907460421049004A800F0DBF8394606 +:100AA000B9E7322000F0B8F8071EFFF677AEBB07B3 +:100AB0007FF474AE384A07EB0903926893423FF61D +:100AC0006DAE0220FFF7D2FC00283FF467AE27F09E +:100AD00003074F44B9453FF4ABAE484609F104095A +:100AE00000F0EAF80421059005A800F0B3F8F1E75A +:100AF0004FF47A70FFF7BAFC00283FF44FAE00F0D5 +:100B000015F9002844D00A9B01330BD008220AA90A +:100B1000002000F0CFF900283AD02022FF210AA8B7 +:100B200000F0C0F9FFF7AAFC1C4801F00FFB13B05E +:100B3000BDE8F08F002E3FF431AE0BF00B030B2B12 +:100B40007FF42CAE0023642105A8059300F078F80B +:100B5000074600287FF422AE0220FFF787FC80467C +:100B600000283FF41BAEFFF789FC41F2883001F00A +:100B7000EDFA059800F026FA46463C4600F0DEF90C +:100B8000BEE5064654E64FF0000907E6BA467FE6A2 +:100B900037467DE67822002000220020A086010052 +:100BA000F7B50C46184E4FF47A71054602FB01F377 +:100BB00096F90020501C0BD1144829460193026875 +:100BC000176A2246B8478442019B03D1002310E0F4 +:100BD000002AF1D096F90020511C01D0012A0DD134 +:100BE0000B4829460268166A2246B047844205D15E +:100BF0000123084A0120137003B0F0BD4FF4FA70CE +:100C000001F0A4FA0020F7E710220020F0290020CC +:100C1000CC230020C8230020002307B50246012171 +:100C20000DF107008DF80730FFF7BAFF20B19DF8EE +:100C3000070003B05DF804FB4FF0FF30F9E7000058 +:100C40000A46042108B5FFF7ABFF80F00100C0B2EF +:100C5000404208BD074B0A4630B41978064B53F89A +:100C60002140014623682046DD69044BAC4630BC78 +:100C7000604700BFC8230020A4400008A0860100F0 +:100C800070B50A4E00240A4D01F00AFD3080286834 +:100C90003388834208D901F0FFFC2B6804440133F8 +:100CA000B4F5003F2B60F2D370BD00BFCA23002013 +:100CB0008423002001F0D2BD00F1006000F5003077 +:100CC0000068704700F10060920000F5003001F00C +:100CD00049BD0000054B1A68054B1B889B1A8342CF +:100CE00002D9104401F0D8BC0020704784230020B2 +:100CF000CA23002038B5074D04462868204401F077 +:100D0000D1FC28B928682044BDE8384001F0DCBC9B +:100D100038BD00BF842300200020704700F1FF5041 +:100D200000F58F10D0F8000870470000064991F8D0 +:100D3000243033B100230822086A81F82430FFF7F9 +:100D4000C1BF0120704700BF88230020014B1868F5 +:100D5000704700BF0010005C244BF0B51A680446D1 +:100D6000234BC2F30B06120C1F885868BE4293F93E +:100D7000085028D09F89BE4206D101200C2505FBD2 +:100D80000033586893F9085041F201039A421CD08D +:100D900041F203039A421AD042F201039A4218D058 +:100DA00042F203039A4208BF5625621E0B46441EB8 +:100DB0000A4493420FD214F9016F581C6EB10346D6 +:100DC00000F8016CF5E70020D8E75A25EDE7592532 +:100DD000EBE75825E9E7184605E02C2482421C7011 +:100DE00001D9981C5D70401AF0BD00BF0010005C76 +:100DF0001422002000207047022804D1054B4FF434 +:100E000080029A6170470128FCD1024B4FF4000226 +:100E1000F7E700BF00200258022803D1044B40220C +:100E20009A6170470128FCD1014B8022F8E700BF8E +:100E300000200258022805D1064A536983F0400376 +:100E4000536170470128FCD1024A536983F0800343 +:100E5000F6E700BF00200258002310B5934203D0EC +:100E6000CC5CC4540133F9E710BD0000013810B563 +:100E700010F9013F3BB191F900409C4203D11AB1F6 +:100E80000131013AF4E71AB191F90020981A10BD26 +:100E90001046FCE703460246D01A12F9011B00294E +:100EA000FAD1704702440346934202D003F8011B73 +:100EB000FAE770472DE9F8431F4D14460746884668 +:100EC00095F8242052BBDFF870909CB395F824303D +:100ED0002BB92022FF2148462F62FFF7E3FF95F848 +:100EE00024004146C0F1080205EB8000A24228BF61 +:100EF0002246D6B29200FFF7AFFF95F82430A41B2C +:100F000017441E449044E4B2F6B2082E85F82460DB +:100F1000DBD1FFF70BFF0028D7D108E02B6A03EBEA +:100F200082038342CFD0FFF701FF0028CBD10020FE +:100F3000BDE8F8830120FBE788230020024B1A78E4 +:100F4000024B1A70704700BFC823002010220020F7 +:100F500038B5164C164D204600F0FAFB29462046BF +:100F600000F022FC2D681348D5F89020D2F8043800 +:100F700043F00203C2F8043801F0E8F80E492846AD +:100F800000F020FDD5F890200C48D2F804380C4928 +:100F9000A04223F00203C2F804384FF4E1330B609F +:100FA00003D0BDE8384000F031BB38BDF029002047 +:100FB000B041000840420F00B8410008CC23002097 +:100FC000B023002038B50B4B04461A780A4B53F86F +:100FD00022500A4B9D420CD0094B00211822184682 +:100FE000FFF760FF046001462846BDE8384000F086 +:100FF0000DBB38BDC8230020A4400008F029002004 +:10100000B023002000B59BB0EFF309816822684649 +:10101000FFF722FFEFF30583044B9A6BDA6A9A6AB3 +:101020009A6A9A6A9A6A9A6A9B6AFEE700ED00E0F9 +:1010300000B59BB0EFF3098168226846FFF70CFF0B +:10104000EFF30583044B9A6B9A6A9A6A9A6A9A6AD2 +:101050009A6A9B6AFEE700BF00ED00E000B59BB016 +:10106000EFF3098168226846FFF7F6FEEFF3058388 +:10107000034B5A6B9A6A9A6A9A6A9A6A9B6AFEE763 +:1010800000ED00E0FEE7000030B50A44084D914253 +:101090000DD011F8013B5840082340F30004013BF8 +:1010A0002C4013F0FF0384EA5000F6D1EFE730BD87 +:1010B0002083B8ED026843681143016003B118470B +:1010C00070470000024A136843F0C0031360704782 +:1010D0000078004013B50E4C204600F08BFA04F166 +:1010E000140000234FF400720A49009400F04CF9F8 +:1010F000094B4FF40072094904F13800009400F0E4 +:10110000C5F9074A074BC4E9172302B010BD00BF59 +:10111000CC23002038240020C510000838260020E9 +:101120000078004000E1F505037C30B5244C00292F +:1011300018BF0C46012B11D1224B98420ED1224BE5 +:10114000D3F8E82042F08042C3F8E820D3F8102119 +:1011500042F08042C3F81021D3F810312268036EA8 +:10116000C16D03EB52038466B3FBF2F362681504AE +:1011700042BF23F0070503F0070343EA4503CB60B2 +:10118000A36843F040034B60E36843F001038B60C6 +:1011900042F4967343F001030B604FF0FF330B6290 +:1011A000510505D512F0102205D0B2F1805F04D0B0 +:1011B00080F8643030BD7F23FAE73F23F8E700BFB3 +:1011C000AC400008CC230020004402582DE9F04731 +:1011D000C66D05463768F4692107346219D014F0EA +:1011E000080118BF8021E20748BF41F02001A30792 +:1011F0004FF0200348BF41F04001600748BF41F471 +:10120000807183F31188281DFFF754FF002383F3B7 +:101210001188E2050AD5202383F311884FF4007169 +:10122000281DFFF747FF002383F311884FF02009A3 +:101230004FF0000A14F0200838D13B0616D54FF0C5 +:10124000200905F1380A200610D589F31188504687 +:1012500000F050F9002836DA0821281DFFF72AFF90 +:1012600027F080033360002383F31188790614D5B7 +:10127000620612D5202383F31188D5E913239A42FD +:1012800008D12B6C33B127F040071021281DFFF740 +:1012900011FF3760002383F31188E30618D5AA6E87 +:1012A0001369ABB15069BDE8F047184789F311885D +:1012B000736A284695F86410194000F0B5F98AF36E +:1012C0001188F469B6E7B06288F31188F469BAE767 +:1012D000BDE8F087F8B51546826804460B46AA4279 +:1012E00000D28568A1692669761AB5420BD21846E4 +:1012F0002A46FFF7B1FDA3692B44A3612846A368E2 +:101300005B1BA360F8BD0CD9AF1B18463246FFF734 +:10131000A3FD3A46E1683044FFF79EFDE3683B4495 +:10132000EBE718462A46FFF797FDE368E5E700007C +:1013300083689342F7B50446154600D28568D4E920 +:101340000460361AB5420BD22A46FFF785FD636961 +:101350002B4463612846A3685B1BA36003B0F0BD08 +:101360000DD93246AF1B0191FFF776FD01993A4640 +:10137000E0683144FFF770FDE3683B44E9E72A4643 +:10138000FFF76AFDE368E4E710B50A440024C3618F +:10139000029B8460C16002610362C0E90000C0E991 +:1013A000051110BD08B5D0E90532934201D182681C +:1013B00082B98268013282605A1C42611970002130 +:1013C000D0E904329A4224BFC368436100F0DAFED8 +:1013D000002008BD4FF0FF30FBE7000070B5202370 +:1013E00004460E4683F31188A568A5B1A368A269D7 +:1013F000013BA360531CA36115782269934224BF6B +:10140000E368A361E3690BB120469847002383F3A7 +:101410001188284607E03146204600F0A3FE002848 +:10142000E2DA85F3118870BD2DE9F74F04460E46C8 +:1014300017469846D0F81C904FF0200A8AF311887E +:101440004FF0000B154665B12A4631462046FFF79E +:1014500041FF034660B94146204600F083FE002864 +:10146000F1D0002383F31188781B03B0BDE8F08F1F +:10147000B9F1000F03D001902046C847019B8BF3C0 +:101480001188ED1A1E448AF31188DCE7C160C3613C +:10149000009B82600362C0E905111144C0E90000AD +:1014A00001617047F8B504460D461646202383F3C4 +:1014B0001188A768A7B1A368013BA36063695A1CA0 +:1014C00062611D70D4E904329A4224BFE36863610B +:1014D000E3690BB120469847002080F3118807E0AC +:1014E0003146204600F03EFE0028E2DA87F31188FC +:1014F000F8BD0000D0E9052310B59A4201D18268F9 +:101500007AB982680021013282605A1C82611C789B +:1015100003699A4224BFC368836100F033FE20460A +:1015200010BD4FF0FF30FBE72DE9F74F04460E46A4 +:1015300017469846D0F81C904FF0200A8AF311887D +:101540004FF0000B154665B12A4631462046FFF79D +:10155000EFFE034660B94146204600F003FE002836 +:10156000F1D0002383F31188781B03B0BDE8F08F1E +:10157000B9F1000F03D001902046C847019B8BF3BF +:101580001188ED1A1E448AF31188DCE7026843686B +:101590001143016003B11847704700001430FFF792 +:1015A00043BF00004FF0FF331430FFF73DBF000092 +:1015B0003830FFF7B9BF00004FF0FF333830FFF786 +:1015C000B3BF00001430FFF709BF00004FF0FF3138 +:1015D0001430FFF703BF00003830FFF763BF00008F +:1015E0004FF0FF323830FFF75DBF0000002070473A +:1015F000FFF770BD044B036000234360C0E9023372 +:1016000001230374704700BFC440000810B52023B5 +:10161000044683F31188FFF787FD02232374002318 +:1016200083F3118810BD000038B5C36904460D4628 +:101630001BB904210844FFF7A9FF294604F114004F +:10164000FFF7B0FE002806DA201D4FF48061BDE8E8 +:101650003840FFF79BBF38BD026843681143016003 +:1016600003B118477047000013B5406B00F5805474 +:10167000D4F8A4381A681178042914D1017C0229FD +:1016800011D11979012312898B4013420BD101A981 +:101690004C3002F06BF8D4F8A4480246019B217943 +:1016A000206800F0DFF902B010BD0000143001F036 +:1016B000EDBF00004FF0FF33143001F0E7BF000032 +:1016C0004C3002F0BFB800004FF0FF334C3002F056 +:1016D000B9B80000143001F0BBBF00004FF0FF317B +:1016E000143001F0B5BF00004C3002F08BB80000A0 +:1016F0004FF0FF324C3002F085B8000000207047F8 +:1017000010B500F58054D4F8A4381A68117804296B +:1017100017D1017C022914D15979012352898B40B8 +:1017200013420ED1143001F04DFF024648B1D4F8F7 +:10173000A4484FF4407361792068BDE8104000F080 +:101740007FB910BD406BFFF7DBBF000070470000A2 +:101750007FB5124B0125042604460360002305745F +:1017600000F1840243602946C0E902330C4B029029 +:10177000143001934FF44073009601F0FFFE094BC3 +:1017800004F69442294604F14C000294CDE900632A +:101790004FF4407301F0C6FF04B070BDEC40000888 +:1017A00045170008691600080A68202383F311888A +:1017B0000B790B3342F823004B79133342F82300A3 +:1017C0008B7913B10B3342F8230000F58053C3F833 +:1017D000A41802230374002383F3118870470000C8 +:1017E00038B5037F044613B190F85430ABB90125E6 +:1017F000201D0221FFF730FF04F114006FF00101FA +:10180000257700F0CBFC04F14C0084F854506FF0C5 +:101810000101BDE8384000F0C1BC38BD10B5012160 +:1018200004460430FFF718FF0023237784F8543070 +:1018300010BD000038B504460025143001F0B6FE96 +:1018400004F14C00257701F085FF201D84F85450E9 +:101850000121FFF701FF2046BDE83840FFF750BFE8 +:1018600090F8803003F06003202B06D190F881209F +:101870000023212A03D81F2A06D800207047222AD5 +:10188000FBD1C0E91D3303E0034A426707228267A8 +:10189000C3670120704700BF2C22002037B500F538 +:1018A0008055D5F8A4381A68117804291AD1017C1A +:1018B000022917D11979012312898B40134211D1C2 +:1018C00000F14C04204602F005F858B101A9204669 +:1018D00001F04CFFD5F8A4480246019B217920680D +:1018E00000F0C0F803B030BD01F10B03F0B550F8C3 +:1018F000236085B004460D46FEB1202383F3118892 +:1019000004EB8507301D0821FFF7A6FEFB6806F1F2 +:101910004C005B691B681BB1019001F035FF019819 +:1019200003A901F023FF024648B1039B2946204644 +:1019300000F098F8002383F3118805B0F0BDFB6830 +:101940005A691268002AF5D01B8A013B1340F1D175 +:1019500004F18002EAE70000133138B550F8214065 +:10196000ECB1202383F3118804F58053D3F8A42825 +:101970001368527903EB8203DB689B695D6845B1AC +:1019800004216018FFF768FE294604F1140001F0F5 +:1019900023FE2046FFF7B4FE002383F3118838BDF1 +:1019A0007047000001F016B901234022002110B554 +:1019B000044600F8303BFFF775FA0023C4E9013311 +:1019C00010BD000010B52023044683F311882422A3 +:1019D000416000210C30FFF765FA204601F01CF948 +:1019E00002232370002383F3118810BD70B500EB30 +:1019F0008103054650690E461446DA6018B110227C +:101A00000021FFF74FFAA06918B110220021FFF75B +:101A100049FA31462846BDE8704001F00FBA00008F +:101A200083682022002103F0011310B5044683606F +:101A30001030FFF737FA2046BDE8104001F08ABAAF +:101A4000F0B4012500EB810447898D40E4683D43F3 +:101A5000A469458123600023A2606360F0BC01F0AB +:101A6000A7BA0000F0B4012500EB810407898D407E +:101A7000E4683D436469058123600023A2606360DC +:101A8000F0BC01F01DBB000070B502230025044628 +:101A9000242203702946C0F888500C3040F8045CBA +:101AA000FFF700FA204684F8705001F05BF9636894 +:101AB0001B6823B129462046BDE87040184770BD19 +:101AC000037880F88C300523037043681B6810B5D9 +:101AD00004460BB1042198470023A36010BD000009 +:101AE00090F88C20436802701B680BB105211847E1 +:101AF0007047000070B590F87030044613B10023B1 +:101B000080F8703004F18002204601F047FA6368E3 +:101B10009B68B3B994F8803013F0600535D000218C +:101B2000204601F0F1FC0021204601F0E1FC636851 +:101B30001B6813B1062120469847062384F87030AD +:101B400070BD204698470028E4D0B4F88630A26FD4 +:101B50009A4288BFA36794F98030A56F002B4FF09D +:101B6000200380F20381002D00F0F280092284F826 +:101B7000702083F3118800212046D4E91D23FFF74C +:101B800071FF002383F31188DAE794F8812003F0D2 +:101B90007F0343EA022340F20232934200F0C58001 +:101BA00021D8B3F5807F48D00DD8012B3FD0022B30 +:101BB00000F09380002BB2D104F188026267022208 +:101BC000A267E367C1E7B3F5817F00F09B80B3F5BF +:101BD000407FA4D194F88230012BA0D1B4F8883092 +:101BE00043F0020332E0B3F5006F4DD017D8B3F5E0 +:101BF000A06F31D0A3F5C063012B90D86368204655 +:101C000094F882205E6894F88310B4F88430B0476A +:101C1000002884D0436863670368A3671AE0B3F5BC +:101C2000106F36D040F6024293427FF478AF5C4B9F +:101C300063670223A3670023C3E794F88230012B74 +:101C40007FF46DAFB4F8883023F00203A4F8883035 +:101C5000C4E91D55E56778E7B4F88030B3F5A06FA7 +:101C60000ED194F88230204684F88A3001F0D8F8FA +:101C700063681B6813B10121204698470323237032 +:101C80000023C4E91D339CE704F18B036367012340 +:101C9000C3E72378042B10D1202383F31188204637 +:101CA000FFF7BEFE85F311880321636884F88B502B +:101CB00021701B680BB12046984794F88230002BA6 +:101CC000DED084F88B300423237063681B68002BFC +:101CD000D6D0022120469847D2E794F88430204697 +:101CE0001D0603F00F010AD501F04AF9012804D0BE +:101CF00002287FF414AF2B4B9AE72B4B98E701F0A7 +:101D000031F9F3E794F88230002B7FF408AF94F8B0 +:101D1000843013F00F01B3D01A06204602D501F02B +:101D20000BFCADE701F0FCFBAAE794F88230002B36 +:101D30007FF4F5AE94F8843013F00F01A0D01B06A9 +:101D4000204602D501F0E0FB9AE701F0D1FB97E7CE +:101D5000142284F8702083F311882B462A462946E2 +:101D60002046FFF76DFE85F31188E9E65DB1152287 +:101D700084F8702083F3118800212046D4E91D23C4 +:101D8000FFF75EFEFDE60B2284F8702083F31188D6 +:101D90002B462A4629462046FFF764FEE3E700BFAC +:101DA0001C410008144100081841000838B590F89B +:101DB00070300446002B3ED0063BDAB20F2A34D8EE +:101DC0000F2B32D8DFE803F03731310822323131BE +:101DD0003131313131313737856FB0F886309D423E +:101DE00014D2C3681B8AB5FBF3F203FB12556DB91D +:101DF000202383F311882B462A462946FFF732FE1B +:101E000085F311880A2384F870300EE0142384F8D7 +:101E10007030202383F31188002320461A46194688 +:101E2000FFF70EFE002383F3118838BDC36F03B1A3 +:101E300098470023E7E70021204601F065FB0021D9 +:101E4000204601F055FB63681B6813B1062120464C +:101E500098470623D7E7000010B590F87030044685 +:101E6000142B29D017D8062B05D001D81BB110BDD3 +:101E7000093B022BFBD80021204601F045FB002145 +:101E8000204601F035FB63681B6813B1062120462C +:101E90009847062319E0152BE9D10B2380F8703001 +:101EA000202383F3118800231A461946FFF7DAFD31 +:101EB000002383F31188DAE7C3689B695B68002B12 +:101EC000D5D1C36F03B19847002384F87030CEE7B3 +:101ED000024B0022C3E900339A6070473828002083 +:101EE000002382680374054B1B6899689142FBD2FA +:101EF0005A680360426010605860704738280020BC +:101F000008B5202383F31188037C032B05D0042B11 +:101F10000DD02BB983F3118808BD436900221A60E4 +:101F20004FF0FF334361FFF7DBFF0023F2E7D0E917 +:101F3000003213605A60F3E7002382680374054B94 +:101F40001B6899689142FBD85A6803604260106030 +:101F50005860704738280020054B196908741868C4 +:101F6000026853601A60186101230374FEF72EBAE9 +:101F7000382800204B1C30B5044687B00A4D10D0DD +:101F80002B6901A8094A00F025F92046FFF7E4FF74 +:101F9000049B13B101A800F059F92B69586907B0E7 +:101FA00030BDFFF7D9FFF8E738280020011F0008EF +:101FB00038B50C4D044641612B6981689A6891429D +:101FC00003D8BDE83840FFF78BBF1846FFF7B4FFD2 +:101FD00001232C61014623742046BDE83840FEF7FA +:101FE000F5B900BF38280020044B1A681B699068B7 +:101FF0009B68984294BF0020012070473828002039 +:1020000010B5084C236820691A68546022600122C8 +:1020100023611A74FFF790FF01462069BDE8104064 +:10202000FEF7D4B93828002008B5FFF7DDFF18B156 +:10203000BDE80840FFF7E4BF08BD0000FFF7E0BFC0 +:10204000FEE7000010B50C4CFFF742FF00F0B4F8BB +:1020500080220A49204600F03BF8012344F8180C7E +:10206000037400F095FC002383F3118862B60448E2 +:10207000BDE8104000F04CB8602800202041000866 +:102080003041000800F01CB9EFF3118020B9EFF3E4 +:102090000583202282F311887047000010B530B903 +:1020A000EFF30584C4F3080414B180F3118810BD64 +:1020B000FFF7BAFF84F31188F9E70000034A51687B +:1020C00053685B1A9842FBD8704700BF001000E0CD +:1020D00082600222028270478368A3F17C0243F887 +:1020E0000C2C026943F83C2C426943F8382C074A0F +:1020F00043F81C2CC268A3F1180043F8102C0222EC +:1021000003F8082C002203F8072C7047E5030008A9 +:1021100010B5202383F31188FFF7DEFF002104466A +:10212000FFF746FF002383F31188204610BD00000F +:10213000024B1B6958610F20FFF70EBF38280020A3 +:10214000202383F31188FFF7F3BF000008B5014691 +:10215000202383F311880820FFF70CFF002383F36B +:10216000118808BD49B1064B42681B6918605A6066 +:10217000136043600420FFF7FDBE4FF0FF3070474F +:10218000382800200368984206D01A680260506020 +:1021900018465961FFF7A4BE7047000038B50446E1 +:1021A0000D462068844200D138BD036823605C601E +:1021B0004561FFF795FEF4E7054B4FF0FF3103F162 +:1021C0001402C3E905220022C3E90712704700BFC9 +:1021D0003828002070B51C4E05460C46C0E9032384 +:1021E00001F0AAFB334653F8142F9A420DD1306206 +:1021F0000A2C2CBF00190A302A60C5E90124C6E95F +:102200000555BDE8704001F085BB316A431AE318FB +:1022100038BF1C469368A34202D9081901F088FB15 +:1022200073699A6894420CD85A68AC602B606A60F3 +:1022300015609A685D60121B9A604FF0FF33F3617E +:1022400070BDA41A1B68ECE73828002038B51B4C79 +:10225000636998420DD08168D0E9003213605A60FA +:102260000022C2609A680A449A604FF0FF33E3612B +:1022700038BD03682246002142F8143F93425A6059 +:10228000C16003D1BDE8384001F04CBB9A68816859 +:10229000256A0A449A6001F04FFB6369411B9A6802 +:1022A0008A42E5D9AB181D1A206A092D98BF01F1A1 +:1022B0000A02BDE83840104401F03ABB382800203B +:1022C0002DE9F041184C002704F11406656901F06E +:1022D00033FB236AAA68C11A8A4215D81344D5F879 +:1022E0000C802362D5E9003213605A606369EF60A5 +:1022F000B34201D101F016FB87F311882869C0476A +:10230000202383F31188E1E76169B14209D01344C6 +:102310001B1ABDE8F0410A2B2CBFC0180A3001F08F +:1023200007BBBDE8F08100BF3828002000207047BF +:10233000FEE70000704700004FF0FF3070470000DC +:1023400002290CD0032904D00129074818BF002016 +:102350007047032A05D8054800EBC20070470448BF +:1023600070470020704700BF144200083C22002044 +:10237000C841000870B59AB005460846144601A940 +:1023800000F0C2F801A8FEF785FD431C0022C6B28A +:102390005B001046C5E9003423700323023404F8BF +:1023A000013C01ABD1B202348E4201D81AB070BDEB +:1023B00013F8011B013204F8010C04F8021CF1E7C8 +:1023C00008B5202383F311880348FFF767FA002339 +:1023D00083F3118808BD00BFF029002090F88030F9 +:1023E00003F01F02012A07D190F881200B2A03D1A4 +:1023F0000023C0E91D3315E003F06003202B08D152 +:10240000B0F884302BB990F88120212A03D81F2AF4 +:1024100004D8FFF725BA222AEBD0FAE7034A42672D +:1024200007228267C3670120704700BF3322002064 +:1024300007B5052917D8DFE801F019160319192087 +:10244000202383F31188104A01210190FFF7CEFA6F +:10245000019802210D4AFFF7C9FA0D48FFF7EAF982 +:10246000002383F3118803B05DF804FB202383F37A +:1024700011880748FFF7B4F9F2E7202383F31188A6 +:102480000348FFF7CBF9EBE7684100088C410008EF +:10249000F029002038B50C4D0C4C2A460C4904F1AB +:1024A0000800FFF767FF05F1CA0204F110000949AF +:1024B000FFF760FF05F5CA7204F118000649BDE890 +:1024C0003840FFF757BF00BFC84200203C22002021 +:1024D00048410008524100085D41000870B50446BB +:1024E00008460D46FEF7D6FCC6B2204601340378F6 +:1024F0000BB9184670BD32462946FEF7B7FC0028D6 +:10250000F3D10120F6E700002DE9F04705460C461F +:10251000FEF7C0FC2A49C6B22846FFF7DFFF08B124 +:102520000936F6B227492846FFF7D8FF08B110361A +:10253000F6B2632E0BD8DFF88880DFF88890224F40 +:10254000DFF890A02E7846B92670BDE8F0872946BE +:102550002046BDE8F04701F08FBD252E2CD1072283 +:1025600041462846FEF782FC60B9184B224603F12B +:10257000100153F8040B8B4242F8040BF9D10735D4 +:102580001034DFE7082249462846FEF76FFC98B969 +:10259000A21C0F4B197802320909C95D02F8041C0C +:1025A00013F8011B01F00F015345C95D02F8031C2C +:1025B000F0D118340835C5E7013504F8016BC1E7DF +:1025C000344200085D4100084D4200083C420008CA +:1025D00000E8F11F0CE8F11FBFF34F8F044B1A699D +:1025E0005107FCD1D3F810215207F8D1704700BF32 +:1025F0000020005208B50D4B1B78ABB9FFF7ECFF7C +:102600000B4BDA68D10704D50A4A5A6002F18832C6 +:102610005A60D3F80C21D20706D5064AC3F8042124 +:1026200002F18832C3F8042108BD00BF264500200E +:10263000002000522301674508B5114B1B78F3B900 +:10264000104B1A69510703D5DA6842F04002DA608C +:10265000D3F81021520705D5D3F80C2142F04002DF +:10266000C3F80C21FFF7B8FF064BDA6842F001020D +:10267000DA60D3F80C2142F00102C3F80C2108BD46 +:1026800026450020002000520F289ABF00F58060E8 +:1026900040040020704700004FF4003070470000F5 +:1026A000102070470F2808B50BD8FFF7EDFF00F595 +:1026B00000330268013204D104308342F9D1012091 +:1026C00008BD0020FCE700000F2870B5054645D87E +:1026D000FFF7DAFC224CFFF77FFF0646FFF78AFF81 +:1026E0004FF0FF33072D6361C4F8143120D8236104 +:1026F000FFF772FF2B0243F02403E360E36843F02B +:102700008003E36023695A07FCD42846FFF764FF7F +:102710004FF40031FFF7B8FF00F002F93046FFF741 +:102720008BFFFFF7BBFC2846BDE87040FFF7BABF40 +:10273000C4F81031FFF750FFA5F108031B0243F066 +:102740002403C4F80C31D4F80C3143F08003C4F8EE +:102750000C31D4F810315B07FBD4D6E7002070BDF4 +:10276000002000522DE9F84F40EA020305460C46CE +:102770001746D80602D00020BDE8F88F27F01F07C3 +:10278000DFF8D4B0FFF736FF2744BC4203D1012065 +:10279000FFF752FFF0E720222946204601F05CFCBB +:1027A00010B920352034F0E72B4605F120021E68D1 +:1027B000711CE0D104339A42F9D1FFF765FC05F1B1 +:1027C0007843234AB3F5801F224B28BF9A4603F172 +:1027D000040338BF9046A2F1080228BF9846A3F12F +:1027E00008033ABF9146DA469946FFF7F5FEC8F866 +:1027F0000060A5EB040CD9F8002004F11C0142F0A4 +:102800000202C9F80020221FDAF8006016F005065F +:10281000FAD152F8043F8A424CF80230F4D1BFF3A7 +:102820004F8FFFF7D9FE4FF0FF32C8F80020D9F8DC +:10283000002022F00202C9F80020FFF72FFC20221E +:102840002146284601F008FC0028AAD030469FE720 +:1028500014200052102100521020005210B5084CD4 +:10286000237828B11BB9FFF7C5FE0123237010BDE3 +:10287000002BFCD02070BDE81040FFF7DDBE00BF8C +:10288000264500200244074BD2B210B5904200D139 +:1028900010BD441C00B253F8200041F8040BE0B214 +:1028A000F4E700BF504000580E4B30B51C6F2404B5 +:1028B00005D41C6F1C671C6F44F400441C670A4C51 +:1028C00002442368D2B243F480732360074B9042E2 +:1028D00000D130BD441C51F8045B00B243F82050D5 +:1028E000E0B2F4E700440258004802585040005853 +:1028F00007B5012201A90020FFF7C4FF019803B02A +:102900005DF804FB13B50446FFF7F2FFA04205D0C3 +:10291000012201A900200194FFF7C6FF02B010BDFB +:102920000144BFF34F8F064B884204D3BFF34F8F50 +:10293000BFF36F8F7047C3F85C022030F4E700BF2D +:1029400000ED00E0034B1A681AB9034AD2F8D0240C +:102950001A607047284500200040025808B5FFF76C +:10296000F1FF024B1868C0F3806008BD28450020C5 +:10297000EFF30983054968334A6B22F001024A6389 +:1029800083F30988002383F31188704700EF00E088 +:10299000202080F3118862B60D4B0E4AD96821F4CD +:1029A000E0610904090C0A430B49DA60D3F8FC2002 +:1029B00042F08072C3F8FC20084AC2F8B01F1168C8 +:1029C00041F0010111601022DA7783F8220070478C +:1029D00000ED00E00003FA0555CEACC5001000E0A4 +:1029E000202310B583F311880E4B5B6813F400634A +:1029F00014D0F1EE103AEFF309844FF08073683C85 +:102A0000E361094BDB6B236684F30988FFF7ECFA7B +:102A100010B1064BA36110BD054BFBE783F3118892 +:102A2000F9E700BF00ED00E000EF00E0F703000869 +:102A3000FA03000870B5BFF34F8FBFF36F8F1A4AC8 +:102A40000021C2F85012BFF34F8FBFF36F8F53694D +:102A500043F400335361BFF34F8FBFF36F8FC2F85E +:102A60008410BFF34F8FD2F8803043F6E074C3F385 +:102A7000C900C3F34E335B0103EA0406014646EA8C +:102A800081750139C2F86052F9D2203B13F1200F51 +:102A9000F2D1BFF34F8F536943F480335361BFF3D7 +:102AA0004F8FBFF36F8F70BD00ED00E0FEE70000B9 +:102AB0000A4B0B480B4A90420BD30B4BC11EDA1C3E +:102AC000121A22F003028B4238BF00220021FEF7C7 +:102AD000E9B953F8041B40F8041BECE72C44000848 +:102AE000FC460020FC460020FC4600207047000009 +:102AF00070B5D0E9244300224FF0FF359E6804EB07 +:102B000042135101D3F80009002805DAD3F800096F +:102B100040F08040C3F80009D3F8000B002805DA24 +:102B2000D3F8000B40F08040C3F8000B013263186B +:102B30009642C3F80859C3F8085BE0D24FF001137E +:102B4000C4F81C3870BD000000EB8103D3F80CC042 +:102B50002DE9F043DCF814204E1CD0F89050D2F848 +:102B600000E005EB063605EB4118506870450AD3C6 +:102B70000122D5F8343802FA01F123EA0101C5F83F +:102B80003418BDE8F083AEEB0003BCF81040A3425C +:102B900028BF2346D8F81849A4B2B3EB840FF0D865 +:102BA0009468A4F1040959F8047F3760A4EB09077D +:102BB0001F44042FF7D81C44034494605360D4E7A7 +:102BC000890141F02001016103699B06FCD41220B8 +:102BD000FFF774BA10B50A4C2046FEF7E5FE094B24 +:102BE000C4F89030084BC4F89430084C2046FEF7E7 +:102BF000DBFE074BC4F89030064BC4F8943010BD90 +:102C00002C4500200000084084420008C8450020F0 +:102C1000000004409042000870B503780546012B7F +:102C20005DD1494BD0F89040984259D1474B0E2185 +:102C30006520D3F8D82042F00062C3F8D820D3F83A +:102C4000002142F00062C3F80021D3F80021D3F83C +:102C5000802042F00062C3F88020D3F8802022F068 +:102C60000062C3F88020D3F8803000F071FC384B4C +:102C7000E360384BC4F800380023D5F89060C4F8FE +:102C8000003EC02323604FF40413A3633369002B79 +:102C9000FCDA01230C203361FFF710FA3369DB07FC +:102CA000FCD41220FFF70AFA3369002BFCDA002665 +:102CB0002846A660FFF71CFF6B68C4F81068DB6845 +:102CC000C4F81468C4F81C68002B3AD1224BA361E5 +:102CD0004FF0FF336361A36843F00103A36070BD4D +:102CE0001E4B9842C8D1194B0E214D20D3F8D82045 +:102CF00042F00072C3F8D820D3F8002142F00072ED +:102D0000C3F80021D3F80021D3F8802042F00072EC +:102D1000C3F88020D3F8802022F00072C3F880200E +:102D2000D3F88020D3F8D82022F08062C3F8D820CE +:102D3000D3F8002122F08062C3F80021D3F80031DB +:102D400093E7074BC3E700BF2C450020004402581F +:102D50004014004003002002003C30C0C845002061 +:102D6000083C30C0F8B5D0F89040054600214FF03F +:102D700000662046FFF724FFD5F8941000234FF09B +:102D800001128F684FF0FF30C4F83438C4F81C28A3 +:102D900004EB431201339F42C2F80069C2F8006B92 +:102DA000C2F80809C2F8080BF2D20B68D5F89020D7 +:102DB000C5F89830636210231361166916F0100687 +:102DC000FBD11220FFF77AF9D4F8003823F4FE6320 +:102DD000C4F80038A36943F4402343F01003A3610F +:102DE0000923C4F81038C4F814380B4BEB604FF0CB +:102DF000C043C4F8103B094BC4F8003BC4F8106949 +:102E0000C4F80039D5F8983003F1100243F4801368 +:102E1000C5F89820A362F8BD604200084080001009 +:102E2000D0F8902090F88A10D2F8003823F4FE638E +:102E300043EA0113C2F80038704700002DE9F84357 +:102E400000EB8103D0F890500C468046DA680FFA08 +:102E500081F94801166806F00306731E022B05EB84 +:102E600041134FF0000194BFB604384EC3F8101B55 +:102E70004FF0010104F1100398BF06F1805601FAEA +:102E800003F3916998BF06F5004600293AD0578AA6 +:102E900004F15801374349016F50D5F81C180B4312 +:102EA0000021C5F81C382B180127C3F81019A740BA +:102EB0005369611E9BB3138A928B9B08012A88BFBA +:102EC0005343D8F89820981842EA034301F140028E +:102ED0002146C8F89800284605EB82025360FFF7A8 +:102EE0006FFE08EB8900C3681B8A43EA84534834A9 +:102EF0001E4364012E51D5F81C381F43C5F81C78B9 +:102F0000BDE8F88305EB4917D7F8001B21F4004111 +:102F1000C7F8001BD5F81C1821EA0303C0E704F129 +:102F20003F030B4A2846214605EB83035A60FFF70F +:102F300047FE05EB4910D0F8003923F40043C0F8F0 +:102F40000039D5F81C3823EA0707D7E700800010BE +:102F500000040002D0F894201268C0F89820FFF70F +:102F6000C7BD00005831D0F8903049015B5813F4C8 +:102F7000004004D013F4001F0CBF02200120704752 +:102F80004831D0F8903049015B5813F4004004D028 +:102F900013F4001F0CBF02200120704700EB8101D9 +:102FA000CB68196A0B6813604B6853607047000068 +:102FB00000EB810330B5DD68AA691368D36019B9E5 +:102FC000402B84BF402313606B8A1468D0F8902094 +:102FD0001C4402EB4110013C09B2B4FBF3F463431F +:102FE000033323F0030343EAC44343F0C043C0F870 +:102FF000103B2B6803F00303012B0ED1D2F80838E5 +:1030000002EB411013F4807FD0F8003B14BF43F073 +:10301000805343F00053C0F8003B02EB4112D2F85A +:10302000003B43F00443C2F8003B30BD2DE9F041C2 +:10303000D0F8906005460C4606EB4113D3F8087BA8 +:103040003A07C3F8087B08D5D6F814381B0704D50F +:1030500000EB8103DB685B689847FA071FD5D6F859 +:103060001438DB071BD505EB8403D968CCB98B6911 +:10307000488A5A68B2FBF0F600FB16228AB9186833 +:10308000DA6890420DD2121AC3E90024202383F398 +:10309000118821462846FFF78BFF84F31188BDE88D +:1030A000F081012303FA04F26B8923EA02036B81A6 +:1030B000CB68002BF3D021462846BDE8F0411847E5 +:1030C00000EB81034A0170B5DD68D0F890306C697F +:1030D0002668E66056BB1A444FF40020C2F8100977 +:1030E0002A6802F00302012A0AB20ED1D3F80808B6 +:1030F00003EB421410F4807FD4F8000914BF40F0B1 +:10310000805040F00050C4F8000903EB4212D2F89E +:10311000000940F00440C2F800090122D3F8340845 +:1031200002FA01F10143C3F8341870BD19B9402EF9 +:1031300084BF4020206020681A442E8A8419013CF4 +:10314000B4FBF6F440EAC44040F00050C6E700008B +:103150002DE9F041D0F8906004460D4606EB41138E +:10316000D3F80879C3F80879FB071CD5D6F81038CE +:10317000DA0718D500EB8103D3F80CC0DCF8143063 +:10318000D3F800E0DA6896451BD2A2EB0E024FF0AE +:1031900000081A60C3F80480202383F31188FFF726 +:1031A0008FFF88F311883B0618D50123D6F8342801 +:1031B000AB40134212D029462046BDE8F041FFF74C +:1031C000C3BC012303FA01F2038923EA020303814A +:1031D000DCF80830002BE6D09847E4E7BDE8F08142 +:1031E0002DE9F84FD0F8905004466E69AB691E4047 +:1031F00016F480586E6103D0BDE8F84FFEF744BC6A +:10320000002E12DAD5F8003E9F0705D0D5F8003E13 +:1032100023F00303C5F8003ED5F80438204623F018 +:103220000103C5F80438FEF75BFC300505D52046E0 +:10323000FFF75EFC2046FEF743FCB1040CD5D5F841 +:10324000083813F0060FEB6823F470530CBF43F4F7 +:10325000105343F4A053EB60320704D56368DB6876 +:103260000BB120469847F30200F1BA80B70226D589 +:10327000D4F8909000274FF0010A09EB4712D2F8DA +:10328000003B03F44023B3F5802F11D1D2F8003B6B +:10329000002B0DDA62890AFA07F322EA030363813D +:1032A00004EB8703DB68DB6813B139462046984797 +:1032B0000137D4F89430FFB29B689F42DDD9F00605 +:1032C00019D5D4F89000026AC2F30A1702F00F036E +:1032D00002F4F012B2F5802F00F0CC80B2F5402F4E +:1032E00009D104EB8303002200F58050DB681B6AE0 +:1032F000974240F0B2803003D5F8185835D5E9032D +:1033000003D500212046FFF791FEAA0303D5012132 +:103310002046FFF78BFE6B0303D502212046FFF703 +:1033200085FE2F0303D503212046FFF77FFEE80229 +:1033300003D504212046FFF779FEA90203D5052114 +:103340002046FFF773FE6A0203D506212046FFF7E9 +:103350006DFE2B0203D507212046FFF767FEEF0124 +:1033600003D508212046FFF761FE700340F1A980D4 +:10337000E90703D500212046FFF7EAFEAA0703D597 +:1033800001212046FFF7E4FE6B0703D5022120460A +:10339000FFF7DEFE2F0703D503212046FFF7D8FEF7 +:1033A000EE0603D504212046FFF7D2FEA80603D57A +:1033B00005212046FFF7CCFE690603D506212046ED +:1033C000FFF7C6FE2A0603D507212046FFF7C0FEF9 +:1033D000EB0576D520460821BDE8F84FFFF7B8BECB +:1033E000D4F8909000274FF0010AD4F894305FFA97 +:1033F00087FB9B689B453FF639AF09EB4B13D3F82E +:10340000002902F44022B2F5802F24D1D3F80029FC +:10341000002A20DAD3F8002942F09042C3F80029AC +:10342000D3F80029002AFBDB5946D4F89000FFF7B7 +:10343000C7FB22890AFA0BF322EA0303238104EB78 +:103440008B03DB689B6813B1594620469847594661 +:103450002046FFF779FB0137C7E7910701D1D0F884 +:103460000080072A02F101029CBF03F8018B4FEA9A +:1034700018283DE704EB830300F58050DA68D2F8A2 +:1034800018C0DCF80820DCE9001CA1EB0C0C0021C2 +:103490008F4208D1DB689B699A683A449A605A68FF +:1034A0003A445A6027E711F0030F01D1D0F80080A9 +:1034B0008C4501F1010184BF02F8018B4FEA182805 +:1034C000E6E7BDE8F88F000008B50348FFF788FE7F +:1034D000BDE80840FFF784BA2C45002008B5034832 +:1034E000FFF77EFEBDE80840FFF77ABAC845002026 +:1034F000D0F8903003EB4111D1F8003B43F40013B6 +:10350000C1F8003B70470000D0F8903003EB411148 +:10351000D1F8003943F40013C1F8003970470000B6 +:10352000D0F8903003EB4111D1F8003B23F40013A5 +:10353000C1F8003B70470000D0F8903003EB411118 +:10354000D1F8003923F40013C1F8003970470000A6 +:10355000090100F16043012203F56143C9B283F818 +:10356000001300F01F039A4043099B0003F16043DE +:1035700003F56143C3F880211A60704730B5043306 +:10358000039C0172002104FB0325C160C0E90653BE +:10359000049B0363059BC0E90000C0E90422C0E965 +:1035A0000842C0E90A11436330BD00000022416AAD +:1035B000C260C0E90411C0E90A226FF00101FEF700 +:1035C000EDBD0000D0E90432934201D1C2680AB9CE +:1035D000181D704700207047036919600021C268F8 +:1035E0000132C260C269134482699342036124BFFD +:1035F000436A0361FEF7C6BD38B504460D46E3686D +:103600003BB162690020131D1268A3621344E36298 +:1036100007E0237A33B929462046FEF7A3FD0028A8 +:10362000EDDA38BD6FF00100FBE70000C368C26946 +:10363000013BC3604369134482699342436124BFE1 +:10364000436A436100238362036B03B118477047E9 +:1036500070B52023044683F31188866A3EB9FFF7CC +:10366000CBFF054618B186F31188284670BDA36AC2 +:10367000E26A13F8015B9342A36202D32046FFF78C +:10368000D5FF002383F31188EFE700002DE9F84F01 +:1036900004460E46174698464FF0200989F31188D4 +:1036A0000025AA46D4F828B0BBF1000F09D1414645 +:1036B0002046FFF7A1FF20B18BF311882846BDE813 +:1036C000F88FD4E90A12A7EB050B521A934528BFCD +:1036D0009346BBF1400F1BD9334601F1400251F82C +:1036E000040B914243F8040BF9D1A36A40364035EC +:1036F0004033A362D4E90A239A4202D32046FFF75B +:1037000095FF8AF31188BD42D8D289F31188C9E7A1 +:1037100030465A46FDF7A0FBA36A5E445D445B4415 +:10372000A362E7E710B5029C0433017204FB032196 +:10373000C460C0E906130023C0E90A33039B036396 +:10374000049BC0E90000C0E90422C0E908424363C9 +:1037500010BD0000026A6FF00101C260426AC0E958 +:1037600004220022C0E90A22FEF718BDD0E9042392 +:103770009A4201D1C26822B9184650F8043B0B6046 +:103780007047002070470000C3680021C269013300 +:10379000C3604369134482699342436124BF436A0F +:1037A0004361FEF7EFBC000038B504460D46E36800 +:1037B0003BB1236900201A1DA262E2691344E3624F +:1037C00007E0237A33B929462046FEF7CBFC0028D0 +:1037D000EDDA38BD6FF00100FBE700000369196006 +:1037E000C268013AC260C2691344826993420361AC +:1037F00024BF436A036100238362036B03B118474C +:103800007047000070B520230D460446114683F32F +:103810001188866A2EB9FFF7C7FF10B186F31188A9 +:1038200070BDA36A1D70A36AE26A01339342A3626A +:1038300004D3E16920460439FFF7D0FF002080F36C +:103840001188EDE72DE9F84F04460D46904699465C +:103850004FF0200A8AF311880026B346A76A4FB9B1 +:1038600049462046FFF7A0FF20B187F31188304674 +:10387000BDE8F88FD4E90A073A1AA8EB0607974281 +:1038800028BF1746402F1BD905F1400355F8042BDC +:103890009D4240F8042BF9D1A36A40364033A3621D +:1038A000D4E90A239A4204D3E16920460439FFF798 +:1038B00095FF8BF311884645D9D28AF31188CDE75D +:1038C00029463A46FDF7C8FAA36A3D443E443B44C4 +:1038D000A362E5E7D0E904239A4217D1C3689BB1FC +:1038E000836A8BB1043B9B1A0ED01360C368013B03 +:1038F000C360C3691A4483699A42026124BF436A60 +:103900000361002383620123184670470023FBE70D +:1039100000F0D4B84FF08043002258631A610222AD +:10392000DA6070474FF080430022DA607047000091 +:103930004FF08043586370474FF08043586A704798 +:103940004B6843608B688360CB68C3600B694361DD +:103950004B6903628B6943620B6803607047000028 +:1039600008B53C4B40F2FF713B48D3F888200A432E +:10397000C3F88820D3F8882022F4FF6222F00702DF +:10398000C3F88820D3F88820D3F8E0200A43C3F88E +:10399000E020D3F808210A43C3F808212F4AD3F8BE +:1039A00008311146FFF7CCFF00F5806002F11C01E1 +:1039B000FFF7C6FF00F5806002F13801FFF7C0FF96 +:1039C00000F5806002F15401FFF7BAFF00F5806056 +:1039D00002F17001FFF7B4FF00F5806002F18C0185 +:1039E000FFF7AEFF00F5806002F1A801FFF7A8FF26 +:1039F00000F5806002F1C401FFF7A2FF00F58060CE +:103A000002F1E001FFF79CFF00F5806002F1FC018C +:103A1000FFF796FF02F58C7100F58060FFF790FFCD +:103A200000F0FEF80E4BD3F8902242F00102C3F8EA +:103A30009022D3F8942242F00102C3F89422052286 +:103A4000C3F898204FF06052C3F89C20054AC3F891 +:103A5000A02008BD00440258000002589C42000803 +:103A600000ED00E01F00080308B500F0D5FAFEF7EE +:103A7000E9FA0F4BD3F8DC2042F04002C3F8DC2017 +:103A8000D3F8042122F04002C3F80421D3F8043112 +:103A9000084B1A6842F008021A601A6842F00402E1 +:103AA0001A60FEF74FFFBDE80840FEF7F3BC00BF09 +:103AB000004402580018024870470000114BD3F828 +:103AC000E82042F00102C3F8E820D3F8102142F0C8 +:103AD0000102C3F810210C4AD3F81031D36B43F024 +:103AE0000103D3634FF08043C7229A624FF0FF3245 +:103AF000DA6200229A615A63DA605A6001225A61DE +:103B00001A607047004402580010005C4FF0804279 +:103B100008B51169D3680B40D9B29B076FEA010160 +:103B2000116107D5202383F31188FEF7ABFA002338 +:103B300083F3118808BD0000384B4FF0FF31D3F8F4 +:103B40008020C3F88010D3F880200022C3F88020A2 +:103B5000D3F88000D3F88400C3F88410D3F884002D +:103B6000C3F88420D3F88400D86F40F0FF4040F4BD +:103B7000FF0040F43F5040F03F00D867D86F20F07E +:103B8000FF4020F4FF0020F43F5020F03F00D867B2 +:103B9000D86FD3F888006FEA40506FEA5050C3F8EE +:103BA0008800D3F88800C0F30A00C3F88800D3F86F +:103BB0008800D3F89000C3F89010D3F89000C3F8B1 +:103BC0009020D3F89000D3F89400C3F89410D3F861 +:103BD0009400C3F89420D3F89400D3F89800C3F865 +:103BE0009810D3F89800C3F89820D3F89800D3F829 +:103BF0008C00C3F88C10D3F88C00C3F88C20D3F859 +:103C00008C00D3F89C00C3F89C10D3F89C10C3F828 +:103C10009C20D3F89C3000F0D3B900BF0044025878 +:103C2000614B0122C3F80821604BD3F8F42042F025 +:103C30000202C3F8F420D3F81C2142F00202C3F8B8 +:103C40001C210222D3F81C31594BDA605A689104C6 +:103C5000FCD5584A1A6001229A60574ADA6000225D +:103C60001A614FF440429A61514B9A699204FCD513 +:103C70001A6842F480721A604C4B1A6F12F4407F3B +:103C800004D04FF480321A6700221A671A6842F093 +:103C900001021A60454B1A685007FCD500221A61D0 +:103CA0001A6912F03802FBD1012119604FF08041EE +:103CB00059605A67414ADA62414A1A611A6842F405 +:103CC00080321A60394B1A689103FCD51A6842F4A5 +:103CD00080521A601A689204FCD53A4A3A499A62AC +:103CE00000225A6319633949DA6399635A64384A7E +:103CF0001A64384ADA621A6842F0A8521A602B4BEA +:103D00001A6802F02852B2F1285FF9D148229A616C +:103D10004FF48862DA6140221A622F4ADA644FF067 +:103D200080521A652D4A5A652D4A9A6532232D4ACA +:103D30001360136803F00F03022BFAD11B4B1A69AF +:103D400042F003021A611A6902F03802182AFAD105 +:103D5000D3F8DC2042F00052C3F8DC20D3F8042171 +:103D600042F00052C3F80421D3F80421D3F8DC2038 +:103D700042F08042C3F8DC20D3F8042142F08042B4 +:103D8000C3F80421D3F80421D3F8DC2042F0004228 +:103D9000C3F8DC20D3F8042142F00042C3F8042128 +:103DA000D3F80431704700BF00800051004402582E +:103DB0000048025800C000F0020000010000FF01AE +:103DC0000088900822204000630209012C020400B0 +:103DD00047040508FD0BFF01200000200010E00053 +:103DE00000010100002000524FF0B04208B5D2F8A7 +:103DF000883003F00103C2F8883023B1044A136805 +:103E00000BB150689847BDE80840FEF7E9BD00BF18 +:103E10007C4600204FF0B04208B5D2F8883003F05D +:103E20000203C2F8883023B1044A93680BB1D0680A +:103E30009847BDE80840FEF7D3BD00BF7C46002090 +:103E40004FF0B04208B5D2F8883003F00403C2F84E +:103E5000883023B1044A13690BB150699847BDE813 +:103E60000840FEF7BDBD00BF7C4600204FF0B042C9 +:103E700008B5D2F8883003F00803C2F8883023B1BF +:103E8000044A93690BB1D0699847BDE80840FEF732 +:103E9000A7BD00BF7C4600204FF0B04208B5D2F865 +:103EA000883003F01003C2F8883023B1044A136A43 +:103EB0000BB1506A9847BDE80840FEF791BD00BFBE +:103EC0007C4600204FF0B04310B5D3F8884004F48E +:103ED0007872C3F88820A30604D5124A936A0BB1FE +:103EE000D06A9847600604D50E4A136B0BB1506B2D +:103EF0009847210604D50B4A936B0BB1D06B9847BA +:103F0000E20504D5074A136C0BB1506C9847A30522 +:103F100004D5044A936C0BB1D06C9847BDE81040AF +:103F2000FEF75EBD7C4600204FF0B04310B5D3F8DD +:103F3000884004F47C42C3F88820620504D5164A00 +:103F4000136D0BB1506D9847230504D5124A936D3C +:103F50000BB1D06D9847E00404D50F4A136E0BB136 +:103F6000506E9847A10404D50B4A936E0BB1D06EE6 +:103F70009847620404D5084A136F0BB1506F9847F5 +:103F8000230404D5044A936F0BB1D06F9847BDE862 +:103F90001040FEF725BD00BF7C46002008B5034851 +:103FA000FDF714F9BDE80840FEF71ABDCC23002048 +:103FB00008B5FFF7ABFDBDE80840FEF711BD0000F6 +:103FC000062108B50846FFF7C3FA06210720FFF7C8 +:103FD000BFFA06210820FFF7BBFA06210920FFF7E8 +:103FE000B7FA06210A20FFF7B3FA06211720FFF7D8 +:103FF000AFFA06212820FFF7ABFA09217A20FFF754 +:10400000A7FA07211C20FFF7A3FA0C215220BDE8D4 +:104010000840FFF79DBA000008B5FFF78DFD00F0DE +:104020000DF8FDF7E5FAFDF7BDFCFDF78FFBFFF797 +:1040300043FDBDE80840FFF76BBC00000023054AC4 +:1040400019460133102BC2E9001102F10802F8D120 +:10405000704700BF7C46002010B5013902449042F1 +:1040600001D1002005E0037811F8014FA34201D0EF +:10407000181B10BD0130F2E7034611F8012B03F8BD +:10408000012B002AF9D1704753544D333248373F42 +:104090003F3F0053544D3332483734332F37353395 +:1040A00000000000F0290020CC2300200096000032 +:1040B0000000000000000000000000000000000000 +:1040C0000000000000000000B9150008A515000858 +:1040D000E1150008CD150008D9150008C515000820 +:1040E000B11500089D150008ED150008000000003E +:1040F000C9160008B5160008F1160008DD160008FC +:10410000E9160008D5160008C1160008AD1600080B +:10411000FD16000800000000010000000000000083 +:104120006D61696E0000000069646C65000000004C +:104130002841000878280020F02900200100000014 +:1041400041200008000000004172647550696C6FE6 +:10415000740025424F415244252D424C00255345C1 +:104160005249414C25000000020000000000000000 +:10417000E918000859190008400040009842002042 +:10418000A842002002000000000000000300000020 +:1041900000000000A119000800000000100000004D +:1041A000B8420020000000000100000000000000F4 +:1041B0002C450020010102003124000841230008A1 +:1041C000DD230008C123000843000000D04100089F +:1041D00009024300020100C032090400000102028A +:1041E000010005240010010524010001042402023D +:1041F0000524060001070582030800FF09040100E9 +:10420000020A0000000705010240000007058102C4 +:1042100040000000120000001C42000812011001C2 +:104220000200004009124157000201020301000090 +:104230000403090425424F41524425004355415689 +:104240002D4E6F72612D626473686F74003031326D +:10425000333435363738394142434445460000004F +:1042600000000000F51A0008AD1D0008591E0008E6 +:104270004000400064460020644600200100000029 +:10428000744600208000000040010000080000008B +:104290000001000000040000080000000000802A67 +:1042A00000000000AAAAAAAA00000024FFFF000044 +:1042B0000000000000A00A00000000000000000054 +:1042C000AAAAAAAA00000000FFFF00000000000048 +:1042D000000000000000000000000000AAAAAAAA36 +:1042E00000000000FFFF00000000000000000000D0 +:1042F0000000000000000000AAAAAAAA0000000016 +:10430000FFFF00000000000000000000000002406D +:1043100000000000AAAAAA2A00000140FFFF000036 +:104320000000000007000000502510000000000001 +:10433000AAA2AAAA50151000FFFF00000000000763 +:10434000000000000010100000000000AA8AAAAAC5 +:1043500000101000FFFF000000000000000000003F +:104360000000000000000000AAAAAAAA00000000A5 +:10437000FFFF0000000000000000000000551105D4 +:10438000E0000000AAAAAAA800011105FFFF000092 +:10439000000000000000000000000000000000001D +:1043A000AAAAAAAA00000000FFFF00000000000067 +:1043B000000000000000000000000000AAAAAAAA55 +:1043C00000000000FFFF00000000000000000000EF +:1043D000F10300000000000000001E0000000000CB +:1043E000FF00000000000000884000083F000000BF +:1043F00050040000934000083F00000000960000B9 +:104400000000080096000000000800000400000002 +:104410003042000800000000000000000000000022 +:0C44200000000000000000000000000090 +:00000001FF diff --git a/Tools/bootloaders/CUAV_GPS_bl.bin b/Tools/bootloaders/CUAV_GPS_bl.bin index e4135b97a85..d6972c9054f 100755 Binary files a/Tools/bootloaders/CUAV_GPS_bl.bin and b/Tools/bootloaders/CUAV_GPS_bl.bin differ diff --git a/Tools/bootloaders/CUAV_GPS_bl.elf b/Tools/bootloaders/CUAV_GPS_bl.elf index 1672a2a5347..46cab2cc83e 100755 Binary files a/Tools/bootloaders/CUAV_GPS_bl.elf and b/Tools/bootloaders/CUAV_GPS_bl.elf differ diff --git a/Tools/bootloaders/CUAV_GPS_bl.hex b/Tools/bootloaders/CUAV_GPS_bl.hex index 1760f250948..7912e299534 100644 --- a/Tools/bootloaders/CUAV_GPS_bl.hex +++ b/Tools/bootloaders/CUAV_GPS_bl.hex @@ -1,1030 +1,1030 @@ :020000040800F2 -:10000000000700202105000831160008B11500087E -:1000100009160008B1150008DD15000823050008C1 -:10002000230500082305000823050008D53700082C -:100030002305000823050008230500082305000800 -:1000400023050008230500082305000823050008F0 -:100050002305000823050008093C0008353C00087A -:10006000613C00088D3C0008B93C000823050008ED -:1000700023050008230500082305000823050008C0 -:10008000230500082305000823050008A52500080E -:100090001126000865260008B9260008E53C00087E -:1000A0002305000823050008230500082305000890 -:1000B000553A000823050008230500082305000819 -:1000C0002305000823050008230500082305000870 -:1000D00023050008612A0008752A00082305000886 -:1000E0004D3D0008230500082305000823050008EE -:1000F0002305000823050008230500082305000840 -:10010000230500082305000823050008230500082F -:10011000230500082305000823050008230500081F -:10012000230500082305000823050008230500080F -:1001300023050008230500082305000823050008FF -:1001400023050008230500082305000823050008EF -:1001500023050008230500082305000823050008DF -:1001600023050008230500082305000823050008CF -:1001700023050008230500082305000823050008BF -:1001800023050008230500082305000823050008AF -:10019000230500082305000823050008230500089F -:1001A000230500082305000823050008230500088F -:1001B000230500082305000823050008230500087F -:1001C000230500082305000823050008230500086F -:1001D000230500082305000823050008230500085F -:1001E000D0400B1CD1409C46203AD3401843524289 -:1001F00063469340184370479140031C90409C46CF -:10020000203A9340194352426346D3401943704702 -:1002100053B94AB9002908BF00281CBF4FF0FF316D -:100220004FF0FF3000F07AB9ADF1080C6DE904CE63 -:1002300000F006F8DDF804E0DDE9022304B07047C1 -:100240002DE9F0478C460D460446089E002B51D1FF -:100250008A4217466DD9B2FA82FEBEF1000F0BD06A -:10026000CEF1200C01FA0EF520FA0CFC02FA0EF782 -:100270004CEA050C00FA0EF44FEA174A250CBCFBB9 -:10028000FAF81FFA87F90AFB18CC45EA0C4508FB77 -:1002900009F3AB420AD9ED1908F1FF3280F023814E -:1002A000AB4240F22081A8F102083D44ED1AA4B20D -:1002B000B5FBFAF00AFB105544EA054400FB09F9C6 -:1002C000A14509D9E41900F1FF3380F00A81A14565 -:1002D00040F2078102383C44A4EB090440EA08409C -:1002E0000021002E61D024FA0EF4002334607360E4 -:1002F000BDE8F0878B4207D9002E54D0002186E854 -:1003000021000846BDE8F087B3FA83F1002940F0E8 -:100310008E80AB4202D3824200F2FA80841A65EBEF -:1003200003050120AC46002E3FD086E81010BDE842 -:10033000F08712B90127B7FBF2F7B7FA87FEBEF1D3 -:10034000000F34D1EB1B3A0C1FFA87FC0121B3FBE1 -:10035000F2F8250C02FB183345EA03450CFB08F3C1 -:10036000AB4207D9ED1908F1FF3002D2AB4200F2DF -:10037000D1808046ED1AA3B2B5FBF2F002FB105516 -:1003800043EA05440CFB00FCA44507D9E41900F13D -:10039000FF3302D2A44500F2B8801846A4EB0C0447 -:1003A00040EA08409DE731463046BDE8F087CEF18F -:1003B000200405FA0EF307FA0EF720FA04F83A0CB7 -:1003C00025FA04F448EA0308B4FBF2F14FEA1845B1 -:1003D00002FB11441FFA87FC45EA044501FB0CF3BC -:1003E000AB4200FA0EF409D9ED1901F1FF3080F0AB -:1003F0008A80AB4240F2878002393D44EB1A1FFAF3 -:1004000088F5B3FBF2F002FB103345EA034500FB2D -:100410000CF3AB4207D9ED1900F1FF386FD2AB42B4 -:100420006DD902383D44EB1A40EA01418FE7C1F132 -:10043000200722FA07F88B4005FA01F448EA030383 -:1004400020FA07FE4FEA134CFD404EEA040EB5FBBE -:10045000FCF94FEA1E440CFB19551FFA83F844EAD5 -:10046000054509FB08F4AC4202FA01F200FA01FA70 -:1004700008D9ED1809F1FF3043D2AC4241D9A9F1B6 -:1004800002091D442D1B1FFA8EFEB5FBFCF00CFB70 -:1004900010554EEA054400FB08F8A04507D9E418BA -:1004A00000F1FF3529D2A04527D902381C4440EA83 -:1004B0000940A4EB0804A0FB02894C45C6464D4602 -:1004C00015D312D056B1BAEB0E0364EB050404FA4F -:1004D00007F7CB401F43CC40376074600021BDE874 -:1004E000F0871846F8E69046E0E6C245EAD2B8EB57 -:1004F000020E69EB03050138E4E72846D7E74046DA -:1005000091E78146BEE7014678E702383C4445E77B -:10051000084608E7A8F102083D442BE7704700BFF2 -:1005200002E000F000F8FEE772B63A4880F308886F -:10053000394880F3098839484EF60851CEF2000157 -:10054000086040F20000CCF200004EF63471CEF2AA -:1005500000010860BFF34F8FBFF36F8F40F20000C0 -:10056000C0F2F0004EF68851CEF200010860BFF3F1 -:100570004F8FBFF36F8F4FF00000E1EE100A4EF681 -:100580003C71CEF200010860062080F31488BFF3AE -:100590006F8F03F09BF903F07BF903F0C1F94FF083 -:1005A00055301F491B4A91423CBF41F8040BFAE702 -:1005B0001C49194A91423CBF41F8040BFAE71A4919 -:1005C0001A4A1B4B9A423EBF51F8040B42F8040BE7 -:1005D000F8E700201749184A91423CBF41F8040B44 -:1005E000FAE703F059F903F0EFF9144C144DAC425B -:1005F00003DA54F8041B8847F9E700F041F8114C7E -:10060000114DAC4203DA54F8041B8847F9E703F0B4 -:1006100041B900000007002000230020000000086E -:100620000001002000070020B04000080023002047 -:100630002423002028230020F83B0020E0010008AC -:10064000E0010008E0010008E00100082DE9F04F9A -:100650002DED108AC1F80CD0C3689D46BDEC108A00 -:10066000BDE8F08F002383F311882846A0470020BF -:1006700002F0B0FDFEE702F017FD00DFFEE700002C -:100680002DE9F04103F042F8804603F08FF805466B -:1006900000283DD12B4B98453AD0013398453AD0AC -:1006A000294B28F0FF029A4238D15FFA88F000F017 -:1006B00051FA2E4642F2107400F062FC08B1002498 -:1006C000264600F04DFA074660B36CBB374635B19D -:1006D0001E4B984503D003F061F800242746002004 -:1006E00003F01EF81A4B1B691B0720D40FB100F052 -:1006F00031F800F09DFC00F091FE00F09BFF0546F4 -:10070000BCB900F045FD4FF47A7002F069FDF7E7DF -:100710002E460024D0E704460126CDE706464FF4D6 -:100720007A74C9E70446D2E74FF47A74CFE700241D -:10073000DFE700F07FFF401BA042E2D900F00AF89B -:10074000DBE700BF010007B0000008B0263A09B09F -:100750000004024010B51E4B1E4953F8042F01320D -:1007600000D110BD8B42F8D11B4C1C4B22689A4221 -:100770002CD91B4B9B6803F1006303F580339A422D -:1007800024D202F0DFFF02F0F1FF002000F060FE53 -:10079000144B0220187000F097FE134B1A6C0022C5 -:1007A0001A64196E1A66196E596C5A64596E5A6633 -:1007B0005B6E72B60D4A0E4B13601B6822682021D7 -:1007C00081F311889D4683F30888104710BD00BF50 -:1007D000FCFF00081C00010804000108FFFF0008DE -:1007E00000230020282300200038024008ED00E00C -:1007F0000000010809490B6849F269009AB21B0C14 -:1008000000FB0233064A0B60136844F2506198B251 -:100810001B0C01FB0030106080B2704720230020C9 -:100820001C23002010B500211022044600F068FEB1 -:10083000034B03CB206061601868A06010BD00BF4F -:10084000107AFF1FF0B51F4CBBB000F0F3FEA36899 -:10085000C31AF92B30D906AD2346A0602822002107 -:10086000284601F0A5FB04F10E0000F041FE002334 -:10087000C6B2591D5F1CDBB2B3424FEAC10107DAB1 -:100880000E3323440822284601F092FB3B46F0E752 -:10089000012303930823207B02930B4B0193C1F3A5 -:1008A000CF013023059100930146049503A3D3E9BA -:1008B0000023064801F0B6F93BB0F0BD78F6339F4F -:1008C00093CACD8D68330020753300204433002057 -:1008D00070B50D4614461E4601F04CF950B9022E73 -:1008E0000ED1012C0CD112A3D3E90023C5E90023BA -:1008F000012070BD052C14D003D8012C09D0002094 -:1009000070BD282C09D0302CF9D10BA3D3E90023DA -:10091000ECE70BA3D3E90023E8E70BA3D3E900231B -:10092000E4E70BA3D3E90023E0E700BFAFF30080C7 -:10093000401DA12026812A0B78F6339F93CACD8DC6 -:100940009E6AC421818A46EE26417272DF25D7B79E -:10095000F017304A39059E5638B504460D46034611 -:1009600020222846002101F023FB22792346032A76 -:1009700028BF032203F8042F28460222202101F079 -:1009800017FB62792346072A28BF072203F8052FA1 -:1009900028460322222101F00BFBA2792346072AD5 -:1009A00028BF072203F8062F28460322252101F03D -:1009B000FFFA284604F108031022282101F0F8FA72 -:1009C000382038BD2DE9F04FFFB01FAE0CAD40F21E -:1009D000791280460F463046002100F091FD4822F2 -:1009E0000021284600F08CFD00F024FE574B4FF408 -:1009F0007A72B0FBF2F0186093E80700012385E8F3 -:100A000007002B740DF1520000236B74FFF70AFFEF -:100A1000032385F82030E92385F8213006AB1846FA -:100A20004B4903F037FA162228643146284685F8E8 -:100A30003C20FFF791FF10AB0446014608223046E8 -:100A400001F0B6FA0822A1180DF14103304601F079 -:100A5000AFFA0DF14203082204F11001304601F013 -:100A6000A7FA11AB202204F11801304601F0A0FAD8 -:100A700012AB402204F13801304601F099FA14AB70 -:100A8000082204F17801304601F092FA0DF1510389 -:100A9000082204F18001304601F08AFA04F1880A44 -:100AA0000DF1520904F5847B4B465146082230462D -:100AB0000AF1080A01F07CFAD34509F10109F3D1E2 -:100AC00019AB08225946304601F072FA04F58874D1 -:100AD0004FF0000995F834304B4510D84FF000091D -:100AE00095F83C304B4515D92B6C21464B440822D8 -:100AF000304601F05DFA083409F10109F0E7AB6B0B -:100B000021464B440822304601F052FA083409F1DC -:100B10000109DFE7E31DC3F3CF03F97E059300234B -:100B200004960393BB7E0293193701230093019728 -:100B300004A3D3E90023404601F074F87FB0BDE878 -:100B4000F08F00BF9E6AC421818A46EE2C230020CC -:100B5000403F0008014B1870704700BF3823002049 -:100B6000F0B5334B1C7B85B034B1324B0E221A8169 -:100B70000024204605B0F0BD2F4A1068516802AB32 -:100B800003C308230DEB03022C492D4803F064F93D -:100B9000054630B9274B2B480A221A8100F004FD84 -:100BA000E6E70169B1F5E02F06D9224B26480B2272 -:100BB0001A8100F0F9FCDCE7438B40F2E932934202 -:100BC00007D01C490C2008811946204800F0ECFC95 -:100BD000CFE71F4A024402F11003994204D2154B99 -:100BE0001C4810221A81E4E710398E1A2046144955 -:100BF00000F024FD3246074605F11801204600F0BA -:100C00001DFDAB689F4202D1EB6898420AD0094BA8 -:100C10000D221A8100903B46EA68A9680E4800F050 -:100C2000C3FCA5E70D4800F0BFFC0124A1E700BF0D -:100C3000683300202C230020A43E0008DCFF0600BF -:100C400000000108AC3E0008B83E0008CA3E00089B -:100C50000800FFF7E83E0008053F00082E3F0008A7 -:100C60002DE9F04FADB006AF80460C4600F082FF94 -:100C7000064600285BD1237E022B19D1E38A012B83 -:100C800016D100F0D7FC0546FFF7B4FD4FF4C8734A -:100C9000B54AB0FBF3F105F5167501FB1300E37ED1 -:100CA00015FA80F01060914633B9B04B00221A70EB -:100CB0009C37BD46BDE8F08FA38AF5B2013BAB423D -:100CC00006F101060CD93B1D691CC9001D440095A5 -:100CD0000023082201F0F801204601F03BF8EBE781 -:100CE00007F11400FFF79EFD2A4607F11401381D95 -:100CF00003F0A2F803460028D7D10F2D08D89B4B4C -:100D00001D70D9F80030A3F51673C9F80030CFE78D -:100D100007F19802014602F8950D2046009207223D -:100D200001F018F8F978404600F01CFFC0E7E38AAC -:100D3000052B00F0068106D8012BB9D1214640468B -:100D4000FFF740FEB4E7282B3DD0302BB0D1637EB7 -:100D5000874D01336A7BDBB29342E94640F0EF8076 -:100D6000E27E2B7B9A4240F0EA8007F1980300264E -:100D700023F8846D1022009331460123204600F0B1 -:100D8000E9FFB4F81480A8F102081FFA88F808F106 -:100D9000030323F003030A3323F00703ADEB030D32 -:100DA0000DF1180A33469BB2B11C98454FEAC101B8 -:100DB00006F101066CDD534400930822002320460F -:100DC00000F0C8FFEEE7A38A013B9BB2C92B3FF6B8 -:100DD0006FAF674E357B4DBB06F10C0300930822C5 -:100DE0002B462946204600F0B5FFA38A05F10109EC -:100DF000013BEDB29D424FEAC90109DA0E35354497 -:100E0000009500230822204600F0A4FF4D46ECE7A1 -:100E100000230022C6E900230023B36086F8D73000 -:100E2000C6F8D830337B0BB9E37E3373002507F166 -:100E300014063B1D0822294630467D60BD60FD60DA -:100E400001F0B6F83B7A05F10109AB424FEAC9015E -:100E500007D9FB6808222B44304601F0A9F84D461B -:100E6000F0E7C1F3CF010023E07E059104960393E0 -:100E7000A37E02931934282301460093019438A3DA -:100E8000D3E90023404600F0CDFEFFF7DBFC0FE77F -:100E900095F8D70000F0E6FAD5F8D83006461BB929 -:100EA00095F8D70000F0EEFAD5F8D83043449E42CA -:100EB00004D295F8D700013000F0E4FA4FEA980B1D -:100EC0000024A0B2584504F1010408DA2B68800020 -:100ED0000AEB00010122184400F01AFBF1E7D5E902 -:100EE0000023D5F8D84095F8D70012EB080243F15B -:100EF00000034444C5E90023C5F8D84000F0B2FA25 -:100F0000844209D395F8D730013385F8D730D5F826 -:100F1000D8309E1BC5F8D860B8F1FF0F08DC00235D -:100F20002B7300F0C1FAFFF71BFE08B1FFF712FCAC -:100F30002B68104A9B0A013313810023AB60CD4616 -:100F4000B6E6BFF34F8F0C490C4BCA6802F4E0625F -:100F50001343CB60BFF34F8F00BFFDE7AFF30080BB -:100F600026417272DF25D7B7403300203D33002081 -:100F7000683300202C23002000ED00E00400FA0577 -:100F800037B54FF00054214B22689A4229D1204BAB -:100F9000627D1A701F48237D0373C9221E490E30DB -:100FA00000F09CFAE0220021204600F0A9FA012579 -:100FB000284603B030BD0321184800F053FB8DE8EC -:100FC0000300636883421ED1236899424FF00003F7 -:100FD00019D1A3600E4B22691A70114BE2681A6096 -:100FE000E6E702F0EDFB054668B10E4A0E4C136CC5 -:100FF00043F000731364A2680C4B9A4203D1236937 -:10100000013B7E2BD7D90025D2E700BF9AAD44C55E -:101010003823002068330020160000205866004066 -:101020001823002000380240506600405041A0B014 -:10103000F0B54B4A4B4CD2F800E085B00223637107 -:10104000BEF57A7F4FF000030293ADF80C304AD31F -:10105000454B464DB5FBFEF19E4594BF1023092339 -:101060005A1CB1FBF2F702FB171222B1022B3ADD38 -:10107000013BDBB2F4E77A1EB2F5806F33D2C3EBEB -:10108000C306F21CC2F3C702991A02F1010CC9B2DD -:101090004FF47A7000FB0CF08C44B0FBFCF080B293 -:1010A000B0F5617F06D9721E082692FBF6F2D2B225 -:1010B0009B1AD9B2531E0F2B50D84B1E072B8CBF37 -:1010C00000230123501800FB0770B5FBF0F5AE4577 -:1010D00009D143B10123ADF808708DF80C308DF8BB -:1010E0000A208DF80B109DF80B30214921485A1E1B -:1010F0009DF80A30013B1B0443EA0253BDF8082067 -:10110000013A13434B6001F009FD002301931A4B90 -:1011100000931A491A4B1B484FF4805200F0FAFC16 -:10112000194B197811B1174800F01CFD00F082FA34 -:101130000546FFF75FFB4FF4C87305F51675B0FB66 -:10114000F3F202FB1300114B15FA80F0186002F065 -:101150002DFB08B10F23238105B0F0BD0023B1E7BB -:10116000182300202C2300203F420F0040787D01EF -:101170001023002080340020D10800083C230020E8 -:10118000610C000844330020382300204033002045 -:101190002DE9F04F96A7D7E900670FF25C29D9E94E -:1011A00000898F4C93B0DFF858B2DFF858A2204680 -:1011B00000F082FD0CAD079098B310220021284664 -:1011C00000F09EF9079B197B4FF0000261F30302C8 -:1011D00019468DF8302051F8040F49680EAA03C251 -:1011E0001B680D9A63F31C029DF830300D9243F09A -:1011F00020038DF8303000232A461946584601F066 -:101200009DFC079030B9204600F05AFD079B8AF8F4 -:101210000030CCE79AF80030072B40DC01338AF825 -:10122000003018220021284600F06AF9DFF8D0B11A -:10123000DFF8D4A1002319462A46584601F0A6FC3F -:10124000014680BB102208A800F05AF9DAF81430E1 -:1012500083F48053CAF8143000F0EEF90B4612A95B -:10126000024611E903000DF1240E8EE803009DF8FB -:101270003410C1F3030089064CBF0E99BDF8381035 -:101280008DF82C0046BFC1F31C0141F00041C1F3B1 -:101290000A010891204608A900F0D2FECAE72046BC -:1012A00000F00EFDBDE7204600F064FC82460028F9 -:1012B0004AD1DFF858B100F0BDF9DBF800309842B0 -:1012C00042D300F0B7F90790FFF794FA079A8DF828 -:1012D00020A04FF4C87302F51672B0FBF3F101FBC6 -:1012E000130012FA80F0CBF80000DFF824B19BF86D -:1012F000001011B901238DF8203028460791FFF71F -:1013000091FA0799C1F1100A5FFA8AFABAF1060F49 -:1013100028BF4FF0060A524629440DF1210000F083 -:10132000DDF80AF10103049308AB03931823029339 -:101330002C4B01930123009332463B46204600F09C -:101340001BFC00238BF8003000F074F9264ADFF80C -:10135000C4A01368C31AB3F57A7F32D3106000F0CB -:101360006BF902460B46204600F0B4FC204600F024 -:1013700001FC30B39AF80C30DFF89CB0002B14BF9E -:10138000032302238BF8053000F054F94FF47A73ED -:101390002946B0FBF3F0CBF800005846FFF7DCFA23 -:1013A000182307300293114B0193C0F3CF0040F292 -:1013B000551304900093039542464B46204600F097 -:1013C000DBFB9AF80C300BB1FFF73CFA9AF80C30C3 -:1013D000002B7FF4E8AE13B0BDE8F08FAFF30080D0 -:1013E000443300203C330020483400204C3400209B -:1013F000401DA12026812A0BF1C6A7C1D068080F85 -:10140000803400204D34002000040240403300208E -:101410003D330020683300202C23002070B502F0FB -:1014200043F8094C094E2080002530682388834208 -:1014300008D902F033F8336805440133B5F5803F2D -:101440003360F2D370BD00BF7C34002050340020E4 -:1014500002F0DAB800F10060920000F5803002F08E -:1014600069B80000054B1A68054B1B889B1A83421C -:1014700002D9104402F012B8002070475034002006 -:101480007C34002038B5074D04462868204402F01B -:101490000DF828B928682044BDE8384002F01EB88D -:1014A00038BD00BF50340020064991F8243033B1D4 -:1014B00000230822086A81F82430FFF7CBBF0120FF -:1014C000704700BF54340020022802BF024B4FF087 -:1014D00080529A61704700BF0004024010B500239B -:1014E000934203D0CC5CC4540133F9E710BD000033 -:1014F00002460346981A13F9011B0029FAD17047D6 -:1015000002440346934202D003F8011BFAE77047F6 -:101510002DE9F047234C94F82430054688461746B9 -:1015200083BB2E46DFF87C90C7B394F824302BB9E8 -:101530002022FF2148462662FFF7E2FF94F82400AC -:10154000C0F10805BD4228BF3D465FFA85FAAD00EF -:1015500041462A4604EB8000FFF7C0FF94F8243090 -:10156000A7EB0A079A445FFA8AFABAF1080F2E44E9 -:10157000A844FFB284F824A0D6D1FFF795FF002835 -:10158000D2D108E0266A06EB8306B042CAD0FFF744 -:101590008BFF0028C5D10020BDE8F0870120BDE801 -:1015A000F08700BF543400200FB4002004B070470F -:1015B00000B59BB0EFF3098168226846FFF78EFF04 -:1015C000EFF30583044B9A6BDA6A9A6A9A6A9A6A0D -:1015D0009A6A9A6A9B6AFEE700ED00E000B59BB04C -:1015E000EFF3098168226846FFF778FFEFF3058380 -:1015F000044B9A6B9A6A9A6A9A6A9A6A9A6A9B6A7E -:10160000FEE700BF00ED00E000B59BB0EFF30981FD -:1016100068226846FFF762FFEFF30583034B5A6BBE -:101620009A6A9A6A9A6A9A6A9B6AFEE700ED00E0F3 -:10163000FEE7000002F026B802F010B830B5084D01 -:101640000A4491420BD011F8013B09245840013C57 -:10165000F7D040F300032B4083EA5000F7E730BD9A -:101660002083B8ED2DE9F7431AA7D7E9006700EB0F -:1016700081014FF0FF324FF0FF330DF1040C88422F -:1016800023D050F804EBCDF804E04FF0000E1EF824 -:101690000C8000244FEA086562406B404FF0090857 -:1016A000B8F101080BD0002A73F1000904DA92188E -:1016B0005B4172407B40F3E792185B41F0E70EF12B -:1016C000010EBEF1040FE2D1D9E7D043D94303B0F4 -:1016D000BDE8F0839336EAA9EBE1F0422DE9F0474B -:1016E000089E01F007054FEAD60C2A4406F00706CB -:1016F00000EBD1004FF47F49954201D1BDE8F0875E -:1017000005F0070E06F0070AD64577464FEAD504DE -:1017100038BF5746C7F10807511B0CEBD6088F425C -:10172000045D28BF0F4604FA0EF413F8081029FAD6 -:1017300007FE24FA0AF45FFA8EFE4C404EFA0AFEC7 -:1017400004EA0E04614003F808103D443E44D3E728 -:101750000246006848B103681360D38811890133D9 -:101760009BB29942D38038BF1381704770B588B05F -:101770000D460446202200216846FFF7C1FE2046A0 -:101780000495FFF7E5FF054658B16B46044608AEE1 -:101790001A4603CAB24220606160134604F108048D -:1017A000F6D1284608B070BD2DE9F041056885B92D -:1017B0000160BDE8F081002B29DA930CB34229D1F6 -:1017C000A54201D10D60F3E7C8F800100C60BDE838 -:1017D000F0814B6823F06047BE0C4FEAD37EC3F321 -:1017E000807C16EA230638BF3E46A8462C4663682E -:1017F000BEEBD37F23F06042DDD1974203D1C3F328 -:1018000080739C450AD1974205E01C46EFE7B2423F -:1018100006D013469E422CBF00230123002BCFD1BC -:101820002368A046002BF0D12160BDE8F0810000C4 -:101830002DE9F04106460F4600254FF6FF7441F2B0 -:1018400021082A4630463946FEF7CAFCC0B284EA6F -:101850000024082314F4004F4FEA4404A4B203F117 -:10186000FF3318BF84EA080413F0FF03F2D10835F0 -:10187000402DE6D12046BDE8F081000010B54B6850 -:1018800033B9CA8A63F30902CA820020002110BD5D -:10189000C4681A681C60C360438A013B43824A6083 -:1018A000EDE7000010B50A4441F22104914200D155 -:1018B00010BD11F8013B80EA0320082310F4004F0B -:1018C0004FEA400080B203F1FF3318BF604013F0CD -:1018D000FF03F3D1EAE700002DE9F04F85B0814620 -:1018E0008DE80A00BDF83C409346002A00F0838052 -:1018F00024B10E9B002B7ED0072C2AD809F10C00B6 -:10190000FFF726FF054628B96FF00205284605B007 -:10191000BDE8F08F14220021FFF7F2FD22460E9958 -:1019200005F10800FFF7DAFD631C2B749BF800300B -:101930002C4403F01F0363F03F032372009B43F02A -:1019400000436B60294609F11C00FFF72DFF0125BC -:10195000DCE7019B1B0A4FF00008029300F10C0327 -:101960004FF0800A4646454603930398FFF7F0FE82 -:1019700007460028C8D014220021FFF7C1FDC6BBCE -:101980009DF804303B729DF808307B7202220E9B5A -:10199000711E1944B4420AD9B8180132D2B211F8F2 -:1019A00001EF80F808E00136072AB6B2F2D19BF8C1 -:1019B000001001F01F01B44208BF4FF0400AB818F0 -:1019C00041EA48114AEA01030372009B013243F0E5 -:1019D00000437B603A74394609F11C00FFF7E4FECE -:1019E0000135B4422DB288F001084FF0000ABCD195 -:1019F0008CE70022CBE76FF0010587E72DE9F04780 -:101A00001E46CB8A9146C3F30902062A80460F463A -:101A100019D013460021B0B28DB25A1992B2052ADC -:101A200009D9A84210D8FA8A034463F30902FA825A -:101A30000120BDE8F087A842F3D93A4419F80140E3 -:101A400094760131E8E70025FB8A7C68C3F309003E -:101A5000821F1C23B2FBF3FA03FB1A2A1FFA8AF235 -:101A60007CB301212368002B39D1B31F03441C2010 -:101A7000B3FBF0F301339BB299420CD2BAF1000FE1 -:101A800009D14046FFF764FE08B1C0F800A020600D -:101A900008B304460022B6B24FF0000AB54230D275 -:101AA000691E49441346E01801339BB211F801EF57 -:101AB00080F804E001351C2BADB214D0AE42F2D850 -:101AC000ECE74046FFF744FE044608B100230360FC -:101AD0007C60002CDED16FF00200BDE8F0870131A0 -:101AE00089B21C46BEE7AE42D8D94046FFF730FE69 -:101AF00008B1C0F800A020600028ECD00446002205 -:101B0000CCE7FB8AC3F30902164466F30903FB82A0 -:101B10008EE70000F8B5044615460E462422002143 -:101B20001F46FFF7EDFC069B6360079B23626A0973 -:101B30004FF6FF739A424FF0000028BF1A46A76085 -:101B4000207097B204F10C0503469A4205D1002398 -:101B50002B6027826382A382F8BD2E600133354655 -:101B60002036F2E703781BB94BB2002BC8BF0170D7 -:101B700070470000007870472DE9F7430D9EBDF8CF -:101B800028900B9D9DF83040BDF8388007461946D7 -:101B9000104616B9B8F1000F40D11F2C3ED83B7843 -:101BA000D3B9B8F1070F36D839F0030336D142461E -:101BB00031464FF6FF70FFF775FE4FEA092920F016 -:101BC000010009F44079400449EA0464400C44EA05 -:101BD00040244FF6FF730DE043EA0923B8F1070FE5 -:101BE00043EA0464F5D9FFF723FE42463146FFF786 -:101BF00059FE03468DE840012A4621463846FFF744 -:101C00006BFE2B780133DBB21F2B88BF00232B70B8 -:101C100003B0BDE8F0836FF00300F9E76FF0010057 -:101C2000F6E700002DE9F7430E9F0B9D9DF83480E9 -:101C3000BDF83C6081469DF8300007B9AEBB1F2857 -:101C400033D899F800E0BEF1000F31D00C0244F017 -:101C500080049DF8281044EAC83444EA014444EA68 -:101C60000E04072E44EA00641CD919461046FFF7FB -:101C7000DFFD32463946FFF715FE03460196009711 -:101C80002A4621464846FFF727FEB8F1010F06D144 -:101C90002B780133DBB21F2B88BF00232B7003B0DE -:101CA000BDE8F0834FF6FF73E8E76FF00100F6E759 -:101CB0006FF00300F3E70000C06900B10430704723 -:101CC000C3691A68C261C2681A60C360438A013B73 -:101CD000438270472DE9F047D0F818A0DFF87080F4 -:101CE000054616461F4654464FF000090CB9BDE89C -:101CF000F087D4E90223B21A67EB0303994508BFC2 -:101D0000904523D2AB699C42214628460FD1FFF76C -:101D1000B5FDAB691B68AB61EB6823606B8AEC6057 -:101D2000AC69013B6B822346A2461C46DEE7FFF707 -:101D3000A5FD2368CAF80030EB6823606B8AEC606D -:101D4000013B6B82DAF800305446EDE72368EBE79D -:101D500080841E002DE9F04F8BB00E461446079389 -:101D6000DDF850808346002800F01081B8F1000FA4 -:101D700000F00C81531E3F2B00F20881012A03D191 -:101D8000079B002B40F00281BBF81450ED000023AC -:101D9000AE420893099304D3002630460BB0BDE849 -:101DA000F08F33199D42DBF80C303ABFAD1BEDB21A -:101DB000254623B9DBF81030002B00F093802F2E3E -:101DC00065D8C6F13007BD424FF000032CBFFFB20B -:101DD0002F460093314608AB3A46DBF80800FFF780 -:101DE0007DFCA5EB07093E445FFA89F9BBF8143086 -:101DF00003F10053063BDB000493DBF80C30039344 -:101E00003021039B13B1B9F1000F43D1DBF810006F -:101E100040B1B9F1000F05D0009708AB4A46711ADE -:101E2000FFF75CFC2EB2002DB6D060070AD00AABDB -:101E300003EBD401624211F8083C02F0070213419F -:101E400001F8083C082C54D9102C54D9202C8CBFF4 -:101E500008230423079A002A00F09E80B4EBC30FE6 -:101E600000F09D80082C48D89DF82030621E23FA8F -:101E700002F2D10706D54FF0FF3202FA04F42343F1 -:101E80008DF820309DF8203088F8003085E7A9468D -:101E90000027ABE7049BE02B28BFE02306930B440D -:101EA000B342059315D9A3EB060AD14503980097D1 -:101EB0002CBF5FFA8AFACA46711A08AB5246043040 -:101EC000FFF70CFC5744A9EB0A095644FFB25FFA2E -:101ED00089F9049B069A05999B1A0493039B1B6836 -:101EE00003938EE700932A4608AB3146DBF80800DF -:101EF00096E70123AEE70223ACE7102C12D8BDF819 -:101F00002030621E23FA02F2D20706D54FF0FF32CC -:101F100002FA04F42343ADF82030BDF82030A8F8CD -:101F200000303AE7202C0FD8089A631E22FA03F3F8 -:101F3000DB0705D54FF0FF3303FA04F4144308948C -:101F4000089BC8F8003028E7402C22D0DDE908AB18 -:101F5000621E50465946FEF743F9002100F0010089 -:101F600050EA01030DD0224601200021FEF744F97A -:101F7000404261EB410140EA0A0041EA0B01CDE930 -:101F80000801DDE90823C8E9002306E76FF0010630 -:101F900003E76FF0080600E7012C3FF473AF082C4D -:101FA0007FF670AF102CB8D9202CEAD8C8E7000013 -:101FB00030B5402A85B01FD8002A08BF012200246E -:101FC000012A0294039419D11B788DF80830530725 -:101FD0000AD004AB03EBD205544215F8083C04F0D8 -:101FE0000704A34005F8083C00910346002102A81D -:101FF000FFF774FB05B030BD4022E0E7082AE3D9C3 -:10200000102A03D81B88ADF80830E0E7202A02D850 -:102010001B680293DBE7D3E90045CDE90245D6E72B -:1020200010B5CB681BB98B600B618B8210BDC46887 -:102030001A681C60C360438A013B4382CA60F0E7B0 -:102040002DE9F04FD1F800908FB0C9F3C0160446C7 -:102050000D46CDE90223002E50D0C9F3C03AC9F392 -:102060000626B9F1000F80F2CB8119F0C04F40F085 -:10207000C7812B7B002B00F0C381BAF1020F03D084 -:102080002278B24240F0BF8109F07F02BAF1020F1C -:10209000059236D119F07F0FC9F30F2B01D10BF048 -:1020A000030B2B447606059A93F8038046EA0A460A -:1020B00046EA82465FEAD81346EA0B06049300F02C -:1020C000A180002200230EA961E90823059B00934B -:1020D000676853465A462046B847002800F08F806C -:1020E000A7698FB9314604F10C00FFF73FFB0746A3 -:1020F000D0B96FF002000FB0BDE8F08F4FF0020AC8 -:10210000AFE7C9F3074BCCE73B699E420DD03F6870 -:10211000002FF9D1314604F10C00FFF727FB0746E9 -:102120000028E6D0A3693B60A761DDE90601FFF75F -:102130007FFBB882F97D08F01F06C1F38401711A94 -:1021400089B20FFA81FED7E90223BEF1000FBCBFAE -:1021500001F1200E0FFA8EFE52EA0301C9F3046961 -:1021600000F05D81DDE90201801A61EB03010246A6 -:102170000B46B6480021994208BF9042C0F04F81FB -:10218000049B002B48D0BEF1010F00F3488118F0EA -:10219000400F41D0DDE902230021C7E9022306A850 -:1021A0002022FFF7ADF9DDE90223CDE906232B1D3F -:1021B00008932B7BADF82EB0013BDBB2ADF82C3091 -:1021C0009DF814308DF833308DF830A0A3688DF869 -:1021D00031608DF8329006A920469847FB7DC3F305 -:1021E0008402013262F38603FB75FB8A6FF30903F5 -:1021F000FB821B0A6FF3C713FB7500207BE76FF0B0 -:102200000B0078E7A76917B96FF00C0073E73B691B -:102210009E428FD03F68F6E7FB7DC8F34012B2EBD9 -:10222000D31F40F0F380C3F38403B34240F0F18046 -:1022300004992B7B4FEA981200293BD012F0010839 -:102240005CD1032B40F2E880DDE90223C7E90223D9 -:102250002B7BAE1D033BDBB23246394604F10C004A -:10226000FFF7CCFB002814DA39462046FFF706FBBF -:10227000FB7DC3F38402013262F38603FB75FB8AA4 -:1022800068F30903FB821B0A68F3C713FB7503207D -:1022900031E7AB883B832A7B033AD2B2B88A314616 -:1022A000FFF700FBFB7DB882DA43C2F3C01262F392 -:1022B000C713A1E712BB2E1D013BDBB232463946E4 -:1022C00004F10C00FFF79AFB002814DA3946204687 -:1022D000FFF7D4FAFB7DC3F38402013262F3860375 -:1022E000FB75049AFB8A62F30903FB82049A1B0ABA -:1022F00062F3C713CAE72A7B013ACEE7F98AC1F332 -:102300000901013B0529DAB25AD8281D00239A4257 -:102310000AD907EB010E013110F801CB8EF81AC073 -:1023200001330629DBB2F2D1DDE902019342CDE9A6 -:10233000060107F11A01089138BF04337968099141 -:1023400034BF5B1900230A93FB8AADF82EB0C3F3A8 -:1023500009031A449DF814308DF833300023ADF88A -:102360002C208DF830A08DF831608DF832907B6094 -:102370002A7BB88A013A291DFFF794FA3B8BB88271 -:10238000834203D1A36806A920469847204606A9A0 -:10239000FFF746FEFB7DB88AC3F38402013262F385 -:1023A0008603FB75FB8A6FF30903FB821B0A6FF33D -:1023B000C713FB753B8B984214BF112000209AE68F -:1023C000D7F804E0BEF1000F18D00623DEF80000B5 -:1023D00088B9C91A05F1040800EB010CBCF11B0F08 -:1023E000C3B2A1D893429FD2F44418F8013B8CF8B1 -:1023F00004300130F0E71C338646E7E7734693E785 -:102400006FF0090077E66FF00A0074E66FF00D00D8 -:1024100071E66FF00E006EE66FF00F006BE6FB7D6D -:1024200068F386036FF3C713FB7539462046FFF741 -:1024300025FA049B002B7FF4AAAEFB7DC3F3840234 -:10244000013262F38603FB75DEE600BF80841E0066 -:102450002DE9F041504EB04240F089804F4CDFF8FA -:1024600040E1256C45F000752564256E45F000754A -:102470002566246E846AD4F8007207EA0E0747F0D6 -:102480000107C4F80072D4F8005205EA0E0545F0C1 -:10249000010545EA0121C4F80012002A69D0002193 -:1024A000C4F81C120F46C4F80412C4F80C12C4F885 -:1024B000141204EBC10501311C29C5F84072C5F89E -:1024C0004472F6D14FF0000E4FF0010C964514D136 -:1024D000826AD2F80032B04223F00103C2F800321F -:1024E00057D12E4B1A6C22F000721A641A6E22F029 -:1024F00000721A661B6EBDE8F0819F781D8817F088 -:10250000010F18BFD4F804820CFA05F11CBF41EA90 -:102510000808C4F8048217F0020F1EBFD4F80C821A -:1025200041EA0808C4F80C827F0742BFD4F814724D -:102530000F43C4F8147204EBC5055F68C5F8407218 -:102540009F68C5F84472D4F81C522943C4F81C1281 -:102550000C330EF1010EB9E7846A0021C4F81C1295 -:10256000C4F80412C4F80C12C4F81412AAE7002A22 -:10257000F2D1836A0022C3F84022C3F84422C3F890 -:102580000422C3F814220122C3F80C22C3F81C222F -:102590009EE7BDE8F08100BF803400200038024093 -:1025A0000000FFFF184A916A08B58B688B6013F032 -:1025B000010105D013F00C0F14BF4FF4803101213D -:1025C000D80506D513F4406F14BF41F4003141F033 -:1025D0000201D80306D513F4402F14BF41F4802123 -:1025E00041F00401D3690BB107489847202383F3D6 -:1025F00011880021054800F01BFE002383F3118899 -:10260000BDE8084001F01AB9803400208834002069 -:1026100038B5124CA36ADD68AA0712D05A6922F0B5 -:1026200002025A61A36913B1012120469847202371 -:1026300083F3118800210A4800F0FAFD002383F398 -:102640001188EB0606D5A36A1021D960236A0BB165 -:1026500002489847BDE8384001F0F0B880340020C7 -:102660009034002038B5124CA36A1D69AA0712D015 -:102670005A6922F010025A61A36913B1022120465F -:102680009847202383F3118800210A4800F0D0FDE9 -:10269000002383F31188EB0606D5A36A1021196184 -:1026A000236A0BB102489847BDE8384001F0C6B82C -:1026B000803400209034002038B50F4CA36A5D6848 -:1026C0005D602A070AD5042222701A6822F00202ED -:1026D0001A60636A13B10021204698476B0706D53C -:1026E000A36A9969236A13B1090403489847BDE8AE -:1026F000384001F0A3B800BF8034002010B50F4C63 -:10270000204600F0F9F90E4BA3620B21132000F0D4 -:10271000DBF90B21142000F0D7F90B21152000F074 -:10272000D3F90B21162000F0CFF9002320461A46DA -:102730000E21BDE81040FFF78BBE00BF80340020A3 -:1027400000640040114B984210B5044609D1104B6B -:102750001A6C42F000721A641A6E42F000721A6625 -:102760001B6EA36A01221A60A36A5A68D20707D5B2 -:10277000626851681268D9611A60064A5A6110BDD0 -:102780000121082000F04AFCEEE700BF8034002061 -:10279000003802405B87010003291AD8DFE801F006 -:1027A000020A0F14836A9B6813F0E05F14BF0120D4 -:1027B00000207047836A9868C0F380607047836A1E -:1027C0009868C0F3C0607047836A9868C0F300706F -:1027D000704700207047000010B503291FD8DFE8BC -:1027E00001F0021F2327816A8B68C3F3016318334A -:1027F00001EB0313107881061ED55468C0F3001155 -:10280000490041EAC40141F0040100F00F005860A2 -:1028100090689860D268DA6041F00101196010BDDB -:10282000836A03F5C073E5E7836A03F5C873E1E7DC -:10283000836A03F5D073DDE79488C0F30011490083 -:1028400041EA4451E1E7000001290CD003D30229F9 -:1028500010D000207047836ADA68920701D11869A6 -:1028600003E001207047836AD86810F0030018BFA6 -:1028700001207047836AF2E710B539B9836AD968D5 -:1028800089071BD11B699B0704D110BD012915D0F5 -:10289000022948D1816AD1F8C031D1F8C401D1F8F8 -:1028A000C8411461D1F8CC41546120240C610C69F9 -:1028B000A40717D14C6944F0100412E0816AD1F8E2 -:1028C000B031D1F8B401D1F8B8411461D1F8BC41AC -:1028D00054612024CC60CC68A40703D14C6944F037 -:1028E00002044C6111795C0864F304119C0864F3E0 -:1028F0004511117189064BBF91681189DB085B0D89 -:102900004CBF63F31C0163F30A01137948BF916064 -:1029100060F3030313714FEA10234FEA104058BFCE -:1029200011811370508010BD02684368114301602B -:1029300003B1184770470000024AD36843F0C00350 -:10294000D360704700100140024AD36843F0C003CF -:10295000D3607047004400402DE9F041D0F85C623C -:10296000F7683368DA0505469CB20DD5202383F35A -:1029700011884FF400710430FFF7D6FF6FF48073B5 -:102980003360002383F31188202383F3118805F13A -:10299000040814F02F0333D183F31188380615D5BA -:1029A000210613D5202383F3118805F1380000F0A8 -:1029B00027FA002846DA0821281DFFF7B5FF4FF651 -:1029C0007F733B40F360002383F311887A060ED5B2 -:1029D00063060CD5202383F31188EA6C2B6D9A4291 -:1029E00002D12B6C002B2FD1002383F31188D5F853 -:1029F0006422D368002B31D01069BDE8F04118473C -:102A0000230713D014F0080F0CBF00218021E0072A -:102A100048BF41F02001A20748BF41F040016307D1 -:102A200048BF41F480714046FFF77EFFA4067368FB -:102A300005D595F860122846194000F083FA3468ED -:102A4000A4B2A6E77060BEE727F040073F0410215C -:102A5000281D3F0CFFF768FFF760C5E7BDE8F08170 -:102A600008B50348FFF778FFBDE8084000F0E6BE70 -:102A7000AC34002008B50348FFF76EFFBDE80840FE -:102A800000F0DCBE1437002010B5094C094A20467E -:102A9000002100F035FA084BC4F85C32074C084AB4 -:102AA0000021204600F02CFA064BC4F85C3210BD21 -:102AB000AC340020392900080010014014370020F0 -:102AC000492900080044004000F1604300F01F0263 -:102AD000400903F5614309018000C9B200F160407B -:102AE00083F8001300F5614001239340C0F8803162 -:102AF00003607047FFF702BE00F108020123037074 -:102B000082600023C26000F11002436002614261F2 -:102B10008361C361036243627047000010B52023E4 -:102B2000044683F31188022303704160FFF70AFE15 -:102B300004232370002383F3118810BD2DE9F04195 -:102B40001F4604460D461646202383F3118800F1E4 -:102B500008082378052B0ED029462046FFF71CFED7 -:102B600048B1204632462946FFF736FE002080F362 -:102B70001188BDE8F0813946404600F03DFB002851 -:102B8000E7D0002383F31188BDE8F0812DE9F041FF -:102B90001F4604460D461646202383F3118800F194 -:102BA00010082378052B0ED029462046FFF74CFE4F -:102BB00048B1204632462946FFF75EFE002080F3EA -:102BC0001188BDE8F0813946404600F015FB002829 -:102BD000E7D0002383F31188BDE8F081F8B51546EE -:102BE00082680669AA420B46816938BF8568761AF1 -:102BF000B542044607D218462A46FEF76FFCA36981 -:102C00002B44A3610DE011D932461846FEF766FC4D -:102C1000AF1B3A46E1683044FEF760FCE2683A4494 -:102C2000A261A3685B1BA3602846F8BD18462A462C -:102C3000FEF754FCE368E4E783682DE9F0410446BD -:102C400093421546266938BF85684069361AB542F1 -:102C50000F4606D22A46FEF741FC63692B446361A6 -:102C60000DE012D93246A5EB0608FEF737FC4246C6 -:102C7000B919E068FEF732FCE26842446261A36879 -:102C80005B1BA3602846BDE8F0812A46FEF726FCC0 -:102C9000E368E4E710B50A440024C361029B0060C6 -:102CA00040608460C160816141610261036210BD66 -:102CB00008B582694369934201D1826882B982680A -:102CC000013282605A1C42611970426903699A425A -:102CD00001D3C3684361002100F09EFA002008BDC3 -:102CE0004FF0FF3008BD000070B5202304460E46AB -:102CF00083F31188A568A5B1A368A269013BA3600D -:102D0000531CA36115782269934224BFE368A36131 -:102D1000E3690BB120469847002383F311882846C6 -:102D200070BD3146204600F067FA0028E2DA85F3EC -:102D3000118870BD2DE9F74F05460F4690469A461B -:102D4000D0F81C90202686F311884FF0000B144613 -:102D500064B1224639462846FFF740FF034668B96A -:102D60005146284600F048FA0028F1D0002383F3AA -:102D70001188A8EB040003B0BDE8F08FB9F1000F93 -:102D800003D001902846C847019B8BF31188E41AB1 -:102D90001F4486F31188DBE7C16081614161C36133 -:102DA0001144009B006040608260016103627047D3 -:102DB000F8B504460E461746202383F31188A5680C -:102DC000A5B1A368013BA36063695A1C62611E70D0 -:102DD000236962699A4224BFE3686361E3690BB1C6 -:102DE00020469847002080F31188F8BD39462046D8 -:102DF00000F002FA0028E2DA85F31188F8BD00003D -:102E0000836942699A4210B501D182687AB98268B1 -:102E1000013282605A1C82611C7803699A4201D394 -:102E2000C3688361002100F0F7F9204610BD4FF020 -:102E3000FF3010BD2DE9F74F05460F4690469A46E4 -:102E4000D0F81C90202686F311884FF0000B144612 -:102E500064B1224639462846FFF7EEFE034668B9BC -:102E60005146284600F0C8F90028F1D0002383F32A -:102E70001188A8EB040003B0BDE8F08FB9F1000F92 -:102E800003D001902846C847019B8BF31188E41AB0 -:102E90001F4486F31188DBE7026843681143016031 -:102EA00003B11847704700001430FFF743BF00001C -:102EB0004FF0FF331430FFF73DBF00003830FFF70D -:102EC000B9BF00004FF0FF333830FFF7B3BF000049 -:102ED0001430FFF709BF00004FF0FF311430FFF747 -:102EE00003BF00003830FFF763BF00004FF0FF3230 -:102EF0003830FFF75DBF000000207047FFF7C4BD0A -:102F000037B50F4B0360002343608360C360012328 -:102F100004460374154600900B464FF4807200F18E -:102F20005C011430FFF7B6FE00942B464FF480721C -:102F300004F5AE7104F13800FFF72EFF03B030BD89 -:102F4000583F000838B5C36904460D461BB9042133 -:102F50000844FFF7A1FF294604F11400FFF7A8FE7B -:102F6000002806DA201D4FF48061BDE83840FFF7E5 -:102F700093BF38BD024B00221B605B609A607047B4 -:102F80007C390020002303748268054B1B68996814 -:102F90009142FBD25A6803604260106058607047EB -:102FA0007C39002008B5202383F31188037C032B90 -:102FB00005D0042B0DD02BB983F3118808BD4369CC -:102FC00000221A604FF0FF334361FFF7DBFF00235D -:102FD000F2E790E80C001A6002685360F2E7000024 -:102FE000002303748268054B1B6899689142FBD8E3 -:102FF0005A68036042601060586070477C39002056 -:10300000054B19690874186802681A6053601861E2 -:1030100001230374FDF71ABB7C39002030B54B1C2B -:1030200087B005460A4C10D023690A4A01A800F06F -:103030001BF92846FFF7E4FF049B13B101A800F039 -:1030400051F92369586907B030BDFFF7D9FFF8E798 -:103050007C390020A52F000838B50C4D41612B6943 -:1030600081689A689142044603D8BDE83840FFF76A -:1030700089BF1846FFF7B4FF01232C610146237472 -:103080002046BDE83840FDF7E1BA00BF7C3900209A -:10309000044B1A681B6990689B68984294BF002093 -:1030A000012070477C39002010B5084C2368206946 -:1030B0001A6822605460012223611A74FFF790FF9E -:1030C00001462069BDE81040FDF7C0BA7C390020F8 -:1030D00008B5FFF7DDFF18B1BDE80840FFF7E4BF12 -:1030E00008BD0000FEE7000010B50C4CFFF742FFE2 -:1030F00000F0ACF880220A49204600F031F80123A4 -:1031000044F8180C037400F075FB002383F3118856 -:1031100062B60448BDE8104000F044B8A43900206D -:10312000803F0008883F000800F018B9EFF31180D5 -:1031300020B9EFF30583202282F311887047000045 -:1031400010B558B9EFF30584C4F3080414B180F343 -:10315000118810BDFFF7BCFF84F3118810BD00007B -:103160008260022202740022427470478368A3F1D5 -:103170007C0243F80C2C026943F83C2C426943F86A -:10318000382C074A43F81C2CC26843F8102C022242 -:1031900003F8082C002203F8072CA3F1180070474D -:1031A0006506000810B5202383F31188FFF7DEFFC2 -:1031B00000210446FFF750FF002383F311882046C7 -:1031C00010BD0000024B1B6958610F20FFF718BFAC -:1031D0007C390020202383F31188FFF7F3BF000020 -:1031E00008B50146202383F311880820FFF716FF56 -:1031F000002383F3118808BD49B1064B42681B695F -:1032000018605A60136043600420FFF707BF4FF057 -:10321000FF3070477C3900200368984206D01A6856 -:103220000260506059611846FFF7ACBE704700005D -:1032300038B504460D462068844200D138BD036885 -:1032400023605C604561FFF79DFEF4E7054B03F1E9 -:1032500014025A619A614FF0FF32DA6100221A6259 -:10326000704700BF7C390020F8B50361C2600E468C -:10327000054600F041FB1A4B19461F4651F8142F22 -:103280008A420DD11862AE606A602A600A2E2CBF95 -:1032900080190A309D615D61BDE8F84000F01ABBFD -:1032A0001B6A9268C41A341928BF3446A24202D954 -:1032B000181900F01DFB7B699A6894420CD8AC6029 -:1032C00098685A682B60041B6A6015605D609C609A -:1032D0004FF0FF33FB61F8BDA41A1B68ECE700BF99 -:1032E0007C39002038B51C4B01685A6990421D4654 -:1032F0000DD044682160026800215460C16091686B -:103300008068014491604FF0FF32DA6138BD1A469F -:1033100042F8141F4A605B6900219342C16003D1E7 -:10332000BDE8384000F0DEBA9A6881680A449A60C5 -:103330002C6A00F0E1FA6A699268001B82420AD99D -:10334000111A092998BF00F10A02286ABDE838401D -:10335000104400F0CDBA38BD7C3900202DE9F04191 -:10336000184D002705F114066C6900F0C5FA2A6AA9 -:10337000A368811A8B4216D813442B6294E80C0080 -:103380001A602268D4F80C8053606B69E760B3421E -:1033900001D100F0A7FA87F311882069C0472023E4 -:1033A00083F31188E0E76A69B24208D05B1A0A2BFE -:1033B0002CBFC0180A30BDE8F04100F099BABDE852 -:1033C000F08100BF7C39002000207047FEE700003C -:1033D000704700004FF0FF3070470000BFF34F8F81 -:1033E000024AD368DB03FCD4704700BF003C0240B4 -:1033F00008B5094B1B7873B9FFF7F0FF074B1A6943 -:10340000002ABFBF064A5A6002F188325A601A6821 -:1034100022F480621A6008BD383B0020003C024064 -:103420002301674508B50B4B1B7893B9FFF7D6FF0F -:10343000094B1A6942F000421A611A6842F480523C -:103440001A601A6822F480521A601A6842F4806284 -:103450001A6008BD383B0020003C0240072870B5C8 -:1034600013D80B4A0B4C137863B90B4E4FF0006125 -:1034700044F8231056F823500133082B2944F7D180 -:103480000123137054F8200070BD002070BD00BFF0 -:103490005C3B00203C3B0020A83F0008014B53F858 -:1034A00020007047A83F000808207047072810B583 -:1034B000044601D9002010BDFFF7D0FF064B53F89A -:1034C00024301844C21A0BB9012010BD1268013211 -:1034D000F0D1043BF6E700BFA83F0008072810B56D -:1034E000044621D8FFF77AFFFFF782FF0F4AF32344 -:1034F000D360C300DBB243F4007343F002031361F3 -:10350000136943F480331361FFF768FFFFF7A6FFE9 -:10351000074B53F8241000F013F9FFF783FF204600 -:10352000BDE81040FFF7C2BF002010BD003C0240C4 -:10353000A83F00082DE9F84312F00103154640D1D9 -:1035400084182E4A94423CD82D4B1B6813F001037B -:1035500037D02C4CFFF74CFFF323E360FFF73EFF1F -:1035600040F20127032D01D9830713D0254C0F46C4 -:10357000401A40F20118EB1B0B44012B00EB07062D -:10358000236924D823F001032361FFF74BFF0120B7 -:10359000BDE8F883236923F44073236123693B4327 -:1035A000236151F8046B0660BFF34F8FFFF716FFDE -:1035B00003689E4208D0236923F001032361FFF7CB -:1035C00031FF0020BDE8F883043D0430CAE723F44E -:1035D00040732361236943EA08032361B94637F83E -:1035E000023B3380BFF34F8FFFF7F8FE3688B9F800 -:1035F0000030B6B2B342BED0DDE700BF000008081D -:1036000000380240003C0240084908B50B7828B158 -:1036100053B9FFF7EDFE01230B7008BD23B1BDE8E0 -:1036200008400870FFF7FEBE08BD00BF383B002011 -:1036300038B500F061F9074B1A68824207D9064A8B -:10364000D2E90045003445F10105C2E900451860A2 -:1036500038BD00BF603B0020683B002070B5FFF71D -:1036600065FD0646FFF7E4FF054BD3E90045241846 -:1036700045F100053046FFF763FD2046294670BD41 -:10368000683B002008B5FFF7E9FF4FF47A7200238A -:10369000FCF7BEFD08BD00BF10B50244064B04395F -:1036A000D2B2904200D110BD441C00B253F82000A9 -:1036B00041F8040FE0B2F4E750280040104B30B559 -:1036C0001C6F240407D41C6F44F400741C671C6F27 -:1036D00044F400441C670B4C236843F4807323605C -:1036E0000244094B0439D2B2904200D130BD441C8F -:1036F00000B251F8045F43F82050E0B2F4E700BF95 -:1037000000380240007000405028004007B50122F8 -:1037100001A90020FFF7C0FF019803B05DF804FB8A -:1037200013B50446FFF7F2FFA04206D002A901221A -:1037300041F8044D0020FFF7C1FF02B010BD0000AA -:1037400070470000074B45F255521A6002225A603A -:1037500040F6FF729A604CF6CC421A60024B01228E -:103760001A70704700300040743B0020034B1B78F8 -:103770001BB1034B4AF6AA221A607047743B002023 -:1037800000300040034B1A6812B9034A12681A60ED -:10379000704700BF703B002074380240024B4FF06E -:1037A00080721A60704700BF7438024008B5FFF796 -:1037B000E9FF024B1868C0F3407008BD703B002061 -:1037C00008B5FFF7DFFF024B1868C0F3007008BDB3 -:1037D000703B0020EFF3098305494A6822F001029B -:1037E0004A60683383F30988002383F311887047A4 -:1037F00030EF00E0202080F3118862B60B4B0C4ABA -:10380000D96821F4E0610904090C0A430949DA6026 -:10381000CA6842F08072CA6007490A6842F0010231 -:103820000A601022DA7783F82200704700ED00E08A -:103830000003FA05F0ED00E0001000E010B52023D1 -:1038400083F311880E4B5B6813F4006314D0F1EE20 -:10385000103AEFF30984683C4FF08073E361094B41 -:10386000DB68236684F30988FFF712FC10B1064B6E -:10387000A36110BD054BFBE783F3118810BD00BFAA -:1038800000ED00E030EF00E0770600087A0600085F -:1038900070470000FEE70000084A094B09498B42C7 -:1038A00004D3094A0021934205D3704752F8040F0C -:1038B00043F8040BF3E743F8041BF4E7D040000897 -:1038C000F83B0020F83B0020F83B00207047000048 -:1038D00000F086B84FF08043002258631A6102223C -:1038E000DA6070474FF080430022DA6070470000D2 -:1038F0004FF08043586370474FF08043586A7047D9 -:103900004B6843608B688360CB68C3600B6943611D -:103910004B6903628B6943620B6803607047000068 -:1039200008B51F4B1F481A6942F0FF021A611A6955 -:1039300022F0FF021A611A691A6B42F0FF021A6341 -:103940001A6D42F0FF021A65174A1B6D1146FFF708 -:10395000D7FF164802F11C01FFF7D2FF144802F10D -:103960003801FFF7CDFF134802F15401FFF7C8FFFC -:10397000114802F17001FFF7C3FF104802F18C01FA -:10398000FFF7BEFF0E4802F1A801FFF7B9FF0D488F -:1039900002F1C401FFF7B4FFBDE8084000F0A4B88D -:1039A0000038024000000240C83F00080004024006 -:1039B00000080240000C02400010024000140240C7 -:1039C00000180240001C024008B500F019FAFFF789 -:1039D0008BFBBDE80840FFF7D5BE00007047000034 -:1039E000104B1A6C42F001021A641A6E42F0010286 -:1039F0001A660D4A1B6E936843F0010393604FF003 -:103A0000804331229A624FF0FF32DA6200229A61DB -:103A10005A63DA605A6001225A6108211A601C2038 -:103A2000FFF752B800380240002004E04FF0804217 -:103A300008B51369D1680B40D9B2C9439B0711611E -:103A400007D5202383F31188FFF76EFB002383F350 -:103A5000118808BD08B5FFF7E9FFBDE80840FFF78A -:103A6000EDBE00001E4B1A6962F0FF021A611A696E -:103A7000D2B21A614FF0FF301A695A6958610021B9 -:103A80005A6959615A691A6A62F080521A621A6A4E -:103A900002F080521A621A6A5A6A58625A6A596265 -:103AA0005A6A1A6C42F080521A641A6E42F08052BE -:103AB0001A661A6E0B4A106840F480701060186F16 -:103AC00000F44070B0F5007F1EBF4FF480301867DF -:103AD0001967536823F40073536000F071B900BF95 -:103AE00000380240007000403C4B3D4A1A643D4A99 -:103AF0004FF4404111601A6842F001021A601A68DE -:103B00009207FCD59A6822F003029A60334B19465B -:103B10009A6812F00C02FBD1186800F0F9001860E6 -:103B20009A601A6842F480321A600B689803FCD5D8 -:103B30004B6F43F001034B67284B5A6F9207FCD53C -:103B4000294A5A601A6842F080721A60254A5368FE -:103B50005804FCD5214B1A4619688901FCD5234924 -:103B6000C3F88410196841F08061196013681B0163 -:103B7000FCD51F4B93600323C2F88C304FF00063D9 -:103B8000C2F894301B4B1A681B4B9A421B4B21D135 -:103B90001B4A11681B4A91421CD140F203121A6061 -:103BA000164A136803F00F03032BFAD10B4B9A68E4 -:103BB00042F002029A609A6802F00C02082AFAD1D6 -:103BC0005A6C42F480425A645A6E42F480425A66F9 -:103BD0005B6E704740F20372E1E700BF00380240BD -:103BE000000400100070004008194002103000244A -:103BF00000948838002004E011640020003C02405A -:103C000000ED00E041C20F41084A08B55369116850 -:103C10000B4003F00103536123B1054A13680BB154 -:103C200050689847BDE80840FFF708BE003C0140D7 -:103C3000783B0020084A08B5536911680B4003F02F -:103C40000203536123B1054A93680BB1D0689847CA -:103C5000BDE80840FFF7F2BD003C0140783B002082 -:103C6000084A08B5536911680B4003F00403536117 -:103C700023B1054A13690BB150699847BDE8084064 -:103C8000FFF7DCBD003C0140783B0020084A08B546 -:103C9000536911680B4003F00803536123B1054ACF -:103CA00093690BB1D0699847BDE80840FFF7C6BDDE -:103CB000003C0140783B0020084A08B55369116870 -:103CC0000B4003F01003536123B1054A136A0BB193 -:103CD000506A9847BDE80840FFF7B0BD003C01407E -:103CE000783B0020174B10B55C691A68144004F447 -:103CF00078725A61A30604D5134A936A0BB1D06A4D -:103D00009847600604D5104A136B0BB1506B984767 -:103D1000210604D50C4A936B0BB1D06B9847E20592 -:103D200004D5094A136C0BB1506C9847A30504D510 -:103D3000054A936C0BB1D06C9847BDE81040FFF773 -:103D40007DBD00BF003C0140783B00201A4B10B500 -:103D50005C691A68144004F47C425A61620504D517 -:103D6000164A136D0BB1506D9847230504D5134ABD -:103D7000936D0BB1D06D9847E00404D50F4A136ED4 -:103D80000BB1506E9847A10404D50C4A936E0BB149 -:103D9000D06E9847620404D5084A136F0BB1506F78 -:103DA0009847230404D5054A936F0BB1D06F984709 -:103DB000BDE81040FFF742BD003C0140783B0020C9 -:103DC000062108B50846FEF77FFE06210720FEF70C -:103DD0007BFE06210820FEF777FE06210920FEF76C -:103DE00073FE06210A20FEF76FFE06211720FEF75C -:103DF0006BFE06212820BDE80840FEF765BE0000E6 -:103E000008B5FFF72FFE00F00BF8FEF773FEFFF783 -:103E100075F8FFF7E3FDBDE80840FFF759BD000066 -:103E2000002304491A465A50C8180833802B4260B0 -:103E3000F9D17047783B002010B501390244904217 -:103E400001D1002010BD10F8013B11F8014FA34231 -:103E5000F5D0181B10BD00002DE9F8430746884631 -:103E600091461E468BB10D46A8EB0500B54207EB07 -:103E7000000402D20020BDE8F883324649462046BD -:103E8000FFF7DAFF18B1013DEEE7BDE8F883204601 -:103E9000BDE8F883034611F8012B03F8012B002A33 -:103EA000F9D1704740A2E4F1646891064E6F206139 -:103EB0007070207369670A00426164206677206C25 -:103EC000656E6774682025750A0042616420626F20 -:103ED0006172645F69642025752073686F756C6416 -:103EE0002062652025750A0042616420667720649F -:103EF000657363726970746F72206C656E67746845 -:103F00002025750A0042616420617070204352438D -:103F1000203078253038783A30782530387820309D -:103F200078253038783A3078253038780A00476F6D -:103F30006F64206669726D776172650A0000000027 -:103F40006F72672E6172647570696C6F742E637521 -:103F500061765F677073000000000000C52E0008E6 -:103F6000B12E0008ED2E0008D92E0008E52E00081D -:103F7000D12E0008BD2E0008A92E0008F92E000839 -:103F80006D61696E00000000A03F0008C03900208C -:103F9000383B002001000000E53000080000000070 -:103FA00069646C65000000000040000000400000F3 -:103FB000004000000040000000000100000002007E -:103FC0000000020000000200A00110280000000014 -:103FD000AAAAAAAA50011024FFFF0000007700003F -:103FE0000000000000A40A0100000000AAA6AAAA7E -:103FF00080500000DFEF0000000000778800000024 -:104000000000000000000000AAAAAAAA0000000008 -:10401000FFFF0000000000000000000000000000A2 +:1000000000070020E5040008BD1500083D150008A4 +:10001000951500083D15000869150008E70400085B +:10002000E7040008E7040008E7040008ED370008CB +:10003000E7040008E7040008E7040008E7040008F4 +:10004000E7040008E7040008E7040008E7040008E4 +:10005000E7040008E7040008193C0008453C0008D4 +:10006000713C00089D3C0008C93C0008E7040008FA +:10007000E7040008E7040008E7040008E7040008B4 +:10008000E7040008E7040008E704000875250008F5 +:10009000E12500083526000889260008F53C0008FF +:1000A000E7040008E7040008E7040008E704000884 +:1000B000693A0008E7040008E7040008E7040008BC +:1000C000E7040008E7040008E7040008E704000864 +:1000D000E70400082D2A0008412A0008E704000868 +:1000E0005D3D0008E7040008E7040008E704000895 +:1000F000E7040008E7040008E7040008E704000834 +:10010000E7040008E7040008E7040008E704000823 +:10011000E7040008E7040008E7040008E704000813 +:10012000E7040008E7040008E7040008E704000803 +:10013000E7040008E7040008E7040008E7040008F3 +:10014000E7040008E7040008E7040008E7040008E3 +:10015000E7040008E7040008E7040008E7040008D3 +:10016000E7040008E7040008E7040008E7040008C3 +:10017000E7040008E7040008E7040008E7040008B3 +:10018000E7040008E7040008E7040008E7040008A3 +:10019000E7040008E7040008E7040008E704000893 +:1001A000E7040008E7040008E7040008E704000883 +:1001B000E7040008E7040008E7040008E704000873 +:1001C000E7040008E7040008E7040008E704000863 +:1001D000E7040008E7040008E7040008E704000853 +:1001E00053B94AB9002908BF00281CBF4FF0FF319E +:1001F0004FF0FF3000F074B9ADF1080C6DE904CE9A +:1002000000F006F8DDF804E0DDE9022304B07047F1 +:100210002DE9F047089D04468E46002B4DD18A42B9 +:10022000944669D9B2FA82F252B101FA02F3C2F1EC +:10023000200120FA01F10CFA02FC41EA030E94407D +:100240004FEA1C48210CBEFBF8F61FFA8CF708FB9E +:1002500016E341EA034306FB07F199420AD91CEB76 +:10026000030306F1FF3080F01F81994240F21C81A8 +:10027000023E63445B1AA4B2B3FBF8F008FB1033F0 +:1002800044EA034400FB07F7A7420AD91CEB040425 +:1002900000F1FF3380F00A81A74240F207816444F5 +:1002A000023840EA0640E41B00261DB1D44000237A +:1002B000C5E900433146BDE8F0878B4209D9002DDE +:1002C00000F0EF800026C5E9000130463146BDE868 +:1002D000F087B3FA83F6002E4AD18B4202D38242D2 +:1002E00000F2F980841A61EB030301209E46002D81 +:1002F000E0D0C5E9004EDDE702B9FFDEB2FA82F2D6 +:10030000002A40F09280A1EB0C014FEA1C471FFA33 +:100310008CFE0126200CB1FBF7F307FB131140EA1A +:1003200001410EFB03F0884208D91CEB010103F1E7 +:10033000FF3802D2884200F2CB804346091AA4B2A9 +:10034000B1FBF7F007FB101144EA01440EFB00FE7D +:10035000A64508D91CEB040400F1FF3102D2A645E2 +:1003600000F2BB800846A4EB0E0440EA03409CE781 +:10037000C6F12007B34022FA07FC4CEA030C20FA2E +:1003800007F401FA06F31C43F9404FEA1C4900FA4E +:1003900006F3B1FBF9F8200C1FFA8CFE09FB1811CB +:1003A00040EA014108FB0EF0884202FA06F20BD93E +:1003B0001CEB010108F1FF3A80F08880884240F28E +:1003C0008580A8F102086144091AA4B2B1FBF9F0D2 +:1003D00009FB101144EA014100FB0EFE8E4508D9CD +:1003E0001CEB010100F1FF346CD28E456AD9023852 +:1003F000614440EA0840A0FB0294A1EB0E01A14237 +:10040000C846A64656D353D05DB1B3EB080261EBA4 +:100410000E0101FA07F722FA06F3F1401F43C5E97E +:10042000007100263146BDE8F087C2F12003D840B4 +:100430000CFA02FC21FA03F3914001434FEA1C47F6 +:100440001FFA8CFEB3FBF7F007FB10360B0C43EAE8 +:10045000064300FB0EF69E4204FA02F408D91CEB98 +:10046000030300F1FF382FD29E422DD90238634496 +:100470009B1B89B2B3FBF7F607FB163341EA034136 +:1004800006FB0EF38B4208D91CEB010106F1FF3885 +:1004900016D28B4214D9023E6144C91A46EA00467C +:1004A00038E72E46284605E70646E3E61846F8E60E +:1004B0004B45A9D2B9EB020864EB0C0E0138A3E757 +:1004C0004646EAE7204694E74046D1E7D0467BE738 +:1004D000023B614432E7304609E76444023842E7B0 +:1004E000704700BF02E000F000F8FEE772B63A483D +:1004F00080F30888394880F3098839484EF6085156 +:10050000CEF20001086040F20000CCF200004EF68E +:100510003471CEF200010860BFF34F8FBFF36F8FCD +:1005200040F20000C0F2F0004EF68851CEF2000119 +:100530000860BFF34F8FBFF36F8F4FF00000E1EE05 +:10054000100A4EF63C71CEF200010860062080F3DE +:100550001488BFF36F8F03F0C9F903F0A5F903F016 +:10056000EFF94FF055301F491B4A91423CBF41F80B +:10057000040BFAE71C49194A91423CBF41F8040BAD +:10058000FAE71A491A4A1B4B9A423EBF51F8040B2C +:1005900042F8040BF8E700201749184A91423CBF83 +:1005A00041F8040BFAE703F083F903F017FA144C4F +:1005B000144DAC4203DA54F8041B8847F9E700F005 +:1005C00041F8114C114DAC4203DA54F8041B884732 +:1005D000F9E703F06BB900000007002000230020BA +:1005E000000000080001002000070020D0400008A3 +:1005F000002300202423002028230020003C00208A +:10060000E0010008E0010008E0010008E001000846 +:100610002DE9F04F2DED108AC1F80CD0C3689D462E +:10062000BDEC108ABDE8F08F002383F311882846C3 +:10063000A047002002F0B0FDFEE702F035FD00DF2C +:10064000FEE700002DE9F04103F06EF8074603F0E5 +:10065000B9F8054600283DD12B4B9F423AD00133D3 +:100660009F423AD0294B27F0FF029A4239D1F8B283 +:1006700000F052FAA84642F2107400F057FC08B19C +:100680000024A04600F04EFA064670B37CBB4646F6 +:1006900035B11F4B9F4203D003F08CF8002426464F +:1006A000002003F04BF81B4B1B691B0722D40EB133 +:1006B00000F032F800F098FC00F07EFE00F080FFC1 +:1006C0000546CCB100F07CFF401BA04214D900F0DD +:1006D00023F8F3E7A8460024CFE704464FF00108CB +:1006E000CBE780464FF47A74C7E70446D0E74FF46F +:1006F0007A74CDE70024DDE700F028FD4FF47A702E +:1007000002F050FDDDE700BF010007B0000008B0B7 +:10071000263A09B0000402401E4B1F4A10B51C4681 +:100720001968013134D004339342F9D162681B4B0C +:100730009A422DD91A4B9B6803F1006303F580336D +:100740009A4225D203F00AF803F01CF8002000F0CA +:100750004DFE144B0220187000F084FE124B1A6CF0 +:1007600000221A64196E1A66196E596C5A64596E11 +:100770005A665B6E72B64FF0E0232021C3F8084D35 +:10078000D4E9003281F311889D4683F3088810472D +:1007900010BD00BF0000010820000108FFFF000895 +:1007A000002300202823002000380240094A136853 +:1007B00049F2690099B21B0C00FB01331360064B30 +:1007C000186844F2506182B2000C01FB020018600C +:1007D00080B27047202300201C23002010B5002188 +:1007E0001022044600F05AFE034B03CB20606160E8 +:1007F0001868A06010BD00BF107AFF1F2DE9F043FC +:10080000224DBBB000F0DCFEAB6840F2ED22C31A13 +:10081000934232D906AFA8602B46282200213846E1 +:1008200001F0DCFB05F10E0000F030FE002604466E +:100830005FFA80F905F10E08F3B2F100994501F174 +:10084000280107D908EB06030822384601F0C6FB49 +:100850000136F1E708230122CDE9023205340C4BC1 +:100860000193A4B230230093CDE9047405A3D3E926 +:100870000023297B074801F0C9F93BB0BDE8F083AC +:10088000AFF3008078F6339F93CACD8D703300208C +:100890007D3300204433002070B50D4614461E46BB +:1008A00001F04AF950B9022E10D1012C0ED112A339 +:1008B000D3E90023C5E90023012007E0282C10D04C +:1008C00005D8012C09D0052C0FD0002070BD302C8C +:1008D000FBD10BA3D3E90023ECE70BA3D3E900235F +:1008E000E8E70BA3D3E90023E4E70BA3D3E9002354 +:1008F000E0E700BFAFF30080401DA12026812A0B56 +:1009000078F6339F93CACD8D9E6AC421818A46EEC4 +:1009100026417272DF25D7B7F017304A39059E5647 +:1009200013B504462346084620220021019001F019 +:1009300055FB22790198032A234628BF032203F896 +:10094000042F2021022201F049FB62790198072A35 +:10095000234628BF072203F8052F2221032201F096 +:100960003DFBA2790198072A234628BF072203F8F6 +:10097000062F2521032201F031FB019804F1080321 +:100980001022282101F02AFB382002B010BD0000FF +:100990002DE9F04FFFB01FAD0CAE40F2751280464E +:1009A0000F4620A80021296000F078FD4822002190 +:1009B000304600F073FD00F003FE554B4FF47A72A1 +:1009C000B0FBF2F0186093E80700012386E8070007 +:1009D0000DF152003382FFF701FF4EF6031333840B +:1009E00006AB18464B4903F063FA162230642946D9 +:1009F000304686F83C20FFF793FF10AB04460146D3 +:100A00000822284601F0EAFA0822A1180DF1410354 +:100A1000284601F0E3FA0DF14203082204F1100127 +:100A2000284601F0DBFA11AB202204F11801284618 +:100A300001F0D4FA12AB402204F13801284601F04B +:100A4000CDFA14AB082204F17801284601F0C6FA69 +:100A50000DF15103082204F18001284601F0BEFA8D +:100A600004F1880A0DF1520904F5847B4B46514686 +:100A7000082228460AF1080A01F0B0FAD34509F124 +:100A80000109F3D119AB08225946284601F0A6FA0C +:100A900004F588744FF0000996F834304B450AD9B4 +:100AA000B36B21464B440822284601F097FA0834DC +:100AB00009F10109F0E74FF0000996F83C304B4589 +:100AC00004EBC90108D9336C08224B44284601F0D5 +:100AD00085FA09F10109F0E700230393BB7E029335 +:100AE000073107F119030193C1F3CF010123CDE9C8 +:100AF00004510093F97E04A3D3E90023404601F09A +:100B000085F87FB0BDE8F08F9E6AC421818A46EEE9 +:100B10002C230020C03E0008014B1870704700BF16 +:100B200038230020F0B5334B1C7B85B034B1324BF9 +:100B30000E221A810024204605B0F0BD2F4A10680D +:100B4000516802AB03C308232D492E480DEB030265 +:100B500003F08CF9054630B9274B2B480A221A813D +:100B600000F0E8FCE6E70169B1F5E02F06D9224B79 +:100B700026480B221A8100F0DDFCDCE7438B40F2B3 +:100B8000E932934207D01C490C20088119462048BD +:100B900000F0D0FCCFE71F4A024402F11003994253 +:100BA00004D2154B1C4810221A81E4E710398E1A22 +:100BB0002046144900F008FD3246074605F11801A9 +:100BC000204600F001FDAB689F4202D1EB689842DD +:100BD0000AD0094B0D221A810090D5E902123B463A +:100BE0000E4800F0A7FCA5E70D4800F0A3FC012487 +:100BF000A1E700BF703300202C230020693F0008CC +:100C0000DCFF060000000108D83E0008E43E0008B2 +:100C1000F63E00080800FFF7143F0008313F0008C7 +:100C20005A3F00082DE9F04FADB006AF80460C46A4 +:100C300000F082FF054600285AD1237E022B1BD1EB +:100C4000E38A012B18D100F0BBFC0646FFF7AEFD8E +:100C500003464FF4C870DFF8D092B3FBF0F206F50C +:100C6000167602FB103316FA83F3C9F80030E37EE0 +:100C700033B9A84B00221A709C37BD46BDE8F08FEF +:100C8000A38AEEB2013BB34205F101050BD93B1D2E +:100C90001E44E90000960023082201F0F8012046D6 +:100CA00001F060F8ECE707F11400FFF797FD32461A +:100CB00007F11401381D03F0C9F80028D9D10F2E0F +:100CC00008D8944B1E70D9F80030A3F51673C9F8F4 +:100CD0000030D1E7FB1CF870014600930722034661 +:100CE000204601F03FF8F978404600F01DFFC3E7C9 +:100CF000E38A282B26D010D8012B1ED0052BBBD180 +:100D0000BFF34F8F8449854BCA6802F4E0621343F6 +:100D1000CB60BFF34F8F00BFFDE7302BACD1637EBC +:100D20007F4D01336A7BDBB29342E94603D1E27E19 +:100D30002B7B9A4265D0CD469EE721464046FFF781 +:100D400027FE99E7A38A013B9BB2C92B94D8744D27 +:100D50002E7B26BB05F10C03009308223346314657 +:100D6000204600F0FFFF731CF2B2D9001E46A38A92 +:100D7000013B9A4205DA0E322A44009200230822EF +:100D8000EEE700230022C5E900230023AB6085F8CD +:100D9000D730C5F8D8302B7B0BB9E37E2B730025F9 +:100DA00007F114093B1D082229464846C7E90155A9 +:100DB000FD6001F013F93B7A05F1010AAB424FEAFD +:100DC000CA0608D9FB6808222B443146484601F080 +:100DD00005F95546EFE7C6F3CF06E17ECDE9049667 +:100DE00000230393A37E02931934282300930194D4 +:100DF00046A3D3E90023404600F008FFFFF7FEFCBE +:100E00003AE74FF0000807F11403A7F81480102206 +:100E1000009341460123204600F0A4FFA68A023E2B +:100E2000B6B2F31C9B109B000733DB08A9EBC3038E +:100E30009D460DF1180A1FFA88F34FEAC801B34224 +:100E400001F110010AD20AEB0803009308220023E3 +:100E5000204600F087FF08F10108ECE795F8D7007D +:100E600000F0CEFAD5F8D83004461BB995F8D70073 +:100E700000F0D6FAD5F8D83033449C4204D295F825 +:100E8000D700013000F0CCFA4FEA960B4FF0000883 +:100E90001FFA88F18B45D5E9003209D90AEB8801A0 +:100EA00003EB8800012200F001FB08F10108EFE7E5 +:100EB000F31842F10002C5E90032D5F8D83095F8B0 +:100EC000D70006EB0308C5F8D88000F099FA8045F2 +:100ED00009D395F8D730D5F8D8000133001B85F831 +:100EE000D730C5F8D800FF2E08D800232B7300F0A8 +:100EF000A9FAFFF717FE08B1FFF70EFC2B68094AA5 +:100F00009B0A013313810023AB6014E72641727200 +:100F1000DF25D7B73D33002000ED00E00400FA05DF +:100F2000703300202C2300204033002030B54FF0D8 +:100F30000054244B22689A4285B007D002F04CFC42 +:100F40000446A8B90024204605B030BD1E4B627D82 +:100F50001A701E48237D03731D49C9220E3000F00C +:100F60008BFA2046E022002100F098FA0124EAE7FB +:100F7000184A194D136C43F000731364AA6D174B94 +:100F80009A42DFD12B6E013B7E2BDBD8144A07CA75 +:100F900001AB83E807001846032100F02BFB6B6DC3 +:100FA00083424FF00003CDD12A6D8A4201BFAB6569 +:100FB000054B2A6E1A7003BF0A4BEA6D1A601C4675 +:100FC000C1E700BF9AAD44C538230020703300202C +:100FD0001600002000380240006600405041A0B0DA +:100FE00058660040182300202DE9FF474B4C022390 +:100FF0006371002302934A4BD3F800C0BCF57A7F9B +:1010000012D3484B484FB7FBFCF69C458CBF0A23D4 +:101010001123581EB6FBF3F503FB1562C1B2002A7B +:101020003ED002280346F4D89DF80B303F49404893 +:101030005A1E9DF80A30013B1B0443EA0253BDF8D7 +:101040000820013A13434B6001F04EFD0023019349 +:10105000384B394900933948394B4FF4805200F0EE +:101060003DFD384B197811B1344800F05DFD00F0BA +:10107000A7FA0546FFF79AFB4FF4C873B0FBF3F2EB +:1010800002FB130305F5167010FA83F02E4B18605F +:1010900002F098FB08B10F23238104B0BDE8F0876C +:1010A0006B1EB3F5806FBFD2C1EBC10E0EF103030F +:1010B0004FEAE309C3F3C703A1EB030809F1010AEF +:1010C0004FF47A705FFA88F609FB00005AFA88F844 +:1010D000B0FBF8F0B0F5617F08D90EF1FF33C3F330 +:1010E000C703C91ACEB2591E0F2914D8721E072A77 +:1010F0008CBF00220122991901FB0551B7FBF1F7C2 +:10110000BC4591D1002A8FD0ADF808508DF80A3037 +:101110008DF80B6088E71346EDE700BF2C23002015 +:10112000182300203F420F0040787D01102300204B +:1011300088340020990800083C2300204433002014 +:10114000250C000838230020403300202DE9F04F03 +:1011500091A7D7E900670FF24829D9E90089874D9F +:1011600093B0DFF844B2864C284600F0B3FD0DF191 +:10117000300A079070B310220021504600F08EF91B +:10118000079B197B4FF0000261F303028DF83020BA +:10119000586899680EAA03C21B680D9A63F31C0273 +:1011A0009DF830300D9243F020038DF8303000234D +:1011B00052461946584601F0A7FC079028B9284620 +:1011C00000F08CFD079B2370CEE72378072B3CD8DB +:1011D0000133237018220021504600F05FF9DFF838 +:1011E000C8B1684C002319465246584601F0B4FC79 +:1011F000014670BB102208A800F050F9636983F41F +:101200008053636100F0DEF90B4612A9024611E932 +:1012100003000DF1240C8CE803009DF83410C1F399 +:10122000030089064CBF0E99BDF838C08DF82C001C +:1012300046BFC1F31C0C4CF00041CCF30A010891ED +:10124000284608A900F012FFCCE7284600F046FD2A +:10125000C0E7284600F070FC0446002848D1DFF8BB +:101260004CB100F0ADF9DBF80030984240D300F00B +:10127000A7F90790FFF79AFA079A8DF820400346DE +:101280004FF4C87002F51672B3FBF0F101FB103396 +:1012900012FA83F3CBF80030DFF814B19BF800109A +:1012A00011B901238DF8203050460791FFF796FAC7 +:1012B0000799C1F11004E4B2062C28BF0624224687 +:1012C00051440DF1210000F0D7F808AB0393182327 +:1012D000029301342C4B0193E4B201230093049454 +:1012E0003B463246284600F029FC00238BF80030AC +:1012F00000F066F9254A264C1368C31AB3F57A7FC5 +:1013000031D3106000F05EF902460B46284600F02B +:10131000EFFC284600F010FC28B3237BDFF894B0E4 +:10132000002B14BF032302238BF8053000F048F98B +:101330004FF47A735146B0FBF3F0CBF800005846F7 +:10134000FFF7EEFA182307300293124B0193C0F314 +:10135000CF0040F25513CDE903A0009342464B461F +:10136000284600F0EBFB237B2BB1FFF747FA237BEA +:10137000002B7FF4F6AE13B0BDE8F08F44330020AD +:1013800055340020000402403C330020503400203B +:101390007033002054340020401DA12026812A0BE8 +:1013A000F1C6A7C1D068080F883400204033002060 +:1013B0003D3300202C23002070B502F055F8094E73 +:1013C000094D3080002428683388834208D902F010 +:1013D00045F82B6804440133B4F5803F2B60F2D309 +:1013E00070BD00BF843400205834002002F000B9E2 +:1013F00000F10060920000F5803002F083B8000038 +:10140000054B1A68054B1B889B1A834202D910446E +:1014100002F024B8002070475834002084340020A3 +:1014200038B5074D04462868204402F01FF828B953 +:1014300028682044BDE8384002F030B838BD00BF0D +:1014400058340020064991F8243033B10023086A4B +:1014500081F824300822FFF7CBBF0120704700BF7E +:101460005C340020022802BF024B4FF080529A6188 +:10147000704700BF0004024010B50023934203D020 +:10148000CC5CC4540133F9E710BD000003460246AA +:10149000D01A12F9011B0029FAD170470244034601 +:1014A000934202D003F8011BFAE770472DE9F84395 +:1014B0001F4D144695F824200746884652BBDFF896 +:1014C00070909CB395F824302BB92022FF21484618 +:1014D0002F62FFF7E3FF95F82400C0F10802A24253 +:1014E00028BF2246D6B24146920005EB8000FFF7A6 +:1014F000C3FF95F82430A41B1E44F6B2082E1744EF +:101500009044E4B285F82460DBD1FFF79BFF00280C +:10151000D7D108E02B6A03EB82038342CFD0FFF7D9 +:1015200091FF0028CBD10020BDE8F8830120FBE724 +:101530005C3400200FB4002004B0704700B59BB0AD +:10154000EFF3098168226846FFF796FFEFF3058302 +:10155000044B9A6BDA6A9A6A9A6A9A6A9A6A9A6ADF +:101560009B6AFEE700ED00E000B59BB0EFF3098158 +:1015700068226846FFF780FFEFF30583044B9A6B00 +:101580009A6A9A6A9A6A9A6A9A6A9B6AFEE700BF9E +:1015900000ED00E000B59BB0EFF3098168226846DA +:1015A000FFF76AFFEFF30583034B5A6B9A6A9A6A57 +:1015B0009A6A9A6A9B6AFEE700ED00E0FEE7000087 +:1015C00002F050B802F028B830B5094D0A449142F3 +:1015D0000DD011F8013B5840082340F30004013BB3 +:1015E0002C4013F0FF0384EA5000F6D1EFE730BD42 +:1015F0002083B8EDF7B54FF0FF33DFF854C0DFF8C4 +:1016000054E000EB81011A4688421CD050F8044B8C +:10161000019401AF042417F8015B82EA05620825F2 +:10162000DB18164605F1FF355241002EBCBF83EA98 +:101630000C0382EA0E0215F0FF05F1D1013C14F013 +:10164000FF04E8D1E0E7D843D14303B0F0BD00BFC9 +:101650009336EAA9EBE1F0422DE9F041C56915B9ED +:10166000C161BDE8F0814B6823F06047C3F38A464F +:101670004FEAD37EC3F3807816EA230638BF3E468E +:10168000AC462B465A68BEEBD27F22F060440AD0AB +:10169000002A18DAA40CB44217D19D420FD10D6074 +:1016A000DEE71346EEE7A74207D102F08044C2F31B +:1016B000807242450BD054B1EFE708D2EDE7CCF889 +:1016C00000100B60CDE7B44201D0B442E5D81A68EF +:1016D0009C46002AE5D11960C3E700002DE9F047D8 +:1016E000089D01F007044FEAD508224405F00705DC +:1016F00000EBD1004FF47F49944201D1BDE8F0875F +:1017000004F0070705F0070A57453E4638BF56461E +:10171000C6F10806111B8E4228BF0E46E10808EBF1 +:10172000D50E415C13F80EC0B94029FA06F721FA2C +:101730000AF1FFB28CEA010147FA0AF739408CEA54 +:10174000010C03F80EC034443544D5E780EA01208B +:10175000082341F2210201B24000002980B203F1C6 +:10176000FF33B8BF504013F0FF03F4D170470000BF +:1017700038B50C468D18A54200D138BD14F8011BB0 +:10178000FFF7E4FFF7E7000002684AB1136803605F +:10179000C388018901339BB29942C38038BF03815A +:1017A0001046704770B588B0202204460D46684642 +:1017B0000021FFF773FE20460495FFF7E5FF024680 +:1017C00058B16B46054608AE1C4603CCB4422860AF +:1017D0006960234605F10805F6D1104608B070BDD2 +:1017E000082817D909280CD00A280CD00B280CD0AF +:1017F0000C280CD00D280CD00E2814BF402030200F +:1018000070470C2070471020704714207047182034 +:101810007047202070470000082817D90C280CD9E1 +:1018200010280CD914280CD918280CD920280CD928 +:1018300030288CBF0F200E207047092070470A20E7 +:1018400070470B2070470C2070470D207047000038 +:1018500010B54B6823B9CA8A63F30902CA8210BD66 +:10186000C4681A681C60C360438A013B43824A60B3 +:10187000EFE700002DE9F84F1D46CB8A0F46C3F372 +:1018800009010629814692460B4630D00020AAB2B3 +:1018900007F119049EB2052E1FFA80F80FD8904563 +:1018A00003F1010306D3FB8A0A4462F30903FB82B6 +:1018B00001201AE01AF80060E6540130EAE790458A +:1018C000F1D2A1F1060B1C237C68BBFBF3F203FBF6 +:1018D00012BB1FFA8BF6002C45D14846FFF754FF88 +:1018E000044638B978606FF00200BDE8F88F4FF019 +:1018F0000008E6E7002606607860ADB24FF0000B06 +:10190000454510D90AEB0803221D13F8011B915518 +:10191000B1B208F101081B291FFA88F82BD0454500 +:1019200006F10106F1D8FB8AC3F30902154465F3F9 +:101930000903BCE7013292B21C462368002BF9D19F +:10194000AB1F0B441C21B3FBF1F301339BB29A4252 +:10195000D3D2BBF1000FD0D14846FFF715FF20B915 +:10196000C4F800B0BFE70122E7E7C0F800B05E4668 +:1019700020600446C1E74545D5D94846FFF704FF36 +:1019800008B92060AFE7C0F800B000262060044628 +:10199000B6E700002DE9F04F2DED028B83B0CDE9C5 +:1019A0000013BDF83C5007469146002A00F0928093 +:1019B0002DB10E9B002B00F08D80072D32D807F142 +:1019C0000C00FFF7E1FE044638B96FF00204204630 +:1019D00003B0BDEC028BBDE8F08F14220021FFF7AD +:1019E0005DFD0E992A4604F10800FFF745FD681CCD +:1019F000C0B2FFF711FFFFF7F3FE207499F8003033 +:101A0000013814FA80F003F01F0363F03F03037200 +:101A1000009B43F00041616038462146FFF71CFE01 +:101A20000124D4E700F10C034FF0000808EE103A4F +:101A30004FF0800A4646444618EE100AFFF7A4FE0F +:101A400083460028C1D014220021FFF727FDC6BB22 +:101A5000019BABF8083002200E9B00F10802991997 +:101A60005BFA82F20130C0B2082801D0AE422AD31C +:101A7000FFF7D2FEFFF7B4FE99F80020009B411E4D +:101A800002F01F0242EA4812AE4208BF4FF0400A7D +:101A90005BFA81F14AEA020A43F0004281F808A0A9 +:101AA0008BF81000CBF8042059463846FFF7D4FDD8 +:101AB0000134AE4224B288F001084FF0000ABBD1D5 +:101AC00085E70020C8E711F801CB02F801CB013609 +:101AD000B6B2C7E76FF0010479E70000F8B5154624 +:101AE0000E462822002104461F46FFF7D7FC069B1E +:101AF0006360B5F5001F079BA76034BF6A094FF606 +:101B0000FF72236204F10C0097B200239A4205D8B9 +:101B10000023036027826382A382F8BD066001333D +:101B200030462036F2E7000003781BB94BB2002B99 +:101B3000C8BF017070470000007870472DE9F74F6B +:101B4000DDF83C90BDF830500D9E9DF83840BDF852 +:101B50004070804692469B46B9F1000F01D1002F9C +:101B600051D11F2C4FD898F80000B0B9072F47D893 +:101B700035F0030347D13A4649464FF6FF70FFF769 +:101B8000F7FD20F001002D02400445EA0464400CFA +:101B900044EA40244FF6FF7321E040EA0520072F76 +:101BA00040EA0464F6D900254FF6FF73C5F1200022 +:101BB000A5F120022AFA05F10BFA00F001432BFAF5 +:101BC00002F211431846C9B2FFF7C0FD0835402D97 +:101BD0000346EBD13A464946FFF7CAFD0346CDE935 +:101BE0000097324621464046FFF7D4FE3378013352 +:101BF000DBB21F2B88BF0023337003B0BDE8F08F2A +:101C00006FF00300F9E76FF00100F6E72DE9F04F00 +:101C100085B09246DDF848800F9D9DF840209DF8E4 +:101C20004490BDF84C7006469B46B8F1000F01D1B8 +:101C3000002F48D11F2A46D83378002B46D00C02FB +:101C400044EA02649DF8381044EAC93444EA014485 +:101C50001C43072F44F0800432D900234FF6FF7253 +:101C6000C3F1200CA3F120002AFA03F10BFA0CFCBB +:101C700041EA0C012BFA00F00143C9B2104603936C +:101C8000FFF764FD039B0833402B0246E8D13A4638 +:101C90004146FFF76DFD0346CDE900872A46214600 +:101CA0003046FFF777FEB9F1010F06D12B780133EB +:101CB000DBB21F2B88BF00232B7005B0BDE8F08F6F +:101CC0004FF6FF73E8E76FF00100F6E76FF00300EF +:101CD000F3E70000C06900B104307047C3691A68B7 +:101CE000C261C2681A60C360438A013B4382704785 +:101CF0002DE9F041D0F81880194E14461D46414692 +:101D0000002709B9BDE8F081D1E90223A21A65EBE9 +:101D10000303964277EB03031ED283698B420DD1F6 +:101D2000FFF796FD83691B688361C3680B60438A74 +:101D3000C1608169013B43828846E2E7FFF788FD85 +:101D40000B68C8F80030C3680B60438AC160013B70 +:101D50004382D8F80010D4E788460968D1E700BF6D +:101D600080841E002DE9F04F8BB00D46DDF85090B9 +:101D700014469B468046002800F01981B9F1000FF7 +:101D800000F01581531E3F2B00F21181012A03D16F +:101D9000BBF1000F40F00B810023CDE90833B8F808 +:101DA0001430B5EBC30F4FEAC30703D300200BB0C9 +:101DB000BDE8F08F2B199F42D8F80C303ABF7F1B3B +:101DC000FFB227461BB9D8F81030002B7AD02F2D40 +:101DD0004ED8C5F13006B7424FF000032CBFF6B223 +:101DE0003E4600932946D8F8080008AB3246FFF774 +:101DF00075FCA7EB060A35445FFA8AFAB8F8143086 +:101E000003F10053063BDB000493D8F80C30039336 +:101E10003021039B13B1BAF1000F2CD1D8F8100078 +:101E200040B1BAF1000F05D0009608AB5246691ACE +:101E3000FFF754FC38B2002FB8D066070AD00AABBF +:101E400003EBD401624211F8083C02F0070213418F +:101E500001F8083C082C3CD9102C40F2B580202C0D +:101E600040F2B780BBF1000F00F09C80082334E003 +:101E7000BA460026C2E7049BE02B28BFE023069366 +:101E80000B44AB42059314D95A1B03980096924514 +:101E900034BF5246D2B2691A08AB04300792FFF73A +:101EA0001DFC079A1644AAEB020A1544F6B25FFA23 +:101EB0008AFA049B069A05999B1A0493039B1B6854 +:101EC0000393A6E70093D8F8080008AB3A462946E2 +:101ED000AEE7BBF1000F13D00123B4EBC30F6CD0FE +:101EE000082C12D89DF82030621E23FA02F2D50782 +:101EF00006D54FF0FF3202FA04F423438DF8203068 +:101F00009DF8203089F8003051E7102C12D8BDF828 +:101F10002030621E23FA02F2D10706D54FF0FF32BD +:101F200002FA04F42343ADF82030BDF82030A9F8BC +:101F300000303CE7202C0FD80899631E21FA03F3E8 +:101F4000DA0705D54FF0FF3202FA04F40C43089487 +:101F5000089BC9F800302AE7402C2BD0DDE9086542 +:101F6000611EC4F12102A4F1210326FA01F105FA50 +:101F700002F225FA03F311431943CB0712D50122CC +:101F8000A4F12003C4F1200102FA03F322FA01F1C3 +:101F9000A240524243EA010363EB430332432B4323 +:101FA000CDE90823DDE90823C9E90023FFE66FF046 +:101FB0000100FCE66FF00800F9E6082CA0D9102C0F +:101FC000B3D9202CEED8C3E7BBF1000FADD002236C +:101FD00083E7BBF1000FBBD004237EE730B5012AB5 +:101FE000144638BF0124402C85B028BF402400256A +:101FF000012ACDE9025518D81B788DF808306307FF +:102000000AD004AB03EBD405624215F8083C02F099 +:102010000702934005F8083C009103462246002140 +:1020200002A8FFF75BFB05B030BD082AE4D9102AEF +:1020300003D81B88ADF80830E1E7202A8DBFD3E92B +:1020400000231B680293CDE90223D8E710B5CB68C3 +:102050001BB98B600B618B8210BDC4681A681C6051 +:10206000C360438A013B4382CA60F0E72DE9F04F29 +:10207000D1F8008093B018F0800FCDE90323C8F3A6 +:10208000C01219BFC8F3C03BC8F306264FF0020BBD +:102090001646B8F1000F04460D4680F2D18118F0C3 +:1020A000C043059340F0CC810B7B002B00F0C8812E +:1020B000BBF1020F03D00178B14240F0C48108F0B7 +:1020C0007F0106916AB3C8F3074A2B44069A93F836 +:1020D0000390760646EA0B4646EA82465FEAD91343 +:1020E00046EA0A06079300F0908000220023CDE91B +:1020F0000A23069B009367685B4652460AA920465E +:10210000B84700287ED0A7699FB9314604F10C007A +:10211000FFF748FB0746E0B96FF0020013B0BDE8D7 +:10212000F08FC8F30F2A18F07F0F08BF0AF0030AD8 +:10213000CBE73B699E420DD03F68002FF9D1314675 +:1021400004F10C00FFF72EFB07460028E4D0A3693A +:102150003B60A761DDE90A2300264FF6FF70C6F158 +:10216000200E22FA06F103FA0EFEA6F1200C23FA45 +:102170000CFC41EA0E0141EA0C01C9B20836099291 +:102180000893FFF7E3FA402EDDE90832E7D1B88281 +:10219000FB7D09F01F06C3F384039B1BD7E90221D3 +:1021A00098B2002BBCBF00F120031BB252EA010021 +:1021B000C8F304680FD00398821A049860EB0101F9 +:1021C000A74890424FF000028A4104D3079A002AA0 +:1021D0005BD0012B23DDFA7D4FEA890302F0030275 +:1021E00003F07C031343FB7539462046FFF730FBB1 +:1021F000079BA3B9FB7DC3F38402013262F386031C +:10220000FB7504E06FF00B0088E7A76917B96FF062 +:102210000C0083E73B699E42BAD03F68F6E719F0AD +:10222000400F32D0039BBB60049BFB601422002153 +:102230000DA8FFF733F9039B0A93049B0B932B1D07 +:102240000C932B7BADF83EA0013BDBB2ADF83C30EC +:10225000069B8DF8433094F824308DF840B083F01D +:1022600001038DF844308DF84160A3688DF84280F9 +:102270000AA920469847FB7DC3F38403013303F08A +:102280001F039B02FB82002048E7FB7DC9F340123D +:10229000B2EBD31F40F0DA80C3F38403B34240F0C3 +:1022A000D88007992B7B4FEA9912002934D0D207A6 +:1022B00041D4032B40F2D080039BBB60049BFB60A6 +:1022C0002B7BAE1D033BDBB23246394604F10C00DA +:1022D000FFF7D0FA00280DDA20463946FFF7B8FAA2 +:1022E000FB7DC3F38403013303F01F039B02FB82D6 +:1022F000032013E7AB883B832A7B033AB88AD2B228 +:102300003146FFF735FAFB7DB882DA43C2F3C012DB +:1023100062F3C713FB75B6E76AB92E1D013BDBB24A +:102320003246394604F10C00FFF7A4FA0028D3DB4B +:102330002A7B013AE2E7F98AC1F30901013B052949 +:10234000DAB259D8281D002307F11A0C9A4208D98D +:1023500010F801EB0CF801E0013101330629DBB282 +:10236000F4D103990A9104990B91934207F11A0150 +:102370000C9138BF043379680D9134BF55FA83F35B +:1023800000230E93FB8AADF83EA0C3F309031A4461 +:10239000069B8DF8433094F82430ADF83C2083F050 +:1023A00001038DF8443000238DF840B08DF8416072 +:1023B0008DF842807B602A7BB88A013A291DFFF79D +:1023C000D7F93B8BB882834203D1A3680AA9204680 +:1023D000984720460AA9FFF739FEFB7DB88AC3F368 +:1023E0008403013303F01F039B02FB823B8B984263 +:1023F00014BF1120002091E67B68002BB1D006208D +:1024000001E01C306346D3F800C0BCF1000FF8D1E6 +:10241000091A081D05F1040C00EB030905989DF845 +:10242000143001EB000EBEF11B0F9AD89A4298D9D6 +:102430001CF8013B09F8013B059B01330593EDE7CF +:102440006FF009006AE66FF00A0067E66FF00D00B2 +:1024500064E66FF00E0061E66FF00F005EE600BF0D +:1024600080841E00404BF0B51C6C404E44F000745C +:102470001C641D6E45F000751D661B6E3C4B9B6A0F +:10248000D3F80052354045F00105C3F80052D3F8A7 +:102490000042344044EA002040F00100C3F800024A +:1024A000002952D00020C3F81C020546C3F80402DC +:1024B000C3F80C02C3F8140203EBC00401301C285B +:1024C000C4F84052C4F84452F6D100254FF0010C34 +:1024D00096781488F70748BFD3F804720CFA04F012 +:1024E00044BF0743C3F80472B70742BFD3F80C7266 +:1024F0000743C3F80C72760742BFD3F81462064351 +:10250000C3F8146203EBC4045668C4F840629668CA +:10251000C4F84462D3F81C4201352043A942C3F8F1 +:102520001C0202F10C02D3D1D3F8002222F00102E6 +:10253000C3F800220C4B1A6C22F000721A641A6E57 +:1025400022F000721A661B6EF0BD0122C3F8401221 +:10255000C3F84412C3F80412C3F81412C3F80C22CF +:10256000C3F81C22E0E700BF003802400000FFFF74 +:1025700088340020184A916A08B58B688B6013F084 +:10258000010104D013F00C0F18BF4FF48031D805AF +:1025900006D513F4406F14BF41F4003141F002013D +:1025A000D80306D513F4402F14BF41F4802141F025 +:1025B0000401D3690BB108489847202383F311889D +:1025C0000648002100F016FE002383F31188BDE8C1 +:1025D000084001F03FB900BF88340020903400204B +:1025E00038B5124CA36ADD68AA0712D05A6922F0E6 +:1025F00002025A61A36913B10121204698472023A2 +:1026000083F311880A48002100F0F4FD002383F3CE +:102610001188EB0606D5A36A1021D960236A0BB195 +:1026200002489847BDE8384001F014B988340020CA +:102630009834002038B5124CA36A1D69AA0712D03D +:102640005A6922F010025A61A36913B1022120468F +:102650009847202383F311880A48002100F0CAFD1F +:10266000002383F31188EB0606D5A36A10211961B4 +:10267000236A0BB102489847BDE8384001F0EAB838 +:10268000883400209834002038B50F4CA36A5D6868 +:102690005D602A070AD5042222701A6822F002021D +:1026A0001A60636A13B10021204698476B0706D56C +:1026B000A36A9969236A13B1034809049847BDE8DE +:1026C000384001F0C7B800BF8834002010B50E4C68 +:1026D000204600F0F7F90D4BA3620B21132000F008 +:1026E000D9F90B21142000F0D5F90B21152000F0A9 +:1026F000D1F90B21162000F0CDF90022BDE81040E1 +:1027000011460E20FFF7AEBE883400200064004062 +:10271000114B984210B5044609D1104B1A6C42F087 +:1027200000721A641A6E42F000721A661B6EA36A77 +:1027300001221A60A36A5A68D20707D562685168F5 +:102740001268D9611A60064A5A6110BD0121082039 +:1027500000F046FCEEE700BF88340020003802405D +:102760005B87010003291AD8DFE801F0020A0F1481 +:10277000836A9B6813F0E05F14BF0120002070475C +:10278000836A9868C0F380607047836A9868C0F372 +:10279000C0607047836A9868C0F30070704700207B +:1027A0007047000010B5032925D8DFE801F00225A5 +:1027B000292D836A9968C1F30161183103EB011374 +:1027C000107884064CBF54689488C0F300114FEA17 +:1027D000410148BF41EAC40100F00F004CBF41F085 +:1027E000040141EA4451586041F001019068D26807 +:1027F0009860DA60196010BD836A03F5C073DFE783 +:10280000836A03F5C873DBE7836A03F5D073D7E700 +:1028100001290AD002290FD081B9836ADA689207A8 +:1028200001D1186903E001207047836AD86810F06D +:10283000030018BF01207047836AF2E70020704749 +:1028400010B539B9836AD96889071BD11B699C0700 +:1028500004D110BD012915D00229FAD1816AD1F81D +:10286000C031D1F8C441D1F8C8011061D1F8CC0110 +:102870005061202008610869800717D1486940F03D +:10288000100012E0816AD1F8B031D1F8B441D1F82A +:10289000B8011061D1F8BC0150612020C860C8683F +:1028A000800703D1486940F002004861C3F340004B +:1028B000C3F38001000140EA4111107920F030009B +:1028C0000143117189064BBF91681189DB085B0DCB +:1028D0004CBF63F31C0163F30A01137948BF916095 +:1028E00064F3030313714FEA14234FEA144458BFEF +:1028F000118113705480ACE7026843681143016092 +:1029000003B1184770470000024AD36843F0C00380 +:10291000D360704700100140024AD36843F0C003FF +:10292000D3607047004400402DE9F041D0F85C626C +:10293000F7683368DA0504469DB20DD5202383F38A +:1029400011884FF400710430FFF7D6FF6FF48073E5 +:102950003360002383F31188202383F3118804F16B +:10296000040815F02F033AD183F31188380615D5E2 +:10297000290613D5202383F3118804F1380000F0D1 +:1029800023FA00284DDA0821201DFFF7B5FF4FF686 +:102990007F733B40F360002383F311887A0616D5DA +:1029A0006B0614D5202383F31188D4E913239A42AC +:1029B0000AD1236C43B127F040073F041021201DAA +:1029C0003F0CFFF799FFF760002383F31188D4F8D9 +:1029D0006422D3683BB3BDE8F041106918472B0768 +:1029E00013D015F0080F0CBF00218021E80748BF65 +:1029F00041F02001AA0748BF41F040016B0748BFE2 +:102A000041F480714046FFF777FFAD06736805D546 +:102A100094F860122046194000F078FA3568ADB29B +:102A20009FE77060B7E7BDE8F081000008B5034894 +:102A3000FFF77AFFBDE8084000F00CBFB434002077 +:102A400008B50348FFF770FFBDE8084000F002BF7B +:102A50001C37002010B5094C094A2046002100F01F +:102A600033FA084BC4F85C32074C084A0021204670 +:102A700000F02AFA064BC4F85C3210BDB4340020D2 +:102A800009290008001001401C37002019290008FE +:102A90000044004000F1604303F561430901C9B2FD +:102AA00083F80013012200F01F039A4043099B00A2 +:102AB00003F1604303F56143C3F880211A60704756 +:102AC000FFF704BE012300F10802C0E902220370EF +:102AD00000F110020023C0E90422C0E90633C0E976 +:102AE000083343607047000010B52023044683F389 +:102AF0001188022303704160FFF70AFE042323704C +:102B0000002383F3118810BD2DE9F0411F460446D0 +:102B10000D461646202383F3118800F10808237818 +:102B2000052B0DD029462046FFF71CFE40B120465C +:102B300032462946FFF736FE002080F3118808E070 +:102B40003946404600F03AFB0028E8D0002383F3E2 +:102B50001188BDE8F08100002DE9F0411F460446D0 +:102B60000D461646202383F3118800F110082378C0 +:102B7000052B0DD029462046FFF74AFE40B12046DE +:102B800032462946FFF75CFE002080F3118808E0FA +:102B90003946404600F012FB0028E8D0002383F3BA +:102BA0001188BDE8F0810000F8B515468268066915 +:102BB000AA420B46816938BF8568761AB542044639 +:102BC0000BD218462A46FEF757FCA3692B44A36193 +:102BD000A3685B1BA3602846F8BD0CD91846324693 +:102BE000FEF74AFCAF1BE1683A463044FEF744FC6E +:102BF000E3683B44EBE718462A46FEF73DFCE368F2 +:102C0000E5E7000083689342F7B51546044638BFF0 +:102C10008568D0E90460361AB5420BD22A46FEF721 +:102C20002BFC63692B446361A36828465B1BA3608C +:102C300003B0F0BD0DD932460191FEF71DFC01999C +:102C4000E068AF1B3A463144FEF716FCE3683B44AC +:102C5000E9E72A46FEF710FCE368E4E710B50A440A +:102C60000024C361029B8460C0E90000C0E9051133 +:102C7000C1600261036210BD08B5D0E9053293421C +:102C800001D1826882B98268013282605A1C426135 +:102C90001970D0E904329A4224BFC368436100210D +:102CA00000F09CFA002008BD4FF0FF30FBE7000069 +:102CB00070B5202304460E4683F31188A568A5B19C +:102CC000A368A269013BA360531CA3611578226924 +:102CD000934224BFE368A361E3690BB120469847A0 +:102CE000002383F31188284607E03146204600F090 +:102CF00065FA0028E2DA85F3118870BD2DE9F74FF7 +:102D000004460E4617469846D0F81C904FF0200A0D +:102D10008AF311884FF0000B154665B12A463146FB +:102D20002046FFF741FF034660B94146204600F0C8 +:102D300045FA0028F1D0002383F31188781B03B0F3 +:102D4000BDE8F08FB9F1000F03D001902046C847CD +:102D5000019B8BF31188ED1A1E448AF31188DCE77E +:102D6000C0E90511C160C3611144009B8260C0E9E4 +:102D70000000016103627047F8B504460D4616462F +:102D8000202383F31188A768A7B1A368013BA36040 +:102D900063695A1C62611D70D4E904329A4224BFEF +:102DA000E3686361E3690BB120469847002080F334 +:102DB000118807E03146204600F000FA0028E2DAE8 +:102DC00087F31188F8BD0000D0E905239A4210B5B9 +:102DD00001D182687AB98268013282605A1C8261AC +:102DE0001C7803699A4224BFC3688361002100F004 +:102DF000F5F9204610BD4FF0FF30FBE72DE9F74F06 +:102E000004460E4617469846D0F81C904FF0200A0C +:102E10008AF311884FF0000B154665B12A463146FA +:102E20002046FFF7EFFE034660B94146204600F01A +:102E3000C5F90028F1D0002383F31188781B03B073 +:102E4000BDE8F08FB9F1000F03D001902046C847CC +:102E5000019B8BF31188ED1A1E448AF31188DCE77D +:102E6000026843681143016003B1184770470000CE +:102E70001430FFF743BF00004FF0FF331430FFF76B +:102E80003DBF00003830FFF7B9BF00004FF0FF33FF +:102E90003830FFF7B3BF00001430FFF709BF000060 +:102EA0004FF0FF311430FFF703BF00003830FFF759 +:102EB00063BF00004FF0FF323830FFF75DBF000006 +:102EC00000207047FFF7C6BD37B515460E4A0260B1 +:102ED00000224260C0E902220122044602740B462D +:102EE000009000F15C014FF480721430FFF7B6FEE1 +:102EF00000942B464FF4807204F5AE7104F1380053 +:102F0000FFF72EFF03B030BD743F000838B5C3692A +:102F100004460D461BB904210844FFF7A1FF2946CA +:102F200004F11400FFF7A8FE002806DA201D4FF474 +:102F30008061BDE83840FFF793BF38BD024B0022E7 +:102F4000C3E900339A60704784390020002303747A +:102F50008268054B1B6899689142FBD25A680360EE +:102F600042601060586070478439002008B5202303 +:102F700083F31188037C032B05D0042B0DD02BB9D0 +:102F800083F3118808BD436900221A604FF0FF33B4 +:102F90004361FFF7DBFF0023F2E7D0E90032136063 +:102FA0005A60F3E7002303748268054B1B68996835 +:102FB0009142FBD85A6803604260106058607047C5 +:102FC00084390020054B19690874186802681A6072 +:102FD0005360186101230374FDF71ABB8439002084 +:102FE00030B54B1C0B4D87B0044610D02B690A4AF4 +:102FF00001A800F01BF92046FFF7E4FF049B13B182 +:1030000001A800F04FF92B69586907B030BDFFF7F0 +:10301000D9FFF8E7843900206D2F000838B50C4D32 +:1030200041612B6981689A689142044603D8BDE8E2 +:103030003840FFF78BBF1846FFF7B4FF01232C6120 +:10304000014623742046BDE83840FDF7E1BA00BFD1 +:1030500084390020044B1A681B6990689B68984269 +:1030600094BF0020012070478439002010B5084C1F +:10307000236820691A6822605460012223611A744F +:10308000FFF790FF01462069BDE81040FDF7C0BA88 +:103090008439002008B5FFF7DDFF18B1BDE808400E +:1030A000FFF7E4BF08BD0000FFF7E0BFFEE7000048 +:1030B00010B50C4CFFF742FF00F0AAF80A49802235 +:1030C000204600F031F8012344F8180C037400F096 +:1030D0009DFB002383F3118862B60448BDE81040CD +:1030E00000F042B8AC3900209C3F0008AC3F00081B +:1030F00000F012B9EFF3118020B9EFF3058320221D +:1031000082F311887047000010B530B9EFF30584E1 +:10311000C4F3080414B180F3118810BDFFF7BAFF9F +:1031200084F31188F9E7000082600222028270476E +:103130008368A3F17C0243F80C2C026943F83C2C11 +:10314000426943F8382C074A43F81C2CC26843F8FC +:10315000102C022203F8082C002203F8072CA3F1FC +:10316000180070472906000810B5202383F3118842 +:10317000FFF7DEFF00210446FFF750FF002383F333 +:103180001188204610BD0000024B1B6958610F20BA +:10319000FFF718BF84390020202383F31188FFF73D +:1031A000F3BF000008B50146202383F311880820EF +:1031B000FFF716FF002383F3118808BD49B1064BC2 +:1031C00042681B6918605A60136043600420FFF76F +:1031D00007BF4FF0FF3070478439002003689842E2 +:1031E00006D01A680260506059611846FFF7AEBEFB +:1031F0007047000038B504460D462068844200D16F +:1032000038BD036823605C604561FFF79FFEF4E70B +:10321000054B03F11402C3E905224FF0FF310022F0 +:10322000C3E90712704700BF8439002070B51C4EF7 +:10323000C0E9032305460C4600F06EFB334653F805 +:10324000142F9A420DD13062C5E901242A600A2C5C +:103250002CBF00190A30C6E90555BDE8704000F0E2 +:1032600049BB316A431AE31838BF1C469368A3422E +:1032700002D9081900F04CFB73699A6894420CD883 +:103280005A68AC602B606A6015609A685D60121BBA +:103290009A604FF0FF33F36170BD1B68A41AECE72E +:1032A0008439002038B51B4C636998420DD0D0E9B1 +:1032B000003213605A6000228168C2609A680A4432 +:1032C0009A604FF0FF33E36138BD2246036842F84D +:1032D000143F002193425A60C16003D1BDE83840D9 +:1032E00000F010BB9A688168256A0A449A6000F071 +:1032F00013FB63699A68411B8A42E5D9AB181D1A12 +:10330000092D206A98BF01F10A02BDE83840104437 +:1033100000F0FEBA843900202DE9F041184C002756 +:1033200004F11406656900F0F7FA236AAA68C11A65 +:103330008A4215D813442362D5E9003213605A60DB +:103340006369D5F80C80EF60B34201D100F0DAFA7E +:1033500087F311882869C047202383F31188E1E7A8 +:103360006169B14209D013441B1ABDE8F0410A2B30 +:103370002CBFC0180A3000F0CBBABDE8F08100BF06 +:103380008439002000207047FEE7000070470000ED +:103390004FF0FF3070470000BFF34F8F024AD368F1 +:1033A000DB03FCD4704700BF003C024008B5094B6A +:1033B0001B7873B9FFF7F0FF074B1A69002ABFBFEC +:1033C000064A5A6002F188325A601A6822F4806212 +:1033D0001A6008BD403B0020003C024023016745C5 +:1033E00008B50B4B1B7893B9FFF7D6FF094B1A6949 +:1033F00042F000421A611A6842F480521A601A6858 +:1034000022F480521A601A6842F480621A6008BD81 +:10341000403B0020003C02400728F0B516D80C4C79 +:103420000C4923787BB90C4D0E4608234FF00062FF +:1034300055F8047B46F8042B013B13F0FF033A4494 +:10344000F6D10123237051F82000F0BD0020FCE7E5 +:10345000643B0020443B0020C43F0008014B53F86C +:1034600020007047C43F000808207047072810B5A7 +:10347000044601D9002010BDFFF7CEFF064B53F8DC +:1034800024301844C21A0BB90120F4E71268013243 +:10349000F0D1043BF6E700BFC43F0008072838B569 +:1034A000044628D8FFF726FEFFF776FFFFF77EFFDA +:1034B000124AF323D360E300DBB243F4007343F01A +:1034C00002031361136943F48033136105462046F8 +:1034D000FFF762FFFFF7A0FF094B53F8241000F03D +:1034E0003BF92846FFF77CFFFFF70EFE2046BDE8BC +:1034F0003840FFF7BBBF002038BD00BF003C024092 +:10350000C43F000812F001032DE9F04105460E46C4 +:1035100014464BD18118334A914261D8324B1B6813 +:1035200013F001035CD0314FFFF7E4FDFFF73EFFDE +:10353000F323FB60FFF730FF314640F20128032CF4 +:1035400018D824F00104294E0C446D1A40F20118D9 +:10355000A142336905EB01072AD123F0010333614E +:10356000FFF73EFFFFF7D0FD0120BDE8F081043CEE +:103570000435E4E7AB07E4D13B6923F440733B61D6 +:103580003B6943EA08033B6151F8046B2E60BFF3CB +:103590004F8FFFF701FF2B689E42E8D03B6923F075 +:1035A00001033B61FFF71CFFFFF7AEFD0020DCE7E6 +:1035B00023F440733361336943EA080333610B88B2 +:1035C0003B80BFF34F8FFFF7E7FE3F8831F8023BA8 +:1035D000BFB2BB42BCD0336923F001033361E1E7E2 +:1035E0001846C2E70000080800380240003C0240CC +:1035F000084908B50B7828B11BB9FFF7D7FE01239E +:103600000B7008BD002BFCD0BDE808400870FFF728 +:10361000E7BE00BF403B002070B582B0FFF76AFDF7 +:103620000E4E054600F078F93268904237BF0C4ADA +:103630000B49516814682EBFD1E900410131516036 +:103640000419034641F10001284601913360FFF758 +:103650005BFD0199204602B070BD00BF683B0020B1 +:10366000703B002070B582B0FFF744FD104E054658 +:1036700000F052F93268904237BF0E4A0D49516846 +:1036800014682EBFD1E9004101315160041941F1A4 +:1036900000010346284601913360FFF735FD01998B +:1036A0004FF47A7200232046FCF79AFD02B070BDF9 +:1036B000683B0020703B002010B50244064BD2B29C +:1036C000904200D110BD441C00B253F8200041F8D4 +:1036D000040BE0B2F4E700BF502800400F4B30B5B8 +:1036E0001C6F240407D41C6F44F400741C671C6F07 +:1036F00044F400441C670A4C236843F4807323603D +:103700000244084BD2B2904200D130BD441C00B2FA +:1037100051F8045B43F82050E0B2F4E7003802406F +:10372000007000405028004007B5012201A9002088 +:10373000FFF7C2FF019803B05DF804FB13B5044620 +:10374000FFF7F2FFA04205D0012201A90020019459 +:10375000FFF7C4FF02B010BD70470000074B45F2F1 +:1037600055521A6002225A6040F6FF729A604CF677 +:10377000CC421A60024B01221A70704700300040A0 +:103780007C3B0020034B1B781BB1034B4AF6AA225B +:103790001A6070477C3B002000300040034B1A68E1 +:1037A0001AB9034AD2F874281A607047783B00208F +:1037B00000300240024B4FF08072C3F8742870470B +:1037C0000030024008B5FFF7E9FF024B1868C0F36C +:1037D000407008BD783B002008B5FFF7DFFF024BC3 +:1037E0001868C0F3007008BD783B0020EFF3098330 +:1037F00005494A6B22F001024A63683383F3098862 +:10380000002383F31188704700EF00E0202080F34D +:10381000118862B60C4B0D4AD96821F4E0610904A5 +:10382000090C0A43DA60D3F8FC20094942F080729F +:10383000C3F8FC200A6842F001020A601022DA771D +:1038400083F82200704700BF00ED00E00003FA0596 +:10385000001000E010B5202383F311880E4B5B6845 +:1038600013F4006314D0F1EE103AEFF30984683CCE +:103870004FF08073E361094BDB6B236684F30988A7 +:10388000FFF7E8FB10B1064BA36110BD054BFBE74A +:1038900083F31188F9E700BF00ED00E000EF00E0DE +:1038A0003B0600083E06000870470000FEE70000E7 +:1038B0000A4B0B480B4A90420BD30B4BDA1C121AE3 +:1038C000C11E22F003028B4238BF00220021FDF707 +:1038D000E5BD53F8041B40F8041BECE7F440000876 +:1038E000003C0020003C0020003C0020704700000D +:1038F00000F080B84FF08043002258631A61022222 +:10390000DA6070474FF080430022DA6070470000B1 +:103910004FF08043586370474FF08043586A7047B8 +:103920004B6843608B688360CB68C3600B694361FD +:103930004B6903628B6943620B6803607047000048 +:1039400008B5234B23481A6942F0FF021A611A692D +:1039500022F0FF021A611A691A6B42F0FF021A6321 +:103960001A6D42F0FF021A651B4A1B6D1146FFF7E4 +:10397000D7FF02F11C0100F58060FFF7D1FF02F1D3 +:10398000380100F58060FFF7CBFF02F1540100F52C +:103990008060FFF7C5FF02F1700100F58060FFF75E +:1039A000BFFF02F18C0100F58060FFF7B9FF02F163 +:1039B000A80100F58060FFF7B3FF02F1C40100F534 +:1039C0008060FFF7ADFFBDE8084000F097B800BF8A +:1039D0000038024000000240E43F000808B500F053 +:1039E00017FAFFF765FBBDE80840FFF7D7BE0000F8 +:1039F00070470000104B1A6C42F001021A641A6EF4 +:103A000042F001021A660D4A1B6E936843F00103EF +:103A100093604FF0804331229A624FF0FF32DA62B6 +:103A200000229A615A63DA605A6001225A610821C1 +:103A30001A601C20FFF72EB800380240002004E076 +:103A40004FF0804208B51169D3680B40D9B2C94321 +:103A50009B07116107D5202383F31188FFF748FBEB +:103A6000002383F3118808BD08B5FFF7E9FFBDE81F +:103A70000840FFF7EFBE00001E4B1A6962F0FF021C +:103A80001A611A69D2B21A614FF0FF301A695A6985 +:103A9000586100215A6959615A691A6A62F0805264 +:103AA0001A621A6A02F080521A621A6A5A6A5862D4 +:103AB0005A6A59625A6A1A6C42F080521A641A6E33 +:103AC00042F080521A661A6E0B4A106840F48070F9 +:103AD0001060186F00F44070B0F5007F1EBF4FF407 +:103AE000803018671967536823F40073536000F03F +:103AF0006FB900BF00380240007000403B4B3C4AA9 +:103B00001A643C4A4FF4404111601A6842F00102C5 +:103B10001A601A689007FCD59A6822F003029A602E +:103B2000324B9A6812F00C02FBD1196801F0F901CE +:103B300019609A601A6842F480321A601A68910318 +:103B4000FCD55A6F42F001025A67284B5A6F920710 +:103B5000FCD5294A5A601A6842F080721A60254AD8 +:103B600053685804FCD5214B1A689101FCD5234AAF +:103B7000C3F884201A6842F080621A601A68120141 +:103B8000FCD51F4A9A600322C3F88C204FF00062D4 +:103B9000C3F894201B4B1A681B4B9A421B4B21D134 +:103BA0001B4A11681B4A91421CD140F203121A6051 +:103BB000164A136803F00F03032BFAD10B4B9A68D4 +:103BC00042F002029A609A6802F00C02082AFAD1C6 +:103BD0005A6C42F480425A645A6E42F480425A66E9 +:103BE0005B6E704740F20372E1E700BF00380240AD +:103BF000000400100070004008194002103000243A +:103C000000948838002004E011640020003C024049 +:103C100000ED00E041C20F41084A08B55169136840 +:103C20000B4003F00103536123B1054A13680BB144 +:103C300050689847BDE80840FFF70CBE003C0140C3 +:103C4000803B0020084A08B5516913680B4003F017 +:103C50000203536123B1054A93680BB1D0689847BA +:103C6000BDE80840FFF7F6BD003C0140803B002066 +:103C7000084A08B5516913680B4003F00403536107 +:103C800023B1054A13690BB150699847BDE8084054 +:103C9000FFF7E0BD003C0140803B0020084A08B52A +:103CA000516913680B4003F00803536123B1054ABF +:103CB00093690BB1D0699847BDE80840FFF7CABDCA +:103CC000003C0140803B0020084A08B55169136858 +:103CD0000B4003F01003536123B1054A136A0BB183 +:103CE000506A9847BDE80840FFF7B4BD003C01406A +:103CF000803B0020174B10B55A691C68144004F42F +:103D000078725A61A30604D5134A936A0BB1D06A3C +:103D10009847600604D5104A136B0BB1506B984757 +:103D2000210604D50C4A936B0BB1D06B9847E20582 +:103D300004D5094A136C0BB1506C9847A30504D500 +:103D4000054A936C0BB1D06C9847BDE81040FFF763 +:103D500081BD00BF003C0140803B00201A4B10B5E4 +:103D60005A691C68144004F47C425A61620504D507 +:103D7000164A136D0BB1506D9847230504D5134AAD +:103D8000936D0BB1D06D9847E00404D50F4A136EC4 +:103D90000BB1506E9847A10404D50C4A936E0BB139 +:103DA000D06E9847620404D5084A136F0BB1506F68 +:103DB0009847230404D5054A936F0BB1D06F9847F9 +:103DC000BDE81040FFF746BD003C0140803B0020AD +:103DD000062108B50846FEF75DFE06210720FEF71E +:103DE00059FE06210820FEF755FE06210920FEF7A0 +:103DF00051FE06210A20FEF74DFE06211720FEF790 +:103E000049FEBDE8084006212820FEF743BE000019 +:103E100008B5FFF731FE00F00BF8FEF751FEFFF793 +:103E200051F8FFF7E5FDBDE80840FFF761BD000070 +:103E30000023054A19460133102BC2E9001102F193 +:103E40000802F8D1704700BF803B002010B501394F +:103E50000244904201D1002005E0037811F8014F9F +:103E6000A34201D0181B10BD0130F2E72DE9F0414B +:103E7000A3B1C91A17780144044603F1FF3C8C42F0 +:103E8000204601D9002009E00578BD4204F1010473 +:103E9000F5D10CEB0405D618A54201D1BDE8F0819F +:103EA00015F8018D16F801EDF045F5D0E7E70000B3 +:103EB000034611F8012B03F8012B002AF9D17047B2 +:103EC0006F72672E6172647570696C6F742E6375A2 +:103ED00061765F67707300004E6F206170702073B1 +:103EE00069670A00426164206677206C656E6774BA +:103EF000682025750A0042616420626F6172645F08 +:103F000069642025752073686F756C642062652074 +:103F100025750A00426164206677206465736372C8 +:103F20006970746F72206C656E6774682025750AFD +:103F30000042616420617070204352432030782534 +:103F40003038783A30782530387820307825303855 +:103F5000783A3078253038780A00476F6F642066E9 +:103F600069726D776172650A0040A2E4F16468913C +:103F700006000000000000008D2E0008792E0008C9 +:103F8000B52E0008A12E0008AD2E0008992E0008BD +:103F9000852E0008712E0008C12E00086D61696E23 +:103FA0000000000069646C6500000000A43F000888 +:103FB000C8390020403B002001000000AD3000085F +:103FC0000000000000400000004000000040000031 +:103FD000004000000000010000000200000002009C +:103FE00000000200A001102800000000AAAAAAAA4E +:103FF00050011024FFFF00000077000000000000C7 +:1040000000A40A0100000000AAA6AAAA805000008D +:10401000DFEF0000000000778800000000000000D3 :1040200000000000AAAAAAAA00000000FFFF0000EA :104030000000000000000000000000000000000080 :10404000AAAAAAAA00000000FFFF000000000000CA @@ -1032,9 +1032,11 @@ :1040600000000000FFFF0000000000000000000052 :104070000000000000000000AAAAAAAA0000000098 :10408000FFFF000000000000000000000000000032 -:10409000000000000A000000000000000300000013 -:1040A000000000000000000098C1FF7F0100000038 -:1040B000E90300000000000000000700000000000D -:1040C000640000000000000040420F00FE2A0100D2 -:0440D000D204000016 +:1040900000000000AAAAAAAA00000000FFFF00007A +:1040A0000000000000000000000000000000000010 +:1040B0000A000000000000000300000000000000F3 +:1040C000000000004CC1FF7F010000000000000064 +:1040D000E9030000000000000000070000000000ED +:1040E000640000000000000040420F00FE2A0100B2 +:0440F000D2040000F6 :00000001FF diff --git a/Tools/bootloaders/CubeOrange-ODID_bl.bin b/Tools/bootloaders/CubeOrange-ODID_bl.bin new file mode 100755 index 00000000000..a63483ca2de Binary files /dev/null and b/Tools/bootloaders/CubeOrange-ODID_bl.bin differ diff --git a/Tools/bootloaders/CubeOrange-bdshot_bl.bin b/Tools/bootloaders/CubeOrange-bdshot_bl.bin old mode 100644 new mode 100755 index 69fd41369a1..5e40768ac46 Binary files a/Tools/bootloaders/CubeOrange-bdshot_bl.bin and b/Tools/bootloaders/CubeOrange-bdshot_bl.bin differ diff --git a/Tools/bootloaders/CubeOrange-bdshot_bl.hex b/Tools/bootloaders/CubeOrange-bdshot_bl.hex new file mode 100755 index 00000000000..ac844a7f485 --- /dev/null +++ b/Tools/bootloaders/CubeOrange-bdshot_bl.hex @@ -0,0 +1,1105 @@ +:020000040800F2 +:1000000000060020A1020008FD0F00087D0F000877 +:10001000D50F00087D0F0008A90F0008A3020008F3 +:10002000A3020008A3020008A3020008DD290008BB +:10003000A3020008A3020008A3020008A30200080C +:10004000A3020008A3020008A3020008A3020008FC +:10005000A3020008A3020008653E0008913E0008C4 +:10006000BD3E0008E93E0008153F0008A302000855 +:10007000A3020008A3020008A3020008A3020008CC +:10008000A3020008A3020008A3020008A3020008BC +:10009000A3020008A3020008A3020008413F0008D1 +:1000A000A3020008A3020008A3020008A30200089C +:1000B000A3020008A3020008A3020008A30200088C +:1000C000A3020008A3020008A3020008A30200087C +:1000D000A3020008A3020008194000082D400008F0 +:1000E000A53F0008A3020008A3020008A30200081D +:1000F000A3020008A3020008A3020008A30200084C +:10010000A3020008A302000855400008A30200084B +:10011000A3020008A3020008A3020008A30200082B +:10012000A3020008A3020008A3020008A30200081B +:10013000A3020008A3020008A3020008A30200080B +:10014000A3020008A3020008A3020008A3020008FB +:10015000A3020008A3020008A3020008A3020008EB +:10016000A3020008A3020008A3020008A3020008DB +:10017000A302000849350008A3020008A3020008F2 +:10018000A3020008A302000841400008A3020008DF +:10019000A3020008A3020008A3020008A3020008AB +:1001A000A3020008A3020008A3020008A30200089B +:1001B000A3020008A3020008A3020008A30200088B +:1001C000A3020008A3020008A3020008A30200087B +:1001D000A302000835350008A3020008A3020008A6 +:1001E000A3020008A3020008A3020008A30200085B +:1001F000A3020008A3020008A3020008A30200084B +:10020000A3020008A3020008A3020008A30200083A +:10021000A3020008A3020008A3020008A30200082A +:10022000A3020008A3020008A3020008A30200081A +:10023000A3020008A3020008A3020008A30200080A +:10024000A3020008A3020008A3020008A3020008FA +:10025000A3020008A3020008A3020008A3020008EA +:10026000A3020008A3020008A3020008A3020008DA +:10027000A3020008A3020008A3020008A3020008CA +:10028000A3020008A3020008A3020008A3020008BA +:10029000A3020008A3020008A3020008A3020008AA +:1002A00002E000F000F8FEE772B63A4880F30888F2 +:1002B000394880F3098839484EF60851CEF20001DA +:1002C000086040F20000CCF200004EF63471CEF22D +:1002D00000010860BFF34F8FBFF36F8F40F2000043 +:1002E000C0F2F0004EF68851CEF200010860BFF374 +:1002F0004F8FBFF36F8F4FF00000E1EE100A4EF604 +:100300003C71CEF200010860062080F31488BFF330 +:100310006F8F02F021FC02F0C3FB03F05DFB4FF096 +:1003200055301F491B4A91423CBF41F8040BFAE784 +:100330001C49194A91423CBF41F8040BFAE71A499B +:100340001A4A1B4B9A423EBF51F8040B42F8040B69 +:10035000F8E700201749184A91423CBF41F8040BC6 +:10036000FAE702F0DBFB03F0BBFB144C144DAC428C +:1003700003DA54F8041B8847F9E700F041F8114C00 +:10038000114DAC4203DA54F8041B8847F9E702F038 +:10039000C3BB00000006002000220020000000086F +:1003A00000000020000600209044000800220020E9 +:1003B0005C22002060220020D44F0020A002000810 +:1003C000A0020008A0020008A00200082DE9F04FDA +:1003D0002DED108AC1F80CD0D0F80CD0BDEC108AED +:1003E000BDE8F08F002383F311882846A047002042 +:1003F00001F0DAFEFEE701F055FE00DFFEE7000047 +:1004000038B500F0D7FC30B1164B00220E211A721D +:100410005A729972DA7202F0A1FA054602F0D4FA21 +:100420000446D0B9104B9D4219D001339D4241F290 +:10043000883512BF044600250124002002F098FAF6 +:100440000CB100F059F800F039FD00F0F9FB284636 +:1004500000F004F900F050F8F9E70025EDE7054653 +:10046000EBE700BF00220020010007B008B500F054 +:10047000B3FBA0F120035842584108BD07B541F233 +:100480001203022101A8ADF8043000F0C3FB03B051 +:100490005DF804FB202310B583F311881248C3686C +:1004A0000BB101F007FF0023104A4FF47A710E4898 +:1004B00001F0C4FE002383F311880D4C236813B1AF +:1004C0002368013B2360636813B16368013B636089 +:1004D000084B1B7833B9636823B9022000F070FC25 +:1004E0003223636010BD00BF602200209504000825 +:1004F0007C23002074220020F8B5514B514A1C4641 +:100500001968013100F09B8004339342F8D162688E +:100510004D4B9A4240F293804C4B9B6803F1006331 +:1005200003F500339A4280F08A80002000F0A2FB9D +:100530000220474B187000F041FC464B0021D3F8D5 +:10054000E820C3F8E810D3F81021C3F81011D3F84D +:100550001021D3F8EC20C3F8EC10D3F81421C3F821 +:100560001411D3F81421D3F8F020C3F8F010D3F805 +:100570001821C3F81811D3F81821D3F8802042F0BD +:100580000062C3F88020D3F8802022F00062C3F814 +:100590008020D3F88020D3F8802042F00072C3F886 +:1005A0008020D3F8802022F00072C3F88020D3F896 +:1005B000803072B64FF0E023C3F8084DD4E9000450 +:1005C000BFF34F8FBFF36F8F234AC2F88410BFF37E +:1005D0004F8F536923F480335361BFF34F8FD2F8A9 +:1005E000803043F6E076C3F3C905C3F34E335B01B5 +:1005F00003EA060C29464CEA81770139C2F8747285 +:10060000F9D2203B13F1200FF2D1BFF34F8FBFF38C +:100610006F8FBFF34F8FBFF36F8F536923F4003396 +:1006200053610023C2F85032BFF34F8FBFF36F8F77 +:10063000202383F31188854680F308882047F8BD7E +:100640000000020820000208FFFF0108002200202D +:10065000742200200044025800ED00E02DE9F04F24 +:1006600093B0A94B2022FF2100900AA89D6800F0BA +:10067000CFFBA64A1378A3B90121A5481170C36026 +:10068000202383F31188C3680BB101F013FE00230C +:10069000A04A4FF47A719E4801F0D0FD002383F305 +:1006A0001188009B9C4A03B1136000239B49009C66 +:1006B00098469B461E469A460B705360012000F0F8 +:1006C0007DFB24B1944B1B68002B00F016820020A8 +:1006D00000F082FA0390039B002BF2DB012000F074 +:1006E0006BFB039B213B162BE8D801A252F823F0A9 +:1006F0004D0700087507000809080008BD06000836 +:10070000BD060008BD0600089D0800086F0A000825 +:1007100089090008EB090008130A0008390A0008D3 +:10072000BD0600084B0A0008BD060008BD0A000807 +:10073000ED070008BD060008010B00085907000876 +:10074000ED070008BD060008EB0900080220FFF7CE +:100750008DFE002840F0FB81009B022105A8B8F126 +:10076000000F08BF1C4641F21233ADF8143000F000 +:1007700051FAA3E74FF47A7000F02EFA071EEBDB74 +:100780000220FFF773FE0028E6D0013F052F00F29C +:10079000E081DFE807F0030A0D101336052304217A +:1007A00005A8059300F036FA17E004215648F9E74A +:1007B00004215B48F6E704215A48F3E74FF01C098F +:1007C000484609F1040900F057FA0421059005A8EC +:1007D00000F020FAB9F12C0FF2D101204FF0000AFD +:1007E00000FA07F747EA0B0B5FFA8BFB00F05CFBA4 +:1007F00026B10BF00B030B2B08BF0024FFF73EFEC6 +:100800005CE704214848CDE7002EA5D00BF00B0390 +:100810000B2BA1D10220FFF729FE074600289BD011 +:1008200001203E4E00F026FA4FF000080220307002 +:1008300000F0C4FA5FFA88F9484600F02BFA044643 +:1008400090B1484608F1010800F034FA0028F1D1CF +:10085000B846044641F21213022105A83E46ADF8FF +:10086000143000F0D7F929E7012325460220337020 +:1008700000F0A2FA244B9B68AB4207D9284600F04F +:10088000FBF9013040F068810435F3E70025234B84 +:10089000B8463E461D70204B5D60A7E7002E3FF432 +:1008A0005BAF0BF00B030B2B7FF456AF02201B4BFF +:1008B000187000F083FA322000F08EF9B0F10009D0 +:1008C000FFF64AAF19F003077FF446AF0E4A09EB73 +:1008D0000503926893423FF63FAFB9F5807F3FF73B +:1008E0003BAF124BB945019322DD4FF47A7000F013 +:1008F00073F90390039A002AFFF62EAF039A01378B +:10090000019B03F8012BEDE7002200207823002053 +:1009100060220020950400087C230020742200201F +:1009200004220020082200200C220020782200202F +:10093000C820FFF79BFD074600283FF40DAF1F2D91 +:1009400011D8C5F120020AAB25F0030084494A45BD +:10095000184428BF4A46019200F034FA019AFF2158 +:100960007F4800F055FA4FEAA903C9F387027C4992 +:100970002846019300F054FA064600283FF46AAF77 +:10098000019B05EB830531E70220FFF76FFD00288F +:100990003FF4E2AE00F0AAF900283FF4DDAE0027F4 +:1009A000B946704B9B68BB4218D91F2F11D80A9BC0 +:1009B00001330ED027F0030312AA134453F8203C4E +:1009C00005934846042205A9043700F019FB814627 +:1009D000E7E7384600F050F90590F2E7CDF81490BB +:1009E000042105A800F016F900E70023642104A8FB +:1009F000049300F005F900287FF4AEAE0220FFF763 +:100A000035FD00283FF4A8AE049800F065F9059084 +:100A1000E6E70023642104A8049300F0F1F800281D +:100A20007FF49AAE0220FFF721FD00283FF494AE38 +:100A3000049800F053F9EAE70220FFF717FD0028B9 +:100A40003FF48AAE00F062F9E1E70220FFF70EFD05 +:100A500000283FF481AE05A9142000F05DF9074697 +:100A60000421049004A800F0D5F83946B9E73220F3 +:100A700000F0B2F8071EFFF66FAEBB077FF46CAE56 +:100A8000384A07EB0A03926893423FF665AE0220AC +:100A9000FFF7ECFC00283FF45FAE27F00307574454 +:100AA000BA453FF4A3AE50460AF1040A00F0E4F858 +:100AB0000421059005A800F0ADF8F1E74FF47A7035 +:100AC000FFF7D4FC00283FF447AE00F00FF90028F0 +:100AD00044D00A9B01330BD008220AA9002000F061 +:100AE0009FF900283AD02022FF210AA800F090F9AF +:100AF000FFF7C4FC1C4801F05DFB13B0BDE8F08FAC +:100B0000002E3FF429AE0BF00B030B2B7FF424AE29 +:100B10000023642105A8059300F072F80746002819 +:100B20007FF41AAE0220FFF7A1FC814600283FF4B3 +:100B300013AEFFF7A3FC41F2883001F03BFB0598B0 +:100B400000F0FCF94E463C4600F0AEF9B6E506462C +:100B50004CE64FF0000AFFE5B8467BE6374679E6FB +:100B60007822002000220020A08601002DE9F84F05 +:100B70004FF47A7306460D46002402FB03F7DFF8B4 +:100B80005080DFF8509098F900305FFA84FA5A1CD0 +:100B900001D0A34210D159F824002A4631460368F7 +:100BA000D3F820B03B46D847854205D1074B0120FA +:100BB00083F800A0BDE8F88F0134042CE3D14FF492 +:100BC000FA7001F0F7FA0020F4E700BFC823002014 +:100BD0001022002058410008002307B502460121D9 +:100BE0000DF107008DF80730FFF7C0FF20B19DF829 +:100BF000070003B05DF804FB4FF0FF30F9E7000099 +:100C00000A46042108B5FFF7B1FF80F00100C0B229 +:100C1000404208BD074B0A4630B41978064B53F8DA +:100C20002140014623682046DD69044BAC4630BCB8 +:100C3000604700BFC823002058410008A08601007B +:100C400070B50A4E00240A4D01F060FD308028681E +:100C50003388834208D901F055FD2B6804440133E1 +:100C6000B4F5003F2B60F2D370BD00BFCA23002053 +:100C70008423002001F028BE00F1006000F5003060 +:100C80000068704700F10060920000F5003001F04C +:100C90009FBD0000054B1A68054B1B889B1A8342B9 +:100CA00002D9104401F02EBD00207047842300209B +:100CB000CA23002038B5074D04462868204401F0B7 +:100CC00027FD28B928682044BDE8384001F032BD2E +:100CD00038BD00BF842300200020704700F1FF5082 +:100CE00000F58F10D0F8000870470000064991F811 +:100CF000243033B100230822086A81F82430FFF73A +:100D0000C1BF0120704700BF88230020014B186835 +:100D1000704700BF0010005C244BF0B51A68044611 +:100D2000234BC2F30B06120C1F885868BE4293F97E +:100D3000085028D09F89BE4206D101200C2505FB12 +:100D40000033586893F9085041F201039A421CD0CD +:100D500041F203039A421AD042F201039A4218D098 +:100D600042F203039A4208BF5625621E0B46441EF8 +:100D70000A4493420FD214F9016F581C6EB1034616 +:100D800000F8016CF5E70020D8E75A25EDE7592572 +:100D9000EBE75825E9E7184605E02C2482421C7051 +:100DA00001D9981C5D70401AF0BD00BF0010005CB6 +:100DB0001422002000207047704700007047000098 +:100DC00070470000002310B5934203D0CC5CC4549C +:100DD0000133F9E710BD0000013810B510F9013FEB +:100DE0003BB191F900409C4203D11AB10131013A63 +:100DF000F4E71AB191F90020981A10BD1046FCE7EB +:100E000003460246D01A12F9011B0029FAD1704795 +:100E100002440346934202D003F8011BFAE77047ED +:100E20002DE9F8431F4D14460746884695F82420BF +:100E300052BBDFF870909CB395F824302BB9202278 +:100E4000FF2148462F62FFF7E3FF95F82400414653 +:100E5000C0F1080205EB8000A24228BF2246D6B2AC +:100E60009200FFF7AFFF95F82430A41B17441E44EF +:100E70009044E4B2F6B2082E85F82460DBD1FFF787 +:100E800035FF0028D7D108E02B6A03EB82038342A9 +:100E9000CFD0FFF72BFF0028CBD10020BDE8F8838F +:100EA0000120FBE788230020024B1A78024B1A70BE +:100EB000704700BFC823002010220020F8B5194C4D +:100EC000194800F079FC2146174800F0A1FC24687D +:100ED0001648D4F89020164ED2F80438154D43F039 +:100EE0000203114FC2F8043801F064F92046124998 +:100EF00000F09CFDD4F890200424D2F8043823F0AC +:100F00000203C2F804384FF4E133336055F8040BA0 +:100F1000B84202D0314600F0ADFB013C14F0FF04B2 +:100F2000F4D1F8BD70420008C832002040420F00E2 +:100F3000B0230020584100087842000838B50B4B18 +:100F400004461A780A4B53F822500A4B9D420CD0A3 +:100F5000094B002118221846FFF75AFF046001468A +:100F60002846BDE8384000F085BB38BDC8230020C6 +:100F700058410008C8320020B023002000B59BB0C3 +:100F8000EFF3098168226846FFF71CFFEFF3058342 +:100F9000044B9A6BDA6A9A6A9A6A9A6A9A6A9A6AA5 +:100FA0009B6AFEE700ED00E000B59BB0EFF309811E +:100FB00068226846FFF706FFEFF30583044B9A6B40 +:100FC0009A6A9A6A9A6A9A6A9A6A9B6AFEE700BF64 +:100FD00000ED00E000B59BB0EFF3098168226846A0 +:100FE000FFF7F0FEEFF30583034B5A6B9A6A9A6A98 +:100FF0009A6A9A6A9B6AFEE700ED00E0FEE700004D +:1010000030B50A44084D91420DD011F8013B5840CB +:10101000082340F30004013B2C4013F0FF0384EA53 +:101020005000F6D1EFE730BD2083B8ED0268436889 +:101030001143016003B1184770470000024A13686A +:1010400043F0C0031360704700440040024A136835 +:1010500043F0C0031360704700480040024A136821 +:1010600043F0C003136070470078004037B5274C49 +:10107000274D204600F0F2FA04F1140000940023FA +:101080004FF40072234900F0B3F94FF40072224983 +:1010900004F138000094214B00F02CFA204BC4E9F5 +:1010A0001735204C204600F0D9FA04F114000094C2 +:1010B00000234FF400721C4900F09AF94FF40072BB +:1010C0001A4904F138000094194B00F013FA194B37 +:1010D000C4E91735184C204600F0C0FA04F114009A +:1010E00000234FF400721549009400F081F9144B6D +:1010F0004FF40072134904F13800009400F0FAF93B +:10110000114BC4E9173503B030BD00BFCC2300201C +:1011100000E1F50510250020102B00203D100008EF +:10112000004400403824002010270020102D00200B +:101130004D10000800480040A42400201029002081 +:101140005D100008102F002000780040037C30B5AF +:10115000334C002918BF0C46012B18D1314B984253 +:101160000FD1314BD3F8E82042F40032C3F8E82025 +:10117000D3F8102142F40032C3F81021D3F8103113 +:1011800005E02A4B98422FD0294B984238D022684C +:10119000036EC16D03EB52038466B3FBF2F3626826 +:1011A000150442BF23F0070503F0070343EA450394 +:1011B000CB60A36843F040034B60E36843F0010356 +:1011C0008B6042F4967343F001030B604FF0FF33E2 +:1011D0000B62510505D512F010221DD0B2F1805FCF +:1011E0001CD080F8643030BD0F4BD3F8E82042F4B7 +:1011F0008022C3F8E820D3F8102142F48022BBE714 +:10120000094BD3F8E82042F08042C3F8E820D3F835 +:10121000102142F08042AFE77F23E2E73F23E0E77F +:1012200068410008CC2300200044025838240020E4 +:10123000A42400202DE9F047C66D05463768F469FF +:101240002107346219D014F0080118BF8021E20789 +:1012500048BF41F02001A3074FF0200348BF41F0F1 +:101260004001600748BF41F4807183F31188281D55 +:10127000FFF7DCFE002383F31188E2050AD5202363 +:1012800083F311884FF40071281DFFF7CFFE002370 +:1012900083F311884FF020094FF0000A14F0200862 +:1012A00038D13B0616D54FF0200905F1380A200643 +:1012B00010D589F31188504600F050F9002836DA2D +:1012C0000821281DFFF7B2FE27F0800333600023BA +:1012D00083F31188790614D5620612D5202383F38F +:1012E0001188D5E913239A4208D12B6C33B127F02A +:1012F00040071021281DFFF799FE3760002383F374 +:101300001188E30618D5AA6E1369ABB15069BDE820 +:10131000F047184789F31188736A284695F86410D6 +:10132000194000F0B5F98AF31188F469B6E7B062A4 +:1013300088F31188F469BAE7BDE8F087F8B5154677 +:10134000826804460B46AA4200D28568A1692669D4 +:10135000761AB5420BD218462A46FFF733FDA36929 +:101360002B44A3612846A3685B1BA360F8BD0CD97E +:10137000AF1B18463246FFF725FD3A46E168304478 +:10138000FFF720FDE3683B44EBE718462A46FFF7EA +:1013900019FDE368E5E7000083689342F7B504466A +:1013A000154600D28568D4E90460361AB5420BD2DE +:1013B0002A46FFF707FD63692B4463612846A3684B +:1013C0005B1BA36003B0F0BD0DD93246AF1B01918A +:1013D000FFF7F8FC01993A46E0683144FFF7F2FC68 +:1013E000E3683B44E9E72A46FFF7ECFCE368E4E7FF +:1013F00010B50A440024C361029B8460C16002618D +:101400000362C0E90000C0E9051110BD08B5D0E9CC +:101410000532934201D1826882B9826801328260CA +:101420005A1C426119700021D0E904329A4224BF4B +:10143000C368436100F0DAFE002008BD4FF0FF30C2 +:10144000FBE7000070B5202304460E4683F31188A5 +:10145000A568A5B1A368A269013BA360531CA36161 +:1014600015782269934224BFE368A361E3690BB155 +:1014700020469847002383F31188284607E0314629 +:10148000204600F0A3FE0028E2DA85F3118870BD43 +:101490002DE9F74F04460E4617469846D0F81C90A3 +:1014A0004FF0200A8AF311884FF0000B154665B102 +:1014B0002A4631462046FFF741FF034660B94146C0 +:1014C000204600F083FE0028F1D0002383F311882A +:1014D000781B03B0BDE8F08FB9F1000F03D0019085 +:1014E0002046C847019B8BF31188ED1A1E448AF3EE +:1014F0001188DCE7C160C361009B82600362C0E9C0 +:1015000005111144C0E9000001617047F8B50446B7 +:101510000D461646202383F31188A768A7B1A36858 +:10152000013BA36063695A1C62611D70D4E90432F7 +:101530009A4224BFE3686361E3690BB12046984790 +:10154000002080F3118807E03146204600F03EFE7F +:101550000028E2DA87F31188F8BD0000D0E90523FE +:1015600010B59A4201D182687AB9826800210132AD +:1015700082605A1C82611C7803699A4224BFC36846 +:10158000836100F033FE204610BD4FF0FF30FBE7D3 +:101590002DE9F74F04460E4617469846D0F81C90A2 +:1015A0004FF0200A8AF311884FF0000B154665B101 +:1015B0002A4631462046FFF7EFFE034660B9414612 +:1015C000204600F003FE0028F1D0002383F31188A9 +:1015D000781B03B0BDE8F08FB9F1000F03D0019084 +:1015E0002046C847019B8BF31188ED1A1E448AF3ED +:1015F0001188DCE7026843681143016003B11847B2 +:10160000704700001430FFF743BF00004FF0FF3376 +:101610001430FFF73DBF00003830FFF7B9BF0000BE +:101620004FF0FF333830FFF7B3BF00001430FFF73F +:1016300009BF00004FF0FF311430FFF703BF000077 +:101640003830FFF763BF00004FF0FF323830FFF74C +:101650005DBF000000207047FFF708BD044B03602A +:1016600000234360C0E9023301230374704700BFC5 +:101670008041000810B52023044683F31188FFF74A +:1016800065FD02232374002383F3118810BD00003D +:1016900038B5C36904460D461BB904210844FFF759 +:1016A000A9FF294604F11400FFF7B0FE002806DA6E +:1016B000201D4FF48061BDE83840FFF79BBF38BD67 +:1016C000026843681143016003B118477047000086 +:1016D00013B5406B00F58054D4F8A4381A6811781B +:1016E000042914D1017C022911D11979012312890D +:1016F0008B4013420BD101A94C3002F06DF8D4F8A5 +:10170000A4480246019B2179206800F0DFF902B06D +:1017100010BD0000143001F0EFBF00004FF0FF33A8 +:10172000143001F0E9BF00004C3002F0C1B80000F5 +:101730004FF0FF334C3002F0BBB80000143001F022 +:10174000BDBF00004FF0FF31143001F0B7BF000003 +:101750004C3002F08DB800004FF0FF324C3002F0F8 +:1017600087B800000020704710B500F58054D4F809 +:10177000A4381A681178042917D1017C022914D1E0 +:101780005979012352898B4013420ED1143001F054 +:101790004FFF024648B1D4F8A4484FF44073617932 +:1017A0002068BDE8104000F07FB910BD406BFFF726 +:1017B000DBBF0000704700007FB5124B01250426F7 +:1017C000044603600023057400F184024360294647 +:1017D000C0E902330C4B0290143001934FF4407374 +:1017E000009601F001FF094B04F69442294604F1EA +:1017F0004C000294CDE900634FF4407301F0C8FF40 +:1018000004B070BDA8410008AD170008D11600084B +:101810000A68202383F311880B790B3342F82300E5 +:101820004B79133342F823008B7913B10B3342F811 +:10183000230000F58053C3F8A41802230374002387 +:1018400083F311887047000038B5037F044613B155 +:1018500090F85430ABB90125201D0221FFF730FF6D +:1018600004F114006FF00101257700F0CBFC04F1C6 +:101870004C0084F854506FF00101BDE8384000F08E +:10188000C1BC38BD10B5012104460430FFF718FF74 +:101890000023237784F8543010BD000038B5044687 +:1018A0000025143001F0B8FE04F14C00257701F05A +:1018B00087FF201D84F854500121FFF701FF2046C7 +:1018C000BDE83840FFF750BF90F8803003F0600368 +:1018D000202B06D190F881200023212A03D81F2A2B +:1018E00006D800207047222AFBD1C0E91D3303E04F +:1018F000034A426707228267C3670120704700BF1F +:101900002C22002037B500F58055D5F8A4381A6888 +:10191000117804291AD1017C022917D119790123E0 +:1019200012898B40134211D100F14C04204602F081 +:1019300007F858B101A9204601F04EFFD5F8A44898 +:101940000246019B2179206800F0C0F803B030BD49 +:1019500001F10B03F0B550F8236085B004460D4645 +:10196000FEB1202383F3118804EB8507301D082185 +:10197000FFF7A6FEFB6806F14C005B691B681BB114 +:10198000019001F037FF019803A901F025FF0246FD +:1019900048B1039B2946204600F098F8002383F3C2 +:1019A000118805B0F0BDFB685A691268002AF5D0AD +:1019B0001B8A013B1340F1D104F18002EAE70000E9 +:1019C000133138B550F82140ECB1202383F311884E +:1019D00004F58053D3F8A4281368527903EB8203EB +:1019E000DB689B695D6845B104216018FFF768FEFC +:1019F000294604F1140001F025FE2046FFF7B4FE4D +:101A0000002383F3118838BD7047000001F018B936 +:101A100001234022002110B5044600F8303BFFF7B7 +:101A2000F7F90023C4E9013310BD000010B52023ED +:101A3000044683F311882422416000210C30FFF713 +:101A4000E7F9204601F01EF902232370002383F3F7 +:101A5000118810BD70B500EB8103054650690E4634 +:101A60001446DA6018B110220021FFF7D1F9A069FD +:101A700018B110220021FFF7CBF931462846BDE806 +:101A8000704001F011BA000083682022002103F0A9 +:101A9000011310B5044683601030FFF7B9F92046F2 +:101AA000BDE8104001F08CBAF0B4012500EB8104D0 +:101AB00047898D40E4683D43A46945812360002344 +:101AC000A2606360F0BC01F0A9BA0000F0B4012587 +:101AD00000EB810407898D40E4683D43646905811A +:101AE00023600023A2606360F0BC01F01FBB000014 +:101AF00070B5022300250446242203702946C0F84D +:101B000088500C3040F8045CFFF782F9204684F8D6 +:101B1000705001F05DF963681B6823B129462046C7 +:101B2000BDE87040184770BD037880F88C300523FD +:101B3000037043681B6810B504460BB10421984735 +:101B40000023A36010BD000090F88C204368027051 +:101B50001B680BB1052118477047000070B590F85D +:101B60007030044613B1002380F8703004F1800215 +:101B7000204601F049FA63689B68B3B994F8803055 +:101B800013F0600535D00021204601F0F3FC002160 +:101B9000204601F0E3FC63681B6813B10621204670 +:101BA0009847062384F8703070BD20469847002877 +:101BB000E4D0B4F88630A26F9A4288BFA36794F944 +:101BC0008030A56F002B4FF0200380F20381002DA1 +:101BD00000F0F280092284F8702083F3118800213C +:101BE0002046D4E91D23FFF771FF002383F31188FA +:101BF000DAE794F8812003F07F0343EA022340F2FE +:101C00000232934200F0C58021D8B3F5807F48D0DE +:101C10000DD8012B3FD0022B00F09380002BB2D1C6 +:101C200004F1880262670222A267E367C1E7B3F5A5 +:101C3000817F00F09B80B3F5407FA4D194F882307F +:101C4000012BA0D1B4F8883043F0020332E0B3F5A1 +:101C5000006F4DD017D8B3F5A06F31D0A3F5C06396 +:101C6000012B90D86368204694F882205E6894F82F +:101C70008310B4F88430B047002884D04368636789 +:101C80000368A3671AE0B3F5106F36D040F602423E +:101C900093427FF478AF5C4B63670223A367002312 +:101CA000C3E794F88230012B7FF46DAFB4F888302D +:101CB00023F00203A4F88830C4E91D55E56778E7EE +:101CC000B4F88030B3F5A06F0ED194F8823020467E +:101CD00084F88A3001F0DAF863681B6813B10121D7 +:101CE00020469847032323700023C4E91D339CE753 +:101CF00004F18B0363670123C3E72378042B10D11E +:101D0000202383F311882046FFF7BEFE85F3118858 +:101D10000321636884F88B5021701B680BB1204647 +:101D2000984794F88230002BDED084F88B3004235F +:101D3000237063681B68002BD6D002212046984789 +:101D4000D2E794F8843020461D0603F00F010AD52F +:101D500001F04CF9012804D002287FF414AF2B4B7A +:101D60009AE72B4B98E701F033F9F3E794F88230C8 +:101D7000002B7FF408AF94F8843013F00F01B3D038 +:101D80001A06204602D501F00DFCADE701F0FEFB7E +:101D9000AAE794F88230002B7FF4F5AE94F88430F3 +:101DA00013F00F01A0D01B06204602D501F0E2FB84 +:101DB0009AE701F0D3FB97E7142284F8702083F3AD +:101DC00011882B462A4629462046FFF76DFE85F3EB +:101DD0001188E9E65DB1152284F8702083F311883B +:101DE00000212046D4E91D23FFF75EFEFDE60B220D +:101DF00084F8702083F311882B462A462946204612 +:101E0000FFF764FEE3E700BFD8410008D0410008B7 +:101E1000D441000838B590F870300446002B3ED00D +:101E2000063BDAB20F2A34D80F2B32D8DFE803F0A2 +:101E300037313108223231313131313131313737B7 +:101E4000856FB0F886309D4214D2C3681B8AB5FBFB +:101E5000F3F203FB12556DB9202383F311882B464F +:101E60002A462946FFF732FE85F311880A2384F8B3 +:101E700070300EE0142384F87030202383F311882F +:101E8000002320461A461946FFF70EFE002383F36F +:101E9000118838BDC36F03B198470023E7E70021DD +:101EA000204601F067FB0021204601F057FB6368E4 +:101EB0001B6813B10621204698470623D7E7000088 +:101EC00010B590F870300446142B29D017D8062B83 +:101ED00005D001D81BB110BD093B022BFBD8002156 +:101EE000204601F047FB0021204601F037FB6368E4 +:101EF0001B6813B1062120469847062319E0152BCD +:101F0000E9D10B2380F87030202383F3118800235C +:101F10001A461946FFF7DAFD002383F31188DAE742 +:101F2000C3689B695B68002BD5D1C36F03B1984729 +:101F3000002384F87030CEE7024B0022C3E900335F +:101F40009A60704710310020002382680374054BAB +:101F50001B6899689142FBD25A6803604260106026 +:101F6000586070471031002008B5202383F3118892 +:101F7000037C032B05D0042B0DD02BB983F31188E0 +:101F800008BD436900221A604FF0FF334361FFF739 +:101F9000DBFF0023F2E7D0E9003213605A60F3E779 +:101FA000002382680374054B1B6899689142FBD833 +:101FB0005A6803604260106058607047103100201A +:101FC000054B196908741868026853601A60186133 +:101FD00001230374FEF7FAB9103100204B1C30B511 +:101FE000044687B00A4D10D02B6901A8094A00F0B9 +:101FF00025F92046FFF7E4FF049B13B101A800F088 +:1020000059F92B69586907B030BDFFF7D9FFF8E7D8 +:1020100010310020691F000838B50C4D044641619D +:102020002B6981689A68914203D8BDE83840FFF770 +:102030008BBF1846FFF7B4FF01232C6101462374C0 +:102040002046BDE83840FEF7C1B900BF103100207E +:10205000044B1A681B6990689B68984294BF0020E3 +:10206000012070471031002010B5084C236820690A +:102070001A6854602260012223611A74FFF790FFEE +:1020800001462069BDE81040FEF7A0B910310020DC +:1020900008B5FFF7DDFF18B1BDE80840FFF7E4BF62 +:1020A00008BD0000FFF7E0BFFEE7000010B50C4CD4 +:1020B000FFF742FF00F0B4F880220A49204600F002 +:1020C0003BF8012344F8180C037400F097FC00233C +:1020D00083F3118862B60448BDE8104000F04CB8A4 +:1020E00038310020DC410008EC41000800F01CB948 +:1020F000EFF3118020B9EFF30583202282F31188DA +:102100007047000010B530B9EFF30584C4F308043C +:1021100014B180F3118810BDFFF7BAFF84F3118862 +:10212000F9E70000034A516853685B1A9842FBD8EC +:10213000704700BF001000E08260022202827047F8 +:102140008368A3F17C0243F80C2C026943F83C2C11 +:10215000426943F8382C074A43F81C2CC268A3F1A3 +:10216000180043F8102C022203F8082C002203F870 +:10217000072C7047E503000810B5202383F311886E +:10218000FFF7DEFF00210446FFF746FF002383F33D +:102190001188204610BD0000024B1B6958610F20BA +:1021A000FFF70EBF10310020202383F31188FFF7C3 +:1021B000F3BF000008B50146202383F311880820EF +:1021C000FFF70CFF002383F3118808BD49B1064BCC +:1021D00042681B6918605A60136043600420FFF76F +:1021E000FDBE4FF0FF307047103100200368984269 +:1021F00006D01A680260506018465961FFF7A4BE05 +:102200007047000038B504460D462068844200D16E +:1022100038BD036823605C604561FFF795FEF4E715 +:10222000054B4FF0FF3103F11402C3E905220022F0 +:10223000C3E90712704700BF1031002070B51C4E73 +:1022400005460C46C0E9032301F0B0FB334653F8C2 +:10225000142F9A420DD130620A2C2CBF00190A307B +:102260002A60C5E90124C6E90555BDE8704001F0C2 +:1022700087BB316A431AE31838BF1C469368A342F0 +:1022800002D9081901F08CFB73699A6894420CD842 +:102290005A68AC602B606A6015609A685D60121BBA +:1022A0009A604FF0FF33F36170BDA41A1B68ECE72E +:1022B0001031002038B51B4C636998420DD08168FD +:1022C000D0E9003213605A600022C2609A680A4462 +:1022D0009A604FF0FF33E36138BD03682246002166 +:1022E00042F8143F93425A60C16003D1BDE83840C0 +:1022F00001F050BB9A688168256A0A449A6001F02F +:1023000055FB6369411B9A688A42E5D9AB181D1ACF +:10231000206A092D98BF01F10A02BDE83840104437 +:1023200001F03EBB103100202DE9F041184C002790 +:1023300004F11406656901F039FB236AAA68C11A21 +:102340008A4215D81344D5F80C802362D5E90032AF +:1023500013605A606369EF60B34201D101F01AFB68 +:1023600087F311882869C047202383F31188E1E7A8 +:102370006169B14209D013441B1ABDE8F0410A2B30 +:102380002CBFC0180A3001F00BBBBDE8F08100BFC4 +:102390001031002000207047FEE700007047000069 +:1023A0004FF0FF307047000002290CD0032904D001 +:1023B0000129074818BF00207047032A05D805489F +:1023C00000EBC2007047044870470020704700BF10 +:1023D000D44200083C2200208842000870B59AB020 +:1023E00005460846144601A900F0C2F801A8FEF708 +:1023F00007FD431C0022C6B25B001046C5E900344D +:1024000023700323023404F8013C01ABD1B202343F +:102410008E4201D81AB070BD13F8011B013204F8C6 +:10242000010C04F8021CF1E708B5202383F311889E +:102430000348FFF767FA002383F3118808BD00BF44 +:10244000C832002090F8803003F01F02012A07D123 +:1024500090F881200B2A03D10023C0E91D3315E039 +:1024600003F06003202B08D1B0F884302BB990F82A +:102470008120212A03D81F2A04D8FFF725BA222A4F +:10248000EBD0FAE7034A426707228267C36701205D +:10249000704700BF3322002007B5052917D8DFE8B1 +:1024A00001F0191603191920202383F31188104A0B +:1024B00001210190FFF7CEFA019802210D4AFFF7A2 +:1024C000C9FA0D48FFF7EAF9002383F3118803B036 +:1024D0005DF804FB202383F311880748FFF7B4F964 +:1024E000F2E7202383F311880348FFF7CBF9EBE7EA +:1024F000284200084C420008C832002038B50C4D74 +:102500000C4C2A460C4904F10800FFF767FF05F15F +:10251000CA0204F110000949FFF760FF05F5CA720D +:1025200004F118000649BDE83840FFF757BF00BF67 +:10253000A04B00203C220020044200081142000869 +:102540001C42000870B5044608460D46FEF758FCCC +:10255000C6B22046013403780BB9184670BD324626 +:102560002946FEF739FC0028F3D10120F6E70000E8 +:102570002DE9F04705460C46FEF742FC2B49C6B252 +:102580002846FFF7DFFF08B10A36F6B22849284689 +:10259000FFF7D8FF08B11036F6B2632E0BD8DFF87C +:1025A0008C80DFF88C90234FDFF894A02E7846B90A +:1025B0002670BDE8F08729462046BDE8F04701F0C7 +:1025C000B5BD252E2ED1072241462846FEF704FC34 +:1025D00070B9194B224603F1100153F8040B8B42DA +:1025E00042F8040BF9D11B78073511341370DDE77D +:1025F000082249462846FEF7EFFB98B9A21C0F4B6C +:10260000197802320909C95D02F8041C13F8011B8C +:1026100001F00F015345C95D02F8031CF0D11834D5 +:102620000835C3E7013504F8016BBFE7F442000841 +:102630001C4200080E430008FC42000800E8F11F9D +:102640000CE8F11FBFF34F8F044B1A695107FCD1FF +:10265000D3F810215207F8D1704700BF0020005274 +:1026600008B50D4B1B78ABB9FFF7ECFF0B4BDA68E5 +:10267000D10704D50A4A5A6002F188325A60D3F869 +:102680000C21D20706D5064AC3F8042102F188328C +:10269000C3F8042108BD00BFFE4D002000200052F9 +:1026A0002301674508B5114B1B78F3B9104B1A6924 +:1026B000510703D5DA6842F04002DA60D3F81021FE +:1026C000520705D5D3F80C2142F04002C3F80C2183 +:1026D000FFF7B8FF064BDA6842F00102DA60D3F880 +:1026E0000C2142F00102C3F80C2108BDFE4D002070 +:1026F000002000520F289ABF00F58060400400209F +:10270000704700004FF40030704700001020704701 +:102710000F2808B50BD8FFF7EDFF00F5003302686E +:10272000013204D104308342F9D1012008BD0020D8 +:10273000FCE700000F2870B5054645D8FFF7D8FC28 +:10274000224CFFF77FFF0646FFF78AFF4FF0FF336B +:10275000072D6361C4F8143120D82361FFF772FF9D +:102760002B0243F02403E360E36843F08003E3605B +:1027700023695A07FCD42846FFF764FF4FF4003161 +:10278000FFF7B8FF00F002F93046FFF78BFFFFF7C5 +:10279000B9FC2846BDE87040FFF7BABFC4F8103155 +:1027A000FFF750FFA5F108031B0243F02403C4F810 +:1027B0000C31D4F80C3143F08003C4F80C31D4F858 +:1027C00010315B07FBD4D6E7002070BD002000521B +:1027D0002DE9F84F40EA020305460C461746D80695 +:1027E00002D00020BDE8F88F27F01F07DFF8D4B033 +:1027F000FFF736FF2744BC4203D10120FFF752FF09 +:10280000F0E720222946204601F080FC10B920354F +:102810002034F0E72B4605F120021E68711CE0D140 +:1028200004339A42F9D1FFF763FC05F17843234A58 +:10283000B3F5801F224B28BF9A4603F1040338BF2B +:102840009046A2F1080228BF9846A3F108033ABFB8 +:102850009146DA469946FFF7F5FEC8F80060A5EB09 +:10286000040CD9F8002004F11C0142F00202C9F85E +:102870000020221FDAF8006016F00506FAD152F89F +:10288000043F8A424CF80230F4D1BFF34F8FFFF778 +:10289000D9FE4FF0FF32C8F80020D9F8002022F00E +:1028A0000202C9F80020FFF72DFC2022214628460D +:1028B00001F02CFC0028AAD030469FE714200052DB +:1028C000102100521020005210B5084C237828B176 +:1028D0001BB9FFF7C5FE0123237010BD002BFCD0F0 +:1028E0002070BDE81040FFF7DDBE00BFFE4D0020A8 +:1028F0000244074BD2B210B5904200D110BD441C27 +:1029000000B253F8200041F8040BE0B2F4E700BF36 +:10291000504000580E4B30B51C6F240405D41C6F7A +:102920001C671C6F44F400441C670A4C0244236873 +:10293000D2B243F480732360074B904200D130BD84 +:10294000441C51F8045B00B243F82050E0B2F4E7B5 +:1029500000440258004802585040005807B5012270 +:1029600001A90020FFF7C4FF019803B05DF804FB44 +:1029700013B50446FFF7F2FFA04205D0012201A9DA +:1029800000200194FFF7C6FF02B010BD0144BFF361 +:102990004F8F064B884204D3BFF34F8FBFF36F8F27 +:1029A0007047C3F85C022030F4E700BF00ED00E0A0 +:1029B000034B1A681AB9034AD2F8D0241A60704738 +:1029C000004E00200040025808B5FFF7F1FF024B0F +:1029D0001868C0F3806008BD004E0020EFF3098343 +:1029E000054968334A6B22F001024A6383F3098880 +:1029F000002383F31188704700EF00E0202080F36C +:102A0000118862B60D4B0E4AD96821F4E0610904C1 +:102A1000090C0A430B49DA60D3F8FC2042F08072BB +:102A2000C3F8FC20084AC2F8B01F116841F0010148 +:102A300011601022DA7783F82200704700ED00E081 +:102A40000003FA0555CEACC5001000E0202310B5F8 +:102A500083F311880E4B5B6813F4006314D0F1EE1E +:102A6000103AEFF309844FF08073683CE361094B3F +:102A7000DB6B236684F30988FFF7EAFA10B1064B93 +:102A8000A36110BD054BFBE783F31188F9E700BF95 +:102A900000ED00E000EF00E0F7030008FA03000893 +:102AA00070B5BFF34F8FBFF36F8F1A4A0021C2F882 +:102AB0005012BFF34F8FBFF36F8F536943F400334E +:102AC0005361BFF34F8FBFF36F8FC2F88410BFF312 +:102AD0004F8FD2F8803043F6E074C3F3C900C3F3DC +:102AE0004E335B0103EA0406014646EA817501396B +:102AF000C2F86052F9D2203B13F1200FF2D1BFF39C +:102B00004F8F536943F480335361BFF34F8FBFF34B +:102B10006F8F70BD00ED00E0FEE700000A4B0B4830 +:102B20000B4A90420BD30B4BC11EDA1C121A22F037 +:102B300003028B4238BF00220021FEF769B953F827 +:102B4000041B40F8041BECE7EC440008D44F0020C1 +:102B5000D44F0020D44F00207047000070B5D0E95A +:102B6000244300224FF0FF359E6804EB42135101CD +:102B7000D3F80009002805DAD3F8000940F08040B6 +:102B8000C3F80009D3F8000B002805DAD3F8000BCE +:102B900040F08040C3F8000B013263189642C3F83E +:102BA0000859C3F8085BE0D24FF00113C4F81C3891 +:102BB00070BD000000EB8103D3F80CC02DE9F04399 +:102BC000DCF814204E1CD0F89050D2F800E005EB51 +:102BD000063605EB4118506870450AD30122D5F836 +:102BE000343802FA01F123EA0101C5F83418BDE8CE +:102BF000F083AEEB0003BCF81040A34228BF23468D +:102C0000D8F81849A4B2B3EB840FF0D89468A4F1B3 +:102C1000040959F8047F3760A4EB09071F44042F07 +:102C2000F7D81C44034494605360D4E7890141F011 +:102C30002001016103699B06FCD41220FFF772BAE0 +:102C400010B50A4C2046FEF7E3FE094BC4F890305D +:102C5000084BC4F89430084C2046FEF7D9FE074BC9 +:102C6000C4F89030064BC4F8943010BD044E0020D8 +:102C70000000084044430008A04E0020000004402B +:102C80005043000870B503780546012B5DD1494BD0 +:102C9000D0F89040984259D1474B0E216520D3F887 +:102CA000D82042F00062C3F8D820D3F8002142F0C7 +:102CB0000062C3F80021D3F80021D3F8802042F04D +:102CC0000062C3F88020D3F8802022F00062C3F8AD +:102CD0008020D3F8803000F071FC384BE360384B33 +:102CE000C4F800380023D5F89060C4F8003EC02333 +:102CF00023604FF40413A3633369002BFCDA012330 +:102D00000C203361FFF70EFA3369DB07FCD4122085 +:102D1000FFF708FA3369002BFCDA00262846A66084 +:102D2000FFF71CFF6B68C4F81068DB68C4F8146810 +:102D3000C4F81C68002B3AD1224BA3614FF0FF333B +:102D40006361A36843F00103A36070BD1E4B98420A +:102D5000C8D1194B0E214D20D3F8D82042F0007273 +:102D6000C3F8D820D3F8002142F00072C3F8002144 +:102D7000D3F80021D3F8802042F00072C3F88020FD +:102D8000D3F8802022F00072C3F88020D3F880208E +:102D9000D3F8D82022F08062C3F8D820D3F80021DD +:102DA00022F08062C3F80021D3F8003193E7074B8B +:102DB000C3E700BF044E0020004402584014004006 +:102DC00003002002003C30C0A04E0020083C30C070 +:102DD000F8B5D0F89040054600214FF00066204637 +:102DE000FFF724FFD5F8941000234FF001128F68ED +:102DF0004FF0FF30C4F83438C4F81C2804EB4312F9 +:102E000001339F42C2F80069C2F8006BC2F808099A +:102E1000C2F8080BF2D20B68D5F89020C5F89830AC +:102E2000636210231361166916F01006FBD112209D +:102E3000FFF778F9D4F8003823F4FE63C4F80038BB +:102E4000A36943F4402343F01003A3610923C4F8AA +:102E50001038C4F814380B4BEB604FF0C043C4F883 +:102E6000103B094BC4F8003BC4F81069C4F80039A2 +:102E7000D5F8983003F1100243F48013C5F8982078 +:102E8000A362F8BD2043000840800010D0F89020D5 +:102E900090F88A10D2F8003823F4FE6343EA011355 +:102EA000C2F80038704700002DE9F84300EB8103B9 +:102EB000D0F890500C468046DA680FFA81F9480144 +:102EC000166806F00306731E022B05EB41134FF044 +:102ED000000194BFB604384EC3F8101B4FF0010137 +:102EE00004F1100398BF06F1805601FA03F39169CB +:102EF00098BF06F5004600293AD0578A04F15801D8 +:102F0000374349016F50D5F81C180B430021C5F811 +:102F10001C382B180127C3F81019A7405369611EEC +:102F20009BB3138A928B9B08012A88BF5343D8F81E +:102F30009820981842EA034301F140022146C8F85C +:102F40009800284605EB82025360FFF76FFE08EBFE +:102F50008900C3681B8A43EA845348341E436401D2 +:102F60002E51D5F81C381F43C5F81C78BDE8F883EE +:102F700005EB4917D7F8001B21F40041C7F8001BE7 +:102F8000D5F81C1821EA0303C0E704F13F030B4AFC +:102F90002846214605EB83035A60FFF747FE05EB01 +:102FA0004910D0F8003923F40043C0F80039D5F8AF +:102FB0001C3823EA0707D7E700800010000400024E +:102FC000D0F894201268C0F89820FFF7C7BD000021 +:102FD0005831D0F8903049015B5813F4004004D0C8 +:102FE00013F4001F0CBF0220012070474831D0F8B5 +:102FF000903049015B5813F4004004D013F4001FD3 +:103000000CBF02200120704700EB8101CB68196AD8 +:103010000B6813604B6853607047000000EB81033E +:1030200030B5DD68AA691368D36019B9402B84BF35 +:10303000402313606B8A1468D0F890201C4402EB84 +:103040004110013C09B2B4FBF3F46343033323F0B2 +:10305000030343EAC44343F0C043C0F8103B2B686A +:1030600003F00303012B0ED1D2F8083802EB411014 +:1030700013F4807FD0F8003B14BF43F0805343F03B +:103080000053C0F8003B02EB4112D2F8003B43F082 +:103090000443C2F8003B30BD2DE9F041D0F8906008 +:1030A00005460C4606EB4113D3F8087B3A07C3F8F4 +:1030B000087B08D5D6F814381B0704D500EB81032C +:1030C000DB685B689847FA071FD5D6F81438DB072A +:1030D0001BD505EB8403D968CCB98B69488A5A683B +:1030E000B2FBF0F600FB16228AB91868DA68904243 +:1030F0000DD2121AC3E90024202383F3118821463C +:103100002846FFF78BFF84F31188BDE8F081012387 +:1031100003FA04F26B8923EA02036B81CB68002B6C +:10312000F3D021462846BDE8F041184700EB810363 +:103130004A0170B5DD68D0F890306C692668E660A9 +:1031400056BB1A444FF40020C2F810092A6802F056 +:103150000302012A0AB20ED1D3F8080803EB421485 +:1031600010F4807FD4F8000914BF40F0805040F084 +:103170000050C4F8000903EB4212D2F8000940F0F5 +:103180000440C2F800090122D3F8340802FA01F120 +:103190000143C3F8341870BD19B9402E84BF4020D4 +:1031A000206020681A442E8A8419013CB4FBF6F48E +:1031B00040EAC44040F00050C6E700002DE9F0416D +:1031C000D0F8906004460D4606EB4113D3F8087919 +:1031D000C3F80879FB071CD5D6F81038DA0718D5DC +:1031E00000EB8103D3F80CC0DCF81430D3F800E016 +:1031F000DA6896451BD2A2EB0E024FF000081A6067 +:10320000C3F80480202383F31188FFF78FFF88F32E +:1032100011883B0618D50123D6F83428AB40134259 +:1032200012D029462046BDE8F041FFF7C3BC012378 +:1032300003FA01F2038923EA02030381DCF8083070 +:10324000002BE6D09847E4E7BDE8F0812DE9F84F80 +:10325000D0F8905004466E69AB691E4016F4805851 +:103260006E6103D0BDE8F84FFEF742BC002E12DAC3 +:10327000D5F8003E9F0705D0D5F8003E23F00303A4 +:10328000C5F8003ED5F80438204623F00103C5F800 +:103290000438FEF759FC300505D52046FFF75EFCE3 +:1032A0002046FEF741FCB1040CD5D5F8083813F0E0 +:1032B000060FEB6823F470530CBF43F4105343F430 +:1032C000A053EB60320704D56368DB680BB120467E +:1032D0009847F30200F1BA80B70226D5D4F890904F +:1032E00000274FF0010A09EB4712D2F8003B03F424 +:1032F0004023B3F5802F11D1D2F8003B002B0DDA1B +:1033000062890AFA07F322EA0303638104EB870365 +:10331000DB68DB6813B13946204698470137D4F89B +:103320009430FFB29B689F42DDD9F00619D5D4F8DE +:103330009000026AC2F30A1702F00F0302F4F012BF +:10334000B2F5802F00F0CC80B2F5402F09D104EB0C +:103350008303002200F58050DB681B6A974240F02F +:10336000B2803003D5F8185835D5E90303D50021CC +:103370002046FFF791FEAA0303D501212046FFF75F +:103380008BFE6B0303D502212046FFF785FE2F033A +:1033900003D503212046FFF77FFEE80203D5042171 +:1033A0002046FFF779FEA90203D505212046FFF745 +:1033B00073FE6A0203D506212046FFF76DFE2B023D +:1033C00003D507212046FFF767FEEF0103D508214B +:1033D0002046FFF761FE700340F1A980E90703D59D +:1033E00000212046FFF7EAFEAA0703D50121204667 +:1033F000FFF7E4FE6B0703D502212046FFF7DEFE50 +:103400002F0703D503212046FFF7D8FEEE0603D58C +:1034100004212046FFF7D2FEA80603D50521204649 +:10342000FFF7CCFE690603D506212046FFF7C6FE4E +:103430002A0603D507212046FFF7C0FEEB0576D507 +:1034400020460821BDE8F84FFFF7B8BED4F89090A9 +:1034500000274FF0010AD4F894305FFA87FB9B688D +:103460009B453FF639AF09EB4B13D3F8002902F423 +:103470004022B2F5802F24D1D3F80029002A20DA87 +:10348000D3F8002942F09042C3F80029D3F800296C +:10349000002AFBDB5946D4F89000FFF7C7FB2289CE +:1034A0000AFA0BF322EA0303238104EB8B03DB68A4 +:1034B0009B6813B159462046984759462046FFF766 +:1034C00079FB0137C7E7910701D1D0F80080072ABF +:1034D00002F101029CBF03F8018B4FEA18283DE777 +:1034E00004EB830300F58050DA68D2F818C0DCF8EA +:1034F0000820DCE9001CA1EB0C0C00218F4208D154 +:10350000DB689B699A683A449A605A683A445A6000 +:1035100027E711F0030F01D1D0F800808C4501F1AD +:10352000010184BF02F8018B4FEA1828E6E7BDE8E5 +:10353000F88F000008B50348FFF788FEBDE8084093 +:10354000FFF784BA044E002008B50348FFF77EFE5B +:10355000BDE80840FFF77ABAA04E0020D0F89030BE +:1035600003EB4111D1F8003B43F40013C1F8003BD9 +:1035700070470000D0F8903003EB4111D1F80039CA +:1035800043F40013C1F8003970470000D0F89030C0 +:1035900003EB4111D1F8003B23F40013C1F8003BC9 +:1035A00070470000D0F8903003EB4111D1F800399A +:1035B00023F40013C1F8003970470000090100F13D +:1035C0006043012203F56143C9B283F8001300F0A0 +:1035D0001F039A4043099B0003F1604303F56143D5 +:1035E000C3F880211A60704730B50433039C017220 +:1035F000002104FB0325C160C0E90653049B03635B +:10360000059BC0E90000C0E90422C0E90842C0E906 +:103610000A11436330BD00000022416AC260C0E964 +:103620000411C0E90A226FF00101FEF7EBBD0000B2 +:10363000D0E90432934201D1C2680AB9181D70471B +:1036400000207047036919600021C2680132C2601E +:10365000C269134482699342036124BF436A0361D0 +:10366000FEF7C4BD38B504460D46E3683BB1626958 +:103670000020131D1268A3621344E36207E0237A5B +:1036800033B929462046FEF7A1FD0028EDDA38BD02 +:103690006FF00100FBE70000C368C269013BC36033 +:1036A0004369134482699342436124BF436A43617F +:1036B00000238362036B03B11847704770B5202362 +:1036C000044683F31188866A3EB9FFF7CBFF0546AF +:1036D00018B186F31188284670BDA36AE26A13F810 +:1036E000015B9342A36202D32046FFF7D5FF00237C +:1036F00083F31188EFE700002DE9F84F04460E46EA +:10370000174698464FF0200989F311880025AA46EC +:10371000D4F828B0BBF1000F09D141462046FFF78D +:10372000A1FF20B18BF311882846BDE8F88FD4E9BA +:103730000A12A7EB050B521A934528BF9346BBF11B +:10374000400F1BD9334601F1400251F8040B91425E +:1037500043F8040BF9D1A36A403640354033A362E5 +:10376000D4E90A239A4202D32046FFF795FF8AF351 +:103770001188BD42D8D289F31188C9E730465A462C +:10378000FDF720FBA36A5E445D445B44A362E7E768 +:1037900010B5029C0433017204FB0321C460C0E92C +:1037A00006130023C0E90A33039B0363049BC0E9AB +:1037B0000000C0E90422C0E90842436310BD0000D4 +:1037C000026A6FF00101C260426AC0E9042200226D +:1037D000C0E90A22FEF716BDD0E904239A4201D1BE +:1037E000C26822B9184650F8043B0B6070470020AD +:1037F00070470000C3680021C2690133C360436998 +:10380000134482699342436124BF436A4361FEF7D4 +:10381000EDBC000038B504460D46E3683BB12369B2 +:1038200000201A1DA262E2691344E36207E0237AD2 +:1038300033B929462046FEF7C9FC0028EDDA38BD29 +:103840006FF00100FBE7000003691960C268013AEC +:10385000C260C269134482699342036124BF436A10 +:10386000036100238362036B03B1184770470000B4 +:1038700070B520230D460446114683F31188866AED +:103880002EB9FFF7C7FF10B186F3118870BDA36A88 +:103890001D70A36AE26A01339342A36204D3E16913 +:1038A00020460439FFF7D0FF002080F31188EDE7B0 +:1038B0002DE9F84F04460D46904699464FF0200AF0 +:1038C0008AF311880026B346A76A4FB949462046B5 +:1038D000FFF7A0FF20B187F311883046BDE8F88FCD +:1038E000D4E90A073A1AA8EB0607974228BF1746F9 +:1038F000402F1BD905F1400355F8042B9D4240F899 +:10390000042BF9D1A36A40364033A362D4E90A23D9 +:103910009A4204D3E16920460439FFF795FF8BF3FF +:1039200011884645D9D28AF31188CDE729463A460F +:10393000FDF748FAA36A3D443E443B44A362E5E7F1 +:10394000D0E904239A4217D1C3689BB1836A8BB133 +:10395000043B9B1A0ED01360C368013BC360C3696C +:103960001A4483699A42026124BF436A03610023B7 +:1039700083620123184670470023FBE700F0DAB8A2 +:10398000034B002258631A610222DA60704700BFBD +:10399000000C0040014B0022DA607047000C004030 +:1039A000014B5863704700BF000C0040014B586A40 +:1039B000704700BF000C00404B6843608B68836019 +:1039C000CB68C3600B6943614B6903628B694362D7 +:1039D0000B6803607047000008B53C4B40F2FF7174 +:1039E0003B48D3F888200A43C3F88820D3F88820BE +:1039F00022F4FF6222F00702C3F88820D3F888205F +:103A0000D3F8E0200A43C3F8E020D3F808210A43A2 +:103A1000C3F808212F4AD3F808311146FFF7CCFF2D +:103A200000F5806002F11C01FFF7C6FF00F5806021 +:103A300002F13801FFF7C0FF00F5806002F1540188 +:103A4000FFF7BAFF00F5806002F17001FFF7B4FFE5 +:103A500000F5806002F18C01FFF7AEFF00F5806099 +:103A600002F1A801FFF7A8FF00F5806002F1C40190 +:103A7000FFF7A2FF00F5806002F1E001FFF79CFF75 +:103A800000F5806002F1FC01FFF796FF02F58C71F2 +:103A900000F58060FFF790FF00F000F90E4BD3F8BF +:103AA000902242F00102C3F89022D3F8942242F00F +:103AB0000102C3F894220522C3F898204FF0605207 +:103AC000C3F89C20054AC3F8A02008BD0044025852 +:103AD000000002585C43000800ED00E01F000803EE +:103AE00008B500F0F3FAFEF7E1FA0F4BD3F8DC204B +:103AF00042F04002C3F8DC20D3F8042122F0400257 +:103B0000C3F80421D3F80431084B1A6842F00802C4 +:103B10001A601A6842F004021A60FEF749FFBDE815 +:103B20000840FEF7EBBC00BF0044025800180248F2 +:103B300070470000114BD3F8E82042F00802C3F8A8 +:103B4000E820D3F8102142F00802C3F810210C4AF3 +:103B5000D3F81031D36B43F00803D363C722094B6A +:103B60009A624FF0FF32DA6200229A615A63DA6099 +:103B70005A6001225A611A60704700BF004402581F +:103B80000010005C000C0040094A08B51169D368B8 +:103B90000B40D9B29B076FEA0101116107D52023C1 +:103BA00083F31188FEF7A2FA002383F3118808BD7E +:103BB000000C0040384B4FF0FF31D3F88020C3F8A1 +:103BC0008010D3F880200022C3F88020D3F8800032 +:103BD000D3F88400C3F88410D3F88400C3F8842099 +:103BE000D3F88400D86F40F0FF4040F4FF0040F469 +:103BF0003F5040F03F00D867D86F20F0FF4020F4DE +:103C0000FF0020F43F5020F03F00D867D86FD3F872 +:103C100088006FEA40506FEA5050C3F88800D3F82C +:103C20008800C0F30A00C3F88800D3F88800D3F8EE +:103C30009000C3F89010D3F89000C3F89020D3F808 +:103C40009000D3F89400C3F89410D3F89400C3F80C +:103C50009420D3F89400D3F89800C3F89810D3F8C0 +:103C60009800C3F89820D3F89800D3F88C00C3F8D4 +:103C70008C10D3F88C00C3F88C20D3F88C00D3F8C8 +:103C80009C00C3F89C10D3F89C10C3F89C20D3F878 +:103C90009C3000F0E7B900BF00440258614B01229C +:103CA000C3F80821604BD3F8F42042F00202C3F8B5 +:103CB000F420D3F81C2142F00202C3F81C21022296 +:103CC000D3F81C31594BDA605A689104FCD5584A34 +:103CD0001A6001229A60574ADA6000221A614FF492 +:103CE00040429A61514B9A699204FCD51A6842F499 +:103CF00080721A604C4B1A6F12F4407F04D04FF45C +:103D000080321A6700221A671A6842F001021A60AC +:103D1000454B1A685007FCD500221A611A6912F047 +:103D20003802FBD1012119604FF0804159605A6778 +:103D3000414ADA62414A1A611A6842F480321A60D2 +:103D4000394B1A689103FCD51A6842F480521A6004 +:103D50001A689204FCD53A4A3A499A6200225A6398 +:103D600019633949DA6399635A64384A1A64384ADC +:103D7000DA621A6842F0A8521A602B4B1A6802F0F5 +:103D80002852B2F1285FF9D148229A614FF4886233 +:103D9000DA6140221A622F4ADA644FF080521A65C3 +:103DA0002D4A5A652D4A9A6532232D4A13601368AD +:103DB00003F00F03022BFAD11B4B1A6942F00302E6 +:103DC0001A611A6902F03802182AFAD1D3F8DC20F5 +:103DD00042F00052C3F8DC20D3F8042142F0005234 +:103DE000C3F80421D3F80421D3F8DC2042F0804248 +:103DF000C3F8DC20D3F8042142F08042C3F8042148 +:103E0000D3F80421D3F8DC2042F00042C3F8DC20D0 +:103E1000D3F8042142F00042C3F80421D3F804315E +:103E2000704700BF0080005100440258004802580B +:103E300000C000F0020000010000FF0100889008AF +:103E400032206000630209011D02040047040508D6 +:103E5000FD0BFF01200000200010E0000001010028 +:103E6000002000524FF0B04208B5D2F8883003F07D +:103E70000103C2F8883023B1044A13680BB15068BB +:103E80009847BDE80840FEF7E1BD00BF544F002051 +:103E90004FF0B04208B5D2F8883003F00203C2F800 +:103EA000883023B1044A93680BB1D0689847BDE8C5 +:103EB0000840FEF7CBBD00BF544F00204FF0B0428A +:103EC00008B5D2F8883003F00403C2F8883023B173 +:103ED000044A13690BB150699847BDE80840FEF7E2 +:103EE000B5BD00BF544F00204FF0B04208B5D2F826 +:103EF000883003F00803C2F8883023B1044A93697C +:103F00000BB1D0699847BDE80840FEF79FBD00BFE0 +:103F1000544F00204FF0B04208B5D2F8883003F07B +:103F20001003C2F8883023B1044A136A0BB1506AF7 +:103F30009847BDE80840FEF789BD00BF544F0020F8 +:103F40004FF0B04310B5D3F8884004F47872C3F84A +:103F50008820A30604D5124A936A0BB1D06A984709 +:103F6000600604D50E4A136B0BB1506B98472106BF +:103F700004D50B4A936B0BB1D06B9847E20504D57F +:103F8000074A136C0BB1506C9847A30504D5044A3B +:103F9000936C0BB1D06C9847BDE81040FEF756BD4E +:103FA000544F00204FF0B04310B5D3F8884004F4CC +:103FB0007C42C3F88820620504D5164A136D0BB104 +:103FC000506D9847230504D5124A936D0BB1D06DFF +:103FD0009847E00404D50F4A136E0BB1506E984712 +:103FE000A10404D50B4A936E0BB1D06E98476204BE +:103FF00004D5084A136F0BB1506F9847230404D5BA +:10400000044A936F0BB1D06F9847BDE81040FEF79C +:104010001DBD00BF544F002008B50348FDF70AF945 +:10402000BDE80840FEF712BDCC23002008B50348C8 +:10403000FDF700F9BDE80840FEF708BD3824002070 +:1040400008B50348FDF7F6F8BDE80840FEF7FEBCEA +:10405000A424002008B5FFF797FDBDE80840FEF74F +:10406000F5BC0000062108B50846FFF7A7FA0621AF +:104070000720FFF7A3FA06210820FFF79FFA062181 +:104080000920FFF79BFA06210A20FFF797FA06217D +:104090001720FFF793FA06212820FFF78FFA09214E +:1040A0007A20FFF78BFA07213220FFF787FA0C21DD +:1040B0002620FFF783FA0C212720FFF77FFA0C2137 +:1040C0005220BDE80840FFF779BA000008B5FFF7B5 +:1040D00071FD00F00DF8FDF7BFFAFDF797FCFDF755 +:1040E00069FBFFF725FDBDE80840FFF747BC00006E +:1040F0000023054A19460133102BC2E9001102F1D1 +:104100000802F8D1704700BF544F002010B50139A4 +:104110000244904201D1002005E0037811F8014FDC +:10412000A34201D0181B10BD0130F2E7034611F87D +:10413000012B03F8012B002AF9D1704753544D335A +:104140003248373F3F3F0053544D333248373433C2 +:104150002F37353300000000C8320020CC23002068 +:1041600038240020A4240020009600000000000055 +:10417000000000000000000000000000000000003F +:1041800000000000211600080D160008491600085E +:1041900035160008411600082D16000819160008EB +:1041A0000516000855160008000000003117000829 +:1041B0001D17000859170008451700085117000877 +:1041C0003D17000829170008151700086517000893 +:1041D0000000000001000000000000006D61696E39 +:1041E0000000000069646C6500000000E441000804 +:1041F00050310020C832002001000000A920000832 +:10420000000000004865782F50726F6669434E4386 +:104210000025424F415244252D424C002553455222 +:1042200049414C2500000000020000000000000091 +:1042300051190008C119000840004000704B0020CF +:10424000804B00200200000000000000030000007E +:1042500000000000091A0008000000001000000023 +:10426000904B002000000000010000000000000052 +:10427000044E00200101020099240008A92300082F +:10428000452400082924000843000000904200084B +:1042900009024300020100C03209040000010202C9 +:1042A000010005240010010524010001042402027C +:1042B0000524060001070582030800FF0904010028 +:1042C000020A000000070501024000000705810204 +:1042D0004000000012000000DC4200081201100142 +:1042E00002000040AE2D1610000201020301000082 +:1042F0000403090425424F41524425004375626579 +:104300004F72616E67652D626473686F740030313F +:10431000323334353637383941424344454600005C +:10432000000000005D1B0008151E0008C11E0008EB +:10433000400040003C4F00203C4F002001000000A6 +:104340004C4F0020800000004001000008000000E9 +:104350000001000000040000080000000000812AA5 +:1043600000000000AAAAAAAA00000024FFFE000084 +:104370000000000000A00A00000100000000000092 +:10438000AAAAAAAA00000000FFFF00000000000087 +:10439000000000001400005400000000AAAAAAAA0D +:1043A00014000054FFFF00000000000000000000A7 +:1043B00000681A0000000000AAAA8AAA005415008A +:1043C000FFFF00000000700777000000408102003E +:1043D00000000000AAAAAAAA00410100F7FF0000FD +:1043E0000000007007000000000000000000000056 +:1043F000AAAAAAAA00000000FFFF00000000000017 +:10440000000000000000000000000000AAAAAAAA04 +:1044100000000000FFFF000000000000000000009E +:104420000000000000000000AAAAAAAA00000000E4 +:10443000FFFF00000000000000000000000000007E +:1044400000000000AAAAAAAA00000000FFFF0000C6 +:10445000000000000000000000000000000000005C +:10446000AAAAAAAA00000000FFFF000000000000A6 +:10447000000000000000000000000000AAAAAAAA94 +:1044800000000000FFFF000000000000000000002E +:104490008C0000000000000000001E000000000072 +:1044A000FF000000000000003C4100083F00000049 +:1044B00050040000474100083F0000000096000043 +:1044C0000000080096000000000800000400000042 +:1044D000F0420008000000000000000000000000A2 +:0C44E000000000000000000000000000D0 +:00000001FF diff --git a/Tools/bootloaders/CubeOrange-joey_bl.bin b/Tools/bootloaders/CubeOrange-joey_bl.bin old mode 100644 new mode 100755 index a582ef1fb89..3270f22c878 Binary files a/Tools/bootloaders/CubeOrange-joey_bl.bin and b/Tools/bootloaders/CubeOrange-joey_bl.bin differ diff --git a/Tools/bootloaders/CubeOrange-joey_bl.hex b/Tools/bootloaders/CubeOrange-joey_bl.hex new file mode 100644 index 00000000000..6ad3df3385e --- /dev/null +++ b/Tools/bootloaders/CubeOrange-joey_bl.hex @@ -0,0 +1,1105 @@ +:020000040800F2 +:1000000000060020A1020008FD0F00087D0F000877 +:10001000D50F00087D0F0008A90F0008A3020008F3 +:10002000A3020008A3020008A3020008E1290008B7 +:10003000A3020008A3020008A3020008A30200080C +:10004000A3020008A3020008A3020008A3020008FC +:10005000A3020008A3020008693E0008953E0008BC +:10006000C13E0008ED3E0008193F0008A302000849 +:10007000A3020008A3020008A3020008A3020008CC +:10008000A3020008A3020008A3020008A3020008BC +:10009000A3020008A3020008A3020008453F0008CD +:1000A000A3020008A3020008A3020008A30200089C +:1000B000A3020008A3020008A3020008A30200088C +:1000C000A3020008A3020008A3020008A30200087C +:1000D000A3020008A30200081D40000831400008E8 +:1000E000A93F0008A3020008A3020008A302000819 +:1000F000A3020008A3020008A3020008A30200084C +:10010000A3020008A302000859400008A302000847 +:10011000A3020008A3020008A3020008A30200082B +:10012000A3020008A3020008A3020008A30200081B +:10013000A3020008A3020008A3020008A30200080B +:10014000A3020008A3020008A3020008A3020008FB +:10015000A3020008A3020008A3020008A3020008EB +:10016000A3020008A3020008A3020008A3020008DB +:10017000A30200084D350008A3020008A3020008EE +:10018000A3020008A302000845400008A3020008DB +:10019000A3020008A3020008A3020008A3020008AB +:1001A000A3020008A3020008A3020008A30200089B +:1001B000A3020008A3020008A3020008A30200088B +:1001C000A3020008A3020008A3020008A30200087B +:1001D000A302000839350008A3020008A3020008A2 +:1001E000A3020008A3020008A3020008A30200085B +:1001F000A3020008A3020008A3020008A30200084B +:10020000A3020008A3020008A3020008A30200083A +:10021000A3020008A3020008A3020008A30200082A +:10022000A3020008A3020008A3020008A30200081A +:10023000A3020008A3020008A3020008A30200080A +:10024000A3020008A3020008A3020008A3020008FA +:10025000A3020008A3020008A3020008A3020008EA +:10026000A3020008A3020008A3020008A3020008DA +:10027000A3020008A3020008A3020008A3020008CA +:10028000A3020008A3020008A3020008A3020008BA +:10029000A3020008A3020008A3020008A3020008AA +:1002A00002E000F000F8FEE772B63A4880F30888F2 +:1002B000394880F3098839484EF60851CEF20001DA +:1002C000086040F20000CCF200004EF63471CEF22D +:1002D00000010860BFF34F8FBFF36F8F40F2000043 +:1002E000C0F2F0004EF68851CEF200010860BFF374 +:1002F0004F8FBFF36F8F4FF00000E1EE100A4EF604 +:100300003C71CEF200010860062080F31488BFF330 +:100310006F8F02F023FC02F0C5FB03F05FFB4FF090 +:1003200055301F491B4A91423CBF41F8040BFAE784 +:100330001C49194A91423CBF41F8040BFAE71A499B +:100340001A4A1B4B9A423EBF51F8040B42F8040B69 +:10035000F8E700201749184A91423CBF41F8040BC6 +:10036000FAE702F0DDFB03F0BDFB144C144DAC4288 +:1003700003DA54F8041B8847F9E700F041F8114C00 +:10038000114DAC4203DA54F8041B8847F9E702F038 +:10039000C5BB00000006002000220020000000086D +:1003A00000000020000600209044000800220020E9 +:1003B0005C22002060220020D44F0020A002000810 +:1003C000A0020008A0020008A00200082DE9F04FDA +:1003D0002DED108AC1F80CD0D0F80CD0BDEC108AED +:1003E000BDE8F08F002383F311882846A047002042 +:1003F00001F0DAFEFEE701F055FE00DFFEE7000047 +:1004000038B500F0D7FC30B1164B00220E211A721D +:100410005A729972DA7202F0A3FA054602F0D6FA1D +:100420000446D0B9104B9D4219D001339D4241F290 +:10043000883512BF044600250124002002F09AFAF4 +:100440000CB100F059F800F039FD00F0F9FB284636 +:1004500000F004F900F050F8F9E70025EDE7054653 +:10046000EBE700BF00220020010007B008B500F054 +:10047000B3FBA0F120035842584108BD07B541F233 +:100480001203022101A8ADF8043000F0C3FB03B051 +:100490005DF804FB202310B583F311881248C3686C +:1004A0000BB101F007FF0023104A4FF47A710E4898 +:1004B00001F0C4FE002383F311880D4C236813B1AF +:1004C0002368013B2360636813B16368013B636089 +:1004D000084B1B7833B9636823B9022000F070FC25 +:1004E0003223636010BD00BF602200209504000825 +:1004F0007C23002074220020F8B5514B514A1C4641 +:100500001968013100F09B8004339342F8D162688E +:100510004D4B9A4240F293804C4B9B6803F1006331 +:1005200003F500339A4280F08A80002000F0A2FB9D +:100530000220474B187000F041FC464B0021D3F8D5 +:10054000E820C3F8E810D3F81021C3F81011D3F84D +:100550001021D3F8EC20C3F8EC10D3F81421C3F821 +:100560001411D3F81421D3F8F020C3F8F010D3F805 +:100570001821C3F81811D3F81821D3F8802042F0BD +:100580000062C3F88020D3F8802022F00062C3F814 +:100590008020D3F88020D3F8802042F00072C3F886 +:1005A0008020D3F8802022F00072C3F88020D3F896 +:1005B000803072B64FF0E023C3F8084DD4E9000450 +:1005C000BFF34F8FBFF36F8F234AC2F88410BFF37E +:1005D0004F8F536923F480335361BFF34F8FD2F8A9 +:1005E000803043F6E076C3F3C905C3F34E335B01B5 +:1005F00003EA060C29464CEA81770139C2F8747285 +:10060000F9D2203B13F1200FF2D1BFF34F8FBFF38C +:100610006F8FBFF34F8FBFF36F8F536923F4003396 +:1006200053610023C2F85032BFF34F8FBFF36F8F77 +:10063000202383F31188854680F308882047F8BD7E +:100640000000020820000208FFFF0108002200202D +:10065000742200200044025800ED00E02DE9F04F24 +:1006600093B0A94B2022FF2100900AA89D6800F0BA +:10067000CFFBA64A1378A3B90121A5481170C36026 +:10068000202383F31188C3680BB101F013FE00230C +:10069000A04A4FF47A719E4801F0D0FD002383F305 +:1006A0001188009B9C4A03B1136000239B49009C66 +:1006B00098469B461E469A460B705360012000F0F8 +:1006C0007DFB24B1944B1B68002B00F016820020A8 +:1006D00000F082FA0390039B002BF2DB012000F074 +:1006E0006BFB039B213B162BE8D801A252F823F0A9 +:1006F0004D0700087507000809080008BD06000836 +:10070000BD060008BD0600089D0800086F0A000825 +:1007100089090008EB090008130A0008390A0008D3 +:10072000BD0600084B0A0008BD060008BD0A000807 +:10073000ED070008BD060008010B00085907000876 +:10074000ED070008BD060008EB0900080220FFF7CE +:100750008DFE002840F0FB81009B022105A8B8F126 +:10076000000F08BF1C4641F21233ADF8143000F000 +:1007700051FAA3E74FF47A7000F02EFA071EEBDB74 +:100780000220FFF773FE0028E6D0013F052F00F29C +:10079000E081DFE807F0030A0D101336052304217A +:1007A00005A8059300F036FA17E004215648F9E74A +:1007B00004215B48F6E704215A48F3E74FF01C098F +:1007C000484609F1040900F057FA0421059005A8EC +:1007D00000F020FAB9F12C0FF2D101204FF0000AFD +:1007E00000FA07F747EA0B0B5FFA8BFB00F05CFBA4 +:1007F00026B10BF00B030B2B08BF0024FFF73EFEC6 +:100800005CE704214848CDE7002EA5D00BF00B0390 +:100810000B2BA1D10220FFF729FE074600289BD011 +:1008200001203E4E00F026FA4FF000080220307002 +:1008300000F0C4FA5FFA88F9484600F02BFA044643 +:1008400090B1484608F1010800F034FA0028F1D1CF +:10085000B846044641F21213022105A83E46ADF8FF +:10086000143000F0D7F929E7012325460220337020 +:1008700000F0A2FA244B9B68AB4207D9284600F04F +:10088000FBF9013040F068810435F3E70025234B84 +:10089000B8463E461D70204B5D60A7E7002E3FF432 +:1008A0005BAF0BF00B030B2B7FF456AF02201B4BFF +:1008B000187000F083FA322000F08EF9B0F10009D0 +:1008C000FFF64AAF19F003077FF446AF0E4A09EB73 +:1008D0000503926893423FF63FAFB9F5807F3FF73B +:1008E0003BAF124BB945019322DD4FF47A7000F013 +:1008F00073F90390039A002AFFF62EAF039A01378B +:10090000019B03F8012BEDE7002200207823002053 +:1009100060220020950400087C230020742200201F +:1009200004220020082200200C220020782200202F +:10093000C820FFF79BFD074600283FF40DAF1F2D91 +:1009400011D8C5F120020AAB25F0030084494A45BD +:10095000184428BF4A46019200F034FA019AFF2158 +:100960007F4800F055FA4FEAA903C9F387027C4992 +:100970002846019300F054FA064600283FF46AAF77 +:10098000019B05EB830531E70220FFF76FFD00288F +:100990003FF4E2AE00F0AAF900283FF4DDAE0027F4 +:1009A000B946704B9B68BB4218D91F2F11D80A9BC0 +:1009B00001330ED027F0030312AA134453F8203C4E +:1009C00005934846042205A9043700F019FB814627 +:1009D000E7E7384600F050F90590F2E7CDF81490BB +:1009E000042105A800F016F900E70023642104A8FB +:1009F000049300F005F900287FF4AEAE0220FFF763 +:100A000035FD00283FF4A8AE049800F065F9059084 +:100A1000E6E70023642104A8049300F0F1F800281D +:100A20007FF49AAE0220FFF721FD00283FF494AE38 +:100A3000049800F053F9EAE70220FFF717FD0028B9 +:100A40003FF48AAE00F062F9E1E70220FFF70EFD05 +:100A500000283FF481AE05A9142000F05DF9074697 +:100A60000421049004A800F0D5F83946B9E73220F3 +:100A700000F0B2F8071EFFF66FAEBB077FF46CAE56 +:100A8000384A07EB0A03926893423FF665AE0220AC +:100A9000FFF7ECFC00283FF45FAE27F00307574454 +:100AA000BA453FF4A3AE50460AF1040A00F0E4F858 +:100AB0000421059005A800F0ADF8F1E74FF47A7035 +:100AC000FFF7D4FC00283FF447AE00F00FF90028F0 +:100AD00044D00A9B01330BD008220AA9002000F061 +:100AE0009FF900283AD02022FF210AA800F090F9AF +:100AF000FFF7C4FC1C4801F05DFB13B0BDE8F08FAC +:100B0000002E3FF429AE0BF00B030B2B7FF424AE29 +:100B10000023642105A8059300F072F80746002819 +:100B20007FF41AAE0220FFF7A1FC814600283FF4B3 +:100B300013AEFFF7A3FC41F2883001F03BFB0598B0 +:100B400000F0FCF94E463C4600F0AEF9B6E506462C +:100B50004CE64FF0000AFFE5B8467BE6374679E6FB +:100B60007822002000220020A08601002DE9F84F05 +:100B70004FF47A7306460D46002402FB03F7DFF8B4 +:100B80005080DFF8509098F900305FFA84FA5A1CD0 +:100B900001D0A34210D159F824002A4631460368F7 +:100BA000D3F820B03B46D847854205D1074B0120FA +:100BB00083F800A0BDE8F88F0134042CE3D14FF492 +:100BC000FA7001F0F7FA0020F4E700BFC823002014 +:100BD000102200205C410008002307B502460121D5 +:100BE0000DF107008DF80730FFF7C0FF20B19DF829 +:100BF000070003B05DF804FB4FF0FF30F9E7000099 +:100C00000A46042108B5FFF7B1FF80F00100C0B229 +:100C1000404208BD074B0A4630B41978064B53F8DA +:100C20002140014623682046DD69044BAC4630BCB8 +:100C3000604700BFC82300205C410008A086010077 +:100C400070B50A4E00240A4D01F062FD308028681C +:100C50003388834208D901F057FD2B6804440133DF +:100C6000B4F5003F2B60F2D370BD00BFCA23002053 +:100C70008423002001F02ABE00F1006000F500305E +:100C80000068704700F10060920000F5003001F04C +:100C9000A1BD0000054B1A68054B1B889B1A8342B7 +:100CA00002D9104401F030BD002070478423002099 +:100CB000CA23002038B5074D04462868204401F0B7 +:100CC00029FD28B928682044BDE8384001F034BD2A +:100CD00038BD00BF842300200020704700F1FF5082 +:100CE00000F58F10D0F8000870470000064991F811 +:100CF000243033B100230822086A81F82430FFF73A +:100D0000C1BF0120704700BF88230020014B186835 +:100D1000704700BF0010005C244BF0B51A68044611 +:100D2000234BC2F30B06120C1F885868BE4293F97E +:100D3000085028D09F89BE4206D101200C2505FB12 +:100D40000033586893F9085041F201039A421CD0CD +:100D500041F203039A421AD042F201039A4218D098 +:100D600042F203039A4208BF5625621E0B46441EF8 +:100D70000A4493420FD214F9016F581C6EB1034616 +:100D800000F8016CF5E70020D8E75A25EDE7592572 +:100D9000EBE75825E9E7184605E02C2482421C7051 +:100DA00001D9981C5D70401AF0BD00BF0010005CB6 +:100DB0001422002000207047704700007047000098 +:100DC00070470000002310B5934203D0CC5CC4549C +:100DD0000133F9E710BD0000013810B510F9013FEB +:100DE0003BB191F900409C4203D11AB10131013A63 +:100DF000F4E71AB191F90020981A10BD1046FCE7EB +:100E000003460246D01A12F9011B0029FAD1704795 +:100E100002440346934202D003F8011BFAE77047ED +:100E20002DE9F8431F4D14460746884695F82420BF +:100E300052BBDFF870909CB395F824302BB9202278 +:100E4000FF2148462F62FFF7E3FF95F82400414653 +:100E5000C0F1080205EB8000A24228BF2246D6B2AC +:100E60009200FFF7AFFF95F82430A41B17441E44EF +:100E70009044E4B2F6B2082E85F82460DBD1FFF787 +:100E800035FF0028D7D108E02B6A03EB82038342A9 +:100E9000CFD0FFF72BFF0028CBD10020BDE8F8838F +:100EA0000120FBE788230020024B1A78024B1A70BE +:100EB000704700BFC823002010220020F8B5194C4D +:100EC000194800F079FC2146174800F0A1FC24687D +:100ED0001648D4F89020164ED2F80438154D43F039 +:100EE0000203114FC2F8043801F064F92046124998 +:100EF00000F09CFDD4F890200424D2F8043823F0AC +:100F00000203C2F804384FF4E133336055F8040BA0 +:100F1000B84202D0314600F0ADFB013C14F0FF04B2 +:100F2000F4D1F8BD6C420008C832002040420F00E6 +:100F3000B02300205C4100087442000838B50B4B18 +:100F400004461A780A4B53F822500A4B9D420CD0A3 +:100F5000094B002118221846FFF75AFF046001468A +:100F60002846BDE8384000F085BB38BDC8230020C6 +:100F70005C410008C8320020B023002000B59BB0BF +:100F8000EFF3098168226846FFF71CFFEFF3058342 +:100F9000044B9A6BDA6A9A6A9A6A9A6A9A6A9A6AA5 +:100FA0009B6AFEE700ED00E000B59BB0EFF309811E +:100FB00068226846FFF706FFEFF30583044B9A6B40 +:100FC0009A6A9A6A9A6A9A6A9A6A9B6AFEE700BF64 +:100FD00000ED00E000B59BB0EFF3098168226846A0 +:100FE000FFF7F0FEEFF30583034B5A6B9A6A9A6A98 +:100FF0009A6A9A6A9B6AFEE700ED00E0FEE700004D +:1010000030B50A44084D91420DD011F8013B5840CB +:10101000082340F30004013B2C4013F0FF0384EA53 +:101020005000F6D1EFE730BD2083B8ED0268436889 +:101030001143016003B1184770470000024A13686A +:1010400043F0C0031360704700440040024A136835 +:1010500043F0C0031360704700480040024A136821 +:1010600043F0C003136070470078004037B5274C49 +:10107000274D204600F0F2FA04F1140000940023FA +:101080004FF40072234900F0B3F94FF40072224983 +:1010900004F138000094214B00F02CFA204BC4E9F5 +:1010A0001735204C204600F0D9FA04F114000094C2 +:1010B00000234FF400721C4900F09AF94FF40072BB +:1010C0001A4904F138000094194B00F013FA194B37 +:1010D000C4E91735184C204600F0C0FA04F114009A +:1010E00000234FF400721549009400F081F9144B6D +:1010F0004FF40072134904F13800009400F0FAF93B +:10110000114BC4E9173503B030BD00BFCC2300201C +:1011100000E1F50510250020102B00203D100008EF +:10112000004400403824002010270020102D00200B +:101130004D10000800480040A42400201029002081 +:101140005D100008102F002000780040037C30B5AF +:10115000334C002918BF0C46012B18D1314B984253 +:101160000FD1314BD3F8E82042F40032C3F8E82025 +:10117000D3F8102142F40032C3F81021D3F8103113 +:1011800005E02A4B98422FD0294B984238D022684C +:10119000036EC16D03EB52038466B3FBF2F3626826 +:1011A000150442BF23F0070503F0070343EA450394 +:1011B000CB60A36843F040034B60E36843F0010356 +:1011C0008B6042F4967343F001030B604FF0FF33E2 +:1011D0000B62510505D512F010221DD0B2F1805FCF +:1011E0001CD080F8643030BD0F4BD3F8E82042F4B7 +:1011F0008022C3F8E820D3F8102142F48022BBE714 +:10120000094BD3F8E82042F08042C3F8E820D3F835 +:10121000102142F08042AFE77F23E2E73F23E0E77F +:101220006C410008CC2300200044025838240020E0 +:10123000A42400202DE9F047C66D05463768F469FF +:101240002107346219D014F0080118BF8021E20789 +:1012500048BF41F02001A3074FF0200348BF41F0F1 +:101260004001600748BF41F4807183F31188281D55 +:10127000FFF7DCFE002383F31188E2050AD5202363 +:1012800083F311884FF40071281DFFF7CFFE002370 +:1012900083F311884FF020094FF0000A14F0200862 +:1012A00038D13B0616D54FF0200905F1380A200643 +:1012B00010D589F31188504600F050F9002836DA2D +:1012C0000821281DFFF7B2FE27F0800333600023BA +:1012D00083F31188790614D5620612D5202383F38F +:1012E0001188D5E913239A4208D12B6C33B127F02A +:1012F00040071021281DFFF799FE3760002383F374 +:101300001188E30618D5AA6E1369ABB15069BDE820 +:10131000F047184789F31188736A284695F86410D6 +:10132000194000F0B5F98AF31188F469B6E7B062A4 +:1013300088F31188F469BAE7BDE8F087F8B5154677 +:10134000826804460B46AA4200D28568A1692669D4 +:10135000761AB5420BD218462A46FFF733FDA36929 +:101360002B44A3612846A3685B1BA360F8BD0CD97E +:10137000AF1B18463246FFF725FD3A46E168304478 +:10138000FFF720FDE3683B44EBE718462A46FFF7EA +:1013900019FDE368E5E7000083689342F7B504466A +:1013A000154600D28568D4E90460361AB5420BD2DE +:1013B0002A46FFF707FD63692B4463612846A3684B +:1013C0005B1BA36003B0F0BD0DD93246AF1B01918A +:1013D000FFF7F8FC01993A46E0683144FFF7F2FC68 +:1013E000E3683B44E9E72A46FFF7ECFCE368E4E7FF +:1013F00010B50A440024C361029B8460C16002618D +:101400000362C0E90000C0E9051110BD08B5D0E9CC +:101410000532934201D1826882B9826801328260CA +:101420005A1C426119700021D0E904329A4224BF4B +:10143000C368436100F0DAFE002008BD4FF0FF30C2 +:10144000FBE7000070B5202304460E4683F31188A5 +:10145000A568A5B1A368A269013BA360531CA36161 +:1014600015782269934224BFE368A361E3690BB155 +:1014700020469847002383F31188284607E0314629 +:10148000204600F0A3FE0028E2DA85F3118870BD43 +:101490002DE9F74F04460E4617469846D0F81C90A3 +:1014A0004FF0200A8AF311884FF0000B154665B102 +:1014B0002A4631462046FFF741FF034660B94146C0 +:1014C000204600F083FE0028F1D0002383F311882A +:1014D000781B03B0BDE8F08FB9F1000F03D0019085 +:1014E0002046C847019B8BF31188ED1A1E448AF3EE +:1014F0001188DCE7C160C361009B82600362C0E9C0 +:1015000005111144C0E9000001617047F8B50446B7 +:101510000D461646202383F31188A768A7B1A36858 +:10152000013BA36063695A1C62611D70D4E90432F7 +:101530009A4224BFE3686361E3690BB12046984790 +:10154000002080F3118807E03146204600F03EFE7F +:101550000028E2DA87F31188F8BD0000D0E90523FE +:1015600010B59A4201D182687AB9826800210132AD +:1015700082605A1C82611C7803699A4224BFC36846 +:10158000836100F033FE204610BD4FF0FF30FBE7D3 +:101590002DE9F74F04460E4617469846D0F81C90A2 +:1015A0004FF0200A8AF311884FF0000B154665B101 +:1015B0002A4631462046FFF7EFFE034660B9414612 +:1015C000204600F003FE0028F1D0002383F31188A9 +:1015D000781B03B0BDE8F08FB9F1000F03D0019084 +:1015E0002046C847019B8BF31188ED1A1E448AF3ED +:1015F0001188DCE7026843681143016003B11847B2 +:10160000704700001430FFF743BF00004FF0FF3376 +:101610001430FFF73DBF00003830FFF7B9BF0000BE +:101620004FF0FF333830FFF7B3BF00001430FFF73F +:1016300009BF00004FF0FF311430FFF703BF000077 +:101640003830FFF763BF00004FF0FF323830FFF74C +:101650005DBF000000207047FFF708BD044B03602A +:1016600000234360C0E9023301230374704700BFC5 +:101670008441000810B52023044683F31188FFF746 +:1016800065FD02232374002383F3118810BD00003D +:1016900038B5C36904460D461BB904210844FFF759 +:1016A000A9FF294604F11400FFF7B0FE002806DA6E +:1016B000201D4FF48061BDE83840FFF79BBF38BD67 +:1016C000026843681143016003B118477047000086 +:1016D00013B5406B00F58054D4F8A4381A6811781B +:1016E000042914D1017C022911D11979012312890D +:1016F0008B4013420BD101A94C3002F06FF8D4F8A3 +:10170000A4480246019B2179206800F0DFF902B06D +:1017100010BD0000143001F0F1BF00004FF0FF33A6 +:10172000143001F0EBBF00004C3002F0C3B80000F1 +:101730004FF0FF334C3002F0BDB80000143001F020 +:10174000BFBF00004FF0FF31143001F0B9BF0000FF +:101750004C3002F08FB800004FF0FF324C3002F0F6 +:1017600089B800000020704710B500F58054D4F807 +:10177000A4381A681178042917D1017C022914D1E0 +:101780005979012352898B4013420ED1143001F054 +:1017900051FF024648B1D4F8A4484FF44073617930 +:1017A0002068BDE8104000F07FB910BD406BFFF726 +:1017B000DBBF0000704700007FB5124B01250426F7 +:1017C000044603600023057400F184024360294647 +:1017D000C0E902330C4B0290143001934FF4407374 +:1017E000009601F003FF094B04F69442294604F1E8 +:1017F0004C000294CDE900634FF4407301F0CAFF3E +:1018000004B070BDAC410008AD170008D116000847 +:101810000A68202383F311880B790B3342F82300E5 +:101820004B79133342F823008B7913B10B3342F811 +:10183000230000F58053C3F8A41802230374002387 +:1018400083F311887047000038B5037F044613B155 +:1018500090F85430ABB90125201D0221FFF730FF6D +:1018600004F114006FF00101257700F0CBFC04F1C6 +:101870004C0084F854506FF00101BDE8384000F08E +:10188000C1BC38BD10B5012104460430FFF718FF74 +:101890000023237784F8543010BD000038B5044687 +:1018A0000025143001F0BAFE04F14C00257701F058 +:1018B00089FF201D84F854500121FFF701FF2046C5 +:1018C000BDE83840FFF750BF90F8803003F0600368 +:1018D000202B06D190F881200023212A03D81F2A2B +:1018E00006D800207047222AFBD1C0E91D3303E04F +:1018F000034A426707228267C3670120704700BF1F +:101900002C22002037B500F58055D5F8A4381A6888 +:10191000117804291AD1017C022917D119790123E0 +:1019200012898B40134211D100F14C04204602F081 +:1019300009F858B101A9204601F050FFD5F8A44894 +:101940000246019B2179206800F0C0F803B030BD49 +:1019500001F10B03F0B550F8236085B004460D4645 +:10196000FEB1202383F3118804EB8507301D082185 +:10197000FFF7A6FEFB6806F14C005B691B681BB114 +:10198000019001F039FF019803A901F027FF0246F9 +:1019900048B1039B2946204600F098F8002383F3C2 +:1019A000118805B0F0BDFB685A691268002AF5D0AD +:1019B0001B8A013B1340F1D104F18002EAE70000E9 +:1019C000133138B550F82140ECB1202383F311884E +:1019D00004F58053D3F8A4281368527903EB8203EB +:1019E000DB689B695D6845B104216018FFF768FEFC +:1019F000294604F1140001F027FE2046FFF7B4FE4B +:101A0000002383F3118838BD7047000001F01AB934 +:101A100001234022002110B5044600F8303BFFF7B7 +:101A2000F7F90023C4E9013310BD000010B52023ED +:101A3000044683F311882422416000210C30FFF713 +:101A4000E7F9204601F020F902232370002383F3F5 +:101A5000118810BD70B500EB8103054650690E4634 +:101A60001446DA6018B110220021FFF7D1F9A069FD +:101A700018B110220021FFF7CBF931462846BDE806 +:101A8000704001F013BA000083682022002103F0A7 +:101A9000011310B5044683601030FFF7B9F92046F2 +:101AA000BDE8104001F08EBAF0B4012500EB8104CE +:101AB00047898D40E4683D43A46945812360002344 +:101AC000A2606360F0BC01F0ABBA0000F0B4012585 +:101AD00000EB810407898D40E4683D43646905811A +:101AE00023600023A2606360F0BC01F021BB000012 +:101AF00070B5022300250446242203702946C0F84D +:101B000088500C3040F8045CFFF782F9204684F8D6 +:101B1000705001F05FF963681B6823B129462046C5 +:101B2000BDE87040184770BD037880F88C300523FD +:101B3000037043681B6810B504460BB10421984735 +:101B40000023A36010BD000090F88C204368027051 +:101B50001B680BB1052118477047000070B590F85D +:101B60007030044613B1002380F8703004F1800215 +:101B7000204601F04BFA63689B68B3B994F8803053 +:101B800013F0600535D00021204601F0F5FC00215E +:101B9000204601F0E5FC63681B6813B1062120466E +:101BA0009847062384F8703070BD20469847002877 +:101BB000E4D0B4F88630A26F9A4288BFA36794F944 +:101BC0008030A56F002B4FF0200380F20381002DA1 +:101BD00000F0F280092284F8702083F3118800213C +:101BE0002046D4E91D23FFF771FF002383F31188FA +:101BF000DAE794F8812003F07F0343EA022340F2FE +:101C00000232934200F0C58021D8B3F5807F48D0DE +:101C10000DD8012B3FD0022B00F09380002BB2D1C6 +:101C200004F1880262670222A267E367C1E7B3F5A5 +:101C3000817F00F09B80B3F5407FA4D194F882307F +:101C4000012BA0D1B4F8883043F0020332E0B3F5A1 +:101C5000006F4DD017D8B3F5A06F31D0A3F5C06396 +:101C6000012B90D86368204694F882205E6894F82F +:101C70008310B4F88430B047002884D04368636789 +:101C80000368A3671AE0B3F5106F36D040F602423E +:101C900093427FF478AF5C4B63670223A367002312 +:101CA000C3E794F88230012B7FF46DAFB4F888302D +:101CB00023F00203A4F88830C4E91D55E56778E7EE +:101CC000B4F88030B3F5A06F0ED194F8823020467E +:101CD00084F88A3001F0DCF863681B6813B10121D5 +:101CE00020469847032323700023C4E91D339CE753 +:101CF00004F18B0363670123C3E72378042B10D11E +:101D0000202383F311882046FFF7BEFE85F3118858 +:101D10000321636884F88B5021701B680BB1204647 +:101D2000984794F88230002BDED084F88B3004235F +:101D3000237063681B68002BD6D002212046984789 +:101D4000D2E794F8843020461D0603F00F010AD52F +:101D500001F04EF9012804D002287FF414AF2B4B78 +:101D60009AE72B4B98E701F035F9F3E794F88230C6 +:101D7000002B7FF408AF94F8843013F00F01B3D038 +:101D80001A06204602D501F00FFCADE701F000FC79 +:101D9000AAE794F88230002B7FF4F5AE94F88430F3 +:101DA00013F00F01A0D01B06204602D501F0E4FB82 +:101DB0009AE701F0D5FB97E7142284F8702083F3AB +:101DC00011882B462A4629462046FFF76DFE85F3EB +:101DD0001188E9E65DB1152284F8702083F311883B +:101DE00000212046D4E91D23FFF75EFEFDE60B220D +:101DF00084F8702083F311882B462A462946204612 +:101E0000FFF764FEE3E700BFDC410008D4410008AF +:101E1000D841000838B590F870300446002B3ED009 +:101E2000063BDAB20F2A34D80F2B32D8DFE803F0A2 +:101E300037313108223231313131313131313737B7 +:101E4000856FB0F886309D4214D2C3681B8AB5FBFB +:101E5000F3F203FB12556DB9202383F311882B464F +:101E60002A462946FFF732FE85F311880A2384F8B3 +:101E700070300EE0142384F87030202383F311882F +:101E8000002320461A461946FFF70EFE002383F36F +:101E9000118838BDC36F03B198470023E7E70021DD +:101EA000204601F069FB0021204601F059FB6368E0 +:101EB0001B6813B10621204698470623D7E7000088 +:101EC00010B590F870300446142B29D017D8062B83 +:101ED00005D001D81BB110BD093B022BFBD8002156 +:101EE000204601F049FB0021204601F039FB6368E0 +:101EF0001B6813B1062120469847062319E0152BCD +:101F0000E9D10B2380F87030202383F3118800235C +:101F10001A461946FFF7DAFD002383F31188DAE742 +:101F2000C3689B695B68002BD5D1C36F03B1984729 +:101F3000002384F87030CEE7024B0022C3E900335F +:101F40009A60704710310020002382680374054BAB +:101F50001B6899689142FBD25A6803604260106026 +:101F6000586070471031002008B5202383F3118892 +:101F7000037C032B05D0042B0DD02BB983F31188E0 +:101F800008BD436900221A604FF0FF334361FFF739 +:101F9000DBFF0023F2E7D0E9003213605A60F3E779 +:101FA000002382680374054B1B6899689142FBD833 +:101FB0005A6803604260106058607047103100201A +:101FC000054B196908741868026853601A60186133 +:101FD00001230374FEF7FAB9103100204B1C30B511 +:101FE000044687B00A4D10D02B6901A8094A00F0B9 +:101FF00025F92046FFF7E4FF049B13B101A800F088 +:1020000059F92B69586907B030BDFFF7D9FFF8E7D8 +:1020100010310020691F000838B50C4D044641619D +:102020002B6981689A68914203D8BDE83840FFF770 +:102030008BBF1846FFF7B4FF01232C6101462374C0 +:102040002046BDE83840FEF7C1B900BF103100207E +:10205000044B1A681B6990689B68984294BF0020E3 +:10206000012070471031002010B5084C236820690A +:102070001A6854602260012223611A74FFF790FFEE +:1020800001462069BDE81040FEF7A0B910310020DC +:1020900008B5FFF7DDFF18B1BDE80840FFF7E4BF62 +:1020A00008BD0000FFF7E0BFFEE7000010B50C4CD4 +:1020B000FFF742FF00F0B4F880220A49204600F002 +:1020C0003BF8012344F8180C037400F099FC00233A +:1020D00083F3118862B60448BDE8104000F04CB8A4 +:1020E00038310020E0410008F041000800F01CB940 +:1020F000EFF3118020B9EFF30583202282F31188DA +:102100007047000010B530B9EFF30584C4F308043C +:1021100014B180F3118810BDFFF7BAFF84F3118862 +:10212000F9E70000034A516853685B1A9842FBD8EC +:10213000704700BF001000E08260022202827047F8 +:102140008368A3F17C0243F80C2C026943F83C2C11 +:10215000426943F8382C074A43F81C2CC268A3F1A3 +:10216000180043F8102C022203F8082C002203F870 +:10217000072C7047E503000810B5202383F311886E +:10218000FFF7DEFF00210446FFF746FF002383F33D +:102190001188204610BD0000024B1B6958610F20BA +:1021A000FFF70EBF10310020202383F31188FFF7C3 +:1021B000F3BF000008B50146202383F311880820EF +:1021C000FFF70CFF002383F3118808BD49B1064BCC +:1021D00042681B6918605A60136043600420FFF76F +:1021E000FDBE4FF0FF307047103100200368984269 +:1021F00006D01A680260506018465961FFF7A4BE05 +:102200007047000038B504460D462068844200D16E +:1022100038BD036823605C604561FFF795FEF4E715 +:10222000054B4FF0FF3103F11402C3E905220022F0 +:10223000C3E90712704700BF1031002070B51C4E73 +:1022400005460C46C0E9032301F0B2FB334653F8C0 +:10225000142F9A420DD130620A2C2CBF00190A307B +:102260002A60C5E90124C6E90555BDE8704001F0C2 +:1022700089BB316A431AE31838BF1C469368A342EE +:1022800002D9081901F08EFB73699A6894420CD840 +:102290005A68AC602B606A6015609A685D60121BBA +:1022A0009A604FF0FF33F36170BDA41A1B68ECE72E +:1022B0001031002038B51B4C636998420DD08168FD +:1022C000D0E9003213605A600022C2609A680A4462 +:1022D0009A604FF0FF33E36138BD03682246002166 +:1022E00042F8143F93425A60C16003D1BDE83840C0 +:1022F00001F052BB9A688168256A0A449A6001F02D +:1023000057FB6369411B9A688A42E5D9AB181D1ACD +:10231000206A092D98BF01F10A02BDE83840104437 +:1023200001F040BB103100202DE9F041184C00278E +:1023300004F11406656901F03BFB236AAA68C11A1F +:102340008A4215D81344D5F80C802362D5E90032AF +:1023500013605A606369EF60B34201D101F01CFB66 +:1023600087F311882869C047202383F31188E1E7A8 +:102370006169B14209D013441B1ABDE8F0410A2B30 +:102380002CBFC0180A3001F00DBBBDE8F08100BFC2 +:102390001031002000207047FEE700007047000069 +:1023A0004FF0FF307047000002290CD0032904D001 +:1023B0000129074818BF00207047032A05D805489F +:1023C00000EBC2007047044870470020704700BF10 +:1023D000D04200083C2200208442000870B59AB028 +:1023E00005460846144601A900F0C2F801A8FEF708 +:1023F00007FD431C0022C6B25B001046C5E900344D +:1024000023700323023404F8013C01ABD1B202343F +:102410008E4201D81AB070BD13F8011B013204F8C6 +:10242000010C04F8021CF1E708B5202383F311889E +:102430000348FFF767FA002383F3118808BD00BF44 +:10244000C832002090F8803003F01F02012A07D123 +:1024500090F881200B2A03D10023C0E91D3315E039 +:1024600003F06003202B08D1B0F884302BB990F82A +:102470008120212A03D81F2A04D8FFF725BA222A4F +:10248000EBD0FAE7034A426707228267C36701205D +:10249000704700BF3322002007B5052917D8DFE8B1 +:1024A00001F0191603191920202383F31188104A0B +:1024B00001210190FFF7CEFA019802210D4AFFF7A2 +:1024C000C9FA0D48FFF7EAF9002383F3118803B036 +:1024D0005DF804FB202383F311880748FFF7B4F964 +:1024E000F2E7202383F311880348FFF7CBF9EBE7EA +:1024F0002442000848420008C832002038B50C4D7C +:102500000C4C2A460C4904F10800FFF767FF05F15F +:10251000CA0204F110000949FFF760FF05F5CA720D +:1025200004F118000649BDE83840FFF757BF00BF67 +:10253000A04B00203C220020084200081242000864 +:102540001A42000870B5044608460D46FEF758FCCE +:10255000C6B22046013403780BB9184670BD324626 +:102560002946FEF739FC0028F3D10120F6E70000E8 +:102570002DE9F04705460C46FEF742FC2C49C6B251 +:102580002846FFF7DFFF08B10836F6B2294928468A +:10259000FFF7D8FF08B11036F6B2632E0BD8DFF87C +:1025A0009080DFF89090244FDFF898A02E7846B9FD +:1025B0002670BDE8F08729462046BDE8F04701F0C7 +:1025C000B7BD252E30D1072241462846FEF704FC30 +:1025D00080B91A4B224603F10C0153F8040B8B42CD +:1025E00042F8040BF9D1198807359B780F34118014 +:1025F0009370DBE7082249462846FEF7EDFB98B9C1 +:10260000A21C0F4B197802320909C95D02F8041C9B +:1026100013F8011B01F00F015345C95D02F8031CBB +:10262000F0D118340835C1E7013504F8016BBDE776 +:10263000F04200081A42000808430008F842000867 +:1026400000E8F11F0CE8F11FBFF34F8F044B1A692C +:102650005107FCD1D3F810215207F8D1704700BFC1 +:102660000020005208B50D4B1B78ABB9FFF7ECFF0B +:102670000B4BDA68D10704D50A4A5A6002F1883256 +:102680005A60D3F80C21D20706D5064AC3F80421B4 +:1026900002F18832C3F8042108BD00BFFE4D0020BE +:1026A000002000522301674508B5114B1B78F3B990 +:1026B000104B1A69510703D5DA6842F04002DA601C +:1026C000D3F81021520705D5D3F80C2142F040026F +:1026D000C3F80C21FFF7B8FF064BDA6842F001029D +:1026E000DA60D3F80C2142F00102C3F80C2108BDD6 +:1026F000FE4D0020002000520F289ABF00F5806098 +:1027000040040020704700004FF400307047000084 +:10271000102070470F2808B50BD8FFF7EDFF00F524 +:1027200000330268013204D104308342F9D1012020 +:1027300008BD0020FCE700000F2870B5054645D80D +:10274000FFF7D6FC224CFFF77FFF0646FFF78AFF14 +:102750004FF0FF33072D6361C4F8143120D8236193 +:10276000FFF772FF2B0243F02403E360E36843F0BA +:102770008003E36023695A07FCD42846FFF764FF0F +:102780004FF40031FFF7B8FF00F002F93046FFF7D1 +:102790008BFFFFF7B7FC2846BDE87040FFF7BABFD4 +:1027A000C4F81031FFF750FFA5F108031B0243F0F6 +:1027B0002403C4F80C31D4F80C3143F08003C4F87E +:1027C0000C31D4F810315B07FBD4D6E7002070BD84 +:1027D000002000522DE9F84F40EA020305460C465E +:1027E0001746D80602D00020BDE8F88F27F01F0753 +:1027F000DFF8D4B0FFF736FF2744BC4203D10120F5 +:10280000FFF752FFF0E720222946204601F080FC26 +:1028100010B920352034F0E72B4605F120021E6860 +:10282000711CE0D104339A42F9D1FFF761FC05F144 +:102830007843234AB3F5801F224B28BF9A4603F101 +:10284000040338BF9046A2F1080228BF9846A3F1BE +:1028500008033ABF9146DA469946FFF7F5FEC8F8F5 +:102860000060A5EB040CD9F8002004F11C0142F033 +:102870000202C9F80020221FDAF8006016F00506EF +:10288000FAD152F8043F8A424CF80230F4D1BFF337 +:102890004F8FFFF7D9FE4FF0FF32C8F80020D9F86C +:1028A000002022F00202C9F80020FFF72BFC2022B2 +:1028B0002146284601F02CFC0028AAD030469FE78C +:1028C00014200052102100521020005210B5084C64 +:1028D000237828B11BB9FFF7C5FE0123237010BD73 +:1028E000002BFCD02070BDE81040FFF7DDBE00BF1C +:1028F000FE4D00200244074BD2B210B5904200D1E9 +:1029000010BD441C00B253F8200041F8040BE0B2A3 +:10291000F4E700BF504000580E4B30B51C6F240444 +:1029200005D41C6F1C671C6F44F400441C670A4CE0 +:1029300002442368D2B243F480732360074B904271 +:1029400000D130BD441C51F8045B00B243F8205064 +:10295000E0B2F4E7004402580048025850400058E2 +:1029600007B5012201A90020FFF7C4FF019803B0B9 +:102970005DF804FB13B50446FFF7F2FFA04205D053 +:10298000012201A900200194FFF7C6FF02B010BD8B +:102990000144BFF34F8F064B884204D3BFF34F8FE0 +:1029A000BFF36F8F7047C3F85C022030F4E700BFBD +:1029B00000ED00E0034B1A681AB9034AD2F8D0249C +:1029C0001A607047004E00200040025808B5FFF71B +:1029D000F1FF024B1868C0F3806008BD004E002074 +:1029E000EFF30983054968334A6B22F001024A6319 +:1029F00083F30988002383F31188704700EF00E018 +:102A0000202080F3118862B60D4B0E4AD96821F45C +:102A1000E0610904090C0A430B49DA60D3F8FC2091 +:102A200042F08072C3F8FC20084AC2F8B01F116857 +:102A300041F0010111601022DA7783F8220070471B +:102A400000ED00E00003FA0555CEACC5001000E033 +:102A5000202310B583F311880E4B5B6813F40063D9 +:102A600014D0F1EE103AEFF309844FF08073683C14 +:102A7000E361094BDB6B236684F30988FFF7E8FA0F +:102A800010B1064BA36110BD054BFBE783F3118822 +:102A9000F9E700BF00ED00E000EF00E0F7030008F9 +:102AA000FA03000870B5BFF34F8FBFF36F8F1A4A58 +:102AB0000021C2F85012BFF34F8FBFF36F8F5369DD +:102AC00043F400335361BFF34F8FBFF36F8FC2F8EE +:102AD0008410BFF34F8FD2F8803043F6E074C3F315 +:102AE000C900C3F34E335B0103EA0406014646EA1C +:102AF00081750139C2F86052F9D2203B13F1200FE1 +:102B0000F2D1BFF34F8F536943F480335361BFF366 +:102B10004F8FBFF36F8F70BD00ED00E0FEE7000048 +:102B20000A4B0B480B4A90420BD30B4BC11EDA1CCD +:102B3000121A22F003028B4238BF00220021FEF756 +:102B400067B953F8041B40F8041BECE7EC44000899 +:102B5000D44F0020D44F0020D44F002070470000F5 +:102B600070B5D0E9244300224FF0FF359E6804EB96 +:102B700042135101D3F80009002805DAD3F80009FF +:102B800040F08040C3F80009D3F8000B002805DAB4 +:102B9000D3F8000B40F08040C3F8000B01326318FB +:102BA0009642C3F80859C3F8085BE0D24FF001130E +:102BB000C4F81C3870BD000000EB8103D3F80CC0D2 +:102BC0002DE9F043DCF814204E1CD0F89050D2F8D8 +:102BD00000E005EB063605EB4118506870450AD356 +:102BE0000122D5F8343802FA01F123EA0101C5F8CF +:102BF0003418BDE8F083AEEB0003BCF81040A342EC +:102C000028BF2346D8F81849A4B2B3EB840FF0D8F4 +:102C10009468A4F1040959F8047F3760A4EB09070C +:102C20001F44042FF7D81C44034494605360D4E736 +:102C3000890141F02001016103699B06FCD4122047 +:102C4000FFF770BA10B50A4C2046FEF7E1FE094BBB +:102C5000C4F89030084BC4F89430084C2046FEF776 +:102C6000D7FE074BC4F89030064BC4F8943010BD23 +:102C7000044E00200000084040430008A04E002001 +:102C8000000004404C43000870B503780546012B52 +:102C90005DD1494BD0F89040984259D1474B0E2115 +:102CA0006520D3F8D82042F00062C3F8D820D3F8CA +:102CB000002142F00062C3F80021D3F80021D3F8CC +:102CC000802042F00062C3F88020D3F8802022F0F8 +:102CD0000062C3F88020D3F8803000F071FC384BDC +:102CE000E360384BC4F800380023D5F89060C4F88E +:102CF000003EC02323604FF40413A3633369002B09 +:102D0000FCDA01230C203361FFF70CFA3369DB078F +:102D1000FCD41220FFF706FA3369002BFCDA0026F8 +:102D20002846A660FFF71CFF6B68C4F81068DB68D4 +:102D3000C4F81468C4F81C68002B3AD1224BA36174 +:102D40004FF0FF336361A36843F00103A36070BDDC +:102D50001E4B9842C8D1194B0E214D20D3F8D820D4 +:102D600042F00072C3F8D820D3F8002142F000727C +:102D7000C3F80021D3F80021D3F8802042F000727C +:102D8000C3F88020D3F8802022F00072C3F880209E +:102D9000D3F88020D3F8D82022F08062C3F8D8205E +:102DA000D3F8002122F08062C3F80021D3F800316B +:102DB00093E7074BC3E700BF044E002000440258CE +:102DC0004014004003002002003C30C0A04E002010 +:102DD000083C30C0F8B5D0F89040054600214FF0CF +:102DE00000662046FFF724FFD5F8941000234FF02B +:102DF00001128F684FF0FF30C4F83438C4F81C2833 +:102E000004EB431201339F42C2F80069C2F8006B21 +:102E1000C2F80809C2F8080BF2D20B68D5F8902066 +:102E2000C5F89830636210231361166916F0100616 +:102E3000FBD11220FFF776F9D4F8003823F4FE63B3 +:102E4000C4F80038A36943F4402343F01003A3619E +:102E50000923C4F81038C4F814380B4BEB604FF05A +:102E6000C043C4F8103B094BC4F8003BC4F81069D8 +:102E7000C4F80039D5F8983003F1100243F48013F8 +:102E8000C5F89820A362F8BD1C43000840800010DC +:102E9000D0F8902090F88A10D2F8003823F4FE631E +:102EA00043EA0113C2F80038704700002DE9F843E7 +:102EB00000EB8103D0F890500C468046DA680FFA98 +:102EC00081F94801166806F00306731E022B05EB14 +:102ED00041134FF0000194BFB604384EC3F8101BE5 +:102EE0004FF0010104F1100398BF06F1805601FA7A +:102EF00003F3916998BF06F5004600293AD0578A36 +:102F000004F15801374349016F50D5F81C180B43A1 +:102F10000021C5F81C382B180127C3F81019A74049 +:102F20005369611E9BB3138A928B9B08012A88BF49 +:102F30005343D8F89820981842EA034301F140021D +:102F40002146C8F89800284605EB82025360FFF737 +:102F50006FFE08EB8900C3681B8A43EA8453483438 +:102F60001E4364012E51D5F81C381F43C5F81C7848 +:102F7000BDE8F88305EB4917D7F8001B21F40041A1 +:102F8000C7F8001BD5F81C1821EA0303C0E704F1B9 +:102F90003F030B4A2846214605EB83035A60FFF79F +:102FA00047FE05EB4910D0F8003923F40043C0F880 +:102FB0000039D5F81C3823EA0707D7E7008000104E +:102FC00000040002D0F894201268C0F89820FFF79F +:102FD000C7BD00005831D0F8903049015B5813F458 +:102FE000004004D013F4001F0CBF022001207047E2 +:102FF0004831D0F8903049015B5813F4004004D0B8 +:1030000013F4001F0CBF02200120704700EB810168 +:10301000CB68196A0B6813604B68536070470000F7 +:1030200000EB810330B5DD68AA691368D36019B974 +:10303000402B84BF402313606B8A1468D0F8902023 +:103040001C4402EB4110013C09B2B4FBF3F46343AE +:10305000033323F0030343EAC44343F0C043C0F8FF +:10306000103B2B6803F00303012B0ED1D2F8083874 +:1030700002EB411013F4807FD0F8003B14BF43F003 +:10308000805343F00053C0F8003B02EB4112D2F8EA +:10309000003B43F00443C2F8003B30BD2DE9F04152 +:1030A000D0F8906005460C4606EB4113D3F8087B38 +:1030B0003A07C3F8087B08D5D6F814381B0704D59F +:1030C00000EB8103DB685B689847FA071FD5D6F8E9 +:1030D0001438DB071BD505EB8403D968CCB98B69A1 +:1030E000488A5A68B2FBF0F600FB16228AB91868C3 +:1030F000DA6890420DD2121AC3E90024202383F328 +:10310000118821462846FFF78BFF84F31188BDE81C +:10311000F081012303FA04F26B8923EA02036B8135 +:10312000CB68002BF3D021462846BDE8F041184774 +:1031300000EB81034A0170B5DD68D0F890306C690E +:103140002668E66056BB1A444FF40020C2F8100906 +:103150002A6802F00302012A0AB20ED1D3F8080845 +:1031600003EB421410F4807FD4F8000914BF40F040 +:10317000805040F00050C4F8000903EB4212D2F82E +:10318000000940F00440C2F800090122D3F83408D5 +:1031900002FA01F10143C3F8341870BD19B9402E89 +:1031A00084BF4020206020681A442E8A8419013C84 +:1031B000B4FBF6F440EAC44040F00050C6E700001B +:1031C0002DE9F041D0F8906004460D4606EB41131E +:1031D000D3F80879C3F80879FB071CD5D6F810385E +:1031E000DA0718D500EB8103D3F80CC0DCF81430F3 +:1031F000D3F800E0DA6896451BD2A2EB0E024FF03E +:1032000000081A60C3F80480202383F31188FFF7B5 +:103210008FFF88F311883B0618D50123D6F8342890 +:10322000AB40134212D029462046BDE8F041FFF7DB +:10323000C3BC012303FA01F2038923EA02030381D9 +:10324000DCF80830002BE6D09847E4E7BDE8F081D1 +:103250002DE9F84FD0F8905004466E69AB691E40D6 +:1032600016F480586E6103D0BDE8F84FFEF740BCFD +:10327000002E12DAD5F8003E9F0705D0D5F8003EA3 +:1032800023F00303C5F8003ED5F80438204623F0A8 +:103290000103C5F80438FEF757FC300505D5204674 +:1032A000FFF75EFC2046FEF73FFCB1040CD5D5F8D5 +:1032B000083813F0060FEB6823F470530CBF43F487 +:1032C000105343F4A053EB60320704D56368DB6806 +:1032D0000BB120469847F30200F1BA80B70226D519 +:1032E000D4F8909000274FF0010A09EB4712D2F86A +:1032F000003B03F44023B3F5802F11D1D2F8003BFB +:10330000002B0DDA62890AFA07F322EA03036381CC +:1033100004EB8703DB68DB6813B139462046984726 +:103320000137D4F89430FFB29B689F42DDD9F00694 +:1033300019D5D4F89000026AC2F30A1702F00F03FD +:1033400002F4F012B2F5802F00F0CC80B2F5402FDD +:1033500009D104EB8303002200F58050DB681B6A6F +:10336000974240F0B2803003D5F8185835D5E903BC +:1033700003D500212046FFF791FEAA0303D50121C2 +:103380002046FFF78BFE6B0303D502212046FFF793 +:1033900085FE2F0303D503212046FFF77FFEE802B9 +:1033A00003D504212046FFF779FEA90203D50521A4 +:1033B0002046FFF773FE6A0203D506212046FFF779 +:1033C0006DFE2B0203D507212046FFF767FEEF01B4 +:1033D00003D508212046FFF761FE700340F1A98064 +:1033E000E90703D500212046FFF7EAFEAA0703D527 +:1033F00001212046FFF7E4FE6B0703D5022120469A +:10340000FFF7DEFE2F0703D503212046FFF7D8FE86 +:10341000EE0603D504212046FFF7D2FEA80603D509 +:1034200005212046FFF7CCFE690603D5062120467C +:10343000FFF7C6FE2A0603D507212046FFF7C0FE88 +:10344000EB0576D520460821BDE8F84FFFF7B8BE5A +:10345000D4F8909000274FF0010AD4F894305FFA26 +:1034600087FB9B689B453FF639AF09EB4B13D3F8BD +:10347000002902F44022B2F5802F24D1D3F800298C +:10348000002A20DAD3F8002942F09042C3F800293C +:10349000D3F80029002AFBDB5946D4F89000FFF747 +:1034A000C7FB22890AFA0BF322EA0303238104EB08 +:1034B0008B03DB689B6813B15946204698475946F1 +:1034C0002046FFF779FB0137C7E7910701D1D0F814 +:1034D0000080072A02F101029CBF03F8018B4FEA2A +:1034E00018283DE704EB830300F58050DA68D2F832 +:1034F00018C0DCF80820DCE9001CA1EB0C0C002152 +:103500008F4208D1DB689B699A683A449A605A688E +:103510003A445A6027E711F0030F01D1D0F8008038 +:103520008C4501F1010184BF02F8018B4FEA182894 +:10353000E6E7BDE8F88F000008B50348FFF788FE0E +:10354000BDE80840FFF784BA044E002008B50348E0 +:10355000FFF77EFEBDE80840FFF77ABAA04E0020D4 +:10356000D0F8903003EB4111D1F8003B43F4001345 +:10357000C1F8003B70470000D0F8903003EB4111D8 +:10358000D1F8003943F40013C1F800397047000046 +:10359000D0F8903003EB4111D1F8003B23F4001335 +:1035A000C1F8003B70470000D0F8903003EB4111A8 +:1035B000D1F8003923F40013C1F800397047000036 +:1035C000090100F16043012203F56143C9B283F8A8 +:1035D000001300F01F039A4043099B0003F160436E +:1035E00003F56143C3F880211A60704730B5043396 +:1035F000039C0172002104FB0325C160C0E906534E +:10360000049B0363059BC0E90000C0E90422C0E9F4 +:103610000842C0E90A11436330BD00000022416A3C +:10362000C260C0E90411C0E90A226FF00101FEF78F +:10363000E9BD0000D0E90432934201D1C2680AB961 +:10364000181D704700207047036919600021C26887 +:103650000132C260C269134482699342036124BF8C +:10366000436A0361FEF7C2BD38B504460D46E36800 +:103670003BB162690020131D1268A3621344E36228 +:1036800007E0237A33B929462046FEF79FFD00283C +:10369000EDDA38BD6FF00100FBE70000C368C269D6 +:1036A000013BC3604369134482699342436124BF71 +:1036B000436A436100238362036B03B11847704779 +:1036C00070B52023044683F31188866A3EB9FFF75C +:1036D000CBFF054618B186F31188284670BDA36A52 +:1036E000E26A13F8015B9342A36202D32046FFF71C +:1036F000D5FF002383F31188EFE700002DE9F84F91 +:1037000004460E46174698464FF0200989F3118863 +:103710000025AA46D4F828B0BBF1000F09D14146D4 +:103720002046FFF7A1FF20B18BF311882846BDE8A2 +:10373000F88FD4E90A12A7EB050B521A934528BF5C +:103740009346BBF1400F1BD9334601F1400251F8BB +:10375000040B914243F8040BF9D1A36A403640357B +:103760004033A362D4E90A239A4202D32046FFF7EA +:1037700095FF8AF31188BD42D8D289F31188C9E731 +:1037800030465A46FDF71EFBA36A5E445D445B4427 +:10379000A362E7E710B5029C0433017204FB032126 +:1037A000C460C0E906130023C0E90A33039B036326 +:1037B000049BC0E90000C0E90422C0E90842436359 +:1037C00010BD0000026A6FF00101C260426AC0E9E8 +:1037D00004220022C0E90A22FEF714BDD0E9042326 +:1037E0009A4201D1C26822B9184650F8043B0B60D6 +:1037F0007047002070470000C3680021C269013390 +:10380000C3604369134482699342436124BF436A9E +:103810004361FEF7EBBC000038B504460D46E36893 +:103820003BB1236900201A1DA262E2691344E362DE +:1038300007E0237A33B929462046FEF7C7FC002863 +:10384000EDDA38BD6FF00100FBE700000369196095 +:10385000C268013AC260C26913448269934203613B +:1038600024BF436A036100238362036B03B11847DB +:103870007047000070B520230D460446114683F3BF +:103880001188866A2EB9FFF7C7FF10B186F3118839 +:1038900070BDA36A1D70A36AE26A01339342A362FA +:1038A00004D3E16920460439FFF7D0FF002080F3FC +:1038B0001188EDE72DE9F84F04460D4690469946EC +:1038C0004FF0200A8AF311880026B346A76A4FB941 +:1038D00049462046FFF7A0FF20B187F31188304604 +:1038E000BDE8F88FD4E90A073A1AA8EB0607974211 +:1038F00028BF1746402F1BD905F1400355F8042B6C +:103900009D4240F8042BF9D1A36A40364033A362AC +:10391000D4E90A239A4204D3E16920460439FFF727 +:1039200095FF8BF311884645D9D28AF31188CDE7EC +:1039300029463A46FDF746FAA36A3D443E443B44D5 +:10394000A362E5E7D0E904239A4217D1C3689BB18B +:10395000836A8BB1043B9B1A0ED01360C368013B92 +:10396000C360C3691A4483699A42026124BF436AEF +:103970000361002383620123184670470023FBE79D +:1039800000F0DAB8034B002258631A610222DA60B1 +:10399000704700BF000C0040014B0022DA60704706 +:1039A000000C0040014B5863704700BF000C004002 +:1039B000014B586A704700BF000C00404B684360E1 +:1039C0008B688360CB68C3600B6943614B6903629A +:1039D0008B6943620B6803607047000008B53C4B7D +:1039E00040F2FF713B48D3F888200A43C3F888208F +:1039F000D3F8882022F4FF6222F00702C3F888205F +:103A0000D3F88820D3F8E0200A43C3F8E020D3F8A5 +:103A100008210A43C3F808212F4AD3F80831114678 +:103A2000FFF7CCFF00F5806002F11C01FFF7C6FF35 +:103A300000F5806002F13801FFF7C0FF00F58060FB +:103A400002F15401FFF7BAFF00F5806002F1700146 +:103A5000FFF7B4FF00F5806002F18C01FFF7AEFFC5 +:103A600000F5806002F1A801FFF7A8FF00F5806073 +:103A700002F1C401FFF7A2FF00F5806002F1E0014E +:103A8000FFF79CFF00F5806002F1FC01FFF796FF55 +:103A900002F58C7100F58060FFF790FF00F000F9EF +:103AA0000E4BD3F8902242F00102C3F89022D3F8D3 +:103AB000942242F00102C3F894220522C3F8982010 +:103AC0004FF06052C3F89C20054AC3F8A02008BDFF +:103AD00000440258000002585843000800ED00E07E +:103AE0001F00080308B500F0F3FAFEF7DFFA0F4BEA +:103AF000D3F8DC2042F04002C3F8DC20D3F80421E4 +:103B000022F04002C3F80421D3F80431084B1A68AC +:103B100042F008021A601A6842F004021A60FEF7C6 +:103B200049FFBDE80840FEF7E9BC00BF0044025869 +:103B30000018024870470000114BD3F8E82042F00B +:103B40000802C3F8E820D3F8102142F00802C3F8B5 +:103B500010210C4AD3F81031D36B43F00803D36320 +:103B6000C722094B9A624FF0FF32DA6200229A6153 +:103B70005A63DA605A6001225A611A60704700BFC6 +:103B8000004402580010005C000C0040094A08B5CF +:103B90001169D3680B40D9B29B076FEA010111612B +:103BA00007D5202383F31188FEF7A0FA002383F3BF +:103BB000118808BD000C0040384B4FF0FF31D3F89E +:103BC0008020C3F88010D3F880200022C3F8802022 +:103BD000D3F88000D3F88400C3F88410D3F88400AD +:103BE000C3F88420D3F88400D86F40F0FF4040F43D +:103BF000FF0040F43F5040F03F00D867D86F20F0FE +:103C0000FF4020F4FF0020F43F5020F03F00D86731 +:103C1000D86FD3F888006FEA40506FEA5050C3F86D +:103C20008800D3F88800C0F30A00C3F88800D3F8EE +:103C30008800D3F89000C3F89010D3F89000C3F830 +:103C40009020D3F89000D3F89400C3F89410D3F8E0 +:103C50009400C3F89420D3F89400D3F89800C3F8E4 +:103C60009810D3F89800C3F89820D3F89800D3F8A8 +:103C70008C00C3F88C10D3F88C00C3F88C20D3F8D8 +:103C80008C00D3F89C00C3F89C10D3F89C10C3F8A8 +:103C90009C20D3F89C3000F0E7B900BF00440258E4 +:103CA000614B0122C3F80821604BD3F8F42042F0A5 +:103CB0000202C3F8F420D3F81C2142F00202C3F838 +:103CC0001C210222D3F81C31594BDA605A68910446 +:103CD000FCD5584A1A6001229A60574ADA600022DD +:103CE0001A614FF440429A61514B9A699204FCD593 +:103CF0001A6842F480721A604C4B1A6F12F4407FBB +:103D000004D04FF480321A6700221A671A6842F012 +:103D100001021A60454B1A685007FCD500221A614F +:103D20001A6912F03802FBD1012119604FF080416D +:103D300059605A67414ADA62414A1A611A6842F484 +:103D400080321A60394B1A689103FCD51A6842F424 +:103D500080521A601A689204FCD53A4A3A499A622B +:103D600000225A6319633949DA6399635A64384AFD +:103D70001A64384ADA621A6842F0A8521A602B4B69 +:103D80001A6802F02852B2F1285FF9D148229A61EC +:103D90004FF48862DA6140221A622F4ADA644FF0E7 +:103DA00080521A652D4A5A652D4A9A6532232D4A4A +:103DB0001360136803F00F03022BFAD11B4B1A692F +:103DC00042F003021A611A6902F03802182AFAD185 +:103DD000D3F8DC2042F00052C3F8DC20D3F80421F1 +:103DE00042F00052C3F80421D3F80421D3F8DC20B8 +:103DF00042F08042C3F8DC20D3F8042142F0804234 +:103E0000C3F80421D3F80421D3F8DC2042F00042A7 +:103E1000C3F8DC20D3F8042142F00042C3F80421A7 +:103E2000D3F80431704700BF0080005100440258AD +:103E30000048025800C000F0020000010000FF012D +:103E40000088900832206000630209011D0204000E +:103E500047040508FD0BFF01200000200010E000D2 +:103E600000010100002000524FF0B04208B5D2F826 +:103E7000883003F00103C2F8883023B1044A136884 +:103E80000BB150689847BDE80840FEF7E1BD00BFA0 +:103E9000544F00204FF0B04208B5D2F8883003F0FC +:103EA0000203C2F8883023B1044A93680BB1D0688A +:103EB0009847BDE80840FEF7CBBD00BF544F002037 +:103EC0004FF0B04208B5D2F8883003F00403C2F8CE +:103ED000883023B1044A13690BB150699847BDE893 +:103EE0000840FEF7B5BD00BF544F00204FF0B04270 +:103EF00008B5D2F8883003F00803C2F8883023B13F +:103F0000044A93690BB1D0699847BDE80840FEF7B1 +:103F10009FBD00BF544F00204FF0B04208B5D2F80B +:103F2000883003F01003C2F8883023B1044A136AC2 +:103F30000BB1506A9847BDE80840FEF789BD00BF45 +:103F4000544F00204FF0B04310B5D3F8884004F42C +:103F50007872C3F88820A30604D5124A936A0BB17D +:103F6000D06A9847600604D50E4A136B0BB1506BAC +:103F70009847210604D50B4A936B0BB1D06B984739 +:103F8000E20504D5074A136C0BB1506C9847A305A2 +:103F900004D5044A936C0BB1D06C9847BDE810402F +:103FA000FEF756BD544F00204FF0B04310B5D3F884 +:103FB000884004F47C42C3F88820620504D5164A80 +:103FC000136D0BB1506D9847230504D5124A936DBC +:103FD0000BB1D06D9847E00404D50F4A136E0BB1B6 +:103FE000506E9847A10404D50B4A936E0BB1D06E66 +:103FF0009847620404D5084A136F0BB1506F984775 +:10400000230404D5044A936F0BB1D06F9847BDE8E1 +:104010001040FEF71DBD00BF544F002008B50348F7 +:10402000FDF708F9BDE80840FEF712BDCC230020DB +:1040300008B50348FDF7FEF8BDE80840FEF708BDE7 +:104040003824002008B50348FDF7F4F8BDE808401F +:10405000FEF7FEBCA424002008B5FFF797FDBDE8DD +:104060000840FEF7F5BC0000062108B50846FFF73A +:10407000A7FA06210720FFF7A3FA06210820FFF779 +:104080009FFA06210920FFF79BFA06210A20FFF775 +:1040900097FA06211720FFF793FA06212820FFF749 +:1040A0008FFA09217A20FFF78BFA07213220FFF7D8 +:1040B00087FA0C212620FFF783FA0C212720FFF72F +:1040C0007FFA0C215220BDE80840FFF779BA0000C2 +:1040D00008B5FFF771FD00F00DF8FDF7BDFAFDF72B +:1040E00095FCFDF767FBFFF725FDBDE80840FFF7EE +:1040F00047BC00000023054A19460133102BC2E9D2 +:10410000001102F10802F8D1704700BF544F00209F +:1041100010B501390244904201D1002005E0037836 +:1041200011F8014FA34201D0181B10BD0130F2E776 +:10413000034611F8012B03F8012B002AF9D170472F +:1041400053544D333248373F3F3F0053544D333281 +:10415000483734332F37353300000000C832002091 +:10416000CC23002038240020A42400200096000046 +:10417000000000000000000000000000000000003F +:104180000000000000000000211600080D160008C5 +:104190004916000835160008411600082D160008BB +:1041A0001916000805160008551600080000000042 +:1041B000311700081D170008591700084517000897 +:1041C000511700083D1700082917000815170008A7 +:1041D000651700080000000001000000000000005A +:1041E0006D61696E0000000069646C65000000008C +:1041F000E841000850310020C832002001000000D2 +:10420000A9200008000000004375626550696C6FCA +:1042100074004A6F65792D424C002553455249413F +:104220004C250000020000000000000051190008A9 +:10423000C119000840004000704B0020804B002056 +:104240000200000000000000030000000000000069 +:10425000091A00080000000010000000904B002028 +:10426000000000000100000000000000044E0020DB +:104270000101020099240008A92300084524000830 +:1042800029240008430000008C4200080902430072 +:10429000020100C0320904000001020201000524ED +:1042A0000010010524010001042402020524060077 +:1042B00001070582030800FF09040100020A00004B +:1042C00000070501024000000705810240000000D0 +:1042D00012000000D8420008120110010200004044 +:1042E000AE2D561000020102030100000403090470 +:1042F00025424F4152442500437562654F72616EFD +:1043000067652D6A6F657900303132333435363761 +:104310003839414243444546000000000000000097 +:104320005D1B0008151E0008C11E0008400040006B +:104330003C4F00203C4F0020010000004C4F00206B +:1043400080000000400100000800000000010000A3 +:1043500000040000080000000000812A00000000A6 +:10436000AAAAAAAA00000024FFFE00000000000084 +:1043700000A00A000001000000000000AAAAAAAAEA +:1043800000000000FFFF000000000000000000002F +:104390001400005400000000AAAAAAAA14000054A5 +:1043A000FFFF0000000000000000000000681A008D +:1043B00000000000AAAA8AAA00541500FFFF00000E +:1043C000000070077700000040810200000000003C +:1043D000AAAAAAAA00410100F7FF0000000000708D +:1043E000070000000000000000000000AAAAAAAA1E +:1043F00000000000FFFF00000000000000000000BF +:104400000000000000000000AAAAAAAA0000000004 +:10441000FFFF00000000000000000000000000009E +:1044200000000000AAAAAAAA00000000FFFF0000E6 +:10443000000000000000000000000000000000007C +:10444000AAAAAAAA00000000FFFF000000000000C6 +:10445000000000000000000000000000AAAAAAAAB4 +:1044600000000000FFFF000000000000000000004E +:104470000000000000000000AAAAAAAA0000000094 +:10448000FFFF00000000000000000000000000002E +:10449000090400000000000000001E0000000000F1 +:1044A000FF00000000000000404100083F00000045 +:1044B000500400004B4100083F000000009600003F +:1044C0000000080096000000000800000400000042 +:1044D000EC420008000000000000000000000000A6 +:0C44E000000000000000000000000000D0 +:00000001FF diff --git a/Tools/bootloaders/CubeOrange-periph-heavy_bl.bin b/Tools/bootloaders/CubeOrange-periph-heavy_bl.bin new file mode 100755 index 00000000000..b8e0bb3b3d5 Binary files /dev/null and b/Tools/bootloaders/CubeOrange-periph-heavy_bl.bin differ diff --git a/Tools/bootloaders/CubeOrange-periph-heavy_bl.hex b/Tools/bootloaders/CubeOrange-periph-heavy_bl.hex new file mode 100644 index 00000000000..ddae0f52348 --- /dev/null +++ b/Tools/bootloaders/CubeOrange-periph-heavy_bl.hex @@ -0,0 +1,1927 @@ +:020000040800F2 +:1000000000060020B5050008ED3100086D3100083C +:10001000C53100086D31000899310008B7050008A6 +:10002000B7050008B7050008B705000841400008FB +:10003000B7050008B7050008B7050008B7050008B0 +:10004000B7050008B7050008B7050008B7050008A0 +:10005000B7050008B7050008C16E0008ED6E00087E +:10006000196F0008456F0008716F0008B705000898 +:10007000B7050008B7050008B7050008B705000870 +:10008000B7050008B7050008B7050008B52D00083A +:10009000DD2D0008C92D0008F12D00089D6F000816 +:1000A000B7050008B7050008B7050008B705000840 +:1000B000B7050008B7050008B7050008B705000830 +:1000C000B7050008B7050008B7050008B705000820 +:1000D000B7050008B7050008B7050008B705000810 +:1000E00001700008B7050008B7050008B70500084B +:1000F000B7050008B7050008B7050008B7050008F0 +:10010000B7050008B705000889700008B7050008A2 +:10011000B7050008B7050008B7050008B7050008CF +:10012000B7050008B7050008B7050008B7050008BF +:10013000B7050008B7050008B7050008B7050008AF +:10014000B7050008B7050008B7050008B70500089F +:10015000B7050008B7050008B7050008B70500088F +:10016000B7050008B7050008B7050008B70500087F +:10017000B7050008E9650008B7050008B7050008DD +:10018000B7050008B705000875700008B705000836 +:10019000B7050008B7050008B7050008B70500084F +:1001A000B7050008B7050008B7050008B70500083F +:1001B000B7050008B7050008B7050008B70500082F +:1001C000B7050008B7050008B7050008B70500081F +:1001D000B7050008D5650008B7050008B705000891 +:1001E000B7050008B7050008B7050008B7050008FF +:1001F000B7050008B7050008B7050008B7050008EF +:10020000B7050008B7050008B7050008B7050008DE +:10021000B7050008B7050008B7050008B7050008CE +:10022000B7050008B7050008B7050008B7050008BE +:10023000B7050008B7050008B7050008B7050008AE +:10024000B7050008B7050008B7050008B70500089E +:10025000B7050008B7050008B7050008B70500088E +:10026000B7050008B7050008B7050008B70500087E +:10027000B7050008B7050008B7050008B70500086E +:10028000B7050008B7050008B7050008B70500085E +:10029000B7050008B7050008B7050008B70500084E +:1002A000391A0008000000000000000000000000F3 +:1002B00053B94AB9002908BF00281CBF4FF0FF31CD +:1002C0004FF0FF3000F074B9ADF1080C6DE904CEC9 +:1002D00000F006F8DDF804E0DDE9022304B0704721 +:1002E0002DE9F047089D04468E46002B4DD18A42E9 +:1002F000944669D9B2FA82F252B101FA02F3C2F11C +:10030000200120FA01F10CFA02FC41EA030E9440AC +:100310004FEA1C48210CBEFBF8F61FFA8CF708FBCD +:1003200016E341EA034306FB07F199420AD91CEBA5 +:10033000030306F1FF3080F01F81994240F21C81D7 +:10034000023E63445B1AA4B2B3FBF8F008FB10331F +:1003500044EA034400FB07F7A7420AD91CEB040454 +:1003600000F1FF3380F00A81A74240F20781644424 +:10037000023840EA0640E41B00261DB1D4400023A9 +:10038000C5E900433146BDE8F0878B4209D9002D0D +:1003900000F0EF800026C5E9000130463146BDE897 +:1003A000F087B3FA83F6002E4AD18B4202D3824201 +:1003B00000F2F980841A61EB030301209E46002DB0 +:1003C000E0D0C5E9004EDDE702B9FFDEB2FA82F205 +:1003D000002A40F09280A1EB0C014FEA1C471FFA63 +:1003E0008CFE0126200CB1FBF7F307FB131140EA4A +:1003F00001410EFB03F0884208D91CEB010103F117 +:10040000FF3802D2884200F2CB804346091AA4B2D8 +:10041000B1FBF7F007FB101144EA01440EFB00FEAC +:10042000A64508D91CEB040400F1FF3102D2A64511 +:1004300000F2BB800846A4EB0E0440EA03409CE7B0 +:10044000C6F12007B34022FA07FC4CEA030C20FA5D +:1004500007F401FA06F31C43F9404FEA1C4900FA7D +:1004600006F3B1FBF9F8200C1FFA8CFE09FB1811FA +:1004700040EA014108FB0EF0884202FA06F20BD96D +:100480001CEB010108F1FF3A80F08880884240F2BD +:100490008580A8F102086144091AA4B2B1FBF9F001 +:1004A00009FB101144EA014100FB0EFE8E4508D9FC +:1004B0001CEB010100F1FF346CD28E456AD9023881 +:1004C000614440EA0840A0FB0294A1EB0E01A14266 +:1004D000C846A64656D353D05DB1B3EB080261EBD4 +:1004E0000E0101FA07F722FA06F3F1401F43C5E9AE +:1004F000007100263146BDE8F087C2F12003D840E4 +:100500000CFA02FC21FA03F3914001434FEA1C4725 +:100510001FFA8CFEB3FBF7F007FB10360B0C43EA17 +:10052000064300FB0EF69E4204FA02F408D91CEBC7 +:10053000030300F1FF382FD29E422DD902386344C5 +:100540009B1B89B2B3FBF7F607FB163341EA034165 +:1005500006FB0EF38B4208D91CEB010106F1FF38B4 +:1005600016D28B4214D9023E6144C91A46EA0046AB +:1005700038E72E46284605E70646E3E61846F8E63D +:100580004B45A9D2B9EB020864EB0C0E0138A3E786 +:100590004646EAE7204694E74046D1E7D0467BE767 +:1005A000023B614432E7304609E76444023842E7DF +:1005B000704700BF02E000F000F8FEE772B63A486C +:1005C00080F30888394880F3098839484EF6085185 +:1005D000CEF20001086040F20000CCF200004EF6BE +:1005E0003471CEF200010860BFF34F8FBFF36F8FFD +:1005F00040F20000C0F2F0004EF68851CEF2000149 +:100600000860BFF34F8FBFF36F8F4FF00000E1EE34 +:10061000100A4EF63C71CEF200010860062080F30D +:100620001488BFF36F8F05F0E7FA05F089FA06F03A +:100630000DFA4FF055301F491B4A91423CBF41F81B +:10064000040BFAE71C49194A91423CBF41F8040BDC +:10065000FAE71A491A4A1B4B9A423EBF51F8040B5B +:1006600042F8040BF8E700201749184A91423CBFB2 +:1006700041F8040BFAE705F0A1FA06F05FFA144C12 +:10068000144DAC4203DA54F8041B8847F9E700F034 +:1006900041F8114C114DAC4203DA54F8041B884761 +:1006A000F9E705F089BA00000006002000220020CA +:1006B00000000008000000200006002088770008E5 +:1006C00000220020C8220020C82200202082002012 +:1006D000A0020008A4020008A4020008A402000866 +:1006E0002DE9F04F2DED108AC1F80CD0D0F80CD0C8 +:1006F000BDEC108ABDE8F08F002383F311882846F3 +:10070000A047002004F066FDFEE704F0D5FC00DF02 +:10071000FEE70000F8B501F0CFFA30B1264B002219 +:100720000E211A725A729972DA7205F08DF9074623 +:1007300005F0FCF90546A0BB204B9F4231D00133A8 +:100740009F4231D027F0FF021D4B9A422FD12E46F7 +:1007500042F21074F8B200F09FFD00F0A7FF08B15C +:100760000024264600F09EFD08B90646044635B131 +:10077000144B9F4203D0002405F0D0F926460020F8 +:1007800005F06CF90EB100F065F801F019FB00F00E +:10079000B1FF01F0D7F9204600F012F900F05AF845 +:1007A000F9E72E460024D8E704460126D5E7064699 +:1007B00041F28834D1E700BF00220020010007B0D9 +:1007C000000008B0263A09B008B501F087F9A0F199 +:1007D00020035842584108BD07B541F212030221D7 +:1007E00001A8ADF8043001F097F903B05DF804FBFF +:1007F000202310B583F311881248C3680BB104F0AD +:100800006FFD0023104A4FF47A710E4804F02CFD5E +:10081000002383F311880D4C236813B12368013B37 +:100820002360636813B16368013B6360084B1B7806 +:1008300033B9636823B9022001F044FA32236360BC +:1008400010BD00BFC8220020F1070008E4230020EB +:10085000DC220020F8B5534B534A1C46196801317D +:1008600000F09F8004339342F8D162684F4B9A4264 +:1008700040F297804E4B9B6803F1006303F5003311 +:100880009A4280F08E8005F01DF905F02FF90020C6 +:1008900001F072F90220474B187001F011FA464B33 +:1008A0000021D3F8E820C3F8E810D3F81021C3F8EA +:1008B0001011D3F81021D3F8EC20C3F8EC10D3F8C2 +:1008C0001421C3F81411D3F81421D3F8F020C3F87D +:1008D000F010D3F81821C3F81811D3F81821D3F861 +:1008E000802042F00062C3F88020D3F8802022F0FC +:1008F0000062C3F88020D3F88020D3F8802042F033 +:100900000072C3F88020D3F8802022F00072C3F870 +:100910008020D3F8803072B64FF0E023C3F8084D42 +:10092000D4E90004BFF34F8FBFF36F8F234AC2F89F +:100930008410BFF34F8F536923F480335361BFF3A7 +:100940004F8FD2F8803043F6E076C3F3C905C3F386 +:100950004E335B0103EA060C29464CEA81770139E4 +:10096000C2F87472F9D2203B13F1200FF2D1BFF319 +:100970004F8FBFF36F8FBFF34F8FBFF36F8F5369ED +:1009800023F4003353610023C2F85032BFF34F8F7A +:10099000BFF36F8F202383F31188854680F3088887 +:1009A0002047F8BD0000020820000208FFFF0108F0 +:1009B00000220020DC2200200044025800ED00E06C +:1009C0002DE9F04F93B0AC4B2022FF2100900AA8F4 +:1009D0009D6801F09FF9A94A1378A3B90121A8489D +:1009E0001170C360202383F31188C3680BB104F036 +:1009F00077FC0023A34A4FF47A71A14804F034FC39 +:100A0000002383F31188009B9F4A03B113600023E6 +:100A10009E49009C98469B461E469A460B70536022 +:100A2000012001F04DF924B1974B1B68002B00F019 +:100A30001C82002001F052F80390039B002B01DA86 +:100A400000F0A8FE039B002BEDDB012001F036F93E +:100A5000039B213B162BE3D801A252F823F000BFE1 +:100A6000BD0A0008E50A0008790B0008210A000801 +:100A7000210A0008210A00080D0C0008DF0D0008FB +:100A8000F90C00085B0D0008830D0008A90D000893 +:100A9000210A0008BB0D0008210A00082D0E0008DD +:100AA0005D0B0008210A0008710E0008C90A000841 +:100AB0005D0B0008210A00085B0D00080220FFF70B +:100AC00083FE002840F0FB81009B022105A8B8F1BD +:100AD000000F08BF1C4641F21233ADF8143001F08C +:100AE0001BF89DE74FF47A7000F0F8FF071EEBDB70 +:100AF0000220FFF769FE0028E6D0013F052F00F233 +:100B0000E081DFE807F0030A0D1013360523042106 +:100B100005A8059301F000F817E004215648F9E70D +:100B200004215B48F6E704215A48F3E74FF01C091B +:100B3000484609F1040901F021F80421059005A8AF +:100B400000F0EAFFB9F12C0FF2D101204FF0000ABA +:100B500000FA07F747EA0B0B5FFA8BFB01F026F967 +:100B600026B10BF00B030B2B08BF0024FFF734FE5C +:100B700056E704214848CDE7002EA5D00BF00B0323 +:100B80000B2BA1D10220FFF71FFE074600289BD0A8 +:100B900001203E4E00F0F0FF4FF0000802203070C0 +:100BA00001F08EF85FFA88F9484600F0F5FF044638 +:100BB00090B1484608F1010800F0FEFF0028F1D18D +:100BC000B846044641F21213022105A83E46ADF88C +:100BD000143000F0A1FF23E70123254602203370E3 +:100BE00001F06CF8244B9B68AB4207D9284600F013 +:100BF000C5FF013040F068810435F3E70025234B41 +:100C0000B8463E461D70204B5D60A7E7002E3FF4BE +:100C10005BAF0BF00B030B2B7FF456AF02201B4B8B +:100C2000187001F04DF8322000F058FFB0F10009C3 +:100C3000FFF64AAF19F003077FF446AF0E4A09EBFF +:100C40000503926893423FF63FAFB9F5807F3FF7C7 +:100C50003BAF124BB945019322DD4FF47A7000F09F +:100C60003DFF0390039A002AFFF62EAF039A013747 +:100C7000019B03F8012BEDE700220020E023002078 +:100C8000C8220020F1070008E4230020DC22002015 +:100C900004220020082200200C220020E022002054 +:100CA000C820FFF791FD074600283FF40DAF1F2D28 +:100CB00011D8C5F120020AAB25F0030084494A454A +:100CC000184428BF4A46019200F0FEFF019AFF2116 +:100CD0007F4801F01FF84FEAA903C9F387027C4956 +:100CE0002846019301F01EF8064600283FF46AAF3B +:100CF000019B05EB830531E70220FFF765FD002826 +:100D00003FF4E2AE00F074FF00283FF4DDAE0027B0 +:100D1000B946704B9B68BB4218D91F2F11D80A9B4C +:100D200001330ED027F0030312AA134453F8203CDA +:100D300005934846042205A9043702F065FA814666 +:100D4000E7E7384600F01AFF0590F2E7CDF8149077 +:100D5000042105A800F0E0FE00E70023642104A8B8 +:100D6000049300F0CFFE00287FF4AEAE0220FFF720 +:100D70002BFD00283FF4A8AE049800F02FFF05904B +:100D8000E6E70023642104A8049300F0BBFE0028DA +:100D90007FF49AAE0220FFF717FD00283FF494AECF +:100DA000049800F01DFFEAE70220FFF70DFD002880 +:100DB0003FF48AAE00F02CFFE1E70220FFF704FDCC +:100DC00000283FF481AE05A9142000F027FF074654 +:100DD0000421049004A800F09FFE3946B9E73220B0 +:100DE00000F07CFE071EFFF66FAEBB077FF46CAE13 +:100DF000384A07EB0A03926893423FF665AE022039 +:100E0000FFF7E2FC00283FF45FAE27F003075744EA +:100E1000BA453FF4A3AE50460AF1040A00F0AEFE14 +:100E20000421059005A800F077FEF1E74FF47A70F1 +:100E3000FFF7CAFC00283FF447AE00F0D9FE0028B7 +:100E400044D00A9B01330BD008220AA9002000F0ED +:100E500069FF00283AD02022FF210AA800F05AFF9B +:100E6000FFF7BAFC1C4804F0BBF913B0BDE8F08FE3 +:100E7000002E3FF429AE0BF00B030B2B7FF424AEB6 +:100E80000023642105A8059300F03CFE07460028D6 +:100E90007FF41AAE0220FFF797FC814600283FF44A +:100EA00013AEFFF799FC41F2883004F099F90598E8 +:100EB00000F0C0FF4E463C4600F078FFB0E5064625 +:100EC0004CE64FF0000AFFE5B8467BE6374679E688 +:100ED000E022002000220020A0860100094A49F2F9 +:100EE0006900136899B21B0C00FB013344F2506196 +:100EF0001360054B186882B2000C01FB02001860F9 +:100F000080B27047142200201022002000211022FD +:100F100010B5044600F0FEFE034B03CB2060616079 +:100F20001868A06010BD00BF00E8F11F2DE9F04374 +:100F3000224DBBB002F062F940F2ED22AB68C31A59 +:100F4000934232D906AF2B4628220021A8603846AA +:100F500002F032FE05F10E0000F0D4FE0026044639 +:100F60005FFA80F905F10E08F3B2F100994501F13D +:100F7000280107D908EB060308223846013602F09B +:100F80001BFEF1E7082301220534297B0C48A4B29B +:100F9000CDE902320B4B01933023CDE90474009369 +:100FA00004A3D3E9002302F01FFC3BB0BDE8F083AB +:100FB000AFF3008078F6339F93CACD8D905D00200B +:100FC000043400209D5D002070B50D4614461E4679 +:100FD00002F0A0FB50B9022E10D1012C0ED112A3A9 +:100FE000D3E900230120C5E9002307E0282C10D015 +:100FF00005D8012C09D0052C0FD0002070BD302C55 +:10100000FBD10BA3D3E90023ECE70BA3D3E9002327 +:10101000E8E70BA3D3E90023E4E70BA3D3E900231C +:10102000E0E700BFAFF30080401DA12026812A0B1E +:1010300078F6339F93CACD8D9E6AC421818A46EE8D +:1010400026417272DF25D7B7F017304A39059E5610 +:1010500013B504460846202200212346019002F0E1 +:10106000ABFD227923460198032A4FF0200128BFC7 +:10107000032203F8042F022202F09EFD6279234628 +:101080000198072A4FF0220128BF072203F8052FF5 +:10109000032202F091FDA27923460198072A4FF01E +:1010A000250128BF072203F8062F032202F084FD42 +:1010B000019804F108031022282102F07DFD382058 +:1010C00002B010BD2DE9F04FADF5017D0F460021B6 +:1010D00040F275120EAE804622A8219100F01AFE51 +:1010E00048220021304600F015FE21AD02F086F8BE +:1010F0004FF47A72554B0DF15A09B0FBF2F01860BB +:1011000093E80700012386E807000DF15A003382B7 +:10111000FFF7FCFE47F605034D49338406AB18463E +:1011200006F0A2F81F2229463064304686F83C209B +:10113000FFF78EFF12AB044601460822284602F054 +:101140003BFD08220DF149032846A11804F1880A45 +:1011500002F032FD0DF14A03082204F11001284685 +:1011600004F5847B02F028FD13AB202204F1180162 +:10117000284602F021FD14AB402204F13801284634 +:1011800002F01AFD16AB082204F17801284602F09D +:1011900013FD0DF15903082204F18001284602F0E5 +:1011A0000BFD51460AF1080A4B460822284609F170 +:1011B000010902F001FDD345F3D104F588744FF025 +:1011C00000091BAB08225946284602F0F5FC96F8A8 +:1011D00034304B450AD9B36B2146082228464B448C +:1011E000083409F1010902F0E7FCF0E74FF00009CB +:1011F00096F83C3004EBC9014B4508D9336C082202 +:1012000028464B4409F1010902F0D6FCF0E700231F +:10121000073140460393C1F3CF01BB7E029307F130 +:10122000190301930123CDE904510093F97E05A32D +:10123000D3E9002302F0D8FA0DF5017DBDE8F08F67 +:10124000AFF300809E6AC421818A46EEEC23002021 +:1012500098720008F8B50E4C02260E4FA4F5805384 +:1012600043F8307C237E3BB965692DB1284601F0F7 +:1012700041FE284605F062FF2046A4F5A55401F082 +:1012800039FE012EA4F1100400D1F8BD0126E5E7D6 +:1012900010590020C8730008014B1870704700BF38 +:1012A000F8230020334BF0B51C7B85B034B1324BB2 +:1012B0000E221A810024204605B0F0BD2F4A02AB51 +:1012C0001068516803C308232D492E480DEB030213 +:1012D00005F05CFF054630B9274B0A222A481A81DF +:1012E00001F090FDE6E70169B1F5F01F06D9224B48 +:1012F0000B2226481A8101F085FDDCE7438BB3F50C +:10130000AF6F09D01C4A0C21214811814FF4AF6204 +:10131000194601F077FDCEE71E4A024402F11003A0 +:10132000994204D2144B10221B481A81E3E710396A +:1013300020468E1A134901F067FF05F11801074690 +:101340003246204601F060FFAB689F4202D1EB6855 +:1013500098420AD0084B0D221A813B4600900F4854 +:10136000D5E9021201F04EFDA4E70D48012401F079 +:1013700049FDA0E7905D0020EC23002049730008A0 +:10138000DCFF1D0000000208B8720008C4720008EB +:10139000D67200080800FEF7F47200081173000806 +:1013A0003A7300082DE9F04FADB080460C4606AF09 +:1013B00002F0B0F90546002859D1237E022B1BD13B +:1013C000E38A012B18D101F019FF0646FFF786FDCD +:1013D00003464FF4C87006F51676DFF8CC92B3FBDF +:1013E000F0F202FB103316FA83F3C9F80030E37E03 +:1013F00033B9A84B00221A709C37BD46BDE8F08F68 +:10140000A38AEEB20135013BB3420BD93B1DE90083 +:10141000082220461E4401F0F8010023009602F045 +:101420008FFAEDE707F11400FFF770FD324607F180 +:101430001401381D05F09AFE0028DAD10F2E08D8C5 +:10144000944B1E70D9F80030A3F51673C9F800301C +:10145000D2E7FB1CF87001460722009303462046A2 +:1014600002F06EFAF978404602F04CF9C4E7E38ADC +:10147000282B26D010D8012B1ED0052BBCD1BFF3B2 +:101480004F8F8549854BCA6802F4E0621343CB60F5 +:10149000BFF34F8F00BFFDE7302BADD1637EE94630 +:1014A0007F4D01336A7BDBB2934203D1E27E2B7B1B +:1014B0009A4265D0CD469FE721464046FFF702FE9F +:1014C0009AE7A38A013B9BB2C92B95D8744D2E7B1A +:1014D00026BB05F10C030822314600933346204613 +:1014E00002F02EFA731CF2B2D9001E46A38A013B09 +:1014F0009A4205DA0E3200232A4400920822EEE7CF +:1015000000230022C5E900230023AB6085F8D73013 +:10151000C5F8D8302B7B0BB9E37E2B73002507F180 +:1015200014093B1D082229464846FD60C7E90155BC +:1015300002F042FB3B7A05F1010AAB424FEACA06D0 +:1015400008D9FB680822314648462B44554602F02C +:1015500033FBEFE7C6F3CF060023E17E1934039394 +:101560004046CDE9049663780194029328230093C2 +:1015700046A3D3E9002302F037F9FFF7D7FC3BE796 +:101580004FF0000807F1140310222046A7F814803A +:1015900041460093012302F0D3F9A68A023EB6B277 +:1015A000F31C9B109B000733DB08A9EBC3039D468C +:1015B0000DF1180A1FFA88F34FEAC801B34201F18E +:1015C00010010AD20AEB08030822204608F101089C +:1015D0000093002302F0B4F9ECE795F8D70000F08F +:1015E000DBFAD5F8D83004461BB995F8D70000F0DF +:1015F000E3FAD5F8D83033449C4204D295F8D700AA +:10160000013000F0D9FA4FEA960B4FF000081FFAAC +:1016100088F18B45D5E9003209D90AEB880101220E +:1016200003EB880008F1010800F07CFBEFE7F318FA +:1016300095F8D70042F10002C5E90032D5F8D8305C +:1016400006EB0308C5F8D88000F0A6FA804509D358 +:1016500095F8D730D5F8D8000133001B85F8D7307E +:10166000C5F8D800FF2E08D800232B7300F0C0FA6D +:10167000FFF718FE08B1FFF7EDF82B68094A9B0A3F +:10168000013313810023AB6014E700BF264172725F +:10169000DF25D7B7FD33002000ED00E00400FA0598 +:1016A000905D0020EC2300200034002010B54FF0A6 +:1016B00040540C4B22689A4212D1627D0A4B0B486F +:1016C0001A70C922237D0E30094900F8023C00F04F +:1016D000FBFAE0220021204600F01CFB012010BD97 +:1016E0000020FCE79AAD44C5F8230020905D00205F +:1016F0001600003037B502231D4C1E4D0122204636 +:101700001D496B71236804F580545B689847D4F8D1 +:10171000B034012218495B6804F5966098470023AD +:1017200016494FF480520193154B16480093164BFF +:1017300001F0C2FF154B197811B1124801F0E2FF18 +:1017400001F05CFD0446FFF7C9FB4FF4C873B0FB22 +:10175000F3F202FB130304F5167010FA83F00C4B3E +:10176000186004F0E3F908B10F232B8103B030BDFA +:1017700030340020EC23002040420F00FC230020E6 +:10178000C90F000804340020A5130008F823002026 +:10179000003400202DE9F04F9C4D2DED028B93B0CD +:1017A000DFF890A29A4F284602F082F803460028FC +:1017B0003DD00024974E0E94A046ADF84440A1467B +:1017C000CDE90F44027B8DF844200FAA9968406848 +:1017D00003C21B6843F000430E93336804F22C5499 +:1017E000D3F810B001F00CFD10EB0A02CDF8009018 +:1017F000304606F5A55641F100030EA9D84740F63C +:1018000058230028C8BF48F0010810369C42E4D194 +:10181000B8F1000F05D0284602F04EF887F8009086 +:10182000C1E73B78072B00F2E08001333B700023D7 +:101830000DF12C084FF0010A0A93ADF834300B93E8 +:10184000C8F804309FED6B8B0026724C3746236836 +:101850004FF0000B0DF11D0207A920468DF81CA0CA +:101860008DF81DB08DED008BD3F808905B46C8470E +:101870009DF81C90B9F1000F1ED0102259460EA8F9 +:1018800000F048FA236808AA0AA95F6920460DF10A +:101890001E03B8470FAB4F4698E8030083E80300E8 +:1018A0009DF834300EA928468DF844300A9B0E93DB +:1018B000DDE9082302F0C8F906F22C5640F6582359 +:1018C00004F5A5549E4204F11004C0D1002FBBD1F1 +:1018D000284601F01FFF002840D14F4E01F08EFC3A +:1018E000336898423AD301F089FC0446FFF7F6FAD0 +:1018F0004FF4C87304F516748DF82870B0FBF3F23A +:1019000002FB130314FA83F33360444E377817B99C +:1019100001238DF82830C7F110040EA8FFF7F6FA5E +:101920000EABE4B20DF12900D919062C28BF06240C +:101930002246013400F0C8F90AABE4B2284603930A +:10194000182304940293364B0193012300932BA395 +:10195000D3E9002301F0E0FE0023337001F04EFCD8 +:10196000304A314C1368C31AB3F57A7F30D3106014 +:1019700001F046FC02460B46284601F0A7FF284628 +:1019800001F0C8FE20B3237B0EAF284E002B14BFFE +:1019900003230223737101F031FC4FF47A7339464B +:1019A000B0FBF3F030603046FFF752FB18230730EE +:1019B00002931F4BC0F3CF00019340F25513CDE9C2 +:1019C0000370009328460FA3D3E9002301F0A4FE7F +:1019D000237B2BB1FFF7AAFA237B002B7FF4E0AE29 +:1019E00013B0BDEC028BBDE8F08F284601F064FF18 +:1019F0001DE700BF0000000000000000401DA12006 +:101A000026812A0BF1C6A7C1D068080F0434002034 +:101A1000755E00203034002000340020FD330020AB +:101A2000FC330020705E0020905D0020EC2300203D +:101A3000745E002040420F0008B5064800F014FD17 +:101A4000054800F011FD054A05490020BDE80840A1 +:101A500005F06EBB30340020E0480020D05E00204E +:101A600055120008F7B50C46184E4FF47A7105462A +:101A700002FB01F396F90020501C0BD114482946B3 +:101A800001930268176A2246B8478442019B03D13A +:101A9000002310E0002AF1D096F90020511C01D05B +:101AA000012A0DD10B4829460268166A2246B04722 +:101AB000844205D10123084A0120137003B0F0BD10 +:101AC0004FF4FA7003F08CFB0020F7E71822002097 +:101AD000F8640020D45E0020BC5E0020002307B51F +:101AE000024601210DF107008DF80730FFF7BAFF1C +:101AF00020B19DF8070003B05DF804FB4FF0FF3004 +:101B0000F9E700000A46042108B5FFF7ABFF80F0B3 +:101B10000100C0B2404208BD074B0A4630B41978F4 +:101B2000064B53F82140014623682046DD69044BEB +:101B3000AC4630BC604700BFBC5E0020707300083C +:101B4000A086010070B50A4E00240A4D03F0F6FD90 +:101B5000308028683388834208D903F0EBFD2B6876 +:101B600004440133B4F5003F2B60F2D370BD00BFD5 +:101B7000BE5E0020785E002003F0BEBE00F1006073 +:101B800000F500300068704700F10060920000F539 +:101B9000003003F035BE0000054B1A68054B1B886A +:101BA0009B1A834202D9104403F0C4BD0020704741 +:101BB000785E0020BE5E002038B5074D04462868D8 +:101BC000204403F0BDFD28B928682044BDE8384012 +:101BD00003F0C8BD38BD00BF785E0020002070470C +:101BE00000F1FF5000F58F10D0F80008704700009A +:101BF000064991F8243033B100230822086A81F89D +:101C00002430FFF7C1BF0120704700BF7C5E002079 +:101C1000014B1868704700BF0010005C244BF0B502 +:101C20001A680446234BC2F30B06120C1F8858682F +:101C3000BE4293F9085028D09F89BE4206D10120A8 +:101C40000C2505FB0033586893F9085041F2010355 +:101C50009A421CD041F203039A421AD042F2010385 +:101C60009A4218D042F203039A4208BF5625621ED8 +:101C70000B46441E0A4493420FD214F9016F581CBC +:101C80006EB1034600F8016CF5E70020D8E75A254D +:101C9000EDE75925EBE75825E9E7184605E02C2440 +:101CA00082421C7001D9981C5D70401AF0BD00BFC3 +:101CB0000010005C1C2200200020704770470000CC +:101CC0007047000070470000002310B5934203D016 +:101CD000CC5CC4540133F9E710BD0000013810B5E5 +:101CE00010F9013F3BB191F900409C4203D11AB178 +:101CF0000131013AF4E71AB191F90020981A10BDA8 +:101D00001046FCE703460246D01A12F9011B0029CF +:101D1000FAD1704702440346934202D003F8011BF4 +:101D2000FAE770472DE9F8431F4D144607468846E9 +:101D300095F8242052BBDFF870909CB395F82430BE +:101D40002BB92022FF2148462F62FFF7E3FF95F8C9 +:101D500024004146C0F1080205EB8000A24228BFE2 +:101D60002246D6B29200FFF7AFFF95F82430A41BAD +:101D700017441E449044E4B2F6B2082E85F824605D +:101D8000DBD1FFF735FF0028D7D108E02B6A03EB42 +:101D900082038342CFD0FFF72BFF0028CBD1002056 +:101DA000BDE8F8830120FBE77C5E0020024B1A7837 +:101DB000024B1A70704700BFBC5E00201822002042 +:101DC00038B5164C164D204602F000FD2946204637 +:101DD00002F028FD2D681348D5F89020D2F8043879 +:101DE00043F00203C2F8043803F0FAF90E4928461A +:101DF00002F026FED5F890200C48D2F804380C49A1 +:101E0000A04223F00203C2F804384FF4E1330B6020 +:101E100003D0BDE8384002F037BC38BDF86400207C +:101E20001075000840420F0018750008D45E0020AD +:101E3000A45E002038B50B4B04461A780A4B53F8C1 +:101E400022500A4B9D420CD0094B00211822184603 +:101E5000FFF760FF046001462846BDE8384002F005 +:101E600013BC38BDBC5E002070730008F86400200D +:101E7000A45E0020202383F3118862B6704700001F +:101E8000002383F3118862B6704700000120704779 +:101E9000704700007047000010B4134602681468D1 +:101EA0000022A4465DF8044B6047000000F5805016 +:101EB00090F859047047000000F5805090F85204E3 +:101EC0007047000000F5805090F9580470470000FA +:101ED0004E20704700F5805208B5FFF7CBFFD2F8CF +:101EE0009834D2F894041844D2F890341844D2F8B4 +:101EF00078341844D2F888341844D2F8843418441A +:101F0000FFF7BEFF08BD00002DE9F74F0C4600F5B6 +:101F100080511F46054691F852349046BDF83090E6 +:101F20009BB1D1F874340133C1F8743423689A003A +:101F300006D4237B082B0BD9627B0AB10F2B07D960 +:101F4000D1F878340133C1F878344FF0FF300FE026 +:101F5000FFF790FFEB6AD3F8C42012F4001A0AD0FE +:101F6000D1F87C3400200133C1F87C34FFF788FFBE +:101F700003B0BDE8F08F22684FF0480BD3F8C4607F +:101F8000002A6B6AC6F30446B4BF42F08042920452 +:101F90001BFB063BCBF8002023685B004FEA06637F +:101FA00044BF42F00052CBF80020227B43EA0243B8 +:101FB0007201CBF80430607B18B343F44013CBF8C4 +:101FC0000430D1F8A4340133C1F8A434AB1803F5BC +:101FD0008353197B41F020011973207B019200F09B +:101FE0006DFF0330019A80105FFA8AF30AF1010A4B +:101FF00083420DDA04EB83010BEB8303496899609C +:10200000F2E7AB1803F58353197B60F34511E3E75F +:102010000121EB6A04F10C00B140C3F8D010AB18F9 +:10202000214603F58253C3E9048705EB461303F504 +:102030008253183351F804CB814243F804CBF9D1D1 +:1020400009882A442846198041F26803D65002F5CF +:10205000805209F0030392F86C1043F0100321F052 +:102060001F010B43214682F86C304246FFF708FF00 +:102070003B46CDF8309003B0BDE8F04F00F0E4BE31 +:102080002DE9F04700F58056044696F85254002D8D +:1020900040F00181037C032B40F092802B462846C0 +:1020A0002F465FFA83FC944510DA01EBCC0E51F811 +:1020B0003CC0BCF1000F04DBDEF804C0BCF1000F33 +:1020C00002DB01370133ECE70130FBE7FFF7D2FE1B +:1020D000E36AF0B9D3F8800040F00200C3F8800052 +:1020E0004E23E06A002F6ED1D0F8803043F0010318 +:1020F000C0F88030694B6A4A1B6803F1805303F5CE +:102100002C539B009342A36240F2AF80654801F0DC +:102110006FF84D2842D8DFF884814FEA004EDFF88F +:102120008891D8F800C04EEA8C0EC3F884E00CF118 +:10213000805303F52C539B00636100EB0C03D4F830 +:102140002CC0C8F80030C0F14E03DCF8800040F02D +:102150003000CCF880004FF0000CD4F81480E64634 +:102160005FFA8CF08242BCDD01EBC00A51F830000E +:10217000002810DBDAF804A0BAF1000F0BDA09EA44 +:1021800000400AF07F0A40EA0A0040F0084048F8A0 +:102190002E000EF1010E0CF1010CE1E79A6922F01C +:1021A00001029A6101F02AF80646E36A9B69D907A1 +:1021B00004D501F023F8831BFA2BF6D9FFF760FE54 +:1021C0002846BDE8F087B7EB530F3DD2DFF8CCE0EF +:1021D0004FEA074CDEF800304CEA830CC0F888C0A8 +:1021E00003F1805003EB4703002700F52C50CEF895 +:1021F0000030BC468000A061E06AD0F8803043F037 +:102200000C03C0F88030D4F818E0FBB29A427FF794 +:1022100071AF51F8330001EBC3080028D8F804303F +:1022200001DB002B0EDB20F0604023F0604340F028 +:10223000005043F000434EF83C000EEBCC000CF194 +:10224000010C43600137E0E7836923F001038361F8 +:1022500000F0D4FF0646E36A9B69DA07AED500F0CA +:10226000CDFF831BFA2BF6D9A8E7E26A936923F026 +:102270000103936100F0C2FF0746E36A9B69DB0735 +:1022800005D500F0BBFFC31BFA2BF6D996E7012555 +:1022900086F8525492E7002592E700BFCC5E0020FA +:1022A000FCB50040787300080000FF0713B500F587 +:1022B00080540191606C00F053FE1F280AD920223F +:1022C0000199606C00F0C2FEA0F120035842584111 +:1022D00002B010BD0020FBE700F5805008B5FFF705 +:1022E000C9FD406C00F010FEBDE80840FFF7C8BD16 +:1022F00000220260828142608260704700220023D7 +:1023000010B5C0E90023002304460C3020F8043C3B +:10231000FFF7EEFF204610BD2DE9F047074688B0D5 +:102320009A46884607F5805468469146FFF7A2FD15 +:10233000FFF7E4FF606C00F0F9FD1F282DD9202283 +:102340006946606C00F006FF202826D194F85234CC +:102350001BB303AD444605AB2E46083403CE9E4264 +:1023600044F8080C44F8041C3546F5D13068414661 +:1023700020603846B388A380DDE90023C9E9002343 +:10238000BDF808304A46AAF80030FFF779FD5346F9 +:1023900008B0BDE8F04700F045BD0020FFF770FD34 +:1023A00008B0BDE8F08700002DE9F84F002306468D +:1023B00000F58154054688461034C0E90133274BA7 +:1023C00046F8303B374638462037FFF797FFA7429D +:1023D000F9D105F580544FF4805305F5A3594FF01A +:1023E000000A26630026676405F5835709F1100982 +:1023F0004FF0000B1037E663C4E90D36012384F873 +:10240000403084F84830A7F11800203747E910AB76 +:10241000FFF76EFF47F8286C4F45F4D1B8F1010F74 +:1024200084F85884A4F85A64A4F85C64A4F85E6440 +:1024300084F86064A4F86264A4F86464A4F8666430 +:1024400084F8686402D9064800F0D2FE054B28469D +:1024500053F82830EB62BDE8F88F00BFC87300085E +:102460009C730008B8730008044B10B51978044633 +:102470004A1C1A70FFF798FF204610BDC95E002065 +:102480002DE9F04700295FD0304F3148B7FBF1F517 +:1024900081428CBF0A201120431EB5FBF0FC00FBDB +:1024A0001C50DCB220B1022B1846F5D8002037E0D2 +:1024B0000CF1FF35B5F5806F32D2C4EBC4094FF48F +:1024C0007A7009F103034FEAE308C3F3C70308F185 +:1024D000010AA4EB030E08FB00085FFA8EF65AFA15 +:1024E0008EFEB8FBFEFEBEF5617F1BDC1FFA8EF48C +:1024F000581C56FA80F00CFB00FCB7FBFCFC614555 +:10250000D4D1013BDBB20F2BD0D8711E0020C9B251 +:10251000072905D8107101201480558053719171DD +:10252000BDE8F08709F1FF334FEAE30EC3F3C703B9 +:102530000EF10108E41A0EFB0000E6B258FA84F42A +:10254000B0FBF4F4A4B2D3E70846E9E700B4C4044E +:102550003F420F0038B540F27772C36A154CC3F89A +:10256000BC200722C36AC3F8C8202268C16A93004E +:1025700043F4C023C1F8A03002F1805302F16C0192 +:10258000C56A03F52C53EA3289009B00226041F0B2 +:10259000E061094AC361C5F8C01003F5D87103F5BD +:1025A0006A7341629342836202D9044800F020FEBC +:1025B00038BD00BFCC5E0020FCB500407873000839 +:1025C0002DE9F04F00F58055994689B0044695F8FD +:1025D00058348A469046022B04D90027384609B061 +:1025E000BDE8F08F9E4A52F8231009B942F8230043 +:1025F0009C49C4F80CA00B7884F81090C3B9FFF77D +:1026000039FC994BD3F8EC2042F48072C3F8EC20EB +:10261000D3F8942042F48072C3F89420D3F8942025 +:1026200022F48072C3F8942001230B70FFF728FC7A +:1026300095F851346BB9FFF71DFC8C4A95F8583466 +:10264000D35CEBB1012B24D0012385F85134FFF783 +:1026500017FCFFF70FFCE26A936923F01003936104 +:1026600000F0CCFD0746E36A9E6916F0080617D015 +:1026700000F0C4FDC31BFA2BF5D9FFF701FCACE752 +:102680000221132001F04EFE0221152001F04AFE26 +:10269000DAE70221142001F045FE02211620F5E7B9 +:1026A0009A6942F001029A6100F0A8FD0746E36AC8 +:1026B0009A69D00705D400F0A1FDC31BFA2BF6D907 +:1026C000DBE79A69002704F5825B42F002020BF116 +:1026D000100B9A61E36A5F65FFF7D2FB686C00F04C +:1026E00013FC202200216846FFF714FB02A8FFF725 +:1026F000FFFD6A460BEB06030DF1180E0697944694 +:102700000833BCE80300F44543F8080C43F8041C04 +:102710006246F4D1DCF8000020361860B6F5806F10 +:102720009CF804201A71DCD1002304F5A252514612 +:1027300020461A3285F8503485F85334FFF7A0FE4E +:10274000074690B9E26A936923F00103936100F0B0 +:1027500055FD0546E36A9B69D9077FF53EAF00F05A +:102760004DFD431BFA2BF5D937E795F85F6495F8D3 +:102770005E243602C5F86CA4E36A46EA426695F820 +:1027800060241643B5F85C2446EA0246DE61B8F1DF +:10279000000F29D004F5A352414620460232FFF72C +:1027A0006FFE90B9E26A936923F00103936100F030 +:1027B00025FD0546E36A9B69DA077FF50EAF00F059 +:1027C0001DFD431BFA2BF5D907E795F8683495F8FA +:1027D00067141B01C5F87084E26A43EA0123B5F867 +:1027E000641443EA0143D360E36A00262046C3F839 +:1027F000BC60FFF7AFFE85F859646FF04042E36AB2 +:10280000B9F1030F1A651A4AE36A5A654FF00222BA +:10281000E36A9A654FF0FF32E36AC3F8E0204FF0B5 +:102820000302E36ADA65E26A936943F440739361F1 +:102830003FF4D4AEE26A936923F00103936100F0A0 +:10284000DDFC0646E36A9B69DB0705D500F0D6FC94 +:10285000831BFA2BF6D9C0E6012385F85234BDE676 +:10286000C05E0020C85E002000440258B07300081B +:10287000550200022DE9F04F054689B09046994671 +:10288000002741F2680A00F58056EB6AD3F8D83089 +:10289000FB40D8074AD505EB47124FEA471B524485 +:1028A0001379190742D4D6F880340133C6F880343E +:1028B00013799A0605EB0B0248BFD6F8A8345244A8 +:1028C00044BF0133C6F8A834137943F008031371E9 +:1028D000DB0723D596F8533403B305F582546846D5 +:1028E000FFF70CFD03AB18345C4404F1080C2068BE +:1028F000083454F8041C1A46644503C21346F6D142 +:102900002068694610602846A2889A800123ADF8A5 +:1029100008302B68CDE900891B6C9847D6F85434F1 +:1029200023B1D6F89C340133C6F89C340137202FEC +:10293000ABD109B0BDE8F08F2DE9F04F0F468DB057 +:10294000044600F05DFC82468946002F5BD1E36AB5 +:10295000D3F8A02012F4FE0F03D100200DB0BDE883 +:10296000F08FD3F8A420920141BF04F58051D1F833 +:1029700094240132C1F89424D3F8A4205606ECD054 +:10298000D3F8A450E669C5F305254823E8464FF07F +:10299000000B03FB05664046FFF7AAFC32685100B6 +:1029A0004ABF22F06043C2F38A4343F000439200DF +:1029B00048BF43F080430093736813F400131BBFB8 +:1029C000012304F580528DF80D308DF80D301EBFB7 +:1029D000D2F8AC340133C2F8AC34F38803F00F03FF +:1029E0008DF80C309DF80C0000F068FA5FFA8BF35C +:1029F000984225D9F2180CA90BF1010B127A0B445D +:102A000003F82C2CEEE7012FA7D1E36AD3F8B0200E +:102A100012F4FE0FA1D0D3F8B420950141BF04F504 +:102A20008051D1F894240132C1F89424D3F8B42011 +:102A3000500692D0D3F8B450266AC5F30525A4E712 +:102A4000EFB9E36AC3F8A85004A807ADFFF756FC36 +:102A500098E80F0007C52B800023204604A9ADF895 +:102A60001830236804F580541B6CCDE904A99847FD +:102A700058B1D4F88C340133C4F88C346EE7012F8C +:102A8000E2D1E36AC3F8B850DEE7D4F8903401200D +:102A90000133C4F8903461E7F8B505460F4600F5F8 +:102AA0008054012639462846FFF746FF10B184F8C6 +:102AB0005364F7E7D4F8543423B1D4F89C34013389 +:102AC000C4F89C34F8BD0000C36AF0B51A6C12F467 +:102AD0007F0F2BD01B6C00F5805441F268054FF03E +:102AE000010CC4F8A0340023471900EB43125E0127 +:102AF0002A44117911F0020F15D0490713D4B9599E +:102B0000C66A0CFA01F1D6F8CCE011EA0E0F0AD031 +:102B1000C6F8D410117941F004011171D4F8882459 +:102B20000132C4F888240133202BDED1F0BD00002F +:102B30002B4B70B51E561B5C012B30D8294D2A4AF1 +:102B400055F8233052F8264013B349B3236D9A0544 +:102B500010D54FF40073236500F052FB50EA0102D8 +:102B60000B4602D0013861F10003024655F82600F9 +:102B7000FFF780FE236D9B012CD54FF0007255F8B6 +:102B80002630226503F58053012283F8592421E081 +:102B900001232365102323654FF48053236570BD03 +:102BA000236DDA0702D4236D5B0706D505230021C8 +:102BB00055F826002365FFF76FFF236DD80602D472 +:102BC000236D590606D55023012155F826002365AB +:102BD000FFF762FF55F82600BDE87040FFF774BFAD +:102BE000B4730008C05E0020B873000808B5FFF792 +:102BF00041F9FFF769FFBDE80840FFF741B9000060 +:102C0000C36AD3F8C00010F07C5005D0D3F8C400DC +:102C100080F40010C0F340507047000000F5805071 +:102C200008B5FFF727F9406C00F080F9FFF728F9A5 +:102C300043090CBF0120002008BD000000F58053AF +:102C400093F8592462B1C16A8A6922F001028A614B +:102C5000D3F898240132C3F89824002283F8592429 +:102C6000704700002DE9F74300F582519846002592 +:102C7000FFF700F9103141F2680E4FF0010900F53D +:102C8000805C00EB4514744423795E071CD4DB069A +:102C90001AD58E69C36A09FA06F6D3F8CC703E429B +:102CA00012D04F6801970F689742019F77EB080792 +:102CB0000AD2C3F8D460237943F004032371DCF80B +:102CC00084340133CCF8843401352031202DD8D11F +:102CD00003B0BDE8F043FFF7D3B80000F8B51E46D7 +:102CE00000230F46054613701446FFF797FF80F048 +:102CF000010038701EB12846FFF782FF2070F8BD32 +:102D00002DE9F04F994685B00B780E468046174660 +:102D100001931378DDE90EBA029300F071FA33786B +:102D200004460D4613B93B78002B41D022462B4672 +:102D30004046FFF797FFFFF759FFFFF77FFF4B462E +:102D40003A463146FFF7CAFF33782BB1019B1BB1DE +:102D5000012005B0BDE8F08F3B7813B1029B002B3A +:102D6000F6D108F5805303935C4575EB0A031FD237 +:102D7000039BD3F85404D8B1BBEB04020368D968B1 +:102D80006AEB050388474B463A4631464046FFF713 +:102D9000A5FF337813B1019B002BD9D13B7813B138 +:102DA000029B002BD4D100F02BFA04460D46DBE742 +:102DB0000020CEE7002108B50846FFF7B9FEBDE8C0 +:102DC000084001F075B9000008B501210020FFF7A7 +:102DD000AFFEBDE8084001F06BB9000008B5002166 +:102DE0000120FFF7A5FEBDE8084001F061B9000031 +:102DF000012108B50846FFF79BFEBDE8084001F039 +:102E000057B900000FB4002004B0704713B56C46EA +:102E1000031D84E8060094E8030083E80500012010 +:102E200002B010BD73B58568019155B11B885B0771 +:102E300007D4D0E90036DB6B9847019AC1B230461F +:102E4000A847012002B070BDF0B5866889B005467C +:102E50000C465EB1BDF838305B070AD4D0E90037C4 +:102E6000DB6B98472246C1B23846B047012009B013 +:102E7000F0BD0022002301F10806CDE90023002364 +:102E80000A46ADF8083003AB1068083252F8041C4B +:102E90001C46B24203C42346F6D1106820609288D3 +:102EA000A28000F0AFF90423ADF808302B68CDE91B +:102EB00000011B6C694628469847D7E7082817D9B0 +:102EC00009280CD00A280CD00B280CD00C280CD0C8 +:102ED0000D280CD00E2814BF4020302070470C2045 +:102EE000704710207047142070471820704720202A +:102EF0007047000010B5037C044613B9006804F065 +:102F00002DF9204610BD00000023BFF35B8FC36086 +:102F1000BFF35B8FBFF35B8F8360BFF35B8F704743 +:102F2000BFF35B8F0068BFF35B8F704770B50546DA +:102F30000C30FFF7F5FF044605F108063046FFF7B1 +:102F4000EFFFA04206D96D683046FFF7E9FF254440 +:102F5000281A70BD3046FFF7E3FF201AF9E700009A +:102F600070B505464068A0B105F10C0605F10800F2 +:102F7000FFF7D6FF04463046FFF7D2FF844204F144 +:102F8000FF34304694BF6D680025FFF7C9FF2C441D +:102F9000201A70BD38B50C460546FFF7C7FFA042A2 +:102FA00010D305F10800FFF7BBFF04446868BFF3C6 +:102FB0005B8FB4FBF0F100FB11440120AC60BFF368 +:102FC0005B8F38BD0020FCE72DE9F0411446074631 +:102FD0000D46FFF7C5FF844228BF0446D4B1B8466A +:102FE00058F80C6B4046FFF79BFF30442860404682 +:102FF0007E68FFF795FF331A9C4203D801206C606E +:10300000BDE8F081A41B6B603B682044AB60E860C6 +:103010000220F5E72046F3E738B50C460546FFF7F2 +:103020009FFFA04210D305F10C00FFF779FF044485 +:103030006868BFF35B8FB4FBF0F100FB1144012023 +:10304000EC60BFF35B8F38BD0020FCE72DE9FF414A +:103050008846694607466C46FFF7B6FF002506B26C +:1030600004EBC606B4420AD0626808EB050120688A +:103070000834FEF729FE54F8043C1D44F2E72946C3 +:103080003846FFF7C9FF284604B0BDE8F0810000CC +:10309000F8B505460C300F46FFF742FF05F108066C +:1030A00004463046FFF73CFFA042304688BF6C68BC +:1030B000FFF736FF201A386020B12C683046FFF742 +:1030C0002FFF2044F8BD000073B5144606460D4698 +:1030D000FFF72CFF8442019028BF0446DCB101A910 +:1030E0003046FFF7D5FF019B33B93268C5E902339B +:1030F000C5E9002401200CE09C42286038BF0194FF +:10310000019884426860F5D93368241A0220AB60C4 +:10311000EC6002B070BD2046FBE700002DE9FF41E6 +:103120000F4669466C46FFF7CFFF00B2002604EB5E +:10313000C005AC4209D0D4F80480B81954F8081B73 +:1031400042464644FEF7C0FDF3E7304604B0BDE812 +:10315000F081000038B50546FFF7E0FF0446014660 +:103160002846FFF717FF204638BD000000B59BB08A +:10317000EFF3098168226846FEF7A6FDEFF30583A9 +:10318000044B9A6BDA6A9A6A9A6A9A6A9A6A9A6A93 +:103190009B6AFEE700ED00E000B59BB0EFF309810C +:1031A00068226846FEF790FDEFF30583044B9A6BA7 +:1031B0009A6A9A6A9A6A9A6A9A6A9B6AFEE700BF52 +:1031C00000ED00E000B59BB0EFF30981682268468E +:1031D000FEF77AFDEFF30583034B5A6B9A6A9A6AFE +:1031E0009A6A9A6A9B6AFEE700ED00E0FEE700003B +:1031F0000FB408B5029801F083FFFEE702F0C4BBEC +:1032000002F09CBB02F09ABB30B50A44084D9142D3 +:103210000DD011F8013B5840082340F30004013B56 +:103220002C4013F0FF0384EA5000F6D1EFE730BDE5 +:103230002083B8ED2DE9F041C56915B9C161BDE83C +:10324000F0814B68AC4623F06047C3F38A464FEAEF +:10325000D37EC3F3807816EA230638BF3E462B465A +:103260005A68BEEBD27F22F060440AD0002A18DAF6 +:10327000A40CB44217D19D420FD10D60DEE7134676 +:10328000EEE7A74207D102F08044C2F380724245C4 +:103290000BD054B1EFE708D2EDE7CCF800100B608B +:1032A000CDE7B44201D0B442E5D81A689C46002A62 +:1032B000E5D11960C3E700002DE9F047089D01F052 +:1032C000070400EBD1004FF47F494FEAD5082244B0 +:1032D00005F00705944201D1BDE8F08704F0070727 +:1032E00005F0070A111B08EBD50E57453E4613F8AB +:1032F0000EC038BF5646C6F108068E4228BF0E469D +:10330000E108415C34443544B94029FA06F721FA12 +:103310000AF1FFB28CEA010147FA0AF739408CEA58 +:10332000010C03F80EC0D5E780EA0120082341F222 +:10333000210201B2013B4000002980B2B8BF5040D9 +:1033400013F0FF03F5D1704738B50C468D18A54230 +:1033500000D138BD14F8011BFFF7E6FFF7E70000C6 +:1033600002684AB1136801890360C38801339BB2C4 +:103370009942C38038BF03811046704770B588B04A +:10338000044620220D4668460021FEF7C3FC204675 +:103390000495FFF7E5FF024660B16B46054608AEAF +:1033A0001C46083503CCB44245F8080C45F8041C0B +:1033B0002346F5D1104608B070BD0000082817D983 +:1033C00009280CD00A280CD00B280CD00C280CD0C3 +:1033D0000D280CD00E2814BF4020302070470C2040 +:1033E0007047102070471420704718207047202025 +:1033F00070470000082817D90C280CD910280CD9C0 +:1034000014280CD918280CD920280CD930288CBFA6 +:103410000F200E207047092070470A2070470B20AC +:1034200070470C2070470D207047000010B54B68A6 +:1034300023B9CA8A63F30902CA8210BDC4681A6834 +:103440001C60C360438A013B43824A60EFE700008F +:103450002DE9F84F1D46CB8A0F468146C3F309017B +:10346000924606290B4630D00020AAB207F1190473 +:103470009EB21FFA80F8052E0FD8904503F1010384 +:1034800006D30A44FB8A62F309030120FB821AE097 +:103490001AF800600130E654EAE79045F1D2A1F154 +:1034A000060B1C237C68BBFBF3F203FB12BB1FFA69 +:1034B0008BF6002C45D14846FFF752FF044638B939 +:1034C00078606FF00200BDE8F88F4FF00008E6E783 +:1034D000002606607860ADB24FF0000B454510D96C +:1034E0000AEB0803221D13F8011B08F1010891558E +:1034F000B1B21FFA88F81B292BD0454506F1010609 +:10350000F1D8FB8AC3F30902154465F30903BCE74C +:1035100001321C4692B22368002BF9D1AB1F0B4439 +:103520001C21B3FBF1F301339BB29A42D3D2BBF11E +:10353000000FD0D14846FFF713FF20B9C4F800B000 +:10354000BFE70122E7E7C0F800B05E46206004460E +:10355000C1E74545D5D94846FFF702FF08B92060C5 +:10356000AFE7C0F800B0002620600446B6E70000D0 +:103570002DE9F04F2DED028B83B007469146BDF843 +:103580003C50CDE90013002A00F092802DB10E9B33 +:10359000002B00F08D80072D32D807F10C00FFF7CB +:1035A000DFFE044638B96FF00204204603B0BDECDC +:1035B000028BBDE8F08F14220021FEF7ABFB2A46F8 +:1035C0000E9904F10800FEF77FFB681CC0B2FFF7FC +:1035D00011FFFFF7F3FE207499F80030013803F073 +:1035E0001F0314FA80F063F03F0303723846009B18 +:1035F00043F0004161602146FFF71CFE0124D4E73F +:103600004FF0000800F10C034FF0800A4646444694 +:1036100008EE103A18EE100AFFF7A2FE83460028C3 +:10362000C1D014220021FEF775FBC6BB019B02200E +:10363000ABF808300E9B00F1080299195BFA82F290 +:103640000130C0B2082801D0AE422AD3FFF7D2FE23 +:10365000AE4208BF4FF0400AFFF7B0FE99F80020D5 +:10366000411E009B02F01F0201345BFA81F142EA25 +:10367000481288F0010824B24AEA020A43F00042E4 +:1036800081F808A059468BF810003846CBF8042082 +:103690004FF0000AFFF7CEFDAE42BBD185E7002018 +:1036A000C8E711F801CB013602F801CBB6B2C7E783 +:1036B0006FF0010479E70000F8B515460E462822A0 +:1036C000002104461F46FEF725FB069BB5F5001FAB +:1036D000A760636004F10C00079B34BF6A094FF6D2 +:1036E000FF722362002397B29A4205D80023036039 +:1036F00027826382A382F8BD0660013330462036FC +:10370000F2E7000003781BB94BB2002BC8BF017071 +:1037100070470000007870472DE9F74FDDF83C90C6 +:10372000804692469B46BDF830500D9E9DF838402D +:10373000BDF84070B9F1000F01D1002F51D11F2CFD +:103740004FD898F80000B0B9072F47D835F00303D9 +:1037500047D13A4649464FF6FF702D02FFF7F4FD78 +:1037600020F0010045EA04644004400C44EA40248F +:103770004FF6FF7321E040EA0520072F40EA04647A +:10378000F6D900254FF6FF73C5F12000A5F1200200 +:103790002AFA05F108350BFA00F02BFA02F2014380 +:1037A00018461143C9B2FFF7BFFD402D0346EBD1C8 +:1037B0003A464946FFF7C8FD034632462146404691 +:1037C000CDE90097FFF7D4FE33780133DBB21F2B2E +:1037D00088BF0023337003B0BDE8F08F6FF00300A3 +:1037E000F9E76FF00100F6E72DE9F04F85B092465A +:1037F00006469B46DDF848800F9D9DF840209DF8C9 +:103800004490BDF84C70B8F1000F01D1002F49D1A0 +:103810001F2A47D83378002B47D00C029DF8381068 +:10382000072F44EA026444EAC93444EA014444EA02 +:10383000030444F0800432D900234FF6FF72C3F131 +:10384000200CA3F120002AFA03F103930BFA0CFCDD +:103850002BFA00F041EA0C0101431046C9B2FFF710 +:1038600063FD039B02460833402BE8D13A464146AC +:10387000FFF76AFD03462A4621463046CDE9008718 +:10388000FFF776FEB9F1010F06D12B780133DBB2D9 +:103890001F2B88BF00232B7005B0BDE8F08F4FF6BB +:1038A000FF73E8E76FF00100F6E76FF00300F3E75E +:1038B000C06900B104307047C3691A68C261C26848 +:1038C0001A60C360438A013B438270472DE9F0418F +:1038D000D0F8188014461D46184E4146002709B9F5 +:1038E000BDE8F081D1E90223A21A65EB03039642F9 +:1038F00077EB03031ED283698B420DD1FFF796FD50 +:1039000083691B688361C3680B60438AC160013BA4 +:10391000816943828846E2E7FFF788FD0B68C8F8B3 +:103920000030C3680B60438AC160013B4382D8F812 +:103930000010D4E788460968D1E700BF80841E00E4 +:103940002DE9F04F8BB00D4614469B46DDF85090A4 +:103950008046002800F01881B9F1000F00F01481B2 +:10396000531E3F2B00F21081012A03D1BBF1000F3F +:1039700040F00A810023CDE90833B8F81430B5EBE4 +:10398000C30F4FEAC30703D300200BB0BDE8F08F8D +:103990002B199F42D8F80C3036BF7F1B2746FFB249 +:1039A0001BB9D8F81030002B7AD02F2D4DD8C5F187 +:1039B000300600232946B742009308ABD8F8080028 +:1039C0002CBFF6B23E46A7EB060A354432465FFAF4 +:1039D0008AFAFFF771FCB8F81430302103F1005374 +:1039E000063BDB000493D8F80C300393039B13B120 +:1039F000BAF1000F2CD1D8F8100040B1BAF1000F85 +:103A000005D008AB5246691A0096FFF755FC38B24C +:103A1000002FB9D066070AD00AAB624203EBD4018B +:103A200002F0070211F8083C134101F8083C082C89 +:103A30003DD9102C40F2B580202C40F2B780BBF16C +:103A4000000F00F09C80082335E0BA460026C2E74C +:103A5000049BE02B28BFE02306930B44AB42059365 +:103A600015D95A1B0398691A0096924508AB00F1C4 +:103A7000040034BF5246D2B20792FFF71DFC079AEA +:103A80001644AAEB020A1544F6B25FFA8AFA049BBE +:103A9000069A05999B1A0493039B1B680393A5E759 +:103AA00000933A4608AB2946D8F80800ADE7BBF1C9 +:103AB000000F13D00123B4EBC30F6BD0082C12D826 +:103AC0009DF82030621E23FA02F2D50706D54FF08A +:103AD000FF3202FA04F423438DF820309DF82030A1 +:103AE00089F8003051E7102C12D8BDF82030621E42 +:103AF00023FA02F2D10706D54FF0FF3202FA04F49E +:103B00002343ADF82030BDF82030A9F800303CE761 +:103B1000202C0FD80899631E21FA03F3DA0705D584 +:103B20004FF0FF3202FA04F40C430894089BC9F8E2 +:103B300000302AE7402C2AD0611EC4F12102A4F1F2 +:103B40002103DDE9086526FA01F105FA02F225FAFA +:103B500003F311431943CB0711D50122A4F120032C +:103B6000C4F1200102FA03F322FA01F1A2400B434F +:103B7000524263EB430332432B43CDE90823DDE993 +:103B80000823C9E9002300E76FF00100FDE66FF0AC +:103B90000800FAE6082CA1D9102CB4D9202CEED8B4 +:103BA000C4E7BBF1000FAED0022384E7BBF1000FE6 +:103BB000BCD004237FE70000012A30B5144638BF8B +:103BC000012485B00025402C28BF4024012ACDE9DE +:103BD000025518D81B788DF8083063070AD004AB5B +:103BE000624203EBD40502F0070215F8083C93404B +:103BF00005F8083C034600912246002102A8FFF781 +:103C00005BFB05B030BD082AE4D9102A03D81B8815 +:103C1000ADF80830E1E7202A95BF1B68D3E90023FF +:103C20000293CDE90223D8E710B5CB681BB98B60AE +:103C30000B618B8210BDC4681A681C60C360438A24 +:103C4000013B4382CA60F0E72DE9F04FD1F80080D4 +:103C500093B004460D4618F0800FCDE90323C8F356 +:103C6000C01219BFC8F3C03BC8F306264FF0020BC1 +:103C70001646B8F1000F80F2D18118F0C0430593C9 +:103C800040F0CC810B7B002B00F0C881BBF1020F10 +:103C900003D00178B14240F0C48108F07F01069161 +:103CA0006AB3C8F3074A2B447606069A46EA0B46DF +:103CB00093F8039046EA82465FEAD91346EA0A0679 +:103CC000079300F090800022002367680AA920462D +:103CD000CDE90A23069B524600935B46B84700286D +:103CE0007ED0A7699FB9314604F10C00FFF746FB6F +:103CF0000746E0B96FF0020013B0BDE8F08FC8F3DB +:103D00000F2A18F07F0F08BF0AF0030ACBE73B69C0 +:103D10009E420DD03F68002FF9D1314604F10C00CE +:103D2000FFF72CFB07460028E4D0A3693B60A7619E +:103D300000264FF6FF70DDE90A23C6F1200E22FAB5 +:103D400006F1A6F1200C083603FA0EFE099223FABA +:103D50000CFC089341EA0E0141EA0C01C9B2FFF7DD +:103D6000E3FA402EDDE90832E7D1B882FB7D09F0A5 +:103D70001F06C8F30468C3F384039B1B98B2002B8F +:103D8000D7E90221BCBF00F120031BB252EA0100B7 +:103D90000FD00398821A049860EB0101A748904263 +:103DA0004FF000028A4104D3079A002A5BD0012B0E +:103DB00023DDFA7D4FEA89033946204602F00302EB +:103DC00003F07C031343FB75FFF730FB079BA3B99C +:103DD000FB7DC3F38402013262F38603FB7504E0CA +:103DE0006FF00B0088E7A76917B96FF00C0083E745 +:103DF0003B699E42BAD03F68F6E719F0400F32D0D7 +:103E0000039B142200210DA8BB60049BFB60FDF7FF +:103E100081FF039B0AA920460A93049BADF83EA0AC +:103E20000B932B1D8DF840B00C932B7B8DF84160CC +:103E3000013B8DF84280DBB2ADF83C30069B8DF83B +:103E4000433094F8243083F001038DF84430A368A4 +:103E50009847FB7DC3F38403013303F01F039B02E8 +:103E6000FB82002048E7FB7DC9F34012B2EBD31F71 +:103E700040F0DA80C3F38403B34240F0D88007995E +:103E80004FEA99122B7B002934D0D20741D4032B5F +:103E900040F2D080039BAE1D394604F10C00BB609C +:103EA0003246049BFB602B7B033BDBB2FFF7D0FA6F +:103EB00000280DDA20463946FFF7B8FAFB7D0320CB +:103EC000C3F38403013303F01F039B02FB8213E758 +:103ED000AB883B832A7B033AD2B2B88A3146FFF7DC +:103EE00033FAFB7DB882DA43C2F3C01262F3C71320 +:103EF000FB75B6E76AB92E1D013B394604F10C008B +:103F0000DBB23246FFF7A4FA0028D3DB2A7B013A62 +:103F1000E2E7F98A013BC1F30901DAB2052959D870 +:103F2000281D002307F11A0C9A4208D910F801EB5A +:103F300001330CF801E00131DBB20629F4D1039919 +:103F400093420A9138BF043304992CBF002355FAD9 +:103F500083F30B9107F11A010C9179680E930D917F +:103F6000291DFB8AADF83EA0C3F309038DF840B0CC +:103F70008DF841601A44069B8DF842808DF84330DD +:103F800094F82430ADF83C2083F001038DF84430E0 +:103F90000023B88A7B602A7B013AFFF7D5F93B8B77 +:103FA000B882834203D1A3680AA9204698472046D5 +:103FB0000AA9FFF739FEFB7DB88AC3F384030133F6 +:103FC00003F01F039B02FB823B8B984214BF11201E +:103FD000002091E67B68002BB1D0062001E01C3068 +:103FE0006346D3F800C0BCF1000FF8D1091A05F1FF +:103FF000040C081D00EB030905989DF8143001EB33 +:10400000000EBEF11B0F9AD89A4298D91CF8013BBA +:1040100009F8013B059B01330593EDE76FF00900BB +:104020006AE66FF00A0067E66FF00D0064E66FF075 +:104030000E0061E66FF00F005EE600BF80841E0098 +:10404000EFF30983054968334A6B22F001024A63A2 +:1040500083F30988002383F31188704700EF00E0A1 +:10406000202080F3118862B60D4B0E4AD96821F4E6 +:10407000E0610904090C0A430B49DA60D3F8FC201B +:1040800042F08072C3F8FC20084AC2F8B01F1168E1 +:1040900041F0010111601022DA7783F822007047A5 +:1040A00000ED00E00003FA0555CEACC5001000E0BD +:1040B000202310B583F311880E4B5B6813F4006363 +:1040C00014D0F1EE103AEFF309844FF08073683C9E +:1040D000E361094BDB6B236684F3098800F0C2FFC0 +:1040E00010B1064BA36110BD054BFBE783F31188AC +:1040F000F9E700BF00ED00E000EF00E00B0700086B +:104100000E070008026843681143016003B11847B5 +:1041100070470000024A136843F0C0031360704701 +:104120000078004013B50E4C204600F0A1FA04F1CF +:10413000140000234FF400720A49009400F062F961 +:10414000094B4FF40072094904F13800009400F063 +:10415000DBF9074A074BC4E9172302B010BD00BFC3 +:10416000D45E0020405F002015410008406100201F +:104170000078004000E1F505037C30B5244C0029AF +:1041800018BF0C46012B11D1224B98420ED1224B65 +:10419000D3F8E82042F08042C3F8E820D3F8102199 +:1041A00042F08042C3F81021D3F810312268036E28 +:1041B000C16D03EB52038466B3FBF2F3626815042E +:1041C00042BF23F0070503F0070343EA4503CB6032 +:1041D000A36843F040034B60E36843F001038B6046 +:1041E00042F4967343F001030B604FF0FF330B6210 +:1041F000510505D512F0102205D0B2F1805F04D030 +:1042000080F8643030BD7F23FAE73F23F8E700BF32 +:104210000C740008D45E0020004402582DE9F047D9 +:10422000C66D05463768F4692107346219D014F069 +:10423000080118BF8021E20748BF41F02001A30711 +:104240004FF0200348BF41F04001600748BF41F4F0 +:10425000807183F31188281DFFF754FF002383F337 +:104260001188E2050AD5202383F311884FF40071E9 +:10427000281DFFF747FF002383F311884FF0200923 +:104280004FF0000A14F0200838D13B0616D54FF045 +:10429000200905F1380A200610D589F31188504607 +:1042A00000F066F9002836DA0821281DFFF72AFFFA +:1042B00027F080033360002383F31188790614D537 +:1042C000620612D5202383F31188D5E913239A427D +:1042D00008D12B6C33B127F040071021281DFFF7C0 +:1042E00011FF3760002383F31188E30618D5AA6E07 +:1042F0001369ABB15069BDE8F047184789F31188DD +:10430000736A284695F86410194000F0CBF98AF3D7 +:104310001188F469B6E7B06288F31188F469BAE7E6 +:10432000BDE8F087090100F16043012203F5614314 +:10433000C9B283F8001300F01F039A4043099B00A1 +:1043400003F1604303F56143C3F880211A607047AD +:10435000F8B51546826804460B46AA4200D2856825 +:10436000A1692669761AB5420BD218462A46FDF78E +:10437000ABFCA3692B44A3612846A3685B1BA36025 +:10438000F8BD0CD9AF1B18463246FDF79DFC3A46E6 +:10439000E1683044FDF798FCE3683B44EBE71846DE +:1043A0002A46FDF791FCE368E5E700008368934245 +:1043B000F7B50446154600D28568D4E90460361A7C +:1043C000B5420BD22A46FDF77FFC63692B4463613B +:1043D0002846A3685B1BA36003B0F0BD0DD932462D +:1043E000AF1B0191FDF770FC01993A46E06831443A +:1043F000FDF76AFCE3683B44E9E72A46FDF764FC05 +:10440000E368E4E710B50A440024C361029B8460BA +:10441000C16002610362C0E90000C0E9051110BD7E +:1044200008B5D0E90532934201D1826882B9826829 +:10443000013282605A1C426119700021D0E90432B5 +:104440009A4224BFC368436100F0E6FE002008BD25 +:104450004FF0FF30FBE7000070B5202304460E4606 +:1044600083F31188A568A5B1A368A269013BA36085 +:10447000531CA36115782269934224BFE368A361AA +:10448000E3690BB120469847002383F3118828463F +:1044900007E03146204600F0AFFE0028E2DA85F35F +:1044A000118870BD2DE9F74F04460E461746984611 +:1044B000D0F81C904FF0200A8AF311884FF0000BBF +:1044C000154665B12A4631462046FFF741FF0346AF +:1044D00060B94146204600F08FFE0028F1D000234D +:1044E00083F31188781B03B0BDE8F08FB9F1000F9A +:1044F00003D001902046C847019B8BF31188ED1A29 +:104500001E448AF31188DCE7C160C361009B8260AE +:104510000362C0E905111144C0E900000161704760 +:10452000F8B504460D461646202383F31188A76884 +:10453000A7B1A368013BA36063695A1C62611D7047 +:10454000D4E904329A4224BFE3686361E3690BB1A2 +:1045500020469847002080F3118807E03146204626 +:1045600000F04AFE0028E2DA87F31188F8BD000067 +:10457000D0E9052310B59A4201D182687AB98268E0 +:104580000021013282605A1C82611C7803699A42C0 +:1045900024BFC368836100F03FFE204610BD4FF08A +:1045A000FF30FBE72DE9F74F04460E4617469846C5 +:1045B000D0F81C904FF0200A8AF311884FF0000BBE +:1045C000154665B12A4631462046FFF7EFFE034601 +:1045D00060B94146204600F00FFE0028F1D00023CC +:1045E00083F31188781B03B0BDE8F08FB9F1000F99 +:1045F00003D001902046C847019B8BF31188ED1A28 +:104600001E448AF31188DCE70268436811430160A5 +:1046100003B11847704700001430FFF743BF000094 +:104620004FF0FF331430FFF73DBF00003830FFF785 +:10463000B9BF00004FF0FF333830FFF7B3BF0000C1 +:104640001430FFF709BF00004FF0FF311430FFF7BF +:1046500003BF00003830FFF763BF00004FF0FF32A8 +:104660003830FFF75DBF000000207047FFF75ABDEC +:10467000044B036000234360C0E902330123037449 +:10468000704700BF2474000810B52023044683F34C +:104690001188FFF771FD02232374002383F311882F +:1046A00010BD000038B5C36904460D461BB904218E +:1046B0000844FFF7A9FF294604F11400FFF7B0FEF4 +:1046C000002806DA201D4FF48061BDE83840FFF76E +:1046D0009BBF38BD026843681143016003B11847AE +:1046E0007047000013B5406B00F58054D4F8A4382F +:1046F0001A681178042914D1017C022911D1197981 +:10470000012312898B4013420BD101A94C3002F0D6 +:104710009DF8D4F8A4480246019B2179206800F056 +:10472000DFF902B010BD0000143002F01FB8000025 +:104730004FF0FF33143002F019B800004C3002F093 +:10474000F1B800004FF0FF334C3002F0EBB800003E +:10475000143001F0EDBF00004FF0FF31143001F0D4 +:10476000E7BF00004C3002F0BDB800004FF0FF3250 +:104770004C3002F0B7B800000020704710B500F5CB +:104780008054D4F8A4381A681178042917D1017C10 +:10479000022914D15979012352898B4013420ED139 +:1047A000143001F07FFF024648B1D4F8A4484FF41A +:1047B000407361792068BDE8104000F07FB910BDFA +:1047C000406BFFF7DBBF0000704700007FB5124B66 +:1047D00001250426044603600023057400F18402C9 +:1047E00043602946C0E902330C4B02901430019318 +:1047F0004FF44073009601F031FF094B04F69442E8 +:10480000294604F14C000294CDE900634FF4407353 +:1048100001F0F8FF04B070BD4C740008C1470008F7 +:10482000E54600080A68202383F311880B790B33CF +:1048300042F823004B79133342F823008B7913B1EC +:104840000B3342F8230000F58053C3F8A418022369 +:104850000374002383F311887047000038B5037F89 +:10486000044613B190F85430ABB90125201D022144 +:10487000FFF730FF04F114006FF00101257700F01D +:10488000D7FC04F14C0084F854506FF00101BDE8EE +:10489000384000F0CDBC38BD10B5012104460430CD +:1048A000FFF718FF0023237784F8543010BD000071 +:1048B00038B504460025143001F0E8FE04F14C0040 +:1048C000257701F0B7FF201D84F854500121FFF730 +:1048D00001FF2046BDE83840FFF750BF90F8803018 +:1048E00003F06003202B06D190F881200023212AB9 +:1048F00003D81F2A06D800207047222AFBD1C0E91E +:104900001D3303E0034A426707228267C367012021 +:10491000704700BF3422002037B500F58055D5F828 +:10492000A4381A68117804291AD1017C022917D1F8 +:104930001979012312898B40134211D100F14C04E3 +:10494000204602F037F858B101A9204601F07EFF59 +:10495000D5F8A4480246019B2179206800F0C0F8F0 +:1049600003B030BD01F10B03F0B550F8236085B002 +:1049700004460D46FEB1202383F3118804EB85071E +:10498000301D0821FFF7A6FEFB6806F14C005B69AD +:104990001B681BB1019001F067FF019803A901F0AA +:1049A00055FF024648B1039B2946204600F098F87F +:1049B000002383F3118805B0F0BDFB685A691268C3 +:1049C000002AF5D01B8A013B1340F1D104F180028B +:1049D000EAE70000133138B550F82140ECB120234C +:1049E00083F3118804F58053D3F8A428136852790F +:1049F00003EB8203DB689B695D6845B104216018A5 +:104A0000FFF768FE294604F1140001F055FE204628 +:104A1000FFF7B4FE002383F3118838BD7047000010 +:104A200001F05EB901234022002110B5044600F8D0 +:104A3000303BFDF76FF90023C4E9013310BD0000DE +:104A400010B52023044683F31188242241600021FD +:104A50000C30FDF75FF9204601F064F90223237062 +:104A6000002383F3118810BD70B500EB8103054668 +:104A700050690E461446DA6018B110220021FDF785 +:104A800049F9A06918B110220021FDF743F9314618 +:104A90002846BDE8704001F057BA00008368202224 +:104AA000002103F0011310B5044683601030FDF7B8 +:104AB00031F92046BDE8104001F0D2BAF0B401252A +:104AC00000EB810447898D40E4683D43A46945813A +:104AD00023600023A2606360F0BC01F0EFBA000025 +:104AE000F0B4012500EB810407898D40E4683D4363 +:104AF0006469058123600023A2606360F0BC01F05B +:104B000065BB000070B50223002504462422037013 +:104B10002946C0F888500C3040F8045CFDF7FAF8DC +:104B2000204684F8705001F0A3F963681B6823B134 +:104B300029462046BDE87040184770BD037880F8CC +:104B40008C300523037043681B6810B504460BB115 +:104B5000042198470023A36010BD000090F88C202A +:104B6000436802701B680BB10521184770470000AD +:104B700070B590F87030044613B1002380F870309F +:104B800004F18002204601F08FFA63689B68B3B994 +:104B900094F8803013F0600535D00021204601F0F4 +:104BA00039FD0021204601F029FD63681B6813B11F +:104BB000062120469847062384F8703070BD2046B1 +:104BC00098470028E4D0B4F88630A26F9A4288BF94 +:104BD000A36794F98030A56F002B4FF0200380F27B +:104BE0000381002D00F0F280092284F8702083F305 +:104BF000118800212046D4E91D23FFF771FF00230F +:104C000083F31188DAE794F8812003F07F0343EA05 +:104C1000022340F20232934200F0C58021D8B3F55E +:104C2000807F48D00DD8012B3FD0022B00F093801D +:104C3000002BB2D104F1880262670222A267E36707 +:104C4000C1E7B3F5817F00F09B80B3F5407FA4D12D +:104C500094F88230012BA0D1B4F8883043F00203DD +:104C600032E0B3F5006F4DD017D8B3F5A06F31D057 +:104C7000A3F5C063012B90D86368204694F8822086 +:104C80005E6894F88310B4F88430B047002884D06C +:104C9000436863670368A3671AE0B3F5106F36D003 +:104CA00040F6024293427FF478AF5C4B6367022385 +:104CB000A3670023C3E794F88230012B7FF46DAF24 +:104CC000B4F8883023F00203A4F88830C4E91D55F5 +:104CD000E56778E7B4F88030B3F5A06F0ED194F8AB +:104CE0008230204684F88A3001F020F963681B681E +:104CF00013B1012120469847032323700023C4E900 +:104D00001D339CE704F18B0363670123C3E723781A +:104D1000042B10D1202383F311882046FFF7BEFE19 +:104D200085F311880321636884F88B5021701B6818 +:104D30000BB12046984794F88230002BDED084F8DF +:104D40008B300423237063681B68002BD6D00221AC +:104D500020469847D2E794F8843020461D0603F099 +:104D60000F010AD501F092F9012804D002287FF43E +:104D700014AF2B4B9AE72B4B98E701F079F9F3E747 +:104D800094F88230002B7FF408AF94F8843013F04D +:104D90000F01B3D01A06204602D501F053FCADE74F +:104DA00001F044FCAAE794F88230002B7FF4F5AEC2 +:104DB00094F8843013F00F01A0D01B06204602D5D2 +:104DC00001F028FC9AE701F019FC97E7142284F817 +:104DD000702083F311882B462A4629462046FFF788 +:104DE0006DFE85F31188E9E65DB1152284F8702027 +:104DF00083F3118800212046D4E91D23FFF75EFECE +:104E0000FDE60B2284F8702083F311882B462A4696 +:104E100029462046FFF764FEE3E700BF7C740008E4 +:104E2000747400087874000838B590F8703004463F +:104E3000002B3ED0063BDAB20F2A34D80F2B32D8E3 +:104E4000DFE803F03731310822323131313131318D +:104E500031313737856FB0F886309D4214D2C36840 +:104E60001B8AB5FBF3F203FB12556DB9202383F3C4 +:104E700011882B462A462946FFF732FE85F3118812 +:104E80000A2384F870300EE0142384F87030202355 +:104E900083F31188002320461A461946FFF70EFEB9 +:104EA000002383F3118838BDC36F03B198470023F3 +:104EB000E7E70021204601F0ADFB0021204601F08C +:104EC0009DFB63681B6813B10621204698470623A3 +:104ED000D7E7000010B590F870300446142B29D0A5 +:104EE00017D8062B05D001D81BB110BD093B022BEA +:104EF000FBD80021204601F08DFB0021204601F067 +:104F00007DFB63681B6813B1062120469847062382 +:104F100019E0152BE9D10B2380F87030202383F39F +:104F2000118800231A461946FFF7DAFD002383F3A0 +:104F30001188DAE7C3689B695B68002BD5D1C36F22 +:104F400003B19847002384F87030CEE7024B00226B +:104F5000C3E900339A6070474063002000238268F1 +:104F60000374054B1B6899689142FBD25A68036031 +:104F700042601060586070474063002008B52023ED +:104F800083F31188037C032B05D0042B0DD02BB9A0 +:104F900083F3118808BD436900221A604FF0FF3384 +:104FA0004361FFF7DBFF0023F2E7D0E90032136033 +:104FB0005A60F3E7002382680374054B1B68996805 +:104FC0009142FBD85A680360426010605860704795 +:104FD00040630020054B1969087418680268536023 +:104FE0001A60186101230374FBF77ABB4063002049 +:104FF0004B1C30B5044687B00A4D10D02B6901A870 +:10500000094A00F031F92046FFF7E4FF049B13B191 +:1050100001A800F065F92B69586907B030BDFFF7AA +:10502000D9FFF8E7406300207D4F000838B50C4DEC +:10503000044641612B6981689A68914203D8BDE8B2 +:105040003840FFF78BBF1846FFF7B4FF01232C61F0 +:10505000014623742046BDE83840FBF741BB00BF42 +:1050600040630020044B1A681B6990689B68984253 +:1050700094BF0020012070474063002010B5084C09 +:10508000236820691A6854602260012223611A741F +:10509000FFF790FF01462069BDE81040FBF720BBF9 +:1050A0004063002008B5FFF7DDFF18B1BDE80840F8 +:1050B000FFF7E4BF08BD0000FFF7E0BFFEE7000018 +:1050C00010B50C4CFFF742FF00F0C0F880220A49EF +:1050D000204600F047F8012344F8180C0374FEF74B +:1050E000BFFF002383F3118862B60448BDE8104077 +:1050F00000F058B8686300208074000890740008BD +:1051000008B572B6034B586200F00AFC00F0D8FCF8 +:10511000FEE700BF4063002000F01CB9EFF31180F0 +:1051200020B9EFF30583202282F311887047000035 +:1051300010B530B9EFF30584C4F3080414B180F35B +:10514000118810BDFFF7AEFF84F31188F9E7000066 +:10515000034A516853685B1A9842FBD8704700BFF6 +:10516000001000E082600222028270478368A3F18F +:105170007C0243F80C2C026943F83C2C426943F84A +:10518000382C074A43F81C2CC268A3F1180043F8D6 +:10519000102C022203F8082C002203F8072C704779 +:1051A000F906000810B5202383F31188FFF7DEFF0E +:1051B00000210446FFF73AFF002383F311882046BD +:1051C00010BD0000024B1B6958610F20FFF702BFA2 +:1051D00040630020202383F31188FFF7F3BF000012 +:1051E00008B50146202383F311880820FFF700FF4C +:1051F000002383F3118808BD49B1064B42681B693F +:1052000018605A60136043600420FFF7F1BE4FF04E +:10521000FF307047406300200368984206D01A6848 +:105220000260506018465961FFF798BE7047000051 +:1052300038B504460D462068844200D138BD036865 +:1052400023605C604561FFF789FEF4E7054B4FF092 +:10525000FF3103F11402C3E905220022C3E907125A +:10526000704700BF4063002070B51C4E05460C46D9 +:10527000C0E9032301F0D4FB334653F8142F9A42BC +:105280000DD130620A2C2CBF00190A302A60C5E902 +:105290000124C6E90555BDE8704001F0ABBB316A99 +:1052A000431AE31838BF1C469368A34202D9081971 +:1052B00001F0B0FB73699A6894420CD85A68AC60EC +:1052C0002B606A6015609A685D60121B9A604FF0EF +:1052D000FF33F36170BDA41A1B68ECE74063002044 +:1052E00038B51B4C636998420DD08168D0E9003213 +:1052F00013605A600022C2609A680A449A604FF0B4 +:10530000FF33E36138BD03682246002142F8143FB1 +:1053100093425A60C16003D1BDE8384001F074BBCC +:105320009A688168256A0A449A6001F079FB63698A +:10533000411B9A688A42E5D9AB181D1A206A092DCB +:1053400098BF01F10A02BDE83840104401F062BB89 +:10535000406300202DE9F041184C002704F11406A9 +:10536000656901F05DFB236AAA68C11A8A4215D8F3 +:105370001344D5F80C802362D5E9003213605A60DB +:105380006369EF60B34201D101F03EFB87F31188FE +:105390002869C047202383F31188E1E76169B1429E +:1053A00009D013441B1ABDE8F0410A2B2CBFC018CA +:1053B0000A3001F02FBBBDE8F08100BF4063002040 +:1053C00000207047FEE70000704700004FF0FF30FC +:1053D0007047000002290CD0032904D00129074896 +:1053E00018BF00207047032A05D8054800EBC2000B +:1053F0007047044870470020704700BF747500086C +:10540000442200202875000870B59AB00546084669 +:10541000144601A900F0C2F801A8FCF773FC431C74 +:105420000022C6B25B001046C5E900342370032396 +:10543000023404F8013C01ABD1B202348E4201D8EF +:105440001AB070BD13F8011B013204F8010C04F806 +:10545000021CF1E708B5202383F311880348FFF706 +:105460005BFA002383F3118808BD00BFF8640020B5 +:1054700090F8803003F01F02012A07D190F88120B4 +:105480000B2A03D10023C0E91D3315E003F06003AC +:10549000202B08D1B0F884302BB990F88120212A34 +:1054A00003D81F2A04D8FFF719BA222AEBD0FAE74B +:1054B000034A426707228267C3670120704700BF23 +:1054C0003B22002007B5052917D8DFE801F019169F +:1054D00003191920202383F31188104A0121019018 +:1054E000FFF7C2FA019802210D4AFFF7BDFA0D48F5 +:1054F000FFF7DEF9002383F3118803B05DF804FBA6 +:10550000202383F311880748FFF7A8F9F2E7202347 +:1055100083F311880348FFF7BFF9EBE7C87400086D +:10552000EC740008F864002038B50C4D0C4C2A4689 +:105530000C4904F10800FFF767FF05F1CA0204F106 +:1055400010000949FFF760FF05F5CA7204F1180061 +:105550000649BDE83840FFF757BF00BFD07D0020A7 +:1055600044220020A8740008B2740008BD7400082A +:1055700070B5044608460D46FCF7C4FBC6B220468B +:10558000013403780BB9184670BD32462946FCF742 +:10559000A5FB0028F3D10120F6E700002DE9F04734 +:1055A00005460C46FCF7AEFB2C49C6B22846FFF771 +:1055B000DFFF08B11036F6B229492846FFF7D8FFB9 +:1055C00008B11036F6B2632E0BD8DFF89080DFF802 +:1055D0009090244FDFF898A02E7846B92670BDE849 +:1055E000F08729462046BDE8F04701F03DBE252E54 +:1055F00030D1072241462846FCF770FB80B91A4B90 +:10560000224603F1140153F8040B8B4242F8040BB9 +:10561000F9D1198807359B78173411809370DBE72F +:10562000082249462846FCF759FB98B9A21C0F4BA3 +:10563000197802320909C95D02F8041C13F8011B2C +:1056400001F00F015345C95D02F8031CF0D1183475 +:105650000835C1E7013504F8016BBDE79475000812 +:10566000BD740008B47500089C75000800E8F11FBF +:105670000CE8F11FBFF34F8F044B1A695107FCD19F +:10568000D3F810215207F8D1704700BF0020005214 +:1056900008B50D4B1B78ABB9FFF7ECFF0B4BDA6885 +:1056A000D10704D50A4A5A6002F188325A60D3F809 +:1056B0000C21D20706D5064AC3F8042102F188322C +:1056C000C3F8042108BD00BF2E8000200020005236 +:1056D0002301674508B5114B1B78F3B9104B1A69C4 +:1056E000510703D5DA6842F04002DA60D3F810219E +:1056F000520705D5D3F80C2142F04002C3F80C2123 +:10570000FFF7B8FF064BDA6842F00102DA60D3F81F +:105710000C2142F00102C3F80C2108BD2E800020AC +:10572000002000520F289ABF00F58060400400203E +:10573000704700004FF400307047000010207047A1 +:105740000F2808B50BD8FFF7EDFF00F5003302680E +:10575000013204D104308342F9D1012008BD002078 +:10576000FCE700000F2870B5054645D8FFF7D6FCCA +:10577000224CFFF77FFF0646FFF78AFF4FF0FF330B +:10578000072D6361C4F8143120D82361FFF772FF3D +:105790002B0243F02403E360E36843F08003E360FB +:1057A00023695A07FCD42846FFF764FF4FF4003101 +:1057B000FFF7B8FF00F060F93046FFF78BFFFFF707 +:1057C000B7FC2846BDE87040FFF7BABFC4F81031F7 +:1057D000FFF750FFA5F108031B0243F02403C4F8B0 +:1057E0000C31D4F80C3143F08003C4F80C31D4F8F8 +:1057F00010315B07FBD4D6E7002070BD00200052BB +:105800002DE9F84F40EA020305460C461746D80634 +:1058100002D00020BDE8F88F27F01F07DFF8D4B0D2 +:10582000FFF736FF2744BC4203D10120FFF752FFA8 +:10583000F0E720222946204601F098FC10B92035D7 +:105840002034F0E72B4605F120021E68711CE0D1E0 +:1058500004339A42F9D1FFF761FC05F17843234AFA +:10586000B3F5801F224B28BF9A4603F1040338BFCB +:105870009046A2F1080228BF9846A3F108033ABF58 +:105880009146DA469946FFF7F5FEC8F80060A5EBA9 +:10589000040CD9F8002004F11C0142F00202C9F8FE +:1058A0000020221FDAF8006016F00506FAD152F83F +:1058B000043F8A424CF80230F4D1BFF34F8FFFF718 +:1058C000D9FE4FF0FF32C8F80020D9F8002022F0AE +:1058D0000202C9F80020FFF72BFC202221462846AF +:1058E00001F044FC0028AAD030469FE71420005263 +:1058F000102100521020005210B5084C237828B116 +:105900001BB9FFF7C5FE0123237010BD002BFCD08F +:105910002070BDE81040FFF7DDBE00BF2E800020E4 +:1059200038B5054D00240334696855F80C0B00F0B8 +:10593000B5F8122CF7D138BDC875000870B5104EF7 +:1059400082B0FFF7EBFB054601F06AF832680346C8 +:105950009042336037BF0B4A0A495168146836BF1A +:105960000131D1E9004151600419284641F100019B +:105970000191FFF7DDFB2046019902B070BD00BF29 +:10598000308000203880002070B5124E82B0FFF7C2 +:10599000C5FB054601F044F8326803469042336087 +:1059A00037BF0D4A0C495168146836BF0131D1E93F +:1059B000004151600419284641F100010191FFF7AF +:1059C000B7FB4FF47A72002320460199FAF770FC76 +:1059D00002B070BD30800020388000200244074BA8 +:1059E000D2B210B5904200D110BD441C00B253F8A1 +:1059F000200041F8040BE0B2F4E700BF504000582B +:105A00000E4B30B51C6F240405D41C6F1C671C6F33 +:105A100044F400441C670A4C02442368D2B243F4A5 +:105A200080732360074B904200D130BD441C51F875 +:105A3000045B00B243F82050E0B2F4E7004402589F +:105A4000004802585040005807B5012201A9002023 +:105A5000FFF7C4FF019803B05DF804FB13B50446DB +:105A6000FFF7F2FFA04205D0012201A90020019416 +:105A7000FFF7C6FF02B010BD0144BFF34F8F064BC6 +:105A8000884204D3BFF34F8FBFF36F8F7047C3F8C3 +:105A90005C022030F4E700BF00ED00E00144BFF3FA +:105AA0004F8F064B884204D3BFF34F8FBFF36F8FE6 +:105AB0007047C3F870022030F4E700BF00ED00E04B +:105AC00070470000074B45F255521A6002225A6097 +:105AD00040F6FF729A604CF6CC421A600122024BEB +:105AE0001A7070470048005844800020034B1B7810 +:105AF0001BB1034B4AF6AA221A607047448000206B +:105B000000480058034B1A681AB9034AD2F8D02447 +:105B10001A6070474080002000400258024B4FF44A +:105B20008032C3F8D02470470040025808B5FFF710 +:105B3000E9FF024B1868C0F3806008BD4080002078 +:105B400070B5BFF34F8FBFF36F8F1A4A0021C2F8B1 +:105B50005012BFF34F8FBFF36F8F536943F400337D +:105B60005361BFF34F8FBFF36F8FC2F88410BFF341 +:105B70004F8FD2F8803043F6E074C3F3C900C3F30B +:105B80004E335B0103EA0406014646EA817501399A +:105B9000C2F86052F9D2203B13F1200FF2D1BFF3CB +:105BA0004F8F536943F480335361BFF34F8FBFF37B +:105BB0006F8F70BD00ED00E0FEE700000A4B0B4860 +:105BC0000B4A90420BD30B4BC11EDA1C121A22F067 +:105BD00003028B4238BF00220021FCF79BB853F828 +:105BE000041B40F8041BECE75078000820820020DA +:105BF00020820020208200207047000070B5D0E98C +:105C0000244300224FF0FF359E6804EB42135101FC +:105C1000D3F80009002805DAD3F8000940F08040E5 +:105C2000C3F80009D3F8000B002805DAD3F8000BFD +:105C300040F08040C3F8000B013263189642C3F86D +:105C40000859C3F8085BE0D24FF00113C4F81C38C0 +:105C500070BD000000EB8103D3F80CC02DE9F043C8 +:105C6000DCF814204E1CD0F89050D2F800E005EB80 +:105C7000063605EB4118506870450AD30122D5F865 +:105C8000343802FA01F123EA0101C5F83418BDE8FD +:105C9000F083AEEB0003BCF81040A34228BF2346BC +:105CA000D8F81849A4B2B3EB840FF0D89468A4F1E3 +:105CB000040959F8047F3760A4EB09071F44042F37 +:105CC000F7D81C44034494605360D4E7890141F041 +:105CD0002001016103699B06FCD41220FFF738BA4A +:105CE00010B50A4C2046FEF79DFE094BC4F89030D3 +:105CF000084BC4F89430084C2046FEF793FE074B3F +:105D0000C4F89030064BC4F8943010BD4880002091 +:105D10000000084034760008E480002000000440C1 +:105D20004076000870B503780546012B5DD1494BDC +:105D3000D0F89040984259D1474B0E216520D3F8B6 +:105D4000D82042F00062C3F8D820D3F8002142F0F6 +:105D50000062C3F80021D3F80021D3F8802042F07C +:105D60000062C3F88020D3F8802022F00062C3F8DC +:105D70008020D3F88030FEF7D5FA384BE360384BFB +:105D8000C4F800380023D5F89060C4F8003EC02362 +:105D900023604FF40413A3633369002BFCDA01235F +:105DA0000C203361FFF7D4F93369DB07FCD41220F0 +:105DB000FFF7CEF93369002BFCDA00262846A660EF +:105DC000FFF71CFF6B68C4F81068DB68C4F8146840 +:105DD000C4F81C68002B3AD1224BA3614FF0FF336B +:105DE0006361A36843F00103A36070BD1E4B98423A +:105DF000C8D1194B0E214D20D3F8D82042F00072A3 +:105E0000C3F8D820D3F8002142F00072C3F8002173 +:105E1000D3F80021D3F8802042F00072C3F880202C +:105E2000D3F8802022F00072C3F88020D3F88020BD +:105E3000D3F8D82022F08062C3F8D820D3F800210C +:105E400022F08062C3F80021D3F8003193E7074BBA +:105E5000C3E700BF488000200044025840140040BF +:105E600003002002003C30C0E4800020083C30C029 +:105E7000F8B5D0F89040054600214FF00066204666 +:105E8000FFF724FFD5F8941000234FF001128F681C +:105E90004FF0FF30C4F83438C4F81C2804EB431228 +:105EA00001339F42C2F80069C2F8006BC2F80809CA +:105EB000C2F8080BF2D20B68D5F89020C5F89830DC +:105EC000636210231361166916F01006FBD11220CD +:105ED000FFF73EF9D4F8003823F4FE63C4F8003825 +:105EE000A36943F4402343F01003A3610923C4F8DA +:105EF0001038C4F814380B4BEB604FF0C043C4F8B3 +:105F0000103B094BC4F8003BC4F81069C4F80039D1 +:105F1000D5F8983003F1100243F48013C5F89820A7 +:105F2000A362F8BD1076000840800010D0F89020E1 +:105F300090F88A10D2F8003823F4FE6343EA011384 +:105F4000C2F80038704700002DE9F84300EB8103E8 +:105F5000D0F890500C468046DA680FFA81F9480173 +:105F6000166806F00306731E022B05EB41134FF073 +:105F7000000194BFB604384EC3F8101B4FF0010166 +:105F800004F1100398BF06F1805601FA03F39169FA +:105F900098BF06F5004600293AD0578A04F1580107 +:105FA000374349016F50D5F81C180B430021C5F841 +:105FB0001C382B180127C3F81019A7405369611E1C +:105FC0009BB3138A928B9B08012A88BF5343D8F84E +:105FD0009820981842EA034301F140022146C8F88C +:105FE0009800284605EB82025360FFF76FFE08EB2E +:105FF0008900C3681B8A43EA845348341E43640102 +:106000002E51D5F81C381F43C5F81C78BDE8F8831D +:1060100005EB4917D7F8001B21F40041C7F8001B16 +:10602000D5F81C1821EA0303C0E704F13F030B4A2B +:106030002846214605EB83035A60FFF747FE05EB30 +:106040004910D0F8003923F40043C0F80039D5F8DE +:106050001C3823EA0707D7E700800010000400027D +:10606000D0F894201268C0F89820FFF7C7BD000050 +:106070005831D0F8903049015B5813F4004004D0F7 +:1060800013F4001F0CBF0220012070474831D0F8E4 +:10609000903049015B5813F4004004D013F4001F02 +:1060A0000CBF02200120704700EB8101CB68196A08 +:1060B0000B6813604B6853607047000000EB81036E +:1060C00030B5DD68AA691368D36019B9402B84BF65 +:1060D000402313606B8A1468D0F890201C4402EBB4 +:1060E0004110013C09B2B4FBF3F46343033323F0E2 +:1060F000030343EAC44343F0C043C0F8103B2B689A +:1061000003F00303012B0ED1D2F8083802EB411043 +:1061100013F4807FD0F8003B14BF43F0805343F06A +:106120000053C0F8003B02EB4112D2F8003B43F0B1 +:106130000443C2F8003B30BD2DE9F041D0F8906037 +:1061400005460C4606EB4113D3F8087B3A07C3F823 +:10615000087B08D5D6F814381B0704D500EB81035B +:10616000DB685B689847FA071FD5D6F81438DB0759 +:106170001BD505EB8403D968CCB98B69488A5A686A +:10618000B2FBF0F600FB16228AB91868DA68904272 +:106190000DD2121AC3E90024202383F3118821466B +:1061A0002846FFF78BFF84F31188BDE8F0810123B7 +:1061B00003FA04F26B8923EA02036B81CB68002B9C +:1061C000F3D021462846BDE8F041184700EB810393 +:1061D0004A0170B5DD68D0F890306C692668E660D9 +:1061E00056BB1A444FF40020C2F810092A6802F086 +:1061F0000302012A0AB20ED1D3F8080803EB4214B5 +:1062000010F4807FD4F8000914BF40F0805040F0B3 +:106210000050C4F8000903EB4212D2F8000940F024 +:106220000440C2F800090122D3F8340802FA01F14F +:106230000143C3F8341870BD19B9402E84BF402003 +:10624000206020681A442E8A8419013CB4FBF6F4BD +:1062500040EAC44040F00050C6E700002DE9F0419C +:10626000D0F8906004460D4606EB4113D3F8087948 +:10627000C3F80879FB071CD5D6F81038DA0718D50B +:1062800000EB8103D3F80CC0DCF81430D3F800E045 +:10629000DA6896451BD2A2EB0E024FF000081A6096 +:1062A000C3F80480202383F31188FFF78FFF88F35E +:1062B00011883B0618D50123D6F83428AB40134289 +:1062C00012D029462046BDE8F041FFF7C3BC0123A8 +:1062D00003FA01F2038923EA02030381DCF80830A0 +:1062E000002BE6D09847E4E7BDE8F0812DE9F84FB0 +:1062F000D0F8905004466E69AB691E4016F4805881 +:106300006E6103D0BDE8F84FFEF7FCBB002E12DA39 +:10631000D5F8003E9F0705D0D5F8003E23F00303D3 +:10632000C5F8003ED5F80438204623F00103C5F82F +:106330000438FEF713FC300505D52046FFF75EFC58 +:106340002046FEF7FBFBB1040CD5D5F8083813F056 +:10635000060FEB6823F470530CBF43F4105343F45F +:10636000A053EB60320704D56368DB680BB12046AD +:106370009847F30200F1BA80B70226D5D4F890907E +:1063800000274FF0010A09EB4712D2F8003B03F453 +:106390004023B3F5802F11D1D2F8003B002B0DDA4A +:1063A00062890AFA07F322EA0303638104EB870395 +:1063B000DB68DB6813B13946204698470137D4F8CB +:1063C0009430FFB29B689F42DDD9F00619D5D4F80E +:1063D0009000026AC2F30A1702F00F0302F4F012EF +:1063E000B2F5802F00F0CC80B2F5402F09D104EB3C +:1063F0008303002200F58050DB681B6A974240F05F +:10640000B2803003D5F8185835D5E90303D50021FB +:106410002046FFF791FEAA0303D501212046FFF78E +:106420008BFE6B0303D502212046FFF785FE2F0369 +:1064300003D503212046FFF77FFEE80203D50421A0 +:106440002046FFF779FEA90203D505212046FFF774 +:1064500073FE6A0203D506212046FFF76DFE2B026C +:1064600003D507212046FFF767FEEF0103D508217A +:106470002046FFF761FE700340F1A980E90703D5CC +:1064800000212046FFF7EAFEAA0703D50121204696 +:10649000FFF7E4FE6B0703D502212046FFF7DEFE7F +:1064A0002F0703D503212046FFF7D8FEEE0603D5BC +:1064B00004212046FFF7D2FEA80603D50521204679 +:1064C000FFF7CCFE690603D506212046FFF7C6FE7E +:1064D0002A0603D507212046FFF7C0FEEB0576D537 +:1064E00020460821BDE8F84FFFF7B8BED4F89090D9 +:1064F00000274FF0010AD4F894305FFA87FB9B68BD +:106500009B453FF639AF09EB4B13D3F8002902F452 +:106510004022B2F5802F24D1D3F80029002A20DAB6 +:10652000D3F8002942F09042C3F80029D3F800299B +:10653000002AFBDB5946D4F89000FFF7C7FB2289FD +:106540000AFA0BF322EA0303238104EB8B03DB68D3 +:106550009B6813B159462046984759462046FFF795 +:1065600079FB0137C7E7910701D1D0F80080072AEE +:1065700002F101029CBF03F8018B4FEA18283DE7A6 +:1065800004EB830300F58050DA68D2F818C0DCF819 +:106590000820DCE9001CA1EB0C0C00218F4208D183 +:1065A000DB689B699A683A449A605A683A445A6030 +:1065B00027E711F0030F01D1D0F800808C4501F1DD +:1065C000010184BF02F8018B4FEA1828E6E7BDE815 +:1065D000F88F000008B50348FFF788FEBDE80840C3 +:1065E000FDF766BD4880002008B50348FFF77EFE32 +:1065F000BDE80840FDF75CBDE4800020D0F8903095 +:1066000003EB4111D1F8003B43F40013C1F8003B08 +:1066100070470000D0F8903003EB4111D1F80039F9 +:1066200043F40013C1F8003970470000D0F89030EF +:1066300003EB4111D1F8003B23F40013C1F8003BF8 +:1066400070470000D0F8903003EB4111D1F80039C9 +:1066500023F40013C1F800397047000030B504334B +:10666000039C0172002104FB0325C160C0E90653AD +:10667000049B0363059BC0E90000C0E90422C0E954 +:106680000842C0E90A11436330BD00000022416A9C +:10669000C260C0E90411C0E90A226FF00101FEF7EF +:1066A000C7BD0000D0E90432934201D1C2680AB9E3 +:1066B000181D704700207047036919600021C268E7 +:1066C0000132C260C269134482699342036124BFEC +:1066D000436A0361FEF7A0BD38B504460D46E36882 +:1066E0003BB162690020131D1268A3621344E36288 +:1066F00007E0237A33B929462046FEF77DFD0028BE +:10670000EDDA38BD6FF00100FBE70000C368C26935 +:10671000013BC3604369134482699342436124BFD0 +:10672000436A436100238362036B03B118477047D8 +:1067300070B52023044683F31188866A3EB9FFF7BB +:10674000CBFF054618B186F31188284670BDA36AB1 +:10675000E26A13F8015B9342A36202D32046FFF77B +:10676000D5FF002383F31188EFE700002DE9F84FF0 +:1067700004460E46174698464FF0200989F31188C3 +:106780000025AA46D4F828B0BBF1000F09D1414634 +:106790002046FFF7A1FF20B18BF311882846BDE802 +:1067A000F88FD4E90A12A7EB050B521A934528BFBC +:1067B0009346BBF1400F1BD9334601F1400251F81B +:1067C000040B914243F8040BF9D1A36A40364035DB +:1067D0004033A362D4E90A239A4202D32046FFF74A +:1067E00095FF8AF31188BD42D8D289F31188C9E791 +:1067F00030465A46FBF768FAA36A5E445D445B4440 +:10680000A362E7E710B5029C0433017204FB032185 +:10681000C460C0E906130023C0E90A33039B036385 +:10682000049BC0E90000C0E90422C0E908424363B8 +:1068300010BD0000026A6FF00101C260426AC0E947 +:1068400004220022C0E90A22FEF7F2BCD0E90423A8 +:106850009A4201D1C26822B9184650F8043B0B6035 +:106860007047002070470000C3680021C2690133EF +:10687000C3604369134482699342436124BF436AFE +:106880004361FEF7C9BC000038B504460D46E36815 +:106890003BB1236900201A1DA262E2691344E3623E +:1068A00007E0237A33B929462046FEF7A5FC0028E5 +:1068B000EDDA38BD6FF00100FBE7000003691960F5 +:1068C000C268013AC260C26913448269934203619B +:1068D00024BF436A036100238362036B03B118473B +:1068E0007047000070B520230D460446114683F31F +:1068F0001188866A2EB9FFF7C7FF10B186F3118899 +:1069000070BDA36A1D70A36AE26A01339342A36259 +:1069100004D3E16920460439FFF7D0FF002080F35B +:106920001188EDE72DE9F84F04460D46904699464B +:106930004FF0200A8AF311880026B346A76A4FB9A0 +:1069400049462046FFF7A0FF20B187F31188304663 +:10695000BDE8F88FD4E90A073A1AA8EB0607974270 +:1069600028BF1746402F1BD905F1400355F8042BCB +:106970009D4240F8042BF9D1A36A40364033A3620C +:10698000D4E90A239A4204D3E16920460439FFF787 +:1069900095FF8BF311884645D9D28AF31188CDE74C +:1069A00029463A46FBF790F9A36A3D443E443B44EE +:1069B000A362E5E7D0E904239A4217D1C3689BB1EB +:1069C000836A8BB1043B9B1A0ED01360C368013BF2 +:1069D000C360C3691A4483699A42026124BF436A4F +:1069E0000361002383620123184670470023FBE7FD +:1069F00000F0CEB8034B002258631A610222DA601D +:106A0000704700BF000C0040014B0022DA60704765 +:106A1000000C0040014B5863704700BF000C004061 +:106A2000014B586A704700BF000C00404B68436040 +:106A30008B688360CB68C3600B6943614B690362F9 +:106A40008B6943620B6803607047000008B5364BE2 +:106A500040F2FF713548D3F888200A43C3F88820F4 +:106A6000D3F8882022F4FF6222F00702C3F88820BE +:106A7000D3F88820D3F8E0200A43C3F8E020D3F805 +:106A800008210A43C3F80821294AD3F808311146DE +:106A9000FFF7CCFF00F5806002F11C01FFF7C6FF95 +:106AA00000F5806002F13801FFF7C0FF00F580605B +:106AB00002F15401FFF7BAFF00F5806002F17001A6 +:106AC000FFF7B4FF00F5806002F18C01FFF7AEFF25 +:106AD00000F5806002F1A801FFF7A8FF00F58060D3 +:106AE00002F1C401FFF7A2FF00F5806002F1E001AE +:106AF000FFF79CFF00F5806002F1FC01FFF796FFB5 +:106B000002F58C7100F58060FFF790FF00F0F4F85B +:106B1000084B0522C3F898204FF06052C3F89C2020 +:106B2000054AC3F8A02008BD0044025800000258DE +:106B30004C76000800ED00E01F00080308B500F0E7 +:106B4000D7FAFEF7BDFA0F4BD3F8DC2042F0400233 +:106B5000C3F8DC20D3F8042122F04002C3F804215A +:106B6000D3F80431084B1A6842F008021A601A6818 +:106B700042F004021A60FEF7C5FFBDE80840FEF7C8 +:106B8000D3BC00BF00440258001802487047000000 +:106B9000114BD3F8E82042F00802C3F8E820D3F8FC +:106BA000102142F00802C3F810210C4AD3F810312A +:106BB000D36B43F00803D363C722094B9A624FF0AB +:106BC000FF32DA6200229A615A63DA605A60012267 +:106BD0005A611A60704700BF004402580010005C00 +:106BE000000C0040094A08B51169D3680B40D9B2BE +:106BF0009B076FEA0101116107D5202383F31188F8 +:106C0000FEF78AFA002383F3118808BD000C0040C8 +:106C1000384B4FF0FF31D3F88020C3F88010D3F801 +:106C200080200022C3F88020D3F88000D3F88400AD +:106C3000C3F88410D3F88400C3F88420D3F8840008 +:106C4000D86F40F0FF4040F4FF0040F43F5040F068 +:106C50003F00D867D86F20F0FF4020F4FF0020F4F9 +:106C60003F5020F03F00D867D86FD3F888006FEA14 +:106C700040506FEA5050C3F88800D3F88800C0F342 +:106C80000A00C3F88800D3F88800D3F89000C3F84E +:106C90009010D3F89000C3F89020D3F89000D3F868 +:106CA0009400C3F89410D3F89400C3F89420D3F858 +:106CB0009400D3F89800C3F89810D3F89800C3F85C +:106CC0009820D3F89800D3F88C00C3F88C10D3F830 +:106CD0008C00C3F88C20D3F88C00D3F89C00C3F848 +:106CE0009C10D3F89C10C3F89C20D3F89C3000F083 +:106CF000D3B900BF00440258614B0122C3F80821F8 +:106D0000604BD3F8F42042F00202C3F8F420D3F829 +:106D10001C2142F00202C3F81C210222D3F81C31CC +:106D2000594BDA605A689104FCD5584A1A6001221E +:106D30009A60574ADA6000221A614FF440429A6121 +:106D4000514B9A699204FCD51A6842F480721A6019 +:106D50004C4B1A6F12F4407F04D04FF480321A6704 +:106D600000221A671A6842F001021A60454B1A683D +:106D70005007FCD500221A611A6912F03802FBD1C3 +:106D8000012119604FF0804159605A67414ADA6227 +:106D9000414A1A611A6842F480321A60394B1A6803 +:106DA0009103FCD51A6842F480521A601A68920462 +:106DB000FCD53A4A3A499A6200225A631963394922 +:106DC000DA6399635A64384A1A64384ADA621A688C +:106DD00042F0A8521A602B4B1A6802F02852B2F106 +:106DE000285FF9D148229A614FF48862DA61402223 +:106DF0001A622F4ADA644FF080521A652D4A5A659A +:106E00002D4A9A6532232D4A1360136803F00F034D +:106E1000022BFAD11B4B1A6942F003021A611A695C +:106E200002F03802182AFAD1D3F8DC2042F00052DE +:106E3000C3F8DC20D3F8042142F00052C3F8042147 +:106E4000D3F80421D3F8DC2042F08042C3F8DC20E0 +:106E5000D3F8042142F08042C3F80421D3F804217E +:106E6000D3F8DC2042F00042C3F8DC20D3F8042140 +:106E700042F00042C3F80421D3F80431704700BF48 +:106E800000800051004402580048025800C000F041 +:106E9000020000010000FF0100889008322060001D +:106EA000630209011D02040047040508FD0BFF01F0 +:106EB000200000200010E00000010100002000522E +:106EC0004FF0B04208B5D2F8883003F00103C2F8A1 +:106ED000883023B1044A13680BB150689847BDE865 +:106EE0000840FDF7E5B800BF988100204FF0B042A0 +:106EF00008B5D2F8883003F00203C2F8883023B115 +:106F0000044A93680BB1D0689847BDE80840FDF784 +:106F1000CFB800BF988100204FF0B04208B5D2F83A +:106F2000883003F00403C2F8883023B1044A13699F +:106F30000BB150699847BDE80840FDF7B9B800BFEC +:106F4000988100204FF0B04208B5D2F8883003F0A5 +:106F50000803C2F8883023B1044A93690BB1D069A1 +:106F60009847BDE80840FDF7A3B800BF988100200E +:106F70004FF0B04208B5D2F8883003F01003C2F8E1 +:106F8000883023B1044A136A0BB1506A9847BDE8B0 +:106F90000840FDF78DB800BF988100204FF0B04346 +:106FA00010B5D3F8884004F47872C3F88820A3069B +:106FB00004D5124A936A0BB1D06A9847600604D58B +:106FC0000E4A136B0BB1506B9847210604D50B4A40 +:106FD000936B0BB1D06B9847E20504D5074A136C4D +:106FE0000BB1506C9847A30504D5044A936C0BB1C0 +:106FF000D06C9847BDE81040FDF75AB89881002042 +:107000004FF0B04310B5D3F8884004F47C42C3F885 +:107010008820620504D5164A136D0BB1506D984750 +:10702000230504D5124A936D0BB1D06D9847E00447 +:1070300004D50F4A136E0BB1506E9847A10404D5C6 +:107040000B4A936E0BB1D06E9847620404D5084A80 +:10705000136F0BB1506F9847230404D5044A936F04 +:107060000BB1D06F9847BDE81040FDF721B800BFC5 +:107070009881002008B50348FDF7D0F8BDE8084026 +:10708000FDF716B8D45E002008B5FFF7ABFDBDE8EC +:107090000840FDF70DB80000062108B50846FDF7C9 +:1070A00041F906210720FDF73DF906210820FDF7EB +:1070B00039F906210920FDF735F906210A20FDF7E7 +:1070C00031F906211720FDF72DF906212820FDF7BB +:1070D00029F909217A20FDF725F907213220FDF74A +:1070E00021F90C215220BDE80840FDF71BB9000032 +:1070F00008B5FFF78DFD00F00DF8FDF7B7FAFDF7C5 +:107100008FFCFDF761FBFFF741FDBDE80840FFF78D +:107110006FBC00000023054A19460133102BC2E959 +:10712000001102F10802F8D1704700BF98810020D9 +:107130000B460146184600F003B8000000F00EB8F8 +:1071400010B5054C13462CB10A4601460220AFF398 +:10715000008010BD2046FCE700000000024B014605 +:10716000186800F035B800BF6422002010B501395E +:107170000244904201D1002005E0037811F8014F4C +:10718000A34201D0181B10BD0130F2E72DE9F041F8 +:10719000A3B1C91A17780144044603F1FF3C8C429D +:1071A000204601D9002009E00578BD4204F1010420 +:1071B000F5D10CEB0405D618A54201D1BDE8F0814C +:1071C00015F8018D16F801EDF045F5D0E7E7000060 +:1071D00037B5002944D051F8043C0190002BA1F1AF +:1071E0000404B8BFE41800F047F81E4A0198136879 +:1071F00033B96360146003B0BDE8304000F042B8BA +:10720000A34208D9256861198B4201BF19685B68E0 +:1072100049192160EDE71A465B680BB1A342FAD920 +:1072200011685518A5420BD1246821445418A34273 +:107230001160E0D11C685B68536021441160DAE79B +:1072400002D90C230360D6E7256861198B4204BF7D +:1072500019685B68636004BF491921605460CAE71C +:1072600003B030BD18820020034611F8012B03F84B +:10727000012B002AF9D17047014800F009B800BF7E +:107280001C820020014800F005B800BF1C820020CD +:1072900070470000704700006F72672E617264755E +:1072A00070696C6F742E437562654F72616E6765AD +:1072B0002D706572697068004E6F20617070207368 +:1072C00069670A00426164206677206C656E6774A6 +:1072D000682025750A0042616420626F6172645FF4 +:1072E00069642025752073686F756C642062652061 +:1072F00025750A00426164206677206465736372B5 +:107300006970746F72206C656E6774682025750AE9 +:107310000042616420617070204352432030782520 +:107320003038783A30782530387820307825303841 +:10733000783A3078253038780A00476F6F642066D5 +:1073400069726D776172650A0040A2E4F164689128 +:107350000600000053544D333248373F3F3F00533F +:10736000544D3332483734332F3735330000000063 +:10737000F8640020D45E002043414E4644496661D3 +:1073800063653A204D6573736167652052414D20F6 +:107390004F766572666C6F77210000004261642051 +:1073A00043414E496661636520696E6465782E00CD +:1073B000000100000001FF0000A0004000A4004008 +:1073C0000000000000000000C1250008991E000810 +:1073D000012D00088D1E0008091F00081923000850 +:1073E00081200008D11E0008D51E0008911E00084B +:1073F000AD1E0008951E0008D9220008B91E00081D +:107400000D2E0008C51E0008AD22000800960000E1 +:10741000000000000000000000000000000000006C +:10742000000000000000000035460008214600086A +:107430005D460008494600085546000841460008D8 +:107440002D460008194600086946000800000000A3 +:1074500045470008314700086D47000859470008B4 +:1074600065470008514700083D47000829470008C4 +:107470007947000800000000010000000000000043 +:107480006D61696E0000000069646C6500000000B9 +:107490008874000880630020F86400200100000068 +:1074A000BD500008000000004172647550696C6FA7 +:1074B000740025424F415244252D424C002553452E +:1074C0005249414C2500000002000000000000006D +:1074D00065490008D549000840004000A07D002013 +:1074E000B07D00200200000000000000030000004A +:1074F000000000001D4A000800000000100000000D +:10750000C07D00200000000001000000000000001D +:107510004880002001010200C5540008D55300082E +:1075200071540008555400084300000030750008ED +:1075300009024300020100C03209040000010202F6 +:1075400001000524001001052401000104240202A9 +:107550000524060001070582030800FF0904010055 +:10756000020A000000070501024000000705810231 +:1075700040000000120000007C750008120110019C +:1075800002000040091241570002010203010000FD +:107590000403090425424F415244250043756265A6 +:1075A0004F72616E67652D7065726970682D6865D0 +:1075B00061767900303132333435363738394142EB +:1075C0004344454600000000000000200000020087 +:1075D0000200000000010030000000000000000078 +:1075E0000000002400000800040000000004000067 +:1075F00000FC0000020000000000043000800000D9 +:107600000000000000000038000001000100000040 +:1076100000000000714B0008294E0008D54E0008FC +:107620004000400080810020808100200100000097 +:107630009081002080000000400100000800000050 +:107640000001000000040000080000000000802A83 +:1076500000000000AAAAAAAA00000024FFFF000060 +:107660000000000000A00A0000210002000000004D +:10767000AAAAAAAA00000000FFFF0000000000095B +:10768000000009001400005400000000AAAAAAAAE1 +:1076900014000054FFFF0000000000000000000084 +:1076A0000A40100000000000AAAA8AAA00401000A8 +:1076B000FFFF0000990000000000000000810200B0 +:1076C00000000000AAAAAAAA00410100FFFF0000D2 +:1076D0000000007007000000000000000000000033 +:1076E000AAAAAAAA00000000FFFF000000000000F4 +:1076F000000000000000000000000000AAAAAAAAE2 +:1077000000000000FFFF000000000000000000007B +:107710000000000000000000AAAAAAAA00000000C1 +:10772000FFFF00000000000000000000000000005B +:1077300000000000AAAAAAAA00000000FFFF0000A3 +:107740000000000000000000000000000000000039 +:10775000AAAAAAAA00000000FFFF00000000000083 +:10776000000000000000000000000000AAAAAAAA71 +:1077700000000000FFFF000000000000000000000B +:10778000608BFF7F01000000780500000000000012 +:1077900000001E0000000000FE2A0100D2040000CC +:1077A000FF00000000000000547300083F000000CC +:1077B000500400005F7300083F00000000960000C6 +:1077C000000008009600000000080000040000000F +:1077D000907500080000000000000000000000009C +:1077E00000000000000000000000000068220020EF +:1077F0000000000000000000000000000000000089 +:107800000000000000000000000000000000000078 +:107810000000000000000000000000000000000068 +:107820000000000000000000000000000000000058 +:107830000000000000000000000000000000000048 +:107840000000000000000000000000000000000038 +:00000001FF diff --git a/Tools/bootloaders/CubeOrange-periph_bl.bin b/Tools/bootloaders/CubeOrange-periph_bl.bin new file mode 100755 index 00000000000..d5d6278e4da Binary files /dev/null and b/Tools/bootloaders/CubeOrange-periph_bl.bin differ diff --git a/Tools/bootloaders/CubeOrange-periph_bl.hex b/Tools/bootloaders/CubeOrange-periph_bl.hex new file mode 100755 index 00000000000..a70909de553 --- /dev/null +++ b/Tools/bootloaders/CubeOrange-periph_bl.hex @@ -0,0 +1,1926 @@ +:020000040800F2 +:1000000000060020B5050008ED3100086D3100083C +:10001000C53100086D31000899310008B7050008A6 +:10002000B7050008B7050008B705000841400008FB +:10003000B7050008B7050008B7050008B7050008B0 +:10004000B7050008B7050008B7050008B7050008A0 +:10005000B7050008B7050008BD6E0008E96E000886 +:10006000156F0008416F00086D6F0008B7050008A4 +:10007000B7050008B7050008B7050008B705000870 +:10008000B7050008B7050008B7050008B52D00083A +:10009000DD2D0008C92D0008F12D0008996F00081A +:1000A000B7050008B7050008B7050008B705000840 +:1000B000B7050008B7050008B7050008B705000830 +:1000C000B7050008B7050008B7050008B705000820 +:1000D000B7050008B7050008B7050008B705000810 +:1000E000FD6F0008B7050008B7050008B705000850 +:1000F000B7050008B7050008B7050008B7050008F0 +:10010000B7050008B705000885700008B7050008A6 +:10011000B7050008B7050008B7050008B7050008CF +:10012000B7050008B7050008B7050008B7050008BF +:10013000B7050008B7050008B7050008B7050008AF +:10014000B7050008B7050008B7050008B70500089F +:10015000B7050008B7050008B7050008B70500088F +:10016000B7050008B7050008B7050008B70500087F +:10017000B7050008E5650008B7050008B7050008E1 +:10018000B7050008B705000871700008B70500083A +:10019000B7050008B7050008B7050008B70500084F +:1001A000B7050008B7050008B7050008B70500083F +:1001B000B7050008B7050008B7050008B70500082F +:1001C000B7050008B7050008B7050008B70500081F +:1001D000B7050008D1650008B7050008B705000895 +:1001E000B7050008B7050008B7050008B7050008FF +:1001F000B7050008B7050008B7050008B7050008EF +:10020000B7050008B7050008B7050008B7050008DE +:10021000B7050008B7050008B7050008B7050008CE +:10022000B7050008B7050008B7050008B7050008BE +:10023000B7050008B7050008B7050008B7050008AE +:10024000B7050008B7050008B7050008B70500089E +:10025000B7050008B7050008B7050008B70500088E +:10026000B7050008B7050008B7050008B70500087E +:10027000B7050008B7050008B7050008B70500086E +:10028000B7050008B7050008B7050008B70500085E +:10029000B7050008B7050008B7050008B70500084E +:1002A000391A0008000000000000000000000000F3 +:1002B00053B94AB9002908BF00281CBF4FF0FF31CD +:1002C0004FF0FF3000F074B9ADF1080C6DE904CEC9 +:1002D00000F006F8DDF804E0DDE9022304B0704721 +:1002E0002DE9F047089D04468E46002B4DD18A42E9 +:1002F000944669D9B2FA82F252B101FA02F3C2F11C +:10030000200120FA01F10CFA02FC41EA030E9440AC +:100310004FEA1C48210CBEFBF8F61FFA8CF708FBCD +:1003200016E341EA034306FB07F199420AD91CEBA5 +:10033000030306F1FF3080F01F81994240F21C81D7 +:10034000023E63445B1AA4B2B3FBF8F008FB10331F +:1003500044EA034400FB07F7A7420AD91CEB040454 +:1003600000F1FF3380F00A81A74240F20781644424 +:10037000023840EA0640E41B00261DB1D4400023A9 +:10038000C5E900433146BDE8F0878B4209D9002D0D +:1003900000F0EF800026C5E9000130463146BDE897 +:1003A000F087B3FA83F6002E4AD18B4202D3824201 +:1003B00000F2F980841A61EB030301209E46002DB0 +:1003C000E0D0C5E9004EDDE702B9FFDEB2FA82F205 +:1003D000002A40F09280A1EB0C014FEA1C471FFA63 +:1003E0008CFE0126200CB1FBF7F307FB131140EA4A +:1003F00001410EFB03F0884208D91CEB010103F117 +:10040000FF3802D2884200F2CB804346091AA4B2D8 +:10041000B1FBF7F007FB101144EA01440EFB00FEAC +:10042000A64508D91CEB040400F1FF3102D2A64511 +:1004300000F2BB800846A4EB0E0440EA03409CE7B0 +:10044000C6F12007B34022FA07FC4CEA030C20FA5D +:1004500007F401FA06F31C43F9404FEA1C4900FA7D +:1004600006F3B1FBF9F8200C1FFA8CFE09FB1811FA +:1004700040EA014108FB0EF0884202FA06F20BD96D +:100480001CEB010108F1FF3A80F08880884240F2BD +:100490008580A8F102086144091AA4B2B1FBF9F001 +:1004A00009FB101144EA014100FB0EFE8E4508D9FC +:1004B0001CEB010100F1FF346CD28E456AD9023881 +:1004C000614440EA0840A0FB0294A1EB0E01A14266 +:1004D000C846A64656D353D05DB1B3EB080261EBD4 +:1004E0000E0101FA07F722FA06F3F1401F43C5E9AE +:1004F000007100263146BDE8F087C2F12003D840E4 +:100500000CFA02FC21FA03F3914001434FEA1C4725 +:100510001FFA8CFEB3FBF7F007FB10360B0C43EA17 +:10052000064300FB0EF69E4204FA02F408D91CEBC7 +:10053000030300F1FF382FD29E422DD902386344C5 +:100540009B1B89B2B3FBF7F607FB163341EA034165 +:1005500006FB0EF38B4208D91CEB010106F1FF38B4 +:1005600016D28B4214D9023E6144C91A46EA0046AB +:1005700038E72E46284605E70646E3E61846F8E63D +:100580004B45A9D2B9EB020864EB0C0E0138A3E786 +:100590004646EAE7204694E74046D1E7D0467BE767 +:1005A000023B614432E7304609E76444023842E7DF +:1005B000704700BF02E000F000F8FEE772B63A486C +:1005C00080F30888394880F3098839484EF6085185 +:1005D000CEF20001086040F20000CCF200004EF6BE +:1005E0003471CEF200010860BFF34F8FBFF36F8FFD +:1005F00040F20000C0F2F0004EF68851CEF2000149 +:100600000860BFF34F8FBFF36F8F4FF00000E1EE34 +:10061000100A4EF63C71CEF200010860062080F30D +:100620001488BFF36F8F05F0E5FA05F087FA06F03E +:100630000BFA4FF055301F491B4A91423CBF41F81D +:10064000040BFAE71C49194A91423CBF41F8040BDC +:10065000FAE71A491A4A1B4B9A423EBF51F8040B5B +:1006600042F8040BF8E700201749184A91423CBFB2 +:1006700041F8040BFAE705F09FFA06F05DFA144C16 +:10068000144DAC4203DA54F8041B8847F9E700F034 +:1006900041F8114C114DAC4203DA54F8041B884761 +:1006A000F9E705F087BA00000006002000220020CC +:1006B00000000008000000200006002070770008FD +:1006C00000220020C8220020C82200202082002012 +:1006D000A0020008A4020008A4020008A402000866 +:1006E0002DE9F04F2DED108AC1F80CD0D0F80CD0C8 +:1006F000BDEC108ABDE8F08F002383F311882846F3 +:10070000A047002004F066FDFEE704F0D5FC00DF02 +:10071000FEE70000F8B501F0CFFA30B1264B002219 +:100720000E211A725A729972DA7205F08BF9074625 +:1007300005F0FAF90546A0BB204B9F4231D00133AA +:100740009F4231D027F0FF021D4B9A422FD12E46F7 +:1007500042F21074F8B200F09FFD00F0A7FF08B15C +:100760000024264600F09EFD08B90646044635B131 +:10077000144B9F4203D0002405F0CEF926460020FA +:1007800005F06AF90EB100F065F801F019FB00F010 +:10079000B1FF01F0D7F9204600F012F900F05AF845 +:1007A000F9E72E460024D8E704460126D5E7064699 +:1007B00041F28834D1E700BF00220020010007B0D9 +:1007C000000008B0263A09B008B501F087F9A0F199 +:1007D00020035842584108BD07B541F212030221D7 +:1007E00001A8ADF8043001F097F903B05DF804FBFF +:1007F000202310B583F311881248C3680BB104F0AD +:100800006FFD0023104A4FF47A710E4804F02CFD5E +:10081000002383F311880D4C236813B12368013B37 +:100820002360636813B16368013B6360084B1B7806 +:1008300033B9636823B9022001F044FA32236360BC +:1008400010BD00BFC8220020F1070008E4230020EB +:10085000DC220020F8B5534B534A1C46196801317D +:1008600000F09F8004339342F8D162684F4B9A4264 +:1008700040F297804E4B9B6803F1006303F5003311 +:100880009A4280F08E8005F01BF905F02DF90020CA +:1008900001F072F90220474B187001F011FA464B33 +:1008A0000021D3F8E820C3F8E810D3F81021C3F8EA +:1008B0001011D3F81021D3F8EC20C3F8EC10D3F8C2 +:1008C0001421C3F81411D3F81421D3F8F020C3F87D +:1008D000F010D3F81821C3F81811D3F81821D3F861 +:1008E000802042F00062C3F88020D3F8802022F0FC +:1008F0000062C3F88020D3F88020D3F8802042F033 +:100900000072C3F88020D3F8802022F00072C3F870 +:100910008020D3F8803072B64FF0E023C3F8084D42 +:10092000D4E90004BFF34F8FBFF36F8F234AC2F89F +:100930008410BFF34F8F536923F480335361BFF3A7 +:100940004F8FD2F8803043F6E076C3F3C905C3F386 +:100950004E335B0103EA060C29464CEA81770139E4 +:10096000C2F87472F9D2203B13F1200FF2D1BFF319 +:100970004F8FBFF36F8FBFF34F8FBFF36F8F5369ED +:1009800023F4003353610023C2F85032BFF34F8F7A +:10099000BFF36F8F202383F31188854680F3088887 +:1009A0002047F8BD0000020820000208FFFF0108F0 +:1009B00000220020DC2200200044025800ED00E06C +:1009C0002DE9F04F93B0AC4B2022FF2100900AA8F4 +:1009D0009D6801F09FF9A94A1378A3B90121A8489D +:1009E0001170C360202383F31188C3680BB104F036 +:1009F00077FC0023A34A4FF47A71A14804F034FC39 +:100A0000002383F31188009B9F4A03B113600023E6 +:100A10009E49009C98469B461E469A460B70536022 +:100A2000012001F04DF924B1974B1B68002B00F019 +:100A30001C82002001F052F80390039B002B01DA86 +:100A400000F0A8FE039B002BEDDB012001F036F93E +:100A5000039B213B162BE3D801A252F823F000BFE1 +:100A6000BD0A0008E50A0008790B0008210A000801 +:100A7000210A0008210A00080D0C0008DF0D0008FB +:100A8000F90C00085B0D0008830D0008A90D000893 +:100A9000210A0008BB0D0008210A00082D0E0008DD +:100AA0005D0B0008210A0008710E0008C90A000841 +:100AB0005D0B0008210A00085B0D00080220FFF70B +:100AC00083FE002840F0FB81009B022105A8B8F1BD +:100AD000000F08BF1C4641F21233ADF8143001F08C +:100AE0001BF89DE74FF47A7000F0F8FF071EEBDB70 +:100AF0000220FFF769FE0028E6D0013F052F00F233 +:100B0000E081DFE807F0030A0D1013360523042106 +:100B100005A8059301F000F817E004215648F9E70D +:100B200004215B48F6E704215A48F3E74FF01C091B +:100B3000484609F1040901F021F80421059005A8AF +:100B400000F0EAFFB9F12C0FF2D101204FF0000ABA +:100B500000FA07F747EA0B0B5FFA8BFB01F026F967 +:100B600026B10BF00B030B2B08BF0024FFF734FE5C +:100B700056E704214848CDE7002EA5D00BF00B0323 +:100B80000B2BA1D10220FFF71FFE074600289BD0A8 +:100B900001203E4E00F0F0FF4FF0000802203070C0 +:100BA00001F08EF85FFA88F9484600F0F5FF044638 +:100BB00090B1484608F1010800F0FEFF0028F1D18D +:100BC000B846044641F21213022105A83E46ADF88C +:100BD000143000F0A1FF23E70123254602203370E3 +:100BE00001F06CF8244B9B68AB4207D9284600F013 +:100BF000C5FF013040F068810435F3E70025234B41 +:100C0000B8463E461D70204B5D60A7E7002E3FF4BE +:100C10005BAF0BF00B030B2B7FF456AF02201B4B8B +:100C2000187001F04DF8322000F058FFB0F10009C3 +:100C3000FFF64AAF19F003077FF446AF0E4A09EBFF +:100C40000503926893423FF63FAFB9F5807F3FF7C7 +:100C50003BAF124BB945019322DD4FF47A7000F09F +:100C60003DFF0390039A002AFFF62EAF039A013747 +:100C7000019B03F8012BEDE700220020E023002078 +:100C8000C8220020F1070008E4230020DC22002015 +:100C900004220020082200200C220020E022002054 +:100CA000C820FFF791FD074600283FF40DAF1F2D28 +:100CB00011D8C5F120020AAB25F0030084494A454A +:100CC000184428BF4A46019200F0FEFF019AFF2116 +:100CD0007F4801F01FF84FEAA903C9F387027C4956 +:100CE0002846019301F01EF8064600283FF46AAF3B +:100CF000019B05EB830531E70220FFF765FD002826 +:100D00003FF4E2AE00F074FF00283FF4DDAE0027B0 +:100D1000B946704B9B68BB4218D91F2F11D80A9B4C +:100D200001330ED027F0030312AA134453F8203CDA +:100D300005934846042205A9043702F065FA814666 +:100D4000E7E7384600F01AFF0590F2E7CDF8149077 +:100D5000042105A800F0E0FE00E70023642104A8B8 +:100D6000049300F0CFFE00287FF4AEAE0220FFF720 +:100D70002BFD00283FF4A8AE049800F02FFF05904B +:100D8000E6E70023642104A8049300F0BBFE0028DA +:100D90007FF49AAE0220FFF717FD00283FF494AECF +:100DA000049800F01DFFEAE70220FFF70DFD002880 +:100DB0003FF48AAE00F02CFFE1E70220FFF704FDCC +:100DC00000283FF481AE05A9142000F027FF074654 +:100DD0000421049004A800F09FFE3946B9E73220B0 +:100DE00000F07CFE071EFFF66FAEBB077FF46CAE13 +:100DF000384A07EB0A03926893423FF665AE022039 +:100E0000FFF7E2FC00283FF45FAE27F003075744EA +:100E1000BA453FF4A3AE50460AF1040A00F0AEFE14 +:100E20000421059005A800F077FEF1E74FF47A70F1 +:100E3000FFF7CAFC00283FF447AE00F0D9FE0028B7 +:100E400044D00A9B01330BD008220AA9002000F0ED +:100E500069FF00283AD02022FF210AA800F05AFF9B +:100E6000FFF7BAFC1C4804F0BBF913B0BDE8F08FE3 +:100E7000002E3FF429AE0BF00B030B2B7FF424AEB6 +:100E80000023642105A8059300F03CFE07460028D6 +:100E90007FF41AAE0220FFF797FC814600283FF44A +:100EA00013AEFFF799FC41F2883004F099F90598E8 +:100EB00000F0C0FF4E463C4600F078FFB0E5064625 +:100EC0004CE64FF0000AFFE5B8467BE6374679E688 +:100ED000E022002000220020A0860100094A49F2F9 +:100EE0006900136899B21B0C00FB013344F2506196 +:100EF0001360054B186882B2000C01FB02001860F9 +:100F000080B27047142200201022002000211022FD +:100F100010B5044600F0FEFE034B03CB2060616079 +:100F20001868A06010BD00BF00E8F11F2DE9F04374 +:100F3000224DBBB002F062F940F2ED22AB68C31A59 +:100F4000934232D906AF2B4628220021A8603846AA +:100F500002F032FE05F10E0000F0D4FE0026044639 +:100F60005FFA80F905F10E08F3B2F100994501F13D +:100F7000280107D908EB060308223846013602F09B +:100F80001BFEF1E7082301220534297B0C48A4B29B +:100F9000CDE902320B4B01933023CDE90474009369 +:100FA00004A3D3E9002302F01FFC3BB0BDE8F083AB +:100FB000AFF3008078F6339F93CACD8D905D00200B +:100FC000043400209D5D002070B50D4614461E4679 +:100FD00002F0A0FB50B9022E10D1012C0ED112A3A9 +:100FE000D3E900230120C5E9002307E0282C10D015 +:100FF00005D8012C09D0052C0FD0002070BD302C55 +:10100000FBD10BA3D3E90023ECE70BA3D3E9002327 +:10101000E8E70BA3D3E90023E4E70BA3D3E900231C +:10102000E0E700BFAFF30080401DA12026812A0B1E +:1010300078F6339F93CACD8D9E6AC421818A46EE8D +:1010400026417272DF25D7B7F017304A39059E5610 +:1010500013B504460846202200212346019002F0E1 +:10106000ABFD227923460198032A4FF0200128BFC7 +:10107000032203F8042F022202F09EFD6279234628 +:101080000198072A4FF0220128BF072203F8052FF5 +:10109000032202F091FDA27923460198072A4FF01E +:1010A000250128BF072203F8062F032202F084FD42 +:1010B000019804F108031022282102F07DFD382058 +:1010C00002B010BD2DE9F04FADF5017D0F460021B6 +:1010D00040F275120EAE804622A8219100F01AFE51 +:1010E00048220021304600F015FE21AD02F086F8BE +:1010F0004FF47A72554B0DF15A09B0FBF2F01860BB +:1011000093E80700012386E807000DF15A003382B7 +:10111000FFF7FCFE47F605034D49338406AB18463E +:1011200006F0A0F81F2229463064304686F83C209D +:10113000FFF78EFF12AB044601460822284602F054 +:101140003BFD08220DF149032846A11804F1880A45 +:1011500002F032FD0DF14A03082204F11001284685 +:1011600004F5847B02F028FD13AB202204F1180162 +:10117000284602F021FD14AB402204F13801284634 +:1011800002F01AFD16AB082204F17801284602F09D +:1011900013FD0DF15903082204F18001284602F0E5 +:1011A0000BFD51460AF1080A4B460822284609F170 +:1011B000010902F001FDD345F3D104F588744FF025 +:1011C00000091BAB08225946284602F0F5FC96F8A8 +:1011D00034304B450AD9B36B2146082228464B448C +:1011E000083409F1010902F0E7FCF0E74FF00009CB +:1011F00096F83C3004EBC9014B4508D9336C082202 +:1012000028464B4409F1010902F0D6FCF0E700231F +:10121000073140460393C1F3CF01BB7E029307F130 +:10122000190301930123CDE904510093F97E05A32D +:10123000D3E9002302F0D8FA0DF5017DBDE8F08F67 +:10124000AFF300809E6AC421818A46EEEC23002021 +:1012500094720008F8B50E4C02260E4FA4F5805388 +:1012600043F8307C237E3BB965692DB1284601F0F7 +:1012700041FE284605F060FF2046A4F5A55401F084 +:1012800039FE012EA4F1100400D1F8BD0126E5E7D6 +:1012900010590020C4730008014B1870704700BF3C +:1012A000F8230020334BF0B51C7B85B034B1324BB2 +:1012B0000E221A810024204605B0F0BD2F4A02AB51 +:1012C0001068516803C308232D492E480DEB030213 +:1012D00005F05AFF054630B9274B0A222A481A81E1 +:1012E00001F090FDE6E70169B1F5F01F06D9224B48 +:1012F0000B2226481A8101F085FDDCE7438BB3F50C +:10130000AF6F09D01C4A0C21214811814FF4AF6204 +:10131000194601F077FDCEE71E4A024402F11003A0 +:10132000994204D2144B10221B481A81E3E710396A +:1013300020468E1A134901F067FF05F11801074690 +:101340003246204601F060FFAB689F4202D1EB6855 +:1013500098420AD0084B0D221A813B4600900F4854 +:10136000D5E9021201F04EFDA4E70D48012401F079 +:1013700049FDA0E7905D0020EC23002045730008A4 +:10138000DCFF1D0000000208B4720008C0720008F3 +:10139000D27200080800FEF7F07200080D73000812 +:1013A000367300082DE9F04FADB080460C4606AF0D +:1013B00002F0B0F90546002859D1237E022B1BD13B +:1013C000E38A012B18D101F019FF0646FFF786FDCD +:1013D00003464FF4C87006F51676DFF8CC92B3FBDF +:1013E000F0F202FB103316FA83F3C9F80030E37E03 +:1013F00033B9A84B00221A709C37BD46BDE8F08F68 +:10140000A38AEEB20135013BB3420BD93B1DE90083 +:10141000082220461E4401F0F8010023009602F045 +:101420008FFAEDE707F11400FFF770FD324607F180 +:101430001401381D05F098FE0028DAD10F2E08D8C7 +:10144000944B1E70D9F80030A3F51673C9F800301C +:10145000D2E7FB1CF87001460722009303462046A2 +:1014600002F06EFAF978404602F04CF9C4E7E38ADC +:10147000282B26D010D8012B1ED0052BBCD1BFF3B2 +:101480004F8F8549854BCA6802F4E0621343CB60F5 +:10149000BFF34F8F00BFFDE7302BADD1637EE94630 +:1014A0007F4D01336A7BDBB2934203D1E27E2B7B1B +:1014B0009A4265D0CD469FE721464046FFF702FE9F +:1014C0009AE7A38A013B9BB2C92B95D8744D2E7B1A +:1014D00026BB05F10C030822314600933346204613 +:1014E00002F02EFA731CF2B2D9001E46A38A013B09 +:1014F0009A4205DA0E3200232A4400920822EEE7CF +:1015000000230022C5E900230023AB6085F8D73013 +:10151000C5F8D8302B7B0BB9E37E2B73002507F180 +:1015200014093B1D082229464846FD60C7E90155BC +:1015300002F042FB3B7A05F1010AAB424FEACA06D0 +:1015400008D9FB680822314648462B44554602F02C +:1015500033FBEFE7C6F3CF060023E17E1934039394 +:101560004046CDE9049663780194029328230093C2 +:1015700046A3D3E9002302F037F9FFF7D7FC3BE796 +:101580004FF0000807F1140310222046A7F814803A +:1015900041460093012302F0D3F9A68A023EB6B277 +:1015A000F31C9B109B000733DB08A9EBC3039D468C +:1015B0000DF1180A1FFA88F34FEAC801B34201F18E +:1015C00010010AD20AEB08030822204608F101089C +:1015D0000093002302F0B4F9ECE795F8D70000F08F +:1015E000DBFAD5F8D83004461BB995F8D70000F0DF +:1015F000E3FAD5F8D83033449C4204D295F8D700AA +:10160000013000F0D9FA4FEA960B4FF000081FFAAC +:1016100088F18B45D5E9003209D90AEB880101220E +:1016200003EB880008F1010800F07CFBEFE7F318FA +:1016300095F8D70042F10002C5E90032D5F8D8305C +:1016400006EB0308C5F8D88000F0A6FA804509D358 +:1016500095F8D730D5F8D8000133001B85F8D7307E +:10166000C5F8D800FF2E08D800232B7300F0C0FA6D +:10167000FFF718FE08B1FFF7EDF82B68094A9B0A3F +:10168000013313810023AB6014E700BF264172725F +:10169000DF25D7B7FD33002000ED00E00400FA0598 +:1016A000905D0020EC2300200034002010B54FF0A6 +:1016B00040540C4B22689A4212D1627D0A4B0B486F +:1016C0001A70C922237D0E30094900F8023C00F04F +:1016D000FBFAE0220021204600F01CFB012010BD97 +:1016E0000020FCE79AAD44C5F8230020905D00205F +:1016F0001600003037B502231D4C1E4D0122204636 +:101700001D496B71236804F580545B689847D4F8D1 +:10171000B034012218495B6804F5966098470023AD +:1017200016494FF480520193154B16480093164BFF +:1017300001F0C2FF154B197811B1124801F0E2FF18 +:1017400001F05CFD0446FFF7C9FB4FF4C873B0FB22 +:10175000F3F202FB130304F5167010FA83F00C4B3E +:10176000186004F0E1F908B10F232B8103B030BDFC +:1017700030340020EC23002040420F00FC230020E6 +:10178000C90F000804340020A5130008F823002026 +:10179000003400202DE9F04F9C4D2DED028B93B0CD +:1017A000DFF890A29A4F284602F082F803460028FC +:1017B0003DD00024974E0E94A046ADF84440A1467B +:1017C000CDE90F44027B8DF844200FAA9968406848 +:1017D00003C21B6843F000430E93336804F22C5499 +:1017E000D3F810B001F00CFD10EB0A02CDF8009018 +:1017F000304606F5A55641F100030EA9D84740F63C +:1018000058230028C8BF48F0010810369C42E4D194 +:10181000B8F1000F05D0284602F04EF887F8009086 +:10182000C1E73B78072B00F2E08001333B700023D7 +:101830000DF12C084FF0010A0A93ADF834300B93E8 +:10184000C8F804309FED6B8B0026724C3746236836 +:101850004FF0000B0DF11D0207A920468DF81CA0CA +:101860008DF81DB08DED008BD3F808905B46C8470E +:101870009DF81C90B9F1000F1ED0102259460EA8F9 +:1018800000F048FA236808AA0AA95F6920460DF10A +:101890001E03B8470FAB4F4698E8030083E80300E8 +:1018A0009DF834300EA928468DF844300A9B0E93DB +:1018B000DDE9082302F0C8F906F22C5640F6582359 +:1018C00004F5A5549E4204F11004C0D1002FBBD1F1 +:1018D000284601F01FFF002840D14F4E01F08EFC3A +:1018E000336898423AD301F089FC0446FFF7F6FAD0 +:1018F0004FF4C87304F516748DF82870B0FBF3F23A +:1019000002FB130314FA83F33360444E377817B99C +:1019100001238DF82830C7F110040EA8FFF7F6FA5E +:101920000EABE4B20DF12900D919062C28BF06240C +:101930002246013400F0C8F90AABE4B2284603930A +:10194000182304940293364B0193012300932BA395 +:10195000D3E9002301F0E0FE0023337001F04EFCD8 +:10196000304A314C1368C31AB3F57A7F30D3106014 +:1019700001F046FC02460B46284601F0A7FF284628 +:1019800001F0C8FE20B3237B0EAF284E002B14BFFE +:1019900003230223737101F031FC4FF47A7339464B +:1019A000B0FBF3F030603046FFF752FB18230730EE +:1019B00002931F4BC0F3CF00019340F25513CDE9C2 +:1019C0000370009328460FA3D3E9002301F0A4FE7F +:1019D000237B2BB1FFF7AAFA237B002B7FF4E0AE29 +:1019E00013B0BDEC028BBDE8F08F284601F064FF18 +:1019F0001DE700BF0000000000000000401DA12006 +:101A000026812A0BF1C6A7C1D068080F0434002034 +:101A1000755E00203034002000340020FD330020AB +:101A2000FC330020705E0020905D0020EC2300203D +:101A3000745E002040420F0008B5064800F014FD17 +:101A4000054800F011FD054A05490020BDE80840A1 +:101A500005F06CBB30340020E0480020D05E002050 +:101A600055120008F7B50C46184E4FF47A7105462A +:101A700002FB01F396F90020501C0BD114482946B3 +:101A800001930268176A2246B8478442019B03D13A +:101A9000002310E0002AF1D096F90020511C01D05B +:101AA000012A0DD10B4829460268166A2246B04722 +:101AB000844205D10123084A0120137003B0F0BD10 +:101AC0004FF4FA7003F08CFB0020F7E71822002097 +:101AD000F8640020D45E0020BC5E0020002307B51F +:101AE000024601210DF107008DF80730FFF7BAFF1C +:101AF00020B19DF8070003B05DF804FB4FF0FF3004 +:101B0000F9E700000A46042108B5FFF7ABFF80F0B3 +:101B10000100C0B2404208BD074B0A4630B41978F4 +:101B2000064B53F82140014623682046DD69044BEB +:101B3000AC4630BC604700BFBC5E00206C73000840 +:101B4000A086010070B50A4E00240A4D03F0F4FD92 +:101B5000308028683388834208D903F0E9FD2B6878 +:101B600004440133B4F5003F2B60F2D370BD00BFD5 +:101B7000BE5E0020785E002003F0BCBE00F1006075 +:101B800000F500300068704700F10060920000F539 +:101B9000003003F033BE0000054B1A68054B1B886C +:101BA0009B1A834202D9104403F0C2BD0020704743 +:101BB000785E0020BE5E002038B5074D04462868D8 +:101BC000204403F0BBFD28B928682044BDE8384014 +:101BD00003F0C6BD38BD00BF785E0020002070470E +:101BE00000F1FF5000F58F10D0F80008704700009A +:101BF000064991F8243033B100230822086A81F89D +:101C00002430FFF7C1BF0120704700BF7C5E002079 +:101C1000014B1868704700BF0010005C244BF0B502 +:101C20001A680446234BC2F30B06120C1F8858682F +:101C3000BE4293F9085028D09F89BE4206D10120A8 +:101C40000C2505FB0033586893F9085041F2010355 +:101C50009A421CD041F203039A421AD042F2010385 +:101C60009A4218D042F203039A4208BF5625621ED8 +:101C70000B46441E0A4493420FD214F9016F581CBC +:101C80006EB1034600F8016CF5E70020D8E75A254D +:101C9000EDE75925EBE75825E9E7184605E02C2440 +:101CA00082421C7001D9981C5D70401AF0BD00BFC3 +:101CB0000010005C1C2200200020704770470000CC +:101CC0007047000070470000002310B5934203D016 +:101CD000CC5CC4540133F9E710BD0000013810B5E5 +:101CE00010F9013F3BB191F900409C4203D11AB178 +:101CF0000131013AF4E71AB191F90020981A10BDA8 +:101D00001046FCE703460246D01A12F9011B0029CF +:101D1000FAD1704702440346934202D003F8011BF4 +:101D2000FAE770472DE9F8431F4D144607468846E9 +:101D300095F8242052BBDFF870909CB395F82430BE +:101D40002BB92022FF2148462F62FFF7E3FF95F8C9 +:101D500024004146C0F1080205EB8000A24228BFE2 +:101D60002246D6B29200FFF7AFFF95F82430A41BAD +:101D700017441E449044E4B2F6B2082E85F824605D +:101D8000DBD1FFF735FF0028D7D108E02B6A03EB42 +:101D900082038342CFD0FFF72BFF0028CBD1002056 +:101DA000BDE8F8830120FBE77C5E0020024B1A7837 +:101DB000024B1A70704700BFBC5E00201822002042 +:101DC00038B5164C164D204602F000FD2946204637 +:101DD00002F028FD2D681348D5F89020D2F8043879 +:101DE00043F00203C2F8043803F0FAF90E4928461A +:101DF00002F026FED5F890200C48D2F804380C49A1 +:101E0000A04223F00203C2F804384FF4E1330B6020 +:101E100003D0BDE8384002F037BC38BDF86400207C +:101E20000C75000840420F0014750008D45E0020B5 +:101E3000A45E002038B50B4B04461A780A4B53F8C1 +:101E400022500A4B9D420CD0094B00211822184603 +:101E5000FFF760FF046001462846BDE8384002F005 +:101E600013BC38BDBC5E00206C730008F864002011 +:101E7000A45E0020202383F3118862B6704700001F +:101E8000002383F3118862B6704700000120704779 +:101E9000704700007047000010B4134602681468D1 +:101EA0000022A4465DF8044B6047000000F5805016 +:101EB00090F859047047000000F5805090F85204E3 +:101EC0007047000000F5805090F9580470470000FA +:101ED0004E20704700F5805208B5FFF7CBFFD2F8CF +:101EE0009834D2F894041844D2F890341844D2F8B4 +:101EF00078341844D2F888341844D2F8843418441A +:101F0000FFF7BEFF08BD00002DE9F74F0C4600F5B6 +:101F100080511F46054691F852349046BDF83090E6 +:101F20009BB1D1F874340133C1F8743423689A003A +:101F300006D4237B082B0BD9627B0AB10F2B07D960 +:101F4000D1F878340133C1F878344FF0FF300FE026 +:101F5000FFF790FFEB6AD3F8C42012F4001A0AD0FE +:101F6000D1F87C3400200133C1F87C34FFF788FFBE +:101F700003B0BDE8F08F22684FF0480BD3F8C4607F +:101F8000002A6B6AC6F30446B4BF42F08042920452 +:101F90001BFB063BCBF8002023685B004FEA06637F +:101FA00044BF42F00052CBF80020227B43EA0243B8 +:101FB0007201CBF80430607B18B343F44013CBF8C4 +:101FC0000430D1F8A4340133C1F8A434AB1803F5BC +:101FD0008353197B41F020011973207B019200F09B +:101FE0006DFF0330019A80105FFA8AF30AF1010A4B +:101FF00083420DDA04EB83010BEB8303496899609C +:10200000F2E7AB1803F58353197B60F34511E3E75F +:102010000121EB6A04F10C00B140C3F8D010AB18F9 +:10202000214603F58253C3E9048705EB461303F504 +:102030008253183351F804CB814243F804CBF9D1D1 +:1020400009882A442846198041F26803D65002F5CF +:10205000805209F0030392F86C1043F0100321F052 +:102060001F010B43214682F86C304246FFF708FF00 +:102070003B46CDF8309003B0BDE8F04F00F0E4BE31 +:102080002DE9F04700F58056044696F85254002D8D +:1020900040F00181037C032B40F092802B462846C0 +:1020A0002F465FFA83FC944510DA01EBCC0E51F811 +:1020B0003CC0BCF1000F04DBDEF804C0BCF1000F33 +:1020C00002DB01370133ECE70130FBE7FFF7D2FE1B +:1020D000E36AF0B9D3F8800040F00200C3F8800052 +:1020E0004E23E06A002F6ED1D0F8803043F0010318 +:1020F000C0F88030694B6A4A1B6803F1805303F5CE +:102100002C539B009342A36240F2AF80654801F0DC +:102110006FF84D2842D8DFF884814FEA004EDFF88F +:102120008891D8F800C04EEA8C0EC3F884E00CF118 +:10213000805303F52C539B00636100EB0C03D4F830 +:102140002CC0C8F80030C0F14E03DCF8800040F02D +:102150003000CCF880004FF0000CD4F81480E64634 +:102160005FFA8CF08242BCDD01EBC00A51F830000E +:10217000002810DBDAF804A0BAF1000F0BDA09EA44 +:1021800000400AF07F0A40EA0A0040F0084048F8A0 +:102190002E000EF1010E0CF1010CE1E79A6922F01C +:1021A00001029A6101F02AF80646E36A9B69D907A1 +:1021B00004D501F023F8831BFA2BF6D9FFF760FE54 +:1021C0002846BDE8F087B7EB530F3DD2DFF8CCE0EF +:1021D0004FEA074CDEF800304CEA830CC0F888C0A8 +:1021E00003F1805003EB4703002700F52C50CEF895 +:1021F0000030BC468000A061E06AD0F8803043F037 +:102200000C03C0F88030D4F818E0FBB29A427FF794 +:1022100071AF51F8330001EBC3080028D8F804303F +:1022200001DB002B0EDB20F0604023F0604340F028 +:10223000005043F000434EF83C000EEBCC000CF194 +:10224000010C43600137E0E7836923F001038361F8 +:1022500000F0D4FF0646E36A9B69DA07AED500F0CA +:10226000CDFF831BFA2BF6D9A8E7E26A936923F026 +:102270000103936100F0C2FF0746E36A9B69DB0735 +:1022800005D500F0BBFFC31BFA2BF6D996E7012555 +:1022900086F8525492E7002592E700BFCC5E0020FA +:1022A000FCB50040747300080000FF0713B500F58B +:1022B00080540191606C00F053FE1F280AD920223F +:1022C0000199606C00F0C2FEA0F120035842584111 +:1022D00002B010BD0020FBE700F5805008B5FFF705 +:1022E000C9FD406C00F010FEBDE80840FFF7C8BD16 +:1022F00000220260828142608260704700220023D7 +:1023000010B5C0E90023002304460C3020F8043C3B +:10231000FFF7EEFF204610BD2DE9F047074688B0D5 +:102320009A46884607F5805468469146FFF7A2FD15 +:10233000FFF7E4FF606C00F0F9FD1F282DD9202283 +:102340006946606C00F006FF202826D194F85234CC +:102350001BB303AD444605AB2E46083403CE9E4264 +:1023600044F8080C44F8041C3546F5D13068414661 +:1023700020603846B388A380DDE90023C9E9002343 +:10238000BDF808304A46AAF80030FFF779FD5346F9 +:1023900008B0BDE8F04700F045BD0020FFF770FD34 +:1023A00008B0BDE8F08700002DE9F84F002306468D +:1023B00000F58154054688461034C0E90133274BA7 +:1023C00046F8303B374638462037FFF797FFA7429D +:1023D000F9D105F580544FF4805305F5A3594FF01A +:1023E000000A26630026676405F5835709F1100982 +:1023F0004FF0000B1037E663C4E90D36012384F873 +:10240000403084F84830A7F11800203747E910AB76 +:10241000FFF76EFF47F8286C4F45F4D1B8F1010F74 +:1024200084F85884A4F85A64A4F85C64A4F85E6440 +:1024300084F86064A4F86264A4F86464A4F8666430 +:1024400084F8686402D9064800F0D2FE054B28469D +:1024500053F82830EB62BDE8F88F00BFC473000862 +:1024600098730008B4730008044B10B5197804463B +:102470004A1C1A70FFF798FF204610BDC95E002065 +:102480002DE9F04700295FD0304F3148B7FBF1F517 +:1024900081428CBF0A201120431EB5FBF0FC00FBDB +:1024A0001C50DCB220B1022B1846F5D8002037E0D2 +:1024B0000CF1FF35B5F5806F32D2C4EBC4094FF48F +:1024C0007A7009F103034FEAE308C3F3C70308F185 +:1024D000010AA4EB030E08FB00085FFA8EF65AFA15 +:1024E0008EFEB8FBFEFEBEF5617F1BDC1FFA8EF48C +:1024F000581C56FA80F00CFB00FCB7FBFCFC614555 +:10250000D4D1013BDBB20F2BD0D8711E0020C9B251 +:10251000072905D8107101201480558053719171DD +:10252000BDE8F08709F1FF334FEAE30EC3F3C703B9 +:102530000EF10108E41A0EFB0000E6B258FA84F42A +:10254000B0FBF4F4A4B2D3E70846E9E700B4C4044E +:102550003F420F0038B540F27772C36A154CC3F89A +:10256000BC200722C36AC3F8C8202268C16A93004E +:1025700043F4C023C1F8A03002F1805302F16C0192 +:10258000C56A03F52C53EA3289009B00226041F0B2 +:10259000E061094AC361C5F8C01003F5D87103F5BD +:1025A0006A7341629342836202D9044800F020FEBC +:1025B00038BD00BFCC5E0020FCB50040747300083D +:1025C0002DE9F04F00F58055994689B0044695F8FD +:1025D00058348A469046022B04D90027384609B061 +:1025E000BDE8F08F9E4A52F8231009B942F8230043 +:1025F0009C49C4F80CA00B7884F81090C3B9FFF77D +:1026000039FC994BD3F8EC2042F48072C3F8EC20EB +:10261000D3F8942042F48072C3F89420D3F8942025 +:1026200022F48072C3F8942001230B70FFF728FC7A +:1026300095F851346BB9FFF71DFC8C4A95F8583466 +:10264000D35CEBB1012B24D0012385F85134FFF783 +:1026500017FCFFF70FFCE26A936923F01003936104 +:1026600000F0CCFD0746E36A9E6916F0080617D015 +:1026700000F0C4FDC31BFA2BF5D9FFF701FCACE752 +:102680000221132001F04EFE0221152001F04AFE26 +:10269000DAE70221142001F045FE02211620F5E7B9 +:1026A0009A6942F001029A6100F0A8FD0746E36AC8 +:1026B0009A69D00705D400F0A1FDC31BFA2BF6D907 +:1026C000DBE79A69002704F5825B42F002020BF116 +:1026D000100B9A61E36A5F65FFF7D2FB686C00F04C +:1026E00013FC202200216846FFF714FB02A8FFF725 +:1026F000FFFD6A460BEB06030DF1180E0697944694 +:102700000833BCE80300F44543F8080C43F8041C04 +:102710006246F4D1DCF8000020361860B6F5806F10 +:102720009CF804201A71DCD1002304F5A252514612 +:1027300020461A3285F8503485F85334FFF7A0FE4E +:10274000074690B9E26A936923F00103936100F0B0 +:1027500055FD0546E36A9B69D9077FF53EAF00F05A +:102760004DFD431BFA2BF5D937E795F85F6495F8D3 +:102770005E243602C5F86CA4E36A46EA426695F820 +:1027800060241643B5F85C2446EA0246DE61B8F1DF +:10279000000F29D004F5A352414620460232FFF72C +:1027A0006FFE90B9E26A936923F00103936100F030 +:1027B00025FD0546E36A9B69DA077FF50EAF00F059 +:1027C0001DFD431BFA2BF5D907E795F8683495F8FA +:1027D00067141B01C5F87084E26A43EA0123B5F867 +:1027E000641443EA0143D360E36A00262046C3F839 +:1027F000BC60FFF7AFFE85F859646FF04042E36AB2 +:10280000B9F1030F1A651A4AE36A5A654FF00222BA +:10281000E36A9A654FF0FF32E36AC3F8E0204FF0B5 +:102820000302E36ADA65E26A936943F440739361F1 +:102830003FF4D4AEE26A936923F00103936100F0A0 +:10284000DDFC0646E36A9B69DB0705D500F0D6FC94 +:10285000831BFA2BF6D9C0E6012385F85234BDE676 +:10286000C05E0020C85E002000440258AC7300081F +:10287000550200022DE9F04F054689B09046994671 +:10288000002741F2680A00F58056EB6AD3F8D83089 +:10289000FB40D8074AD505EB47124FEA471B524485 +:1028A0001379190742D4D6F880340133C6F880343E +:1028B00013799A0605EB0B0248BFD6F8A8345244A8 +:1028C00044BF0133C6F8A834137943F008031371E9 +:1028D000DB0723D596F8533403B305F582546846D5 +:1028E000FFF70CFD03AB18345C4404F1080C2068BE +:1028F000083454F8041C1A46644503C21346F6D142 +:102900002068694610602846A2889A800123ADF8A5 +:1029100008302B68CDE900891B6C9847D6F85434F1 +:1029200023B1D6F89C340133C6F89C340137202FEC +:10293000ABD109B0BDE8F08F2DE9F04F0F468DB057 +:10294000044600F05DFC82468946002F5BD1E36AB5 +:10295000D3F8A02012F4FE0F03D100200DB0BDE883 +:10296000F08FD3F8A420920141BF04F58051D1F833 +:1029700094240132C1F89424D3F8A4205606ECD054 +:10298000D3F8A450E669C5F305254823E8464FF07F +:10299000000B03FB05664046FFF7AAFC32685100B6 +:1029A0004ABF22F06043C2F38A4343F000439200DF +:1029B00048BF43F080430093736813F400131BBFB8 +:1029C000012304F580528DF80D308DF80D301EBFB7 +:1029D000D2F8AC340133C2F8AC34F38803F00F03FF +:1029E0008DF80C309DF80C0000F068FA5FFA8BF35C +:1029F000984225D9F2180CA90BF1010B127A0B445D +:102A000003F82C2CEEE7012FA7D1E36AD3F8B0200E +:102A100012F4FE0FA1D0D3F8B420950141BF04F504 +:102A20008051D1F894240132C1F89424D3F8B42011 +:102A3000500692D0D3F8B450266AC5F30525A4E712 +:102A4000EFB9E36AC3F8A85004A807ADFFF756FC36 +:102A500098E80F0007C52B800023204604A9ADF895 +:102A60001830236804F580541B6CCDE904A99847FD +:102A700058B1D4F88C340133C4F88C346EE7012F8C +:102A8000E2D1E36AC3F8B850DEE7D4F8903401200D +:102A90000133C4F8903461E7F8B505460F4600F5F8 +:102AA0008054012639462846FFF746FF10B184F8C6 +:102AB0005364F7E7D4F8543423B1D4F89C34013389 +:102AC000C4F89C34F8BD0000C36AF0B51A6C12F467 +:102AD0007F0F2BD01B6C00F5805441F268054FF03E +:102AE000010CC4F8A0340023471900EB43125E0127 +:102AF0002A44117911F0020F15D0490713D4B9599E +:102B0000C66A0CFA01F1D6F8CCE011EA0E0F0AD031 +:102B1000C6F8D410117941F004011171D4F8882459 +:102B20000132C4F888240133202BDED1F0BD00002F +:102B30002B4B70B51E561B5C012B30D8294D2A4AF1 +:102B400055F8233052F8264013B349B3236D9A0544 +:102B500010D54FF40073236500F052FB50EA0102D8 +:102B60000B4602D0013861F10003024655F82600F9 +:102B7000FFF780FE236D9B012CD54FF0007255F8B6 +:102B80002630226503F58053012283F8592421E081 +:102B900001232365102323654FF48053236570BD03 +:102BA000236DDA0702D4236D5B0706D505230021C8 +:102BB00055F826002365FFF76FFF236DD80602D472 +:102BC000236D590606D55023012155F826002365AB +:102BD000FFF762FF55F82600BDE87040FFF774BFAD +:102BE000B0730008C05E0020B473000808B5FFF79A +:102BF00041F9FFF769FFBDE80840FFF741B9000060 +:102C0000C36AD3F8C00010F07C5005D0D3F8C400DC +:102C100080F40010C0F340507047000000F5805071 +:102C200008B5FFF727F9406C00F080F9FFF728F9A5 +:102C300043090CBF0120002008BD000000F58053AF +:102C400093F8592462B1C16A8A6922F001028A614B +:102C5000D3F898240132C3F89824002283F8592429 +:102C6000704700002DE9F74300F582519846002592 +:102C7000FFF700F9103141F2680E4FF0010900F53D +:102C8000805C00EB4514744423795E071CD4DB069A +:102C90001AD58E69C36A09FA06F6D3F8CC703E429B +:102CA00012D04F6801970F689742019F77EB080792 +:102CB0000AD2C3F8D460237943F004032371DCF80B +:102CC00084340133CCF8843401352031202DD8D11F +:102CD00003B0BDE8F043FFF7D3B80000F8B51E46D7 +:102CE00000230F46054613701446FFF797FF80F048 +:102CF000010038701EB12846FFF782FF2070F8BD32 +:102D00002DE9F04F994685B00B780E468046174660 +:102D100001931378DDE90EBA029300F071FA33786B +:102D200004460D4613B93B78002B41D022462B4672 +:102D30004046FFF797FFFFF759FFFFF77FFF4B462E +:102D40003A463146FFF7CAFF33782BB1019B1BB1DE +:102D5000012005B0BDE8F08F3B7813B1029B002B3A +:102D6000F6D108F5805303935C4575EB0A031FD237 +:102D7000039BD3F85404D8B1BBEB04020368D968B1 +:102D80006AEB050388474B463A4631464046FFF713 +:102D9000A5FF337813B1019B002BD9D13B7813B138 +:102DA000029B002BD4D100F02BFA04460D46DBE742 +:102DB0000020CEE7002108B50846FFF7B9FEBDE8C0 +:102DC000084001F075B9000008B501210020FFF7A7 +:102DD000AFFEBDE8084001F06BB9000008B5002166 +:102DE0000120FFF7A5FEBDE8084001F061B9000031 +:102DF000012108B50846FFF79BFEBDE8084001F039 +:102E000057B900000FB4002004B0704713B56C46EA +:102E1000031D84E8060094E8030083E80500012010 +:102E200002B010BD73B58568019155B11B885B0771 +:102E300007D4D0E90036DB6B9847019AC1B230461F +:102E4000A847012002B070BDF0B5866889B005467C +:102E50000C465EB1BDF838305B070AD4D0E90037C4 +:102E6000DB6B98472246C1B23846B047012009B013 +:102E7000F0BD0022002301F10806CDE90023002364 +:102E80000A46ADF8083003AB1068083252F8041C4B +:102E90001C46B24203C42346F6D1106820609288D3 +:102EA000A28000F0AFF90423ADF808302B68CDE91B +:102EB00000011B6C694628469847D7E7082817D9B0 +:102EC00009280CD00A280CD00B280CD00C280CD0C8 +:102ED0000D280CD00E2814BF4020302070470C2045 +:102EE000704710207047142070471820704720202A +:102EF0007047000010B5037C044613B9006804F065 +:102F00002BF9204610BD00000023BFF35B8FC36088 +:102F1000BFF35B8FBFF35B8F8360BFF35B8F704743 +:102F2000BFF35B8F0068BFF35B8F704770B50546DA +:102F30000C30FFF7F5FF044605F108063046FFF7B1 +:102F4000EFFFA04206D96D683046FFF7E9FF254440 +:102F5000281A70BD3046FFF7E3FF201AF9E700009A +:102F600070B505464068A0B105F10C0605F10800F2 +:102F7000FFF7D6FF04463046FFF7D2FF844204F144 +:102F8000FF34304694BF6D680025FFF7C9FF2C441D +:102F9000201A70BD38B50C460546FFF7C7FFA042A2 +:102FA00010D305F10800FFF7BBFF04446868BFF3C6 +:102FB0005B8FB4FBF0F100FB11440120AC60BFF368 +:102FC0005B8F38BD0020FCE72DE9F0411446074631 +:102FD0000D46FFF7C5FF844228BF0446D4B1B8466A +:102FE00058F80C6B4046FFF79BFF30442860404682 +:102FF0007E68FFF795FF331A9C4203D801206C606E +:10300000BDE8F081A41B6B603B682044AB60E860C6 +:103010000220F5E72046F3E738B50C460546FFF7F2 +:103020009FFFA04210D305F10C00FFF779FF044485 +:103030006868BFF35B8FB4FBF0F100FB1144012023 +:10304000EC60BFF35B8F38BD0020FCE72DE9FF414A +:103050008846694607466C46FFF7B6FF002506B26C +:1030600004EBC606B4420AD0626808EB050120688A +:103070000834FEF729FE54F8043C1D44F2E72946C3 +:103080003846FFF7C9FF284604B0BDE8F0810000CC +:10309000F8B505460C300F46FFF742FF05F108066C +:1030A00004463046FFF73CFFA042304688BF6C68BC +:1030B000FFF736FF201A386020B12C683046FFF742 +:1030C0002FFF2044F8BD000073B5144606460D4698 +:1030D000FFF72CFF8442019028BF0446DCB101A910 +:1030E0003046FFF7D5FF019B33B93268C5E902339B +:1030F000C5E9002401200CE09C42286038BF0194FF +:10310000019884426860F5D93368241A0220AB60C4 +:10311000EC6002B070BD2046FBE700002DE9FF41E6 +:103120000F4669466C46FFF7CFFF00B2002604EB5E +:10313000C005AC4209D0D4F80480B81954F8081B73 +:1031400042464644FEF7C0FDF3E7304604B0BDE812 +:10315000F081000038B50546FFF7E0FF0446014660 +:103160002846FFF717FF204638BD000000B59BB08A +:10317000EFF3098168226846FEF7A6FDEFF30583A9 +:10318000044B9A6BDA6A9A6A9A6A9A6A9A6A9A6A93 +:103190009B6AFEE700ED00E000B59BB0EFF309810C +:1031A00068226846FEF790FDEFF30583044B9A6BA7 +:1031B0009A6A9A6A9A6A9A6A9A6A9B6AFEE700BF52 +:1031C00000ED00E000B59BB0EFF30981682268468E +:1031D000FEF77AFDEFF30583034B5A6B9A6A9A6AFE +:1031E0009A6A9A6A9B6AFEE700ED00E0FEE700003B +:1031F0000FB408B5029801F083FFFEE702F0C2BBEE +:1032000002F09ABB02F098BB30B50A44084D9142D7 +:103210000DD011F8013B5840082340F30004013B56 +:103220002C4013F0FF0384EA5000F6D1EFE730BDE5 +:103230002083B8ED2DE9F041C56915B9C161BDE83C +:10324000F0814B68AC4623F06047C3F38A464FEAEF +:10325000D37EC3F3807816EA230638BF3E462B465A +:103260005A68BEEBD27F22F060440AD0002A18DAF6 +:10327000A40CB44217D19D420FD10D60DEE7134676 +:10328000EEE7A74207D102F08044C2F380724245C4 +:103290000BD054B1EFE708D2EDE7CCF800100B608B +:1032A000CDE7B44201D0B442E5D81A689C46002A62 +:1032B000E5D11960C3E700002DE9F047089D01F052 +:1032C000070400EBD1004FF47F494FEAD5082244B0 +:1032D00005F00705944201D1BDE8F08704F0070727 +:1032E00005F0070A111B08EBD50E57453E4613F8AB +:1032F0000EC038BF5646C6F108068E4228BF0E469D +:10330000E108415C34443544B94029FA06F721FA12 +:103310000AF1FFB28CEA010147FA0AF739408CEA58 +:10332000010C03F80EC0D5E780EA0120082341F222 +:10333000210201B2013B4000002980B2B8BF5040D9 +:1033400013F0FF03F5D1704738B50C468D18A54230 +:1033500000D138BD14F8011BFFF7E6FFF7E70000C6 +:1033600002684AB1136801890360C38801339BB2C4 +:103370009942C38038BF03811046704770B588B04A +:10338000044620220D4668460021FEF7C3FC204675 +:103390000495FFF7E5FF024660B16B46054608AEAF +:1033A0001C46083503CCB44245F8080C45F8041C0B +:1033B0002346F5D1104608B070BD0000082817D983 +:1033C00009280CD00A280CD00B280CD00C280CD0C3 +:1033D0000D280CD00E2814BF4020302070470C2040 +:1033E0007047102070471420704718207047202025 +:1033F00070470000082817D90C280CD910280CD9C0 +:1034000014280CD918280CD920280CD930288CBFA6 +:103410000F200E207047092070470A2070470B20AC +:1034200070470C2070470D207047000010B54B68A6 +:1034300023B9CA8A63F30902CA8210BDC4681A6834 +:103440001C60C360438A013B43824A60EFE700008F +:103450002DE9F84F1D46CB8A0F468146C3F309017B +:10346000924606290B4630D00020AAB207F1190473 +:103470009EB21FFA80F8052E0FD8904503F1010384 +:1034800006D30A44FB8A62F309030120FB821AE097 +:103490001AF800600130E654EAE79045F1D2A1F154 +:1034A000060B1C237C68BBFBF3F203FB12BB1FFA69 +:1034B0008BF6002C45D14846FFF752FF044638B939 +:1034C00078606FF00200BDE8F88F4FF00008E6E783 +:1034D000002606607860ADB24FF0000B454510D96C +:1034E0000AEB0803221D13F8011B08F1010891558E +:1034F000B1B21FFA88F81B292BD0454506F1010609 +:10350000F1D8FB8AC3F30902154465F30903BCE74C +:1035100001321C4692B22368002BF9D1AB1F0B4439 +:103520001C21B3FBF1F301339BB29A42D3D2BBF11E +:10353000000FD0D14846FFF713FF20B9C4F800B000 +:10354000BFE70122E7E7C0F800B05E46206004460E +:10355000C1E74545D5D94846FFF702FF08B92060C5 +:10356000AFE7C0F800B0002620600446B6E70000D0 +:103570002DE9F04F2DED028B83B007469146BDF843 +:103580003C50CDE90013002A00F092802DB10E9B33 +:10359000002B00F08D80072D32D807F10C00FFF7CB +:1035A000DFFE044638B96FF00204204603B0BDECDC +:1035B000028BBDE8F08F14220021FEF7ABFB2A46F8 +:1035C0000E9904F10800FEF77FFB681CC0B2FFF7FC +:1035D00011FFFFF7F3FE207499F80030013803F073 +:1035E0001F0314FA80F063F03F0303723846009B18 +:1035F00043F0004161602146FFF71CFE0124D4E73F +:103600004FF0000800F10C034FF0800A4646444694 +:1036100008EE103A18EE100AFFF7A2FE83460028C3 +:10362000C1D014220021FEF775FBC6BB019B02200E +:10363000ABF808300E9B00F1080299195BFA82F290 +:103640000130C0B2082801D0AE422AD3FFF7D2FE23 +:10365000AE4208BF4FF0400AFFF7B0FE99F80020D5 +:10366000411E009B02F01F0201345BFA81F142EA25 +:10367000481288F0010824B24AEA020A43F00042E4 +:1036800081F808A059468BF810003846CBF8042082 +:103690004FF0000AFFF7CEFDAE42BBD185E7002018 +:1036A000C8E711F801CB013602F801CBB6B2C7E783 +:1036B0006FF0010479E70000F8B515460E462822A0 +:1036C000002104461F46FEF725FB069BB5F5001FAB +:1036D000A760636004F10C00079B34BF6A094FF6D2 +:1036E000FF722362002397B29A4205D80023036039 +:1036F00027826382A382F8BD0660013330462036FC +:10370000F2E7000003781BB94BB2002BC8BF017071 +:1037100070470000007870472DE9F74FDDF83C90C6 +:10372000804692469B46BDF830500D9E9DF838402D +:10373000BDF84070B9F1000F01D1002F51D11F2CFD +:103740004FD898F80000B0B9072F47D835F00303D9 +:1037500047D13A4649464FF6FF702D02FFF7F4FD78 +:1037600020F0010045EA04644004400C44EA40248F +:103770004FF6FF7321E040EA0520072F40EA04647A +:10378000F6D900254FF6FF73C5F12000A5F1200200 +:103790002AFA05F108350BFA00F02BFA02F2014380 +:1037A00018461143C9B2FFF7BFFD402D0346EBD1C8 +:1037B0003A464946FFF7C8FD034632462146404691 +:1037C000CDE90097FFF7D4FE33780133DBB21F2B2E +:1037D00088BF0023337003B0BDE8F08F6FF00300A3 +:1037E000F9E76FF00100F6E72DE9F04F85B092465A +:1037F00006469B46DDF848800F9D9DF840209DF8C9 +:103800004490BDF84C70B8F1000F01D1002F49D1A0 +:103810001F2A47D83378002B47D00C029DF8381068 +:10382000072F44EA026444EAC93444EA014444EA02 +:10383000030444F0800432D900234FF6FF72C3F131 +:10384000200CA3F120002AFA03F103930BFA0CFCDD +:103850002BFA00F041EA0C0101431046C9B2FFF710 +:1038600063FD039B02460833402BE8D13A464146AC +:10387000FFF76AFD03462A4621463046CDE9008718 +:10388000FFF776FEB9F1010F06D12B780133DBB2D9 +:103890001F2B88BF00232B7005B0BDE8F08F4FF6BB +:1038A000FF73E8E76FF00100F6E76FF00300F3E75E +:1038B000C06900B104307047C3691A68C261C26848 +:1038C0001A60C360438A013B438270472DE9F0418F +:1038D000D0F8188014461D46184E4146002709B9F5 +:1038E000BDE8F081D1E90223A21A65EB03039642F9 +:1038F00077EB03031ED283698B420DD1FFF796FD50 +:1039000083691B688361C3680B60438AC160013BA4 +:10391000816943828846E2E7FFF788FD0B68C8F8B3 +:103920000030C3680B60438AC160013B4382D8F812 +:103930000010D4E788460968D1E700BF80841E00E4 +:103940002DE9F04F8BB00D4614469B46DDF85090A4 +:103950008046002800F01881B9F1000F00F01481B2 +:10396000531E3F2B00F21081012A03D1BBF1000F3F +:1039700040F00A810023CDE90833B8F81430B5EBE4 +:10398000C30F4FEAC30703D300200BB0BDE8F08F8D +:103990002B199F42D8F80C3036BF7F1B2746FFB249 +:1039A0001BB9D8F81030002B7AD02F2D4DD8C5F187 +:1039B000300600232946B742009308ABD8F8080028 +:1039C0002CBFF6B23E46A7EB060A354432465FFAF4 +:1039D0008AFAFFF771FCB8F81430302103F1005374 +:1039E000063BDB000493D8F80C300393039B13B120 +:1039F000BAF1000F2CD1D8F8100040B1BAF1000F85 +:103A000005D008AB5246691A0096FFF755FC38B24C +:103A1000002FB9D066070AD00AAB624203EBD4018B +:103A200002F0070211F8083C134101F8083C082C89 +:103A30003DD9102C40F2B580202C40F2B780BBF16C +:103A4000000F00F09C80082335E0BA460026C2E74C +:103A5000049BE02B28BFE02306930B44AB42059365 +:103A600015D95A1B0398691A0096924508AB00F1C4 +:103A7000040034BF5246D2B20792FFF71DFC079AEA +:103A80001644AAEB020A1544F6B25FFA8AFA049BBE +:103A9000069A05999B1A0493039B1B680393A5E759 +:103AA00000933A4608AB2946D8F80800ADE7BBF1C9 +:103AB000000F13D00123B4EBC30F6BD0082C12D826 +:103AC0009DF82030621E23FA02F2D50706D54FF08A +:103AD000FF3202FA04F423438DF820309DF82030A1 +:103AE00089F8003051E7102C12D8BDF82030621E42 +:103AF00023FA02F2D10706D54FF0FF3202FA04F49E +:103B00002343ADF82030BDF82030A9F800303CE761 +:103B1000202C0FD80899631E21FA03F3DA0705D584 +:103B20004FF0FF3202FA04F40C430894089BC9F8E2 +:103B300000302AE7402C2AD0611EC4F12102A4F1F2 +:103B40002103DDE9086526FA01F105FA02F225FAFA +:103B500003F311431943CB0711D50122A4F120032C +:103B6000C4F1200102FA03F322FA01F1A2400B434F +:103B7000524263EB430332432B43CDE90823DDE993 +:103B80000823C9E9002300E76FF00100FDE66FF0AC +:103B90000800FAE6082CA1D9102CB4D9202CEED8B4 +:103BA000C4E7BBF1000FAED0022384E7BBF1000FE6 +:103BB000BCD004237FE70000012A30B5144638BF8B +:103BC000012485B00025402C28BF4024012ACDE9DE +:103BD000025518D81B788DF8083063070AD004AB5B +:103BE000624203EBD40502F0070215F8083C93404B +:103BF00005F8083C034600912246002102A8FFF781 +:103C00005BFB05B030BD082AE4D9102A03D81B8815 +:103C1000ADF80830E1E7202A95BF1B68D3E90023FF +:103C20000293CDE90223D8E710B5CB681BB98B60AE +:103C30000B618B8210BDC4681A681C60C360438A24 +:103C4000013B4382CA60F0E72DE9F04FD1F80080D4 +:103C500093B004460D4618F0800FCDE90323C8F356 +:103C6000C01219BFC8F3C03BC8F306264FF0020BC1 +:103C70001646B8F1000F80F2D18118F0C0430593C9 +:103C800040F0CC810B7B002B00F0C881BBF1020F10 +:103C900003D00178B14240F0C48108F07F01069161 +:103CA0006AB3C8F3074A2B447606069A46EA0B46DF +:103CB00093F8039046EA82465FEAD91346EA0A0679 +:103CC000079300F090800022002367680AA920462D +:103CD000CDE90A23069B524600935B46B84700286D +:103CE0007ED0A7699FB9314604F10C00FFF746FB6F +:103CF0000746E0B96FF0020013B0BDE8F08FC8F3DB +:103D00000F2A18F07F0F08BF0AF0030ACBE73B69C0 +:103D10009E420DD03F68002FF9D1314604F10C00CE +:103D2000FFF72CFB07460028E4D0A3693B60A7619E +:103D300000264FF6FF70DDE90A23C6F1200E22FAB5 +:103D400006F1A6F1200C083603FA0EFE099223FABA +:103D50000CFC089341EA0E0141EA0C01C9B2FFF7DD +:103D6000E3FA402EDDE90832E7D1B882FB7D09F0A5 +:103D70001F06C8F30468C3F384039B1B98B2002B8F +:103D8000D7E90221BCBF00F120031BB252EA0100B7 +:103D90000FD00398821A049860EB0101A748904263 +:103DA0004FF000028A4104D3079A002A5BD0012B0E +:103DB00023DDFA7D4FEA89033946204602F00302EB +:103DC00003F07C031343FB75FFF730FB079BA3B99C +:103DD000FB7DC3F38402013262F38603FB7504E0CA +:103DE0006FF00B0088E7A76917B96FF00C0083E745 +:103DF0003B699E42BAD03F68F6E719F0400F32D0D7 +:103E0000039B142200210DA8BB60049BFB60FDF7FF +:103E100081FF039B0AA920460A93049BADF83EA0AC +:103E20000B932B1D8DF840B00C932B7B8DF84160CC +:103E3000013B8DF84280DBB2ADF83C30069B8DF83B +:103E4000433094F8243083F001038DF84430A368A4 +:103E50009847FB7DC3F38403013303F01F039B02E8 +:103E6000FB82002048E7FB7DC9F34012B2EBD31F71 +:103E700040F0DA80C3F38403B34240F0D88007995E +:103E80004FEA99122B7B002934D0D20741D4032B5F +:103E900040F2D080039BAE1D394604F10C00BB609C +:103EA0003246049BFB602B7B033BDBB2FFF7D0FA6F +:103EB00000280DDA20463946FFF7B8FAFB7D0320CB +:103EC000C3F38403013303F01F039B02FB8213E758 +:103ED000AB883B832A7B033AD2B2B88A3146FFF7DC +:103EE00033FAFB7DB882DA43C2F3C01262F3C71320 +:103EF000FB75B6E76AB92E1D013B394604F10C008B +:103F0000DBB23246FFF7A4FA0028D3DB2A7B013A62 +:103F1000E2E7F98A013BC1F30901DAB2052959D870 +:103F2000281D002307F11A0C9A4208D910F801EB5A +:103F300001330CF801E00131DBB20629F4D1039919 +:103F400093420A9138BF043304992CBF002355FAD9 +:103F500083F30B9107F11A010C9179680E930D917F +:103F6000291DFB8AADF83EA0C3F309038DF840B0CC +:103F70008DF841601A44069B8DF842808DF84330DD +:103F800094F82430ADF83C2083F001038DF84430E0 +:103F90000023B88A7B602A7B013AFFF7D5F93B8B77 +:103FA000B882834203D1A3680AA9204698472046D5 +:103FB0000AA9FFF739FEFB7DB88AC3F384030133F6 +:103FC00003F01F039B02FB823B8B984214BF11201E +:103FD000002091E67B68002BB1D0062001E01C3068 +:103FE0006346D3F800C0BCF1000FF8D1091A05F1FF +:103FF000040C081D00EB030905989DF8143001EB33 +:10400000000EBEF11B0F9AD89A4298D91CF8013BBA +:1040100009F8013B059B01330593EDE76FF00900BB +:104020006AE66FF00A0067E66FF00D0064E66FF075 +:104030000E0061E66FF00F005EE600BF80841E0098 +:10404000EFF30983054968334A6B22F001024A63A2 +:1040500083F30988002383F31188704700EF00E0A1 +:10406000202080F3118862B60D4B0E4AD96821F4E6 +:10407000E0610904090C0A430B49DA60D3F8FC201B +:1040800042F08072C3F8FC20084AC2F8B01F1168E1 +:1040900041F0010111601022DA7783F822007047A5 +:1040A00000ED00E00003FA0555CEACC5001000E0BD +:1040B000202310B583F311880E4B5B6813F4006363 +:1040C00014D0F1EE103AEFF309844FF08073683C9E +:1040D000E361094BDB6B236684F3098800F0C2FFC0 +:1040E00010B1064BA36110BD054BFBE783F31188AC +:1040F000F9E700BF00ED00E000EF00E00B0700086B +:104100000E070008026843681143016003B11847B5 +:1041100070470000024A136843F0C0031360704701 +:104120000078004013B50E4C204600F0A1FA04F1CF +:10413000140000234FF400720A49009400F062F961 +:10414000094B4FF40072094904F13800009400F063 +:10415000DBF9074A074BC4E9172302B010BD00BFC3 +:10416000D45E0020405F002015410008406100201F +:104170000078004000E1F505037C30B5244C0029AF +:1041800018BF0C46012B11D1224B98420ED1224B65 +:10419000D3F8E82042F08042C3F8E820D3F8102199 +:1041A00042F08042C3F81021D3F810312268036E28 +:1041B000C16D03EB52038466B3FBF2F3626815042E +:1041C00042BF23F0070503F0070343EA4503CB6032 +:1041D000A36843F040034B60E36843F001038B6046 +:1041E00042F4967343F001030B604FF0FF330B6210 +:1041F000510505D512F0102205D0B2F1805F04D030 +:1042000080F8643030BD7F23FAE73F23F8E700BF32 +:1042100008740008D45E0020004402582DE9F047DD +:10422000C66D05463768F4692107346219D014F069 +:10423000080118BF8021E20748BF41F02001A30711 +:104240004FF0200348BF41F04001600748BF41F4F0 +:10425000807183F31188281DFFF754FF002383F337 +:104260001188E2050AD5202383F311884FF40071E9 +:10427000281DFFF747FF002383F311884FF0200923 +:104280004FF0000A14F0200838D13B0616D54FF045 +:10429000200905F1380A200610D589F31188504607 +:1042A00000F066F9002836DA0821281DFFF72AFFFA +:1042B00027F080033360002383F31188790614D537 +:1042C000620612D5202383F31188D5E913239A427D +:1042D00008D12B6C33B127F040071021281DFFF7C0 +:1042E00011FF3760002383F31188E30618D5AA6E07 +:1042F0001369ABB15069BDE8F047184789F31188DD +:10430000736A284695F86410194000F0CBF98AF3D7 +:104310001188F469B6E7B06288F31188F469BAE7E6 +:10432000BDE8F087090100F16043012203F5614314 +:10433000C9B283F8001300F01F039A4043099B00A1 +:1043400003F1604303F56143C3F880211A607047AD +:10435000F8B51546826804460B46AA4200D2856825 +:10436000A1692669761AB5420BD218462A46FDF78E +:10437000ABFCA3692B44A3612846A3685B1BA36025 +:10438000F8BD0CD9AF1B18463246FDF79DFC3A46E6 +:10439000E1683044FDF798FCE3683B44EBE71846DE +:1043A0002A46FDF791FCE368E5E700008368934245 +:1043B000F7B50446154600D28568D4E90460361A7C +:1043C000B5420BD22A46FDF77FFC63692B4463613B +:1043D0002846A3685B1BA36003B0F0BD0DD932462D +:1043E000AF1B0191FDF770FC01993A46E06831443A +:1043F000FDF76AFCE3683B44E9E72A46FDF764FC05 +:10440000E368E4E710B50A440024C361029B8460BA +:10441000C16002610362C0E90000C0E9051110BD7E +:1044200008B5D0E90532934201D1826882B9826829 +:10443000013282605A1C426119700021D0E90432B5 +:104440009A4224BFC368436100F0E6FE002008BD25 +:104450004FF0FF30FBE7000070B5202304460E4606 +:1044600083F31188A568A5B1A368A269013BA36085 +:10447000531CA36115782269934224BFE368A361AA +:10448000E3690BB120469847002383F3118828463F +:1044900007E03146204600F0AFFE0028E2DA85F35F +:1044A000118870BD2DE9F74F04460E461746984611 +:1044B000D0F81C904FF0200A8AF311884FF0000BBF +:1044C000154665B12A4631462046FFF741FF0346AF +:1044D00060B94146204600F08FFE0028F1D000234D +:1044E00083F31188781B03B0BDE8F08FB9F1000F9A +:1044F00003D001902046C847019B8BF31188ED1A29 +:104500001E448AF31188DCE7C160C361009B8260AE +:104510000362C0E905111144C0E900000161704760 +:10452000F8B504460D461646202383F31188A76884 +:10453000A7B1A368013BA36063695A1C62611D7047 +:10454000D4E904329A4224BFE3686361E3690BB1A2 +:1045500020469847002080F3118807E03146204626 +:1045600000F04AFE0028E2DA87F31188F8BD000067 +:10457000D0E9052310B59A4201D182687AB98268E0 +:104580000021013282605A1C82611C7803699A42C0 +:1045900024BFC368836100F03FFE204610BD4FF08A +:1045A000FF30FBE72DE9F74F04460E4617469846C5 +:1045B000D0F81C904FF0200A8AF311884FF0000BBE +:1045C000154665B12A4631462046FFF7EFFE034601 +:1045D00060B94146204600F00FFE0028F1D00023CC +:1045E00083F31188781B03B0BDE8F08FB9F1000F99 +:1045F00003D001902046C847019B8BF31188ED1A28 +:104600001E448AF31188DCE70268436811430160A5 +:1046100003B11847704700001430FFF743BF000094 +:104620004FF0FF331430FFF73DBF00003830FFF785 +:10463000B9BF00004FF0FF333830FFF7B3BF0000C1 +:104640001430FFF709BF00004FF0FF311430FFF7BF +:1046500003BF00003830FFF763BF00004FF0FF32A8 +:104660003830FFF75DBF000000207047FFF75ABDEC +:10467000044B036000234360C0E902330123037449 +:10468000704700BF2074000810B52023044683F350 +:104690001188FFF771FD02232374002383F311882F +:1046A00010BD000038B5C36904460D461BB904218E +:1046B0000844FFF7A9FF294604F11400FFF7B0FEF4 +:1046C000002806DA201D4FF48061BDE83840FFF76E +:1046D0009BBF38BD026843681143016003B11847AE +:1046E0007047000013B5406B00F58054D4F8A4382F +:1046F0001A681178042914D1017C022911D1197981 +:10470000012312898B4013420BD101A94C3002F0D6 +:104710009BF8D4F8A4480246019B2179206800F058 +:10472000DFF902B010BD0000143002F01DB8000027 +:104730004FF0FF33143002F017B800004C3002F095 +:10474000EFB800004FF0FF334C3002F0E9B8000042 +:10475000143001F0EBBF00004FF0FF31143001F0D6 +:10476000E5BF00004C3002F0BBB800004FF0FF3254 +:104770004C3002F0B5B800000020704710B500F5CD +:104780008054D4F8A4381A681178042917D1017C10 +:10479000022914D15979012352898B4013420ED139 +:1047A000143001F07DFF024648B1D4F8A4484FF41C +:1047B000407361792068BDE8104000F07FB910BDFA +:1047C000406BFFF7DBBF0000704700007FB5124B66 +:1047D00001250426044603600023057400F18402C9 +:1047E00043602946C0E902330C4B02901430019318 +:1047F0004FF44073009601F02FFF094B04F69442EA +:10480000294604F14C000294CDE900634FF4407353 +:1048100001F0F6FF04B070BD48740008C1470008FD +:10482000E54600080A68202383F311880B790B33CF +:1048300042F823004B79133342F823008B7913B1EC +:104840000B3342F8230000F58053C3F8A418022369 +:104850000374002383F311887047000038B5037F89 +:10486000044613B190F85430ABB90125201D022144 +:10487000FFF730FF04F114006FF00101257700F01D +:10488000D7FC04F14C0084F854506FF00101BDE8EE +:10489000384000F0CDBC38BD10B5012104460430CD +:1048A000FFF718FF0023237784F8543010BD000071 +:1048B00038B504460025143001F0E6FE04F14C0042 +:1048C000257701F0B5FF201D84F854500121FFF732 +:1048D00001FF2046BDE83840FFF750BF90F8803018 +:1048E00003F06003202B06D190F881200023212AB9 +:1048F00003D81F2A06D800207047222AFBD1C0E91E +:104900001D3303E0034A426707228267C367012021 +:10491000704700BF3422002037B500F58055D5F828 +:10492000A4381A68117804291AD1017C022917D1F8 +:104930001979012312898B40134211D100F14C04E3 +:10494000204602F035F858B101A9204601F07CFF5D +:10495000D5F8A4480246019B2179206800F0C0F8F0 +:1049600003B030BD01F10B03F0B550F8236085B002 +:1049700004460D46FEB1202383F3118804EB85071E +:10498000301D0821FFF7A6FEFB6806F14C005B69AD +:104990001B681BB1019001F065FF019803A901F0AC +:1049A00053FF024648B1039B2946204600F098F881 +:1049B000002383F3118805B0F0BDFB685A691268C3 +:1049C000002AF5D01B8A013B1340F1D104F180028B +:1049D000EAE70000133138B550F82140ECB120234C +:1049E00083F3118804F58053D3F8A428136852790F +:1049F00003EB8203DB689B695D6845B104216018A5 +:104A0000FFF768FE294604F1140001F053FE20462A +:104A1000FFF7B4FE002383F3118838BD7047000010 +:104A200001F05CB901234022002110B5044600F8D2 +:104A3000303BFDF76FF90023C4E9013310BD0000DE +:104A400010B52023044683F31188242241600021FD +:104A50000C30FDF75FF9204601F062F90223237064 +:104A6000002383F3118810BD70B500EB8103054668 +:104A700050690E461446DA6018B110220021FDF785 +:104A800049F9A06918B110220021FDF743F9314618 +:104A90002846BDE8704001F055BA00008368202226 +:104AA000002103F0011310B5044683601030FDF7B8 +:104AB00031F92046BDE8104001F0D0BAF0B401252C +:104AC00000EB810447898D40E4683D43A46945813A +:104AD00023600023A2606360F0BC01F0EDBA000027 +:104AE000F0B4012500EB810407898D40E4683D4363 +:104AF0006469058123600023A2606360F0BC01F05B +:104B000063BB000070B50223002504462422037015 +:104B10002946C0F888500C3040F8045CFDF7FAF8DC +:104B2000204684F8705001F0A1F963681B6823B136 +:104B300029462046BDE87040184770BD037880F8CC +:104B40008C300523037043681B6810B504460BB115 +:104B5000042198470023A36010BD000090F88C202A +:104B6000436802701B680BB10521184770470000AD +:104B700070B590F87030044613B1002380F870309F +:104B800004F18002204601F08DFA63689B68B3B996 +:104B900094F8803013F0600535D00021204601F0F4 +:104BA00037FD0021204601F027FD63681B6813B123 +:104BB000062120469847062384F8703070BD2046B1 +:104BC00098470028E4D0B4F88630A26F9A4288BF94 +:104BD000A36794F98030A56F002B4FF0200380F27B +:104BE0000381002D00F0F280092284F8702083F305 +:104BF000118800212046D4E91D23FFF771FF00230F +:104C000083F31188DAE794F8812003F07F0343EA05 +:104C1000022340F20232934200F0C58021D8B3F55E +:104C2000807F48D00DD8012B3FD0022B00F093801D +:104C3000002BB2D104F1880262670222A267E36707 +:104C4000C1E7B3F5817F00F09B80B3F5407FA4D12D +:104C500094F88230012BA0D1B4F8883043F00203DD +:104C600032E0B3F5006F4DD017D8B3F5A06F31D057 +:104C7000A3F5C063012B90D86368204694F8822086 +:104C80005E6894F88310B4F88430B047002884D06C +:104C9000436863670368A3671AE0B3F5106F36D003 +:104CA00040F6024293427FF478AF5C4B6367022385 +:104CB000A3670023C3E794F88230012B7FF46DAF24 +:104CC000B4F8883023F00203A4F88830C4E91D55F5 +:104CD000E56778E7B4F88030B3F5A06F0ED194F8AB +:104CE0008230204684F88A3001F01EF963681B6820 +:104CF00013B1012120469847032323700023C4E900 +:104D00001D339CE704F18B0363670123C3E723781A +:104D1000042B10D1202383F311882046FFF7BEFE19 +:104D200085F311880321636884F88B5021701B6818 +:104D30000BB12046984794F88230002BDED084F8DF +:104D40008B300423237063681B68002BD6D00221AC +:104D500020469847D2E794F8843020461D0603F099 +:104D60000F010AD501F090F9012804D002287FF440 +:104D700014AF2B4B9AE72B4B98E701F077F9F3E749 +:104D800094F88230002B7FF408AF94F8843013F04D +:104D90000F01B3D01A06204602D501F051FCADE751 +:104DA00001F042FCAAE794F88230002B7FF4F5AEC4 +:104DB00094F8843013F00F01A0D01B06204602D5D2 +:104DC00001F026FC9AE701F017FC97E7142284F81B +:104DD000702083F311882B462A4629462046FFF788 +:104DE0006DFE85F31188E9E65DB1152284F8702027 +:104DF00083F3118800212046D4E91D23FFF75EFECE +:104E0000FDE60B2284F8702083F311882B462A4696 +:104E100029462046FFF764FEE3E700BF78740008E8 +:104E2000707400087474000838B590F87030044647 +:104E3000002B3ED0063BDAB20F2A34D80F2B32D8E3 +:104E4000DFE803F03731310822323131313131318D +:104E500031313737856FB0F886309D4214D2C36840 +:104E60001B8AB5FBF3F203FB12556DB9202383F3C4 +:104E700011882B462A462946FFF732FE85F3118812 +:104E80000A2384F870300EE0142384F87030202355 +:104E900083F31188002320461A461946FFF70EFEB9 +:104EA000002383F3118838BDC36F03B198470023F3 +:104EB000E7E70021204601F0ABFB0021204601F08E +:104EC0009BFB63681B6813B10621204698470623A5 +:104ED000D7E7000010B590F870300446142B29D0A5 +:104EE00017D8062B05D001D81BB110BD093B022BEA +:104EF000FBD80021204601F08BFB0021204601F069 +:104F00007BFB63681B6813B1062120469847062384 +:104F100019E0152BE9D10B2380F87030202383F39F +:104F2000118800231A461946FFF7DAFD002383F3A0 +:104F30001188DAE7C3689B695B68002BD5D1C36F22 +:104F400003B19847002384F87030CEE7024B00226B +:104F5000C3E900339A6070474063002000238268F1 +:104F60000374054B1B6899689142FBD25A68036031 +:104F700042601060586070474063002008B52023ED +:104F800083F31188037C032B05D0042B0DD02BB9A0 +:104F900083F3118808BD436900221A604FF0FF3384 +:104FA0004361FFF7DBFF0023F2E7D0E90032136033 +:104FB0005A60F3E7002382680374054B1B68996805 +:104FC0009142FBD85A680360426010605860704795 +:104FD00040630020054B1969087418680268536023 +:104FE0001A60186101230374FBF77ABB4063002049 +:104FF0004B1C30B5044687B00A4D10D02B6901A870 +:10500000094A00F031F92046FFF7E4FF049B13B191 +:1050100001A800F065F92B69586907B030BDFFF7AA +:10502000D9FFF8E7406300207D4F000838B50C4DEC +:10503000044641612B6981689A68914203D8BDE8B2 +:105040003840FFF78BBF1846FFF7B4FF01232C61F0 +:10505000014623742046BDE83840FBF741BB00BF42 +:1050600040630020044B1A681B6990689B68984253 +:1050700094BF0020012070474063002010B5084C09 +:10508000236820691A6854602260012223611A741F +:10509000FFF790FF01462069BDE81040FBF720BBF9 +:1050A0004063002008B5FFF7DDFF18B1BDE80840F8 +:1050B000FFF7E4BF08BD0000FFF7E0BFFEE7000018 +:1050C00010B50C4CFFF742FF00F0C0F880220A49EF +:1050D000204600F047F8012344F8180C0374FEF74B +:1050E000BFFF002383F3118862B60448BDE8104077 +:1050F00000F058B8686300207C7400088C740008C5 +:1051000008B572B6034B586200F008FC00F0D6FCFC +:10511000FEE700BF4063002000F01CB9EFF31180F0 +:1051200020B9EFF30583202282F311887047000035 +:1051300010B530B9EFF30584C4F3080414B180F35B +:10514000118810BDFFF7AEFF84F31188F9E7000066 +:10515000034A516853685B1A9842FBD8704700BFF6 +:10516000001000E082600222028270478368A3F18F +:105170007C0243F80C2C026943F83C2C426943F84A +:10518000382C074A43F81C2CC268A3F1180043F8D6 +:10519000102C022203F8082C002203F8072C704779 +:1051A000F906000810B5202383F31188FFF7DEFF0E +:1051B00000210446FFF73AFF002383F311882046BD +:1051C00010BD0000024B1B6958610F20FFF702BFA2 +:1051D00040630020202383F31188FFF7F3BF000012 +:1051E00008B50146202383F311880820FFF700FF4C +:1051F000002383F3118808BD49B1064B42681B693F +:1052000018605A60136043600420FFF7F1BE4FF04E +:10521000FF307047406300200368984206D01A6848 +:105220000260506018465961FFF798BE7047000051 +:1052300038B504460D462068844200D138BD036865 +:1052400023605C604561FFF789FEF4E7054B4FF092 +:10525000FF3103F11402C3E905220022C3E907125A +:10526000704700BF4063002070B51C4E05460C46D9 +:10527000C0E9032301F0D2FB334653F8142F9A42BE +:105280000DD130620A2C2CBF00190A302A60C5E902 +:105290000124C6E90555BDE8704001F0A9BB316A9B +:1052A000431AE31838BF1C469368A34202D9081971 +:1052B00001F0AEFB73699A6894420CD85A68AC60EE +:1052C0002B606A6015609A685D60121B9A604FF0EF +:1052D000FF33F36170BDA41A1B68ECE74063002044 +:1052E00038B51B4C636998420DD08168D0E9003213 +:1052F00013605A600022C2609A680A449A604FF0B4 +:10530000FF33E36138BD03682246002142F8143FB1 +:1053100093425A60C16003D1BDE8384001F072BBCE +:105320009A688168256A0A449A6001F077FB63698C +:10533000411B9A688A42E5D9AB181D1A206A092DCB +:1053400098BF01F10A02BDE83840104401F060BB8B +:10535000406300202DE9F041184C002704F11406A9 +:10536000656901F05BFB236AAA68C11A8A4215D8F5 +:105370001344D5F80C802362D5E9003213605A60DB +:105380006369EF60B34201D101F03CFB87F3118800 +:105390002869C047202383F31188E1E76169B1429E +:1053A00009D013441B1ABDE8F0410A2B2CBFC018CA +:1053B0000A3001F02DBBBDE8F08100BF4063002042 +:1053C00000207047FEE70000704700004FF0FF30FC +:1053D0007047000002290CD0032904D00129074896 +:1053E00018BF00207047032A05D8054800EBC2000B +:1053F0007047044870470020704700BF7075000870 +:10540000442200202475000870B59AB0054608466D +:10541000144601A900F0C2F801A8FCF773FC431C74 +:105420000022C6B25B001046C5E900342370032396 +:10543000023404F8013C01ABD1B202348E4201D8EF +:105440001AB070BD13F8011B013204F8010C04F806 +:10545000021CF1E708B5202383F311880348FFF706 +:105460005BFA002383F3118808BD00BFF8640020B5 +:1054700090F8803003F01F02012A07D190F88120B4 +:105480000B2A03D10023C0E91D3315E003F06003AC +:10549000202B08D1B0F884302BB990F88120212A34 +:1054A00003D81F2A04D8FFF719BA222AEBD0FAE74B +:1054B000034A426707228267C3670120704700BF23 +:1054C0003B22002007B5052917D8DFE801F019169F +:1054D00003191920202383F31188104A0121019018 +:1054E000FFF7C2FA019802210D4AFFF7BDFA0D48F5 +:1054F000FFF7DEF9002383F3118803B05DF804FBA6 +:10550000202383F311880748FFF7A8F9F2E7202347 +:1055100083F311880348FFF7BFF9EBE7C474000871 +:10552000E8740008F864002038B50C4D0C4C2A468D +:105530000C4904F10800FFF767FF05F1CA0204F106 +:1055400010000949FFF760FF05F5CA7204F1180061 +:105550000649BDE83840FFF757BF00BFD07D0020A7 +:1055600044220020A4740008AE740008B974000836 +:1055700070B5044608460D46FCF7C4FBC6B220468B +:10558000013403780BB9184670BD32462946FCF742 +:10559000A5FB0028F3D10120F6E700002DE9F04734 +:1055A00005460C46FCF7AEFB2B49C6B22846FFF772 +:1055B000DFFF08B10A36F6B228492846FFF7D8FFC0 +:1055C00008B11036F6B2632E0BD8DFF88C80DFF806 +:1055D0008C90234FDFF894A02E7846B92670BDE852 +:1055E000F08729462046BDE8F04701F03BBE252E56 +:1055F0002ED1072241462846FCF770FB70B9194BA3 +:10560000224603F1100153F8040B8B4242F8040BBD +:10561000F9D11B78073511341370DDE708224946AC +:105620002846FCF75BFB98B9A21C0F4B1978023295 +:105630000909C95D02F8041C13F8011B01F00F01F0 +:105640005345C95D02F8031CF0D118340835C3E78F +:10565000013504F8016BBFE790750008B9740008C4 +:1056600098750008A272000800E8F11F0CE8F11F0D +:10567000BFF34F8F044B1A695107FCD1D3F81021A7 +:105680005207F8D1704700BF0020005208B50D4BFB +:105690001B78ABB9FFF7ECFF0B4BDA68D10704D5E9 +:1056A0000A4A5A6002F188325A60D3F80C21D207B4 +:1056B00006D5064AC3F8042102F18832C3F8042152 +:1056C00008BD00BF2E800020002000522301674546 +:1056D00008B5114B1B78F3B9104B1A69510703D564 +:1056E000DA6842F04002DA60D3F81021520705D59B +:1056F000D3F80C2142F04002C3F80C21FFF7B8FFA9 +:10570000064BDA6842F00102DA60D3F80C2142F06D +:105710000102C3F80C2108BD2E8000200020005299 +:105720000F289ABF00F580604004002070470000F9 +:105730004FF4003070470000102070470F2808B564 +:105740000BD8FFF7EDFF00F500330268013204D1FA +:1057500004308342F9D1012008BD0020FCE700009D +:105760000F2870B5054645D8FFF7D8FC224CFFF747 +:105770007FFF0646FFF78AFF4FF0FF33072D636177 +:10578000C4F8143120D82361FFF772FF2B0243F0D5 +:105790002403E360E36843F08003E36023695A076E +:1057A000FCD42846FFF764FF4FF40031FFF7B8FF41 +:1057B00000F060F93046FFF78BFFFFF7B9FC284691 +:1057C000BDE87040FFF7BABFC4F81031FFF750FFD3 +:1057D000A5F108031B0243F02403C4F80C31D4F8EC +:1057E0000C3143F08003C4F80C31D4F810315B075E +:1057F000FBD4D6E7002070BD002000522DE9F84F01 +:1058000040EA020305460C461746D80602D000209F +:10581000BDE8F88F27F01F07DFF8D4B0FFF736FF99 +:105820002744BC4203D10120FFF752FFF0E72022BA +:105830002946204601F098FC10B920352034F0E7C5 +:105840002B4605F120021E68711CE0D104339A42F8 +:10585000F9D1FFF763FC05F17843234AB3F5801FC4 +:10586000224B28BF9A4603F1040338BF9046A2F1A9 +:10587000080228BF9846A3F108033ABF9146DA46CA +:105880009946FFF7F5FEC8F80060A5EB040CD9F8BF +:10589000002004F11C0142F00202C9F80020221F7E +:1058A000DAF8006016F00506FAD152F8043F8A4291 +:1058B0004CF80230F4D1BFF34F8FFFF7D9FE4FF011 +:1058C000FF32C8F80020D9F8002022F00202C9F8FF +:1058D0000020FFF72DFC20222146284601F044FC41 +:1058E0000028AAD030469FE7142000521021005211 +:1058F0001020005210B5084C237828B11BB9FFF7CF +:10590000C5FE0123237010BD002BFCD02070BDE824 +:105910001040FFF7DDBE00BF2E80002038B5054DDA +:1059200000240334696855F80C0B00F0B5F8122C0C +:10593000F7D138BDAC75000870B5104E82B0FFF7D6 +:10594000EDFB054601F06AF8326803469042336089 +:1059500037BF0B4A0A495168146836BF0131D1E993 +:10596000004151600419284641F100010191FFF7FF +:10597000DFFB2046019902B070BD00BF30800020DF +:105980003880002070B5124E82B0FFF7C7FB054685 +:1059900001F044F8326803469042336037BF0D4A45 +:1059A0000C495168146836BF0131D1E9004151609A +:1059B0000419284641F100010191FFF7B9FB4FF4AA +:1059C0007A72002320460199FAF772FC02B070BD8A +:1059D00030800020388000200244074BD2B210B53E +:1059E000904200D110BD441C00B253F8200041F891 +:1059F000040BE0B2F4E700BF504000580E4B30B546 +:105A00001C6F240405D41C6F1C671C6F44F40044F5 +:105A10001C670A4C02442368D2B243F480732360AB +:105A2000074B904200D130BD441C51F8045B00B2DA +:105A300043F82050E0B2F4E700440258004802580E +:105A40005040005807B5012201A90020FFF7C4FF0C +:105A5000019803B05DF804FB13B50446FFF7F2FFAD +:105A6000A04205D0012201A900200194FFF7C6FF42 +:105A700002B010BD0144BFF34F8F064B884204D3E0 +:105A8000BFF34F8FBFF36F8F7047C3F85C022030B6 +:105A9000F4E700BF00ED00E00144BFF34F8F064B79 +:105AA000884204D3BFF34F8FBFF36F8F7047C3F8A3 +:105AB00070022030F4E700BF00ED00E07047000006 +:105AC000074B45F255521A6002225A6040F6FF72A7 +:105AD0009A604CF6CC421A600122024B1A70704751 +:105AE0000048005844800020034B1B781BB1034B37 +:105AF0004AF6AA221A6070474480002000480058E5 +:105B0000034B1A681AB9034AD2F8D0241A607047B6 +:105B10004080002000400258024B4FF48032C3F80E +:105B2000D02470470040025808B5FFF7E9FF024B48 +:105B30001868C0F3806008BD4080002070B5BFF3D6 +:105B40004F8FBFF36F8F1A4A0021C2F85012BFF374 +:105B50004F8FBFF36F8F536943F400335361BFF32B +:105B60004F8FBFF36F8FC2F88410BFF34F8FD2F8FF +:105B7000803043F6E074C3F3C900C3F34E335B01D6 +:105B800003EA0406014646EA81750139C2F860520B +:105B9000F9D2203B13F1200FF2D1BFF34F8F53699D +:105BA00043F480335361BFF34F8FBFF36F8F70BDEA +:105BB00000ED00E0FEE700000A4B0B480B4A904264 +:105BC0000BD30B4BC11EDA1C121A22F003028B42BC +:105BD00038BF00220021FCF79DB853F8041B40F8A1 +:105BE000041BECE738780008208200202082002087 +:105BF000208200207047000070B5D0E924430022C5 +:105C00004FF0FF359E6804EB42135101D3F80009B1 +:105C1000002805DAD3F8000940F08040C3F80009F5 +:105C2000D3F8000B002805DAD3F8000B40F08040D1 +:105C3000C3F8000B013263189642C3F80859C3F841 +:105C4000085BE0D24FF00113C4F81C3870BD0000AF +:105C500000EB8103D3F80CC02DE9F043DCF81420ED +:105C60004E1CD0F89050D2F800E005EB063605EB5C +:105C70004118506870450AD30122D5F8343802FA29 +:105C800001F123EA0101C5F83418BDE8F083AEEB59 +:105C90000003BCF81040A34228BF2346D8F8184997 +:105CA000A4B2B3EB840FF0D89468A4F1040959F8B6 +:105CB000047F3760A4EB09071F44042FF7D81C4466 +:105CC000034494605360D4E7890141F020010161ED +:105CD00003699B06FCD41220FFF73ABA10B50A4CB0 +:105CE0002046FEF79FFE094BC4F89030084BC4F8DD +:105CF0009430084C2046FEF795FE074BC4F89030D0 +:105D0000064BC4F8943010BD4880002000000840C5 +:105D100018760008E4800020000004402476000883 +:105D200070B503780546012B5DD1494BD0F8904002 +:105D3000984259D1474B0E216520D3F8D82042F024 +:105D40000062C3F8D820D3F8002142F00062C3F803 +:105D50000021D3F80021D3F8802042F00062C3F87C +:105D60008020D3F8802022F00062C3F88020D3F88E +:105D70008030FEF7D7FA384BE360384BC4F8003870 +:105D80000023D5F89060C4F8003EC02323604FF490 +:105D90000413A3633369002BFCDA01230C20336165 +:105DA000FFF7D6F93369DB07FCD41220FFF7D0F9EF +:105DB0003369002BFCDA00262846A660FFF71CFF9B +:105DC0006B68C4F81068DB68C4F81468C4F81C6811 +:105DD000002B3AD1224BA3614FF0FF336361A368DC +:105DE00043F00103A36070BD1E4B9842C8D1194B0C +:105DF0000E214D20D3F8D82042F00072C3F8D820ED +:105E0000D3F8002142F00072C3F80021D3F800213A +:105E1000D3F8802042F00072C3F88020D3F88020AD +:105E200022F00072C3F88020D3F88020D3F8D82065 +:105E300022F08062C3F8D820D3F8002122F08062DB +:105E4000C3F80021D3F8003193E7074BC3E700BF45 +:105E50004880002000440258401400400300200203 +:105E6000003C30C0E4800020083C30C0F8B5D0F8D9 +:105E70009040054600214FF000662046FFF724FFC2 +:105E8000D5F8941000234FF001128F684FF0FF30C7 +:105E9000C4F83438C4F81C2804EB431201339F4281 +:105EA000C2F80069C2F8006BC2F80809C2F8080B12 +:105EB000F2D20B68D5F89020C5F8983063621023B1 +:105EC0001361166916F01006FBD11220FFF740F996 +:105ED000D4F8003823F4FE63C4F80038A36943F40F +:105EE000402343F01003A3610923C4F81038C4F819 +:105EF00014380B4BEB604FF0C043C4F8103B094B18 +:105F0000C4F8003BC4F81069C4F80039D5F89830DB +:105F100003F1100243F48013C5F89820A362F8BD82 +:105F2000F475000840800010D0F8902090F88A1096 +:105F3000D2F8003823F4FE6343EA0113C2F80038B4 +:105F4000704700002DE9F84300EB8103D0F8905032 +:105F50000C468046DA680FFA81F94801166806F0A7 +:105F60000306731E022B05EB41134FF0000194BF93 +:105F7000B604384EC3F8101B4FF0010104F11003B2 +:105F800098BF06F1805601FA03F3916998BF06F5B0 +:105F9000004600293AD0578A04F158013743490195 +:105FA0006F50D5F81C180B430021C5F81C382B186E +:105FB0000127C3F81019A7405369611E9BB3138AC8 +:105FC000928B9B08012A88BF5343D8F898209818D1 +:105FD00042EA034301F140022146C8F898002846EE +:105FE00005EB82025360FFF76FFE08EB8900C36880 +:105FF0001B8A43EA845348341E4364012E51D5F86A +:106000001C381F43C5F81C78BDE8F88305EB491719 +:10601000D7F8001B21F40041C7F8001BD5F81C1865 +:1060200021EA0303C0E704F13F030B4A2846214657 +:1060300005EB83035A60FFF747FE05EB4910D0F8E4 +:10604000003923F40043C0F80039D5F81C3823EA9E +:106050000707D7E70080001000040002D0F8942062 +:106060001268C0F89820FFF7C7BD00005831D0F87B +:10607000903049015B5813F4004004D013F4001F22 +:106080000CBF0220012070474831D0F89030490100 +:106090005B5813F4004004D013F4001F0CBF02201F +:1060A0000120704700EB8101CB68196A0B6813600F +:1060B0004B6853607047000000EB810330B5DD682A +:1060C000AA691368D36019B9402B84BF40231360B9 +:1060D0006B8A1468D0F890201C4402EB4110013CFC +:1060E00009B2B4FBF3F46343033323F0030343EA3D +:1060F000C44343F0C043C0F8103B2B6803F00303D4 +:10610000012B0ED1D2F8083802EB411013F4807F36 +:10611000D0F8003B14BF43F0805343F00053C0F865 +:10612000003B02EB4112D2F8003B43F00443C2F8BB +:10613000003B30BD2DE9F041D0F8906005460C469B +:1061400006EB4113D3F8087B3A07C3F8087B08D560 +:10615000D6F814381B0704D500EB8103DB685B68B5 +:106160009847FA071FD5D6F81438DB071BD505EB7F +:106170008403D968CCB98B69488A5A68B2FBF0F6B7 +:1061800000FB16228AB91868DA6890420DD2121AFA +:10619000C3E90024202383F3118821462846FFF712 +:1061A0008BFF84F31188BDE8F081012303FA04F228 +:1061B0006B8923EA02036B81CB68002BF3D0214665 +:1061C0002846BDE8F041184700EB81034A0170B54D +:1061D000DD68D0F890306C692668E66056BB1A44DA +:1061E0004FF40020C2F810092A6802F00302012AC5 +:1061F0000AB20ED1D3F8080803EB421410F4807FE2 +:10620000D4F8000914BF40F0805040F00050C4F8AA +:10621000000903EB4212D2F8000940F00440C2F832 +:1062200000090122D3F8340802FA01F10143C3F84E +:10623000341870BD19B9402E84BF402020602068FA +:106240001A442E8A8419013CB4FBF6F440EAC44097 +:1062500040F00050C6E700002DE9F041D0F8906012 +:1062600004460D4606EB4113D3F80879C3F80879C4 +:10627000FB071CD5D6F81038DA0718D500EB8103D8 +:10628000D3F80CC0DCF81430D3F800E0DA68964597 +:106290001BD2A2EB0E024FF000081A60C3F8048074 +:1062A000202383F31188FFF78FFF88F311883B06C3 +:1062B00018D50123D6F83428AB40134212D0294612 +:1062C0002046BDE8F041FFF7C3BC012303FA01F209 +:1062D000038923EA02030381DCF80830002BE6D0AF +:1062E0009847E4E7BDE8F0812DE9F84FD0F89050E9 +:1062F00004466E69AB691E4016F480586E6103D087 +:10630000BDE8F84FFEF7FEBB002E12DAD5F8003ECE +:106310009F0705D0D5F8003E23F00303C5F8003EE3 +:10632000D5F80438204623F00103C5F80438FEF7F9 +:1063300015FC300505D52046FFF75EFC2046FEF72C +:10634000FDFBB1040CD5D5F8083813F0060FEB6847 +:1063500023F470530CBF43F4105343F4A053EB6089 +:10636000320704D56368DB680BB120469847F30217 +:1063700000F1BA80B70226D5D4F8909000274FF0EC +:10638000010A09EB4712D2F8003B03F44023B3F5AE +:10639000802F11D1D2F8003B002B0DDA62890AFA66 +:1063A00007F322EA0303638104EB8703DB68DB68FE +:1063B00013B13946204698470137D4F89430FFB2DC +:1063C0009B689F42DDD9F00619D5D4F89000026A87 +:1063D000C2F30A1702F00F0302F4F012B2F5802F95 +:1063E00000F0CC80B2F5402F09D104EB83030022EA +:1063F00000F58050DB681B6A974240F0B2803003A2 +:10640000D5F8185835D5E90303D500212046FFF704 +:1064100091FEAA0303D501212046FFF78BFE6B03F3 +:1064200003D502212046FFF785FE2F0303D5032164 +:106430002046FFF77FFEE80203D504212046FFF740 +:1064400079FEA90203D505212046FFF773FE6A02F3 +:1064500003D506212046FFF76DFE2B0203D5072149 +:106460002046FFF767FEEF0103D508212046FFF71E +:1064700061FE700340F1A980E90703D500212046A1 +:10648000FFF7EAFEAA0703D501212046FFF7E4FE45 +:106490006B0703D502212046FFF7DEFE2F0703D549 +:1064A00003212046FFF7D8FEEE0603D5042120463F +:1064B000FFF7D2FEA80603D505212046FFF7CCFE44 +:1064C000690603D506212046FFF7C6FE2A0603D536 +:1064D00007212046FFF7C0FEEB0576D520460821B0 +:1064E000BDE8F84FFFF7B8BED4F8909000274FF002 +:1064F000010AD4F894305FFA87FB9B689B453FF60E +:1065000039AF09EB4B13D3F8002902F44022B2F55E +:10651000802F24D1D3F80029002A20DAD3F80029CB +:1065200042F09042C3F80029D3F80029002AFBDB8F +:106530005946D4F89000FFF7C7FB22890AFA0BF3FB +:1065400022EA0303238104EB8B03DB689B6813B10E +:1065500059462046984759462046FFF779FB0137B0 +:10656000C7E7910701D1D0F80080072A02F10102A4 +:106570009CBF03F8018B4FEA18283DE704EB830327 +:1065800000F58050DA68D2F818C0DCF80820DCE9A1 +:10659000001CA1EB0C0C00218F4208D1DB689B6929 +:1065A0009A683A449A605A683A445A6027E711F068 +:1065B000030F01D1D0F800808C4501F1010184BFA7 +:1065C00002F8018B4FEA1828E6E7BDE8F88F0000D3 +:1065D00008B50348FFF788FEBDE80840FDF768BD31 +:1065E0004880002008B50348FFF77EFEBDE808405C +:1065F000FDF75EBDE4800020D0F8903003EB411140 +:10660000D1F8003B43F40013C1F8003B7047000091 +:10661000D0F8903003EB4111D1F8003943F4001366 +:10662000C1F8003970470000D0F8903003EB4111F9 +:10663000D1F8003B23F40013C1F8003B7047000081 +:10664000D0F8903003EB4111D1F8003923F4001356 +:10665000C1F800397047000030B50433039C017263 +:10666000002104FB0325C160C0E90653049B0363BA +:10667000059BC0E90000C0E90422C0E90842C0E966 +:106680000A11436330BD00000022416AC260C0E9C4 +:106690000411C0E90A226FF00101FEF7C9BD000034 +:1066A000D0E90432934201D1C2680AB9181D70477B +:1066B00000207047036919600021C2680132C2607E +:1066C000C269134482699342036124BF436A036130 +:1066D000FEF7A2BD38B504460D46E3683BB16269DA +:1066E0000020131D1268A3621344E36207E0237ABB +:1066F00033B929462046FEF77FFD0028EDDA38BD84 +:106700006FF00100FBE70000C368C269013BC36092 +:106710004369134482699342436124BF436A4361DE +:1067200000238362036B03B11847704770B52023C1 +:10673000044683F31188866A3EB9FFF7CBFF05460E +:1067400018B186F31188284670BDA36AE26A13F86F +:10675000015B9342A36202D32046FFF7D5FF0023DB +:1067600083F31188EFE700002DE9F84F04460E4649 +:10677000174698464FF0200989F311880025AA464C +:10678000D4F828B0BBF1000F09D141462046FFF7ED +:10679000A1FF20B18BF311882846BDE8F88FD4E91A +:1067A0000A12A7EB050B521A934528BF9346BBF17B +:1067B000400F1BD9334601F1400251F8040B9142BE +:1067C00043F8040BF9D1A36A403640354033A36245 +:1067D000D4E90A239A4202D32046FFF795FF8AF3B1 +:1067E0001188BD42D8D289F31188C9E730465A468C +:1067F000FBF76AFAA36A5E445D445B44A362E7E781 +:1068000010B5029C0433017204FB0321C460C0E98B +:1068100006130023C0E90A33039B0363049BC0E90A +:106820000000C0E90422C0E90842436310BD000033 +:10683000026A6FF00101C260426AC0E904220022CC +:10684000C0E90A22FEF7F4BCD0E904239A4201D140 +:10685000C26822B9184650F8043B0B60704700200C +:1068600070470000C3680021C2690133C3604369F7 +:10687000134482699342436124BF436A4361FEF734 +:10688000CBBC000038B504460D46E3683BB1236934 +:1068900000201A1DA262E2691344E36207E0237A32 +:1068A00033B929462046FEF7A7FC0028EDDA38BDAB +:1068B0006FF00100FBE7000003691960C268013A4C +:1068C000C260C269134482699342036124BF436A70 +:1068D000036100238362036B03B118477047000014 +:1068E00070B520230D460446114683F31188866A4D +:1068F0002EB9FFF7C7FF10B186F3118870BDA36AE8 +:106900001D70A36AE26A01339342A36204D3E16972 +:1069100020460439FFF7D0FF002080F31188EDE70F +:106920002DE9F84F04460D46904699464FF0200A4F +:106930008AF311880026B346A76A4FB94946204614 +:10694000FFF7A0FF20B187F311883046BDE8F88F2C +:10695000D4E90A073A1AA8EB0607974228BF174658 +:10696000402F1BD905F1400355F8042B9D4240F8F8 +:10697000042BF9D1A36A40364033A362D4E90A2339 +:106980009A4204D3E16920460439FFF795FF8BF35F +:1069900011884645D9D28AF31188CDE729463A466F +:1069A000FBF792F9A36A3D443E443B44A362E5E70A +:1069B000D0E904239A4217D1C3689BB1836A8BB193 +:1069C000043B9B1A0ED01360C368013BC360C369CC +:1069D0001A4483699A42026124BF436A0361002317 +:1069E00083620123184670470023FBE700F0CEB80E +:1069F000034B002258631A610222DA60704700BF1D +:106A0000000C0040014B0022DA607047000C00408F +:106A1000014B5863704700BF000C0040014B586A9F +:106A2000704700BF000C00404B6843608B68836078 +:106A3000CB68C3600B6943614B6903628B69436236 +:106A40000B6803607047000008B5364B40F2FF71D9 +:106A50003548D3F888200A43C3F88820D3F8882023 +:106A600022F4FF6222F00702C3F88820D3F88820BE +:106A7000D3F8E0200A43C3F8E020D3F808210A4302 +:106A8000C3F80821294AD3F808311146FFF7CCFF93 +:106A900000F5806002F11C01FFF7C6FF00F5806081 +:106AA00002F13801FFF7C0FF00F5806002F15401E8 +:106AB000FFF7BAFF00F5806002F17001FFF7B4FF45 +:106AC00000F5806002F18C01FFF7AEFF00F58060F9 +:106AD00002F1A801FFF7A8FF00F5806002F1C401F0 +:106AE000FFF7A2FF00F5806002F1E001FFF79CFFD5 +:106AF00000F5806002F1FC01FFF796FF02F58C7152 +:106B000000F58060FFF790FF00F0F4F8084B0522D5 +:106B1000C3F898204FF06052C3F89C20054AC3F890 +:106B2000A02008BD0044025800000258307600083A +:106B300000ED00E01F00080308B500F0D7FAFEF7EB +:106B4000BFFA0F4BD3F8DC2042F04002C3F8DC2040 +:106B5000D3F8042122F04002C3F80421D3F8043111 +:106B6000084B1A6842F008021A601A6842F00402E0 +:106B70001A60FEF7C5FFBDE80840FEF7D5BC00BFB0 +:106B8000004402580018024870470000114BD3F827 +:106B9000E82042F00802C3F8E820D3F8102142F0C0 +:106BA0000802C3F810210C4AD3F81031D36B43F01C +:106BB0000803D363C722094B9A624FF0FF32DA62AF +:106BC00000229A615A63DA605A6001225A611A609F +:106BD000704700BF004402580010005C000C0040E9 +:106BE000094A08B51169D3680B40D9B29B076FEA0F +:106BF0000101116107D5202383F31188FEF78CFA78 +:106C0000002383F3118808BD000C0040384B4FF07F +:106C1000FF31D3F88020C3F88010D3F88020002201 +:106C2000C3F88020D3F88000D3F88400C3F8841020 +:106C3000D3F88400C3F88420D3F88400D86F40F0E0 +:106C4000FF4040F4FF0040F43F5040F03F00D86761 +:106C5000D86F20F0FF4020F4FF0020F43F5020F0D8 +:106C60003F00D867D86FD3F888006FEA40506FEACA +:106C70005050C3F88800D3F88800C0F30A00C3F866 +:106C80008800D3F88800D3F89000C3F89010D3F8A8 +:106C90009000C3F89020D3F89000D3F89400C3F884 +:106CA0009410D3F89400C3F89420D3F89400D3F848 +:106CB0009800C3F89810D3F89800C3F89820D3F838 +:106CC0009800D3F88C00C3F88C10D3F88C00C3F86C +:106CD0008C20D3F88C00D3F89C00C3F89C10D3F818 +:106CE0009C10C3F89C20D3F89C3000F0D3B900BFAF +:106CF00000440258614B0122C3F80821604BD3F8CD +:106D0000F42042F00202C3F8F420D3F81C2142F030 +:106D10000202C3F81C210222D3F81C31594BDA605D +:106D20005A689104FCD5584A1A6001229A60574A61 +:106D3000DA6000221A614FF440429A61514B9A691D +:106D40009204FCD51A6842F480721A604C4B1A6F98 +:106D500012F4407F04D04FF480321A6700221A6781 +:106D60001A6842F001021A60454B1A685007FCD5B8 +:106D700000221A611A6912F03802FBD10121196050 +:106D80004FF0804159605A67414ADA62414A1A61BC +:106D90001A6842F480321A60394B1A689103FCD5A4 +:106DA0001A6842F480521A601A689204FCD53A4A72 +:106DB0003A499A6200225A6319633949DA6399633E +:106DC0005A64384A1A64384ADA621A6842F0A85299 +:106DD0001A602B4B1A6802F02852B2F1285FF9D1E1 +:106DE00048229A614FF48862DA6140221A622F4A7F +:106DF000DA644FF080521A652D4A5A652D4A9A6519 +:106E000032232D4A1360136803F00F03022BFAD1CB +:106E10001B4B1A6942F003021A611A6902F0380228 +:106E2000182AFAD1D3F8DC2042F00052C3F8DC2053 +:106E3000D3F8042142F00052C3F80421D3F804210E +:106E4000D3F8DC2042F08042C3F8DC20D3F80421E0 +:106E500042F08042C3F80421D3F80421D3F8DC20A7 +:106E600042F00042C3F8DC20D3F8042142F0004293 +:106E7000C3F80421D3F80431704700BF00800051EB +:106E8000004402580048025800C000F0020000010F +:106E90000000FF01008890083220600063020901B1 +:106EA0001D02040047040508FD0BFF01200000201F +:106EB0000010E00000010100002000524FF0B0423D +:106EC00008B5D2F8883003F00103C2F8883023B146 +:106ED000044A13680BB150689847BDE80840FDF7B5 +:106EE000E7B800BF988100204FF0B04208B5D2F853 +:106EF000883003F00203C2F8883023B1044A936853 +:106F00000BB1D0689847BDE80840FDF7D1B800BF85 +:106F1000988100204FF0B04208B5D2F8883003F0D5 +:106F20000403C2F8883023B1044A13690BB15069D5 +:106F30009847BDE80840FDF7BBB800BF9881002026 +:106F40004FF0B04208B5D2F8883003F00803C2F819 +:106F5000883023B1044A93690BB1D0699847BDE8E2 +:106F60000840FDF7A5B800BF988100204FF0B0425F +:106F700008B5D2F8883003F01003C2F8883023B186 +:106F8000044A136A0BB1506A9847BDE80840FDF700 +:106F90008FB800BF988100204FF0B04310B5D3F8F0 +:106FA000884004F47872C3F88820A30604D5124AF6 +:106FB000936A0BB1D06A9847600604D50E4A136BEA +:106FC0000BB1506B9847210604D50B4A936B0BB15C +:106FD000D06B9847E20504D5074A136C0BB1506C8F +:106FE0009847A30504D5044A936C0BB1D06C98471D +:106FF000BDE81040FDF75CB8988100204FF0B04329 +:1070000010B5D3F8884004F47C42C3F888206205A8 +:1070100004D5164A136D0BB1506D9847230504D55E +:10702000124A936D0BB1D06D9847E00404D50F4A16 +:10703000136E0BB1506E9847A10404D50B4A936EA2 +:107040000BB1D06E9847620404D5084A136F0BB198 +:10705000506F9847230404D5044A936F0BB1D06F47 +:107060009847BDE81040FDF723B800BF9881002085 +:1070700008B50348FDF7D2F8BDE80840FDF718B899 +:10708000D45E002008B5FFF7ABFDBDE80840FDF772 +:107090000FB80000062108B50846FDF743F90621A0 +:1070A0000720FDF73FF906210820FDF73BF90621EF +:1070B0000920FDF737F906210A20FDF733F90621EB +:1070C0001720FDF72FF906212820FDF72BF90921BC +:1070D0007A20FDF727F907213220FDF723F90C214B +:1070E0005220BDE80840FDF71DB9000008B5FFF7C4 +:1070F0008DFD00F00DF8FDF7B9FAFDF791FCFDF7F5 +:1071000063FBFFF741FDBDE80840FFF76FBC0000DF +:107110000023054A19460133102BC2E9001102F180 +:107120000802F8D1704700BF988100200B46014645 +:10713000184600F003B8000000F00EB810B5054C7A +:1071400013462CB10A4601460220AFF3008010BD61 +:107150002046FCE700000000024B0146186800F0E2 +:1071600035B800BF6422002010B5013902449042B6 +:1071700001D1002005E0037811F8014FA34201D0AE +:10718000181B10BD0130F2E72DE9F041A3B1C91A77 +:1071900017780144044603F1FF3C8C42204601D994 +:1071A000002009E00578BD4204F10104F5D10CEBA3 +:1071B0000405D618A54201D1BDE8F08115F8018D6E +:1071C00016F801EDF045F5D0E7E7000037B50029E6 +:1071D00044D051F8043C0190002BA1F10404B8BF45 +:1071E000E41800F047F81E4A0198136833B9636049 +:1071F000146003B0BDE8304000F042B8A34208D9A3 +:10720000256861198B4201BF19685B6849192160C3 +:10721000EDE71A465B680BB1A342FAD9116855181D +:10722000A5420BD1246821445418A3421160E0D137 +:107230001C685B68536021441160DAE702D90C23B3 +:107240000360D6E7256861198B4204BF19685B6843 +:10725000636004BF491921605460CAE703B030BDC0 +:1072600018820020034611F8012B03F8012B002A95 +:10727000F9D17047014800F009B800BF1C82002016 +:10728000014800F005B800BF1C82002070470000D4 +:10729000704700006F72672E6172647570696C6F61 +:1072A000742E437562654F72616E67652D706572ED +:1072B000697068004E6F20617070207369670A0002 +:1072C000426164206677206C656E6774682025755E +:1072D0000A0042616420626F6172645F6964202504 +:1072E000752073686F756C642062652025750A00CF +:1072F0004261642066772064657363726970746F9D +:1073000072206C656E6774682025750A004261649E +:107310002061707020435243203078253038783A0D +:10732000307825303878203078253038783A307801 +:10733000253038780A00476F6F64206669726D7770 +:107340006172650A0040A2E4F164689106000000E1 +:1073500053544D333248373F3F3F0053544D33323F +:10736000483734332F37353300000000F8640020ED +:10737000D45E002043414E464449666163653A202D +:107380004D6573736167652052414D204F7665727C +:10739000666C6F77210000004261642043414E49D2 +:1073A0006661636520696E6465782E0000010000E7 +:1073B0000001FF0000A0004000A400400000000009 +:1073C00000000000C1250008991E0008012D0008DA +:1073D0008D1E0008091F00081923000881200008DD +:1073E000D11E0008D51E0008911E0008AD1E000821 +:1073F000951E0008D9220008B91E00080D2E0008AD +:10740000C51E0008AD220008009600000000000024 +:10741000000000000000000000000000000000006C +:107420000000000035460008214600085D460008BF +:107430004946000855460008414600082D46000808 +:10744000194600086946000800000000454700088A +:10745000314700086D470008594700086547000894 +:10746000514700083D4700082947000879470008B0 +:107470000000000001000000000000006D61696E66 +:107480000000000069646C6500000000847400085E +:1074900080630020F864002001000000BD50000857 +:1074A000000000004172647550696C6F74002542E1 +:1074B0004F415244252D424C002553455249414CE1 +:1074C00025000000020000000000000065490008DF +:1074D000D549000840004000A07D0020B07D00207C +:1074E0000200000000000000030000000000000097 +:1074F0001D4A00080000000010000000C07D0020B0 +:107500000000000001000000000000004880002092 +:1075100001010200C5540008D55300087154000849 +:1075200055540008430000002C7500080902430070 +:10753000020100C03209040000010202010005241A +:1075400000100105240100010424020205240600A4 +:1075500001070582030800FF09040100020A000078 +:1075600000070501024000000705810240000000FD +:10757000120000007875000812011001020000409E +:10758000091241570002010203010000040309042B +:1075900025424F415244250030313233343536379D +:1075A00038394142434445460000000000000020B5 +:1075B0000000020002000000000100300000000096 +:1075C000000000000000002400000800040000008B +:1075D0000004000000FC0000020000000000043075 +:1075E00000800000000000000000003800000100E2 +:1075F0000100000000000000714B0008294E000847 +:10760000D54E00084000400080810020808100208D +:107610000100000090810020800000004001000077 +:107620000800000000010000000400000800000045 +:107630000000802A00000000AAAAAAAA00000024D4 +:10764000FFFF00000000000000A00A00002100026F +:1076500000000000AAAAAAAA00000000FFFF000084 +:1076600000000009000009001400005400000000A0 +:10767000AAAAAAAA14000054FFFF000000000000FC +:10768000000000000A40100000000000AAAA8AAA18 +:1076900000401000FFFF0000990000000000000003 +:1076A0000081020000000000AAAAAAAA004101006D +:1076B000FFFF000000000070070000000000000055 +:1076C00000000000AAAAAAAA00000000FFFF000014 +:1076D00000000000000000000000000000000000AA +:1076E000AAAAAAAA00000000FFFF000000000000F4 +:1076F000000000000000000000000000AAAAAAAAE2 +:1077000000000000FFFF000000000000000000007B +:107710000000000000000000AAAAAAAA00000000C1 +:10772000FFFF00000000000000000000000000005B +:1077300000000000AAAAAAAA00000000FFFF0000A3 +:107740000000000000000000000000000000000039 +:10775000AAAAAAAA00000000FFFF00000000000083 +:10776000000000007C8BFF7F010000000000000093 +:10777000780500000000000000001E00000000006E +:10778000FE2A0100D2040000FF00000000000000FB +:10779000507300083F000000500400005B730008B5 +:1077A0003F00000000960000000008009600000066 +:1077B00000080000040000008C75000800000000B4 +:1077C00000000000000000000000000000000000B9 +:1077D00000000000682200200000000000000000FF +:1077E0000000000000000000000000000000000099 +:1077F0000000000000000000000000000000000089 +:107800000000000000000000000000000000000078 +:107810000000000000000000000000000000000068 +:107820000000000000000000000000000000000058 +:08783000000000000000000050 +:00000001FF diff --git a/Tools/bootloaders/CubeOrangePlus-bdshot_bl.bin b/Tools/bootloaders/CubeOrangePlus-bdshot_bl.bin new file mode 100755 index 00000000000..4ec5e201871 Binary files /dev/null and b/Tools/bootloaders/CubeOrangePlus-bdshot_bl.bin differ diff --git a/Tools/bootloaders/CubeOrangePlus-bdshot_bl.hex b/Tools/bootloaders/CubeOrangePlus-bdshot_bl.hex new file mode 100644 index 00000000000..53219c70343 --- /dev/null +++ b/Tools/bootloaders/CubeOrangePlus-bdshot_bl.hex @@ -0,0 +1,1118 @@ +:020000040800F2 +:1000000000060020A102000865100008E50F0008A6 +:100010003D100008E50F000811100008A3020008B9 +:10002000A3020008A3020008A30200089D2A0008FA +:10003000A3020008A3020008A3020008A30200080C +:10004000A3020008A3020008A3020008A3020008FC +:10005000A3020008A3020008253F0008513F000842 +:100060007D3F0008A93F0008D53F0008A302000813 +:10007000A3020008A3020008A3020008A3020008CC +:10008000A3020008A3020008A3020008A3020008BC +:10009000A3020008A3020008A30200080140000810 +:1000A000A3020008A3020008A3020008A30200089C +:1000B000A3020008A3020008A3020008A30200088C +:1000C000A3020008A3020008A3020008A30200087C +:1000D000A3020008A3020008D9400008ED40000870 +:1000E00065400008A3020008A3020008A30200085C +:1000F000A3020008A3020008A3020008A30200084C +:10010000A3020008A302000815410008A30200088A +:10011000A3020008A3020008A3020008A30200082B +:10012000A3020008A3020008A3020008A30200081B +:10013000A3020008A3020008A3020008A30200080B +:10014000A3020008A3020008A3020008A3020008FB +:10015000A3020008A3020008A3020008A3020008EB +:10016000A3020008A3020008A3020008A3020008DB +:10017000A302000809360008A3020008A302000831 +:10018000A3020008A302000801410008A30200081E +:10019000A3020008A3020008A3020008A3020008AB +:1001A000A3020008A3020008A3020008A30200089B +:1001B000A3020008A3020008A3020008A30200088B +:1001C000A3020008A3020008A3020008A30200087B +:1001D000A3020008F5350008A3020008A3020008E6 +:1001E000A3020008A3020008A3020008A30200085B +:1001F000A3020008A3020008A3020008A30200084B +:10020000A3020008A3020008A3020008A30200083A +:10021000A3020008A3020008A3020008A30200082A +:10022000A3020008A3020008A3020008A30200081A +:10023000A3020008A3020008A3020008A30200080A +:10024000A3020008A3020008A3020008A3020008FA +:10025000A3020008A3020008A3020008A3020008EA +:10026000A3020008A3020008A3020008A3020008DA +:10027000A3020008A3020008A3020008A3020008CA +:10028000A3020008A3020008A3020008A3020008BA +:10029000A3020008A3020008A3020008A3020008AA +:1002A00002E000F000F8FEE73B48804772B63B48AA +:1002B00080F308883A4880F309883A484EF6085196 +:1002C000CEF20001086040F20000CCF200004EF6D1 +:1002D0003471CEF200010860BFF34F8FBFF36F8F10 +:1002E00040F20000C0F2F0004EF68851CEF200015C +:1002F0000860BFF34F8FBFF36F8F4FF00000E1EE48 +:10030000100A4EF63C71CEF200010860062080F320 +:100310001488BFF36F8F02F07FFC02F021FC03F022 +:10032000BBFB4FF0553020491C4A91423CBF41F87D +:10033000040BFAE71D491A4A91423CBF41F8040BED +:10034000FAE71B491B4A1C4B9A423EBF51F8040B6B +:1003500042F8040BF8E700201849194A91423CBFC3 +:1003600041F8040BFAE702F039FC03F019FC154CD4 +:10037000154DAC4203DA54F8041B8847F9E700F046 +:1003800043F8124C124DAC4203DA54F8041B884770 +:10039000F9E702F021BC0000691000080006002007 +:1003A00000220020000000080000002000060020BD +:1003B00058450008002200205C2200206022002016 +:1003C000D44F0020A0020008A0020008A0020008EC +:1003D000A00200082DE9F04F2DED108AC1F80CD0D5 +:1003E000D0F80CD0BDEC108ABDE8F08F002383F369 +:1003F00011882846A047002001F028FFFEE701F001 +:10040000A3FE00DFFEE7000038B502F023FB30B1A9 +:10041000164B00220E211A725A729972DA7202F089 +:10042000EFFA054602F024FB0446D0B9104B9D427A +:1004300019D001339D4241F2883512BF0446002590 +:100440000124002002F0E6FA0CB100F079F800F087 +:1004500069FD00F013FC284600F020F900F070F868 +:10046000F9E70025EDE70546EBE700BF0022002095 +:10047000010007B008B500F0CDFBA0F12003584201 +:10048000584108BD07B541F21203022101A8ADF899 +:10049000043000F0DDFB03B05DF804FB38B5202329 +:1004A00083F311881748C3680BB101F055FF00238F +:1004B000154A4FF47A71134801F012FF002383F3B9 +:1004C0001188124C236813B12368013B23606368D1 +:1004D00013B16368013B63600D4D2B7833B96368DA +:1004E0007BB9022000F098FC322363602B78032B49 +:1004F00007D163682BB9022000F08EFC4FF47A73A9 +:10050000636038BD602200209D0400087C23002029 +:1005100074220020084B187003280CD8DFE800F084 +:1005200008050208022000F06DBC022000F060BC4B +:10053000024B00225A607047742200207C23002066 +:10054000F8B5504B504A1C461968013100F09980AB +:1005500004339342F8D162684C4B9A4240F2918046 +:100560004B4B9B6803F1006303F500339A4280F024 +:100570008880002000F09CFB0220FFF7CBFF454B5A +:100580000021D3F8E820C3F8E810D3F81021C3F80D +:100590001011D3F81021D3F8EC20C3F8EC10D3F8E5 +:1005A0001421C3F81411D3F81421D3F8F020C3F8A0 +:1005B000F010D3F81821C3F81811D3F81821D3F884 +:1005C000802042F00062C3F88020D3F8802022F01F +:1005D0000062C3F88020D3F88020D3F8802042F056 +:1005E0000072C3F88020D3F8802022F00072C3F894 +:1005F0008020D3F8803072B64FF0E023C3F8084D66 +:10060000D4E90004BFF34F8FBFF36F8F224AC2F8C3 +:100610008410BFF34F8F536923F480335361BFF3CA +:100620004F8FD2F8803043F6E076C3F3C905C3F3A9 +:100630004E335B0103EA060C29464CEA8177013907 +:10064000C2F87472F9D2203B13F1200FF2D1BFF33C +:100650004F8FBFF36F8FBFF34F8FBFF36F8F536910 +:1006600023F4003353610023C2F85032BFF34F8F9D +:10067000BFF36F8F202383F31188854680F30888AA +:100680002047F8BD0000020820000208FFFF010813 +:10069000002200200044025800ED00E02DE9F04F58 +:1006A00093B0A84B2022FF2100900AA89D6800F07B +:1006B000E3FBA54A1378A3B90121A4481170C360D4 +:1006C000202383F31188C3680BB101F045FE00239A +:1006D0009F4A4FF47A719D4801F002FE002383F394 +:1006E0001188009B13B19B4B009A1A609A4A1378A9 +:1006F000032B03D000231370964A53604FF0000A77 +:10070000009CD3465646D146012000F07BFB24B125 +:10071000904B1B68002B00F00E82002000F07AFA4C +:100720000390039B002BF2DB012000F061FB039B95 +:10073000213B162BE8D801A252F823F099070008B4 +:10074000C107000855080008090700080907000844 +:1007500009070008DD080008AB0A0008C509000801 +:10076000270A00084F0A0008750A00080907000850 +:10077000870A000809070008F90A00083908000874 +:10078000090700083D0B0008A50700083908000804 +:1007900009070008270A00080220FFF76BFE00285F +:1007A00040F0F381009B022105A8BAF1000F08BFB9 +:1007B0001C4641F21233ADF8143000F049FAA3E7B9 +:1007C0004FF47A7000F026FA071EEBDB0220FFF7E9 +:1007D00051FE0028E6D0013F052F00F2D881DFE866 +:1007E00007F0030A0D1013360523042105A805930D +:1007F00000F02EFA17E004215248F9E70421574887 +:10080000F6E704215648F3E74FF01C08404608F18C +:10081000040800F04FFA0421059005A800F018FA2A +:10082000B8F12C0FF2D101204FF0000900FA07F7C0 +:1008300047EA0B0B5FFA8BFB00F06AFB26B10BF06B +:100840000B030B2B08BF0024FFF71CFE5CE7042101 +:100850004448CDE7002EA5D00BF00B030B2BA1D104 +:100860000220FFF707FE074600289BD00120002644 +:1008700000F01EFA0220FFF74DFE5FFA86F84046B0 +:1008800000F026FA044688B14046013600F030FAFE +:100890000028F2D1BA46044641F21213022105A8FB +:1008A0003E46ADF8143000F0D3F92DE7254601207F +:1008B000FFF730FE234B9B68AB4207D9284600F078 +:1008C000F9F9013040F066810435F3E70025224B49 +:1008D000BA463E461D701F4B5D60ADE7002E3FF4EB +:1008E00061AF0BF00B030B2B7FF45CAF0220FFF723 +:1008F00011FE322000F08EF9B0F10008FFF652AF81 +:1009000018F003077FF44EAF0E4A08EB0503926818 +:1009100093423FF647AFB8F5807F3FF743AF124BA6 +:10092000B845019322DD4FF47A7000F073F903901B +:10093000039A002AFFF636AF039A0137019B03F8AA +:10094000012BEDE700220020782300206022002008 +:100950009D0400087C230020742200200422002033 +:10096000082200200C22002078220020C820FFF757 +:1009700081FD074600283FF415AF1F2D11D8C5F1A2 +:1009800020020AAB25F0030084494245184428BFE1 +:100990004246019200F04AFA019AFF217F4800F096 +:1009A0006BFA4FEAA803C8F387027C4928460193F3 +:1009B00000F06AFA064600283FF46EAF019B05EB93 +:1009C000830539E70220FFF755FD00283FF4EAAE22 +:1009D00000F0AAF900283FF4E5AE0027B846704BB6 +:1009E0009B68BB4218D91F2F11D80A9B01330ED028 +:1009F00027F0030312AA134453F8203C0593404602 +:100A0000042205A9043700F04DFB8046E7E738468D +:100A100000F050F90590F2E7CDF81480042105A804 +:100A200000F016F908E70023642104A8049300F0FD +:100A300005F900287FF4B6AE0220FFF71BFD002861 +:100A40003FF4B0AE049800F065F90590E6E70023A6 +:100A5000642104A8049300F0F1F800287FF4A2AE0A +:100A60000220FFF707FD00283FF49CAE049800F039 +:100A700053F9EAE70220FFF7FDFC00283FF492AEAD +:100A800000F062F9E1E70220FFF7F4FC00283FF4F0 +:100A900089AE05A9142000F05DF9074604210490F1 +:100AA00004A800F0D5F83946B9E7322000F0B2F8D2 +:100AB000071EFFF677AEBB077FF474AE384A07EB2C +:100AC0000903926893423FF66DAE0220FFF7D2FC15 +:100AD00000283FF467AE27F003074F44B9453FF4C1 +:100AE000ABAE484609F1040900F0E4F80421059092 +:100AF00005A800F0ADF8F1E74FF47A70FFF7BAFC03 +:100B000000283FF44FAE00F00FF9002844D00A9BB4 +:100B100001330BD008220AA9002000F0B5F9002803 +:100B20003AD02022FF210AA800F0A6F9FFF7AAFC7C +:100B30001C4801F091FB13B0BDE8F08F002E3FF48C +:100B400031AE0BF00B030B2B7FF42CAE0023642192 +:100B500005A8059300F072F8074600287FF422AE3E +:100B60000220FFF787FC804600283FF41BAEFFF70A +:100B700089FC41F2883001F06FFB059800F012FA11 +:100B800046463C4600F0C4F9BEE5064654E64FF042 +:100B9000000907E6BA467FE637467DE67822002060 +:100BA00000220020A08601002DE9F84F4FF47A734F +:100BB00006460D46002402FB03F7DFF85080DFF8FD +:100BC000509098F900305FFA84FA5A1C01D0A34281 +:100BD00010D159F824002A4631460368D3F820B0D2 +:100BE0003B46D847854205D1074B012083F800A03A +:100BF000BDE8F88F0134042CE3D14FF4FA7001F012 +:100C00002BFB0020F4E700BFC823002010220020A7 +:100C100018420008002307B5024601210DF1070024 +:100C20008DF80730FFF7C0FF20B19DF8070003B033 +:100C30005DF804FB4FF0FF30F9E700000A4604219D +:100C400008B5FFF7B1FF80F00100C0B2404208BD17 +:100C5000074B0A4630B41978064B53F82140014639 +:100C600023682046DD69044BAC4630BC604700BFBA +:100C7000C823002018420008A086010070B50A4E63 +:100C800000240A4D01F094FD3080286833888342A7 +:100C900008D901F089FD2B6804440133B4F5003F05 +:100CA0002B60F2D370BD00BFCA2300208423002034 +:100CB00001F05CBE00F1006000F500300068704794 +:100CC00000F10060920000F5003001F0D3BD00009B +:100CD000054B1A68054B1B889B1A834202D91044A6 +:100CE00001F062BD0020704784230020CA23002049 +:100CF00038B5074D04462868204401F05BFD28B94B +:100D000028682044BDE8384001F066BD38BD00BF0A +:100D1000842300200020704700F1FF5000F58F1061 +:100D2000D0F8000870470000064991F8243033B12C +:100D300000230822086A81F82430FFF7C1BF012090 +:100D4000704700BF88230020014B1868704700BF20 +:100D50000010005C244BF0B51A680446234BC2F324 +:100D60000B06120C1F885868BE4293F9085028D011 +:100D70009F89BE4206D101200C2505FB003358682F +:100D800093F9085041F201039A421CD041F2030347 +:100D90009A421AD042F201039A4218D042F2030357 +:100DA0009A4208BF5625621E0B46441E0A449342CF +:100DB0000FD214F9016F581C6EB1034600F8016C94 +:100DC000F5E70020D8E75A25EDE75925EBE7582548 +:100DD000E9E7184605E02C2482421C7001D9981CD2 +:100DE0005D70401AF0BD00BF0010005C14220020AE +:100DF000022803D1024B4FF080529A61704700BF26 +:100E000000100258022803D1024B4FF480529A611D +:100E1000704700BF00100258022804D1024A5369EB +:100E200083F480535361704700100258002310B5BB +:100E3000934203D0CC5CC4540133F9E710BD0000E9 +:100E4000013810B510F9013F3BB191F900409C42C7 +:100E500003D11AB10131013AF4E71AB191F9002036 +:100E6000981A10BD1046FCE703460246D01A12F944 +:100E7000011B0029FAD1704702440346934202D075 +:100E800003F8011BFAE770472DE9F8431F4D14469C +:100E90000746884695F8242052BBDFF870909CB333 +:100EA00095F824302BB92022FF2148462F62FFF706 +:100EB000E3FF95F824004146C0F1080205EB8000ED +:100EC000A24228BF2246D6B29200FFF7AFFF95F8A4 +:100ED0002430A41B17441E449044E4B2F6B2082EFA +:100EE00085F82460DBD1FFF71FFF0028D7D108E089 +:100EF0002B6A03EB82038342CFD0FFF715FF002854 +:100F0000CBD10020BDE8F8830120FBE78823002037 +:100F1000024B1A78024B1A70704700BFC82300209A +:100F200010220020F8B5194C194800F097FC214612 +:100F3000174800F0BFFC24681648D4F89020164EDD +:100F4000D2F80438154D43F00203114FC2F80438AB +:100F500001F082F92046124900F0BAFDD4F8902041 +:100F60000424D2F8043823F00203C2F804384FF402 +:100F7000E133336055F8040BB84202D0314600F03B +:100F8000CBFB013C14F0FF04F4D1F8BD3043000862 +:100F9000C832002040420F00B02300201842000851 +:100FA0003843000838B50B4B04461A780A4B53F8FF +:100FB00022500A4B9D420CD0094B002118221846A2 +:100FC000FFF75AFF046001462846BDE8384000F0AC +:100FD000A3BB38BDC823002018420008C832002037 +:100FE000B023002000B59BB0EFF30981682268466A +:100FF000FFF71CFFEFF30583044B9A6BDA6A9A6ADA +:101000009A6A9A6A9A6A9A6A9B6AFEE700ED00E019 +:1010100000B59BB0EFF3098168226846FFF706FF31 +:10102000EFF30583044B9A6B9A6A9A6A9A6A9A6AF2 +:101030009A6A9B6AFEE700BF00ED00E000B59BB036 +:10104000EFF3098168226846FFF7F0FEEFF30583AE +:10105000034B5A6B9A6A9A6A9A6A9A6A9B6AFEE783 +:1010600000ED00E0FEE7000000B595B0132101A8F7 +:1010700001F00EFD9DF84F307BB10023132101A834 +:101080008DF84F3001F0FEFC054BD3F8002882F3B9 +:101090000888D3F804389847FEE715B05DF804FBDC +:1010A0000090F01F30B50A44084D91420DD011F860 +:1010B000013B5840082340F30004013B2C4013F04F +:1010C000FF0384EA5000F6D1EFE730BD2083B8ED8E +:1010D000026843681143016003B11847704700007C +:1010E000024A136843F0C003136070470044004095 +:1010F000024A136843F0C003136070470048004081 +:10110000024A136843F0C003136070470078004040 +:1011100037B5274C274D204600F0F2FA04F11400B1 +:10112000009400234FF40072234900F0B3F94FF408 +:101130000072224904F138000094214B00F02CFA8F +:10114000204BC4E91735204C204600F0D9FA04F1B1 +:101150001400009400234FF400721C4900F09AF927 +:101160004FF400721A4904F138000094194B00F052 +:1011700013FA194BC4E91735184C204600F0C0FA91 +:1011800004F1140000234FF400721549009400F09C +:1011900081F9144B4FF40072134904F138000094A4 +:1011A00000F0FAF9114BC4E9173503B030BD00BFA8 +:1011B000CC23002000E1F50510250020102B002095 +:1011C000E1100008004400403824002010270020CF +:1011D000102D0020F110000800480040A424002039 +:1011E0001029002001110008102F00200078004075 +:1011F000037C30B5334C002918BF0C46012B18D1A5 +:10120000314B98420FD1314BD3F8E82042F40032F1 +:10121000C3F8E820D3F8102142F40032C3F81021BB +:10122000D3F8103105E02A4B98422FD0294B984231 +:1012300038D02268036EC16D03EB52038466B3FBA2 +:10124000F2F36268150442BF23F0070503F00703B9 +:1012500043EA4503CB60A36843F040034B60E36877 +:1012600043F001038B6042F4967343F001030B607B +:101270004FF0FF330B62510505D512F010221DD03F +:10128000B2F1805F1CD080F8643030BD0F4BD3F8D2 +:10129000E82042F48022C3F8E820D3F8102142F479 +:1012A0008022BBE7094BD3F8E82042F08042C3F824 +:1012B000E820D3F8102142F08042AFE77F23E2E735 +:1012C0003F23E0E728420008CC23002000440258D6 +:1012D00038240020A42400202DE9F047C66D0546DF +:1012E0003768F4692107346219D014F0080118BF77 +:1012F0008021E20748BF41F02001A3074FF02003FF +:1013000048BF41F04001600748BF41F4807183F35A +:101310001188281DFFF7DCFE002383F31188E20506 +:101320000AD5202383F311884FF40071281DFFF79D +:10133000CFFE002383F311884FF020094FF0000AFD +:1013400014F0200838D13B0616D54FF0200905F1DE +:10135000380A200610D589F31188504600F050F95C +:10136000002836DA0821281DFFF7B2FE27F0800397 +:101370003360002383F31188790614D5620612D5F1 +:10138000202383F31188D5E913239A4208D12B6CCB +:1013900033B127F040071021281DFFF799FE376071 +:1013A000002383F31188E30618D5AA6E1369ABB145 +:1013B0005069BDE8F047184789F31188736A2846D9 +:1013C00095F86410194000F0B5F98AF31188F469B2 +:1013D000B6E7B06288F31188F469BAE7BDE8F08730 +:1013E000F8B51546826804460B46AA4200D28568C5 +:1013F000A1692669761AB5420BD218462A46FFF72C +:1014000015FDA3692B44A3612846A3685B1BA36059 +:10141000F8BD0CD9AF1B18463246FFF707FD3A4618 +:10142000E1683044FFF702FDE3683B44EBE7184610 +:101430002A46FFF7FBFCE368E5E700008368934278 +:10144000F7B50446154600D28568D4E90460361A1B +:10145000B5420BD22A46FFF7E9FC63692B4463616E +:101460002846A3685B1BA36003B0F0BD0DD93246CC +:10147000AF1B0191FFF7DAFC01993A46E06831446D +:10148000FFF7D4FCE3683B44E9E72A46FFF7CEFCCC +:10149000E368E4E710B50A440024C361029B84605A +:1014A000C16002610362C0E90000C0E9051110BD1E +:1014B00008B5D0E90532934201D1826882B98268C9 +:1014C000013282605A1C426119700021D0E9043255 +:1014D0009A4224BFC368436100F0DAFE002008BDD1 +:1014E0004FF0FF30FBE7000070B5202304460E46A6 +:1014F00083F31188A568A5B1A368A269013BA36025 +:10150000531CA36115782269934224BFE368A36149 +:10151000E3690BB120469847002383F311882846DE +:1015200007E03146204600F0A3FE0028E2DA85F30A +:10153000118870BD2DE9F74F04460E4617469846B0 +:10154000D0F81C904FF0200A8AF311884FF0000B5E +:10155000154665B12A4631462046FFF741FF03464E +:1015600060B94146204600F083FE0028F1D00023F8 +:1015700083F31188781B03B0BDE8F08FB9F1000F39 +:1015800003D001902046C847019B8BF31188ED1AC8 +:101590001E448AF31188DCE7C160C361009B82604E +:1015A0000362C0E905111144C0E900000161704700 +:1015B000F8B504460D461646202383F31188A76824 +:1015C000A7B1A368013BA36063695A1C62611D70E7 +:1015D000D4E904329A4224BFE3686361E3690BB142 +:1015E00020469847002080F3118807E031462046C6 +:1015F00000F03EFE0028E2DA87F31188F8BD000013 +:10160000D0E9052310B59A4201D182687AB982687F +:101610000021013282605A1C82611C7803699A425F +:1016200024BFC368836100F033FE204610BD4FF035 +:10163000FF30FBE72DE9F74F04460E461746984664 +:10164000D0F81C904FF0200A8AF311884FF0000B5D +:10165000154665B12A4631462046FFF7EFFE0346A0 +:1016600060B94146204600F003FE0028F1D0002377 +:1016700083F31188781B03B0BDE8F08FB9F1000F38 +:1016800003D001902046C847019B8BF31188ED1AC7 +:101690001E448AF31188DCE7026843681143016045 +:1016A00003B11847704700001430FFF743BF000034 +:1016B0004FF0FF331430FFF73DBF00003830FFF725 +:1016C000B9BF00004FF0FF333830FFF7B3BF000061 +:1016D0001430FFF709BF00004FF0FF311430FFF75F +:1016E00003BF00003830FFF763BF00004FF0FF3248 +:1016F0003830FFF75DBF000000207047FFF708BDDE +:10170000044B036000234360C0E9023301230374E8 +:10171000704700BF4042000810B52023044683F301 +:101720001188FFF765FD02232374002383F31188DA +:1017300010BD000038B5C36904460D461BB904212D +:101740000844FFF7A9FF294604F11400FFF7B0FE93 +:10175000002806DA201D4FF48061BDE83840FFF70D +:101760009BBF38BD026843681143016003B118474D +:101770007047000013B5406B00F58054D4F8A438CE +:101780001A681178042914D1017C022911D1197920 +:10179000012312898B4013420BD101A94C3002F076 +:1017A0007BF8D4F8A4480246019B2179206800F018 +:1017B000DFF902B010BD0000143001F0FDBF0000E1 +:1017C0004FF0FF33143001F0F7BF00004C3002F04F +:1017D000CFB800004FF0FF334C3002F0C9B8000022 +:1017E000143001F0CBBF00004FF0FF31143001F096 +:1017F000C5BF00004C3002F09BB800004FF0FF3234 +:101800004C3002F095B800000020704710B500F58C +:101810008054D4F8A4381A681178042917D1017CAF +:10182000022914D15979012352898B4013420ED1D8 +:10183000143001F05DFF024648B1D4F8A4484FF4DB +:10184000407361792068BDE8104000F07FB910BD99 +:10185000406BFFF7DBBF0000704700007FB5124B05 +:1018600001250426044603600023057400F1840268 +:1018700043602946C0E902330C4B029014300193B7 +:101880004FF44073009601F00FFF094B04F69442A9 +:10189000294604F14C000294CDE900634FF44073F3 +:1018A00001F0D6FF04B070BD68420008511800086E +:1018B000751700080A68202383F311880B790B330E +:1018C00042F823004B79133342F823008B7913B18C +:1018D0000B3342F8230000F58053C3F8A418022309 +:1018E0000374002383F311887047000038B5037F29 +:1018F000044613B190F85430ABB90125201D0221E4 +:10190000FFF730FF04F114006FF00101257700F0BC +:10191000CBFC04F14C0084F854506FF00101BDE899 +:10192000384000F0C1BC38BD10B501210446043078 +:10193000FFF718FF0023237784F8543010BD000010 +:1019400038B504460025143001F0C6FE04F14C0001 +:10195000257701F095FF201D84F854500121FFF7F1 +:1019600001FF2046BDE83840FFF750BF90F88030B7 +:1019700003F06003202B06D190F881200023212A58 +:1019800003D81F2A06D800207047222AFBD1C0E9BD +:101990001D3303E0034A426707228267C3670120C1 +:1019A000704700BF2C22002037B500F58055D5F8D0 +:1019B000A4381A68117804291AD1017C022917D198 +:1019C0001979012312898B40134211D100F14C0483 +:1019D000204602F015F858B101A9204601F05CFF3D +:1019E000D5F8A4480246019B2179206800F0C0F890 +:1019F00003B030BD01F10B03F0B550F8236085B0A2 +:101A000004460D46FEB1202383F3118804EB8507BD +:101A1000301D0821FFF7A6FEFB6806F14C005B694C +:101A20001B681BB1019001F045FF019803A901F06B +:101A300033FF024648B1039B2946204600F098F840 +:101A4000002383F3118805B0F0BDFB685A69126862 +:101A5000002AF5D01B8A013B1340F1D104F180022A +:101A6000EAE70000133138B550F82140ECB12023EB +:101A700083F3118804F58053D3F8A42813685279AE +:101A800003EB8203DB689B695D6845B10421601844 +:101A9000FFF768FE294604F1140001F033FE2046EA +:101AA000FFF7B4FE002383F3118838BD70470000B0 +:101AB00001F026B901234022002110B5044600F8A8 +:101AC000303BFFF7D9F90023C4E9013310BD000012 +:101AD00010B52023044683F311882422416000219D +:101AE0000C30FFF7C9F9204601F02CF902232370CE +:101AF000002383F3118810BD70B500EB8103054608 +:101B000050690E461446DA6018B110220021FFF722 +:101B1000B3F9A06918B110220021FFF7ADF93146E1 +:101B20002846BDE8704001F01FBA000083682022FB +:101B3000002103F0011310B5044683601030FFF755 +:101B40009BF92046BDE8104001F09ABAF0B4012597 +:101B500000EB810447898D40E4683D43A4694581D9 +:101B600023600023A2606360F0BC01F0B7BA0000FC +:101B7000F0B4012500EB810407898D40E4683D4302 +:101B80006469058123600023A2606360F0BC01F0FA +:101B90002DBB000070B502230025044624220370EB +:101BA0002946C0F888500C3040F8045CFFF764F90F +:101BB000204684F8705001F06BF963681B6823B10C +:101BC00029462046BDE87040184770BD037880F86C +:101BD0008C300523037043681B6810B504460BB1B5 +:101BE000042198470023A36010BD000090F88C20CA +:101BF000436802701B680BB105211847704700004D +:101C000070B590F87030044613B1002380F870303E +:101C100004F18002204601F057FA63689B68B3B96B +:101C200094F8803013F0600535D00021204601F093 +:101C300001FD0021204601F0F1FC63681B6813B12F +:101C4000062120469847062384F8703070BD204650 +:101C500098470028E4D0B4F88630A26F9A4288BF33 +:101C6000A36794F98030A56F002B4FF0200380F21A +:101C70000381002D00F0F280092284F8702083F3A4 +:101C8000118800212046D4E91D23FFF771FF0023AE +:101C900083F31188DAE794F8812003F07F0343EAA5 +:101CA000022340F20232934200F0C58021D8B3F5FE +:101CB000807F48D00DD8012B3FD0022B00F09380BD +:101CC000002BB2D104F1880262670222A267E367A7 +:101CD000C1E7B3F5817F00F09B80B3F5407FA4D1CD +:101CE00094F88230012BA0D1B4F8883043F002037D +:101CF00032E0B3F5006F4DD017D8B3F5A06F31D0F7 +:101D0000A3F5C063012B90D86368204694F8822025 +:101D10005E6894F88310B4F88430B047002884D00B +:101D2000436863670368A3671AE0B3F5106F36D0A2 +:101D300040F6024293427FF478AF5C4B6367022324 +:101D4000A3670023C3E794F88230012B7FF46DAFC3 +:101D5000B4F8883023F00203A4F88830C4E91D5594 +:101D6000E56778E7B4F88030B3F5A06F0ED194F84A +:101D70008230204684F88A3001F0E8F863681B68F6 +:101D800013B1012120469847032323700023C4E99F +:101D90001D339CE704F18B0363670123C3E72378BA +:101DA000042B10D1202383F311882046FFF7BEFEB9 +:101DB00085F311880321636884F88B5021701B68B8 +:101DC0000BB12046984794F88230002BDED084F87F +:101DD0008B300423237063681B68002BD6D002214C +:101DE00020469847D2E794F8843020461D0603F039 +:101DF0000F010AD501F05AF9012804D002287FF416 +:101E000014AF2B4B9AE72B4B98E701F041F9F3E71E +:101E100094F88230002B7FF408AF94F8843013F0EC +:101E20000F01B3D01A06204602D501F01BFCADE726 +:101E300001F00CFCAAE794F88230002B7FF4F5AE99 +:101E400094F8843013F00F01A0D01B06204602D571 +:101E500001F0F0FB9AE701F0E1FB97E7142284F828 +:101E6000702083F311882B462A4629462046FFF727 +:101E70006DFE85F31188E9E65DB1152284F87020C6 +:101E800083F3118800212046D4E91D23FFF75EFE6D +:101E9000FDE60B2284F8702083F311882B462A4636 +:101EA00029462046FFF764FEE3E700BF984200089A +:101EB000904200089442000838B590F8703004460B +:101EC000002B3ED0063BDAB20F2A34D80F2B32D883 +:101ED000DFE803F03731310822323131313131312D +:101EE00031313737856FB0F886309D4214D2C368E0 +:101EF0001B8AB5FBF3F203FB12556DB9202383F364 +:101F000011882B462A462946FFF732FE85F31188B1 +:101F10000A2384F870300EE0142384F870302023F4 +:101F200083F31188002320461A461946FFF70EFE58 +:101F3000002383F3118838BDC36F03B19847002392 +:101F4000E7E70021204601F075FB0021204601F063 +:101F500065FB63681B6813B106212046984706237A +:101F6000D7E7000010B590F870300446142B29D044 +:101F700017D8062B05D001D81BB110BD093B022B89 +:101F8000FBD80021204601F055FB0021204601F03E +:101F900045FB63681B6813B106212046984706235A +:101FA00019E0152BE9D10B2380F87030202383F33F +:101FB000118800231A461946FFF7DAFD002383F340 +:101FC0001188DAE7C3689B695B68002BD5D1C36FC2 +:101FD00003B19847002384F87030CEE7024B00220B +:101FE000C3E900339A6070471031002000238268F3 +:101FF0000374054B1B6899689142FBD25A680360D1 +:1020000042601060586070471031002008B52023EE +:1020100083F31188037C032B05D0042B0DD02BB93F +:1020200083F3118808BD436900221A604FF0FF3323 +:102030004361FFF7DBFF0023F2E7D0E900321360D2 +:102040005A60F3E7002382680374054B1B689968A4 +:102050009142FBD85A680360426010605860704734 +:1020600010310020054B1969087418680268536024 +:102070001A60186101230374FEF7ACB91031002017 +:102080004B1C30B5044687B00A4D10D02B6901A80F +:10209000094A00F025F92046FFF7E4FF049B13B13D +:1020A00001A800F059F92B69586907B030BDFFF756 +:1020B000D9FFF8E7103100200D20000838B50C4D8D +:1020C000044641612B6981689A68914203D8BDE852 +:1020D0003840FFF78BBF1846FFF7B4FF01232C6190 +:1020E000014623742046BDE83840FEF773B900BFAF +:1020F00010310020044B1A681B6990689B68984255 +:1021000094BF0020012070471031002010B5084C0A +:10211000236820691A6854602260012223611A74BE +:10212000FFF790FF01462069BDE81040FEF752B965 +:102130001031002008B5FFF7DDFF18B1BDE80840F9 +:10214000FFF7E4BF08BD0000FFF7E0BFFEE70000B7 +:1021500010B50C4CFFF742FF00F0B4F880220A499A +:10216000204600F03BF8012344F8180C037400F0FB +:10217000A5FC002383F3118862B60448BDE8104033 +:1021800000F04CB8383100209C420008AC420008F6 +:1021900000F01CB9EFF3118020B9EFF30583202282 +:1021A00082F311887047000010B530B9EFF3058451 +:1021B000C4F3080414B180F3118810BDFFF7BAFF0F +:1021C00084F31188F9E70000034A516853685B1AE9 +:1021D0009842FBD8704700BF001000E082600222E6 +:1021E000028270478368A3F17C0243F80C2C0269D9 +:1021F00043F83C2C426943F8382C074A43F81C2C1E +:10220000C268A3F1180043F8102C022203F8082C2E +:10221000002203F8072C7047ED03000810B52023B7 +:1022200083F31188FFF7DEFF00210446FFF746FF26 +:10223000002383F31188204610BD0000024B1B6968 +:1022400058610F20FFF70EBF10310020202383F3C9 +:102250001188FFF7F3BF000008B50146202383F380 +:1022600011880820FFF70CFF002383F3118808BDB5 +:1022700049B1064B42681B6918605A60136043609D +:102280000420FFF7FDBE4FF0FF30704710310020F3 +:102290000368984206D01A68026050601846596177 +:1022A000FFF7A4BE7047000038B504460D4620680D +:1022B000844200D138BD036823605C604561FFF74C +:1022C00095FEF4E7054B4FF0FF3103F11402C3E92B +:1022D00005220022C3E90712704700BF1031002019 +:1022E00070B51C4E05460C46C0E9032301F0BEFB49 +:1022F000334653F8142F9A420DD130620A2C2CBF6A +:1023000000190A302A60C5E90124C6E90555BDE86F +:10231000704001F095BB316A431AE31838BF1C4680 +:102320009368A34202D9081901F09AFB73699A686D +:1023300094420CD85A68AC602B606A6015609A6849 +:102340005D60121B9A604FF0FF33F36170BDA41AF9 +:102350001B68ECE71031002038B51B4C63699842CC +:102360000DD08168D0E9003213605A600022C2604B +:102370009A680A449A604FF0FF33E36138BD0368FE +:102380002246002142F8143F93425A60C16003D1B3 +:10239000BDE8384001F05EBB9A688168256A0A444E +:1023A0009A6001F063FB6369411B9A688A42E5D930 +:1023B000AB181D1A206A092D98BF01F10A02BDE869 +:1023C0003840104401F04CBB103100202DE9F041A1 +:1023D000184C002704F11406656901F047FB236AD5 +:1023E000AA68C11A8A4215D81344D5F80C80236212 +:1023F000D5E9003213605A606369EF60B34201D1DE +:1024000001F028FB87F311882869C047202383F354 +:102410001188E1E76169B14209D013441B1ABDE894 +:10242000F0410A2B2CBFC0180A3001F019BBBDE8DF +:10243000F08100BF1031002000207047FEE700004F +:10244000704700004FF0FF307047000002290CD0A9 +:10245000032904D00129074818BF00207047032A28 +:1024600005D8054800EBC2007047044870470020BB +:10247000704700BF944300083C22002048430008F6 +:1024800070B59AB005460846144601A900F0C2F896 +:1024900001A8FEF7E9FC431C0022C6B25B0010460F +:1024A000C5E9003423700323023404F8013C01AB76 +:1024B000D1B202348E4201D81AB070BD13F8011B9C +:1024C000013204F8010C04F8021CF1E708B52023DE +:1024D00083F311880348FFF767FA002383F3118819 +:1024E00008BD00BFC832002090F8803003F01F0202 +:1024F000012A07D190F881200B2A03D10023C0E9DB +:102500001D3315E003F06003202B08D1B0F88430B0 +:102510002BB990F88120212A03D81F2A04D8FFF76D +:1025200025BA222AEBD0FAE7034A426707228267DC +:10253000C3670120704700BF3322002007B505297B +:1025400017D8DFE801F0191603191920202383F3A7 +:102550001188104A01210190FFF7CEFA019802215B +:102560000D4AFFF7C9FA0D48FFF7EAF9002383F394 +:10257000118803B05DF804FB202383F3118807481A +:10258000FFF7B4F9F2E7202383F311880348FFF73C +:10259000CBF9EBE7E84200080C430008C832002002 +:1025A00038B50C4D0C4C2A460C4904F10800FFF7D5 +:1025B00067FF05F1CA0204F110000949FFF760FF47 +:1025C00005F5CA7204F118000649BDE83840FFF766 +:1025D00057BF00BFA04B00203C220020C44200088F +:1025E000CE420008DD42000870B5044608460D469C +:1025F000FEF73AFCC6B22046013403780BB9184600 +:1026000070BD32462946FEF71BFC0028F3D101209D +:10261000F6E700002DE9F04705460C46FEF724FCDE +:102620002B49C6B22846FFF7DFFF08B10E36F6B2D7 +:1026300028492846FFF7D8FF08B11036F6B2632EB6 +:102640000BD8DFF88C80DFF88C90234FDFF894A054 +:102650002E7846B92670BDE8F08729462046BDE8A9 +:10266000F04701F0C3BD252E2ED107224146284652 +:10267000FEF7E6FB70B9194B224603F1140153F83B +:10268000040B8B4242F8040BF9D11B780735153443 +:102690001370DDE7082249462846FEF7D1FB98B9BA +:1026A000A21C0F4B197802320909C95D02F8041CFB +:1026B00013F8011B01F00F015345C95D02F8031C1B +:1026C000F0D118340835C3E7013504F8016BBFE7D2 +:1026D000B4430008DD420008D2430008BC430008B0 +:1026E00000E8F11F0CE8F11FBFF34F8F044B1A698C +:1026F0005107FCD1D3F810215207F8D1704700BF21 +:102700000020005208B50D4B1B78ABB9FFF7ECFF6A +:102710000B4BDA68D10704D50A4A5A6002F18832B5 +:102720005A60D3F80C21D20706D5064AC3F8042113 +:1027300002F18832C3F8042108BD00BFFE4D00201D +:10274000002000522301674508B5114B1B78F3B9EF +:10275000104B1A69510703D5DA6842F04002DA607B +:10276000D3F81021520705D5D3F80C2142F04002CE +:10277000C3F80C21FFF7B8FF064BDA6842F00102FC +:10278000DA60D3F80C2142F00102C3F80C2108BD35 +:10279000FE4D0020002000520F289ABF00F58060F7 +:1027A00040040020704700004FF4003070470000E4 +:1027B000102070470F2808B50BD8FFF7EDFF00F584 +:1027C00000330268013204D104308342F9D1012080 +:1027D00008BD0020FCE700000F2870B5054645D86D +:1027E000FFF7D8FC224CFFF77FFF0646FFF78AFF72 +:1027F0004FF0FF33072D6361C4F8143120D82361F3 +:10280000FFF772FF2B0243F02403E360E36843F019 +:102810008003E36023695A07FCD42846FFF764FF6E +:102820004FF40031FFF7B8FF00F002F93046FFF730 +:102830008BFFFFF7B9FC2846BDE87040FFF7BABF31 +:10284000C4F81031FFF750FFA5F108031B0243F055 +:102850002403C4F80C31D4F80C3143F08003C4F8DD +:102860000C31D4F810315B07FBD4D6E7002070BDE3 +:10287000002000522DE9F84F40EA020305460C46BD +:102880001746D80602D00020BDE8F88F27F01F07B2 +:10289000DFF8D4B0FFF736FF2744BC4203D1012054 +:1028A000FFF752FFF0E720222946204601F08EFC78 +:1028B00010B920352034F0E72B4605F120021E68C0 +:1028C000711CE0D104339A42F9D1FFF763FC05F1A2 +:1028D0007843234AB3F5801F224B28BF9A4603F161 +:1028E000040338BF9046A2F1080228BF9846A3F11E +:1028F00008033ABF9146DA469946FFF7F5FEC8F855 +:102900000060A5EB040CD9F8002004F11C0142F092 +:102910000202C9F80020221FDAF8006016F005064E +:10292000FAD152F8043F8A424CF80230F4D1BFF396 +:102930004F8FFFF7D9FE4FF0FF32C8F80020D9F8CB +:10294000002022F00202C9F80020FFF72DFC20220F +:102950002146284601F03AFC0028AAD030469FE7DD +:1029600014200052102100521020005210B5084CC3 +:10297000237828B11BB9FFF7C5FE0123237010BDD2 +:10298000002BFCD02070BDE81040FFF7DDBE00BF7B +:10299000FE4D00200244074BD2B210B5904200D148 +:1029A00010BD441C00B253F8200041F8040BE0B203 +:1029B000F4E700BF504000580E4B30B51C6F2404A4 +:1029C00005D41C6F1C671C6F44F400441C670A4C40 +:1029D00002442368D2B243F480732360074B9042D1 +:1029E00000D130BD441C51F8045B00B243F82050C4 +:1029F000E0B2F4E700440258004802585040005842 +:102A000007B5012201A90020FFF7C4FF019803B018 +:102A10005DF804FB13B50446FFF7F2FFA04205D0B2 +:102A2000012201A900200194FFF7C6FF02B010BDEA +:102A30000144BFF34F8F064B884204D3BFF34F8F3F +:102A4000BFF36F8F7047C3F85C022030F4E700BF1C +:102A500000ED00E000207047034B1A681AB9034AE2 +:102A6000D2F8D0241A607047004E0020004002586F +:102A700008B5FFF7F1FF024B1868C0F3806008BD8E +:102A8000004E0020CAB201460120FFF795BF0000AA +:102A9000CAB201460120FFF77DBF0000EFF30983B2 +:102AA000054968334A6B22F001024A6383F30988BF +:102AB000002383F31188704700EF00E0202080F3AB +:102AC000118862B60D4B0E4AD96821F4E061090401 +:102AD000090C0A430B49DA60D3F8FC2042F08072FB +:102AE000C3F8FC20084AC2F8B01F116841F0010188 +:102AF00011601022DA7783F82200704700ED00E0C1 +:102B00000003FA0555CEACC5001000E0202310B537 +:102B100083F311880E4B5B6813F4006314D0F1EE5D +:102B2000103AEFF309844FF08073683CE361094B7E +:102B3000DB6B236684F30988FFF7DCFA10B1064BE0 +:102B4000A36110BD054BFBE783F31188F9E700BFD4 +:102B500000ED00E000EF00E0FF03000802040008C1 +:102B600070B5BFF34F8FBFF36F8F1A4A0021C2F8C1 +:102B70005012BFF34F8FBFF36F8F536943F400338D +:102B80005361BFF34F8FBFF36F8FC2F88410BFF351 +:102B90004F8FD2F8803043F6E074C3F3C900C3F31B +:102BA0004E335B0103EA0406014646EA81750139AA +:102BB000C2F86052F9D2203B13F1200FF2D1BFF3DB +:102BC0004F8F536943F480335361BFF34F8FBFF38B +:102BD0006F8F70BD00ED00E0FEE700000A4B0B4870 +:102BE0000B4A90420BD30B4BC11EDA1C121A22F077 +:102BF00003028B4238BF00220021FEF73DB953F893 +:102C0000041B40F8041BECE7B4450008D44F002037 +:102C1000D44F0020D44F00207047000070B5D0E999 +:102C2000244300224FF0FF359E6804EB421351010C +:102C3000D3F80009002805DAD3F8000940F08040F5 +:102C4000C3F80009D3F8000B002805DAD3F8000B0D +:102C500040F08040C3F8000B013263189642C3F87D +:102C60000859C3F8085BE0D24FF00113C4F81C38D0 +:102C700070BD000000EB8103D3F80CC02DE9F043D8 +:102C8000DCF814204E1CD0F89050D2F800E005EB90 +:102C9000063605EB4118506870450AD30122D5F875 +:102CA000343802FA01F123EA0101C5F83418BDE80D +:102CB000F083AEEB0003BCF81040A34228BF2346CC +:102CC000D8F81849A4B2B3EB840FF0D89468A4F1F3 +:102CD000040959F8047F3760A4EB09071F44042F47 +:102CE000F7D81C44034494605360D4E7890141F051 +:102CF0002001016103699B06FCD41220FFF764BA2E +:102D000010B50A4C2046FEF7D5FE094BC4F89030AA +:102D1000084BC4F89430084C2046FEF7CBFE074B16 +:102D2000C4F89030064BC4F8943010BD044E002017 +:102D30000000084008440008A04E002000000440A5 +:102D40001444000870B503780546012B5DD1494B4A +:102D5000D0F89040984259D1474B0E216520D3F8C6 +:102D6000D82042F00062C3F8D820D3F8002142F006 +:102D70000062C3F80021D3F80021D3F8802042F08C +:102D80000062C3F88020D3F8802022F00062C3F8EC +:102D90008020D3F8803000F071FC384BE360384B72 +:102DA000C4F800380023D5F89060C4F8003EC02372 +:102DB00023604FF40413A3633369002BFCDA01236F +:102DC0000C203361FFF700FA3369DB07FCD41220D3 +:102DD000FFF7FAF93369002BFCDA00262846A660D3 +:102DE000FFF71CFF6B68C4F81068DB68C4F8146850 +:102DF000C4F81C68002B3AD1224BA3614FF0FF337B +:102E00006361A36843F00103A36070BD1E4B984249 +:102E1000C8D1194B0E214D20D3F8D82042F00072B2 +:102E2000C3F8D820D3F8002142F00072C3F8002183 +:102E3000D3F80021D3F8802042F00072C3F880203C +:102E4000D3F8802022F00072C3F88020D3F88020CD +:102E5000D3F8D82022F08062C3F8D820D3F800211C +:102E600022F08062C3F80021D3F8003193E7074BCA +:102E7000C3E700BF044E0020004402584014004045 +:102E800003002002003C30C0A04E0020083C30C0AF +:102E9000F8B5D0F89040054600214FF00066204676 +:102EA000FFF724FFD5F8941000234FF001128F682C +:102EB0004FF0FF30C4F83438C4F81C2804EB431238 +:102EC00001339F42C2F80069C2F8006BC2F80809DA +:102ED000C2F8080BF2D20B68D5F89020C5F89830EC +:102EE000636210231361166916F01006FBD11220DD +:102EF000FFF76AF9D4F8003823F4FE63C4F8003809 +:102F0000A36943F4402343F01003A3610923C4F8E9 +:102F10001038C4F814380B4BEB604FF0C043C4F8C2 +:102F2000103B094BC4F8003BC4F81069C4F80039E1 +:102F3000D5F8983003F1100243F48013C5F89820B7 +:102F4000A362F8BDE443000840800010D0F8902050 +:102F500090F88A10D2F8003823F4FE6343EA011394 +:102F6000C2F80038704700002DE9F84300EB8103F8 +:102F7000D0F890500C468046DA680FFA81F9480183 +:102F8000166806F00306731E022B05EB41134FF083 +:102F9000000194BFB604384EC3F8101B4FF0010176 +:102FA00004F1100398BF06F1805601FA03F391690A +:102FB00098BF06F5004600293AD0578A04F1580117 +:102FC000374349016F50D5F81C180B430021C5F851 +:102FD0001C382B180127C3F81019A7405369611E2C +:102FE0009BB3138A928B9B08012A88BF5343D8F85E +:102FF0009820981842EA034301F140022146C8F89C +:103000009800284605EB82025360FFF76FFE08EB3D +:103010008900C3681B8A43EA845348341E43640111 +:103020002E51D5F81C381F43C5F81C78BDE8F8832D +:1030300005EB4917D7F8001B21F40041C7F8001B26 +:10304000D5F81C1821EA0303C0E704F13F030B4A3B +:103050002846214605EB83035A60FFF747FE05EB40 +:103060004910D0F8003923F40043C0F80039D5F8EE +:103070001C3823EA0707D7E700800010000400028D +:10308000D0F894201268C0F89820FFF7C7BD000060 +:103090005831D0F8903049015B5813F4004004D007 +:1030A00013F4001F0CBF0220012070474831D0F8F4 +:1030B000903049015B5813F4004004D013F4001F12 +:1030C0000CBF02200120704700EB8101CB68196A18 +:1030D0000B6813604B6853607047000000EB81037E +:1030E00030B5DD68AA691368D36019B9402B84BF75 +:1030F000402313606B8A1468D0F890201C4402EBC4 +:103100004110013C09B2B4FBF3F46343033323F0F1 +:10311000030343EAC44343F0C043C0F8103B2B68A9 +:1031200003F00303012B0ED1D2F8083802EB411053 +:1031300013F4807FD0F8003B14BF43F0805343F07A +:103140000053C0F8003B02EB4112D2F8003B43F0C1 +:103150000443C2F8003B30BD2DE9F041D0F8906047 +:1031600005460C4606EB4113D3F8087B3A07C3F833 +:10317000087B08D5D6F814381B0704D500EB81036B +:10318000DB685B689847FA071FD5D6F81438DB0769 +:103190001BD505EB8403D968CCB98B69488A5A687A +:1031A000B2FBF0F600FB16228AB91868DA68904282 +:1031B0000DD2121AC3E90024202383F3118821467B +:1031C0002846FFF78BFF84F31188BDE8F0810123C7 +:1031D00003FA04F26B8923EA02036B81CB68002BAC +:1031E000F3D021462846BDE8F041184700EB8103A3 +:1031F0004A0170B5DD68D0F890306C692668E660E9 +:1032000056BB1A444FF40020C2F810092A6802F095 +:103210000302012A0AB20ED1D3F8080803EB4214C4 +:1032200010F4807FD4F8000914BF40F0805040F0C3 +:103230000050C4F8000903EB4212D2F8000940F034 +:103240000440C2F800090122D3F8340802FA01F15F +:103250000143C3F8341870BD19B9402E84BF402013 +:10326000206020681A442E8A8419013CB4FBF6F4CD +:1032700040EAC44040F00050C6E700002DE9F041AC +:10328000D0F8906004460D4606EB4113D3F8087958 +:10329000C3F80879FB071CD5D6F81038DA0718D51B +:1032A00000EB8103D3F80CC0DCF81430D3F800E055 +:1032B000DA6896451BD2A2EB0E024FF000081A60A6 +:1032C000C3F80480202383F31188FFF78FFF88F36E +:1032D00011883B0618D50123D6F83428AB40134299 +:1032E00012D029462046BDE8F041FFF7C3BC0123B8 +:1032F00003FA01F2038923EA02030381DCF80830B0 +:10330000002BE6D09847E4E7BDE8F0812DE9F84FBF +:10331000D0F8905004466E69AB691E4016F4805890 +:103320006E6103D0BDE8F84FFEF734BC002E12DA10 +:10333000D5F8003E9F0705D0D5F8003E23F00303E3 +:10334000C5F8003ED5F80438204623F00103C5F83F +:103350000438FEF74BFC300505D52046FFF75EFC30 +:103360002046FEF733FCB1040CD5D5F8083813F02D +:10337000060FEB6823F470530CBF43F4105343F46F +:10338000A053EB60320704D56368DB680BB12046BD +:103390009847F30200F1BA80B70226D5D4F890908E +:1033A00000274FF0010A09EB4712D2F8003B03F463 +:1033B0004023B3F5802F11D1D2F8003B002B0DDA5A +:1033C00062890AFA07F322EA0303638104EB8703A5 +:1033D000DB68DB6813B13946204698470137D4F8DB +:1033E0009430FFB29B689F42DDD9F00619D5D4F81E +:1033F0009000026AC2F30A1702F00F0302F4F012FF +:10340000B2F5802F00F0CC80B2F5402F09D104EB4B +:103410008303002200F58050DB681B6A974240F06E +:10342000B2803003D5F8185835D5E90303D500210B +:103430002046FFF791FEAA0303D501212046FFF79E +:103440008BFE6B0303D502212046FFF785FE2F0379 +:1034500003D503212046FFF77FFEE80203D50421B0 +:103460002046FFF779FEA90203D505212046FFF784 +:1034700073FE6A0203D506212046FFF76DFE2B027C +:1034800003D507212046FFF767FEEF0103D508218A +:103490002046FFF761FE700340F1A980E90703D5DC +:1034A00000212046FFF7EAFEAA0703D501212046A6 +:1034B000FFF7E4FE6B0703D502212046FFF7DEFE8F +:1034C0002F0703D503212046FFF7D8FEEE0603D5CC +:1034D00004212046FFF7D2FEA80603D50521204689 +:1034E000FFF7CCFE690603D506212046FFF7C6FE8E +:1034F0002A0603D507212046FFF7C0FEEB0576D547 +:1035000020460821BDE8F84FFFF7B8BED4F89090E8 +:1035100000274FF0010AD4F894305FFA87FB9B68CC +:103520009B453FF639AF09EB4B13D3F8002902F462 +:103530004022B2F5802F24D1D3F80029002A20DAC6 +:10354000D3F8002942F09042C3F80029D3F80029AB +:10355000002AFBDB5946D4F89000FFF7C7FB22890D +:103560000AFA0BF322EA0303238104EB8B03DB68E3 +:103570009B6813B159462046984759462046FFF7A5 +:1035800079FB0137C7E7910701D1D0F80080072AFE +:1035900002F101029CBF03F8018B4FEA18283DE7B6 +:1035A00004EB830300F58050DA68D2F818C0DCF829 +:1035B0000820DCE9001CA1EB0C0C00218F4208D193 +:1035C000DB689B699A683A449A605A683A445A6040 +:1035D00027E711F0030F01D1D0F800808C4501F1ED +:1035E000010184BF02F8018B4FEA1828E6E7BDE825 +:1035F000F88F000008B50348FFF788FEBDE80840D3 +:10360000FFF784BA044E002008B50348FFF77EFE9A +:10361000BDE80840FFF77ABAA04E0020D0F89030FD +:1036200003EB4111D1F8003B43F40013C1F8003B18 +:1036300070470000D0F8903003EB4111D1F8003909 +:1036400043F40013C1F8003970470000D0F89030FF +:1036500003EB4111D1F8003B23F40013C1F8003B08 +:1036600070470000D0F8903003EB4111D1F80039D9 +:1036700023F40013C1F8003970470000090100F17C +:103680006043012203F56143C9B283F8001300F0DF +:103690001F039A4043099B0003F1604303F5614314 +:1036A000C3F880211A60704730B50433039C01725F +:1036B000002104FB0325C160C0E90653049B03639A +:1036C000059BC0E90000C0E90422C0E90842C0E946 +:1036D0000A11436330BD00000022416AC260C0E9A4 +:1036E0000411C0E90A226FF00101FEF7DDBD000000 +:1036F000D0E90432934201D1C2680AB9181D70475B +:1037000000207047036919600021C2680132C2605D +:10371000C269134482699342036124BF436A03610F +:10372000FEF7B6BD38B504460D46E3683BB16269A5 +:103730000020131D1268A3621344E36207E0237A9A +:1037400033B929462046FEF793FD0028EDDA38BD4F +:103750006FF00100FBE70000C368C269013BC36072 +:103760004369134482699342436124BF436A4361BE +:1037700000238362036B03B11847704770B52023A1 +:10378000044683F31188866A3EB9FFF7CBFF0546EE +:1037900018B186F31188284670BDA36AE26A13F84F +:1037A000015B9342A36202D32046FFF7D5FF0023BB +:1037B00083F31188EFE700002DE9F84F04460E4629 +:1037C000174698464FF0200989F311880025AA462C +:1037D000D4F828B0BBF1000F09D141462046FFF7CD +:1037E000A1FF20B18BF311882846BDE8F88FD4E9FA +:1037F0000A12A7EB050B521A934528BF9346BBF15B +:10380000400F1BD9334601F1400251F8040B91429D +:1038100043F8040BF9D1A36A403640354033A36224 +:10382000D4E90A239A4202D32046FFF795FF8AF390 +:103830001188BD42D8D289F31188C9E730465A466B +:10384000FDF7F4FAA36A5E445D445B44A362E7E7D4 +:1038500010B5029C0433017204FB0321C460C0E96B +:1038600006130023C0E90A33039B0363049BC0E9EA +:103870000000C0E90422C0E90842436310BD000013 +:10388000026A6FF00101C260426AC0E904220022AC +:10389000C0E90A22FEF708BDD0E904239A4201D10B +:1038A000C26822B9184650F8043B0B6070470020EC +:1038B00070470000C3680021C2690133C3604369D7 +:1038C000134482699342436124BF436A4361FEF714 +:1038D000DFBC000038B504460D46E3683BB1236900 +:1038E00000201A1DA262E2691344E36207E0237A12 +:1038F00033B929462046FEF7BBFC0028EDDA38BD77 +:103900006FF00100FBE7000003691960C268013A2B +:10391000C260C269134482699342036124BF436A4F +:10392000036100238362036B03B1184770470000F3 +:1039300070B520230D460446114683F31188866A2C +:103940002EB9FFF7C7FF10B186F3118870BDA36AC7 +:103950001D70A36AE26A01339342A36204D3E16952 +:1039600020460439FFF7D0FF002080F31188EDE7EF +:103970002DE9F84F04460D46904699464FF0200A2F +:103980008AF311880026B346A76A4FB949462046F4 +:10399000FFF7A0FF20B187F311883046BDE8F88F0C +:1039A000D4E90A073A1AA8EB0607974228BF174638 +:1039B000402F1BD905F1400355F8042B9D4240F8D8 +:1039C000042BF9D1A36A40364033A362D4E90A2319 +:1039D0009A4204D3E16920460439FFF795FF8BF33F +:1039E00011884645D9D28AF31188CDE729463A464F +:1039F000FDF71CFAA36A3D443E443B44A362E5E75D +:103A0000D0E904239A4217D1C3689BB1836A8BB172 +:103A1000043B9B1A0ED01360C368013BC360C369AB +:103A20001A4483699A42026124BF436A03610023F6 +:103A300083620123184670470023FBE700F0DAB8E1 +:103A4000034B002258631A610222DA60704700BFFC +:103A5000000C0040014B0022DA607047000C00406F +:103A6000014B5863704700BF000C0040014B586A7F +:103A7000704700BF000C00404B6843608B68836058 +:103A8000CB68C3600B6943614B6903628B69436216 +:103A90000B6803607047000008B53C4B40F2FF71B3 +:103AA0003B48D3F888200A43C3F88820D3F88820FD +:103AB00022F4FF6222F00702C3F88820D3F888209E +:103AC000D3F8E0200A43C3F8E020D3F808210A43E2 +:103AD000C3F808212F4AD3F808311146FFF7CCFF6D +:103AE00000F5806002F11C01FFF7C6FF00F5806061 +:103AF00002F13801FFF7C0FF00F5806002F15401C8 +:103B0000FFF7BAFF00F5806002F17001FFF7B4FF24 +:103B100000F5806002F18C01FFF7AEFF00F58060D8 +:103B200002F1A801FFF7A8FF00F5806002F1C401CF +:103B3000FFF7A2FF00F5806002F1E001FFF79CFFB4 +:103B400000F5806002F1FC01FFF796FF02F58C7131 +:103B500000F58060FFF790FF00F000F90E4BD3F8FE +:103B6000902242F00102C3F89022D3F8942242F04E +:103B70000102C3F894220522C3F898204FF0605246 +:103B8000C3F89C20054AC3F8A02008BD0044025891 +:103B9000000002582044000800ED00E01F00080368 +:103BA00008B500F0F3FAFEF7D3FA0F4BD3F8DC2098 +:103BB00042F04002C3F8DC20D3F8042122F0400296 +:103BC000C3F80421D3F80431084B1A6842F0080204 +:103BD0001A601A6842F004021A60FEF73DFFBDE861 +:103BE0000840FEF7DDBC00BF004402580018024840 +:103BF00070470000114BD3F8E82042F00802C3F8E8 +:103C0000E820D3F8102142F00802C3F810210C4A32 +:103C1000D3F81031D36B43F00803D363C722094BA9 +:103C20009A624FF0FF32DA6200229A615A63DA60D8 +:103C30005A6001225A611A60704700BF004402585E +:103C40000010005C000C0040094A08B51169D368F7 +:103C50000B40D9B29B076FEA0101116107D5202300 +:103C600083F31188FEF794FA002383F3118808BDCB +:103C7000000C0040384B4FF0FF31D3F88020C3F8E0 +:103C80008010D3F880200022C3F88020D3F8800071 +:103C9000D3F88400C3F88410D3F88400C3F88420D8 +:103CA000D3F88400D86F40F0FF4040F4FF0040F4A8 +:103CB0003F5040F03F00D867D86F20F0FF4020F41D +:103CC000FF0020F43F5020F03F00D867D86FD3F8B2 +:103CD00088006FEA40506FEA5050C3F88800D3F86C +:103CE0008800C0F30A00C3F88800D3F88800D3F82E +:103CF0009000C3F89010D3F89000C3F89020D3F848 +:103D00009000D3F89400C3F89410D3F89400C3F84B +:103D10009420D3F89400D3F89800C3F89810D3F8FF +:103D20009800C3F89820D3F89800D3F88C00C3F813 +:103D30008C10D3F88C00C3F88C20D3F88C00D3F807 +:103D40009C00C3F89C10D3F89C10C3F89C20D3F8B7 +:103D50009C3000F0E7B900BF00440258614B0122DB +:103D6000C3F80821604BD3F8F42042F00202C3F8F4 +:103D7000F420D3F81C2142F00202C3F81C210422D3 +:103D8000D3F81C31594BDA605A689104FCD5584A73 +:103D90001A6001229A60574ADA6000221A614FF4D1 +:103DA00040429A61514B9A699204FCD51A6842F4D8 +:103DB00080721A604C4B1A6F12F4407F04D04FF49B +:103DC00080321A6700221A671A6842F001021A60EC +:103DD000454B1A685007FCD500221A611A6912F087 +:103DE0003802FBD1012119604FF0804159605A67B8 +:103DF000414ADA62414A1A611A6842F480321A6012 +:103E0000394B1A689103FCD51A6842F480521A6043 +:103E10001A689204FCD53A4A3A499A6200225A63D7 +:103E200019633949DA6399635A64384A1A64384A1B +:103E3000DA621A6842F0A8521A602B4B1A6802F034 +:103E40002852B2F1285FF9D148229A614FF4886272 +:103E5000DA6140221A622F4ADA644FF080521A6502 +:103E60002D4A5A652D4A9A6532232D4A13601368EC +:103E700003F00F03022BFAD11B4B1A6942F0030225 +:103E80001A611A6902F03802182AFAD1D3F8DC2034 +:103E900042F00052C3F8DC20D3F8042142F0005273 +:103EA000C3F80421D3F80421D3F8DC2042F0804287 +:103EB000C3F8DC20D3F8042142F08042C3F8042187 +:103EC000D3F80421D3F8DC2042F00042C3F8DC2010 +:103ED000D3F8042142F00042C3F80421D3F804319E +:103EE000704700BF0080005100440258004802584B +:103EF00000C000F0040000010000FF0100889008ED +:103F000032206000630209011D0204004704050815 +:103F1000FD0BFF01200000200010E0000001010067 +:103F2000002000524FF0B04208B5D2F8883003F0BC +:103F30000103C2F8883023B1044A13680BB15068FA +:103F40009847BDE80840FEF7E1BD00BF544F002090 +:103F50004FF0B04208B5D2F8883003F00203C2F83F +:103F6000883023B1044A93680BB1D0689847BDE804 +:103F70000840FEF7CBBD00BF544F00204FF0B042C9 +:103F800008B5D2F8883003F00403C2F8883023B1B2 +:103F9000044A13690BB150699847BDE80840FEF721 +:103FA000B5BD00BF544F00204FF0B04208B5D2F865 +:103FB000883003F00803C2F8883023B1044A9369BB +:103FC0000BB1D0699847BDE80840FEF79FBD00BF20 +:103FD000544F00204FF0B04208B5D2F8883003F0BB +:103FE0001003C2F8883023B1044A136A0BB1506A37 +:103FF0009847BDE80840FEF789BD00BF544F002038 +:104000004FF0B04310B5D3F8884004F47872C3F889 +:104010008820A30604D5124A936A0BB1D06A984748 +:10402000600604D50E4A136B0BB1506B98472106FE +:1040300004D50B4A936B0BB1D06B9847E20504D5BE +:10404000074A136C0BB1506C9847A30504D5044A7A +:10405000936C0BB1D06C9847BDE81040FEF756BD8D +:10406000544F00204FF0B04310B5D3F8884004F40B +:104070007C42C3F88820620504D5164A136D0BB143 +:10408000506D9847230504D5124A936D0BB1D06D3E +:104090009847E00404D50F4A136E0BB1506E984751 +:1040A000A10404D50B4A936E0BB1D06E98476204FD +:1040B00004D5084A136F0BB1506F9847230404D5F9 +:1040C000044A936F0BB1D06F9847BDE81040FEF7DC +:1040D0001DBD00BF544F002008B50348FDF7FCF894 +:1040E000BDE80840FEF712BDCC23002008B5034808 +:1040F000FDF7F2F8BDE80840FEF708BD38240020BF +:1041000008B50348FDF7E8F8BDE80840FEF7FEBC37 +:10411000A424002008B5FFF797FDBDE80840FEF78E +:10412000F5BC0000062108B50846FFF7A7FA0621EE +:104130000720FFF7A3FA06210820FFF79FFA0621C0 +:104140000920FFF79BFA06210A20FFF797FA0621BC +:104150001720FFF793FA06212820FFF78FFA09218D +:104160007A20FFF78BFA07213220FFF787FA0C211C +:104170002620FFF783FA0C212720FFF77FFA0C2176 +:104180005220BDE80840FFF779BA000008B5FFF7F4 +:1041900071FD00F00DF8FDF7B1FAFDF789FCFDF7B0 +:1041A0005BFBFFF725FDBDE80840FFF747BC0000BB +:1041B0000023054A19460133102BC2E9001102F110 +:1041C0000802F8D1704700BF544F002010B50139E4 +:1041D0000244904201D1002005E0037811F8014F1C +:1041E000A34201D0181B10BD0130F2E7034611F8BD +:1041F000012B03F8012B002AF9D1704753544D339A +:104200003248373F3F3F0053544D33324837343301 +:104210002F37353300000000C8320020CC230020A7 +:1042200038240020A4240020009600000000000094 +:10423000000000000000000000000000000000007E +:1042400000000000C5160008B1160008ED160008B1 +:10425000D9160008E5160008D1160008BD1600089A +:10426000A9160008F916000800000000D51700087C +:10427000C1170008FD170008E9170008F517000826 +:10428000E1170008CD170008B91700080918000841 +:104290000000000001000000000000006D61696E78 +:1042A0000000000069646C6500000000A442000882 +:1042B00050310020C8320020010000004D210008CC +:1042C000000000004375626550696C6F74004375AF +:1042D00062654F72616E67652B2D424C0025534518 +:1042E0005249414C2500000002000000000000007F +:1042F000F5190008651A000840004000704B0020C6 +:10430000804B0020020000000000000003000000BD +:1043100000000000AD1A00080000000010000000BE +:10432000904B002000000000010000000000000091 +:10433000044E0020010102003D2500084D24000824 +:10434000E9240008CD240008430000005043000881 +:1043500009024300020100C0320904000001020208 +:1043600001000524001001052401000104240202BB +:104370000524060001070582030800FF0904010067 +:10438000020A000000070501024000000705810243 +:1043900040000000120000009C43000812011001C0 +:1043A00002000040AE2D581000020102030100007F +:1043B0000403090425424F415244250043756265B8 +:1043C0004F72616E6765506C75732D626473686FB0 +:1043D0007400303132333435363738394142434452 +:1043E0004546000000000000011C0008B91E00083E +:1043F000651F0008400040003C4F00203C4F00205B +:10440000010000004C4F002080000000400100002F +:104410000800000000010000000400000800000087 +:104420000000812A00000000AAAAAAAA0000002415 +:10443000FFFE00000000000000A00A0000010000D4 +:1044400000000000AAAAAAAA00000000FFFF0000C6 +:1044500000000000000000001400005400000000F4 +:10446000AAAAAAAA14000054FFFF0000000000003E +:104470000000000000681A0000000000AAAA8AAA32 +:1044800000541500FFFF00000000700777000000D7 +:104490004081020100100000AAAAAAAA004101005E +:1044A000F7FF00000000007007000000000000009F +:1044B00000000000AAAAAAAA00000000FFFF000056 +:1044C00000000000000000000400000000000000E8 +:1044D000A2AAAAAA04000000FFFF0000000000003A +:1044E000000000000000000000000000AAAAAAAA24 +:1044F00000000000FFFF00000000000000000000BE +:104500000000000000000000AAAAAAAA0000000003 +:10451000FFFF00000000000000000000000000009D +:1045200000000000AAAAAAAA00000000FFFF0000E5 +:10453000000000000000000000000000000000007B +:10454000AAAAAAAA00000000FFFF000000000000C5 +:104550000000000000000000270400000000000030 +:1045600000001E0000000000FF000000000000002E +:10457000FC4100083F000000500400000742000812 +:104580003F000000009600000000080096000000B8 +:104590000008000004000000B04300080000000014 +:1045A000000000000000000000000000000000000B +:0445B0000000000007 +:00000001FF diff --git a/Tools/bootloaders/CubeOrangePlus_bl.bin b/Tools/bootloaders/CubeOrangePlus_bl.bin new file mode 100755 index 00000000000..22cee0be3a7 Binary files /dev/null and b/Tools/bootloaders/CubeOrangePlus_bl.bin differ diff --git a/Tools/bootloaders/CubeOrangePlus_bl.elf b/Tools/bootloaders/CubeOrangePlus_bl.elf new file mode 100755 index 00000000000..34a0a2b4a18 Binary files /dev/null and b/Tools/bootloaders/CubeOrangePlus_bl.elf differ diff --git a/Tools/bootloaders/CubeOrangePlus_bl.hex b/Tools/bootloaders/CubeOrangePlus_bl.hex new file mode 100644 index 00000000000..a01ab8adc35 --- /dev/null +++ b/Tools/bootloaders/CubeOrangePlus_bl.hex @@ -0,0 +1,1105 @@ +:020000040800F2 +:1000000000060020A1020008FD0F00087D0F000877 +:10001000D50F00087D0F0008A90F0008A3020008F3 +:10002000A3020008A3020008A3020008DD290008BB +:10003000A3020008A3020008A3020008A30200080C +:10004000A3020008A3020008A3020008A3020008FC +:10005000A3020008A3020008653E0008913E0008C4 +:10006000BD3E0008E93E0008153F0008A302000855 +:10007000A3020008A3020008A3020008A3020008CC +:10008000A3020008A3020008A3020008A3020008BC +:10009000A3020008A3020008A3020008413F0008D1 +:1000A000A3020008A3020008A3020008A30200089C +:1000B000A3020008A3020008A3020008A30200088C +:1000C000A3020008A3020008A3020008A30200087C +:1000D000A3020008A3020008194000082D400008F0 +:1000E000A53F0008A3020008A3020008A30200081D +:1000F000A3020008A3020008A3020008A30200084C +:10010000A3020008A302000855400008A30200084B +:10011000A3020008A3020008A3020008A30200082B +:10012000A3020008A3020008A3020008A30200081B +:10013000A3020008A3020008A3020008A30200080B +:10014000A3020008A3020008A3020008A3020008FB +:10015000A3020008A3020008A3020008A3020008EB +:10016000A3020008A3020008A3020008A3020008DB +:10017000A302000849350008A3020008A3020008F2 +:10018000A3020008A302000841400008A3020008DF +:10019000A3020008A3020008A3020008A3020008AB +:1001A000A3020008A3020008A3020008A30200089B +:1001B000A3020008A3020008A3020008A30200088B +:1001C000A3020008A3020008A3020008A30200087B +:1001D000A302000835350008A3020008A3020008A6 +:1001E000A3020008A3020008A3020008A30200085B +:1001F000A3020008A3020008A3020008A30200084B +:10020000A3020008A3020008A3020008A30200083A +:10021000A3020008A3020008A3020008A30200082A +:10022000A3020008A3020008A3020008A30200081A +:10023000A3020008A3020008A3020008A30200080A +:10024000A3020008A3020008A3020008A3020008FA +:10025000A3020008A3020008A3020008A3020008EA +:10026000A3020008A3020008A3020008A3020008DA +:10027000A3020008A3020008A3020008A3020008CA +:10028000A3020008A3020008A3020008A3020008BA +:10029000A3020008A3020008A3020008A3020008AA +:1002A00002E000F000F8FEE772B63A4880F30888F2 +:1002B000394880F3098839484EF60851CEF20001DA +:1002C000086040F20000CCF200004EF63471CEF22D +:1002D00000010860BFF34F8FBFF36F8F40F2000043 +:1002E000C0F2F0004EF68851CEF200010860BFF374 +:1002F0004F8FBFF36F8F4FF00000E1EE100A4EF604 +:100300003C71CEF200010860062080F31488BFF330 +:100310006F8F02F021FC02F0C3FB03F05DFB4FF096 +:1003200055301F491B4A91423CBF41F8040BFAE784 +:100330001C49194A91423CBF41F8040BFAE71A499B +:100340001A4A1B4B9A423EBF51F8040B42F8040B69 +:10035000F8E700201749184A91423CBF41F8040BC6 +:10036000FAE702F0DBFB03F0BBFB144C144DAC428C +:1003700003DA54F8041B8847F9E700F041F8114C00 +:10038000114DAC4203DA54F8041B8847F9E702F038 +:10039000C3BB00000006002000220020000000086F +:1003A00000000020000600209044000800220020E9 +:1003B0005C22002060220020D44F0020A002000810 +:1003C000A0020008A0020008A00200082DE9F04FDA +:1003D0002DED108AC1F80CD0D0F80CD0BDEC108AED +:1003E000BDE8F08F002383F311882846A047002042 +:1003F00001F0DAFEFEE701F055FE00DFFEE7000047 +:1004000038B500F0D7FC30B1164B00220E211A721D +:100410005A729972DA7202F0A1FA054602F0D4FA21 +:100420000446D0B9104B9D4219D001339D4241F290 +:10043000883512BF044600250124002002F098FAF6 +:100440000CB100F059F800F039FD00F0F9FB284636 +:1004500000F004F900F050F8F9E70025EDE7054653 +:10046000EBE700BF00220020010007B008B500F054 +:10047000B3FBA0F120035842584108BD07B541F233 +:100480001203022101A8ADF8043000F0C3FB03B051 +:100490005DF804FB202310B583F311881248C3686C +:1004A0000BB101F007FF0023104A4FF47A710E4898 +:1004B00001F0C4FE002383F311880D4C236813B1AF +:1004C0002368013B2360636813B16368013B636089 +:1004D000084B1B7833B9636823B9022000F070FC25 +:1004E0003223636010BD00BF602200209504000825 +:1004F0007C23002074220020F8B5514B514A1C4641 +:100500001968013100F09B8004339342F8D162688E +:100510004D4B9A4240F293804C4B9B6803F1006331 +:1005200003F500339A4280F08A80002000F0A2FB9D +:100530000220474B187000F041FC464B0021D3F8D5 +:10054000E820C3F8E810D3F81021C3F81011D3F84D +:100550001021D3F8EC20C3F8EC10D3F81421C3F821 +:100560001411D3F81421D3F8F020C3F8F010D3F805 +:100570001821C3F81811D3F81821D3F8802042F0BD +:100580000062C3F88020D3F8802022F00062C3F814 +:100590008020D3F88020D3F8802042F00072C3F886 +:1005A0008020D3F8802022F00072C3F88020D3F896 +:1005B000803072B64FF0E023C3F8084DD4E9000450 +:1005C000BFF34F8FBFF36F8F234AC2F88410BFF37E +:1005D0004F8F536923F480335361BFF34F8FD2F8A9 +:1005E000803043F6E076C3F3C905C3F34E335B01B5 +:1005F00003EA060C29464CEA81770139C2F8747285 +:10060000F9D2203B13F1200FF2D1BFF34F8FBFF38C +:100610006F8FBFF34F8FBFF36F8F536923F4003396 +:1006200053610023C2F85032BFF34F8FBFF36F8F77 +:10063000202383F31188854680F308882047F8BD7E +:100640000000020820000208FFFF0108002200202D +:10065000742200200044025800ED00E02DE9F04F24 +:1006600093B0A94B2022FF2100900AA89D6800F0BA +:10067000CFFBA64A1378A3B90121A5481170C36026 +:10068000202383F31188C3680BB101F013FE00230C +:10069000A04A4FF47A719E4801F0D0FD002383F305 +:1006A0001188009B9C4A03B1136000239B49009C66 +:1006B00098469B461E469A460B705360012000F0F8 +:1006C0007DFB24B1944B1B68002B00F016820020A8 +:1006D00000F082FA0390039B002BF2DB012000F074 +:1006E0006BFB039B213B162BE8D801A252F823F0A9 +:1006F0004D0700087507000809080008BD06000836 +:10070000BD060008BD0600089D0800086F0A000825 +:1007100089090008EB090008130A0008390A0008D3 +:10072000BD0600084B0A0008BD060008BD0A000807 +:10073000ED070008BD060008010B00085907000876 +:10074000ED070008BD060008EB0900080220FFF7CE +:100750008DFE002840F0FB81009B022105A8B8F126 +:10076000000F08BF1C4641F21233ADF8143000F000 +:1007700051FAA3E74FF47A7000F02EFA071EEBDB74 +:100780000220FFF773FE0028E6D0013F052F00F29C +:10079000E081DFE807F0030A0D101336052304217A +:1007A00005A8059300F036FA17E004215648F9E74A +:1007B00004215B48F6E704215A48F3E74FF01C098F +:1007C000484609F1040900F057FA0421059005A8EC +:1007D00000F020FAB9F12C0FF2D101204FF0000AFD +:1007E00000FA07F747EA0B0B5FFA8BFB00F05CFBA4 +:1007F00026B10BF00B030B2B08BF0024FFF73EFEC6 +:100800005CE704214848CDE7002EA5D00BF00B0390 +:100810000B2BA1D10220FFF729FE074600289BD011 +:1008200001203E4E00F026FA4FF000080220307002 +:1008300000F0C4FA5FFA88F9484600F02BFA044643 +:1008400090B1484608F1010800F034FA0028F1D1CF +:10085000B846044641F21213022105A83E46ADF8FF +:10086000143000F0D7F929E7012325460220337020 +:1008700000F0A2FA244B9B68AB4207D9284600F04F +:10088000FBF9013040F068810435F3E70025234B84 +:10089000B8463E461D70204B5D60A7E7002E3FF432 +:1008A0005BAF0BF00B030B2B7FF456AF02201B4BFF +:1008B000187000F083FA322000F08EF9B0F10009D0 +:1008C000FFF64AAF19F003077FF446AF0E4A09EB73 +:1008D0000503926893423FF63FAFB9F5807F3FF73B +:1008E0003BAF124BB945019322DD4FF47A7000F013 +:1008F00073F90390039A002AFFF62EAF039A01378B +:10090000019B03F8012BEDE7002200207823002053 +:1009100060220020950400087C230020742200201F +:1009200004220020082200200C220020782200202F +:10093000C820FFF79BFD074600283FF40DAF1F2D91 +:1009400011D8C5F120020AAB25F0030084494A45BD +:10095000184428BF4A46019200F034FA019AFF2158 +:100960007F4800F055FA4FEAA903C9F387027C4992 +:100970002846019300F054FA064600283FF46AAF77 +:10098000019B05EB830531E70220FFF76FFD00288F +:100990003FF4E2AE00F0AAF900283FF4DDAE0027F4 +:1009A000B946704B9B68BB4218D91F2F11D80A9BC0 +:1009B00001330ED027F0030312AA134453F8203C4E +:1009C00005934846042205A9043700F019FB814627 +:1009D000E7E7384600F050F90590F2E7CDF81490BB +:1009E000042105A800F016F900E70023642104A8FB +:1009F000049300F005F900287FF4AEAE0220FFF763 +:100A000035FD00283FF4A8AE049800F065F9059084 +:100A1000E6E70023642104A8049300F0F1F800281D +:100A20007FF49AAE0220FFF721FD00283FF494AE38 +:100A3000049800F053F9EAE70220FFF717FD0028B9 +:100A40003FF48AAE00F062F9E1E70220FFF70EFD05 +:100A500000283FF481AE05A9142000F05DF9074697 +:100A60000421049004A800F0D5F83946B9E73220F3 +:100A700000F0B2F8071EFFF66FAEBB077FF46CAE56 +:100A8000384A07EB0A03926893423FF665AE0220AC +:100A9000FFF7ECFC00283FF45FAE27F00307574454 +:100AA000BA453FF4A3AE50460AF1040A00F0E4F858 +:100AB0000421059005A800F0ADF8F1E74FF47A7035 +:100AC000FFF7D4FC00283FF447AE00F00FF90028F0 +:100AD00044D00A9B01330BD008220AA9002000F061 +:100AE0009FF900283AD02022FF210AA800F090F9AF +:100AF000FFF7C4FC1C4801F05DFB13B0BDE8F08FAC +:100B0000002E3FF429AE0BF00B030B2B7FF424AE29 +:100B10000023642105A8059300F072F80746002819 +:100B20007FF41AAE0220FFF7A1FC814600283FF4B3 +:100B300013AEFFF7A3FC41F2883001F03BFB0598B0 +:100B400000F0FCF94E463C4600F0AEF9B6E506462C +:100B50004CE64FF0000AFFE5B8467BE6374679E6FB +:100B60007822002000220020A08601002DE9F84F05 +:100B70004FF47A7306460D46002402FB03F7DFF8B4 +:100B80005080DFF8509098F900305FFA84FA5A1CD0 +:100B900001D0A34210D159F824002A4631460368F7 +:100BA000D3F820B03B46D847854205D1074B0120FA +:100BB00083F800A0BDE8F88F0134042CE3D14FF492 +:100BC000FA7001F0F7FA0020F4E700BFC823002014 +:100BD0001022002058410008002307B502460121D9 +:100BE0000DF107008DF80730FFF7C0FF20B19DF829 +:100BF000070003B05DF804FB4FF0FF30F9E7000099 +:100C00000A46042108B5FFF7B1FF80F00100C0B229 +:100C1000404208BD074B0A4630B41978064B53F8DA +:100C20002140014623682046DD69044BAC4630BCB8 +:100C3000604700BFC823002058410008A08601007B +:100C400070B50A4E00240A4D01F060FD308028681E +:100C50003388834208D901F055FD2B6804440133E1 +:100C6000B4F5003F2B60F2D370BD00BFCA23002053 +:100C70008423002001F028BE00F1006000F5003060 +:100C80000068704700F10060920000F5003001F04C +:100C90009FBD0000054B1A68054B1B889B1A8342B9 +:100CA00002D9104401F02EBD00207047842300209B +:100CB000CA23002038B5074D04462868204401F0B7 +:100CC00027FD28B928682044BDE8384001F032BD2E +:100CD00038BD00BF842300200020704700F1FF5082 +:100CE00000F58F10D0F8000870470000064991F811 +:100CF000243033B100230822086A81F82430FFF73A +:100D0000C1BF0120704700BF88230020014B186835 +:100D1000704700BF0010005C244BF0B51A68044611 +:100D2000234BC2F30B06120C1F885868BE4293F97E +:100D3000085028D09F89BE4206D101200C2505FB12 +:100D40000033586893F9085041F201039A421CD0CD +:100D500041F203039A421AD042F201039A4218D098 +:100D600042F203039A4208BF5625621E0B46441EF8 +:100D70000A4493420FD214F9016F581C6EB1034616 +:100D800000F8016CF5E70020D8E75A25EDE7592572 +:100D9000EBE75825E9E7184605E02C2482421C7051 +:100DA00001D9981C5D70401AF0BD00BF0010005CB6 +:100DB0001422002000207047704700007047000098 +:100DC00070470000002310B5934203D0CC5CC4549C +:100DD0000133F9E710BD0000013810B510F9013FEB +:100DE0003BB191F900409C4203D11AB10131013A63 +:100DF000F4E71AB191F90020981A10BD1046FCE7EB +:100E000003460246D01A12F9011B0029FAD1704795 +:100E100002440346934202D003F8011BFAE77047ED +:100E20002DE9F8431F4D14460746884695F82420BF +:100E300052BBDFF870909CB395F824302BB9202278 +:100E4000FF2148462F62FFF7E3FF95F82400414653 +:100E5000C0F1080205EB8000A24228BF2246D6B2AC +:100E60009200FFF7AFFF95F82430A41B17441E44EF +:100E70009044E4B2F6B2082E85F82460DBD1FFF787 +:100E800035FF0028D7D108E02B6A03EB82038342A9 +:100E9000CFD0FFF72BFF0028CBD10020BDE8F8838F +:100EA0000120FBE788230020024B1A78024B1A70BE +:100EB000704700BFC823002010220020F8B5194C4D +:100EC000194800F079FC2146174800F0A1FC24687D +:100ED0001648D4F89020164ED2F80438154D43F039 +:100EE0000203114FC2F8043801F064F92046124998 +:100EF00000F09CFDD4F890200424D2F8043823F0AC +:100F00000203C2F804384FF4E133336055F8040BA0 +:100F1000B84202D0314600F0ADFB013C14F0FF04B2 +:100F2000F4D1F8BD70420008C832002040420F00E2 +:100F3000B0230020584100087842000838B50B4B18 +:100F400004461A780A4B53F822500A4B9D420CD0A3 +:100F5000094B002118221846FFF75AFF046001468A +:100F60002846BDE8384000F085BB38BDC8230020C6 +:100F700058410008C8320020B023002000B59BB0C3 +:100F8000EFF3098168226846FFF71CFFEFF3058342 +:100F9000044B9A6BDA6A9A6A9A6A9A6A9A6A9A6AA5 +:100FA0009B6AFEE700ED00E000B59BB0EFF309811E +:100FB00068226846FFF706FFEFF30583044B9A6B40 +:100FC0009A6A9A6A9A6A9A6A9A6A9B6AFEE700BF64 +:100FD00000ED00E000B59BB0EFF3098168226846A0 +:100FE000FFF7F0FEEFF30583034B5A6B9A6A9A6A98 +:100FF0009A6A9A6A9B6AFEE700ED00E0FEE700004D +:1010000030B50A44084D91420DD011F8013B5840CB +:10101000082340F30004013B2C4013F0FF0384EA53 +:101020005000F6D1EFE730BD2083B8ED0268436889 +:101030001143016003B1184770470000024A13686A +:1010400043F0C0031360704700440040024A136835 +:1010500043F0C0031360704700480040024A136821 +:1010600043F0C003136070470078004037B5274C49 +:10107000274D204600F0F2FA04F1140000940023FA +:101080004FF40072234900F0B3F94FF40072224983 +:1010900004F138000094214B00F02CFA204BC4E9F5 +:1010A0001735204C204600F0D9FA04F114000094C2 +:1010B00000234FF400721C4900F09AF94FF40072BB +:1010C0001A4904F138000094194B00F013FA194B37 +:1010D000C4E91735184C204600F0C0FA04F114009A +:1010E00000234FF400721549009400F081F9144B6D +:1010F0004FF40072134904F13800009400F0FAF93B +:10110000114BC4E9173503B030BD00BFCC2300201C +:1011100000E1F50510250020102B00203D100008EF +:10112000004400403824002010270020102D00200B +:101130004D10000800480040A42400201029002081 +:101140005D100008102F002000780040037C30B5AF +:10115000334C002918BF0C46012B18D1314B984253 +:101160000FD1314BD3F8E82042F40032C3F8E82025 +:10117000D3F8102142F40032C3F81021D3F8103113 +:1011800005E02A4B98422FD0294B984238D022684C +:10119000036EC16D03EB52038466B3FBF2F3626826 +:1011A000150442BF23F0070503F0070343EA450394 +:1011B000CB60A36843F040034B60E36843F0010356 +:1011C0008B6042F4967343F001030B604FF0FF33E2 +:1011D0000B62510505D512F010221DD0B2F1805FCF +:1011E0001CD080F8643030BD0F4BD3F8E82042F4B7 +:1011F0008022C3F8E820D3F8102142F48022BBE714 +:10120000094BD3F8E82042F08042C3F8E820D3F835 +:10121000102142F08042AFE77F23E2E73F23E0E77F +:1012200068410008CC2300200044025838240020E4 +:10123000A42400202DE9F047C66D05463768F469FF +:101240002107346219D014F0080118BF8021E20789 +:1012500048BF41F02001A3074FF0200348BF41F0F1 +:101260004001600748BF41F4807183F31188281D55 +:10127000FFF7DCFE002383F31188E2050AD5202363 +:1012800083F311884FF40071281DFFF7CFFE002370 +:1012900083F311884FF020094FF0000A14F0200862 +:1012A00038D13B0616D54FF0200905F1380A200643 +:1012B00010D589F31188504600F050F9002836DA2D +:1012C0000821281DFFF7B2FE27F0800333600023BA +:1012D00083F31188790614D5620612D5202383F38F +:1012E0001188D5E913239A4208D12B6C33B127F02A +:1012F00040071021281DFFF799FE3760002383F374 +:101300001188E30618D5AA6E1369ABB15069BDE820 +:10131000F047184789F31188736A284695F86410D6 +:10132000194000F0B5F98AF31188F469B6E7B062A4 +:1013300088F31188F469BAE7BDE8F087F8B5154677 +:10134000826804460B46AA4200D28568A1692669D4 +:10135000761AB5420BD218462A46FFF733FDA36929 +:101360002B44A3612846A3685B1BA360F8BD0CD97E +:10137000AF1B18463246FFF725FD3A46E168304478 +:10138000FFF720FDE3683B44EBE718462A46FFF7EA +:1013900019FDE368E5E7000083689342F7B504466A +:1013A000154600D28568D4E90460361AB5420BD2DE +:1013B0002A46FFF707FD63692B4463612846A3684B +:1013C0005B1BA36003B0F0BD0DD93246AF1B01918A +:1013D000FFF7F8FC01993A46E0683144FFF7F2FC68 +:1013E000E3683B44E9E72A46FFF7ECFCE368E4E7FF +:1013F00010B50A440024C361029B8460C16002618D +:101400000362C0E90000C0E9051110BD08B5D0E9CC +:101410000532934201D1826882B9826801328260CA +:101420005A1C426119700021D0E904329A4224BF4B +:10143000C368436100F0DAFE002008BD4FF0FF30C2 +:10144000FBE7000070B5202304460E4683F31188A5 +:10145000A568A5B1A368A269013BA360531CA36161 +:1014600015782269934224BFE368A361E3690BB155 +:1014700020469847002383F31188284607E0314629 +:10148000204600F0A3FE0028E2DA85F3118870BD43 +:101490002DE9F74F04460E4617469846D0F81C90A3 +:1014A0004FF0200A8AF311884FF0000B154665B102 +:1014B0002A4631462046FFF741FF034660B94146C0 +:1014C000204600F083FE0028F1D0002383F311882A +:1014D000781B03B0BDE8F08FB9F1000F03D0019085 +:1014E0002046C847019B8BF31188ED1A1E448AF3EE +:1014F0001188DCE7C160C361009B82600362C0E9C0 +:1015000005111144C0E9000001617047F8B50446B7 +:101510000D461646202383F31188A768A7B1A36858 +:10152000013BA36063695A1C62611D70D4E90432F7 +:101530009A4224BFE3686361E3690BB12046984790 +:10154000002080F3118807E03146204600F03EFE7F +:101550000028E2DA87F31188F8BD0000D0E90523FE +:1015600010B59A4201D182687AB9826800210132AD +:1015700082605A1C82611C7803699A4224BFC36846 +:10158000836100F033FE204610BD4FF0FF30FBE7D3 +:101590002DE9F74F04460E4617469846D0F81C90A2 +:1015A0004FF0200A8AF311884FF0000B154665B101 +:1015B0002A4631462046FFF7EFFE034660B9414612 +:1015C000204600F003FE0028F1D0002383F31188A9 +:1015D000781B03B0BDE8F08FB9F1000F03D0019084 +:1015E0002046C847019B8BF31188ED1A1E448AF3ED +:1015F0001188DCE7026843681143016003B11847B2 +:10160000704700001430FFF743BF00004FF0FF3376 +:101610001430FFF73DBF00003830FFF7B9BF0000BE +:101620004FF0FF333830FFF7B3BF00001430FFF73F +:1016300009BF00004FF0FF311430FFF703BF000077 +:101640003830FFF763BF00004FF0FF323830FFF74C +:101650005DBF000000207047FFF708BD044B03602A +:1016600000234360C0E9023301230374704700BFC5 +:101670008041000810B52023044683F31188FFF74A +:1016800065FD02232374002383F3118810BD00003D +:1016900038B5C36904460D461BB904210844FFF759 +:1016A000A9FF294604F11400FFF7B0FE002806DA6E +:1016B000201D4FF48061BDE83840FFF79BBF38BD67 +:1016C000026843681143016003B118477047000086 +:1016D00013B5406B00F58054D4F8A4381A6811781B +:1016E000042914D1017C022911D11979012312890D +:1016F0008B4013420BD101A94C3002F06DF8D4F8A5 +:10170000A4480246019B2179206800F0DFF902B06D +:1017100010BD0000143001F0EFBF00004FF0FF33A8 +:10172000143001F0E9BF00004C3002F0C1B80000F5 +:101730004FF0FF334C3002F0BBB80000143001F022 +:10174000BDBF00004FF0FF31143001F0B7BF000003 +:101750004C3002F08DB800004FF0FF324C3002F0F8 +:1017600087B800000020704710B500F58054D4F809 +:10177000A4381A681178042917D1017C022914D1E0 +:101780005979012352898B4013420ED1143001F054 +:101790004FFF024648B1D4F8A4484FF44073617932 +:1017A0002068BDE8104000F07FB910BD406BFFF726 +:1017B000DBBF0000704700007FB5124B01250426F7 +:1017C000044603600023057400F184024360294647 +:1017D000C0E902330C4B0290143001934FF4407374 +:1017E000009601F001FF094B04F69442294604F1EA +:1017F0004C000294CDE900634FF4407301F0C8FF40 +:1018000004B070BDA8410008AD170008D11600084B +:101810000A68202383F311880B790B3342F82300E5 +:101820004B79133342F823008B7913B10B3342F811 +:10183000230000F58053C3F8A41802230374002387 +:1018400083F311887047000038B5037F044613B155 +:1018500090F85430ABB90125201D0221FFF730FF6D +:1018600004F114006FF00101257700F0CBFC04F1C6 +:101870004C0084F854506FF00101BDE8384000F08E +:10188000C1BC38BD10B5012104460430FFF718FF74 +:101890000023237784F8543010BD000038B5044687 +:1018A0000025143001F0B8FE04F14C00257701F05A +:1018B00087FF201D84F854500121FFF701FF2046C7 +:1018C000BDE83840FFF750BF90F8803003F0600368 +:1018D000202B06D190F881200023212A03D81F2A2B +:1018E00006D800207047222AFBD1C0E91D3303E04F +:1018F000034A426707228267C3670120704700BF1F +:101900002C22002037B500F58055D5F8A4381A6888 +:10191000117804291AD1017C022917D119790123E0 +:1019200012898B40134211D100F14C04204602F081 +:1019300007F858B101A9204601F04EFFD5F8A44898 +:101940000246019B2179206800F0C0F803B030BD49 +:1019500001F10B03F0B550F8236085B004460D4645 +:10196000FEB1202383F3118804EB8507301D082185 +:10197000FFF7A6FEFB6806F14C005B691B681BB114 +:10198000019001F037FF019803A901F025FF0246FD +:1019900048B1039B2946204600F098F8002383F3C2 +:1019A000118805B0F0BDFB685A691268002AF5D0AD +:1019B0001B8A013B1340F1D104F18002EAE70000E9 +:1019C000133138B550F82140ECB1202383F311884E +:1019D00004F58053D3F8A4281368527903EB8203EB +:1019E000DB689B695D6845B104216018FFF768FEFC +:1019F000294604F1140001F025FE2046FFF7B4FE4D +:101A0000002383F3118838BD7047000001F018B936 +:101A100001234022002110B5044600F8303BFFF7B7 +:101A2000F7F90023C4E9013310BD000010B52023ED +:101A3000044683F311882422416000210C30FFF713 +:101A4000E7F9204601F01EF902232370002383F3F7 +:101A5000118810BD70B500EB8103054650690E4634 +:101A60001446DA6018B110220021FFF7D1F9A069FD +:101A700018B110220021FFF7CBF931462846BDE806 +:101A8000704001F011BA000083682022002103F0A9 +:101A9000011310B5044683601030FFF7B9F92046F2 +:101AA000BDE8104001F08CBAF0B4012500EB8104D0 +:101AB00047898D40E4683D43A46945812360002344 +:101AC000A2606360F0BC01F0A9BA0000F0B4012587 +:101AD00000EB810407898D40E4683D43646905811A +:101AE00023600023A2606360F0BC01F01FBB000014 +:101AF00070B5022300250446242203702946C0F84D +:101B000088500C3040F8045CFFF782F9204684F8D6 +:101B1000705001F05DF963681B6823B129462046C7 +:101B2000BDE87040184770BD037880F88C300523FD +:101B3000037043681B6810B504460BB10421984735 +:101B40000023A36010BD000090F88C204368027051 +:101B50001B680BB1052118477047000070B590F85D +:101B60007030044613B1002380F8703004F1800215 +:101B7000204601F049FA63689B68B3B994F8803055 +:101B800013F0600535D00021204601F0F3FC002160 +:101B9000204601F0E3FC63681B6813B10621204670 +:101BA0009847062384F8703070BD20469847002877 +:101BB000E4D0B4F88630A26F9A4288BFA36794F944 +:101BC0008030A56F002B4FF0200380F20381002DA1 +:101BD00000F0F280092284F8702083F3118800213C +:101BE0002046D4E91D23FFF771FF002383F31188FA +:101BF000DAE794F8812003F07F0343EA022340F2FE +:101C00000232934200F0C58021D8B3F5807F48D0DE +:101C10000DD8012B3FD0022B00F09380002BB2D1C6 +:101C200004F1880262670222A267E367C1E7B3F5A5 +:101C3000817F00F09B80B3F5407FA4D194F882307F +:101C4000012BA0D1B4F8883043F0020332E0B3F5A1 +:101C5000006F4DD017D8B3F5A06F31D0A3F5C06396 +:101C6000012B90D86368204694F882205E6894F82F +:101C70008310B4F88430B047002884D04368636789 +:101C80000368A3671AE0B3F5106F36D040F602423E +:101C900093427FF478AF5C4B63670223A367002312 +:101CA000C3E794F88230012B7FF46DAFB4F888302D +:101CB00023F00203A4F88830C4E91D55E56778E7EE +:101CC000B4F88030B3F5A06F0ED194F8823020467E +:101CD00084F88A3001F0DAF863681B6813B10121D7 +:101CE00020469847032323700023C4E91D339CE753 +:101CF00004F18B0363670123C3E72378042B10D11E +:101D0000202383F311882046FFF7BEFE85F3118858 +:101D10000321636884F88B5021701B680BB1204647 +:101D2000984794F88230002BDED084F88B3004235F +:101D3000237063681B68002BD6D002212046984789 +:101D4000D2E794F8843020461D0603F00F010AD52F +:101D500001F04CF9012804D002287FF414AF2B4B7A +:101D60009AE72B4B98E701F033F9F3E794F88230C8 +:101D7000002B7FF408AF94F8843013F00F01B3D038 +:101D80001A06204602D501F00DFCADE701F0FEFB7E +:101D9000AAE794F88230002B7FF4F5AE94F88430F3 +:101DA00013F00F01A0D01B06204602D501F0E2FB84 +:101DB0009AE701F0D3FB97E7142284F8702083F3AD +:101DC00011882B462A4629462046FFF76DFE85F3EB +:101DD0001188E9E65DB1152284F8702083F311883B +:101DE00000212046D4E91D23FFF75EFEFDE60B220D +:101DF00084F8702083F311882B462A462946204612 +:101E0000FFF764FEE3E700BFD8410008D0410008B7 +:101E1000D441000838B590F870300446002B3ED00D +:101E2000063BDAB20F2A34D80F2B32D8DFE803F0A2 +:101E300037313108223231313131313131313737B7 +:101E4000856FB0F886309D4214D2C3681B8AB5FBFB +:101E5000F3F203FB12556DB9202383F311882B464F +:101E60002A462946FFF732FE85F311880A2384F8B3 +:101E700070300EE0142384F87030202383F311882F +:101E8000002320461A461946FFF70EFE002383F36F +:101E9000118838BDC36F03B198470023E7E70021DD +:101EA000204601F067FB0021204601F057FB6368E4 +:101EB0001B6813B10621204698470623D7E7000088 +:101EC00010B590F870300446142B29D017D8062B83 +:101ED00005D001D81BB110BD093B022BFBD8002156 +:101EE000204601F047FB0021204601F037FB6368E4 +:101EF0001B6813B1062120469847062319E0152BCD +:101F0000E9D10B2380F87030202383F3118800235C +:101F10001A461946FFF7DAFD002383F31188DAE742 +:101F2000C3689B695B68002BD5D1C36F03B1984729 +:101F3000002384F87030CEE7024B0022C3E900335F +:101F40009A60704710310020002382680374054BAB +:101F50001B6899689142FBD25A6803604260106026 +:101F6000586070471031002008B5202383F3118892 +:101F7000037C032B05D0042B0DD02BB983F31188E0 +:101F800008BD436900221A604FF0FF334361FFF739 +:101F9000DBFF0023F2E7D0E9003213605A60F3E779 +:101FA000002382680374054B1B6899689142FBD833 +:101FB0005A6803604260106058607047103100201A +:101FC000054B196908741868026853601A60186133 +:101FD00001230374FEF7FAB9103100204B1C30B511 +:101FE000044687B00A4D10D02B6901A8094A00F0B9 +:101FF00025F92046FFF7E4FF049B13B101A800F088 +:1020000059F92B69586907B030BDFFF7D9FFF8E7D8 +:1020100010310020691F000838B50C4D044641619D +:102020002B6981689A68914203D8BDE83840FFF770 +:102030008BBF1846FFF7B4FF01232C6101462374C0 +:102040002046BDE83840FEF7C1B900BF103100207E +:10205000044B1A681B6990689B68984294BF0020E3 +:10206000012070471031002010B5084C236820690A +:102070001A6854602260012223611A74FFF790FFEE +:1020800001462069BDE81040FEF7A0B910310020DC +:1020900008B5FFF7DDFF18B1BDE80840FFF7E4BF62 +:1020A00008BD0000FFF7E0BFFEE7000010B50C4CD4 +:1020B000FFF742FF00F0B4F880220A49204600F002 +:1020C0003BF8012344F8180C037400F097FC00233C +:1020D00083F3118862B60448BDE8104000F04CB8A4 +:1020E00038310020DC410008EC41000800F01CB948 +:1020F000EFF3118020B9EFF30583202282F31188DA +:102100007047000010B530B9EFF30584C4F308043C +:1021100014B180F3118810BDFFF7BAFF84F3118862 +:10212000F9E70000034A516853685B1A9842FBD8EC +:10213000704700BF001000E08260022202827047F8 +:102140008368A3F17C0243F80C2C026943F83C2C11 +:10215000426943F8382C074A43F81C2CC268A3F1A3 +:10216000180043F8102C022203F8082C002203F870 +:10217000072C7047E503000810B5202383F311886E +:10218000FFF7DEFF00210446FFF746FF002383F33D +:102190001188204610BD0000024B1B6958610F20BA +:1021A000FFF70EBF10310020202383F31188FFF7C3 +:1021B000F3BF000008B50146202383F311880820EF +:1021C000FFF70CFF002383F3118808BD49B1064BCC +:1021D00042681B6918605A60136043600420FFF76F +:1021E000FDBE4FF0FF307047103100200368984269 +:1021F00006D01A680260506018465961FFF7A4BE05 +:102200007047000038B504460D462068844200D16E +:1022100038BD036823605C604561FFF795FEF4E715 +:10222000054B4FF0FF3103F11402C3E905220022F0 +:10223000C3E90712704700BF1031002070B51C4E73 +:1022400005460C46C0E9032301F0B0FB334653F8C2 +:10225000142F9A420DD130620A2C2CBF00190A307B +:102260002A60C5E90124C6E90555BDE8704001F0C2 +:1022700087BB316A431AE31838BF1C469368A342F0 +:1022800002D9081901F08CFB73699A6894420CD842 +:102290005A68AC602B606A6015609A685D60121BBA +:1022A0009A604FF0FF33F36170BDA41A1B68ECE72E +:1022B0001031002038B51B4C636998420DD08168FD +:1022C000D0E9003213605A600022C2609A680A4462 +:1022D0009A604FF0FF33E36138BD03682246002166 +:1022E00042F8143F93425A60C16003D1BDE83840C0 +:1022F00001F050BB9A688168256A0A449A6001F02F +:1023000055FB6369411B9A688A42E5D9AB181D1ACF +:10231000206A092D98BF01F10A02BDE83840104437 +:1023200001F03EBB103100202DE9F041184C002790 +:1023300004F11406656901F039FB236AAA68C11A21 +:102340008A4215D81344D5F80C802362D5E90032AF +:1023500013605A606369EF60B34201D101F01AFB68 +:1023600087F311882869C047202383F31188E1E7A8 +:102370006169B14209D013441B1ABDE8F0410A2B30 +:102380002CBFC0180A3001F00BBBBDE8F08100BFC4 +:102390001031002000207047FEE700007047000069 +:1023A0004FF0FF307047000002290CD0032904D001 +:1023B0000129074818BF00207047032A05D805489F +:1023C00000EBC2007047044870470020704700BF10 +:1023D000D44200083C2200208842000870B59AB020 +:1023E00005460846144601A900F0C2F801A8FEF708 +:1023F00007FD431C0022C6B25B001046C5E900344D +:1024000023700323023404F8013C01ABD1B202343F +:102410008E4201D81AB070BD13F8011B013204F8C6 +:10242000010C04F8021CF1E708B5202383F311889E +:102430000348FFF767FA002383F3118808BD00BF44 +:10244000C832002090F8803003F01F02012A07D123 +:1024500090F881200B2A03D10023C0E91D3315E039 +:1024600003F06003202B08D1B0F884302BB990F82A +:102470008120212A03D81F2A04D8FFF725BA222A4F +:10248000EBD0FAE7034A426707228267C36701205D +:10249000704700BF3322002007B5052917D8DFE8B1 +:1024A00001F0191603191920202383F31188104A0B +:1024B00001210190FFF7CEFA019802210D4AFFF7A2 +:1024C000C9FA0D48FFF7EAF9002383F3118803B036 +:1024D0005DF804FB202383F311880748FFF7B4F964 +:1024E000F2E7202383F311880348FFF7CBF9EBE7EA +:1024F000284200084C420008C832002038B50C4D74 +:102500000C4C2A460C4904F10800FFF767FF05F15F +:10251000CA0204F110000949FFF760FF05F5CA720D +:1025200004F118000649BDE83840FFF757BF00BF67 +:10253000A04B00203C220020044200080E4200086C +:102540001D42000870B5044608460D46FEF758FCCB +:10255000C6B22046013403780BB9184670BD324626 +:102560002946FEF739FC0028F3D10120F6E70000E8 +:102570002DE9F04705460C46FEF742FC2B49C6B252 +:102580002846FFF7DFFF08B10736F6B2284928468C +:10259000FFF7D8FF08B11036F6B2632E0BD8DFF87C +:1025A0008C80DFF88C90234FDFF894A02E7846B90A +:1025B0002670BDE8F08729462046BDE8F04701F0C7 +:1025C000B5BD252E2ED1072241462846FEF704FC34 +:1025D00070B9194B224603F10C0153F8040B8B42DE +:1025E00042F8040BF9D11B8807350E341380DDE760 +:1025F000082249462846FEF7EFFB98B9A21C0F4B6C +:10260000197802320909C95D02F8041C13F8011B8C +:1026100001F00F015345C95D02F8031CF0D11834D5 +:102620000835C3E7013504F8016BBFE7F442000841 +:102630001D4200080B430008FC42000800E8F11F9F +:102640000CE8F11FBFF34F8F044B1A695107FCD1FF +:10265000D3F810215207F8D1704700BF0020005274 +:1026600008B50D4B1B78ABB9FFF7ECFF0B4BDA68E5 +:10267000D10704D50A4A5A6002F188325A60D3F869 +:102680000C21D20706D5064AC3F8042102F188328C +:10269000C3F8042108BD00BFFE4D002000200052F9 +:1026A0002301674508B5114B1B78F3B9104B1A6924 +:1026B000510703D5DA6842F04002DA60D3F81021FE +:1026C000520705D5D3F80C2142F04002C3F80C2183 +:1026D000FFF7B8FF064BDA6842F00102DA60D3F880 +:1026E0000C2142F00102C3F80C2108BDFE4D002070 +:1026F000002000520F289ABF00F58060400400209F +:10270000704700004FF40030704700001020704701 +:102710000F2808B50BD8FFF7EDFF00F5003302686E +:10272000013204D104308342F9D1012008BD0020D8 +:10273000FCE700000F2870B5054645D8FFF7D8FC28 +:10274000224CFFF77FFF0646FFF78AFF4FF0FF336B +:10275000072D6361C4F8143120D82361FFF772FF9D +:102760002B0243F02403E360E36843F08003E3605B +:1027700023695A07FCD42846FFF764FF4FF4003161 +:10278000FFF7B8FF00F002F93046FFF78BFFFFF7C5 +:10279000B9FC2846BDE87040FFF7BABFC4F8103155 +:1027A000FFF750FFA5F108031B0243F02403C4F810 +:1027B0000C31D4F80C3143F08003C4F80C31D4F858 +:1027C00010315B07FBD4D6E7002070BD002000521B +:1027D0002DE9F84F40EA020305460C461746D80695 +:1027E00002D00020BDE8F88F27F01F07DFF8D4B033 +:1027F000FFF736FF2744BC4203D10120FFF752FF09 +:10280000F0E720222946204601F080FC10B920354F +:102810002034F0E72B4605F120021E68711CE0D140 +:1028200004339A42F9D1FFF763FC05F17843234A58 +:10283000B3F5801F224B28BF9A4603F1040338BF2B +:102840009046A2F1080228BF9846A3F108033ABFB8 +:102850009146DA469946FFF7F5FEC8F80060A5EB09 +:10286000040CD9F8002004F11C0142F00202C9F85E +:102870000020221FDAF8006016F00506FAD152F89F +:10288000043F8A424CF80230F4D1BFF34F8FFFF778 +:10289000D9FE4FF0FF32C8F80020D9F8002022F00E +:1028A0000202C9F80020FFF72DFC2022214628460D +:1028B00001F02CFC0028AAD030469FE714200052DB +:1028C000102100521020005210B5084C237828B176 +:1028D0001BB9FFF7C5FE0123237010BD002BFCD0F0 +:1028E0002070BDE81040FFF7DDBE00BFFE4D0020A8 +:1028F0000244074BD2B210B5904200D110BD441C27 +:1029000000B253F8200041F8040BE0B2F4E700BF36 +:10291000504000580E4B30B51C6F240405D41C6F7A +:102920001C671C6F44F400441C670A4C0244236873 +:10293000D2B243F480732360074B904200D130BD84 +:10294000441C51F8045B00B243F82050E0B2F4E7B5 +:1029500000440258004802585040005807B5012270 +:1029600001A90020FFF7C4FF019803B05DF804FB44 +:1029700013B50446FFF7F2FFA04205D0012201A9DA +:1029800000200194FFF7C6FF02B010BD0144BFF361 +:102990004F8F064B884204D3BFF34F8FBFF36F8F27 +:1029A0007047C3F85C022030F4E700BF00ED00E0A0 +:1029B000034B1A681AB9034AD2F8D0241A60704738 +:1029C000004E00200040025808B5FFF7F1FF024B0F +:1029D0001868C0F3806008BD004E0020EFF3098343 +:1029E000054968334A6B22F001024A6383F3098880 +:1029F000002383F31188704700EF00E0202080F36C +:102A0000118862B60D4B0E4AD96821F4E0610904C1 +:102A1000090C0A430B49DA60D3F8FC2042F08072BB +:102A2000C3F8FC20084AC2F8B01F116841F0010148 +:102A300011601022DA7783F82200704700ED00E081 +:102A40000003FA0555CEACC5001000E0202310B5F8 +:102A500083F311880E4B5B6813F4006314D0F1EE1E +:102A6000103AEFF309844FF08073683CE361094B3F +:102A7000DB6B236684F30988FFF7EAFA10B1064B93 +:102A8000A36110BD054BFBE783F31188F9E700BF95 +:102A900000ED00E000EF00E0F7030008FA03000893 +:102AA00070B5BFF34F8FBFF36F8F1A4A0021C2F882 +:102AB0005012BFF34F8FBFF36F8F536943F400334E +:102AC0005361BFF34F8FBFF36F8FC2F88410BFF312 +:102AD0004F8FD2F8803043F6E074C3F3C900C3F3DC +:102AE0004E335B0103EA0406014646EA817501396B +:102AF000C2F86052F9D2203B13F1200FF2D1BFF39C +:102B00004F8F536943F480335361BFF34F8FBFF34B +:102B10006F8F70BD00ED00E0FEE700000A4B0B4830 +:102B20000B4A90420BD30B4BC11EDA1C121A22F037 +:102B300003028B4238BF00220021FEF769B953F827 +:102B4000041B40F8041BECE7EC440008D44F0020C1 +:102B5000D44F0020D44F00207047000070B5D0E95A +:102B6000244300224FF0FF359E6804EB42135101CD +:102B7000D3F80009002805DAD3F8000940F08040B6 +:102B8000C3F80009D3F8000B002805DAD3F8000BCE +:102B900040F08040C3F8000B013263189642C3F83E +:102BA0000859C3F8085BE0D24FF00113C4F81C3891 +:102BB00070BD000000EB8103D3F80CC02DE9F04399 +:102BC000DCF814204E1CD0F89050D2F800E005EB51 +:102BD000063605EB4118506870450AD30122D5F836 +:102BE000343802FA01F123EA0101C5F83418BDE8CE +:102BF000F083AEEB0003BCF81040A34228BF23468D +:102C0000D8F81849A4B2B3EB840FF0D89468A4F1B3 +:102C1000040959F8047F3760A4EB09071F44042F07 +:102C2000F7D81C44034494605360D4E7890141F011 +:102C30002001016103699B06FCD41220FFF772BAE0 +:102C400010B50A4C2046FEF7E3FE094BC4F890305D +:102C5000084BC4F89430084C2046FEF7D9FE074BC9 +:102C6000C4F89030064BC4F8943010BD044E0020D8 +:102C70000000084040430008A04E0020000004402F +:102C80004C43000870B503780546012B5DD1494BD4 +:102C9000D0F89040984259D1474B0E216520D3F887 +:102CA000D82042F00062C3F8D820D3F8002142F0C7 +:102CB0000062C3F80021D3F80021D3F8802042F04D +:102CC0000062C3F88020D3F8802022F00062C3F8AD +:102CD0008020D3F8803000F071FC384BE360384B33 +:102CE000C4F800380023D5F89060C4F8003EC02333 +:102CF00023604FF40413A3633369002BFCDA012330 +:102D00000C203361FFF70EFA3369DB07FCD4122085 +:102D1000FFF708FA3369002BFCDA00262846A66084 +:102D2000FFF71CFF6B68C4F81068DB68C4F8146810 +:102D3000C4F81C68002B3AD1224BA3614FF0FF333B +:102D40006361A36843F00103A36070BD1E4B98420A +:102D5000C8D1194B0E214D20D3F8D82042F0007273 +:102D6000C3F8D820D3F8002142F00072C3F8002144 +:102D7000D3F80021D3F8802042F00072C3F88020FD +:102D8000D3F8802022F00072C3F88020D3F880208E +:102D9000D3F8D82022F08062C3F8D820D3F80021DD +:102DA00022F08062C3F80021D3F8003193E7074B8B +:102DB000C3E700BF044E0020004402584014004006 +:102DC00003002002003C30C0A04E0020083C30C070 +:102DD000F8B5D0F89040054600214FF00066204637 +:102DE000FFF724FFD5F8941000234FF001128F68ED +:102DF0004FF0FF30C4F83438C4F81C2804EB4312F9 +:102E000001339F42C2F80069C2F8006BC2F808099A +:102E1000C2F8080BF2D20B68D5F89020C5F89830AC +:102E2000636210231361166916F01006FBD112209D +:102E3000FFF778F9D4F8003823F4FE63C4F80038BB +:102E4000A36943F4402343F01003A3610923C4F8AA +:102E50001038C4F814380B4BEB604FF0C043C4F883 +:102E6000103B094BC4F8003BC4F81069C4F80039A2 +:102E7000D5F8983003F1100243F48013C5F8982078 +:102E8000A362F8BD1C43000840800010D0F89020D9 +:102E900090F88A10D2F8003823F4FE6343EA011355 +:102EA000C2F80038704700002DE9F84300EB8103B9 +:102EB000D0F890500C468046DA680FFA81F9480144 +:102EC000166806F00306731E022B05EB41134FF044 +:102ED000000194BFB604384EC3F8101B4FF0010137 +:102EE00004F1100398BF06F1805601FA03F39169CB +:102EF00098BF06F5004600293AD0578A04F15801D8 +:102F0000374349016F50D5F81C180B430021C5F811 +:102F10001C382B180127C3F81019A7405369611EEC +:102F20009BB3138A928B9B08012A88BF5343D8F81E +:102F30009820981842EA034301F140022146C8F85C +:102F40009800284605EB82025360FFF76FFE08EBFE +:102F50008900C3681B8A43EA845348341E436401D2 +:102F60002E51D5F81C381F43C5F81C78BDE8F883EE +:102F700005EB4917D7F8001B21F40041C7F8001BE7 +:102F8000D5F81C1821EA0303C0E704F13F030B4AFC +:102F90002846214605EB83035A60FFF747FE05EB01 +:102FA0004910D0F8003923F40043C0F80039D5F8AF +:102FB0001C3823EA0707D7E700800010000400024E +:102FC000D0F894201268C0F89820FFF7C7BD000021 +:102FD0005831D0F8903049015B5813F4004004D0C8 +:102FE00013F4001F0CBF0220012070474831D0F8B5 +:102FF000903049015B5813F4004004D013F4001FD3 +:103000000CBF02200120704700EB8101CB68196AD8 +:103010000B6813604B6853607047000000EB81033E +:1030200030B5DD68AA691368D36019B9402B84BF35 +:10303000402313606B8A1468D0F890201C4402EB84 +:103040004110013C09B2B4FBF3F46343033323F0B2 +:10305000030343EAC44343F0C043C0F8103B2B686A +:1030600003F00303012B0ED1D2F8083802EB411014 +:1030700013F4807FD0F8003B14BF43F0805343F03B +:103080000053C0F8003B02EB4112D2F8003B43F082 +:103090000443C2F8003B30BD2DE9F041D0F8906008 +:1030A00005460C4606EB4113D3F8087B3A07C3F8F4 +:1030B000087B08D5D6F814381B0704D500EB81032C +:1030C000DB685B689847FA071FD5D6F81438DB072A +:1030D0001BD505EB8403D968CCB98B69488A5A683B +:1030E000B2FBF0F600FB16228AB91868DA68904243 +:1030F0000DD2121AC3E90024202383F3118821463C +:103100002846FFF78BFF84F31188BDE8F081012387 +:1031100003FA04F26B8923EA02036B81CB68002B6C +:10312000F3D021462846BDE8F041184700EB810363 +:103130004A0170B5DD68D0F890306C692668E660A9 +:1031400056BB1A444FF40020C2F810092A6802F056 +:103150000302012A0AB20ED1D3F8080803EB421485 +:1031600010F4807FD4F8000914BF40F0805040F084 +:103170000050C4F8000903EB4212D2F8000940F0F5 +:103180000440C2F800090122D3F8340802FA01F120 +:103190000143C3F8341870BD19B9402E84BF4020D4 +:1031A000206020681A442E8A8419013CB4FBF6F48E +:1031B00040EAC44040F00050C6E700002DE9F0416D +:1031C000D0F8906004460D4606EB4113D3F8087919 +:1031D000C3F80879FB071CD5D6F81038DA0718D5DC +:1031E00000EB8103D3F80CC0DCF81430D3F800E016 +:1031F000DA6896451BD2A2EB0E024FF000081A6067 +:10320000C3F80480202383F31188FFF78FFF88F32E +:1032100011883B0618D50123D6F83428AB40134259 +:1032200012D029462046BDE8F041FFF7C3BC012378 +:1032300003FA01F2038923EA02030381DCF8083070 +:10324000002BE6D09847E4E7BDE8F0812DE9F84F80 +:10325000D0F8905004466E69AB691E4016F4805851 +:103260006E6103D0BDE8F84FFEF742BC002E12DAC3 +:10327000D5F8003E9F0705D0D5F8003E23F00303A4 +:10328000C5F8003ED5F80438204623F00103C5F800 +:103290000438FEF759FC300505D52046FFF75EFCE3 +:1032A0002046FEF741FCB1040CD5D5F8083813F0E0 +:1032B000060FEB6823F470530CBF43F4105343F430 +:1032C000A053EB60320704D56368DB680BB120467E +:1032D0009847F30200F1BA80B70226D5D4F890904F +:1032E00000274FF0010A09EB4712D2F8003B03F424 +:1032F0004023B3F5802F11D1D2F8003B002B0DDA1B +:1033000062890AFA07F322EA0303638104EB870365 +:10331000DB68DB6813B13946204698470137D4F89B +:103320009430FFB29B689F42DDD9F00619D5D4F8DE +:103330009000026AC2F30A1702F00F0302F4F012BF +:10334000B2F5802F00F0CC80B2F5402F09D104EB0C +:103350008303002200F58050DB681B6A974240F02F +:10336000B2803003D5F8185835D5E90303D50021CC +:103370002046FFF791FEAA0303D501212046FFF75F +:103380008BFE6B0303D502212046FFF785FE2F033A +:1033900003D503212046FFF77FFEE80203D5042171 +:1033A0002046FFF779FEA90203D505212046FFF745 +:1033B00073FE6A0203D506212046FFF76DFE2B023D +:1033C00003D507212046FFF767FEEF0103D508214B +:1033D0002046FFF761FE700340F1A980E90703D59D +:1033E00000212046FFF7EAFEAA0703D50121204667 +:1033F000FFF7E4FE6B0703D502212046FFF7DEFE50 +:103400002F0703D503212046FFF7D8FEEE0603D58C +:1034100004212046FFF7D2FEA80603D50521204649 +:10342000FFF7CCFE690603D506212046FFF7C6FE4E +:103430002A0603D507212046FFF7C0FEEB0576D507 +:1034400020460821BDE8F84FFFF7B8BED4F89090A9 +:1034500000274FF0010AD4F894305FFA87FB9B688D +:103460009B453FF639AF09EB4B13D3F8002902F423 +:103470004022B2F5802F24D1D3F80029002A20DA87 +:10348000D3F8002942F09042C3F80029D3F800296C +:10349000002AFBDB5946D4F89000FFF7C7FB2289CE +:1034A0000AFA0BF322EA0303238104EB8B03DB68A4 +:1034B0009B6813B159462046984759462046FFF766 +:1034C00079FB0137C7E7910701D1D0F80080072ABF +:1034D00002F101029CBF03F8018B4FEA18283DE777 +:1034E00004EB830300F58050DA68D2F818C0DCF8EA +:1034F0000820DCE9001CA1EB0C0C00218F4208D154 +:10350000DB689B699A683A449A605A683A445A6000 +:1035100027E711F0030F01D1D0F800808C4501F1AD +:10352000010184BF02F8018B4FEA1828E6E7BDE8E5 +:10353000F88F000008B50348FFF788FEBDE8084093 +:10354000FFF784BA044E002008B50348FFF77EFE5B +:10355000BDE80840FFF77ABAA04E0020D0F89030BE +:1035600003EB4111D1F8003B43F40013C1F8003BD9 +:1035700070470000D0F8903003EB4111D1F80039CA +:1035800043F40013C1F8003970470000D0F89030C0 +:1035900003EB4111D1F8003B23F40013C1F8003BC9 +:1035A00070470000D0F8903003EB4111D1F800399A +:1035B00023F40013C1F8003970470000090100F13D +:1035C0006043012203F56143C9B283F8001300F0A0 +:1035D0001F039A4043099B0003F1604303F56143D5 +:1035E000C3F880211A60704730B50433039C017220 +:1035F000002104FB0325C160C0E90653049B03635B +:10360000059BC0E90000C0E90422C0E90842C0E906 +:103610000A11436330BD00000022416AC260C0E964 +:103620000411C0E90A226FF00101FEF7EBBD0000B2 +:10363000D0E90432934201D1C2680AB9181D70471B +:1036400000207047036919600021C2680132C2601E +:10365000C269134482699342036124BF436A0361D0 +:10366000FEF7C4BD38B504460D46E3683BB1626958 +:103670000020131D1268A3621344E36207E0237A5B +:1036800033B929462046FEF7A1FD0028EDDA38BD02 +:103690006FF00100FBE70000C368C269013BC36033 +:1036A0004369134482699342436124BF436A43617F +:1036B00000238362036B03B11847704770B5202362 +:1036C000044683F31188866A3EB9FFF7CBFF0546AF +:1036D00018B186F31188284670BDA36AE26A13F810 +:1036E000015B9342A36202D32046FFF7D5FF00237C +:1036F00083F31188EFE700002DE9F84F04460E46EA +:10370000174698464FF0200989F311880025AA46EC +:10371000D4F828B0BBF1000F09D141462046FFF78D +:10372000A1FF20B18BF311882846BDE8F88FD4E9BA +:103730000A12A7EB050B521A934528BF9346BBF11B +:10374000400F1BD9334601F1400251F8040B91425E +:1037500043F8040BF9D1A36A403640354033A362E5 +:10376000D4E90A239A4202D32046FFF795FF8AF351 +:103770001188BD42D8D289F31188C9E730465A462C +:10378000FDF720FBA36A5E445D445B44A362E7E768 +:1037900010B5029C0433017204FB0321C460C0E92C +:1037A00006130023C0E90A33039B0363049BC0E9AB +:1037B0000000C0E90422C0E90842436310BD0000D4 +:1037C000026A6FF00101C260426AC0E9042200226D +:1037D000C0E90A22FEF716BDD0E904239A4201D1BE +:1037E000C26822B9184650F8043B0B6070470020AD +:1037F00070470000C3680021C2690133C360436998 +:10380000134482699342436124BF436A4361FEF7D4 +:10381000EDBC000038B504460D46E3683BB12369B2 +:1038200000201A1DA262E2691344E36207E0237AD2 +:1038300033B929462046FEF7C9FC0028EDDA38BD29 +:103840006FF00100FBE7000003691960C268013AEC +:10385000C260C269134482699342036124BF436A10 +:10386000036100238362036B03B1184770470000B4 +:1038700070B520230D460446114683F31188866AED +:103880002EB9FFF7C7FF10B186F3118870BDA36A88 +:103890001D70A36AE26A01339342A36204D3E16913 +:1038A00020460439FFF7D0FF002080F31188EDE7B0 +:1038B0002DE9F84F04460D46904699464FF0200AF0 +:1038C0008AF311880026B346A76A4FB949462046B5 +:1038D000FFF7A0FF20B187F311883046BDE8F88FCD +:1038E000D4E90A073A1AA8EB0607974228BF1746F9 +:1038F000402F1BD905F1400355F8042B9D4240F899 +:10390000042BF9D1A36A40364033A362D4E90A23D9 +:103910009A4204D3E16920460439FFF795FF8BF3FF +:1039200011884645D9D28AF31188CDE729463A460F +:10393000FDF748FAA36A3D443E443B44A362E5E7F1 +:10394000D0E904239A4217D1C3689BB1836A8BB133 +:10395000043B9B1A0ED01360C368013BC360C3696C +:103960001A4483699A42026124BF436A03610023B7 +:1039700083620123184670470023FBE700F0DAB8A2 +:10398000034B002258631A610222DA60704700BFBD +:10399000000C0040014B0022DA607047000C004030 +:1039A000014B5863704700BF000C0040014B586A40 +:1039B000704700BF000C00404B6843608B68836019 +:1039C000CB68C3600B6943614B6903628B694362D7 +:1039D0000B6803607047000008B53C4B40F2FF7174 +:1039E0003B48D3F888200A43C3F88820D3F88820BE +:1039F00022F4FF6222F00702C3F88820D3F888205F +:103A0000D3F8E0200A43C3F8E020D3F808210A43A2 +:103A1000C3F808212F4AD3F808311146FFF7CCFF2D +:103A200000F5806002F11C01FFF7C6FF00F5806021 +:103A300002F13801FFF7C0FF00F5806002F1540188 +:103A4000FFF7BAFF00F5806002F17001FFF7B4FFE5 +:103A500000F5806002F18C01FFF7AEFF00F5806099 +:103A600002F1A801FFF7A8FF00F5806002F1C40190 +:103A7000FFF7A2FF00F5806002F1E001FFF79CFF75 +:103A800000F5806002F1FC01FFF796FF02F58C71F2 +:103A900000F58060FFF790FF00F000F90E4BD3F8BF +:103AA000902242F00102C3F89022D3F8942242F00F +:103AB0000102C3F894220522C3F898204FF0605207 +:103AC000C3F89C20054AC3F8A02008BD0044025852 +:103AD000000002585843000800ED00E01F000803F2 +:103AE00008B500F0F3FAFEF7E1FA0F4BD3F8DC204B +:103AF00042F04002C3F8DC20D3F8042122F0400257 +:103B0000C3F80421D3F80431084B1A6842F00802C4 +:103B10001A601A6842F004021A60FEF749FFBDE815 +:103B20000840FEF7EBBC00BF0044025800180248F2 +:103B300070470000114BD3F8E82042F00802C3F8A8 +:103B4000E820D3F8102142F00802C3F810210C4AF3 +:103B5000D3F81031D36B43F00803D363C722094B6A +:103B60009A624FF0FF32DA6200229A615A63DA6099 +:103B70005A6001225A611A60704700BF004402581F +:103B80000010005C000C0040094A08B51169D368B8 +:103B90000B40D9B29B076FEA0101116107D52023C1 +:103BA00083F31188FEF7A2FA002383F3118808BD7E +:103BB000000C0040384B4FF0FF31D3F88020C3F8A1 +:103BC0008010D3F880200022C3F88020D3F8800032 +:103BD000D3F88400C3F88410D3F88400C3F8842099 +:103BE000D3F88400D86F40F0FF4040F4FF0040F469 +:103BF0003F5040F03F00D867D86F20F0FF4020F4DE +:103C0000FF0020F43F5020F03F00D867D86FD3F872 +:103C100088006FEA40506FEA5050C3F88800D3F82C +:103C20008800C0F30A00C3F88800D3F88800D3F8EE +:103C30009000C3F89010D3F89000C3F89020D3F808 +:103C40009000D3F89400C3F89410D3F89400C3F80C +:103C50009420D3F89400D3F89800C3F89810D3F8C0 +:103C60009800C3F89820D3F89800D3F88C00C3F8D4 +:103C70008C10D3F88C00C3F88C20D3F88C00D3F8C8 +:103C80009C00C3F89C10D3F89C10C3F89C20D3F878 +:103C90009C3000F0E7B900BF00440258614B01229C +:103CA000C3F80821604BD3F8F42042F00202C3F8B5 +:103CB000F420D3F81C2142F00202C3F81C21042294 +:103CC000D3F81C31594BDA605A689104FCD5584A34 +:103CD0001A6001229A60574ADA6000221A614FF492 +:103CE00040429A61514B9A699204FCD51A6842F499 +:103CF00080721A604C4B1A6F12F4407F04D04FF45C +:103D000080321A6700221A671A6842F001021A60AC +:103D1000454B1A685007FCD500221A611A6912F047 +:103D20003802FBD1012119604FF0804159605A6778 +:103D3000414ADA62414A1A611A6842F480321A60D2 +:103D4000394B1A689103FCD51A6842F480521A6004 +:103D50001A689204FCD53A4A3A499A6200225A6398 +:103D600019633949DA6399635A64384A1A64384ADC +:103D7000DA621A6842F0A8521A602B4B1A6802F0F5 +:103D80002852B2F1285FF9D148229A614FF4886233 +:103D9000DA6140221A622F4ADA644FF080521A65C3 +:103DA0002D4A5A652D4A9A6532232D4A13601368AD +:103DB00003F00F03022BFAD11B4B1A6942F00302E6 +:103DC0001A611A6902F03802182AFAD1D3F8DC20F5 +:103DD00042F00052C3F8DC20D3F8042142F0005234 +:103DE000C3F80421D3F80421D3F8DC2042F0804248 +:103DF000C3F8DC20D3F8042142F08042C3F8042148 +:103E0000D3F80421D3F8DC2042F00042C3F8DC20D0 +:103E1000D3F8042142F00042C3F80421D3F804315E +:103E2000704700BF0080005100440258004802580B +:103E300000C000F0040000010000FF0100889008AD +:103E400032206000630209011D02040047040508D6 +:103E5000FD0BFF01200000200010E0000001010028 +:103E6000002000524FF0B04208B5D2F8883003F07D +:103E70000103C2F8883023B1044A13680BB15068BB +:103E80009847BDE80840FEF7E1BD00BF544F002051 +:103E90004FF0B04208B5D2F8883003F00203C2F800 +:103EA000883023B1044A93680BB1D0689847BDE8C5 +:103EB0000840FEF7CBBD00BF544F00204FF0B0428A +:103EC00008B5D2F8883003F00403C2F8883023B173 +:103ED000044A13690BB150699847BDE80840FEF7E2 +:103EE000B5BD00BF544F00204FF0B04208B5D2F826 +:103EF000883003F00803C2F8883023B1044A93697C +:103F00000BB1D0699847BDE80840FEF79FBD00BFE0 +:103F1000544F00204FF0B04208B5D2F8883003F07B +:103F20001003C2F8883023B1044A136A0BB1506AF7 +:103F30009847BDE80840FEF789BD00BF544F0020F8 +:103F40004FF0B04310B5D3F8884004F47872C3F84A +:103F50008820A30604D5124A936A0BB1D06A984709 +:103F6000600604D50E4A136B0BB1506B98472106BF +:103F700004D50B4A936B0BB1D06B9847E20504D57F +:103F8000074A136C0BB1506C9847A30504D5044A3B +:103F9000936C0BB1D06C9847BDE81040FEF756BD4E +:103FA000544F00204FF0B04310B5D3F8884004F4CC +:103FB0007C42C3F88820620504D5164A136D0BB104 +:103FC000506D9847230504D5124A936D0BB1D06DFF +:103FD0009847E00404D50F4A136E0BB1506E984712 +:103FE000A10404D50B4A936E0BB1D06E98476204BE +:103FF00004D5084A136F0BB1506F9847230404D5BA +:10400000044A936F0BB1D06F9847BDE81040FEF79C +:104010001DBD00BF544F002008B50348FDF70AF945 +:10402000BDE80840FEF712BDCC23002008B50348C8 +:10403000FDF700F9BDE80840FEF708BD3824002070 +:1040400008B50348FDF7F6F8BDE80840FEF7FEBCEA +:10405000A424002008B5FFF797FDBDE80840FEF74F +:10406000F5BC0000062108B50846FFF7A7FA0621AF +:104070000720FFF7A3FA06210820FFF79FFA062181 +:104080000920FFF79BFA06210A20FFF797FA06217D +:104090001720FFF793FA06212820FFF78FFA09214E +:1040A0007A20FFF78BFA07213220FFF787FA0C21DD +:1040B0002620FFF783FA0C212720FFF77FFA0C2137 +:1040C0005220BDE80840FFF779BA000008B5FFF7B5 +:1040D00071FD00F00DF8FDF7BFFAFDF797FCFDF755 +:1040E00069FBFFF725FDBDE80840FFF747BC00006E +:1040F0000023054A19460133102BC2E9001102F1D1 +:104100000802F8D1704700BF544F002010B50139A4 +:104110000244904201D1002005E0037811F8014FDC +:10412000A34201D0181B10BD0130F2E7034611F87D +:10413000012B03F8012B002AF9D1704753544D335A +:104140003248373F3F3F0053544D333248373433C2 +:104150002F37353300000000C8320020CC23002068 +:1041600038240020A4240020009600000000000055 +:10417000000000000000000000000000000000003F +:1041800000000000211600080D160008491600085E +:1041900035160008411600082D16000819160008EB +:1041A0000516000855160008000000003117000829 +:1041B0001D17000859170008451700085117000877 +:1041C0003D17000829170008151700086517000893 +:1041D0000000000001000000000000006D61696E39 +:1041E0000000000069646C6500000000E441000804 +:1041F00050310020C832002001000000A920000832 +:10420000000000004375626550696C6F740043756F +:1042100062654F72616E67652B2D424C00255345D8 +:104220005249414C2500000002000000000000003F +:1042300051190008C119000840004000704B0020CF +:10424000804B00200200000000000000030000007E +:1042500000000000091A0008000000001000000023 +:10426000904B002000000000010000000000000052 +:10427000044E00200101020099240008A92300082F +:10428000452400082924000843000000904200084B +:1042900009024300020100C03209040000010202C9 +:1042A000010005240010010524010001042402027C +:1042B0000524060001070582030800FF0904010028 +:1042C000020A000000070501024000000705810204 +:1042D0004000000012000000DC4200081201100142 +:1042E00002000040AE2D5810000201020301000040 +:1042F0000403090425424F41524425004375626579 +:104300004F72616E6765506C7573003031323334B3 +:1043100035363738394142434445460000000000F5 +:104320005D1B0008151E0008C11E0008400040006B +:104330003C4F00203C4F0020010000004C4F00206B +:1043400080000000400100000800000000010000A3 +:1043500000040000080000000000812A00000000A6 +:10436000AAAAAAAA00000024FFFE00000000000084 +:1043700000A00A000001000000000000AAAAAAAAEA +:1043800000000000FFFF000000000000000000002F +:104390001400005400000000AAAAAAAA14000054A5 +:1043A000FFFF0000000000000000000000681A008D +:1043B00000000000AAAA8AAA00541500FFFF00000E +:1043C000000070077700000040810200000000003C +:1043D000AAAAAAAA00410100F7FF0000000000708D +:1043E000070000000000000000000000AAAAAAAA1E +:1043F00000000000FFFF00000000000000000000BF +:104400000000000000000000AAAAAAAA0000000004 +:10441000FFFF00000000000000000000000000009E +:1044200000000000AAAAAAAA00000000FFFF0000E6 +:10443000000000000000000000000000000000007C +:10444000AAAAAAAA00000000FFFF000000000000C6 +:10445000000000000000000000000000AAAAAAAAB4 +:1044600000000000FFFF000000000000000000004E +:104470000000000000000000AAAAAAAA0000000094 +:10448000FFFF00000000000000000000000000002E +:10449000270400000000000000001E0000000000D3 +:1044A000FF000000000000003C4100083F00000049 +:1044B00050040000474100083F0000000096000043 +:1044C0000000080096000000000800000400000042 +:1044D000F0420008000000000000000000000000A2 +:0C44E000000000000000000000000000D0 +:00000001FF diff --git a/Tools/bootloaders/CubeOrange_bl.bin b/Tools/bootloaders/CubeOrange_bl.bin index 0e45742aa5a..243033814f0 100755 Binary files a/Tools/bootloaders/CubeOrange_bl.bin and b/Tools/bootloaders/CubeOrange_bl.bin differ diff --git a/Tools/bootloaders/CubeOrange_bl.elf b/Tools/bootloaders/CubeOrange_bl.elf index c4c1623b1eb..376200bb94e 100755 Binary files a/Tools/bootloaders/CubeOrange_bl.elf and b/Tools/bootloaders/CubeOrange_bl.elf differ diff --git a/Tools/bootloaders/CubeOrange_bl.hex b/Tools/bootloaders/CubeOrange_bl.hex index 10269e4d6b4..d9b147151e1 100644 --- a/Tools/bootloaders/CubeOrange_bl.hex +++ b/Tools/bootloaders/CubeOrange_bl.hex @@ -1,34 +1,34 @@ :020000040800F2 :1000000000060020A102000869100008E90F00089E :1000100041100008E90F000815100008A3020008AD -:10002000A3020008A3020008A30200083D2A00085A +:10002000A3020008A3020008A3020008A12A0008F6 :10003000A3020008A3020008A3020008A30200080C :10004000A3020008A3020008A3020008A3020008FC -:10005000A3020008A3020008F93E0008253F00089B -:10006000513F00087D3F0008A93F0008A302000897 +:10005000A3020008A3020008293F0008553F00083A +:10006000813F0008AD3F0008D93F0008A302000807 :10007000A3020008A3020008A3020008A3020008CC :10008000A3020008A3020008A3020008A3020008BC -:10009000A3020008A3020008A3020008D53F00083D +:10009000A3020008A3020008A3020008054000080C :1000A000A3020008A3020008A3020008A30200089C :1000B000A3020008A3020008A3020008A30200088C :1000C000A3020008A3020008A3020008A30200087C -:1000D000A3020008A3020008AD400008C1400008C8 -:1000E00039400008A3020008A3020008A302000888 +:1000D000A3020008A3020008DD400008F140000868 +:1000E00069400008A3020008A3020008A302000858 :1000F000A3020008A3020008A3020008A30200084C -:10010000A3020008A3020008E9400008A3020008B7 +:10010000A3020008A302000819410008A302000886 :10011000A3020008A3020008A3020008A30200082B :10012000A3020008A3020008A3020008A30200081B :10013000A3020008A3020008A3020008A30200080B :10014000A3020008A3020008A3020008A3020008FB :10015000A3020008A3020008A3020008A3020008EB :10016000A3020008A3020008A3020008A3020008DB -:10017000A3020008E1350008A3020008A30200085A -:10018000A3020008A3020008D5400008A30200084B +:10017000A30200080D360008A3020008A30200082D +:10018000A3020008A302000805410008A30200081A :10019000A3020008A3020008A3020008A3020008AB :1001A000A3020008A3020008A3020008A30200089B :1001B000A3020008A3020008A3020008A30200088B :1001C000A3020008A3020008A3020008A30200087B -:1001D000A3020008CD350008A3020008A30200080E +:1001D000A3020008F9350008A3020008A3020008E2 :1001E000A3020008A3020008A3020008A30200085B :1001F000A3020008A3020008A3020008A30200084B :10020000A3020008A3020008A3020008A30200083A @@ -41,1074 +41,1077 @@ :10027000A3020008A3020008A3020008A3020008CA :10028000A3020008A3020008A3020008A3020008BA :10029000A3020008A3020008A3020008A3020008AA -:1002A00002E000F000F8FEE772B63A4880F30888F2 -:1002B000394880F3098839484EF60851CEF20001DA -:1002C000086040F20000CCF200004EF63471CEF22D -:1002D00000010860BFF34F8FBFF36F8F40F2000043 -:1002E000C0F2F0004EF68851CEF200010860BFF374 -:1002F0004F8FBFF36F8F4FF00000E1EE100A4EF604 -:100300003C71CEF200010860062080F31488BFF330 -:100310006F8F02F055FC02F0F5FB03F0ABFB4FF0E2 -:1003200055301F491B4A91423CBF41F8040BFAE784 -:100330001C49194A91423CBF41F8040BFAE71A499B -:100340001A4A1B4B9A423EBF51F8040B42F8040B69 -:10035000F8E700201749184A91423CBF41F8040BC6 -:10036000FAE702F013FC03F005FC144C144DAC4208 -:1003700003DA54F8041B8847F9E700F041F8114C00 -:10038000114DAC4203DA54F8041B8847F9E702F038 -:10039000FBBB000000060020002200200000000837 -:1003A0000000002000060020204500080022002058 -:1003B0005C22002060220020D04F0020A002000814 -:1003C000A0020008A0020008A00200082DE9F04FDA -:1003D0002DED108AC1F80CD0D0F80CD0BDEC108AED -:1003E000BDE8F08F002383F311882846A047002042 -:1003F00001F01AFFFEE701F09BFE00DFFEE70000C0 -:1004000038B500F003FD30B1164B00220E211A72F0 -:100410005A729972DA7202F0D3FA044602F008FBBB -:100420000546D0B9104B9C4219D001339C4241F291 -:10043000883412BF054600240125002002F0CAFAC4 -:100440000DB100F05BF800F06FFD00F027FC2046D6 -:1004500000F014F900F052F8F9E70024EDE7044643 -:10046000EBE700BF00220020010007B008B500F054 -:10047000E1FBA0F120035842584108BD054B07B5E8 -:100480001B88022101A8ADF8043000F0F1FB03B095 -:100490005DF804FBCC41000810B5202383F31188DC -:1004A0001248C3680BB101F047FF0023104A4FF414 -:1004B0007A710E4801F002FF002383F311880D4C7E -:1004C000236813B12368013B2360636813B1636839 -:1004D000013B6360084B1B7833B9636823B9022082 -:1004E00000F09AFC3223636010BD00BF6022002040 -:1004F000990400087C23002074220020554B5649A3 -:100500002DE9F04153F8042F013201D1BDE8F0810B -:100510008B42F7D1514C524B22689A4240F298805C -:10052000504B9B6803F1006303F500339A4280F05F -:100530008F80002000F0CEFB02204B4B187000F0A3 -:1005400069FC4A4BD3F8E8200022C3F8E820D3F82E -:100550001011C3F81021D3F81011D3F8EC10C3F820 -:10056000EC20D3F81411C3F81421D3F81411D3F8E4 -:10057000F010C3F8F020D3F81811C3F81821D3F8FD -:100580001811D3F8801041F00061C3F88010D3F83F -:10059000801021F00061C3F88010D3F88010D3F8E8 -:1005A000801041F00071C3F88010D3F8801021F062 -:1005B0000071C3F88010D3F8803072B62C4B2D49EF -:1005C0000B601D682468BFF34F8FBFF36F8F2A4BFA -:1005D000C3F88420BFF34F8F5A6922F480325A61E6 -:1005E000BFF34F8FD3F8802043F6E07EC2F3C906F5 -:1005F000C2F34E32B707520102EA0E0838463146BE -:10060000013948EA000C00F14040B1F1FF3FC3F866 -:1006100074C2F5D1203A12F1200FEDD1BFF34F8F04 -:10062000BFF36F8FBFF34F8FBFF36F8F5A6922F401 -:1006300000325A610022C3F85022BFF34F8FBFF33C -:100640006F8F202383F31188AD4685F308882047F8 -:10065000BDE8F081FCFF01081C000208040002084C -:10066000FFFF0108002200207422002000440258ED -:100670000000020808ED00E000ED00E02DE9F04F79 -:1006800099B0BB4D2022FF21009010A8AC6800F06B -:10069000EDFBB84A01951378A3B90121B648117052 -:1006A000C360202383F31188C3680BB101F044FEBB -:1006B0000023B24A4FF47A71AF4801F0FFFD0023E6 -:1006C00083F31188009BAE4A03B113600026AD4B43 -:1006D000009DB2463746B1461E7056600293012017 -:1006E00000F098FB002D00F02B82A54B1B68002B1F -:1006F00040F0268219B0BDE8F08F0220FFF7B6FE69 -:10070000002840F01682009B02210BA8002E08BF93 -:100710001D469D4B1B88ADF82C3000F0A9FADEE792 -:100720004FF47A7000F086FAB0F10008EBDB02209B -:10073000FFF79CFE0028E6D008F1FF38B8F1050F5E -:1007400000F2F981DFE808F0030B0E11143718A846 -:100750000523042140F8343D00F08AFA17E0042113 -:100760008348F9E704218948F6E704218848F3E73C -:100770004FF01C09484609F1040900F0ADFA0421C4 -:100780000B900BA800F074FAB9F12C0FF2D10123F1 -:100790004FF0000903FA08F848EA0A0A5FFA8AFAF1 -:1007A00000F0B8FB27B10AF00B030B2B08BF0025A4 -:1007B000FFF764FE93E704217648CDE7002FA2D02F -:1007C0000AF00B030B2B9ED10220FFF74FFE804651 -:1007D000002898D001206B4E00F07CFA0027022000 -:1007E000307000F017FB5FFA87FB584600F082FA82 -:1007F000054688B15846013700F08CFA0028F2D13E -:1008000046460025644B02210BA847461B88ADF8DD -:100810002C3000F02DFA62E701232C4602203370C1 -:1008200000F0F6FA019B9B689C4206D2204600F03D -:1008300053FA0130E4D10434F4E70024029B464625 -:1008400047461C7025464E4B5C60A9E7002F3FF4DD -:100850005AAF0AF00B030B2B7FF455AF0220029B1B -:10086000187000F0D7FA322000F0E4F9B0F1000B74 -:10087000FFF649AF1BF003087FF445AF019B04EB83 -:100880000B0299688A423FF63EAFBBF5807F3FF688 -:100890003AAF424AD84503920FDA4FF47A7000F02B -:1008A000C9F9049004990029FFF62DAF0499039A21 -:1008B00008F8021008F10108ECE7C820FFF7D6FDA0 -:1008C000804600283FF41FAF1F2C11D8C4F1200729 -:1008D00010AB24F0030031495F45184428BF5F4640 -:1008E0003A4600F09BFA3A46FF212C4800F0BEFA47 -:1008F0004FEAAB0329492046DAB2039300F0BEFA6F -:10090000074600283FF47EAF039B04EB830447E7D0 -:100910000220FFF7ABFD00283FF4F5AE00F014FA1B -:1009200000283FF4F0AE4FF000084346019A926869 -:10093000904535D2B8F11F0F12D8109A01320FD05E -:1009400028F0030218A90A4452F8202C0B921846EA -:1009500004220BA908F1040800F088FB0346E5E730 -:100960004046039300F0B8F9039B0B90EFE700BFFC -:100970000022002078230020602200209904000833 -:100980007C23002074220020CE4100080422002095 -:10099000082200200C220020D041000878220020EC -:1009A00018A8042140F84C3D00F062F9F8E618A8B8 -:1009B0000023642140F8343D00F050F900287FF412 -:1009C000A2AE0220FFF752FD00283FF49CAE0B9828 -:1009D00000F0B2F918AB43F8480D04211846E3E7DC -:1009E00018A80023642140F8343D00F037F90028AE -:1009F0007FF489AE0220FFF739FD00283FF483AE73 -:100A00000B9800F09BF918AB43F8440DE5E7022082 -:100A1000FFF72CFD00283FF476AE00F0A5F918ABE7 -:100A200043F8400DD9E70220FFF720FD00283FF4EE -:100A30006AAE0BA9142000F09DF9804618A8042185 -:100A400040F83C8D00F014F941460BA8ACE7322089 -:100A500000F0F0F8B0F10008FFF655AE18F0030F03 -:100A60007FF451AE019A08EB0903926893423FF676 -:100A70004AAE0220FFF7FAFC00283FF444AE28F00B -:100A80000308C844C1453FF48BAE484609F1040948 -:100A900000F022F904210A900AA800F0E9F8F1E731 -:100AA0004FF47A70FFF7E2FC00283FF42CAE00F020 -:100AB0004BF9002842D0109B01330BD0082210A91B -:100AC000002000F0DBF9002838D02022FF2110A8F8 -:100AD00000F0CCF9FFF7D2FC3A4801F0ABFB09E695 -:100AE000002F3FF410AE0AF00B030B2B7FF40BAE7C -:100AF00018A80023642140F8343D00F0AFF8804688 -:100B000000287FF400AE0220FFF7B0FC00283FF47D -:100B1000FAAD0390FFF7B2FC41F28830454601F090 -:100B200089FB0B9800F040FA00F0F4F9039B1F4694 -:100B3000D5E5074634E64FF00009E4E5B84661E63E -:100B4000002000F077F80490049B002BFFF6CAAD5C -:100B5000012000F05DF9049B213B162B3FF6BFAD51 -:100B600001A252F823F000BFFB060008210700088D -:100B7000BD070008DF060008DF060008DF060008E2 -:100B80004D0800084F0A000811090008AF090008C5 -:100B9000E10900080F0A0008DF060008270A00081C -:100BA000DF060008A10A0008A1070008DF06000808 -:100BB000E10A000807070008A1070008DF0600088F -:100BC000AF090008A08601002DE9F84F4FF47A75AF -:100BD00007460E4600245543DFF85080DFF850905A -:100BE00098F900305FFA84FA5A1C01D0A34210D160 -:100BF00059F82400324639460368D3F820B02B4612 -:100C0000D847864205D1084B012083F800A0BDE8F3 -:100C1000F88F0134042CE3D14FF4FA7001F00AFB91 -:100C20000020BDE8F88F00BFC8230020102200205C -:100C3000D441000807B5002202AB012103F8012DC1 -:100C400002461846FFF7C0FF20B19DF8070003B029 -:100C50005DF804FB4FF0FF30F9E700000A4604217D -:100C600008B5FFF7B1FF80F00100C0B2404208BDF7 -:100C7000074B30B41A78074B53F822400A46014616 -:100C800023682046DD69044BAC4630BC604700BF9A -:100C9000C8230020D4410008A0860100F8B50A4C02 -:100CA00000250A4E01F072FD094F2080306823882C -:100CB000834207D901F066FD336805440133BD4224 -:100CC0003360F3D9F8BD00BFCA230020842300207D -:100CD000FFFF010001F028BE00F1006000F50030C8 -:100CE0000068704700F10060920000F5003001F0EC -:100CF000A9BD0000054B1A68054B1B889B1A83424F -:100D000002D9104401F03EBD00207047842300202A -:100D1000CA23002038B5074D04462868204401F056 -:100D200037FD28B928682044BDE8384001F042BDAD -:100D300038BD00BF8423002000207047014BC058FD -:100D4000704700BF00E8F11F064991F8243033B125 -:100D500000230822086A81F82430FFF7C3BF01206E -:100D6000704700BF88230020014B1868704700BF00 -:100D70000010005C234BF0B5234C1B682788C3F39D -:100D80000B0665681B0C94F90820BE4228D0A78981 -:100D9000BE4206D101220C2505FB0244656894F988 -:100DA000082041F20104A3421CD041F20304A342F3 -:100DB0001AD042F20104A34218D042F20304A34223 -:100DC00008BF5622441E013D0B460C44A34217D2D5 -:100DD00015F9016F581C5EB1034600F8016CF5E788 -:100DE0000022D8E75A22EDE75922EBE75822E9E73B -:100DF0002C2584421D7001D9981C5A70401AF0BDF0 -:100E00001846FBE70010005C142200200020704709 -:100E1000704700007047000070470000002310B5C5 -:100E2000934203D0CC5CC4540133F9E710BD0000F9 -:100E300030B5441E14F9010F0B4658B193F9005018 -:100E40000131854206D11AB993F90020801A30BDCC -:100E5000013AEFE7002AF7D1104630BD02460346BB -:100E6000981A13F9011B0029FAD17047024403466E -:100E7000934202D003F8011BFAE770472DE9F047CF -:100E8000234C05468846174694F8243083BB2E46EB -:100E9000DFF87C90C7B394F824302BB92022FF21CF -:100EA00048462662FFF7E2FF94F824004146C0F16D -:100EB000080504EB8000BD4228BF3D465FFA85FA75 -:100EC000AD00A7EB0A072A462E44FFF7A7FF94F8C8 -:100ED0002430A844FFB29A445FFA8AFABAF1080FA4 -:100EE00084F824A0D6D1FFF72FFF0028D2D108E044 -:100EF000266A06EB8306B042CAD0FFF725FF00281A -:100F0000C5D10020BDE8F0870120BDE8F08700BF13 +:1002A00002E000F000F8FEE73B48804772B63B48AA +:1002B00080F308883A4880F309883A484EF6085196 +:1002C000CEF20001086040F20000CCF200004EF6D1 +:1002D0003471CEF200010860BFF34F8FBFF36F8F10 +:1002E00040F20000C0F2F0004EF68851CEF200015C +:1002F0000860BFF34F8FBFF36F8F4FF00000E1EE48 +:10030000100A4EF63C71CEF200010860062080F320 +:100310001488BFF36F8F02F081FC02F023FC03F01E +:10032000BDFB4FF0553020491C4A91423CBF41F87B +:10033000040BFAE71D491A4A91423CBF41F8040BED +:10034000FAE71B491B4A1C4B9A423EBF51F8040B6B +:1003500042F8040BF8E700201849194A91423CBFC3 +:1003600041F8040BFAE702F03BFC03F01BFC154CD0 +:10037000154DAC4203DA54F8041B8847F9E700F046 +:1003800043F8124C124DAC4203DA54F8041B884770 +:10039000F9E702F023BC00006D1000080006002001 +:1003A00000220020000000080000002000060020BD +:1003B00050450008002200205C220020602200201E +:1003C000D44F0020A0020008A0020008A0020008EC +:1003D000A00200082DE9F04F2DED108AC1F80CD0D5 +:1003E000D0F80CD0BDEC108ABDE8F08F002383F369 +:1003F00011882846A047002001F02AFFFEE701F0FF +:10040000A5FE00DFFEE7000038B500F0F1FC30B1DA +:10041000164B00220E211A725A729972DA7202F089 +:10042000F3FA054602F026FB0446D0B9104B9D4274 +:1004300019D001339D4241F2883512BF0446002590 +:100440000124002002F0EAFA0CB100F079F800F083 +:100450006BFD00F013FC284600F020F900F070F866 +:10046000F9E70025EDE70546EBE700BF0022002095 +:10047000010007B008B500F0CDFBA0F12003584201 +:10048000584108BD07B541F21203022101A8ADF899 +:10049000043000F0DDFB03B05DF804FB38B5202329 +:1004A00083F311881748C3680BB101F057FF00238D +:1004B000154A4FF47A71134801F014FF002383F3B7 +:1004C0001188124C236813B12368013B23606368D1 +:1004D00013B16368013B63600D4D2B7833B96368DA +:1004E0007BB9022000F09AFC322363602B78032B47 +:1004F00007D163682BB9022000F090FC4FF47A73A7 +:10050000636038BD602200209D0400087C23002029 +:1005100074220020084B187003280CD8DFE800F084 +:1005200008050208022000F06FBC022000F062BC47 +:10053000024B00225A607047742200207C23002066 +:10054000F8B5504B504A1C461968013100F09980AB +:1005500004339342F8D162684C4B9A4240F2918046 +:100560004B4B9B6803F1006303F500339A4280F024 +:100570008880002000F09CFB0220FFF7CBFF454B5A +:100580000021D3F8E820C3F8E810D3F81021C3F80D +:100590001011D3F81021D3F8EC20C3F8EC10D3F8E5 +:1005A0001421C3F81411D3F81421D3F8F020C3F8A0 +:1005B000F010D3F81821C3F81811D3F81821D3F884 +:1005C000802042F00062C3F88020D3F8802022F01F +:1005D0000062C3F88020D3F88020D3F8802042F056 +:1005E0000072C3F88020D3F8802022F00072C3F894 +:1005F0008020D3F8803072B64FF0E023C3F8084D66 +:10060000D4E90004BFF34F8FBFF36F8F224AC2F8C3 +:100610008410BFF34F8F536923F480335361BFF3CA +:100620004F8FD2F8803043F6E076C3F3C905C3F3A9 +:100630004E335B0103EA060C29464CEA8177013907 +:10064000C2F87472F9D2203B13F1200FF2D1BFF33C +:100650004F8FBFF36F8FBFF34F8FBFF36F8F536910 +:1006600023F4003353610023C2F85032BFF34F8F9D +:10067000BFF36F8F202383F31188854680F30888AA +:100680002047F8BD0000020820000208FFFF010813 +:10069000002200200044025800ED00E02DE9F04F58 +:1006A00093B0A84B2022FF2100900AA89D6800F07B +:1006B000E5FBA54A1378A3B90121A4481170C360D2 +:1006C000202383F31188C3680BB101F047FE002398 +:1006D0009F4A4FF47A719D4801F004FE002383F392 +:1006E0001188009B13B19B4B009A1A609A4A1378A9 +:1006F000032B03D000231370964A53604FF0000A77 +:10070000009CD3465646D146012000F07DFB24B123 +:10071000904B1B68002B00F00E82002000F07AFA4C +:100720000390039B002BF2DB012000F063FB039B93 +:10073000213B162BE8D801A252F823F099070008B4 +:10074000C107000855080008090700080907000844 +:1007500009070008DD080008AB0A0008C509000801 +:10076000270A00084F0A0008750A00080907000850 +:10077000870A000809070008F90A00083908000874 +:10078000090700083D0B0008A50700083908000804 +:1007900009070008270A00080220FFF76BFE00285F +:1007A00040F0F381009B022105A8BAF1000F08BFB9 +:1007B0001C4641F21233ADF8143000F049FAA3E7B9 +:1007C0004FF47A7000F026FA071EEBDB0220FFF7E9 +:1007D00051FE0028E6D0013F052F00F2D881DFE866 +:1007E00007F0030A0D1013360523042105A805930D +:1007F00000F02EFA17E004215248F9E70421574887 +:10080000F6E704215648F3E74FF01C08404608F18C +:10081000040800F04FFA0421059005A800F018FA2A +:10082000B8F12C0FF2D101204FF0000900FA07F7C0 +:1008300047EA0B0B5FFA8BFB00F06CFB26B10BF069 +:100840000B030B2B08BF0024FFF71CFE5CE7042101 +:100850004448CDE7002EA5D00BF00B030B2BA1D104 +:100860000220FFF707FE074600289BD00120002644 +:1008700000F01EFA0220FFF74DFE5FFA86F84046B0 +:1008800000F026FA044688B14046013600F030FAFE +:100890000028F2D1BA46044641F21213022105A8FB +:1008A0003E46ADF8143000F0D3F92DE7254601207F +:1008B000FFF730FE234B9B68AB4207D9284600F078 +:1008C000F9F9013040F066810435F3E70025224B49 +:1008D000BA463E461D701F4B5D60ADE7002E3FF4EB +:1008E00061AF0BF00B030B2B7FF45CAF0220FFF723 +:1008F00011FE322000F08EF9B0F10008FFF652AF81 +:1009000018F003077FF44EAF0E4A08EB0503926818 +:1009100093423FF647AFB8F5807F3FF743AF124BA6 +:10092000B845019322DD4FF47A7000F073F903901B +:10093000039A002AFFF636AF039A0137019B03F8AA +:10094000012BEDE700220020782300206022002008 +:100950009D0400087C230020742200200422002033 +:10096000082200200C22002078220020C820FFF757 +:1009700081FD074600283FF415AF1F2D11D8C5F1A2 +:1009800020020AAB25F0030084494245184428BFE1 +:100990004246019200F04CFA019AFF217F4800F094 +:1009A0006DFA4FEAA803C8F387027C4928460193F1 +:1009B00000F06CFA064600283FF46EAF019B05EB91 +:1009C000830539E70220FFF755FD00283FF4EAAE22 +:1009D00000F0AAF900283FF4E5AE0027B846704BB6 +:1009E0009B68BB4218D91F2F11D80A9B01330ED028 +:1009F00027F0030312AA134453F8203C0593404602 +:100A0000042205A9043700F04FFB8046E7E738468B +:100A100000F050F90590F2E7CDF81480042105A804 +:100A200000F016F908E70023642104A8049300F0FD +:100A300005F900287FF4B6AE0220FFF71BFD002861 +:100A40003FF4B0AE049800F065F90590E6E70023A6 +:100A5000642104A8049300F0F1F800287FF4A2AE0A +:100A60000220FFF707FD00283FF49CAE049800F039 +:100A700053F9EAE70220FFF7FDFC00283FF492AEAD +:100A800000F062F9E1E70220FFF7F4FC00283FF4F0 +:100A900089AE05A9142000F05DF9074604210490F1 +:100AA00004A800F0D5F83946B9E7322000F0B2F8D2 +:100AB000071EFFF677AEBB077FF474AE384A07EB2C +:100AC0000903926893423FF66DAE0220FFF7D2FC15 +:100AD00000283FF467AE27F003074F44B9453FF4C1 +:100AE000ABAE484609F1040900F0E4F80421059092 +:100AF00005A800F0ADF8F1E74FF47A70FFF7BAFC03 +:100B000000283FF44FAE00F00FF9002844D00A9BB4 +:100B100001330BD008220AA9002000F0B7F9002801 +:100B20003AD02022FF210AA800F0A8F9FFF7AAFC7A +:100B30001C4801F093FB13B0BDE8F08F002E3FF48A +:100B400031AE0BF00B030B2B7FF42CAE0023642192 +:100B500005A8059300F072F8074600287FF422AE3E +:100B60000220FFF787FC804600283FF41BAEFFF70A +:100B700089FC41F2883001F071FB059800F014FA0D +:100B800046463C4600F0C6F9BEE5064654E64FF040 +:100B9000000907E6BA467FE637467DE67822002060 +:100BA00000220020A08601002DE9F84F4FF47A734F +:100BB00006460D46002402FB03F7DFF85080DFF8FD +:100BC000509098F900305FFA84FA5A1C01D0A34281 +:100BD00010D159F824002A4631460368D3F820B0D2 +:100BE0003B46D847854205D1074B012083F800A03A +:100BF000BDE8F88F0134042CE3D14FF4FA7001F012 +:100C00002DFB0020F4E700BFC823002010220020A5 +:100C10001C420008002307B5024601210DF1070020 +:100C20008DF80730FFF7C0FF20B19DF8070003B033 +:100C30005DF804FB4FF0FF30F9E700000A4604219D +:100C400008B5FFF7B1FF80F00100C0B2404208BD17 +:100C5000074B0A4630B41978064B53F82140014639 +:100C600023682046DD69044BAC4630BC604700BFBA +:100C7000C82300201C420008A086010070B50A4E5F +:100C800000240A4D01F098FD3080286833888342A3 +:100C900008D901F08DFD2B6804440133B4F5003F01 +:100CA0002B60F2D370BD00BFCA2300208423002034 +:100CB00001F060BE00F1006000F500300068704790 +:100CC00000F10060920000F5003001F0D7BD000097 +:100CD000054B1A68054B1B889B1A834202D91044A6 +:100CE00001F066BD0020704784230020CA23002045 +:100CF00038B5074D04462868204401F05FFD28B947 +:100D000028682044BDE8384001F06ABD38BD00BF06 +:100D1000842300200020704700F1FF5000F58F1061 +:100D2000D0F8000870470000064991F8243033B12C +:100D300000230822086A81F82430FFF7C1BF012090 +:100D4000704700BF88230020014B1868704700BF20 +:100D50000010005C244BF0B51A680446234BC2F324 +:100D60000B06120C1F885868BE4293F9085028D011 +:100D70009F89BE4206D101200C2505FB003358682F +:100D800093F9085041F201039A421CD041F2030347 +:100D90009A421AD042F201039A4218D042F2030357 +:100DA0009A4208BF5625621E0B46441E0A449342CF +:100DB0000FD214F9016F581C6EB1034600F8016C94 +:100DC000F5E70020D8E75A25EDE75925EBE7582548 +:100DD000E9E7184605E02C2482421C7001D9981CD2 +:100DE0005D70401AF0BD00BF0010005C14220020AE +:100DF00000207047022803D1024B4FF080529A61C5 +:100E0000704700BF00100258022803D1024B4FF474 +:100E100080529A61704700BF00100258022804D126 +:100E2000024A536983F4805353617047001002589B +:100E3000002310B5934203D0CC5CC4540133F9E7CE +:100E400010BD0000013810B510F9013F3BB191F918 +:100E500000409C4203D11AB10131013AF4E71AB1C2 +:100E600091F90020981A10BD1046FCE7034602468F +:100E7000D01A12F9011B0029FAD170470244034627 +:100E8000934202D003F8011BFAE770472DE9F843BB +:100E90001F4D14460746884695F8242052BBDFF8BC +:100EA00070909CB395F824302BB92022FF2148463E +:100EB0002F62FFF7E3FF95F824004146C0F10802D6 +:100EC00005EB8000A24228BF2246D6B29200FFF76F +:100ED000AFFF95F82430A41B17441E449044E4B29D +:100EE000F6B2082E85F82460DBD1FFF71DFF00283D +:100EF000D7D108E02B6A03EB82038342CFD0FFF700 +:100F000013FF0028CBD10020BDE8F8830120FBE7C8 :100F100088230020024B1A78024B1A70704700BFDA :100F2000C823002010220020F8B5194C194800F001 -:100F30007FFC2146174800F0A7FC24681648D4F827 -:100F40009020164DD2F80438154E43F00203114F8D -:100F5000C2F8043801F06EF92046124900F0A6FDEF -:100F6000D4F890200024D2F8043823F00203C2F809 -:100F700004384FF4E1332B6056F82400B84202D015 -:100F8000294600F0B3FB0134042CF5D1F8BD00BFB5 -:100F9000E4420008C832002040420F00B023002085 -:100FA000D44100081043000838B50B4B05461A78A9 -:100FB0000A4B53F822400A4B9C420CD0094B0021AB -:100FC00018221846FFF752FF056001462046BDE88B -:100FD000384000F08BBB38BDC8230020D441000846 +:100F300097FC2146174800F0BFFC24681648D4F8F7 +:100F40009020164ED2F80438154D43F00203114F8D +:100F5000C2F8043801F082F92046124900F0BAFDC7 +:100F6000D4F890200424D2F8043823F00203C2F805 +:100F700004384FF4E133336055F8040BB84202D023 +:100F8000314600F0CBFB013C14F0FF04F4D1F8BD76 +:100F900034430008C832002040420F00B023002034 +:100FA0001C4200083C43000838B50B4B04461A7835 +:100FB0000A4B53F822500A4B9D420CD0094B00219A +:100FC00018221846FFF75AFF046001462846BDE87C +:100FD000384000F0A3BB38BDC82300201C420008E5 :100FE000C8320020B023002000B59BB0EFF3098188 -:100FF00068226846FFF712FFEFF30583044B9A6BF4 +:100FF00068226846FFF71CFFEFF30583044B9A6BEA :10100000DA6A9A6A9A6A9A6A9A6A9A6A9B6AFEE79E :1010100000ED00E000B59BB0EFF30981682268465F -:10102000FFF7FCFEEFF30583044B9A6B9A6A9A6A0A +:10102000FFF706FFEFF30583044B9A6B9A6A9A6AFF :101030009A6A9A6A9A6A9B6AFEE700BF00ED00E02E -:1010400000B59BB0EFF3098168226846FFF7E6FE22 +:1010400000B59BB0EFF3098168226846FFF7F0FE18 :10105000EFF30583034B5A6B9A6A9A6A9A6A9A6A03 -:101060009B6AFEE700ED00E0FEE7000030B50A44B1 -:10107000074D91420BD011F8013B09245840013C27 -:10108000F7D040F300032B4083EA5000F7E730BD70 -:101090002083B8ED026843681143016003B118472B -:1010A00070470000024A136843F0C00313607047A2 -:1010B00000440040024A136843F0C00313607047C5 -:1010C00000480040024A136843F0C00313607047B1 -:1010D0000078004037B5274C274D204600F0FAFA3B -:1010E000009404F1140000234FF40072234900F02F -:1010F000BBF900944FF40072214904F13800214BF0 -:1011000000F034FA204B2566E365204C204600F0C1 -:10111000E1FA009404F1140000234FF400721C491A -:1011200000F0A2F900944FF400721A4904F138005B -:10113000194B00F01BFA194B2566E365184C204645 -:1011400000F0C8FA04F11400009400234FF4007278 -:10115000144900F089F90094134B4FF400721349BD -:1011600004F1380000F002FA114B2566E36503B084 -:1011700030BD00BFCC23002000E1F5051025002084 -:10118000102B0020A5100008004400403824002047 -:1011900010270020102D0020B51000080048004046 -:1011A000A424002010290020C5100008102F0020C2 -:1011B00000780040344B002908BF1946037C012BFE -:1011C00030B511D1314B98423BD1314BD3F8E820A7 -:1011D00042F40032C3F8E820D3F8102142F4003280 -:1011E000C3F81021D3F810310A68036EC46D03EB05 -:1011F00052038166B3FBF2F34A68150442BF23F041 -:10120000070503F0070343EA4503E3608B6843F0F7 -:1012100040036360CB68510543F00103A36042F4CF -:10122000967343F0010323604FF0FF33236205D52B -:1012300012F0102223D0B2F1805F22D080F8643007 -:1012400030BD144B98420BD1114BD3F8E82042F437 -:101250008022C3F8E820D3F8102142F48022BFE7AF -:101260000D4B9842C0D10A4BD3F8E82042F080429F -:10127000C3F8E820D3F8102142F08042B0E77F2382 -:10128000DCE73F23DAE700BF00420008CC23002060 -:101290000044025838240020A42400202DE9F047FF -:1012A000C66D05463768F469200734621AD014F019 -:1012B000080F0CBF00218021E20748BF41F0200148 -:1012C000A3074FF0200348BF41F04001600748BF2B -:1012D00041F4807183F31188281DFFF7DBFE0023A2 -:1012E00083F31188E2050AD5202383F311884FF494 -:1012F0000071281DFFF7CEFE002383F311884FF005 -:1013000020094FF0000A14F0200831D13B0616D511 -:101310004FF0200905F1380A200610D589F311880D -:10132000504600F057F900282FDA0821281DFFF752 -:10133000B1FE27F080033360002383F31188790620 -:101340000DD562060BD5202383F31188EA6C2B6D33 -:101350009A4201D12B6CEBB9002383F31188E30689 -:1013600020D5AA6E1369EBB15069BDE8F047184764 -:1013700089F31188736A284695F86410194000F0C3 -:10138000C3F98AF31188F469BDE7B06288F3118864 -:10139000F469C1E727F040071021281DFFF77AFE06 -:1013A0003760D9E7BDE8F087F8B51546826804468E -:1013B0000B46AA4200D28568A1692669761AB54211 -:1013C00007D218462A46FFF729FDA3692B44A361DB -:1013D0000DE011D9AF1B32461846FFF71FFD3A4604 -:1013E000E1683044FFF71AFDE2683A44A261A3685D -:1013F00028465B1BA360F8BD18462A46FFF70EFD82 -:10140000E368E4E7836893422DE9F04104460F4620 -:10141000154600D2856860692669361AB54207D23A -:101420002A463946FFF7FAFC63692B4463610EE0F4 -:1014300013D9A5EB060832463946FFF7EFFC4246C2 -:10144000B919E068FFF7EAFCE26842446261A36808 -:1014500028465B1BA360BDE8F0812A463946FFF7AA -:10146000DDFCE368E2E7000010B50A440024C36134 -:10147000029B006040608460C160816141610261E3 -:10148000036210BD08B582694369934201D1826845 -:1014900082B98268013282605A1C426119704269C5 -:1014A00003699A4201D3C3684361002100F0DEFE64 -:1014B000002008BD4FF0FF3008BD000070B52023AC -:1014C00004460E4683F31188A568A5B1A368A269F6 -:1014D000013BA360531CA36115782269934224BF8A -:1014E000E368A361E3690BB120469847002383F3C7 -:1014F0001188284670BD3146204600F0A7FE00281E -:10150000E2DA85F3118870BD2DE9F74F05460F46E5 -:1015100090469A46D0F81C90202686F311884FF00A -:10152000000B144664B1224639462846FFF73CFFBB -:10153000034668B95146284600F088FE0028F1D0DD -:10154000002383F31188A8EB040003B0BDE8F08FFB -:10155000B9F1000F03D001902846C847019B8BF3D7 -:101560001188E41A1F4486F31188DBE7C1608161AA -:1015700041611144C361009B006040608260016171 -:1015800003627047F8B504460E461746202383F3DE -:101590001188A568A5B1A368013BA36063695A1CC3 -:1015A00062611E70236962699A4224BFE3686361C5 -:1015B000E3690BB120469847002080F31188F8BDFD -:1015C0003946204600F042FE0028E2DA85F3118811 -:1015D000F8BD0000836942699A4210B501D1826862 -:1015E0007AB98268013282605A1C82611C78036970 -:1015F0009A4201D3C3688361002100F037FE204680 -:1016000010BD4FF0FF3010BD2DE9F74F05460F46D6 -:1016100090469A46D0F81C90202686F311884FF009 -:10162000000B144664B1224639462846FFF7EAFE0D -:10163000034668B95146284600F008FE0028F1D05C -:10164000002383F31188A8EB040003B0BDE8F08FFA -:10165000B9F1000F03D001902846C847019B8BF3D6 -:101660001188E41A1F4486F31188DBE70268436897 -:101670001143016003B11847704700001430FFF7B1 -:1016800043BF00004FF0FF331430FFF73DBF0000B1 -:101690003830FFF7B9BF00004FF0FF333830FFF7A5 -:1016A000B3BF00001430FFF709BF00004FF0FF3157 -:1016B0001430FFF703BF00003830FFF763BF0000AE -:1016C0004FF0FF323830FFF75DBF00000020704759 -:1016D000FFF700BD044B0360002343608360C360D9 -:1016E00001230374704700BF1842000810B520237F -:1016F000044683F31188FFF75DFD02232374002362 -:1017000083F3118810BD000038B5C36904460D4647 -:101710001BB904210844FFF7A9FF294604F114006E -:10172000FFF7B0FE002806DA201D4FF48061BDE807 -:101730003840FFF79BBF38BD026843681143016022 -:1017400003B118477047000037B5446B41F6A40554 -:1017500063591A681178042914D1217C022911D106 -:101760001979012312898B4013420BD101A904F18D -:101770004C0002F07DF864590246019B21792068F3 -:1017800000F0ECF903B030BD143002F001B80000F5 -:101790004FF0FF33143001F0FBBF00004C3002F07B -:1017A000D3B800004FF0FF334C3002F0CDB800004A -:1017B000143001F0CFBF00004FF0FF31143001F0C2 -:1017C000C9BF00004C3002F09FB800004FF0FF325C -:1017D0004C3002F099B8000070B541F6A4060546F9 -:1017E000825913681978042901D0012070BD017C49 -:1017F0000229FAD1527901205C8990400440F4D149 -:1018000005F1140001F060FF02460028EDD0AD594B -:101810004FF440732868697900F08EF9204670BD56 -:10182000406BFFF7D9BF00000020704770470000F1 -:101830007FB5124B0125042604460360002305747E -:1018400000F18402436029468360C3600C4B029020 -:10185000143001934FF44073009601F011FF094BCF -:1018600004F694422946019304F14C004FF440736E -:101870000294009601F0D8FF04B070BD4042000809 -:1018800021180008491700080A68202383F31188EB -:101890000B790B3342F823004B79133342F82300C2 -:1018A0008B7913B10B3342F8230041F6A403C150E6 -:1018B00002230374002383F31188704738B5037F34 -:1018C000044613B190F85430ABB90125201D022114 -:1018D000FFF732FF04F1140025776FF0010100F0EB -:1018E000D1FC84F8545004F14C006FF00101BDE8C4 -:1018F000384000F0C7BC38BD10B5012104460430A3 -:10190000FFF71AFF0023237784F8543010BD00003E -:1019100038B504460025143001F0CAFE04F14C002D -:10192000257701F099FF201D84F854500121FFF71D -:1019300003FF2046BDE83840FFF74EBF90F88030E7 -:1019400003F06003202B19D190F88120212A0AD0BE -:10195000222A4FF000030ED0202A0FD1084A4267F6 -:101960000722826704E0064B43670723836700234F -:10197000C3670120704743678367F9E7002070471A -:101980002C22002073B541F6A405044643591A6879 -:101990001178042919D1017C022916D11979012362 -:1019A00012898B40134210D100F14C06304602F0F0 -:1019B00013F850B101A9304601F05AFF64590246AC -:1019C000019B2179206800F0C9F802B070BD0000C9 -:1019D00001F10B03F7B550F8234005460E46F4B16C -:1019E000202383F3118805EB8607201D08214C3442 -:1019F000FFF7A2FEFB685B691B6813B1204601F08C -:101A000045FF01A9204601F033FF024648B1019B82 -:101A10003146284600F0A2F8002383F3118803B072 -:101A2000F0BDFB685A691268002AF5D01B8A013B99 -:101A30001340F1D105F18002EAE70000133138B517 -:101A400050F82140E4B1202383F3118841F6A40328 -:101A5000E2581368527903EB8203DB689B695D6887 -:101A600045B104216018FFF767FE294604F1140010 -:101A700001F034FE2046FFF7AFFE002383F3118808 -:101A800038BD00007047000001F016B9012300F1D5 -:101A9000300200F1500103700023436042F8043B20 -:101AA0008A42D361FAD103814381704738B5044635 -:101AB000202383F31188002500F10C0300F130028C -:101AC000416043F8045B9342FBD1204601F016F9D4 -:101AD0000223237085F3118838BD000070B500EB38 -:101AE0008103054650690E461446DA6018B110228B -:101AF0000021FFF7BBF9A06918B110220021FFF700 -:101B0000B5F931462846BDE8704001F009BA000039 -:101B1000038900F13002002103F0010303814389AE -:101B200003F00103438100F1100343F8041B9342C7 -:101B3000FBD101F08DBA0000F0B4012500EB810467 -:101B400047898D40E4683D43A469458123600023B3 -:101B5000A2606360F0BC01F0A9BA0000F0B40125F6 -:101B600000EB810407898D40E4683D436469058189 -:101B700023600023A2606360F0BC01F021BB000081 -:101B8000022300F10C0200F1300110B5037004468D -:101B90000023A0F8883080F88A3080F88B300381E9 -:101BA000438142F8043B8A42FBD184F870302046DE -:101BB00001F04AF963681B6823B120460021BDE8A3 -:101BC0001040184710BD0000037880F88C300523C2 -:101BD000037043681B6810B504460BB10421984795 -:101BE00000232381638110BD436890F88C201B681B -:101BF00002700BB1052118477047000090F8703053 -:101C000070B5044613B1002380F8703004F18002EF -:101C1000204601F041FA63689B6863BB94F88050EA -:101C200015F0600615D194F8813005F07F0545EA7E -:101C3000032540F202339D4200F00E815BD8022D55 -:101C400000F0DC803FD8002D00F08780012D00F0EF -:101C5000CF800021204601F0D9FC0021204601F070 -:101C6000C9FC63681B6813B1062120469847062308 -:101C700084F8703070BD204698470028CED094F884 -:101C8000872094F8863043EA0223A26F934238BF3C -:101C9000A36794F98030A56F002B4FF0200380F2EA -:101CA000FD80002D00F0EC80092284F8702083F381 -:101CB00011880021A36F626F2046FFF74FFF0023BA -:101CC00083F3118870BDB5F5817F00F0B180B5F563 -:101CD000407F49D0B5F5807FBBD194F88230012B8D -:101CE000B7D1B4F8883023F00203A4F888306667CF -:101CF000A667E667C3E740F201639D421ED8B5F5CB -:101D0000C06F3BD2B5F5A06FA3D1B4F88030B3F566 -:101D1000A06F0ED194F88230204684F88A3001F00A -:101D2000F1F863681B6813B101212046984703232B -:101D3000237000236367A367E367A0E7B5F5106F1F -:101D400032D040F602439D4252D0B5F5006F80D1AB -:101D500004F18B036367012324E004F18803E56742 -:101D600063670223A3678AE794F88230012B7FF42C -:101D700070AFB4F8883043F00203B6E794F88520DA -:101D80002046616894F884304D6843EA022394F851 -:101D9000831094F88220A84700283FF45AAF436884 -:101DA00063670368A367A4E72378042B10D120237B -:101DB00083F311882046FFF7ABFE86F31188636832 -:101DC000032184F88B601B6821700BB12046984773 -:101DD00094F88230002BACD084F88B30042323702D -:101DE00063681B68002BA4D0022120469847A0E717 -:101DF000374B63670223A36700239DE794F88410A1 -:101E0000204611F0800F01F00F010ED001F036F9DD -:101E1000012806D002287FF41CAF2E4BA067636711 -:101E200067E72D4BA567636763E701F019F9EFE7F3 -:101E300094F88230002B7FF40CAF94F8843013F0C8 -:101E40000F013FF476AF1A06204602D501F0F6FBEB -:101E50006FE701F0E7FB6CE794F88230002B7FF42A -:101E6000F8AE94F8843013F00F013FF462AF1B0614 -:101E7000204602D501F0CAFB5BE701F0BBFB58E747 -:101E8000142284F8702083F311882B462A462946B1 -:101E90002046FFF751FE85F3118870BD5DB1152214 -:101EA00084F8702083F311880021A36F626F2046AD -:101EB000FFF742FE03E70B2284F8702083F31188BA -:101EC0002B462A4629462046FFF748FEE3E700BF97 -:101ED00070420008684200086C42000838B590F86B -:101EE00070300446152B29D8DFE803F03E28282857 -:101EF00028283E28280B2939282828282828282857 -:101F00003E3E90F8871090F88620836F42EA0122C7 -:101F10009A4214D9C268128AB3FBF2F502FB153556 -:101F20006DB9202383F311882B462A462946FFF7F3 -:101F300015FE85F311880A2384F8703038BD142308 -:101F400084F87030202383F31188002320461A463A -:101F50001946FFF7F1FD002383F3118838BDC36FE5 -:101F600003B198470023E7E7002101F04FFB002170 -:101F7000204601F03FFB63681B6813B10621204631 -:101F800098470623D8E7000090F87020152A38B546 -:101F9000044622D80123934040F6416213421DD1EA -:101FA00013F480150FD19B0217D50B2380F87030E6 -:101FB000202383F311882B462A462946FFF7CEFDBE -:101FC00085F3118838BDC3689B695B682BB9C36F03 -:101FD00003B19847002384F8703038BD002101F028 -:101FE00015FB0021204601F005FB63681B6813B157 -:101FF0000621204698470623EDE70000024B002209 -:102000001B605B609A60704710310020002382687B -:102010000374054B1B6899689142FBD25A680360B0 -:1020200042601060586070471031002008B52023CE -:1020300083F31188037C032B05D0042B0DD02BB91F -:1020400083F3118808BD436900221A604FF0FF3303 -:102050004361FFF7DBFF0023F2E790E80C001A6012 -:1020600002685360F2E70000002382680374054BA6 -:102070001B6899689142FBD85A68036042601060FF -:102080005860704710310020054B196908741868B2 -:10209000026853601A60186101230374FEF796B951 -:1020A000103100204B1C30B5054687B00A4C10D0CB -:1020B000236901A8094A00F001F92846FFF7E4FF67 -:1020C000049B13B101A800F037F92369586907B0E0 -:1020D00030BDFFF7D9FFF8E7103100202D200008B0 -:1020E00038B50C4D044641612B6981689A6891426C -:1020F00003D8BDE83840FFF789BF1846FFF7B4FFA3 -:1021000001232C61014623742046BDE83840FEF7C8 -:102110005DB900BF10310020044B1A681B6990683C -:102120009B68984294BF0020012070471031002026 -:1021300010B5084C236820691A6854602260012297 -:1021400023611A74FFF790FF01462069BDE8104033 -:10215000FEF73CB910310020FEE7000010B50C4C32 -:10216000FFF74CFF00F09CF880220A49204600F05F -:1021700021F8012344F8180C037400F06FFC0023CD -:1021800083F3118862B60448BDE8104000F034B80B -:1021900038310020744200087C42000800F008B981 -:1021A000034B59685A68521A9042FBD8704700BFD7 -:1021B000001000E082600222027400224274704724 -:1021C0008368A3F17C0243F80C2C026943F83C2C91 -:1021D000426943F8382C074A43F81C2CC268A3F123 -:1021E000180043F8102C022203F8082C002203F8F0 -:1021F000072C7047E503000810B5202383F31188EE -:10220000FFF7DEFF00210446FFF76AFF002383F398 -:102210001188204610BD0000024B1B6958610F2039 -:10222000FFF732BF10310020202383F31188FFF71E -:10223000F3BF000008B50146202383F3118808206E -:10224000FFF730FF002383F3118808BD49B1064B27 -:1022500042681B6918605A60136043600420FFF7EE -:1022600021BF4FF0FF3070471031002003689842C3 -:1022700006D01A680260506018465961FFF7C6BE62 -:102280007047000038B504460D462068844200D1EE -:1022900038BD036823605C604561FFF7B7FEF4E773 -:1022A000054B03F114025A619A614FF0FF32DA6173 -:1022B00000221A62704700BF10310020F8B5036198 -:1022C0000E46C260054601F0BFFB1A4B19461F4679 -:1022D00051F8142F8A420DD118620A2E2CBF801992 -:1022E0000A30AE606A602A609D615D61BDE8F840B9 -:1022F00001F094BB1B6A9268C41A341928BF344693 -:10230000A24202D9181901F099FB7B699A6894429C -:102310000CD8AC6098685A68041B2B606A60156022 -:102320005D609C604FF0FF33FB61F8BDA41A1B6831 -:10233000ECE700BF1031002038B51C4B01685A692A -:102340001D4690420DD0446821600021026854600F -:10235000C16091688068014491604FF0FF32DA619A -:1023600038BD1A4642F8141F4A6000215B69C160FB -:10237000934203D1BDE8384001F05ABB9A688168A6 -:102380000A449A602C6A01F05FFB6A69001B92683C -:1023900082420AD9111A092998BF00F10A02286A53 -:1023A000BDE83840104401F049BB38BD1031002071 -:1023B0002DE9F041184D002705F114066C6901F074 -:1023C00043FB2A6AA368811A8B4216D81344D4F8B7 -:1023D0000C802B6294E80C001A60226853606B69D1 -:1023E000E760B34201D101F023FB87F31188206934 -:1023F000C047202383F31188E0E76A69B24208D01E -:102400005B1ABDE8F0410A2B2CBFC0180A3001F05E -:1024100015BBBDE8F08100BF1031002000207047DF -:10242000FEE70000704700004FF0FF3070470000EB -:10243000022906D0032906D00129064818BF00202A -:10244000704705487047032A9ABF044800EBC20052 -:10245000002070476C430008204300083C22002005 -:1024600070B59AB006460846144601AD294600F0FC -:10247000BDF82846FEF7F2FCC0B2431C5B0086E8BC -:10248000180023700323023404F8013C002319468A -:10249000DAB20234904201D81AB070BDEA5C01335E -:1024A00004F8011C04F8022CF2E7000008B5202310 -:1024B00083F311880348FFF765FA002383F311883B -:1024C00008BD00BFC832002090F8803003F01F0222 -:1024D000012A07D190F881200B2A03D100234367FA -:1024E000836712E003F06003202B11D1B0F8843031 -:1024F00073B990F88120212A03D0222AEFD0202A14 -:1025000006D1044A426707228267C36701207047E9 -:10251000FFF714BA3322002010B50446052916D857 -:10252000DFE801F016150316161D202383F311882A -:102530000E4A0121FFF7D2FA20460D4A0221FFF789 -:10254000CDFA0C48FFF7E4F9002383F3118810BD9E -:10255000202383F311880748FFF7B0F9F4E720231D -:1025600083F311880348FFF7C7F9EDE79C420008A1 -:10257000C0420008C832002038B50C4D0C4C2A4629 -:102580000C4904F10800FFF76BFF05F1CA0204F1E2 -:1025900010000949FFF764FF05F5CA7204F118003D -:1025A0000649BDE83840FFF75BBF00BFA04B0020E5 -:1025B0003C220020EC420008F942000804430008D5 -:1025C00070B5044608460D46FEF748FCC6B22046E4 -:1025D000013403780BB9184670BD32462946FEF720 -:1025E00027FC0028F3D1012070BD00002DE9F84F31 -:1025F00005460C46FEF732FC2C49C6B22846FFF7CA -:10260000DFFF08B10336F6B229492846FFF7D8FFA5 -:1026100008B11036F6B2632E0DD8DFF89080DFF8DF -:102620009090244FDFF894A0DFF894B02E7846B94C -:102630002670BDE8F88F29462046BDE8F84F01F026 -:10264000BDBD252E2ED1072241462846FEF7F0FBC0 -:1026500070B9DBF8003007350A3444F80A3CDBF87F -:10266000043044F8063CBBF8083024F8023CDDE7AF -:10267000082249462846FEF7DBFB98B9A21C0E4B00 -:1026800013F8011F023209095345C95D02F8041C01 -:10269000197801F00F01C95D02F8031CF0D118345C -:1026A0000835C3E7267001350134BFE78C430008C5 -:1026B000044300089F430008FFE7F11F0BE8F11FE8 -:1026C00094430008BFF34F8F044B1A695107FCD1A4 -:1026D000D3F810215207F8D1704700BF00200052F4 -:1026E00008B50D4B1B78ABB9FFF7ECFF0B4BDA6865 -:1026F000D10704D50A4A5A6002F188325A60D3F8E9 -:102700000C21D20706D5064AC3F8042102F188320B -:10271000C3F8042108BD00BFFE4D00200020005278 -:102720002301674508B5114B1B78F3B9104B1A69A3 -:10273000510703D5DA6842F04002DA60D3F810217D -:10274000520705D5D3F80C2142F04002C3F80C2102 -:10275000FFF7B8FF064BDA6842F00102DA60D3F8FF -:102760000C2142F00102C3F80C2108BDFE4D0020EF -:10277000002000520F289ABF00F58060400400201E -:10278000704700004FF40030704700001020704781 -:102790000F2808B50BD8FFF7EDFF00F500330268EE -:1027A000013204D104308342F9D1012008BD002058 -:1027B00008BD00000F2810B504463FD8FFF782FF80 -:1027C000FFF78EFF1E484FF0FF33072C4361C0F820 -:1027D00014311DD80361FFF775FF230243F0240372 -:1027E000C360C36843F08003C36003695A07FCD425 -:1027F000FFF768FF2046FFF7BDFF4FF4003100F000 -:10280000F9F8FFF78FFF2046BDE81040FFF7C0BF83 -:10281000C0F81031FFF756FFA4F108031B0243F084 -:102820002403C0F80C31D0F80C3143F08003C0F819 -:102830000C31D0F810315B07FBD4D9E7002010BD74 -:10284000002000522DE9F84F40EA02030546894670 -:102850009046DB065AD122F003020346024493421B -:1028600005D1FFF73DFF4E46DFF8B8B042E01968EA -:1028700001314BD10433F2E7264A05F1784326486B -:102880009342264B264F88BF9A46A3F1FC039CBF78 -:10289000DA46184603F1F80388BF1F46FFF712FF18 -:1028A0004FF0FF3306F11C02A5EB060E03603B68F8 -:1028B00043F002033B60331FDAF8004014F00504D4 -:1028C000FAD153F8041F9A424EF80310F4D1BFF323 -:1028D0004F8FFFF7F7FE4FF0FF33202231460360A2 -:1028E00028463B6823F002033B6001F057FC58B9CF -:1028F00020352036A8EB06034B441F2BBCD8012003 -:10290000FFF710FFBDE8F88F2046F9E70020BDE88B -:10291000F88F00BFFFFF0F0014210052102100525A -:102920000C2000521020005210B5084C237828B11A -:1029300053B9FFF7D5FE0123237010BD23B12070DA -:10294000BDE81040FFF7EEBE10BD00BFFE4D0020F9 -:1029500002440439064BD2B210B5904200D110BDEA -:10296000441C00B253F8200041F8040FE0B2F4E731 -:10297000504000580F4B30B51C6F240405D41C6F19 -:102980001C671C6F44F400441C670B4C0244043960 -:102990002368D2B243F480732360084B904200D185 -:1029A00030BD441C51F8045F00B243F82050E0B23F -:1029B000F4E700BF00440258004802585040005855 -:1029C00007B5012201A90020FFF7C2FF019803B05B -:1029D0005DF804FB13B50446FFF7F2FFA04206D0F2 -:1029E00002A90122002041F8044DFFF7C3FF02B005 -:1029F00010BD00000144BFF34F8F064B884204D343 -:102A0000BFF34F8FBFF36F8F7047C3F85C02203066 -:102A1000F4E700BF00ED00E0034B1B685B0142BF21 -:102A20000122024B1A707047D0440258FF4D00201B -:102A3000014B1878704700BFFF4D0020EFF309836A -:102A4000054968334A6822F001024A6083F3098825 -:102A5000002383F31188704730EF00E0202080F3DB -:102A6000118862B60D4B0E4AD96821F4E061090461 -:102A7000090C0A430B49DA60CA6842F08072CA60E6 -:102A8000094A0A49C2F8B01F116841F001011160FA -:102A90001022DA7783F82200704700BF00ED00E0D3 -:102AA0000003FA05F0ED00E0001000E055CEACC5E3 -:102AB00010B5202383F311880E4B5B6813F4006379 -:102AC00014D0F1EE103AEFF309844FF08073683CB4 -:102AD000E361094BDB68236684F30988FFF71CFB7D -:102AE00010B1064BA36110BD054BFBE783F31188C2 -:102AF00010BD00BF00ED00E030EF00E0F70300087C -:102B0000FA030008F0B5BFF34F8FBFF36F8F1D4B73 -:102B10000021C3F85012BFF34F8FBFF36F8F5A6974 -:102B200042F400325A61BFF34F8FBFF36F8FC3F887 -:102B30008410BFF34F8FD3F8802043F6E076C2F3C2 -:102B4000C904C2F34E32A507520102EA060E284616 -:102B500021464EEA0007013900F14040C3F8607297 -:102B60004F1CF6D1203A12F1200FEED1BFF34F8F58 -:102B70005A6942F480325A61BFF34F8FBFF36F8FAF -:102B8000F0BD00BF00ED00E0FEE70000084A094B81 -:102B900009498B4204D3094A0021934205D3704767 -:102BA00052F8040F43F8040BF3E743F8041BF4E76F -:102BB00078450008D04F0020D04F0020D04F002093 -:102BC00070470000D0F89430002170B5D0F89040E4 -:102BD0004FF0FF359E684A01A318D3F8000900287A -:102BE00005DAD3F8000940F08040C3F80009D3F8B3 -:102BF000000B002805DAD3F8000B40F08040C3F842 -:102C0000000B0131A3188E42C3F80859C3F8085BC2 -:102C1000E1D24FF00113C4F81C3870BD00EB810302 -:102C20002DE9F04FD3F80CE04F1C4FEA4118DEF8C5 -:102C300014403F03D4F800C06568D0F89020654583 -:102C40000AD30120D2F8343800FA01F123EA010155 -:102C5000C2F83418BDE8F08FACEB0503BEF8106085 -:102C6000B34228BF334602EB0806D6F81869B6B25D -:102C7000B3EB860F13D8A6683A449946A6F1040A26 -:102C80005AF804BFB9F1040FC2F800B002D9A9F193 -:102C90000409F5E71E442B44A6606360CCE70020DE -:102CA000BDE8F08F890141F02001016103699B06B5 -:102CB000FCD41220FFF774BA10B50A4C2046FEF778 -:102CC000E5FE094BC4F89030084BC4F89430084C2A -:102CD0002046FEF7DBFE074BC4F89030064BC4F8E5 -:102CE000943010BD004E002000000840D44300087E -:102CF0009C4E002000000440E04300080378012BB4 -:102D000070B505465DD1494BD0F89040984259D1F5 -:102D1000474B0E216520D3F8D82042F00062C3F85B -:102D2000D820D3F8002142F00062C3F80021D3F884 -:102D30000021D3F8802042F00062C3F88020D3F84D -:102D4000802022F00062C3F88020D3F8803000F0A9 -:102D500081FC384BE360384BC4F800380023D5F8C9 -:102D60009060C4F8003EC02323604FF40413A363B3 -:102D70003369002BFCDA01230C203361FFF710FAD2 -:102D80003369DB07FCD41220FFF70AFA3369002B02 -:102D9000FCDA00262846A660FFF714FF6B68C4F82B -:102DA0001068DB68C4F81468C4F81C68002B3AD1BA -:102DB000224BA3614FF0FF336361A36843F001032B -:102DC000A36070BD1E4B9842C8D1194B0E214D20F7 -:102DD000D3F8D82042F00072C3F8D820D3F80021ED -:102DE00042F00072C3F80021D3F80021D3F880200C -:102DF00042F00072C3F88020D3F8802022F00072E5 -:102E0000C3F88020D3F88020D3F8D82022F0806245 -:102E1000C3F8D820D3F8002122F08062C3F8002143 -:102E2000D3F8003193E7074BC3E700BF004E002003 -:102E3000004402584014004003002002003C30C00F -:102E40009C4E0020083C30C0F8B5D0F890400546B4 -:102E500000214FF000662046FFF724FFD5F89410BC -:102E600000234FF001128F684FF0FF30C4F8343860 -:102E7000C4F81C2804EB431201339F42C2F80069D6 -:102E8000C2F8006BC2F80809C2F8080BF2D20B684E -:102E9000D5F89020C5F89830636210231361166945 -:102EA00016F01006FBD11220FFF77AF9D4F800389B -:102EB00023F4FE63C4F80038A36943F4402343F0CD -:102EC0001003A3610923C4F81038C4F814380B4B5D -:102ED000EB604FF0C043C4F8103B094BC4F8003B13 -:102EE000C4F81069C4F80039D5F8983003F110021D -:102EF00043F48013C5F89820A362F8BDB0430008DE -:102F000040800010D0F8902090F88A10D2F8003855 -:102F100023F4FE6343EA0113C2F80038704700004F -:102F20002DE9F0410EB20D4600EB8608D8F80C10E2 -:102F30000F6807F00303022B53D0032B53D03F4AF3 -:102F40003F4F012B18BF1746D0F890404FEA451E5F -:102F5000002205F1100C04EB0E03C3F8102B8A6954 -:102F6000002A42D04A8A05F158033A435B01E250F5 -:102F70000123D4F81C2803FA0CF31343C4F81C38BB -:102F8000A64400234A69CEF8103905F13F03002A10 -:102F90003BD00A8A04EB8303898B9208012988BFFE -:102FA0004A43D0F89810561841EA02422946C0F820 -:102FB000986020465A60FFF775FED8F80C301B8ADF -:102FC00043EA85531F4305F148035B01E7500123A2 -:102FD000D4F81C2803FA05F51543C4F81C58BDE8BD -:102FE000F081184FB0E7184FAEE704EB4613D3F863 -:102FF000002B22F40042C3F8002B0123D4F81C2834 -:1030000003FA0CF322EA0303B8E704EB83030F4A45 -:1030100004EB461629465A602046FFF743FED6F8D1 -:103020000039012223F4004302FA05F5C6F80039FD -:10303000D4F81C3823EA0505CFE700BF0080001054 -:10304000008004100080081000800C1000040002B2 -:10305000D0F894201268C0F89820FFF7B3BD0000A4 -:103060005831D0F8903049015B5813F4004004D037 -:1030700013F4001F14BF0120022070474831D0F81C -:10308000903049015B5813F4004004D013F4001F42 -:1030900014BF01200220704700EB8101CB68196A40 -:1030A0000B6813604B6853607047000000EB8103AE -:1030B00030B5DD68AA691368D36019B9402B84BFA5 -:1030C000402313606B8A1468D0F890201C4402EBF4 -:1030D0004110013C09B2B4FBF3F46343033323F022 -:1030E000030343EAC44343F0C043C0F8103B2B68DA -:1030F00003F00303012B0ED1D2F8083802EB411084 -:1031000013F4807FD0F8003B14BF43F0805343F0AA -:103110000053C0F8003B02EB4112D2F8003B43F0F1 -:103120000443C2F8003B30BD2DE9F041D0F8906077 -:1031300005460C4606EB4113D3F8087B3A07C3F863 -:10314000087B08D5D6F814381B0704D500EB81039B -:10315000DB685B689847FA072FD5D6F81438DB0789 -:103160002BD505EB8403D968CCB98B69488A5E6896 -:10317000B6FBF0F200FB12628AB91868DA68904276 -:103180000DD2121A83E81400202383F311882146FC -:103190002846FFF78BFF84F31188BDE8F0810123F7 -:1031A00003FA04F26B8923EA02036B81CB6823B133 -:1031B00021462846BDE8F0411847BDE8F0810000EF -:1031C00000EB81034A0170B5DD68D0F890306C697E -:1031D0002668E66056BB1A444FF40020C2F8100976 -:1031E0002A6802F00302012A0AB20ED1D3F80808B5 -:1031F00003EB421410F4807FD4F8000914BF40F0B0 -:10320000805040F00050C4F8000903EB4212D2F89D -:10321000000940F00440C2F800090122D3F8340844 -:1032200002FA01F10143C3F8341870BD19B9402EF8 -:1032300084BF4020206020681A442E8A841940F000 -:103240000050013CB4FBF6F440EAC440C6E700007D -:103250002DE9F041D0F8906004460D4606EB41138D -:10326000D3F80879C3F80879FB071CD5D6F81038CD -:10327000DA0718D500EB8103D3F80CE0DEF8143040 -:10328000D3F800C0DA6894451BD2A2EB0C024FF0D1 -:1032900000081A60C3F80480202383F31188FFF725 -:1032A0008FFF88F311883B0618D50123D6F8342800 -:1032B000AB40134212D029462046BDE8F041FFF74B -:1032C000ADBC012303FA01F2038923EA020303815F -:1032D000DEF80830002BE6D09847E4E7BDE8F0813F -:1032E0002DE9F047D0F8905004466E69AB691E4056 -:1032F000F1046E6103D5BDE8F047FEF741BC002E36 -:1033000012DAD5F8003E9A0705D0D5F8003E23F032 -:103310000303C5F8003ED5F80438204623F0010326 -:10332000C5F80438FEF760FC330505D52046FFF7E5 -:1033300049FC2046FEF748FCB7040CD5D5F8083800 -:1033400013F0060FEB6823F470530CBF43F41053D3 -:1033500043F4A053EB60300704D56368DB680BB11E -:1033600020469847F10200F1A180B2020BD5D4F8B3 -:10337000908000274FF00109D4F89430F9B29B688F -:103380008B4280F0D280F3061AD5D4F890100A6AE6 -:10339000C2F30A1702F00F0302F4F012B2F5802F05 -:1033A00000F0EB80B2F5402F0AD104EB830301F566 -:1033B0008051DB68186A00231A469F4240F0D18092 -:1033C0003003D5F8185835D5E90303D50021204638 -:1033D000FFF7AAFEAA0303D501212046FFF7A4FEAA -:1033E0006B0303D502212046FFF79EFE2F0303D572 -:1033F00003212046FFF798FEE80203D5042120466A -:10340000FFF792FEA90203D505212046FFF78CFEA7 -:103410006A0203D506212046FFF786FE2B0203D55C -:1034200007212046FFF780FEEF0103D50821204643 -:10343000FFF77AFE700340F1C780E90703D500214A -:103440002046FFF705FFAA0703D501212046FFF715 -:10345000FFFE6B0703D502212046FFF7F9FE2F0779 -:1034600003D503212046FFF7F3FEEE0603D5042122 -:103470002046FFF7EDFEA80603D505212046FFF7FD -:10348000E7FE690603D506212046FFF7E1FE2A067E -:1034900003D507212046FFF7DBFEEB0540F19480C2 -:1034A00020460821BDE8F047FFF7D2BED4F890903F -:1034B0004FF000084FF0010AD4F894305FFA88F713 -:1034C0009B68BB42FFF451AF09EB4713D3F80029C7 -:1034D00002F44022B2F5802F24D1D3F80029002A2B -:1034E00020DAD3F8002942F09042C3F80029D3F83B -:1034F0000029002AFBDB3946D4F89000FFF7D2FB05 -:1035000022890AFA07F322EA0303238104EB8703E3 -:10351000DB689B6813B139462046984739462046F8 -:10352000FFF77CFB08F10108C6E708EB4112D2F86F -:10353000003B03F44023B3F5802F10D1D2F8003BB9 -:10354000002B0CDA628909FA01F322EA0303638192 -:1035500004EB8103DB68DB680BB120469847013739 -:103560000AE713F0030F00D10A68072B03F10103E8 -:103570009EBF0270120A01301FE704EB830301F5BE -:103580008051DA6890690268D0F808C04068A2EB00 -:10359000000E00221046974208D1DB689B699A68AA -:1035A0003A449A605A6817445F6009E712F0030FC3 -:1035B00000D10868964502F1010282BF8CF8000034 -:1035C000000A0CF1010CE6E7BDE8F08708B50348F6 -:1035D000FFF786FEBDE80840FFF76ABA004E0020FC -:1035E00008B50348FFF77CFEBDE80840FFF760BA66 -:1035F0009C4E0020D0F8903003EB4111D1F8003BF5 -:1036000043F40013C1F8003B70470000D0F890303D -:1036100003EB4111D1F8003943F40013C1F800392C -:1036200070470000D0F8903003EB4111D1F8003B17 -:1036300023F40013C1F8003B70470000D0F890302D -:1036400003EB4111D1F8003923F40013C1F800391C -:103650007047000000F1604300F01F0209014009BB -:1036600003F56143C9B2800083F80013012300F120 -:103670006040934000F56140C0F8803103607047BE -:1036800030B50433039C0172002104FB0325C361A0 -:10369000049B00600363059B4060C160426102615E -:1036A0008561046242628162C162436330BD000091 -:1036B0000022416AC260416101616FF001018262D2 -:1036C000C262FEF7DFBD000003694269934203D185 -:1036D000C2680AB100207047181D7047036919605D -:1036E0000021C2680132C260C269134482699342F8 -:1036F000036124BF436A0361FEF7B8BD38B50446D1 -:103700000D46E3683BB162690020131D1268A36295 -:103710001344E36238BD237A33B929462046FEF7C5 -:1037200095FD0028EDDA38BD6FF00100FBE70000E1 -:10373000C368C269013BC360436913448269934211 -:10374000436124BF436A436100238362036B03B177 -:103750001847704770B52023044683F31188866AA2 -:103760003EB9FFF7CBFF054618B186F3118828460E -:1037700070BDA36AE26A13F8015B9342A36202D3AD -:103780002046FFF7D5FF002383F31188EFE7000001 -:103790002DE9F84F04460E4690469946202787F3B8 -:1037A00011880025AA46D4F828B0BBF1000F09D132 -:1037B00049462046FFF7A2FF20B18BF31188284627 -:1037C000BDE8F88FA16AA8EB050BE36A5B1A9B457D -:1037D00028BF9B46BBF1400F1BD9334601F1400285 -:1037E00051F8040B914243F8040BF9D1A36A403617 -:1037F00040354033A362A26AE36A9A4202D320466C -:10380000FFF796FF8AF311884545D8D287F31188D0 -:10381000C9E730465A46FDF701FBA36A5E445D44A2 -:103820005B44A362E7E7000010B5029C0433017219 -:10383000C36103FB0421002300608362C362039B16 -:1038400040600363049BC460426102618161046261 -:103850004262436310BD0000026A6FF00101C26062 -:10386000426A4261026100228262C262FEF70ABDC0 -:10387000436902699A4203D1C2680AB100207047C5 -:10388000184650F8043B0B6070470000C3680021E5 -:10389000C2690133C360436913448269934243613F -:1038A00024BF436A4361FEF7E1BC000038B504461B -:1038B0000D46E3683BB1236900201A1DA262E2694C -:1038C0001344E36238BD237A33B929462046FEF714 -:1038D000BDFC0028EDDA38BD6FF00100FBE7000009 -:1038E00003691960C268013AC260C26913448269FF -:1038F0009342036124BF436A036100238362036B25 -:1039000003B118477047000070B5202304460E46E7 -:1039100083F31188856A35B91146FFF7C7FF10B1E7 -:1039200085F3118870BDA36A1E70A36AE26A013331 -:103930009342A36204D3E16920460439FFF7D0FF24 -:10394000002080F3118870BD2DE9F84F04460D4624 -:1039500091469A464FF0200888F311880026B34616 -:10396000A76A4FB951462046FFF7A0FF20B187F361 -:1039700011883046BDE8F88FA06AA9EB0603E76A14 -:103980003F1A9F4228BF1F46402F1BD905F1400315 -:1039900055F8042B9D4240F8042BF9D1A36A403618 -:1039A0004033A362A26AE36A9A4204D3E1692046E3 -:1039B0000439FFF795FF8BF311884E45D9D288F370 -:1039C0001188CDE729463A46FDF728FAA36A3D4417 -:1039D0003E443B44A362E5E7026943699A4203D14E -:1039E000C3681BB9184670470023FBE7836A002BA6 -:1039F000F8D0043B9B1AF5D01360C368013BC36049 -:103A0000C3691A4483699A42026124BF436A03610D -:103A1000002383620123E5E700F0D6B8034B0022C0 -:103A200058631A610222DA60704700BF000C004040 -:103A30000022014BDA607047000C0040014B5863D4 -:103A4000704700BF000C0040014B586A704700BF30 -:103A5000000C00404B6843608B688360CB68C36098 -:103A60000B6943614B6903628B6943620B680360B6 -:103A70007047000008B5304B40F2FF712F48D3F873 -:103A800088200A43C3F88820D3F8882022F4FF62F4 -:103A900022F00702C3F88820D3F88820D3F8E0206A -:103AA0000A43C3F8E020D3F808210A43C3F80821E9 -:103AB000234AD3F808311146FFF7CCFF214802F121 -:103AC0001C01FFF7C7FF204802F13801FFF7C2FFD2 -:103AD0001E4802F15401FFF7BDFF1D4802F17001BD -:103AE000FFF7B8FF1B4802F18C01FFF7B3FF1A483C -:103AF00002F1A801FFF7AEFF184802F1C401FFF779 -:103B0000A9FF174802F1E001FFF7A4FF154802F1F1 -:103B1000FC01FFF79FFF144802F58C71FFF79AFF35 -:103B200000F006F9114B05229A604FF06052DA60FE -:103B30000F4A1A6108BD00BF004402580000025835 -:103B4000EC4300080004025800080258000C025818 -:103B5000001002580014025800180258001C0258A5 -:103B600000200258002402580028025890ED00E07E -:103B70001F00080308B500F0F3FAFEF7EFFA0F4B49 -:103B8000D3F8DC2042F04002C3F8DC20D3F8042153 -:103B900022F04002C3F80421D3F80431084B1A681C -:103BA00042F008021A601A6842F004021A60FEF736 -:103BB00033FFBDE80840FEF7DFBC00BF00440258F9 -:103BC0000018024870470000114BD3F8E82042F07B -:103BD0000802C3F8E820D3F8102142F00802C3F825 -:103BE00010210C4AD3F81031D36B43F00803D36390 -:103BF000C722094B9A624FF0FF32DA6200229A61C3 -:103C00005A63DA605A6001225A611A60704700BF35 -:103C1000004402580010005C000C0040094A08B53E -:103C20001369D1680B40D9B29B076FEA010111619A -:103C300007D5202383F31188FEF7B0FA002383F31E -:103C4000118808BD000C0040384B4FF0FF31D3F80D -:103C50008020C3F88010D3F880200022C3F8802091 -:103C6000D3F88000D3F88400C3F88410D3F884001C -:103C7000C3F88420D3F88400D86F40F0FF4040F4AC -:103C8000FF0040F43F5040F03F00D867D86F20F06D -:103C9000FF4020F4FF0020F43F5020F03F00D867A1 -:103CA000D86FD3F888006FEA40506FEA5050C3F8DD -:103CB0008800D3F88800C0F30A00C3F88800D3F85E -:103CC0008800D3F89000C3F89010D3F89000C3F8A0 -:103CD0009020D3F89000D3F89400C3F89410D3F850 -:103CE0009400C3F89420D3F89400D3F89800C3F854 -:103CF0009810D3F89800C3F89820D3F89800D3F818 -:103D00008C00C3F88C10D3F88C00C3F88C20D3F847 -:103D10008C00D3F89C00C3F89C10D3F89C10C3F817 -:103D20009C20D3F89C3000F0E7B900BF0044025853 -:103D30000122614B1A60614BD3F8F42042F0020279 -:103D4000C3F8F420D3F81C2142F00202C3F81C216E -:103D50000222D3F81C315A4BDA605A689104FCD520 -:103D6000584A1A6001229A60574ADA6000221A61A2 -:103D70004FF440429A61524B9A699204FCD51A68FA -:103D800042F480721A604D4B1A6F12F4407F04D0D7 -:103D90004FF480321A6700221A671A6842F0010253 -:103DA0001A60464A134611684807FCD50021116184 -:103DB0001A6912F03802FBD1012119604FF08041DD -:103DC00059605A67414ADA62414A1A611A6842F4F4 -:103DD00080321A60394A134611688903FCD511688C -:103DE00041F4805111601A689204FCD5394A3A496D -:103DF0009A6200225A6319633849DA6399635A64F4 -:103E0000374A1A64374ADA621A6842F0A8521A60CE -:103E10002A4B1A6802F02852B2F1285FF9D14822E1 -:103E20009A614FF48862DA6140221A622E4ADA649B -:103E30004FF000521A652D4A5A652D4A9A65322272 -:103E40002C4B1A601A6802F00F02022AFAD11B4B9F -:103E50001A6942F003021A611A6902F03802182A3C -:103E6000FAD1D3F8DC2042F00052C3F8DC20D3F8BA -:103E7000042142F00052C3F80421D3F80421D3F8FE -:103E8000DC2042F08042C3F8DC20D3F8042142F069 -:103E90008042C3F80421D3F80421D3F8DC2042F097 -:103EA0000042C3F8DC20D3F8042142F00042C3F8FA -:103EB0000421D3F8043170470881005100440258AE -:103EC0000048025800C000F0020000010000FF019D -:103ED0000088900832206000630207011D02040080 -:103EE00047040508FD0BFF01200000200010E00042 -:103EF00000010100002000524FF0B04208B5D2F896 -:103F0000883003F00103C2F8883023B1044A1368F3 -:103F10000BB150689847BDE80840FEF7C9BD00BF27 -:103F2000504F00204FF0B04208B5D2F8883003F06F -:103F30000203C2F8883023B1044A93680BB1D068F9 -:103F40009847BDE80840FEF7B3BD00BF504F0020C2 -:103F50004FF0B04208B5D2F8883003F00403C2F83D -:103F6000883023B1044A13690BB150699847BDE802 -:103F70000840FEF79DBD00BF504F00204FF0B042FB -:103F800008B5D2F8883003F00803C2F8883023B1AE -:103F9000044A93690BB1D0699847BDE80840FEF721 -:103FA00087BD00BF504F00204FF0B04208B5D2F897 -:103FB000883003F01003C2F8883023B1044A136A32 -:103FC0000BB1506A9847BDE80840FEF771BD00BFCD -:103FD000504F00204FF0B04310B5D3F8884004F4A0 -:103FE0007872C3F88820A30604D5124A936A0BB1ED -:103FF000D06A9847600604D50E4A136B0BB1506B1C -:104000009847210604D50B4A936B0BB1D06B9847A8 -:10401000E20504D5074A136C0BB1506C9847A30511 -:1040200004D5044A936C0BB1D06C9847BDE810409E -:10403000FEF73EBD504F00204FF0B04310B5D3F80F -:10404000884004F47C42C3F88820620504D5164AEF -:10405000136D0BB1506D9847230504D5124A936D2B -:104060000BB1D06D9847E00404D50F4A136E0BB125 -:10407000506E9847A10404D50B4A936E0BB1D06ED5 -:104080009847620404D5084A136F0BB1506F9847E4 -:10409000230404D5044A936F0BB1D06F9847BDE851 -:1040A0001040FEF705BD00BF504F002008B5034883 -:1040B000FDF7F4F8BDE80840FEF7FABCCC23002079 -:1040C00008B50348FDF7EAF8BDE80840FEF7F0BC84 -:1040D0003824002008B50348FDF7E0F8BDE80840A3 -:1040E000FEF7E6BCA424002008B5FFF797FDBDE865 -:1040F0000840FEF7DDBC0000062108B50846FFF7C2 -:10410000A9FA06210720FFF7A5FA06210820FFF7E4 -:10411000A1FA06210920FFF79DFA06210A20FFF7E0 -:1041200099FA06211720FFF795FA06212820FFF7B4 -:1041300091FA09217A20FFF78DFA07213220FFF743 -:1041400089FA0C212620FFF785FA0C212720FFF79A -:1041500081FA0C215220BDE80840FFF77BBA00002D -:1041600008B5FFF771FD00F00DF8FDF7B1FAFDF7A6 -:104170008BFCFDF75BFBFFF725FDBDE80840FFF773 -:104180004BBC0000002304491A465A50C818083393 -:104190004260802BF9D17047504F002010B5013993 -:1041A0000244904201D1002010BD10F8013B11F8EB -:1041B000014FA342F5D0181B10BD0000034611F8B3 -:1041C000012B03F8012B002AF9D1704712101213AA -:1041D00012110000C8320020CC2300203824002017 -:1041E000A424002053544D333248373F3F3F0053FF -:1041F000544D3332483734332F3735330000000005 -:104200000096000000000000000000000000000018 -:1042100000000000000000000000000099160008E7 -:1042200085160008C1160008AD160008B91600086A -:10423000A5160008911600087D160008CD16000886 -:1042400000000000A517000891170008CD1700080E -:10425000B9170008C5170008B11700089D17000816 -:10426000891700082918000800000000010000005C -:10427000000000006D61696E0000000094420008BB -:1042800050310020C83200200100000059210008F0 -:104290000000000069646C6500000000020000007E -:1042A00000000000D11900083D1A0008400040003D -:1042B000704B0020804B0020020000000000000036 -:1042C0000300000000000000851A00080000000044 -:1042D00010000000904B00200000000001000000D2 -:1042E00000000000004E0020010102004865782F08 -:1042F00050726F6669434E430025424F4152442538 -:104300002D424C002553455249414C2500000000E8 -:104310001925000831240008C9240008AD2400082C -:10432000430000002843000809024300020100C0C6 -:1043300032090400000102020100052400100105F9 -:10434000240100010424020205240600010705825D -:10435000030800FF09040100020A0000000705012C -:10436000024000000705810240000000120000002A -:10437000744300081201100102000040AE2D161017 -:1043800000020102030100000403090425424F4119 -:1043900052442500437562654F72616E6765003057 -:1043A000313233343536373839414243444546009B -:1043B00000000000FD1B0008DD1E0008891F00082A -:1043C00040004000384F0020384F0020010000001E -:1043D000484F00208000000040010000080000005D -:1043E0000001000000040000080000000000812A15 -:1043F00000000000AAAAAAAA00000000FFFF000017 -:104400000000000000A00A00000100000000000001 -:10441000AAAAAAAA00000000FFFF000000000000F6 -:10442000000000001400005400000000AAAAAAAA7C -:1044300014000054FFFF0000000000000000000016 -:1044400000681A0000000000AAAA8AAA00541500F9 -:10445000FFFF0000000070077700000040810200AD -:1044600000000000AAAAAAAA00410100F7FF00006C -:1044700000000070070000000000000000000000C5 -:10448000AAAAAAAA00000000FFFF00000000000086 -:10449000000000000000000000000000AAAAAAAA74 -:1044A00000000000FFFF000000000000000000000E -:1044B0000000000000000000AAAAAAAA0000000054 -:1044C000FFFF0000000000000000000000000000EE -:1044D00000000000AAAAAAAA00000000FFFF000036 -:1044E00000000000000000000000000000000000CC -:1044F000AAAAAAAA00000000FFFF00000000000016 -:10450000000000000000000000000000AAAAAAAA03 -:1045100000000000FFFF000000000000000000009D -:104520008C0000000000000000001E0000000000E1 -:10453000FF00000000000000E44100083F00000010 -:1045400050040000EF4100083F000000009600000A -:1045500000000800960000000008000004000000B1 -:104560008843000800000000000000000000000078 -:0C4570000000000000000000000000003F +:101060009B6AFEE700ED00E0FEE7000000B595B0EA +:10107000132101A801F00EFD9DF84F307BB1002334 +:10108000132101A88DF84F3001F0FEFC054BD3F879 +:10109000002882F30888D3F804389847FEE715B093 +:1010A0005DF804FB0090F01F30B50A44084D9142F2 +:1010B0000DD011F8013B5840082340F30004013BD8 +:1010C0002C4013F0FF0384EA5000F6D1EFE730BD67 +:1010D0002083B8ED026843681143016003B11847EB +:1010E00070470000024A136843F0C0031360704762 +:1010F00000440040024A136843F0C0031360704785 +:1011000000480040024A136843F0C0031360704770 +:101110000078004037B5274C274D204600F0F2FA02 +:1011200004F11400009400234FF40072234900F0EE +:10113000B3F94FF40072224904F138000094214BB6 +:1011400000F02CFA204BC4E91735204C204600F063 +:10115000D9FA04F11400009400234FF400721C49E2 +:1011600000F09AF94FF400721A4904F13800009423 +:10117000194B00F013FA194BC4E91735184C2046E7 +:1011800000F0C0FA04F1140000234FF40072154976 +:10119000009400F081F9144B4FF40072134904F1EC +:1011A0003800009400F0FAF9114BC4E9173503B088 +:1011B00030BD00BFCC23002000E1F5051025002044 +:1011C000102B0020E51000080044004038240020C7 +:1011D00010270020102D0020F510000800480040C6 +:1011E000A42400201029002005110008102F002041 +:1011F00000780040037C30B5334C002918BF0C4602 +:10120000012B18D1314B98420FD1314BD3F8E82044 +:1012100042F40032C3F8E820D3F8102142F400323F +:10122000C3F81021D3F8103105E02A4B98422FD093 +:10123000294B984238D02268036EC16D03EB5203EC +:101240008466B3FBF2F36268150442BF23F007051E +:1012500003F0070343EA4503CB60A36843F0400370 +:101260004B60E36843F001038B6042F4967343F0F4 +:1012700001030B604FF0FF330B62510505D512F0EF +:1012800010221DD0B2F1805F1CD080F8643030BDD8 +:101290000F4BD3F8E82042F48022C3F8E820D3F8BB +:1012A000102142F48022BBE7094BD3F8E82042F03A +:1012B0008042C3F8E820D3F8102142F08042AFE723 +:1012C0007F23E2E73F23E0E72C420008CC23002005 +:1012D0000044025838240020A42400202DE9F047BF +:1012E000C66D05463768F4692107346219D014F0D9 +:1012F000080118BF8021E20748BF41F02001A30781 +:101300004FF0200348BF41F04001600748BF41F45F +:10131000807183F31188281DFFF7DCFE002383F31F +:101320001188E2050AD5202383F311884FF4007158 +:10133000281DFFF7CFFE002383F311884FF020090B +:101340004FF0000A14F0200838D13B0616D54FF0B4 +:10135000200905F1380A200610D589F31188504676 +:1013600000F050F9002836DA0821281DFFF7B2FEF8 +:1013700027F080033360002383F31188790614D5A6 +:10138000620612D5202383F31188D5E913239A42EC +:1013900008D12B6C33B127F040071021281DFFF72F +:1013A00099FE3760002383F31188E30618D5AA6EEF +:1013B0001369ABB15069BDE8F047184789F311884C +:1013C000736A284695F86410194000F0B5F98AF35D +:1013D0001188F469B6E7B06288F31188F469BAE756 +:1013E000BDE8F087F8B51546826804460B46AA4268 +:1013F00000D28568A1692669761AB5420BD21846D3 +:101400002A46FFF715FDA3692B44A3612846A3686C +:101410005B1BA360F8BD0CD9AF1B18463246FFF723 +:1014200007FD3A46E1683044FFF702FDE3683B44BC +:10143000EBE718462A46FFF7FBFCE368E5E7000008 +:1014400083689342F7B50446154600D28568D4E90F +:101450000460361AB5420BD22A46FFF7E9FC6369ED +:101460002B4463612846A3685B1BA36003B0F0BDF7 +:101470000DD93246AF1B0191FFF7DAFC01993A46CC +:10148000E0683144FFF7D4FCE3683B44E9E72A46CF +:10149000FFF7CEFCE368E4E710B50A440024C3611B +:1014A000029B8460C16002610362C0E90000C0E980 +:1014B000051110BD08B5D0E90532934201D182680B +:1014C00082B98268013282605A1C4261197000211F +:1014D000D0E904329A4224BFC368436100F0DAFEC7 +:1014E000002008BD4FF0FF30FBE7000070B520235F +:1014F00004460E4683F31188A568A5B1A368A269C6 +:10150000013BA360531CA36115782269934224BF59 +:10151000E368A361E3690BB120469847002383F396 +:101520001188284607E03146204600F0A3FE002837 +:10153000E2DA85F3118870BD2DE9F74F04460E46B7 +:1015400017469846D0F81C904FF0200A8AF311886D +:101550004FF0000B154665B12A4631462046FFF78D +:1015600041FF034660B94146204600F083FE002853 +:10157000F1D0002383F31188781B03B0BDE8F08F0E +:10158000B9F1000F03D001902046C847019B8BF3AF +:101590001188ED1A1E448AF31188DCE7C160C3612B +:1015A000009B82600362C0E905111144C0E900009C +:1015B00001617047F8B504460D461646202383F3B3 +:1015C0001188A768A7B1A368013BA36063695A1C8F +:1015D00062611D70D4E904329A4224BFE3686361FA +:1015E000E3690BB120469847002080F3118807E09B +:1015F0003146204600F03EFE0028E2DA87F31188EB +:10160000F8BD0000D0E9052310B59A4201D18268E7 +:101610007AB982680021013282605A1C82611C788A +:1016200003699A4224BFC368836100F033FE2046F9 +:1016300010BD4FF0FF30FBE72DE9F74F04460E4693 +:1016400017469846D0F81C904FF0200A8AF311886C +:101650004FF0000B154665B12A4631462046FFF78C +:10166000EFFE034660B94146204600F003FE002825 +:10167000F1D0002383F31188781B03B0BDE8F08F0D +:10168000B9F1000F03D001902046C847019B8BF3AE +:101690001188ED1A1E448AF31188DCE7026843685A +:1016A0001143016003B11847704700001430FFF781 +:1016B00043BF00004FF0FF331430FFF73DBF000081 +:1016C0003830FFF7B9BF00004FF0FF333830FFF775 +:1016D000B3BF00001430FFF709BF00004FF0FF3127 +:1016E0001430FFF703BF00003830FFF763BF00007E +:1016F0004FF0FF323830FFF75DBF00000020704729 +:10170000FFF708BD044B036000234360C0E90233C8 +:1017100001230374704700BF4442000810B5202322 +:10172000044683F31188FFF765FD02232374002329 +:1017300083F3118810BD000038B5C36904460D4617 +:101740001BB904210844FFF7A9FF294604F114003E +:10175000FFF7B0FE002806DA201D4FF48061BDE8D7 +:101760003840FFF79BBF38BD0268436811430160F2 +:1017700003B118477047000013B5406B00F5805463 +:10178000D4F8A4381A681178042914D1017C0229EC +:1017900011D11979012312898B4013420BD101A970 +:1017A0004C3002F07BF8D4F8A4480246019B217922 +:1017B000206800F0DFF902B010BD0000143001F025 +:1017C000FDBF00004FF0FF33143001F0F7BF000001 +:1017D0004C3002F0CFB800004FF0FF334C3002F035 +:1017E000C9B80000143001F0CBBF00004FF0FF314A +:1017F000143001F0C5BF00004C3002F09BB800006F +:101800004FF0FF324C3002F095B8000000207047D6 +:1018100010B500F58054D4F8A4381A68117804295A +:1018200017D1017C022914D15979012352898B40A7 +:1018300013420ED1143001F05DFF024648B1D4F8D6 +:10184000A4484FF4407361792068BDE8104000F06F +:101850007FB910BD406BFFF7DBBF00007047000091 +:101860007FB5124B0125042604460360002305744E +:1018700000F1840243602946C0E902330C4B029018 +:10188000143001934FF44073009601F00FFF094BA1 +:1018900004F69442294604F14C000294CDE9006319 +:1018A0004FF4407301F0D6FF04B070BD6C420008E5 +:1018B00055180008791700080A68202383F3118857 +:1018C0000B790B3342F823004B79133342F8230092 +:1018D0008B7913B10B3342F8230000F58053C3F822 +:1018E000A41802230374002383F3118870470000B7 +:1018F00038B5037F044613B190F85430ABB90125D5 +:10190000201D0221FFF730FF04F114006FF00101E8 +:10191000257700F0CBFC04F14C0084F854506FF0B4 +:101920000101BDE8384000F0C1BC38BD10B501214F +:1019300004460430FFF718FF0023237784F854305F +:1019400010BD000038B504460025143001F0C6FE75 +:1019500004F14C00257701F095FF201D84F85450C8 +:101960000121FFF701FF2046BDE83840FFF750BFD7 +:1019700090F8803003F06003202B06D190F881208E +:101980000023212A03D81F2A06D800207047222AC4 +:10199000FBD1C0E91D3303E0034A42670722826797 +:1019A000C3670120704700BF2C22002037B500F527 +:1019B0008055D5F8A4381A68117804291AD1017C09 +:1019C000022917D11979012312898B40134211D1B1 +:1019D00000F14C04204602F015F858B101A9204648 +:1019E00001F05CFFD5F8A4480246019B21792068EC +:1019F00000F0C0F803B030BD01F10B03F0B550F8B2 +:101A0000236085B004460D46FEB1202383F3118880 +:101A100004EB8507301D0821FFF7A6FEFB6806F1E1 +:101A20004C005B691B681BB1019001F045FF0198F8 +:101A300003A901F033FF024648B1039B2946204623 +:101A400000F098F8002383F3118805B0F0BDFB681F +:101A50005A691268002AF5D01B8A013B1340F1D164 +:101A600004F18002EAE70000133138B550F8214054 +:101A7000ECB1202383F3118804F58053D3F8A42814 +:101A80001368527903EB8203DB689B695D6845B19B +:101A900004216018FFF768FE294604F1140001F0E4 +:101AA00033FE2046FFF7B4FE002383F3118838BDD0 +:101AB0007047000001F026B901234022002110B533 +:101AC000044600F8303BFFF7D9F90023C4E901339D +:101AD00010BD000010B52023044683F31188242292 +:101AE000416000210C30FFF7C9F9204601F02CF9C4 +:101AF00002232370002383F3118810BD70B500EB1F +:101B00008103054650690E461446DA6018B110226A +:101B10000021FFF7B3F9A06918B110220021FFF7E7 +:101B2000ADF931462846BDE8704001F01FBA00000B +:101B300083682022002103F0011310B5044683605E +:101B40001030FFF79BF92046BDE8104001F09ABA2B +:101B5000F0B4012500EB810447898D40E4683D43E2 +:101B6000A469458123600023A2606360F0BC01F09A +:101B7000B7BA0000F0B4012500EB810407898D405D +:101B8000E4683D436469058123600023A2606360CB +:101B9000F0BC01F02DBB000070B502230025044607 +:101BA000242203702946C0F888500C3040F8045CA9 +:101BB000FFF764F9204684F8705001F06BF9636810 +:101BC0001B6823B129462046BDE87040184770BD08 +:101BD000037880F88C300523037043681B6810B5C8 +:101BE00004460BB1042198470023A36010BD0000F8 +:101BF00090F88C20436802701B680BB105211847D0 +:101C00007047000070B590F87030044613B100239F +:101C100080F8703004F18002204601F057FA6368C2 +:101C20009B68B3B994F8803013F0600535D000217B +:101C3000204601F001FD0021204601F0F1FC63681F +:101C40001B6813B1062120469847062384F870309C +:101C500070BD204698470028E4D0B4F88630A26FC3 +:101C60009A4288BFA36794F98030A56F002B4FF08C +:101C7000200380F20381002D00F0F280092284F815 +:101C8000702083F3118800212046D4E91D23FFF73B +:101C900071FF002383F31188DAE794F8812003F0C1 +:101CA0007F0343EA022340F20232934200F0C580F0 +:101CB00021D8B3F5807F48D00DD8012B3FD0022B1F +:101CC00000F09380002BB2D104F1880262670222F7 +:101CD000A267E367C1E7B3F5817F00F09B80B3F5AE +:101CE000407FA4D194F88230012BA0D1B4F8883081 +:101CF00043F0020332E0B3F5006F4DD017D8B3F5CF +:101D0000A06F31D0A3F5C063012B90D86368204643 +:101D100094F882205E6894F88310B4F88430B04759 +:101D2000002884D0436863670368A3671AE0B3F5AB +:101D3000106F36D040F6024293427FF478AF5C4B8E +:101D400063670223A3670023C3E794F88230012B63 +:101D50007FF46DAFB4F8883023F00203A4F8883024 +:101D6000C4E91D55E56778E7B4F88030B3F5A06F96 +:101D70000ED194F88230204684F88A3001F0E8F8D9 +:101D800063681B6813B10121204698470323237021 +:101D90000023C4E91D339CE704F18B03636701232F +:101DA000C3E72378042B10D1202383F31188204626 +:101DB000FFF7BEFE85F311880321636884F88B501A +:101DC00021701B680BB12046984794F88230002B95 +:101DD000DED084F88B300423237063681B68002BEB +:101DE000D6D0022120469847D2E794F88430204686 +:101DF0001D0603F00F010AD501F05AF9012804D09D +:101E000002287FF414AF2B4B9AE72B4B98E701F095 +:101E100041F9F3E794F88230002B7FF408AF94F88F +:101E2000843013F00F01B3D01A06204602D501F01A +:101E30001BFCADE701F00CFCAAE794F88230002B04 +:101E40007FF4F5AE94F8843013F00F01A0D01B0698 +:101E5000204602D501F0F0FB9AE701F0E1FB97E79D +:101E6000142284F8702083F311882B462A462946D1 +:101E70002046FFF76DFE85F31188E9E65DB1152276 +:101E800084F8702083F3118800212046D4E91D23B3 +:101E9000FFF75EFEFDE60B2284F8702083F31188C5 +:101EA0002B462A4629462046FFF764FEE3E700BF9B +:101EB0009C420008944200089842000838B590F807 +:101EC00070300446002B3ED0063BDAB20F2A34D8DD +:101ED0000F2B32D8DFE803F03731310822323131AD +:101EE0003131313131313737856FB0F886309D422D +:101EF00014D2C3681B8AB5FBF3F203FB12556DB90C +:101F0000202383F311882B462A462946FFF732FE09 +:101F100085F311880A2384F870300EE0142384F8C6 +:101F20007030202383F31188002320461A46194677 +:101F3000FFF70EFE002383F3118838BDC36F03B192 +:101F400098470023E7E70021204601F075FB0021B8 +:101F5000204601F065FB63681B6813B1062120462B +:101F600098470623D7E7000010B590F87030044674 +:101F7000142B29D017D8062B05D001D81BB110BDC2 +:101F8000093B022BFBD80021204601F055FB002124 +:101F9000204601F045FB63681B6813B1062120460B +:101FA0009847062319E0152BE9D10B2380F87030F0 +:101FB000202383F3118800231A461946FFF7DAFD20 +:101FC000002383F31188DAE7C3689B695B68002B01 +:101FD000D5D1C36F03B19847002384F87030CEE7A2 +:101FE000024B0022C3E900339A6070471031002091 +:101FF000002382680374054B1B6899689142FBD2E9 +:102000005A680360426010605860704710310020C9 +:1020100008B5202383F31188037C032B05D0042B00 +:102020000DD02BB983F3118808BD436900221A60D3 +:102030004FF0FF334361FFF7DBFF0023F2E7D0E906 +:10204000003213605A60F3E7002382680374054B83 +:102050001B6899689142FBD85A680360426010601F +:102060005860704710310020054B196908741868D2 +:10207000026853601A60186101230374FEF7AAB95D +:10208000103100204B1C30B5044687B00A4D10D0EB +:102090002B6901A8094A00F025F92046FFF7E4FF63 +:1020A000049B13B101A800F059F92B69586907B0D6 +:1020B00030BDFFF7D9FFF8E71031002011200008EC +:1020C00038B50C4D044641612B6981689A6891428C +:1020D00003D8BDE83840FFF78BBF1846FFF7B4FFC1 +:1020E00001232C61014623742046BDE83840FEF7E9 +:1020F00071B900BF10310020044B1A681B69906849 +:102100009B68984294BF0020012070471031002046 +:1021100010B5084C236820691A68546022600122B7 +:1021200023611A74FFF790FF01462069BDE8104053 +:10213000FEF750B91031002008B5FFF7DDFF18B1E8 +:10214000BDE80840FFF7E4BF08BD0000FFF7E0BFAF +:10215000FEE7000010B50C4CFFF742FF00F0B4F8AA +:1021600080220A49204600F03BF8012344F8180C6D +:10217000037400F0A5FC002383F3118862B60448C1 +:10218000BDE8104000F04CB838310020A0420008F3 +:10219000B042000800F01CB9EFF3118020B9EFF352 +:1021A0000583202282F311887047000010B530B9F2 +:1021B000EFF30584C4F3080414B180F3118810BD53 +:1021C000FFF7BAFF84F31188F9E70000034A51686A +:1021D00053685B1A9842FBD8704700BF001000E0BC +:1021E00082600222028270478368A3F17C0243F876 +:1021F0000C2C026943F83C2C426943F8382C074AFE +:1022000043F81C2CC268A3F1180043F8102C0222DA +:1022100003F8082C002203F8072C7047ED03000890 +:1022200010B5202383F31188FFF7DEFF0021044659 +:10223000FFF746FF002383F31188204610BD0000FE +:10224000024B1B6958610F20FFF70EBF10310020B1 +:10225000202383F31188FFF7F3BF000008B5014680 +:10226000202383F311880820FFF70CFF002383F35A +:10227000118808BD49B1064B42681B6918605A6055 +:10228000136043600420FFF7FDBE4FF0FF3070473E +:10229000103100200368984206D01A68026050602E +:1022A00018465961FFF7A4BE7047000038B50446D0 +:1022B0000D462068844200D138BD036823605C600D +:1022C0004561FFF795FEF4E7054B4FF0FF3103F151 +:1022D0001402C3E905220022C3E90712704700BFB8 +:1022E0001031002070B51C4E05460C46C0E9032392 +:1022F00001F0BEFB334653F8142F9A420DD13062E1 +:102300000A2C2CBF00190A302A60C5E90124C6E94D +:102310000555BDE8704001F095BB316A431AE318DA +:1023200038BF1C469368A34202D9081901F09AFBF2 +:1023300073699A6894420CD85A68AC602B606A60E2 +:1023400015609A685D60121B9A604FF0FF33F3616D +:1023500070BDA41A1B68ECE71031002038B51B4C87 +:10236000636998420DD08168D0E9003213605A60E9 +:102370000022C2609A680A449A604FF0FF33E3611A +:1023800038BD03682246002142F8143F93425A6048 +:10239000C16003D1BDE8384001F05EBB9A68816836 +:1023A000256A0A449A6001F063FB6369411B9A68DD +:1023B0008A42E5D9AB181D1A206A092D98BF01F190 +:1023C0000A02BDE83840104401F04CBB1031002037 +:1023D0002DE9F041184C002704F11406656901F05D +:1023E00047FB236AAA68C11A8A4215D81344D5F854 +:1023F0000C802362D5E9003213605A606369EF6094 +:10240000B34201D101F028FB87F311882869C04746 +:10241000202383F31188E1E76169B14209D01344B5 +:102420001B1ABDE8F0410A2B2CBFC0180A3001F07E +:1024300019BBBDE8F08100BF1031002000207047BB +:10244000FEE70000704700004FF0FF3070470000CB +:1024500002290CD0032904D00129074818BF002005 +:102460007047032A05D8054800EBC20070470448AE +:1024700070470020704700BF984300083C220020AE +:102480004C43000870B59AB005460846144601A9A9 +:1024900000F0C2F801A8FEF7E9FC431C0022C6B216 +:1024A0005B001046C5E9003423700323023404F8AE +:1024B000013C01ABD1B202348E4201D81AB070BDDA +:1024C00013F8011B013204F8010C04F8021CF1E7B7 +:1024D00008B5202383F311880348FFF767FA002328 +:1024E00083F3118808BD00BFC832002090F8803007 +:1024F00003F01F02012A07D190F881200B2A03D193 +:102500000023C0E91D3315E003F06003202B08D140 +:10251000B0F884302BB990F88120212A03D81F2AE3 +:1025200004D8FFF725BA222AEBD0FAE7034A42671C +:1025300007228267C3670120704700BF3322002053 +:1025400007B5052917D8DFE801F019160319192076 +:10255000202383F31188104A01210190FFF7CEFA5E +:10256000019802210D4AFFF7C9FA0D48FFF7EAF971 +:10257000002383F3118803B05DF804FB202383F369 +:1025800011880748FFF7B4F9F2E7202383F3118895 +:102590000348FFF7CBF9EBE7EC42000810430008D3 +:1025A000C832002038B50C4D0C4C2A460C4904F1B9 +:1025B0000800FFF767FF05F1CA0204F1100009499E +:1025C000FFF760FF05F5CA7204F118000649BDE87F +:1025D0003840FFF757BF00BFA04B00203C2200202F +:1025E000C8420008D5420008E042000870B5044621 +:1025F00008460D46FEF73AFCC6B220460134037881 +:102600000BB9184670BD32462946FEF71BFC002860 +:10261000F3D10120F6E700002DE9F84F05460C46FE +:10262000FEF724FC2C49C6B22846FFF7DFFF08B1AD +:102630000336F6B229492846FFF7D8FF08B110360D +:10264000F6B2632E0DD8DFF89080DFF89090244F1B +:10265000DFF894A0DFF894B02E7846B92670BDE874 +:10266000F88F29462046BDE8F84F01F0C1BD252E60 +:102670002ED1072241462846FEF7E4FB70B9DBF86D +:10268000003007350A3444F80A3CDBF8043044F8DB +:10269000063CBBF8083024F8023CDDE70822494636 +:1026A0002846FEF7CFFB98B9A21C0E4B19780232D0 +:1026B0000909C95D02F8041C13F8011B01F00F01A0 +:1026C0005345C95D02F8031CF0D118340835C3E73F +:1026D000013504F8016BBFE7B8430008E042000889 +:1026E000CB43000800E8F11F0CE8F11FC0430008CD +:1026F000BFF34F8F044B1A695107FCD1D3F8102157 +:102700005207F8D1704700BF0020005208B50D4BAA +:102710001B78ABB9FFF7ECFF0B4BDA68D10704D598 +:102720000A4A5A6002F188325A60D3F80C21D20763 +:1027300006D5064AC3F8042102F18832C3F8042101 +:1027400008BD00BFFE4D0020002000522301674558 +:1027500008B5114B1B78F3B9104B1A69510703D513 +:10276000DA6842F04002DA60D3F81021520705D54A +:10277000D3F80C2142F04002C3F80C21FFF7B8FF58 +:10278000064BDA6842F00102DA60D3F80C2142F01D +:102790000102C3F80C2108BDFE4D002000200052AC +:1027A0000F289ABF00F580604004002070470000A9 +:1027B0004FF4003070470000102070470F2808B514 +:1027C0000BD8FFF7EDFF00F500330268013204D1AA +:1027D00004308342F9D1012008BD0020FCE700004D +:1027E0000F2870B5054645D8FFF7D6FC224CFFF7F9 +:1027F0007FFF0646FFF78AFF4FF0FF33072D636127 +:10280000C4F8143120D82361FFF772FF2B0243F084 +:102810002403E360E36843F08003E36023695A071D +:10282000FCD42846FFF764FF4FF40031FFF7B8FFF0 +:1028300000F002F93046FFF78BFFFFF7B7FC2846A0 +:10284000BDE87040FFF7BABFC4F81031FFF750FF82 +:10285000A5F108031B0243F02403C4F80C31D4F89B +:102860000C3143F08003C4F80C31D4F810315B070D +:10287000FBD4D6E7002070BD002000522DE9F84FB0 +:1028800040EA020305460C461746D80602D000204F +:10289000BDE8F88F27F01F07DFF8D4B0FFF736FF49 +:1028A0002744BC4203D10120FFF752FFF0E720226A +:1028B0002946204601F08CFC10B920352034F0E781 +:1028C0002B4605F120021E68711CE0D104339A42A8 +:1028D000F9D1FFF761FC05F17843234AB3F5801F76 +:1028E000224B28BF9A4603F1040338BF9046A2F159 +:1028F000080228BF9846A3F108033ABF9146DA467A +:102900009946FFF7F5FEC8F80060A5EB040CD9F86E +:10291000002004F11C0142F00202C9F80020221F2D +:10292000DAF8006016F00506FAD152F8043F8A4240 +:102930004CF80230F4D1BFF34F8FFFF7D9FE4FF0C0 +:10294000FF32C8F80020D9F8002022F00202C9F8AE +:102950000020FFF72BFC20222146284601F038FCFE +:102960000028AAD030469FE71420005210210052C0 +:102970001020005210B5084C237828B11BB9FFF77E +:10298000C5FE0123237010BD002BFCD02070BDE8D4 +:102990001040FFF7DDBE00BFFE4D00200244074B94 +:1029A000D2B210B5904200D110BD441C00B253F811 +:1029B000200041F8040BE0B2F4E700BF504000589B +:1029C0000E4B30B51C6F240405D41C6F1C671C6FA4 +:1029D00044F400441C670A4C02442368D2B243F416 +:1029E00080732360074B904200D130BD441C51F8E6 +:1029F000045B00B243F82050E0B2F4E70044025810 +:102A0000004802585040005807B5012201A9002093 +:102A1000FFF7C4FF019803B05DF804FB13B504464B +:102A2000FFF7F2FFA04205D0012201A90020019486 +:102A3000FFF7C6FF02B010BD0144BFF34F8F064B36 +:102A4000884204D3BFF34F8FBFF36F8F7047C3F833 +:102A50005C022030F4E700BF00ED00E0034B1A6891 +:102A60001AB9034AD2F8D0241A607047004E0020E9 +:102A70000040025808B5FFF7F1FF024B1868C0F399 +:102A8000806008BD004E0020CAB201460120FFF759 +:102A900097BF0000CAB201460120FFF77FBF0000C8 +:102AA000EFF30983054968334A6B22F001024A6358 +:102AB00083F30988002383F31188704700EF00E057 +:102AC000202080F3118862B60D4B0E4AD96821F49C +:102AD000E0610904090C0A430B49DA60D3F8FC20D1 +:102AE00042F08072C3F8FC20084AC2F8B01F116897 +:102AF00041F0010111601022DA7783F8220070475B +:102B000000ED00E00003FA0555CEACC5001000E072 +:102B1000202310B583F311880E4B5B6813F4006318 +:102B200014D0F1EE103AEFF309844FF08073683C53 +:102B3000E361094BDB6B236684F30988FFF7DCFA5A +:102B400010B1064BA36110BD054BFBE783F3118861 +:102B5000F9E700BF00ED00E000EF00E0FF03000830 +:102B60000204000870B5BFF34F8FBFF36F8F1A4A8E +:102B70000021C2F85012BFF34F8FBFF36F8F53691C +:102B800043F400335361BFF34F8FBFF36F8FC2F82D +:102B90008410BFF34F8FD2F8803043F6E074C3F354 +:102BA000C900C3F34E335B0103EA0406014646EA5B +:102BB00081750139C2F86052F9D2203B13F1200F20 +:102BC000F2D1BFF34F8F536943F480335361BFF3A6 +:102BD0004F8FBFF36F8F70BD00ED00E0FEE7000088 +:102BE0000A4B0B480B4A90420BD30B4BC11EDA1C0D +:102BF000121A22F003028B4238BF00220021FEF796 +:102C00003DB953F8041B40F8041BECE7AC45000841 +:102C1000D44F0020D44F0020D44F00207047000034 +:102C200070B5D0E9244300224FF0FF359E6804EBD5 +:102C300042135101D3F80009002805DAD3F800093E +:102C400040F08040C3F80009D3F8000B002805DAF3 +:102C5000D3F8000B40F08040C3F8000B013263183A +:102C60009642C3F80859C3F8085BE0D24FF001134D +:102C7000C4F81C3870BD000000EB8103D3F80CC011 +:102C80002DE9F043DCF814204E1CD0F89050D2F817 +:102C900000E005EB063605EB4118506870450AD395 +:102CA0000122D5F8343802FA01F123EA0101C5F80E +:102CB0003418BDE8F083AEEB0003BCF81040A3422B +:102CC00028BF2346D8F81849A4B2B3EB840FF0D834 +:102CD0009468A4F1040959F8047F3760A4EB09074C +:102CE0001F44042FF7D81C44034494605360D4E776 +:102CF000890141F02001016103699B06FCD4122087 +:102D0000FFF764BA10B50A4C2046FEF7D5FE094B12 +:102D1000C4F89030084BC4F89430084C2046FEF7B5 +:102D2000CBFE074BC4F89030064BC4F8943010BD6E +:102D3000044E00200000084000440008A04E00207F +:102D4000000004400C44000870B503780546012BD0 +:102D50005DD1494BD0F89040984259D1474B0E2154 +:102D60006520D3F8D82042F00062C3F8D820D3F809 +:102D7000002142F00062C3F80021D3F80021D3F80B +:102D8000802042F00062C3F88020D3F8802022F037 +:102D90000062C3F88020D3F8803000F071FC384B1B +:102DA000E360384BC4F800380023D5F89060C4F8CD +:102DB000003EC02323604FF40413A3633369002B48 +:102DC000FCDA01230C203361FFF700FA3369DB07DB +:102DD000FCD41220FFF7FAF93369002BFCDA002645 +:102DE0002846A660FFF71CFF6B68C4F81068DB6814 +:102DF000C4F81468C4F81C68002B3AD1224BA361B4 +:102E00004FF0FF336361A36843F00103A36070BD1B +:102E10001E4B9842C8D1194B0E214D20D3F8D82013 +:102E200042F00072C3F8D820D3F8002142F00072BB +:102E3000C3F80021D3F80021D3F8802042F00072BB +:102E4000C3F88020D3F8802022F00072C3F88020DD +:102E5000D3F88020D3F8D82022F08062C3F8D8209D +:102E6000D3F8002122F08062C3F80021D3F80031AA +:102E700093E7074BC3E700BF044E0020004402580D +:102E80004014004003002002003C30C0A04E00204F +:102E9000083C30C0F8B5D0F89040054600214FF00E +:102EA00000662046FFF724FFD5F8941000234FF06A +:102EB00001128F684FF0FF30C4F83438C4F81C2872 +:102EC00004EB431201339F42C2F80069C2F8006B61 +:102ED000C2F80809C2F8080BF2D20B68D5F89020A6 +:102EE000C5F89830636210231361166916F0100656 +:102EF000FBD11220FFF76AF9D4F8003823F4FE63FF +:102F0000C4F80038A36943F4402343F01003A361DD +:102F10000923C4F81038C4F814380B4BEB604FF099 +:102F2000C043C4F8103B094BC4F8003BC4F8106917 +:102F3000C4F80039D5F8983003F1100243F4801337 +:102F4000C5F89820A362F8BDDC430008408000105B +:102F5000D0F8902090F88A10D2F8003823F4FE635D +:102F600043EA0113C2F80038704700002DE9F84326 +:102F700000EB8103D0F890500C468046DA680FFAD7 +:102F800081F94801166806F00306731E022B05EB53 +:102F900041134FF0000194BFB604384EC3F8101B24 +:102FA0004FF0010104F1100398BF06F1805601FAB9 +:102FB00003F3916998BF06F5004600293AD0578A75 +:102FC00004F15801374349016F50D5F81C180B43E1 +:102FD0000021C5F81C382B180127C3F81019A74089 +:102FE0005369611E9BB3138A928B9B08012A88BF89 +:102FF0005343D8F89820981842EA034301F140025D +:103000002146C8F89800284605EB82025360FFF776 +:103010006FFE08EB8900C3681B8A43EA8453483477 +:103020001E4364012E51D5F81C381F43C5F81C7887 +:10303000BDE8F88305EB4917D7F8001B21F40041E0 +:10304000C7F8001BD5F81C1821EA0303C0E704F1F8 +:103050003F030B4A2846214605EB83035A60FFF7DE +:1030600047FE05EB4910D0F8003923F40043C0F8BF +:103070000039D5F81C3823EA0707D7E7008000108D +:1030800000040002D0F894201268C0F89820FFF7DE +:10309000C7BD00005831D0F8903049015B5813F497 +:1030A000004004D013F4001F0CBF02200120704721 +:1030B0004831D0F8903049015B5813F4004004D0F7 +:1030C00013F4001F0CBF02200120704700EB8101A8 +:1030D000CB68196A0B6813604B6853607047000037 +:1030E00000EB810330B5DD68AA691368D36019B9B4 +:1030F000402B84BF402313606B8A1468D0F8902063 +:103100001C4402EB4110013C09B2B4FBF3F46343ED +:10311000033323F0030343EAC44343F0C043C0F83E +:10312000103B2B6803F00303012B0ED1D2F80838B3 +:1031300002EB411013F4807FD0F8003B14BF43F042 +:10314000805343F00053C0F8003B02EB4112D2F829 +:10315000003B43F00443C2F8003B30BD2DE9F04191 +:10316000D0F8906005460C4606EB4113D3F8087B77 +:103170003A07C3F8087B08D5D6F814381B0704D5DE +:1031800000EB8103DB685B689847FA071FD5D6F828 +:103190001438DB071BD505EB8403D968CCB98B69E0 +:1031A000488A5A68B2FBF0F600FB16228AB9186802 +:1031B000DA6890420DD2121AC3E90024202383F367 +:1031C000118821462846FFF78BFF84F31188BDE85C +:1031D000F081012303FA04F26B8923EA02036B8175 +:1031E000CB68002BF3D021462846BDE8F0411847B4 +:1031F00000EB81034A0170B5DD68D0F890306C694E +:103200002668E66056BB1A444FF40020C2F8100945 +:103210002A6802F00302012A0AB20ED1D3F8080884 +:1032200003EB421410F4807FD4F8000914BF40F07F +:10323000805040F00050C4F8000903EB4212D2F86D +:10324000000940F00440C2F800090122D3F8340814 +:1032500002FA01F10143C3F8341870BD19B9402EC8 +:1032600084BF4020206020681A442E8A8419013CC3 +:10327000B4FBF6F440EAC44040F00050C6E700005A +:103280002DE9F041D0F8906004460D4606EB41135D +:10329000D3F80879C3F80879FB071CD5D6F810389D +:1032A000DA0718D500EB8103D3F80CC0DCF8143032 +:1032B000D3F800E0DA6896451BD2A2EB0E024FF07D +:1032C00000081A60C3F80480202383F31188FFF7F5 +:1032D0008FFF88F311883B0618D50123D6F83428D0 +:1032E000AB40134212D029462046BDE8F041FFF71B +:1032F000C3BC012303FA01F2038923EA0203038119 +:10330000DCF80830002BE6D09847E4E7BDE8F08110 +:103310002DE9F84FD0F8905004466E69AB691E4015 +:1033200016F480586E6103D0BDE8F84FFEF734BC48 +:10333000002E12DAD5F8003E9F0705D0D5F8003EE2 +:1033400023F00303C5F8003ED5F80438204623F0E7 +:103350000103C5F80438FEF74BFC300505D52046BF +:10336000FFF75EFC2046FEF733FCB1040CD5D5F820 +:10337000083813F0060FEB6823F470530CBF43F4C6 +:10338000105343F4A053EB60320704D56368DB6845 +:103390000BB120469847F30200F1BA80B70226D558 +:1033A000D4F8909000274FF0010A09EB4712D2F8A9 +:1033B000003B03F44023B3F5802F11D1D2F8003B3A +:1033C000002B0DDA62890AFA07F322EA030363810C +:1033D00004EB8703DB68DB6813B139462046984766 +:1033E0000137D4F89430FFB29B689F42DDD9F006D4 +:1033F00019D5D4F89000026AC2F30A1702F00F033D +:1034000002F4F012B2F5802F00F0CC80B2F5402F1C +:1034100009D104EB8303002200F58050DB681B6AAE +:10342000974240F0B2803003D5F8185835D5E903FB +:1034300003D500212046FFF791FEAA0303D5012101 +:103440002046FFF78BFE6B0303D502212046FFF7D2 +:1034500085FE2F0303D503212046FFF77FFEE802F8 +:1034600003D504212046FFF779FEA90203D50521E3 +:103470002046FFF773FE6A0203D506212046FFF7B8 +:103480006DFE2B0203D507212046FFF767FEEF01F3 +:1034900003D508212046FFF761FE700340F1A980A3 +:1034A000E90703D500212046FFF7EAFEAA0703D566 +:1034B00001212046FFF7E4FE6B0703D502212046D9 +:1034C000FFF7DEFE2F0703D503212046FFF7D8FEC6 +:1034D000EE0603D504212046FFF7D2FEA80603D549 +:1034E00005212046FFF7CCFE690603D506212046BC +:1034F000FFF7C6FE2A0603D507212046FFF7C0FEC8 +:10350000EB0576D520460821BDE8F84FFFF7B8BE99 +:10351000D4F8909000274FF0010AD4F894305FFA65 +:1035200087FB9B689B453FF639AF09EB4B13D3F8FC +:10353000002902F44022B2F5802F24D1D3F80029CB +:10354000002A20DAD3F8002942F09042C3F800297B +:10355000D3F80029002AFBDB5946D4F89000FFF786 +:10356000C7FB22890AFA0BF322EA0303238104EB47 +:103570008B03DB689B6813B1594620469847594630 +:103580002046FFF779FB0137C7E7910701D1D0F853 +:103590000080072A02F101029CBF03F8018B4FEA69 +:1035A00018283DE704EB830300F58050DA68D2F871 +:1035B00018C0DCF80820DCE9001CA1EB0C0C002191 +:1035C0008F4208D1DB689B699A683A449A605A68CE +:1035D0003A445A6027E711F0030F01D1D0F8008078 +:1035E0008C4501F1010184BF02F8018B4FEA1828D4 +:1035F000E6E7BDE8F88F000008B50348FFF788FE4E +:10360000BDE80840FFF784BA044E002008B503481F +:10361000FFF77EFEBDE80840FFF77ABAA04E002013 +:10362000D0F8903003EB4111D1F8003B43F4001384 +:10363000C1F8003B70470000D0F8903003EB411117 +:10364000D1F8003943F40013C1F800397047000085 +:10365000D0F8903003EB4111D1F8003B23F4001374 +:10366000C1F8003B70470000D0F8903003EB4111E7 +:10367000D1F8003923F40013C1F800397047000075 +:10368000090100F16043012203F56143C9B283F8E7 +:10369000001300F01F039A4043099B0003F16043AD +:1036A00003F56143C3F880211A60704730B50433D5 +:1036B000039C0172002104FB0325C160C0E906538D +:1036C000049B0363059BC0E90000C0E90422C0E934 +:1036D0000842C0E90A11436330BD00000022416A7C +:1036E000C260C0E90411C0E90A226FF00101FEF7CF +:1036F000DDBD0000D0E90432934201D1C2680AB9AD +:10370000181D704700207047036919600021C268C6 +:103710000132C260C269134482699342036124BFCB +:10372000436A0361FEF7B6BD38B504460D46E3684B +:103730003BB162690020131D1268A3621344E36267 +:1037400007E0237A33B929462046FEF793FD002887 +:10375000EDDA38BD6FF00100FBE70000C368C26915 +:10376000013BC3604369134482699342436124BFB0 +:10377000436A436100238362036B03B118477047B8 +:1037800070B52023044683F31188866A3EB9FFF79B +:10379000CBFF054618B186F31188284670BDA36A91 +:1037A000E26A13F8015B9342A36202D32046FFF75B +:1037B000D5FF002383F31188EFE700002DE9F84FD0 +:1037C00004460E46174698464FF0200989F31188A3 +:1037D0000025AA46D4F828B0BBF1000F09D1414614 +:1037E0002046FFF7A1FF20B18BF311882846BDE8E2 +:1037F000F88FD4E90A12A7EB050B521A934528BF9C +:103800009346BBF1400F1BD9334601F1400251F8FA +:10381000040B914243F8040BF9D1A36A40364035BA +:103820004033A362D4E90A239A4202D32046FFF729 +:1038300095FF8AF31188BD42D8D289F31188C9E770 +:1038400030465A46FDF7F4FAA36A5E445D445B4491 +:10385000A362E7E710B5029C0433017204FB032165 +:10386000C460C0E906130023C0E90A33039B036365 +:10387000049BC0E90000C0E90422C0E90842436398 +:1038800010BD0000026A6FF00101C260426AC0E927 +:1038900004220022C0E90A22FEF708BDD0E9042371 +:1038A0009A4201D1C26822B9184650F8043B0B6015 +:1038B0007047002070470000C3680021C2690133CF +:1038C000C3604369134482699342436124BF436ADE +:1038D0004361FEF7DFBC000038B504460D46E368DF +:1038E0003BB1236900201A1DA262E2691344E3621E +:1038F00007E0237A33B929462046FEF7BBFC0028AF +:10390000EDDA38BD6FF00100FBE7000003691960D4 +:10391000C268013AC260C26913448269934203617A +:1039200024BF436A036100238362036B03B118471A +:103930007047000070B520230D460446114683F3FE +:103940001188866A2EB9FFF7C7FF10B186F3118878 +:1039500070BDA36A1D70A36AE26A01339342A36239 +:1039600004D3E16920460439FFF7D0FF002080F33B +:103970001188EDE72DE9F84F04460D46904699462B +:103980004FF0200A8AF311880026B346A76A4FB980 +:1039900049462046FFF7A0FF20B187F31188304643 +:1039A000BDE8F88FD4E90A073A1AA8EB0607974250 +:1039B00028BF1746402F1BD905F1400355F8042BAB +:1039C0009D4240F8042BF9D1A36A40364033A362EC +:1039D000D4E90A239A4204D3E16920460439FFF767 +:1039E00095FF8BF311884645D9D28AF31188CDE72C +:1039F00029463A46FDF71CFAA36A3D443E443B443F +:103A0000A362E5E7D0E904239A4217D1C3689BB1CA +:103A1000836A8BB1043B9B1A0ED01360C368013BD1 +:103A2000C360C3691A4483699A42026124BF436A2E +:103A30000361002383620123184670470023FBE7DC +:103A400000F0DAB8034B002258631A610222DA60F0 +:103A5000704700BF000C0040014B0022DA60704745 +:103A6000000C0040014B5863704700BF000C004041 +:103A7000014B586A704700BF000C00404B68436020 +:103A80008B688360CB68C3600B6943614B690362D9 +:103A90008B6943620B6803607047000008B53C4BBC +:103AA00040F2FF713B48D3F888200A43C3F88820CE +:103AB000D3F8882022F4FF6222F00702C3F888209E +:103AC000D3F88820D3F8E0200A43C3F8E020D3F8E5 +:103AD00008210A43C3F808212F4AD3F808311146B8 +:103AE000FFF7CCFF00F5806002F11C01FFF7C6FF75 +:103AF00000F5806002F13801FFF7C0FF00F580603B +:103B000002F15401FFF7BAFF00F5806002F1700185 +:103B1000FFF7B4FF00F5806002F18C01FFF7AEFF04 +:103B200000F5806002F1A801FFF7A8FF00F58060B2 +:103B300002F1C401FFF7A2FF00F5806002F1E0018D +:103B4000FFF79CFF00F5806002F1FC01FFF796FF94 +:103B500002F58C7100F58060FFF790FF00F000F92E +:103B60000E4BD3F8902242F00102C3F89022D3F812 +:103B7000942242F00102C3F894220522C3F898204F +:103B80004FF06052C3F89C20054AC3F8A02008BD3E +:103B900000440258000002581844000800ED00E0FC +:103BA0001F00080308B500F0F3FAFEF7D3FA0F4B35 +:103BB000D3F8DC2042F04002C3F8DC20D3F8042123 +:103BC00022F04002C3F80421D3F80431084B1A68EC +:103BD00042F008021A601A6842F004021A60FEF706 +:103BE0003DFFBDE80840FEF7DDBC00BF00440258C1 +:103BF0000018024870470000114BD3F8E82042F04B +:103C00000802C3F8E820D3F8102142F00802C3F8F4 +:103C100010210C4AD3F81031D36B43F00803D3635F +:103C2000C722094B9A624FF0FF32DA6200229A6192 +:103C30005A63DA605A6001225A611A60704700BF05 +:103C4000004402580010005C000C0040094A08B50E +:103C50001169D3680B40D9B29B076FEA010111616A +:103C600007D5202383F31188FEF794FA002383F30A +:103C7000118808BD000C0040384B4FF0FF31D3F8DD +:103C80008020C3F88010D3F880200022C3F8802061 +:103C9000D3F88000D3F88400C3F88410D3F88400EC +:103CA000C3F88420D3F88400D86F40F0FF4040F47C +:103CB000FF0040F43F5040F03F00D867D86F20F03D +:103CC000FF4020F4FF0020F43F5020F03F00D86771 +:103CD000D86FD3F888006FEA40506FEA5050C3F8AD +:103CE0008800D3F88800C0F30A00C3F88800D3F82E +:103CF0008800D3F89000C3F89010D3F89000C3F870 +:103D00009020D3F89000D3F89400C3F89410D3F81F +:103D10009400C3F89420D3F89400D3F89800C3F823 +:103D20009810D3F89800C3F89820D3F89800D3F8E7 +:103D30008C00C3F88C10D3F88C00C3F88C20D3F817 +:103D40008C00D3F89C00C3F89C10D3F89C10C3F8E7 +:103D50009C20D3F89C3000F0E7B900BF0044025823 +:103D6000614B0122C3F80821604BD3F8F42042F0E4 +:103D70000202C3F8F420D3F81C2142F00202C3F877 +:103D80001C210222D3F81C31594BDA605A68910485 +:103D9000FCD5584A1A6001229A60574ADA6000221C +:103DA0001A614FF440429A61514B9A699204FCD5D2 +:103DB0001A6842F480721A604C4B1A6F12F4407FFA +:103DC00004D04FF480321A6700221A671A6842F052 +:103DD00001021A60454B1A685007FCD500221A618F +:103DE0001A6912F03802FBD1012119604FF08041AD +:103DF00059605A67414ADA62414A1A611A6842F4C4 +:103E000080321A60394B1A689103FCD51A6842F463 +:103E100080521A601A689204FCD53A4A3A499A626A +:103E200000225A6319633949DA6399635A64384A3C +:103E30001A64384ADA621A6842F0A8521A602B4BA8 +:103E40001A6802F02852B2F1285FF9D148229A612B +:103E50004FF48862DA6140221A622F4ADA644FF026 +:103E600080521A652D4A5A652D4A9A6532232D4A89 +:103E70001360136803F00F03022BFAD11B4B1A696E +:103E800042F003021A611A6902F03802182AFAD1C4 +:103E9000D3F8DC2042F00052C3F8DC20D3F8042130 +:103EA00042F00052C3F80421D3F80421D3F8DC20F7 +:103EB00042F08042C3F8DC20D3F8042142F0804273 +:103EC000C3F80421D3F80421D3F8DC2042F00042E7 +:103ED000C3F8DC20D3F8042142F00042C3F80421E7 +:103EE000D3F80431704700BF0080005100440258ED +:103EF0000048025800C000F0020000010000FF016D +:103F00000088900832206000630209011D0204004D +:103F100047040508FD0BFF01200000200010E00011 +:103F200000010100002000524FF0B04208B5D2F865 +:103F3000883003F00103C2F8883023B1044A1368C3 +:103F40000BB150689847BDE80840FEF7E1BD00BFDF +:103F5000544F00204FF0B04208B5D2F8883003F03B +:103F60000203C2F8883023B1044A93680BB1D068C9 +:103F70009847BDE80840FEF7CBBD00BF544F002076 +:103F80004FF0B04208B5D2F8883003F00403C2F80D +:103F9000883023B1044A13690BB150699847BDE8D2 +:103FA0000840FEF7B5BD00BF544F00204FF0B042AF +:103FB00008B5D2F8883003F00803C2F8883023B17E +:103FC000044A93690BB1D0699847BDE80840FEF7F1 +:103FD0009FBD00BF544F00204FF0B04208B5D2F84B +:103FE000883003F01003C2F8883023B1044A136A02 +:103FF0000BB1506A9847BDE80840FEF789BD00BF85 +:10400000544F00204FF0B04310B5D3F8884004F46B +:104010007872C3F88820A30604D5124A936A0BB1BC +:10402000D06A9847600604D50E4A136B0BB1506BEB +:104030009847210604D50B4A936B0BB1D06B984778 +:10404000E20504D5074A136C0BB1506C9847A305E1 +:1040500004D5044A936C0BB1D06C9847BDE810406E +:10406000FEF756BD544F00204FF0B04310B5D3F8C3 +:10407000884004F47C42C3F88820620504D5164ABF +:10408000136D0BB1506D9847230504D5124A936DFB +:104090000BB1D06D9847E00404D50F4A136E0BB1F5 +:1040A000506E9847A10404D50B4A936E0BB1D06EA5 +:1040B0009847620404D5084A136F0BB1506F9847B4 +:1040C000230404D5044A936F0BB1D06F9847BDE821 +:1040D0001040FEF71DBD00BF544F002008B5034837 +:1040E000FDF7FCF8BDE80840FEF712BDCC23002028 +:1040F00008B50348FDF7F2F8BDE80840FEF708BD33 +:104100003824002008B50348FDF7E8F8BDE808406A +:10411000FEF7FEBCA424002008B5FFF797FDBDE81C +:104120000840FEF7F5BC0000062108B50846FFF779 +:10413000A7FA06210720FFF7A3FA06210820FFF7B8 +:104140009FFA06210920FFF79BFA06210A20FFF7B4 +:1041500097FA06211720FFF793FA06212820FFF788 +:104160008FFA09217A20FFF78BFA07213220FFF717 +:1041700087FA0C212620FFF783FA0C212720FFF76E +:104180007FFA0C215220BDE80840FFF779BA000001 +:1041900008B5FFF771FD00F00DF8FDF7B1FAFDF776 +:1041A00089FCFDF75BFBFFF725FDBDE80840FFF745 +:1041B00047BC00000023054A19460133102BC2E911 +:1041C000001102F10802F8D1704700BF544F0020DF +:1041D00010B501390244904201D1002005E0037876 +:1041E00011F8014FA34201D0181B10BD0130F2E7B6 +:1041F000034611F8012B03F8012B002AF9D170476F +:1042000053544D333248373F3F3F0053544D3332C0 +:10421000483734332F37353300000000C8320020D0 +:10422000CC23002038240020A42400200096000085 +:10423000000000000000000000000000000000007E +:104240000000000000000000C9160008B5160008B4 +:10425000F1160008DD160008E9160008D51600085A +:10426000C1160008AD160008FD1600080000000089 +:10427000D9170008C517000801180008ED17000835 +:10428000F9170008E5170008D1170008BD17000846 +:104290000D180008000000000100000000000000F0 +:1042A0006D61696E0000000069646C6500000000CB +:1042B000A842000850310020C83200200100000050 +:1042C00051210008000000004865782F50726F6689 +:1042D00069434E430025424F415244252D424C0034 +:1042E0002553455249414C250000000002000000C2 +:1042F00000000000F9190008691A00084000400099 +:10430000704B0020804B00200200000000000000E5 +:104310000300000000000000B11A000800000000C7 +:1043200010000000904B0020000000000100000081 +:1043300000000000044E0020010102004125000899 +:1043400051240008ED240008D12400084300000097 +:104350005443000809024300020100C0320904006E +:1043600000010202010005240010010524010001E2 +:10437000042402020524060001070582030800FF49 +:1043800009040100020A00000007050102400000C4 +:10439000070581024000000012000000A043000851 +:1043A0001201100102000040AE2D161000020102A1 +:1043B000030100000403090425424F415244250033 +:1043C000437562654F72616E676500303132333418 +:1043D0003536373839414243444546000000000035 +:1043E000051C0008BD1E0008691F000840004000B1 +:1043F0003C4F00203C4F0020010000004C4F0020AB +:1044000080000000400100000800000000010000E2 +:1044100000040000080000000000812A00000000E5 +:10442000AAAAAAAA00000024FFFE000000000000C3 +:1044300000A00A000001000000000000AAAAAAAA29 +:1044400000000000FFFF000000000000000000006E +:104450001400005400000000AAAAAAAA14000054E4 +:10446000FFFF0000000000000000000000681A00CC +:1044700000000000AAAA8AAA00541500FFFF00004D +:10448000000070077700000040810201001000006A +:10449000AAAAAAAA00410100F7FF000000000070CC +:1044A000070000000000000000000000AAAAAAAA5D +:1044B00000000000FFFF00000000000000000000FE +:1044C0000000000000000000AAAAAAAA0000000044 +:1044D000FFFF0000000000000000000000000000DE +:1044E00000000000AAAAAAAA00000000FFFF000026 +:1044F00000000000000000000000000000000000BC +:10450000AAAAAAAA00000000FFFF00000000000005 +:10451000000000000000000000000000AAAAAAAAF3 +:1045200000000000FFFF000000000000000000008D +:104530000000000000000000AAAAAAAA00000000D3 +:10454000FFFF00000000000000000000000000006D +:104550008C0000000000000000001E0000000000B1 +:10456000FF00000000000000004200083F000000C3 +:10457000500400000B4200083F00000000960000BD +:104580000000080096000000000800000400000081 +:10459000B44300080000000000000000000000001C +:0C45A0000000000000000000000000000F :00000001FF diff --git a/Tools/bootloaders/CubeYellow-bdshot_bl.bin b/Tools/bootloaders/CubeYellow-bdshot_bl.bin old mode 100644 new mode 100755 index df1d815c2e9..d0e5fb604aa Binary files a/Tools/bootloaders/CubeYellow-bdshot_bl.bin and b/Tools/bootloaders/CubeYellow-bdshot_bl.bin differ diff --git a/Tools/bootloaders/CubeYellow-bdshot_bl.hex b/Tools/bootloaders/CubeYellow-bdshot_bl.hex index 8185dc517f6..2ddca5245c6 100644 --- a/Tools/bootloaders/CubeYellow-bdshot_bl.hex +++ b/Tools/bootloaders/CubeYellow-bdshot_bl.hex @@ -1,29 +1,29 @@ :020000040800F2 -:100000000006022001020008190F00081D0F000859 -:10001000750F00081D0F0008490F000803020008B3 -:10002000030200080302000803020008692900080F +:100000000006022001020008850F0008050F000805 +:100010005D0F0008050F0008310F000803020008FB +:10002000030200080302000803020008ED2800088C :10003000030200080302000803020008030200088C :10004000030200080302000803020008030200087C -:100050000302000803020008553A0008813A00082C -:10006000AD3A0008D93A0008053B00080302000831 +:100050000302000803020008513A0008793A000838 +:10006000A13A0008C93A0008F13A00080302000862 :10007000030200080302000803020008030200084C :10008000030200080302000803020008030200083C -:10009000030200080302000803020008313B0008C5 +:10009000030200080302000803020008193B0008DD :1000A000030200080302000803020008030200081C -:1000B0007938000803020008030200080302000860 +:1000B000293C0008030200080302000803020008AC :1000C00003020008030200080302000803020008FC -:1000D0000302000803020008291100083D1100086E -:1000E000993B00080302000803020008030200080D +:1000D0000302000803020008ED3B0008013C000891 +:1000E0007D3B000803020008030200080302000829 :1000F00003020008030200080302000803020008CC :1001000003020008030200080302000803020008BB :1001100003020008030200080302000803020008AB :10012000030200080302000803020008030200089B :10013000030200080302000803020008030200088B -:10014000030200080302000803020008D53000087B +:10014000030200080302000803020008A1300008AF :10015000030200080302000803020008030200086B :10016000030200080302000803020008030200085B :10017000030200080302000803020008030200084B -:1001800003020008030200085111000803020008DE +:100180000302000803020008153C000803020008EF :10019000030200080302000803020008030200082B :1001A000030200080302000803020008030200081B :1001B000030200080302000803020008030200080B @@ -31,1002 +31,1010 @@ :1001D00003020008030200080302000803020008EB :1001E00003020008030200080302000803020008DB :1001F00003020008030200080302000803020008CB -:1002000002E000F000F8FEE772B6394880F3088893 -:10021000384880F3098838484EF60851CEF200017C +:1002000002E000F000F8FEE772B63A4880F3088892 +:10021000394880F3098839484EF60851CEF200017A :10022000086040F20000CCF200004EF63471CEF2CD :1002300000010860BFF34F8FBFF36F8F40F20000E3 :10024000C0F2F0004EF68851CEF200010860BFF314 :100250004F8FBFF36F8F4FF00000E1EE100A4EF6A4 :100260003C71CEF200010860062080F31488BFF3D1 -:100270006F8F02F0B7FB03F087FA4FF055301F493C -:100280001B4A91423CBF41F8040BFAE71C49194A4A -:1002900091423CBF41F8040BFAE71A491A4A1B4B3A -:1002A0009A423EBF51F8040B42F8040BF8E70020D5 -:1002B0001749184A91423CBF41F8040BFAE702F093 -:1002C000D5FB03F0CBFA144C144DAC4203DA54F8CE -:1002D000041B8847F9E700F03FF8114C114DAC4280 -:1002E00003DA54F8041B8847F9E702F0BDBB0000AD -:1002F0000006022000220220000000080000022068 -:100300000006022010400008002202205022022095 -:1003100050220220343502200002000800020008AA -:1003200000020008000200082DE9F04F2DED108AB0 -:10033000C1F80CD0D0F80CD0BDEC108ABDE8F08F1D -:10034000002383F311882846A047002001F094FF82 -:1003500001F0B2FE00DFFEE770B578231F4C0025E8 -:100360006FF07F0623701E236570A570E570257100 -:100370006571A571E57125726672A372E57200F070 -:10038000DFFC20B10E2325726672A372E57202F0C3 -:10039000ADFA044602F0E2FA0546D0B9104B9C4291 -:1003A00019D001339C4241F2883412BF0546002423 -:1003B0000125002002F0A4FA0DB100F05BF800F076 -:1003C0004DFD00F001FC204600F0F4F800F052F87A -:1003D000F9E70024EDE70446EBE700BF50220220D6 -:1003E000010007B008B500F06DFBA0F120035842F2 -:1003F000584108BD054B07B51B88022101A8ADF87F -:10040000043000F0CBFB03B05DF804FB803C000837 -:1004100010B5202383F311881248C3680BB101F093 -:10042000B1FF0023104A4FF47A710E4801F06EFFBD -:10043000002383F311880D4C236813B12368013B1B -:100440002360636813B16368013B6360084B1B78EA -:1004500033B9636823B9022000F078FC322363606B -:1004600010BD00BF5C220220110400087823022086 -:1004700070220220454B46492DE9F04153F8042FE4 -:10048000013201D1BDE8F0818B42F7D1414C424BA2 -:1004900022689A4278D9414B9B6803F1006303F5C7 -:1004A000C0339A4270D2002000F0AAFB02203C4BDD -:1004B000187000F049FC3B4B1A6C00221A64196E4C -:1004C0001A66196E596C5A64596E5A66596E596992 -:1004D00041F080015961596921F0800159615969E0 -:1004E000196941F000511961196921F00051196130 -:1004F0001B6972B62C4B2D490B601D682468BFF335 -:100500004F8FBFF36F8F2A4BC3F88420BFF34F8FF9 -:100510005A6922F480325A61BFF34F8FD3F880209A -:1005200043F6E07EC2F3C906C2F34E32B70752016A -:1005300002EA0E0838463146013948EA000C00F15B -:100540004040B1F1FF3FC3F874C2F5D1203A12F137 -:10055000200FEDD1BFF34F8FBFF36F8FBFF34F8FDE -:10056000BFF36F8F5A6922F400325A610022C3F838 -:100570005022BFF34F8FBFF36F8F202383F3118877 -:10058000AD4685F308882047BDE8F081FC7F01086F -:100590001C80010804800108FF7F0108502202200E -:1005A00070220220003802400080010808ED00E0BF -:1005B00000ED00E02DE9F04F99B0B34C2022FF216F -:1005C000019010A8A66800F0EBFBB04AA346137890 -:1005D000A3B90121AE481170C360202383F31188B1 -:1005E000C3680BB101F0CEFE0023AA4A4FF47A7122 -:1005F000A74801F08BFE002383F31188019B13B100 -:10060000A54B019A1A600023A44AA349019F994669 -:100610001C461D46984613704B600292012000F064 -:1006200093FB002F00F012829B4B1B68002B40F0C5 -:100630000D8219B0BDE8F08F0220FFF7D3FE00282D -:1006400040F0FB81019BB9F1000F08BF1F46944B9E -:100650001B8802210BA8ADF82C3000F09FFADDE7D3 -:100660004FF47A7000F02EFA031E0393EADB0220A7 -:10067000FFF7B8FE82460028E4D0039B581E0428EA -:1006800000F2DD81DFE800F0030E1114170018A856 -:100690000523042140F8343D00F080FA54464FF021 -:1006A000000856E004217848F6E704217D48F3E786 -:1006B00004217D48F0E71C242046043400F0A2FA0F -:1006C00004210B900BA800F069FA2C2CF4D1E5E77B -:1006D000002DB7D0002CB5D00220FFF783FE0546D1 -:1006E000002800F0AF8101206C4C00F089FA4FF037 -:1006F00000090220207000F027FB5FFA89FA5046BB -:1007000000F08EFA074658B1504609F1010900F091 -:1007100097FA0028F1D12C46A9460027634B97E7AA -:1007200001233E460220237000F00CFBDBF808306A -:100730009E4206D2304600F065FA0130EBD1043615 -:10074000F4E70026029BA9462C461E703746524B02 -:100750005E6000F079FB15B1002C18BF0027FFF791 -:1007600049FE5BE7002D3FF46DAF002C3FF46AAF0C -:100770000220029B187000F0E7FA322000F0A2F984 -:10078000B0F1000AC0F25E811AF0030540F05A8110 -:1007900006EB0A03DBF80820934200F25381BAF516 -:1007A000807F00F24F8155450DDA4FF47A7000F0EA -:1007B00089F90490049B002BC0F24481049B3C4ABD -:1007C000AB540135EFE7C820FFF70CFE05460028C3 -:1007D00000F038811F2E11D8C6F1200410AB26F08E -:1007E000030033495445184428BF5446224600F0BC -:1007F000AFFA2246FF212E4800F0D2FA4FEAAA0AA9 -:100800002B4930465FFA8AF200F0D2FA04460028FB -:1008100000F01A8106EB8A0605469AE70220FFF7E8 -:10082000E1FD00283FF40EAF00F030FA00283FF45D -:1008300009AF4FF0000A5346DBF8082092451CD25E -:10084000BAF11F0F12D8109A01320FD02AF003020A -:1008500018A90A4452F8202C0B92184604220BA91E -:100860000AF1040A00F09AFB0346E5E750460393B9 -:1008700000F0C8F9039B0B90EFE718A8042140F89B -:100880004C3D00F08BF964E75022022074230220D3 -:100890005C2202201104000878230220702202202A -:1008A000823C00085422022058220220843C000886 -:1008B0007422022018A80023642140F8343D00F07F -:1008C00039F900287FF4BEAE0220FFF78BFD002827 -:1008D0003FF4B8AE0B9800F0C5F918AB43F8480DDB -:1008E00004211846CDE718A80023642140F8343DC0 -:1008F00000F020F900287FF4A5AE0220FFF772FD7A -:1009000000283FF49FAE0B9800F0BAF918AB43F8FB -:10091000440DE5E70220FFF765FD00283FF492AEA5 -:1009200000F0C4F918AB43F8400DD9E70220FFF7F7 -:1009300059FD00283FF486AE0BA9142000F0BCF945 -:10094000824618A8042140F83CAD00F027F9514632 -:100950000BA896E7322000F0B5F8B0F1000AFFF6D8 -:1009600071AE1AF0030F7FF46DAE0AEB0803DBF8EB -:10097000082093423FF666AE0220FFF733FD0028C1 -:100980003FF460AE2AF0030AC244D0453FF4E1AE22 -:10099000404608F1040800F035F904210A900AA83D -:1009A00000F0FCF8F1E74FF47A70FFF71BFD002828 -:1009B0003FF448AE00F06AF900283FF4AFAE109B58 -:1009C00001330CD0082210A9002000F0F1F9002812 -:1009D0003FF4A4AE2022FF2110A800F0E1F9FFF7B8 -:1009E00009FD374801F04EFC23E6002D3FF42AAE06 -:1009F000002C3FF427AE18A80023642140F8343DB2 -:100A000000F098F8824600287FF41CAE0220FFF721 -:100A1000E9FC00283FF416AE0390FFF7EBFC41F22F -:100A20008830574601F02EFC0B9800F055FA00F084 -:100A30000BFA039B1C461D46F0E5054689E64FF080 -:100A40000008FFE52546FDE52C4667E6002000F09E -:100A500039F80490049B002BFFF6E3AD012000F071 -:100A600071F9049B213B122B3FF6D8AD01A252F83D -:100A700023F000BF3906000861060008D10600080F -:100A80001D0600081D0600081D0600086507000871 -:100A9000550900081D080008B5080008E708000807 -:100AA000150900081D0600082D0900081D0600088C -:100AB000A7090008530700081D060008EB090008F5 -:100AC000A08601002DE9F3474FF47A75002402AEA9 -:100AD000154F4543DFF8588006F8014D97F900306F -:100AE0005FFA84F95A1C01D0A34212D158F82400AD -:100AF000012231460368D3F820A02B46D0470128B5 -:100B000007D10A4B9DF8070083F8009002B0BDE8BA -:100B1000F0870134042CE1D14FF4FA7001F0B2FBFC -:100B20004FF0FF30F2E700BF00220220C423022072 -:100B3000883C00082DE9F0474FF47A7506460024FA -:100B4000134F4D43DFF8508097F900305FFA84F976 -:100B50005A1C01D0A34210D158F824000422314677 -:100B60000368D3F820A02B46D047042805D1094BB1 -:100B7000002083F80090BDE8F0870134042CE3D115 -:100B80004FF4FA7001F07EFB4FF0FF30BDE8F087C4 -:100B900000220220C4230220883C0008074B30B406 -:100BA0001A78074B53F822400A460146236820462C -:100BB000DD69044BAC4630BC604700BFC423022053 -:100BC000883C0008A0860100F8B50A4C00250A4EB2 -:100BD00001F092FD094F207030682378834207D9D5 -:100BE00001F084FD336805440133BD423360F3D91D -:100BF000F8BD00BFC523022080230220FF7F010033 -:100C000001F026BE00F1006000F5C03000687047BA -:100C100000F10060920000F5C03001F0B3BD0000AB -:100C2000054B1A68054B1B789B1A834202D9104466 -:100C300001F05CBD0020704780230220C523022004 -:100C400038B5074D04462868204401F057FD28B9FF -:100C500028682044BDE8384001F068BD38BD00BFB9 -:100C60008023022010F0030308D1B0F5806F05D86F -:100C700000F10050A0F57120006870470020704717 -:100C8000014BC058704700BF20F4F01F064991F88F +:100270006F8F02F0F9FB02F09BFB03F08BFA4FF05B +:1002800055301F491B4A91423CBF41F8040BFAE725 +:100290001C49194A91423CBF41F8040BFAE71A493C +:1002A0001A4A1B4B9A423EBF51F8040B42F8040B0A +:1002B000F8E700201749184A91423CBF41F8040B67 +:1002C000FAE702F0B3FB03F0C5FA144C144DAC424C +:1002D00003DA54F8041B8847F9E700F041F8114CA1 +:1002E000114DAC4203DA54F8041B8847F9E702F0D9 +:1002F0009BBB000000060220002202200000000834 +:1003000000000220000602207040000800220220A7 +:1003100068220220682202205039022000020008D0 +:100320000002000800020008000200082DE9F04F5A +:100330002DED108AC1F80CD0D0F80CD0BDEC108A8D +:10034000BDE8F08F002383F311882846A0470020E2 +:1003500001F0D6FEFEE701F051FE00DFFEE70000EF +:1003600038B502F0ABFA40B1174B6FF07F010022B5 +:1003700059720E211A729972DA7202F075FA0546F4 +:1003800002F0AAFA0446D0B9104B9D4219D00133AD +:100390009D4241F2883512BF044600250124002009 +:1003A00002F06CFA0CB100F079F800F04DFD00F0AD +:1003B00007FC284600F0FCF800F070F8F9E700258B +:1003C000EDE70546EBE700BF00220220010007B081 +:1003D00008B500F0C1FBA0F120035842584108BD08 +:1003E00007B541F21203022101A8ADF8043000F074 +:1003F000D1FB03B05DF804FB38B5202383F31188EB +:100400001748C3680BB101F001FF0023154A4FF4F0 +:100410007A71134801F0BEFE002383F31188124C59 +:10042000236813B12368013B2360636813B16368D9 +:10043000013B63600D4D2B7833B963687BB90220B3 +:1004400000F084FC322363602B78032B07D16368B0 +:100450002BB9022000F07AFC4FF47A73636038BD48 +:1004600068220220F9030008842302207C22022053 +:10047000084B187003280CD8DFE800F008050208C4 +:10048000022000F061BC022000F05CBC024B0022A4 +:100490005A6070477C22022084230220F8B53F4B2B +:1004A0003F4A1C461968013177D004339342F9D191 +:1004B0006268A24271D33B4B9B6803F1006303F572 +:1004C000C0339A4269D2002000F094FB0220FFF76B +:1004D000CFFF354B00211A6C19641A6E19661A6E1B +:1004E0005A6C59645A6E59665A6E5A6942F08002C3 +:1004F0005A615A6922F080025A615A691A6942F0B7 +:1005000000521A611A6922F000521A611B6972B610 +:100510004FF0E023C3F8084DD4E90004BFF34F8F38 +:10052000BFF36F8F214AC2F88410BFF34F8F536916 +:1005300023F480335361BFF34F8FD2F8803043F6FA +:10054000E076C3F3C905C3F34E335B0103EA060C3F +:1005500029464CEA81770139C2F87472F9D2203BFE +:1005600013F1200FF2D1BFF34F8FBFF36F8FBFF3A3 +:100570004F8FBFF36F8F536923F400335361002310 +:10058000C2F85032BFF34F8FBFF36F8F202383F336 +:100590001188854680F308882047F8BD008001084F +:1005A00020800108002202200038024000ED00E017 +:1005B0002DE9F04F93B0B44B2022FF2100900AA800 +:1005C0009D6800F0EBFBB14A1378A3B90121B04854 +:1005D0001170C360202383F31188C3680BB101F04D +:1005E00015FE0023AB4A4FF47A71A94801F0D2FD01 +:1005F000002383F31188009B13B1A74B009A1A6064 +:10060000A64A1378032B03D000231370A24A536029 +:100610004FF0000A009CD3465646D146012000F018 +:1006200093FB24B19C4B1B68002B00F0268200201A +:1006300000F092FA0390039B002BF2DB012000F004 +:1006400081FB039B213B1F2BE8D801A252F823F02A +:10065000D1060008F90600088D0700081D060008ED +:100660001D0600081D0600081F080008EF09000805 +:10067000090900086B09000893090008B909000876 +:100680001D060008CB0900081D0600083D0A0008E9 +:10069000710700081D060008810A0008DD06000831 +:1006A000710700081D0600086B0900081D060008F8 +:1006B0001D0600081D0600081D0600081D0600088E +:1006C0001D0600081D0600081D0600088D0700080D +:1006D0000220FFF77DFE002840F0F981009B0221F7 +:1006E00005A8BAF1000F08BF1C4641F21233ADF85D +:1006F000143000F04FFA91E74FF47A7000F02CFAC2 +:10070000071EEBDB0220FFF763FE0028E6D0013F67 +:10071000052F00F2DE81DFE807F0030A0D10133623 +:100720000523042105A8059300F034FA17E00421FD +:100730005548F9E704215A48F6E704215948F3E7F8 +:100740004FF01C08404608F1040800F055FA042157 +:10075000059005A800F01EFAB8F12C0FF2D1012087 +:100760004FF0000900FA07F747EA0B0B5FFA8BFB23 +:1007700000F060FB26B10BF00B030B2B08BF00242D +:10078000FFF72EFE4AE704214748CDE7002EA5D00B +:100790000BF00B030B2BA1D10220FFF719FE07462C +:1007A00000289BD00120002600F024FA0220FFF749 +:1007B0005FFE5FFA86F8404600F02CFA0446B0B1BE +:1007C000039940460136A1F140025142514100F0E7 +:1007D00031FA0028EDD1BA46044641F21213022143 +:1007E00005A83E46ADF8143000F0D4F916E72546CA +:1007F0000120FFF73DFE244B9B68AB4207D92846FA +:1008000000F0FAF9013040F067810435F3E7002584 +:10081000224BBA463E461D701F4B5D60A8E7002E76 +:100820003FF45CAF0BF00B030B2B7FF457AF0220B0 +:10083000FFF71EFE322000F08FF9B0F10008FFF63E +:100840004DAF18F003077FF449AF0F4A08EB0503DB +:10085000926893423FF642AFB8F5807F3FF73EAFD4 +:10086000124BB845019323DD4FF47A7000F074F910 +:100870000390039A002AFFF631AF039A0137019BD8 +:1008800003F8012BEDE700BF0022022080230220A5 +:1008900068220220F9030008842302207C2202201F +:1008A00004220220082202200C22022080220220A0 +:1008B000C820FFF78DFD074600283FF40FAF1F2D1E +:1008C00011D8C5F120020AAB25F003008449424546 +:1008D000184428BF4246019200F03AFA019AFF21DB +:1008E0007F4800F05BFA4FEAA803C8F387027C490F +:1008F0002846019300F05AFA064600283FF46DAFEF +:10090000019B05EB830533E70220FFF761FD00281B +:100910003FF4E4AE00F0BAF900283FF4DFAE002760 +:10092000B846704B9B68BB4218D91F2F11D80A9B41 +:1009300001330ED027F0030312AA134453F8203CCE +:1009400005934046042205A9043700F01DFB8046AC +:10095000E7E7384600F050F90590F2E7CDF814804B +:10096000042105A800F016F902E70023642104A879 +:10097000049300F005F900287FF4B0AE0220FFF7E1 +:1009800027FD00283FF4AAAE049800F067F905900F +:10099000E6E70023642104A8049300F0F1F800289E +:1009A0007FF49CAE0220FFF713FD00283FF496AEC3 +:1009B000049800F063F9EAE70220FFF709FD002838 +:1009C0003FF48CAE00F072F9E1E70220FFF700FD82 +:1009D00000283FF483AE05A9142000F06DF9074606 +:1009E0000421049004A800F0D5F83946B9E7322074 +:1009F00000F0B2F8071EFFF671AEBB077FF46EAED3 +:100A0000384A07EB0903926893423FF667AE02202B +:100A1000FFF7DEFC00283FF461AE27F003074F44E8 +:100A2000B9453FF4A5AE484609F1040900F0E4F8E1 +:100A30000421059005A800F0ADF8F1E74FF47A70B5 +:100A4000FFF7C6FC00283FF449AE00F01FF900286C +:100A500044D00A9B01330BD008220AA9002000F0E1 +:100A6000A5F900283AD02022FF210AA800F096F923 +:100A7000FFF7B6FC1C4801F049FB13B0BDE8F08F4E +:100A8000002E3FF42BAE0BF00B030B2B7FF426AEA6 +:100A90000023642105A8059300F072F8074600289A +:100AA0007FF41CAE0220FFF793FC804600283FF441 +:100AB00015AEFFF795FC41F2883001F027FB059851 +:100AC00000F000FA46463C4600F0B4F9A6E50646BA +:100AD0004EE64FF0000901E6BA467EE637467CE670 +:100AE0008022022000220220A08601002DE9F84F7A +:100AF0004FF47A7306460D46002402FB03F7DFF835 +:100B00005080DFF8509098F900305FFA84FA5A1C50 +:100B100001D0A34210D159F824002A463146036877 +:100B2000D3F820B03B46D847854205D1074B01207A +:100B300083F800A0BDE8F88F0134042CE3D14FF412 +:100B4000FA7001F0E3FA0020F4E700BFD02302209E +:100B500010220220143D0008002307B5024601219F +:100B60000DF107008DF80730FFF7C0FF20B19DF8A9 +:100B7000070003B05DF804FB4FF0FF30F9E7000019 +:100B80000A46042108B5FFF7B1FF80F00100C0B2AA +:100B9000404208BD074B0A4630B41978064B53F85B +:100BA0002140014623682046DD69044BAC4630BC39 +:100BB000604700BFD0230220143D0008A08601003A +:100BC00070B50A4E00240A4D01F040FD30802868BF +:100BD0003388834208D901F033FD2B680444013384 +:100BE000B4F5C03F2B60F2D370BD00BFD22302200A +:100BF0008C23022001F0ECBD00F1006000F5C03054 +:100C00000068704700F10060920000F5C03001F00C +:100C10006BBD0000054B1A68054B1B889B1A83426D +:100C200002D9104401F00CBD002070478C23022033 +:100C3000D223022038B50446074D29B12868204444 +:100C4000BDE8384001F01CBD2868204401F000FDDB +:100C50000028F3D038BD00BF8C23022010F003031E +:100C600009D1B0F5846F04D200F10050A0F57120D5 +:100C70000368184670470023FBE7000000F10050AE +:100C8000A0F57120D0F8200470470000064991F8C3 :100C9000243033B100230822086A81F82430FFF79A -:100CA000B7BF0120704700BF84230220014B1868A2 -:100CB000704700BF002004E01F4BF0B51E681F4BBB -:100CC000C6F30B02360C1F885D68BA4293F90840E0 -:100CD00022D09F89BA4221D01F8BBA4206D102226C -:100CE0000C2404FB02335D6893F90840B6F5805F7D -:100CF00016D041F201039E4208BF5A24421E013D14 -:100D00000B460A44934215D215F9016F581C4EB197 -:100D1000034600F8016CF5E70022E1E70122DFE776 -:100D20004124EBE72C2582421D7001D9981C5C7090 -:100D3000401AF0BD1846FBE7002004E00422022020 -:100D400000207047704700007047000070470000A7 +:100CA000B1BF0120704700BF90230220014B18689C +:100CB000704700BF002004E0204B0246F0B51868E2 +:100CC0001F4BC0F30B06000C1F885D68BE4293F9F2 +:100CD000084022D09F89BE4221D01F8BBE4206D140 +:100CE00002240C2505FB04335D6893F90840B0F538 +:100CF000805F16D041F20103984208BF5A24013A9E +:100D0000013D0B460A4493420DD215F9016F581C60 +:100D10005EB1034600F8016CF5E70024E1E7012429 +:100D2000DFE74124EBE7184605E02C2590421D70D3 +:100D300001D2981C5C70401AF0BD00BF002004E096 +:100D40001422022070470000704700007047000026 :100D5000002310B5934203D0CC5CC4540133F9E7AF -:100D600010BD000030B5441E14F9010F0B4658B1F8 -:100D700093F900500131854206D11AB993F9002048 -:100D8000801A30BD013AEFE7002AF7D1104630BD96 -:100D900002460346981A13F9011B0029FAD170473D -:100DA00002440346934202D003F8011BFAE770475E -:100DB0002DE9F047234C05468846174694F8243021 -:100DC00083BB2E46DFF87C90C7B394F824302BB950 -:100DD0002022FF2148462662FFF7E2FF94F8240014 -:100DE0004146C0F1080504EB8000BD4228BF3D46E6 -:100DF0005FFA85FAAD00A7EB0A072A462E44FFF7F3 -:100E0000A7FF94F82430A844FFB29A445FFA8AFA04 -:100E1000BAF1080F84F824A0D6D1FFF737FF0028D5 -:100E2000D2D108E0266A06EB8306B042CAD0FFF7AB -:100E30002DFF0028C5D10020BDE8F0870120BDE8C6 -:100E4000F08700BF84230220024B1A78024B1A70ED -:100E5000704700BFC423022000220220F8B5184CBE -:100E6000184800F0BDFC2146164800F0E5FC246857 -:100E70001548E26E154DD2F80438154E43F00203C2 -:100E8000104FC2F8043801F0FDF92046114900F076 -:100E9000E1FDE26E0024D2F8043823F00203C2F828 -:100EA00004384FF4E1332B6056F82400B84202D0E6 -:100EB000294600F0F3FB0134042CF5D1F8BD00BF46 -:100EC000A83D0008482D022040420F00AC2302201C -:100ED000883C0008D43D000838B50B4B05461A780D -:100EE0000A4B53F822400A4B9C420CD0094B00217C -:100EF00018221846FFF754FF056001462046BDE85A -:100F0000384000F0CBBB38BDC4230220883C000829 -:100F1000482D0220AC230220FEE7000000B59BB064 -:100F2000EFF3098168226846FFF712FFEFF30583AC -:100F3000044B9A6BDA6A9A6A9A6A9A6A9A6A9A6A05 -:100F40009B6AFEE700ED00E000B59BB0EFF309817E -:100F500068226846FFF7FCFEEFF30583044B9A6BAB -:100F60009A6A9A6A9A6A9A6A9A6A9B6AFEE700BFC4 -:100F700000ED00E000B59BB0EFF309816822684600 -:100F8000FFF7E6FEEFF30583034B5A6B9A6A9A6A02 -:100F90009A6A9A6A9B6AFEE700ED00E030B50A445F -:100FA000074D91420BD011F8013B09245840013CF8 -:100FB000F7D040F300032B4083EA5000F7E730BD41 -:100FC0002083B8ED002304491A465A50C818083344 -:100FD0004260802BF9D17047C82302200268436821 -:100FE0001143016003B1184770470000024A1368BB -:100FF00043F0C0031360704700440040024A136886 -:1010000043F0C0031360704700480040024A136871 -:1010100043F0C00313607047007800402DE9F047AB -:10102000C66D05463768F469200734621AD014F09B -:10103000080F0CBF00218021E20748BF41F02001CA -:10104000A3074FF0200348BF41F04001600748BFAD -:1010500041F4807183F31188281DFFF7BFFF00233F -:1010600083F31188E2050AD5202383F311884FF416 -:101070000071281DFFF7B2FF002383F311884FF0A2 -:1010800020094FF0000A14F0200831D13B0616D594 -:101090004FF0200905F1380A200610D589F3118890 -:1010A000504600F06FFA00282FDA0821281DFFF7BC -:1010B00095FF27F080033360002383F311887906BE -:1010C0000DD562060BD5202383F31188EA6C2B6DB6 -:1010D0009A4201D12B6CEBB9002383F31188E3060C -:1010E00020D5AA6E1369EBB15069BDE8F0471847E7 -:1010F00089F31188736A284695F86410194000F046 -:10110000DBFA8AF31188F469BDE7B06288F31188CD -:10111000F469C1E727F040071021281DFFF75EFFA3 -:101120003760D9E7BDE8F08708B50348FFF776FFD9 -:10113000BDE8084001F028BC4824022008B5034857 -:10114000FFF76CFFBDE8084001F01EBCB42402208C -:1011500008B50348FFF762FFBDE8084001F014BC82 -:101160002025022037B52D4C2D4D204600F08AFA5F -:10117000009404F1140000234FF48072294900F018 -:101180004BF94FF48072009404F13800264B274944 -:1011900000F0C4F9264B25660B21E3652620254C7B -:1011A00000F0C4F8204600F06DFA009404F1140039 -:1011B00000234FF48072204900F02EF94FF4807222 -:1011C000009404F138001D4B1D4900F0A7F91D4B98 -:1011D00025660B21E36527201B4C00F0A7F820466D -:1011E00000F050FA04F11400009400234FF48072D0 -:1011F000164900F011F904F1380000944FF48072A0 -:10120000134B144900F08AF9134B0B215220E3656C -:10121000256603B0BDE8304000F088B848240220BD -:1012200080F937038C250220ED0F00088C2802205E -:1012300000440040B42402208C260220FD0F000848 -:101240008C29022000480040202502208C27022003 -:101250000D1000088C2A0220007800402E4B002937 -:1012600008BF1946037C012B816630B50CD12B4B8E -:10127000984235D12A4B1A6C42F400321A641A6E25 -:1012800042F400321A661B6E0A68036EC46D03EBEB -:101290005203B3FBF2F34A68150442BF23F007057B -:1012A00003F0070343EA4503E3608B6843F0400320 -:1012B0006360CB68510543F00103A36042F4967369 -:1012C00043F0010323604FF0FF33236205D512F092 -:1012D00010221DD0B2F1805F1CD080F8643030BD88 -:1012E000104B984208D10E4B1A6C42F480221A64BB -:1012F0001A6E42F48022C5E70B4B9842C4D1084BCA -:101300001A6C42F080421A641A6E42F08042B9E7C9 -:101310007F23E2E73F23E0E7C43C000848240220A3 -:1013200000380240B42402202025022000F160434E -:1013300000F01F020901400903F56143C9B28000B2 -:1013400083F80013012300F16040934000F56140F1 -:10135000C0F8803103607047F8B5154682680446CE -:101360000B46AA4200D28568A1692669761AB54261 -:1013700007D218462A46FFF7EBFCA3692B44A3616A -:101380000DE011D9AF1B32461846FFF7E1FC3A4693 -:10139000E1683044FFF7DCFCE2683A44A261A368EC -:1013A00028465B1BA360F8BD18462A46FFF7D0FC11 -:1013B000E368E4E7836893422DE9F04104460F4671 -:1013C000154600D2856860692669361AB54207D28B -:1013D0002A463946FFF7BCFC63692B4463610EE083 -:1013E00013D9A5EB060832463946FFF7B1FC424651 -:1013F000B919E068FFF7ACFCE26842446261A36897 -:1014000028465B1BA360BDE8F0812A463946FFF7FA -:101410009FFCE368E2E7000010B50A440024C361C2 -:10142000029B006040608460C16081614161026133 -:10143000036210BD08B582694369934201D1826895 -:1014400082B98268013282605A1C42611970426915 -:1014500003699A4201D3C3684361002100F02EFF63 -:10146000002008BD4FF0FF3008BD000070B52023FC -:1014700004460E4683F31188A568A5B1A368A26946 -:10148000013BA360531CA36115782269934224BFDA -:10149000E368A361E3690BB120469847002383F317 -:1014A0001188284670BD3146204600F0F7FE00281E -:1014B000E2DA85F3118870BD2DE9F74F05460F4636 -:1014C00090469A46D0F81C90202686F311884FF05B -:1014D000000B144664B1224639462846FFF73CFF0C -:1014E000034668B95146284600F0D8FE0028F1D0DE -:1014F000002383F31188A8EB040003B0BDE8F08F4C -:10150000B9F1000F03D001902846C847019B8BF327 -:101510001188E41A1F4486F31188DBE7C1608161FA -:1015200041611144C361009B0060406082600161C1 -:1015300003627047F8B504460E461746202383F32E -:101540001188A568A5B1A368013BA36063695A1C13 -:1015500062611E70236962699A4224BFE368636115 -:10156000E3690BB120469847002080F31188F8BD4D -:101570003946204600F092FE0028E2DA85F3118811 -:10158000F8BD0000836942699A4210B501D18268B2 -:101590007AB98268013282605A1C82611C780369C0 -:1015A0009A4201D3C3688361002100F087FE204680 -:1015B00010BD4FF0FF3010BD2DE9F74F05460F4627 -:1015C00090469A46D0F81C90202686F311884FF05A -:1015D000000B144664B1224639462846FFF7EAFE5E -:1015E000034668B95146284600F058FE0028F1D05D -:1015F000002383F31188A8EB040003B0BDE8F08F4B -:10160000B9F1000F03D001902846C847019B8BF326 -:101610001188E41A1F4486F31188DBE702684368E7 -:101620001143016003B11847704700001430FFF701 -:1016300043BF00004FF0FF331430FFF73DBF000001 -:101640003830FFF7B9BF00004FF0FF333830FFF7F5 -:10165000B3BF00001430FFF709BF00004FF0FF31A7 -:101660001430FFF703BF00003830FFF763BF0000FE -:101670004FF0FF323830FFF75DBF000000207047A9 -:10168000FFF770BD044B0360002343608360C360B9 -:1016900001230374704700BFDC3C000810B5202311 -:1016A000044683F31188FFF7D9FD02232374002336 -:1016B00083F3118810BD000038B5C36904460D4698 -:1016C0001BB904210844FFF7A9FF294604F11400BF -:1016D000FFF7B0FE002806DA201D4FF48061BDE858 -:1016E0003840FFF79BBF38BD026843681143016073 -:1016F00003B118477047000013B5446BD4F8943415 -:101700001A681178042915D1217C022912D119797E -:10171000012312898B4013420CD101A904F14C0022 -:1017200001F03AFFD4F894440246019B21792068E5 -:1017300000F0E0F902B010BD143001F0BDBE0000B1 -:101740004FF0FF33143001F0B7BE00004C3001F011 -:101750008FBF00004FF0FF334C3001F089BF000015 -:10176000143001F08BBE00004FF0FF31143001F057 -:1017700085BE00004C3001F05BBF00004FF0FF322F -:101780004C3001F055BF0000D0F8942438B51368F0 -:1017900005461978042901D0012038BD017C0229B1 -:1017A000FAD1127901205C8990400440F4D105F10E -:1017B000140001F01DFE02460028EDD0D5F8945427 -:1017C0004FF480732868697900F082F9204638BDAB -:1017D000406BFFF7D9BF0000002070477047000042 -:1017E0007FB5124B012502260446036000230574D1 -:1017F00000F18402436029468360C3600C4B029071 -:10180000143001934FF48073009601F0CDFD094B25 -:1018100004F523722946019304F14C004FF48073C0 -:101820000294009601F094FE04B070BD043D0008DF -:10183000D1170008F91600080B68202282F31188DE -:101840000A7903EB820210624A790D3243F82200D2 -:101850008A7912B103EB820318620223C0F8941450 -:101860000374002383F311887047000038B5037FA9 -:10187000044613B190F85430ABB90125201D022164 -:10188000FFF732FF04F1140025776FF0010100F03B -:1018900021FD84F8545004F14C006FF00101BDE8C3 -:1018A000384000F017BD38BD10B5012104460430A2 -:1018B000FFF71AFF0023237784F8543010BD00008F -:1018C00038B504460025143001F086FD04F14C00C3 -:1018D000257701F055FE201D84F854500121FFF7B3 -:1018E00003FF2046BDE83840FFF74EBF90F85C305C -:1018F00003F06003202B19D190F85D20212A0AD033 -:10190000222A4FF000030ED0202A0FD1084A026588 -:101910000722426504E0064B036507234365002365 -:1019200083650120704703654365F9E70020704730 -:1019300028220220D0F8943437B51A68044611786A -:1019400004291AD1017C022917D11979012312899E -:101950008B40134211D100F14C05284601F0D0FE16 -:1019600058B101A9284601F017FED4F89444024664 -:10197000019B2179206800F0BDF803B030BD000064 -:1019800000EB8103F7B51C6A05460E46F4B120232F -:1019900083F3118805EB8607201D08214C34FFF7DF -:1019A000A3FEFB685B691B6813B1204601F002FED1 -:1019B00001A9204601F0F0FD024648B1019B3146E5 -:1019C000284600F097F8002383F3118803B0F0BD98 -:1019D000FB685A691268002AF5D01B8A013B134044 -:1019E000F1D105F15C02EAE70D3138B550F821403C -:1019F000DCB1202383F31188D4F89424136852793E -:101A000003EB8203DB689B695D6845B104216018C4 -:101A1000FFF76AFE294604F1140001F0F3FC2046AA -:101A2000FFF7B2FE002383F3118838BD7047000032 -:101A300001F0A2B8012300F1240200F13801037083 -:101A40000023436042F8043B8A421361FAD10381C8 -:101A50004381704738B50446202383F3118800255D -:101A60004160C560056145618561C561056201F040 -:101A700093F80223237085F3118838BD70B500EB0D -:101A80008103054650690E461446DA6018B11022EB -:101A90000021FFF785F9A06918B110220021FFF796 -:101AA0007FF931462846BDE8704001F03FB900009B -:101AB000028902F001020281428902F001024281A0 -:101AC0000022026142618261C261026201F0C2B918 -:101AD000F0B4012500EB810447898D40E4683D4363 -:101AE000A469458123600023A2606360F0BC01F01B -:101AF000DDB90000F0B4012500EB810407898D40B9 -:101B0000E4683D436469058123600023A26063604B -:101B1000F0BC01F057BA000070B50223002504465E -:101B20000370A0F8645080F8665080F86750058113 -:101B30004581C560056145618561C561056280F8C3 -:101B40004C5001F08FF863681B6823B1294620468A -:101B5000BDE87040184770BD0278436880F868207F -:101B600005221B6802700BB1042118477047000062 -:101B7000436890F868201B6802700BB10521184774 -:101B80007047000090F84C3070B5044613B1002344 -:101B900080F84C3004F15C02204601F07DF9636866 -:101BA0009B6863BB94F85C5015F0600615D194F8FF -:101BB0005D3005F07F0545EA032540F202339D4282 -:101BC00000F00E815BD8022D00F0DC803FD8002DA4 -:101BD00000F08780012D00F0CF800021204601F029 -:101BE000C5FB0021204601F0B7FB63681B6813B1F9 -:101BF000062120469847062384F84C3070BD2046C5 -:101C000098470028CED094F8632094F8623043EAD5 -:101C10000223626D934238BF636594F95C30656D51 -:101C2000002B4FF0200380F2FD80002D00F0EC80AF -:101C3000092284F84C2083F311880021636D226D02 -:101C40002046FFF757FF002383F3118870BDB5F5D9 -:101C5000817F00F0B180B5F5407F49D0B5F5807F38 -:101C6000BBD194F85E30012BB7D1B4F8643023F0C7 -:101C70000203A4F8643026656665A665C3E740F2F2 -:101C800001639D421ED8B5F5C06F3BD2B5F5A06F7C -:101C9000A3D1B4F85C30B3F5A06F0ED194F85E30E8 -:101CA000204684F8663001F035F863681B6813B18C -:101CB0000121204698470323237000232365636591 -:101CC000A365A0E7B5F5106F32D040F602439D4200 -:101CD00052D0B5F5006F80D104F16703236501236D -:101CE00024E004F16403A5652365022363658AE7A4 -:101CF00094F85E30012B7FF470AFB4F8643043F099 -:101D00000203B6E794F861202046616894F86030D9 -:101D10004D6843EA022394F85F1094F85E20A847C8 -:101D200000283FF45AAF4368236503686365A4E75E -:101D30002378042B10D1202383F311882046FFF74A -:101D4000B7FE86F311886368032184F867601B6817 -:101D500021700BB12046984794F85E30002BACD030 -:101D600084F867300423237063681B68002BA4D0B9 -:101D7000022120469847A0E7374B2365022363657D -:101D800000239DE794F86010204611F0800F01F0C9 -:101D90000F010ED001F072F8012806D002287FF45E -:101DA0001CAF2E4B6065236567E72D4B656523658A -:101DB00063E701F055F8EFE794F85E30002B7FF40D -:101DC0000CAF94F8603013F00F013FF476AF1A06B1 -:101DD000204602D501F0DEFA6FE701F0D1FA6CE798 -:101DE00094F85E30002B7FF4F8AE94F8603013F076 -:101DF0000F013FF462AF1B06204602D501F0B6FA90 -:101E00005BE701F0A9FA58E7142284F84C2083F329 -:101E100011882B462A4629462046FFF759FE85F3AE -:101E2000118870BD5DB1152284F84C2083F31188B0 -:101E30000021636D226D2046FFF74AFE03E70B2267 -:101E400084F84C2083F311882B462A4629462046E5 -:101E5000FFF750FEE3E700BF343D00082C3D0008CB -:101E6000303D000838B590F84C300446152B29D881 -:101E7000DFE803F03E28282828283E28280B2939A7 -:101E800028282828282828283E3E90F8631090F813 -:101E90006220436D42EA01229A4214D9C268128A32 -:101EA000B3FBF2F502FB15356DB9202383F31188DE -:101EB0002B462A462946FFF71DFE85F311880A2383 -:101EC00084F84C3038BD142384F84C30202383F33D -:101ED0001188002320461A461946FFF7F9FD002312 -:101EE00083F3118838BD836D03B198470023E7E77A -:101EF000002101F03BFA0021204601F02DFA636831 -:101F00001B6813B10621204698470623D8E7000036 -:101F100090F84C20152A38B5044622D80123934066 -:101F200040F6416213421DD113F480150FD19B027C -:101F300017D50B2380F84C30202383F311882B46D0 -:101F40002A462946FFF7D6FD85F3118838BDC368B8 -:101F50009B695B682BB9836D03B19847002384F8B4 -:101F60004C3038BD002101F001FA0021204601F07B -:101F7000F3F963681B6813B10621204698470623CE -:101F8000EDE70000024B00221B605B609A60704727 -:101F90008C2B0220002382680374054B1B68996810 -:101FA0009142FBD25A6803604260106058607047EB -:101FB0008C2B022008B5202383F31188037C032B8C -:101FC00005D0042B0DD02BB983F3118808BD4369CC -:101FD00000221A604FF0FF334361FFF7DBFF00235D -:101FE000F2E790E80C001A6002685360F2E7000024 -:101FF000002382680374054B1B6899689142FBD8E3 -:102000005A68036042601060586070478C2B022051 -:10201000054B196908741868026853601A601861E2 -:1020200001230374FEF780B98C2B02204B1C30B5C2 -:10203000054687B00A4C10D0236901A8094A00F070 -:1020400065F92846FFF7E4FF049B13B101A800F0EF -:1020500099F92369586907B030BDFFF7D9FFF8E750 -:102060008C2B0220B51F000838B50C4D0446416189 -:102070002B6981689A68914203D8BDE83840FFF720 -:1020800089BF1846FFF786FF01232C6101462374A0 -:102090002046BDE83840FEF747B900BF8C2B022030 -:1020A000044B1A681B6990689B68984294BF002093 -:1020B000012070478C2B022010B5084C2368206942 -:1020C0001A6854602260012223611A74FFF790FF9E -:1020D00001462069BDE81040FEF726B98C2B02208E -:1020E000FEE7000010B5194CFFF74CFF00F000F9B7 -:1020F00080221749204600F085F8012344F8180C87 -:102100000374144B144AD96821F4E0610904090CE2 -:102110000A431249DA60CA6842F08072CA60104A03 -:102120001049C2F8B01F116841F00101116010227E -:10213000DA77202283F82220002383F3118862B605 -:102140000948BDE8104000F07FB800BFB42B022062 -:10215000383D000800ED00E00003FA05F0ED00E076 -:10216000001000E055CEACC5403D00082DE9F84F09 -:102170001E4C4FF00008656904F11407C1464FF08A -:102180008043266AAA685B6A9E1B96421CD34FF066 -:10219000200AAA68236AD5F80CB0B61A1344236241 -:1021A0002B68BB425F606361C5F80C8001D101F010 -:1021B000D1FA89F311882869D8478AF311886569AB -:1021C000AB689E42E5D2DAE76269BA420CD0916808 -:1021D00023628E1B9660A86802282CBF1818981CD2 -:1021E000BDE8F84F01F0BCBABDE8F88F8C2B022097 -:1021F000034B59685A68521A9042FBD8704700BF87 -:10220000001000E0826002220274002242747047D3 -:102210008368A3F17C0243F80C2C026943F83C2C40 -:10222000426943F8382C074A43F81C2CC268A3F1D2 -:10223000180043F8102C022203F8082C002203F89F -:10224000072C70474103000810B5202383F3118841 -:10225000FFF7DEFF00210446FFF706FF002383F3AC -:102260001188204610BD0000024B1B6958610F20E9 -:10227000FFF7CEBE8C2B0220202383F31188FFF7BB -:10228000F3BF000008B50146202383F3118808201E -:10229000FFF7CCFE002383F3118808BD49B1064B3C -:1022A00042681B6918605A60136043600420FFF79E -:1022B000BDBE4FF0FF3070478C2B02200368984260 -:1022C00006D01A680260506018465961FFF762BE76 -:1022D0007047000038B504460D462068844200D19E -:1022E00038BD036823605C604561FFF753FEF4E787 -:1022F000054B03F114025A619A614FF0FF32DA6123 -:1023000000221A62704700BF8C2B0220F8B50361CF -:102310004FF08043C26002295C6A0646184B38BF02 -:1023200002211A461F4652F8145F95420AD158619D -:1023300098611C620560456081600819BDE8F8403D -:1023400001F000BA186AAB68241A0C1902D3E41A17 -:102350002D6804E09C4202D2204401F001FAAB68EF -:102360009C42F4D86B68356073601E604FF0FF3399 -:102370006E60B460A968091BA960FB61F8BD00BF6D -:102380008C2B022010B41B4C234653F8141F81429F -:1023900010D0416802680A60026851609A424FF0AA -:1023A0000001C16003D0936881680B4493605DF8BD -:1023B000044B70470A6800209A4262615360C8600B -:1023C00003D15DF8044B01F0C5B9936888680344F4 -:1023D000206A93604FF08042526A121A9342E6D903 -:1023E000991A5DF8044B012998BF931C184401F019 -:1023F000B7B900BF8C2B022000207047FEE7000019 -:10240000704700004FF0FF3070470000022906D0EF -:10241000032906D00129064818BF00207047054847 -:102420007047032A9ABF044800EBC200002070479F -:10243000303E0008E43D00083022022070B59AB01A -:1024400006460846144601AD294600F095F8284690 -:10245000FEF79EFCC0B2431C5B0086E818002370A8 -:102460000323023404F8013C00231946DAB2023493 -:10247000904201D81AB070BDEA5C013304F8011C27 -:1024800004F8022CF2E7000008B5202383F311883A -:102490000348FFF74FFA002383F3118808BD00BFFC -:1024A000482D022010B50446052916D8DFE801F0B2 -:1024B00016150316161D202383F311880E4A0121D9 -:1024C000FFF7DCFA20460D4A0221FFF7D7FA0C4845 -:1024D000FFF7F6F9002383F3118810BD202383F35F -:1024E00011880748FFF7C2F9F4E7202383F3118826 -:1024F0000348FFF7D9F9EDE7603D0008843D000887 -:10250000482D022038B50C4D0C4C2A460C4904F1DC -:102510000800FFF793FF05F1CA0204F11000094912 -:10252000FFF78CFF05F5CA7204F118000649BDE8F3 -:102530003840FFF783BF00BF103202203022022054 -:10254000B03D0008BD3D0008CB3D000870B5044615 -:1025500008460D46FEF71CFCC6B22046013403783F -:102560000BB9184670BD32462946FEF7FBFB002822 -:10257000F3D1012070BD00002DE9F04704460D465F -:10258000FEF706FC2B49C6B22046FFF7DFFF08B175 -:102590000A36F6B228492046FFF7D8FF08B11036B0 -:1025A000F6B2632E0BD8DFF88C80DFF88C90234FC7 -:1025B000DFF894A0267846B92E70BDE8F087214652 -:1025C0002846BDE8F04701F053BB252E2ED1072247 -:1025D00041462046FEF7C6FB70B9194B2A4603F167 -:1025E000100153F8040B8B4242F8040BF9D11B780D -:1025F000073411351370DDE7082249462046FEF7FF -:10260000B1FB98B9AA1C0F4B13F8011F023209093C -:102610005345C95D02F8041C197801F00F01C95D2A -:1026200002F8031CF0D118350834C3E72E700134CA -:102630000135BFE7503E0008CB3D00086A3E000868 -:10264000583E00081FF4F01F2BF4F01FBFF34F8F0C -:10265000024AD368DB03FCD4704700BF003C024051 -:1026600008B5074B1B7853B9FFF7F0FF054B1A6904 -:10267000002A04DA044A5A6002F188325A6008BD1E -:102680006E340220003C02402301674508B5054B2B -:102690001B7833B9FFF7DAFF034A136943F00043AD -:1026A000136108BD6E340220003C02400B2870B557 -:1026B00013D80B4A0B4C137863B94FF000610A4EE4 -:1026C00044F8231056F8235001330C2B2944F7D13A -:1026D0000123137054F8200070BD002070BD00BFAE -:1026E000A0340220703402207C3E0008014B53F8D5 -:1026F000200070477C3E00080C2070470B2810B566 -:10270000044601D9002010BDFFF7D0FF064B53F857 -:1027100024301844C21A0BB9012010BD12680132CE -:10272000F0D1043BF6E700BF7C3E00080B2810B553 -:10273000044621D8FFF78AFFFFF792FF0F4AF323E1 -:10274000D360C300DBB243F4007343F002031361B0 -:10275000136943F480331361FFF778FFFFF7A6FF97 -:10276000074B53F8241000F0DBF8FFF78FFF2046EB -:10277000BDE81040FFF7C2BF002010BD003C024082 -:102780007C3E00082DE9F84312F0010315463FD1C5 -:102790008218B2F1026F3BD22B4B1B6813F001037E -:1027A00036D0FFF75DFF294CF32340F20127E360A9 -:1027B000FFF74CFF032D01D9830712D00F46401AB3 -:1027C000224C40F20118EB1BC6190B44012B236964 -:1027D00024D823F001032361FFF758FF0120BDE84F -:1027E000F883236923F44073236123693B43236106 -:1027F00051F8046B0660BFF34F8FFFF727FF0368A4 -:102800009E4208D0236923F001032361FFF73EFFB6 -:102810000020BDE8F883043D0430CBE723F4407387 -:10282000B9462361236943EA0803236137F8023B71 -:102830003380BFF34F8FFFF709FF3688B6B2B9F880 -:102840000030B342BFD0DDE700380240003C024018 -:10285000084908B50B7828B153B9FFF701FF0123E8 -:102860000B7008BD23B10870BDE80840FFF70EBF2C -:1028700008BD00BF6E34022002440439064BD2B2B8 -:1028800010B5904200D110BD441C00B253F8200096 -:1028900041F8040FE0B2F4E750280040104B30B587 -:1028A0001C6F240407D41C6F44F400741C671C6F55 -:1028B00044F400441C670B4C024404392368D2B230 -:1028C00043F480732360084B904200D130BD441C18 -:1028D00051F8045F00B243F82050E0B2F4E700BFC3 -:1028E00000380240007000405028004007B5012227 -:1028F00001A90020FFF7C0FF019803B05DF804FBB9 -:1029000013B50446FFF7F2FFA04206D002A9012248 -:10291000002041F8044DFFF7C1FF02B010BD0000D8 -:102920000144BFF34F8F064B884204D3BFF34F8F50 -:10293000BFF36F8F7047C3F85C022030F4E700BF2D -:1029400000ED00E0034B1B689B0042BF0122024BDD -:102950001A70704774380240A1340220014B187875 -:10296000704700BFA1340220064A536823F00103D8 -:102970005360EFF30983683383F30988002383F3FB -:102980001188704730EF00E010B5202383F31188E1 -:10299000104B5B6813F4006318D0F1EE103AEFF3BC -:1029A00009844FF0807344F84C3C0B4BDB6844F8CF -:1029B000083CA4F1680383F30988FFF771FB18B1A1 -:1029C000064B44F8503C10BD054BFAE783F31188E1 -:1029D00010BD00BF00ED00E030EF00E05103000843 -:1029E00054030008F0B5BFF34F8FBFF36F8F1D4B3B -:1029F0000021C3F85012BFF34F8FBFF36F8F5A6996 -:102A000042F400325A61BFF34F8FBFF36F8FC3F8A8 -:102A10008410BFF34F8FD3F8802043F6E076C2F3E3 -:102A2000C904C2F34E32A507520102EA060E284637 -:102A300021464EEA0007013900F14040C3F86072B8 -:102A40004F1CF6D1203A12F1200FEED1BFF34F8F79 -:102A50005A6942F480325A61BFF34F8FBFF36F8FD0 -:102A6000F0BD00BF00ED00E0FEE70000084A094BA2 -:102A700009498B4204D3094A0021934205D3704788 -:102A800052F8040F43F8040BF3E743F8041BF4E790 -:102A90005C400008343502203435022034350220F1 -:102AA000036F002230B51146C46E9D684FF0FF30B1 -:102AB00004EB421301329542C3F80019C3F8101910 -:102AC000C3F80809C3F8001BC3F8101BC3F8080BB0 -:102AD000EED24FF00113C4F81C3830BD890141F02B -:102AE0002001016103699B06FCD41220FFF780BB23 -:102AF000204B03EB80022DE9F047D2F80CE0461C96 -:102B0000DD6EDEF8142005EB0636D2F800C005EBCA -:102B10004018516861450BD30123D5F8342803FAD6 -:102B200000F022EA0000C5F834081846BDE8F08736 -:102B3000ACEB0103BEF81040A34228BF2346D8F8EF -:102B40001849A4B2B3EB840F10D894681F46A4F1BF -:102B5000040959F804AF042FC6F800A001D9043FB6 -:102B6000F7E71C440B4494605360D2E70020BDE8B3 -:102B7000F08700BFA434022010B5054C2046FEF7B4 -:102B800059FF4FF0A043E366024B236710BD00BF1F -:102B9000A4340220D03E00080378012B70B505460E -:102BA00050D12A4BC46E98421BD1294B0E21432091 -:102BB0005A6B42F080025A635A6D42F080025A65A5 -:102BC0005A6D5A6942F080025A615A6922F08002B5 -:102BD0005A615B69FEF7AAFB1E4BE3601E4BC4F80B -:102BE00000380023EE6EC4F8003EC02323604FF48B -:102BF0000413A3633369002BFCDA01230C20336137 -:102C0000FFF7F6FA3369DB07FCD41220FFF7F0FA7E -:102C10003369002BFCDA00262846A660FFF740FF48 -:102C20006B68C4F81068DB68C4F81468C4F81C68E2 -:102C30004BB90A4BA3614FF0FF336361A36843F0C4 -:102C40000103A36070BD064BF4E700BFA43402206B -:102C5000003802404014004003002002003C30C015 -:102C6000083C30C0F8B5C46E054600214FF0006640 -:102C70002046FFF733FF296F00234FF001128F68C2 -:102C80004FF0FF30C4F83438C4F81C2804EB43126A -:102C900001339F42C2F80069C2F8006BC2F808090C -:102CA000C2F8080BF2D20B68EA6E6B6763621023FE -:102CB0001361166916F01006FBD11220FFF798FA7F -:102CC000D4F8003823F4FE63C4F80038A36943F451 -:102CD000402343F01003A3610923C4F81038C4F85B -:102CE00014380A4BEB604FF0C043C4F8103B084B5C -:102CF000C4F8003BC4F81069C4F800396B6F03F1E5 -:102D0000100243F480136A67A362F8BDAC3E00086A -:102D100040800010C26E90F86610D2F8003823F49C -:102D2000FE6343EA0113C2F8003870472DE9F04111 -:102D30000EB20D4600EB8608D8F80C100F6807F0AD -:102D40000303022B50D0032B50D03D4A3D4F012BA3 -:102D500018BF1746C46E4FEA451E002205F1100C3D -:102D600004EB0E03C3F8102B8A69002A40D04A8A6C -:102D700005F158033A435B01E2500123D4F81C28C3 -:102D800003FA0CF31343C4F81C38A64400234A6921 -:102D9000CEF8103905F13F03002A39D00A8A04EB36 -:102DA0008303898B9208012988BF4A43416F5618D3 -:102DB00041EA02422946466720465A60FFF78EFEE6 -:102DC000D8F80C301B8A43EA85531F4305F14803AA -:102DD0005B01E7500123D4F81C2803FA05F51543DD -:102DE000C4F81C58BDE8F081174FB3E7174FB1E79F -:102DF00004EB4613D3F8002B22F40042C3F8002B57 -:102E00000123D4F81C2803FA0CF322EA0303BAE7DF -:102E100004EB83030E4A04EB461629465A6020460B -:102E2000FFF75CFED6F80039012223F4004302FAD2 -:102E300005F5C6F80039D4F81C3823EA0505CFE7B4 -:102E400000800010008004100080081000800C102A -:102E500000040002026F12684267FFF721BE000003 -:102E60005831C36E49015B5813F4004004D013F489 -:102E7000001F14BF01200220704700004831C36EBC -:102E800049015B5813F4004004D013F4001F14BF31 -:102E9000012002207047000000EB8101CB68196A15 -:102EA0000B6813604B6853607047000000EB8103B0 -:102EB00030B5DD68AA691368D36019B9402B84BFA7 -:102EC000402313606B8A1468C26E1C4402EB4110ED -:102ED000013C09B2B4FBF3F46343033323F003036F -:102EE00043EAC44343F0C043C0F8103B2B6803F0EF -:102EF0000303012B0ED1D2F8083802EB411013F472 -:102F0000807FD0F8003B14BF43F0805343F0005360 -:102F1000C0F8003B02EB4112D2F8003B43F00443FF -:102F2000C2F8003B30BD00002DE9F041244D0446BD -:102F3000EE6E06EB4013D3F8087B3807C3F8087B26 -:102F40000AD5D6F81438190706D505EB84032146AF -:102F50002846DB685B689847FA072FD5D6F81438FF -:102F6000DB072BD505EB8403D968CCB98B69488A7C -:102F70005E68B6FBF0F200FB12628AB91868DA6884 -:102F800090420DD2121A83E81400202383F3118893 -:102F90000B482146FFF78AFF84F31188BDE8F081D2 -:102FA000012303FA04F26B8923EA02036B81CB68E5 -:102FB00023B121460248BDE8F0411847BDE8F08141 -:102FC000A434022000EB81034A0170B5DD68C36EB2 -:102FD0006C692668E66056BB1A444FF40020C2F8BC -:102FE00010092A6802F00302012A0AB20ED1D3F8AE -:102FF000080803EB421410F4807FD4F8000914BFD2 -:1030000040F0805040F00050C4F8000903EB421239 -:10301000D2F8000940F00440C2F800090122D3F8B8 -:10302000340802FA01F10143C3F8341870BD19B92C -:10303000402E84BF4020206020681A442E8A8419C4 -:1030400040F00050013CB4FBF6F440EAC440C6E74F -:10305000F8B504461E48C56E05EB4413D3F808695D -:10306000F107C3F8086917D5D5F81038DA0713D572 -:1030700000EB8403D9684B691F68DA68974218D25D -:10308000D21B00271A605F60202383F3118821463A -:10309000FFF798FF87F31188330617D50123D5F87A -:1030A0003428A340134211D02046BDE8F840FFF772 -:1030B0001FBD012303FA04F2038923EA02030381FB -:1030C0008B68002BE8D021469847E5E7F8BD00BFA4 -:1030D000A43402209F482DE9F84FC56E04466E695E -:1030E000AB691E4016F4805F6E6105D0FEF714FDDB -:1030F000BDE8F84FFFF748BC002E12DAD5F8003EC5 -:103100009B0705D0D5F8003E23F00303C5F8003E29 -:10311000D5F804388F4823F00103C5F80438FEF7CA -:1031200027FD370502D58B48FEF716FDB0040CD5F8 -:10313000D5F8083813F0060FEB6823F470530CBF72 -:1031400043F4105343F4A053EB60310704D5636894 -:10315000DB680BB17F489847F2026FD4B3020CD5FD -:10316000D4F86C8000274FF00109DFF8E8A1236F45 -:10317000F9B29B688B4280F09C80F70619D5E16E0E -:103180000A6AC2F30A1702F00F0302F4F012B2F552 -:10319000802F00F0B580B2F5402F0AD104EB8303F5 -:1031A00001F58051DB68186A00231A469F4240F0FF -:1031B0009C803303D5F818481DD5E70302D50020BD -:1031C000FFF7B2FEA50302D50120FFF7ADFE6003B5 -:1031D00002D50220FFF7A8FE210302D50320FFF746 -:1031E000A3FEE20202D50420FFF79EFEA30202D551 -:1031F0000520FFF799FE77037FF57AAFE60702D542 -:103200000020FFF725FFA50702D50120FFF720FFCB -:10321000600702D50220FFF71BFF210702D503201C -:10322000FFF716FFE20602D50420FFF711FFA30601 -:103230007FF55EAF0520FFF70BFF59E7D4F86C80F0 -:1032400000274FF00109DFF80CA1236F5FFA87FB1D -:103250009B685B4582D308EB4B13D3F8002902F43B -:103260004022B2F5802F22D1D3F80029002A1EDA9D -:10327000D3F8002942F09042C3F80029D3F800297E -:10328000002AFBDB5946E06EFFF728FC228909FA89 -:103290000BF322EA0303238104EB8B03DB689B68B7 -:1032A00013B15946504698475846FFF721FC01375D -:1032B000CBE708EB4112D2F8003B03F44023B3F50F -:1032C000802F10D1D2F8003B002B0CDA628909FA6A -:1032D00001F322EA0303638104EB8103DB68DB680B -:1032E0000BB150469847013741E79C0700D10A6867 -:1032F000072B03F101039EBF0270120A013055E74C -:10330000023301F5805104EB830252689069026830 -:10331000D0F808C04068A2EB000E00221046974289 -:103320000AD104EB830463689B699A683A449A6003 -:103330005A6817445F603CE712F0030F00D1086839 -:10334000964502F1010282BF8CF80000000A0CF1E0 -:10335000010CE4E7A4340220C36E03EB4111D1F861 -:10336000003B43F40013C1F8003B7047C36E03EB0E -:103370004111D1F8003943F40013C1F80039704706 -:10338000C36E03EB4111D1F8003B23F40013C1F8E5 -:10339000003B7047C36E03EB4111D1F8003923F4B1 -:1033A0000013C1F80039704730B50433039C017233 -:1033B000002104FB0325C361049B00600363059B9C -:1033C0004060C16042610261856104624262816263 -:1033D000C162436330BD00000022416AC2604161A6 -:1033E00001616FF001018262C262FEF773BF0000EB -:1033F00003694269934203D1C2680AB10020704751 -:10340000181D7047036919600021C2680132C2604B -:10341000C269134482699342036124BF436A036112 -:10342000FEF74CBF38B504460D46E3683BB1626910 -:103430000020131D1268A3621344E36238BD237A8F -:1034400033B929462046FEF729FF0028EDDA38BDBA -:103450006FF00100FBE70000C368C269013BC36075 -:103460004369134482699342436124BF436A4361C1 -:1034700000238362036B03B11847704770B52023A4 -:10348000044683F31188866A3EB9FFF7CBFF0546F1 -:1034900018B186F31188284670BDA36AE26A13F852 -:1034A000015B9342A36202D32046FFF7D5FF0023BE -:1034B00083F31188EFE700002DE9F84F04460E462C -:1034C00090469946202787F311880025AA46D4F80C -:1034D00028B0BBF1000F09D149462046FFF7A2FFF3 -:1034E00020B18BF311882846BDE8F88FA16AA8EBBC -:1034F000050BE36A5B1A9B4528BF9B46BBF1400F57 -:103500001BD9334601F1400251F8040B914243F8B4 -:10351000040BF9D1A36A403640354033A362A26A56 -:10352000E36A9A4202D32046FFF796FF8AF3118896 -:103530004545D8D287F31188C9E730465A46FDF78A -:1035400007FCA36A5E445D445B44A362E7E70000B6 -:1035500010B5029C04330172C36103FB04210023F4 -:1035600000608362C362039B40600363049BC4608A -:1035700042610261816104624262436310BD0000E6 -:10358000026A6FF00101C260426A42610261002278 -:103590008262C262FEF79EBE436902699A4203D10B -:1035A000C2680AB100207047184650F8043B0B600F -:1035B00070470000C3680021C2690133C3604369DA -:1035C000134482699342436124BF436A4361FEF717 -:1035D00075BE000038B504460D46E3683BB123696B -:1035E00000201A1DA262E2691344E36238BD237A07 -:1035F00033B929462046FEF751FE0028EDDA38BDE2 -:103600006FF00100FBE7000003691960C268013A2E -:10361000C260C269134482699342036124BF436A52 -:10362000036100238362036B03B1184770470000F6 -:1036300070B5202304460E4683F31188856A35B998 -:103640001146FFF7C7FF10B185F3118870BDA36A5B -:103650001E70A36AE26A01339342A36204D3E16954 -:1036600020460439FFF7D0FF002080F3118870BD99 -:103670002DE9F84F04460D4691469A464FF0200832 -:1036800088F311880026B346A76A4FB951462046F1 -:10369000FFF7A0FF20B187F311883046BDE8F88F0F -:1036A000A06AA9EB0603E76A3F1A9F4228BF1F469C -:1036B000402F1BD905F1400355F8042B9D4240F8DB -:1036C000042BF9D1A36A40364033A362A26AE36AAD -:1036D0009A4204D3E16920460439FFF795FF8BF342 -:1036E00011884E45D9D288F31188CDE729463A464C -:1036F000FDF72EFBA36A3D443E443B44A362E5E74D -:10370000026943699A4203D1C3681BB918467047DE -:103710000023FBE7836A002BF8D0043B9B1AF5D00B -:103720001360C368013BC360C3691A4483699A424A -:10373000026124BF436A0361002383620123E5E73A -:1037400000F0AEB84FF08043002258631A610222A5 -:10375000DA60704700224FF08043DA607047000063 -:103760004FF08043586370474B6843608B688360B9 -:10377000CB68C3600B6943614B6903628B69436229 -:103780000B6803607047000008B5274B40F2FF71DB -:1037900026481A690A431A611A6922F4FF6222F064 -:1037A00007021A611A691A6B0A431A631A6D0A43EF -:1037B0001A651F4A1B6D1146FFF7D6FF1D4802F11F -:1037C0001C01FFF7D1FF1C4802F13801FFF7CCFFC5 -:1037D0001A4802F15401FFF7C7FF194802F17001BE -:1037E000FFF7C2FF174802F18C01FFF7BDFF164833 -:1037F00002F1A801FFF7B8FF144802F1C401FFF776 -:10380000B3FF134802F1E001FFF7AEFF114802F1E8 -:10381000FC01FFF7A9FF104802F58C71FFF7A4FF28 -:10382000BDE8084000F09EB80038024000000240A9 -:10383000DC3E00080004024000080240000C024088 -:10384000001002400014024000180240001C024018 -:1038500000200240002402400028024008B500F089 -:10386000F5F9FEF73FFCFFF76DF8BDE80840FEF7FD -:1038700049BE0000704700004FF080431A6992076C -:1038800010B508D500241C61202383F31188FEF7AE -:103890006DFC84F31188BDE81040FFF775B8000097 -:1038A000104B08211C201A6C42F001021A641A6E97 -:1038B00042F001021A660C4A1B6E936843F0010342 -:1038C00093604FF080436B229A624FF0FF32DA62CE -:1038D00000229A615A63DA605A6001225A611A60C2 -:1038E000FDF724BD00380240002004E01B4B4FF0E0 -:1038F000FF3000211A696FEA42526FEA52521A6190 -:103900001A69C2F30A021A611A695A6958615A6936 -:1039100059615A691A6A62F080521A621A6A02F090 -:1039200080521A621A6A5A6A58625A6A59625A6A04 -:103930000B4A106840F480701060186F00F44070FB -:10394000B0F5007F03D04FF48030186719675368D3 -:1039500023F40073536000F059B900BF00380240EF -:1039600000700040354B4FF44041354A1A64354AE7 -:1039700011601A6842F001021A601A689207FCD5B9 -:103980009A6822F003029A602C4B19469A6812F04A -:103990000C02FBD1186800F0F90018609A601A68F0 -:1039A00042F480321A600B689B03FCD54B6F43F0E6 -:1039B00001034B67214B5A6F9007FCD5224A5A608E -:1039C0001A6842F080721A601E4B1A465968490400 -:1039D000FCD5196841F4803119605368D803FCD5CF -:1039E000136843F400331360164A53689903FCD5F7 -:1039F000124B1A689201FCD5144A40F207319A60C2 -:103A000040F20112C3F88C200022C3F89020104A23 -:103A100011609A6842F002029A60084B9A6802F0BC -:103A20000C02082AFAD15A6C42F480425A645A6E47 -:103A300042F480425A665B6E704700BF0038024015 -:103A40000004001000700040186C40090094883891 -:103A5000003C0240084A08B5536911680B4003F066 -:103A60000103536123B1054A13680BB150689847AD -:103A7000BDE80840FEF788BF003C0140C823022093 -:103A8000084A08B5536911680B4003F002035361FB -:103A900023B1054A93680BB1D0689847BDE8084048 -:103AA000FEF772BF003C0140C8230220084A08B557 -:103AB000536911680B4003F00403536123B1054AB5 -:103AC00013690BB150699847BDE80840FEF75CBF29 -:103AD000003C0140C8230220084A08B55369116818 -:103AE0000B4003F00803536123B1054A93690BB1FE -:103AF000D0699847BDE80840FEF746BF003C01404A -:103B0000C8230220084A08B5536911680B4003F026 -:103B10001003536123B1054A136A0BB1506A9847E9 -:103B2000BDE80840FEF730BF003C0140C82302203A -:103B3000174B10B55C691A68144004F478725A6126 -:103B4000A30604D5134A936A0BB1D06A984760065E -:103B500004D5104A136B0BB1506B9847210604D55E -:103B60000C4A936B0BB1D06B9847E20504D5094A18 -:103B7000136C0BB1506C9847A30504D5054A936CA0 -:103B80000BB1D06C9847BDE81040FEF7FDBE00BFFA -:103B9000003C0140C82302201A4B10B55C691A682A -:103BA000144004F47C425A61620504D5164A136D30 -:103BB0000BB1506D9847230504D5134A936D0BB193 -:103BC000D06D9847E00404D50F4A136E0BB1506EC8 -:103BD0009847A10404D50C4A936E0BB1D06E984758 -:103BE000620404D5084A136F0BB1506F9847230441 -:103BF00004D5054A936F0BB1D06F9847BDE81040CC -:103C0000FEF7C2BE003C0140C8230220062108B5D1 -:103C10000846FDF78BFB06210720FDF787FB0621F1 -:103C20000820FDF783FB06210920FDF77FFB062115 -:103C30000A20FDF77BFB06211720FDF777FB062105 -:103C40002820BDE80840FDF771BB000008B5FFF76C -:103C50004DFEFDF7B7F9FDF713FDFDF7E9FEFDF7A2 -:103C6000BDFDFFF707FEBDE80840FFF769BD000096 -:103C7000034611F8012B03F8012B002AF9D17047F4 -:103C80001210121312110000482D022048240220A5 -:103C9000B42402202025022053544D3332463F3FA6 -:103CA0003F3F3F3F0053544D333246375B347C3502 -:103CB0005D780053544D333246375B367C375D7840 -:103CC000000000000096000000000000000000005E -:103CD00000000000000000000000000000000000E4 -:103CE0004916000835160008711600085D16000810 -:103CF0006916000855160008411600082D16000820 -:103D00007D16000800000000551700084117000844 -:103D10007D1700086917000875170008611700086B -:103D20004D17000839170008D917000800000000D7 -:103D300001000000000000006D61696E00000000DD -:103D4000583D0008D02B0220482D02200100000021 -:103D5000E12000080000000069646C6500000000BC -:103D6000020000000000000081190008E9190008A5 -:103D700040004000E0310220F0310220020000004B -:103D80000000000003000000000000002D1A0008E1 -:103D900000000000100000000032022000000000BF -:103DA0000100000000000000A43402200101020014 -:103DB0004865782F50726F6669434E4300437562C1 -:103DC0006559656C6C6F772D424C002553455249FF -:103DD000414C2500A52400080D240008ED1800081A -:103DE0008924000843000000EC3D0008090243005C -:103DF000020100C032090400000102020100052492 -:103E0000001001052401000104240202052406001B -:103E100001070582030800FF09040100020A0000EF -:103E20000007050102400000070581024000000074 -:103E300012000000383E000812011001020000408C -:103E4000AE2D021000020102030100000403090468 -:103E500025424F41524425004375626559656C6C9B -:103E60006F772D626473686F74003031323334358C -:103E7000363738394142434445460000008000004F -:103E800000800000008000000080000000000200B0 -:103E90000000040000000400000004000000040012 -:103EA0000000040000000400000004000000000006 -:103EB000851B0008651E0008111F00084000400017 -:103EC0001C3502201C350220010000002C35022088 -:103ED0008000000040010000050000000000802A72 -:103EE00000000000AAAAAAAA00000000FFFF00002C -:103EF0000000000000A00A00000100000000000017 -:103F0000AAAAAAAA00000000FFFF0000000000000B -:103F1000000000001400005400000000AAAAAAAA91 -:103F200014000054FFFF000000000000000000002B -:103F300080699A0100000000AAAA8AAA405555018A -:103F4000FFFF000000707007777000000081020022 -:103F500000000000AAAAAAAA00410100FFFF000079 -:103F600000000080080000000000000000000000C9 -:103F7000AAAAAAAA00000000FFFF0000000000009B -:103F8000000000000000000000000000AAAAAAAA89 -:103F900000000000FFFF0000000000000000000023 -:103FA0000000000000000000AAAAAAAA0000000069 -:103FB000FFFF000000000000000000000000000003 -:103FC00000000000AAAAAAAA00000000FFFF00004B -:103FD00000000000000000000000000000000000E1 -:103FE00000000000000000000000000000000000D1 -:103FF00000000000000000000000000000000000C1 -:1040000000000000000000000000000000000000B0 -:10401000FF00000000000000983C00083F00000086 -:1040200049040000A53C00083F00000051040000C6 -:10403000B33C00083F0000000096000000000800AC -:10404000040000004C3E00080000000000000000DA -:104050000000000000000000000000000000000060 +:100D600010BD0000013810B510F9013F3BB191F9F9 +:100D700000409C4203D11AB10131013AF4E71AB1A3 +:100D800091F90020981A10BD1046FCE70346024670 +:100D9000D01A12F9011B0029FAD170470244034608 +:100DA000934202D003F8011BFAE770472DE9F8439C +:100DB0001F4D14460746884695F8242052BBDFF89D +:100DC00070909CB395F824302BB92022FF2148461F +:100DD0002F62FFF7E3FF95F824004146C0F10802B7 +:100DE00005EB8000A24228BF2246D6B29200FFF750 +:100DF000AFFF95F82430A41B17441E449044E4B27E +:100E0000F6B2082E85F82460DBD1FFF73FFF0028FB +:100E1000D7D108E02B6A03EB82038342CFD0FFF7E0 +:100E200035FF0028CBD10020BDE8F8830120FBE787 +:100E300090230220024B1A78024B1A70704700BFB1 +:100E4000D023022010220220F8B5184C184800F0D8 +:100E50006BFC2146164800F093FC24681548E26EAE +:100E6000154ED2F80438154D43F00203104FC2F866 +:100E7000043801F04BF92046114900F089FDE26E7B +:100E80000424D2F8043823F00203C2F804384FF4E3 +:100E9000E133336055F8040BB84202D0314600F01C +:100EA000A3FB013C14F0FF04F4D1F8BD2C3E000874 +:100EB000D02C022040420F00B8230220143D00082D +:100EC000343E000838B50B4B04461A780A4B53F8E9 +:100ED00022500A4B9D420CD0094B00211822184683 +:100EE000FFF75CFF046001462846BDE8384000F08B +:100EF0007BBB38BDD0230220143D0008D02C02203B +:100F0000B823022000B59BB0EFF309816822684640 +:100F1000FFF71EFFEFF30583044B9A6BDA6A9A6AB8 +:100F20009A6A9A6A9A6A9A6A9B6AFEE700ED00E0FA +:100F300000B59BB0EFF3098168226846FFF708FF10 +:100F4000EFF30583044B9A6B9A6A9A6A9A6A9A6AD3 +:100F50009A6A9B6AFEE700BF00ED00E000B59BB017 +:100F6000EFF3098168226846FFF7F2FEEFF305838D +:100F7000034B5A6B9A6A9A6A9A6A9A6A9B6AFEE764 +:100F800000ED00E0FEE7000030B50A44084D914254 +:100F90000DD011F8013B5840082340F30004013BF9 +:100FA0002C4013F0FF0384EA5000F6D1EFE730BD88 +:100FB0002083B8ED026843681143016003B118470C +:100FC00070470000024A136843F0C0031360704783 +:100FD00000440040024A136843F0C00313607047A6 +:100FE00000480040024A136843F0C0031360704792 +:100FF0000078004037B5274C274D204600F0E8FA2E +:1010000004F11400009400234FF48072234900F08F +:10101000A9F94FF48072224904F138000094214B61 +:1010200000F022FA204BC4E91735204C204600F08E +:10103000CFFA04F11400009400234FF480721C498D +:1010400000F090F94FF480721A4904F138000094CE +:10105000194B00F009FA194BC4E91735184C204612 +:1010600000F0B6FA04F1140000234FF48072154921 +:10107000009400F077F9144B4FF48072134904F197 +:101080003800009400F0F0F9114BC4E9173503B0B3 +:1010900030BD00BFD423022080F937031825022079 +:1010A00018280220C50F00080044004040240220F8 +:1010B0001826022018290220D50F000800480040F9 +:1010C000AC24022018270220E50F0008182A02206D +:1010D00000780040037C30B52E4C002918BF0C4628 +:1010E000012B13D12C4B98420AD12C4B1A6C42F491 +:1010F00000321A641A6E42F400321A661B6E05E062 +:10110000274B98422FD0274B984235D02268036E48 +:10111000C16D03EB52038466B3FBF2F362681504FE +:1011200042BF23F0070503F0070343EA4503CB6002 +:10113000A36843F040034B60E36843F001038B6016 +:1011400042F4967343F001030B604FF0FF330B62E0 +:10115000510505D512F0102217D0B2F1805F16D0DC +:1011600080F8643030BD0D4B1A6C42F480221A6452 +:101170001A6E42F48022C0E7084B1A6C42F080429B +:101180001A641A6E42F08042B7E77F23E8E73F23F4 +:10119000E6E700BF243D0008D423022000380240C7 +:1011A00040240220AC2402202DE9F047C66D0546FC +:1011B0003768F4692107346219D014F0080118BFA8 +:1011C0008021E20748BF41F02001A3074FF0200330 +:1011D00048BF41F04001600748BF41F4807183F38C +:1011E0001188281DFFF7E6FE002383F31188E2052E +:1011F0000AD5202383F311884FF40071281DFFF7CF +:10120000D9FE002383F311884FF020094FF0000A24 +:1012100014F0200838D13B0616D54FF0200905F10F +:10122000380A200610D589F31188504600F050F98D +:10123000002836DA0821281DFFF7BCFE27F08003BE +:101240003360002383F31188790614D5620612D522 +:10125000202383F31188D5E913239A4208D12B6CFC +:1012600033B127F040071021281DFFF7A3FE376098 +:10127000002383F31188E30618D5AA6E1369ABB176 +:101280005069BDE8F047184789F31188736A28460A +:1012900095F86410194000F0B5F98AF31188F469E3 +:1012A000B6E7B06288F31188F469BAE7BDE8F08761 +:1012B000F8B51546826804460B46AA4200D28568F6 +:1012C000A1692669761AB5420BD218462A46FFF75D +:1012D0003FFDA3692B44A3612846A3685B1BA36061 +:1012E000F8BD0CD9AF1B18463246FFF731FD3A4620 +:1012F000E1683044FFF72CFDE3683B44EBE7184618 +:101300002A46FFF725FDE368E5E70000836893427E +:10131000F7B50446154600D28568D4E90460361A4C +:10132000B5420BD22A46FFF713FD63692B44636174 +:101330002846A3685B1BA36003B0F0BD0DD93246FD +:10134000AF1B0191FFF704FD01993A46E068314473 +:10135000FFF7FEFCE3683B44E9E72A46FFF7F8FCA9 +:10136000E368E4E710B50A440024C361029B84608B +:10137000C16002610362C0E90000C0E9051110BD4F +:1013800008B5D0E90532934201D1826882B98268FA +:10139000013282605A1C426119700021D0E9043286 +:1013A0009A4224BFC368436100F0CCFE002008BD10 +:1013B0004FF0FF30FBE7000070B5202304460E46D7 +:1013C00083F31188A568A5B1A368A269013BA36056 +:1013D000531CA36115782269934224BFE368A3617B +:1013E000E3690BB120469847002383F31188284610 +:1013F00007E03146204600F095FE0028E2DA85F34A +:10140000118870BD2DE9F74F04460E4617469846E1 +:10141000D0F81C904FF0200A8AF311884FF0000B8F +:10142000154665B12A4631462046FFF741FF03467F +:1014300060B94146204600F075FE0028F1D0002337 +:1014400083F31188781B03B0BDE8F08FB9F1000F6A +:1014500003D001902046C847019B8BF31188ED1AF9 +:101460001E448AF31188DCE7C160C361009B82607F +:101470000362C0E905111144C0E900000161704731 +:10148000F8B504460D461646202383F31188A76855 +:10149000A7B1A368013BA36063695A1C62611D7018 +:1014A000D4E904329A4224BFE3686361E3690BB173 +:1014B00020469847002080F3118807E031462046F7 +:1014C00000F030FE0028E2DA87F31188F8BD000052 +:1014D000D0E9052310B59A4201D182687AB98268B1 +:1014E0000021013282605A1C82611C7803699A4291 +:1014F00024BFC368836100F025FE204610BD4FF075 +:10150000FF30FBE72DE9F74F04460E461746984695 +:10151000D0F81C904FF0200A8AF311884FF0000B8E +:10152000154665B12A4631462046FFF7EFFE0346D1 +:1015300060B94146204600F0F5FD0028F1D00023B7 +:1015400083F31188781B03B0BDE8F08FB9F1000F69 +:1015500003D001902046C847019B8BF31188ED1AF8 +:101560001E448AF31188DCE7026843681143016076 +:1015700003B11847704700001430FFF743BF000065 +:101580004FF0FF331430FFF73DBF00003830FFF756 +:10159000B9BF00004FF0FF333830FFF7B3BF000092 +:1015A0001430FFF709BF00004FF0FF311430FFF790 +:1015B00003BF00003830FFF763BF00004FF0FF3279 +:1015C0003830FFF75DBF000000207047FFF712BD05 +:1015D000044B036000234360C0E90233012303741A +:1015E000704700BF3C3D000810B52023044683F33C +:1015F0001188FFF76FFD02232374002383F3118802 +:1016000010BD000038B5C36904460D461BB904215E +:101610000844FFF7A9FF294604F11400FFF7B0FEC4 +:10162000002806DA201D4FF48061BDE83840FFF73E +:101630009BBF38BD026843681143016003B118477E +:101640007047000013B5446BD4F8A4381A681178B9 +:10165000042915D1217C022912D11979012312897B +:101660008B4013420CD101A904F14C0001F098FF0A +:10167000D4F8A4480246019B2179206800F0D4F9EF +:1016800002B010BD143001F01BBF00004FF0FF335B +:10169000143001F015BF00004C3001F0EDBF000028 +:1016A0004FF0FF334C3001F0E7BF0000143001F081 +:1016B000E9BE00004FF0FF31143001F0E3BE00003E +:1016C0004C3001F0B9BF00004FF0FF324C3001F058 +:1016D000B3BF000000207047D0F8A4381A6810B5D6 +:1016E00011780446042917D1017C022914D15979B3 +:1016F000012352898B4013420ED1143001F07CFE3D +:10170000024648B1D4F8A4484FF480736179206848 +:10171000BDE8104000F076B910BD0000406BFFF747 +:10172000DBBF0000704700007FB5124B0125042687 +:10173000044603600023057400F1840243602946D7 +:10174000C0E902330C4B0290143001934FF48073C4 +:10175000009601F02DFE094B04F29442294604F153 +:101760004C000294CDE900634FF4807301F0F4FE65 +:1017700004B070BD643D00081D1700084516000840 +:101780000B68202282F311880A7903EB820210622F +:101790004A790D3243F822008A7912B103EB8203B1 +:1017A00018620223C0F8A4180374002383F311887D +:1017B0007047000038B5037F044613B190F85430E9 +:1017C000ABB90125201D0221FFF734FF04F11400FD +:1017D0006FF00101257700F0C1FC04F14C0084F8A2 +:1017E00054506FF00101BDE8384000F0B7BC38BD7F +:1017F00010B5012104460430FFF71CFF00232377B6 +:1018000084F8543010BD000038B50446002514306B +:1018100001F0E6FD04F14C00257701F0B5FE201D36 +:1018200084F854500121FFF705FF2046BDE83840F9 +:10183000FFF752BF90F85C3003F06003202B06D115 +:1018400090F85D200023212A03D81F2A06D8002003 +:101850007047222AFBD1C0E9143303E0034A026532 +:101860000722426583650120704700BF38220220AD +:10187000D0F8A43837B51A680446117804291AD16B +:10188000017C022917D11979012312898B40134257 +:1018900011D100F14C05284601F036FF58B101A9DD +:1018A000284601F07DFED4F8A4480246019B217928 +:1018B000206800F0B9F803B030BD000000EB8103F0 +:1018C000F0B51E6A85B004460D46FEB1202383F3B1 +:1018D000118804EB8507301D0821FFF7ABFEFB687C +:1018E00006F14C005B691B681BB1019001F066FEBC +:1018F000019803A901F054FE024648B1039B294612 +:10190000204600F091F8002383F3118805B0F0BD64 +:10191000FB685A691268002AF5D01B8A013B134004 +:10192000F1D104F15C02EAE70D3138B550F82140FD +:10193000DCB1202383F31188D4F8A42813685279EA +:1019400003EB8203DB689B695D6845B10421601885 +:10195000FFF770FE294604F1140001F057FD204600 +:10196000FFF7BAFE002383F3118838BD70470000EB +:1019700001F0F0B801232822002110B5044600F838 +:10198000243BFFF70BFA0023C4E9013310BD00002C +:1019900038B50446202383F3118800254160C0E94F +:1019A0000355C0E90555C0E9075501F0E3F80223E6 +:1019B000237085F3118838BD70B500EB81030546AF +:1019C00050690E461446DA6018B110220021FFF764 +:1019D000E5F9A06918B110220021FFF7DFF93146BF +:1019E0002846BDE8704001F08FB90000826802F01F +:1019F000011282600022C0E90422C0E906220262CC +:101A000001F00EBAF0B4012500EB810447898D4046 +:101A1000E4683D43A469458123600023A2606360BC +:101A2000F0BC01F029BA0000F0B4012500EB8104FC +:101A300007898D40E4683D43646905812360002384 +:101A4000A2606360F0BC01F0A3BA000070B502238D +:101A50000025044603704566056280F84C50C0E9D5 +:101A60000255C0E90455C0E9065501F0E9F863687C +:101A70001B6823B129462046BDE87040184770BD59 +:101A8000037880F868300523037043681B6810B53D +:101A900004460BB1042198470023A36010BD000049 +:101AA00090F86820436802701B680BB10521184745 +:101AB0007047000070B590F84C30044613B1002315 +:101AC00080F84C3004F15C02204601F0CBF96368E9 +:101AD0009B68B3B994F85C3013F0600535D00021F1 +:101AE000204601F031FC0021204601F023FC636810 +:101AF0001B6813B1062120469847062384F84C3012 +:101B000070BD204698470028E4D0B4F86230626D7A +:101B10009A4288BF636594F95C30656D002B4FF085 +:101B2000200380F20381002D00F0F280092284F866 +:101B30004C2083F3118800212046D4E91423FFF7B9 +:101B400073FF002383F31188DAE794F85D2003F034 +:101B50007F0343EA022340F20232934200F0C58041 +:101B600021D8B3F5807F48D00DD8012B3FD0022B70 +:101B700000F09380002BB2D104F1640222650222AE +:101B80006265A365C1E7B3F5817F00F09B80B3F583 +:101B9000407FA4D194F85E30012BA0D1B4F864301A +:101BA00043F0020332E0B3F5006F4DD017D8B3F520 +:101BB000A06F31D0A3F5C063012B90D86368204695 +:101BC00094F85E205E6894F85F10B4F86030B04717 +:101BD000002884D043682365036863651AE0B3F581 +:101BE000106F36D040F6024293427FF478AF5C4BE0 +:101BF0002365022363650023C3E794F85E30012B5D +:101C00007FF46DAFB4F8643023F00203A4F86430BD +:101C1000C4E91455A56578E7B4F85C30B3F5A06F56 +:101C20000ED194F85E30204684F8663001F060F8FA +:101C300063681B6813B10121204698470323237072 +:101C40000023C4E914339CE704F1670323650123EF +:101C5000C3E72378042B10D1202383F31188204677 +:101C6000FFF7C4FE85F311880321636884F8675089 +:101C700021701B680BB12046984794F85E30002B0A +:101C8000DED084F867300423237063681B68002B60 +:101C9000D6D0022120469847D2E794F860302046FB +:101CA0001D0603F00F010AD501F0CEF8012804D07B +:101CB00002287FF414AF2B4B9AE72B4B98E701F0E7 +:101CC000B5F8F3E794F85E30002B7FF408AF94F892 +:101CD000603013F00F01B3D01A06204602D501F090 +:101CE00047FBADE701F03AFBAAE794F85E30002B22 +:101CF0007FF4F5AE94F8603013F00F01A0D01B060E +:101D0000204602D501F020FB9AE701F013FB97E78C +:101D1000142284F84C2083F311882B462A46294646 +:101D20002046FFF76FFE85F31188E9E65DB11522C5 +:101D300084F84C2083F3118800212046D4E9142331 +:101D4000FFF760FEFDE60B2284F84C2083F3118838 +:101D50002B462A4629462046FFF766FEE3E700BFEA +:101D6000943D00088C3D0008903D000838B590F87F +:101D70004C300446002B3ED0063BDAB20F2A34D852 +:101D80000F2B32D8DFE803F03731310822323131FE +:101D90003131313131313737456DB0F862309D42E4 +:101DA00014D2C3681B8AB5FBF3F203FB12556DB95D +:101DB000202383F311882B462A462946FFF734FE59 +:101DC00085F311880A2384F84C300EE0142384F83C +:101DD0004C30202383F31188002320461A461946ED +:101DE000FFF710FE002383F3118838BD836D03B124 +:101DF00098470023E7E70021204601F0A5FA0021DB +:101E0000204601F097FA63681B6813B1062120464B +:101E100098470623D7E7000010B590F84C300446E9 +:101E2000142B29D017D8062B05D001D81BB110BD13 +:101E3000093B022BFBD80021204601F085FA002146 +:101E4000204601F077FA63681B6813B1062120462B +:101E50009847062319E0152BE9D10B2380F84C3065 +:101E6000202383F3118800231A461946FFF7DCFD6F +:101E7000002383F31188DAE7C3689B695B68002B52 +:101E8000D5D1836D03B19847002384F84C30CEE759 +:101E9000024B0022C3E900339A607047182B0220DE +:101EA000002382680374054B1B6899689142FBD23A +:101EB0005A6803604260106058607047182B022017 +:101EC00008B5202383F31188037C032B05D0042B52 +:101ED0000DD02BB983F3118808BD436900221A6025 +:101EE0004FF0FF334361FFF7DBFF0023F2E7D0E958 +:101EF000003213605A60F3E7002382680374054BD5 +:101F00001B6899689142FBD85A6803604260106070 +:101F100058607047182B0220054B1969087418681F +:101F2000026853601A60186101230374FEF7FEB95A +:101F3000182B02204B1C30B5044687B00A4D10D038 +:101F40002B6901A8094A00F025F92046FFF7E4FFB4 +:101F5000049B13B101A800F059F92B69586907B027 +:101F600030BDFFF7D9FFF8E7182B0220C11E00088B +:101F700038B50C4D044641612B6981689A689142DD +:101F800003D8BDE83840FFF78BBF1846FFF7B4FF12 +:101F900001232C61014623742046BDE83840FEF73A +:101FA000C5B900BF182B0220044B1A681B69906842 +:101FB0009B68984294BF002001207047182B022094 +:101FC00010B5084C236820691A6854602260012209 +:101FD00023611A74FFF790FF01462069BDE81040A5 +:101FE000FEF7A4B9182B022008B5FFF7DDFF18B1E2 +:101FF000BDE80840FFF7E4BF08BD0000FFF7E0BF01 +:10200000FEE7000010B50C4CFFF742FF00F0B4F8FB +:1020100080220A49204600F03BF8012344F8180CBE +:10202000037400F073FC002383F3118862B6044844 +:10203000BDE8104000F04CB8402B0220983D00084D +:10204000A83D000800F01CB9EFF3118020B9EFF3B0 +:102050000583202282F311887047000010B530B943 +:10206000EFF30584C4F3080414B180F3118810BDA4 +:10207000FFF7BAFF84F31188F9E70000034A5168BB +:1020800053685B1A9842FBD8704700BF001000E00D +:1020900082600222028270478368A3F17C0243F8C7 +:1020A0000C2C026943F83C2C426943F8382C074A4F +:1020B00043F81C2CC268A3F1180043F8102C02222C +:1020C00003F8082C002203F8072C7047450300088A +:1020D00010B5202383F31188FFF7DEFF00210446AB +:1020E000FFF746FF002383F31188204610BD000050 +:1020F000024B1B6958610F20FFF70EBF182B0220FF +:10210000202383F31188FFF7F3BF000008B50146D1 +:10211000202383F311880820FFF70CFF002383F3AB +:10212000118808BD49B1064B42681B6918605A60A6 +:10213000136043600420FFF7FDBE4FF0FF3070478F +:10214000182B02200368984206D01A68026050607B +:1021500018465961FFF7A4BE7047000038B5044621 +:102160000D462068844200D138BD036823605C605E +:102170004561FFF795FEF4E7054B4FF0FF3103F1A2 +:102180001402C3E905220022C3E90712704700BF09 +:10219000182B022070B51C4E05460C46C0E90323DF +:1021A00001F0E4FA334653F8142F9A420DD130620D +:1021B0000A2C2CBF00190A302A60C5E90124C6E99F +:1021C0000555BDE8704001F0BFBA316A431AE31803 +:1021D00038BF1C469368A34202D9081901F0C2FA1D +:1021E00073699A6894420CD85A68AC602B606A6034 +:1021F00015609A685D60121B9A604FF0FF33F361BF +:1022000070BDA41A1B68ECE7182B022038B51B4CD4 +:10221000636998420DD08168D0E9003213605A603A +:102220000022C2609A680A449A604FF0FF33E3616B +:1022300038BD03682246002142F8143F93425A6099 +:10224000C16003D1BDE8384001F086BA9A68816860 +:10225000256A0A449A6001F089FA6369411B9A6809 +:102260008A42E5D9AB181D1A206A092D98BF01F1E1 +:102270000A02BDE83840104401F074BA182B02205D +:102280002DE9F041184C002704F11406656901F0AE +:102290006DFA236AAA68C11A8A4215D81344D5F880 +:1022A0000C802362D5E9003213605A606369EF60E5 +:1022B000B34201D101F050FA87F311882869C04771 +:1022C000202383F31188E1E76169B14209D0134407 +:1022D0001B1ABDE8F0410A2B2CBFC0180A3001F0D0 +:1022E00041BABDE8F08100BF182B022000207047E2 +:1022F000FEE70000704700004FF0FF30704700001D +:1023000002290CD0032904D00129074818BF002056 +:102310007047032A05D8054800EBC20070470448FF +:1023200070470020704700BF903E000848220220FE +:10233000443E000870B59AB005460846144601A907 +:1023400000F0C2F801A8FEF721FD431C0022C6B22E +:102350005B001046C5E9003423700323023404F8FF +:10236000013C01ABD1B202348E4201D81AB070BD2B +:1023700013F8011B013204F8010C04F8021CF1E708 +:1023800008B5202383F311880348FFF771FA00236F +:1023900083F3118808BD00BFD02C022090F85C3078 +:1023A00003F01F02012A07D190F85D200B2A03D108 +:1023B0000023C0E9143315E003F06003202B08D19B +:1023C000B0F860302BB990F85D20212A03D81F2A7D +:1023D00004D8FFF72FBA222AEBD0FAE7034A0265A6 +:1023E0000722426583650120704700BF3F2202201B +:1023F00007B5052917D8DFE801F0191603191920C8 +:10240000202383F31188104A01210190FFF7D4FAA9 +:10241000019802210D4AFFF7CFFA0D48FFF7F4F9B2 +:10242000002383F3118803B05DF804FB202383F3BA +:1024300011880748FFF7BEF9F2E7202383F31188DC +:102440000348FFF7D5F9EBE7E43D0008083E000834 +:10245000D02C022038B50C4D0C4C2A460C4904F106 +:102460000800FFF767FF05F1CA0204F110000949EF +:10247000FFF760FF05F5CA7204F118000649BDE8D0 +:102480003840FFF757BF00BFA8350220482202207E +:10249000C03D0008CD3D0008D83D000870B5044699 +:1024A00008460D46FEF772FCC6B22046013403789A +:1024B0000BB9184670BD32462946FEF753FC00287A +:1024C000F3D10120F6E700002DE9F04705460C4660 +:1024D000FEF75CFC2B49C6B22846FFF7DFFF08B1C8 +:1024E0000A36F6B228492846FFF7D8FF08B1103659 +:1024F000F6B2632E0BD8DFF88C80DFF88C90234F78 +:10250000DFF894A02E7846B92670BDE8F0872946FA +:102510002046BDE8F04701F0DFBB252E2ED1072273 +:1025200041462846FEF71EFC70B9194B224603F1BE +:10253000100153F8040B8B4242F8040BF9D11B78BD +:10254000073511341370DDE7082249462846FEF7A7 +:1025500009FC98B9A21C0F4B197802320909C95D10 +:1025600002F8041C13F8011B01F00F015345C95D6B +:1025700002F8031CF0D118340835C3E7013504F81C +:10258000016BBFE7B03E0008D83D0008CA3E000816 +:10259000B83E000820F4F01F2CF4F01FBFF34F8F5B +:1025A000024AD368DB03FCD4704700BF003C024002 +:1025B00008B5074B1B7853B9FFF7F0FF054B1A69B5 +:1025C000002A04DA044A5A6002F188325A6008BDCF +:1025D00006380220003C02402301674508B5054B40 +:1025E0001B7833B9FFF7DAFF034A136943F000435E +:1025F000136108BD06380220003C02400B28F0B5EC +:1026000016D80C4C0C4923787BB90E460B4D0C2385 +:102610004FF00062013B55F8047B46F8042B13F0A1 +:10262000FF033A44F6D10123237051F82000F0BD96 +:102630000020FCE73838022008380220DC3E000881 +:10264000014B53F820007047DC3E00080C20704717 +:102650000B2810B5044601D9002010BDFFF7CEFFAE +:10266000064B53F824301844C21A0BB90120F4E782 +:1026700012680132F0D1043BF6E700BFDC3E0008EF +:102680000B2838B5044628D8FFF7DEFC0546FFF7CF +:1026900085FF2046FFF78CFF114AF323D360E30048 +:1026A000DBB243F4007343F002031361136943F494 +:1026B00080331361FFF772FFFFF7A0FF094B53F858 +:1026C000241000F0E9F82846FFF788FFFFF7C6FC62 +:1026D0002046BDE83840FFF7BBBF002038BD00BF33 +:1026E000003C0240DC3E000812F001032DE9F041FD +:1026F00005460E4614464BD18218B2F1026F61D8DE +:10270000314B1B6813F001035CD0FFF79DFC2F4F8A +:10271000FFF74EFFF323314640F20128FB60FFF73D +:102720003DFF032C18D824F001046D1A274E40F207 +:1027300001180C44A14205EB010733692AD123F0AB +:1027400001033361FFF74AFFFFF788FC0120BDE872 +:10275000F081043C0435E4E7AB07E4D13B6923F4A2 +:1027600040733B613B6943EA08033B6151F8046BEA +:102770002E60BFF34F8FFFF711FF2B689E42E8D00A +:102780003B6923F001033B61FFF728FFFFF766FC7D +:102790000020DCE723F440733361336943EA080324 +:1027A00033610B883B80BFF34F8FFFF7F7FE3F8805 +:1027B000BFB231F8023BBB42BCD0336923F0010306 +:1027C0003361E1E71846C2E700380240003C0240AE +:1027D000084908B50B7828B11BB9FFF7E9FE0123BA +:1027E0000B7008BD002BFCD00870BDE80840FFF757 +:1027F000F5BE00BF063802200244074BD2B210B526 +:10280000904200D110BD441C00B253F8200041F8A2 +:10281000040BE0B2F4E700BF502800400F4B30B586 +:102820001C6F240407D41C6F44F400741C671C6FD5 +:1028300044F400441C670A4C02442368D2B243F4B7 +:1028400080732360074B904200D130BD441C51F887 +:10285000045B00B243F82050E0B2F4E700380240D5 +:10286000007000405028004007B5012201A9002057 +:10287000FFF7C2FF019803B05DF804FB13B50446EF +:10288000FFF7F2FFA04205D0012201A90020019428 +:10289000FFF7C4FF02B010BD0144BFF34F8F064BDA +:1028A000884204D3BFF34F8FBFF36F8F7047C3F8D5 +:1028B0005C022030F4E700BF00ED00E0002070472C +:1028C000034B1A681AB9034AD2F874281A60704781 +:1028D0003C3802200030024008B5FFF7F1FF024B00 +:1028E0001868C0F3407008BD3C380220EFF309833C +:1028F000054968334A6B22F001024A6383F3098871 +:10290000002383F31188704700EF00E0202080F35C +:10291000118862B60D4B0E4AD96821F4E0610904B2 +:10292000090C0A430B49DA60D3F8FC2042F08072AC +:10293000C3F8FC20084AC2F8B01F116841F0010139 +:1029400011601022DA7783F82200704700ED00E072 +:102950000003FA0555CEACC5001000E0202310B5E9 +:1029600083F311880E4B5B6813F4006314D0F1EE0F +:10297000103AEFF309844FF08073683CE361094B30 +:10298000DB6B236684F30988FFF70EFB10B1064B5F +:10299000A36110BD054BFBE783F31188F9E700BF86 +:1029A00000ED00E000EF00E0570300085A030008C4 +:1029B00070B5BFF34F8FBFF36F8F1A4A0021C2F873 +:1029C0005012BFF34F8FBFF36F8F536943F400333F +:1029D0005361BFF34F8FBFF36F8FC2F88410BFF303 +:1029E0004F8FD2F8803043F6E074C3F3C900C3F3CD +:1029F0004E335B0103EA0406014646EA817501395C +:102A0000C2F86052F9D2203B13F1200FF2D1BFF38C +:102A10004F8F536943F480335361BFF34F8FBFF33C +:102A20006F8F70BD00ED00E0FEE700000A4B0B4821 +:102A30000B4A90420BD30B4BC11EDA1C121A22F028 +:102A400003028B4238BF00220021FEF7A7B953F8DA +:102A5000041B40F8041BECE7D84000085039022062 +:102A600050390220503902207047000070B5D0E97B +:102A70001B4300224FF0FF359E6804EB42135101C7 +:102A8000D3F80009002805DAD3F8000940F08040A7 +:102A9000C3F80009D3F8000B002805DAD3F8000BBF +:102AA00040F08040C3F8000B013263189642C3F82F +:102AB0000859C3F8085BE0D24FF00113C4F81C3882 +:102AC00070BD00001D4B03EB8002D2F80CC02DE955 +:102AD000F043DCF81420461CDD6ED2F800E005EB74 +:102AE000063605EB4018516871450AD30122D5F826 +:102AF000343802FA00F023EA0000C5F83408BDE8D3 +:102B0000F083AEEB0103BCF81040A34228BF23467C +:102B1000D8F81849A4B2B3EB840FF0D89468A4F1A4 +:102B2000040959F8047F3760A4EB09071F44042FF8 +:102B3000F7D81C440B4494605360D4E7403802201B +:102B4000890141F02001016103699B06FCD4122038 +:102B5000FFF794BA10B5054C2046FEF70BFF4FF077 +:102B6000A043E366024B236710BD00BF403802203C +:102B7000303F000870B503780546012B50D12A4B31 +:102B8000C46E98421BD1294B0E2143205A6B42F050 +:102B900080025A635A6D42F080025A655A6D5A6932 +:102BA00042F080025A615A6922F080025A615B69E0 +:102BB00000F0E8FB1E4BE3601E4BC4F80038002316 +:102BC000EE6EC4F8003EC02323604FF40413A363E9 +:102BD0003369002BFCDA01230C203361FFF74EFA36 +:102BE0003369DB07FCD41220FFF748FA3369002B66 +:102BF000FCDA00262846A660FFF738FF6B68C4F8A9 +:102C00001068DB68C4F81468C4F81C684BB90A4B38 +:102C1000A3614FF0FF336361A36843F00103A36036 +:102C200070BD064BF4E700BF403802200038024078 +:102C30004014004003002002003C30C0083C30C07B +:102C4000F8B5C46E054600214FF000662046FFF738 +:102C500077FF296F00234FF001128F684FF0FF308C +:102C6000C4F83438C4F81C2804EB431201339F42E3 +:102C7000C2F80069C2F8006BC2F80809C2F8080B74 +:102C8000F2D20B68EA6E6B676362102313611669F8 +:102C900016F01006FBD11220FFF7F0F9D4F8003837 +:102CA00023F4FE63C4F80038A36943F4402343F0DF +:102CB0001003A3610923C4F81038C4F814380A4B70 +:102CC000EB604FF0C043C4F8103B084BC4F8003B26 +:102CD000C4F81069C4F800396B6F03F1100243F4B3 +:102CE00080136A67A362F8BD0C3F000840800010A3 +:102CF000C26E90F86610D2F8003823F4FE6343EAFF +:102D00000113C2F8003870472DE9F84300EB810346 +:102D1000C56E0C468046DA680FFA81F948011668DC +:102D200006F00306731E022B05EB41134FF0000162 +:102D300094BFB604384EC3F8101B4FF0010104F1E4 +:102D4000100398BF06F1805601FA03F3916998BF0A +:102D500006F5004600293AD0578A04F15801374356 +:102D600049016F50D5F81C180B430021C5F81C38D9 +:102D70002B180127C3F81019A7405369611E9BB394 +:102D8000138A928B9B08012A88BF5343D8F874207A +:102D9000981842EA034301F140022146C8F8740042 +:102DA000284605EB82025360FFF7CAFE08EB890054 +:102DB000C3681B8A43EA845348341E4364012E517E +:102DC000D5F81C381F43C5F81C78BDE8F88305EB1F +:102DD0004917D7F8001B21F40041C7F8001BD5F8AC +:102DE0001C1821EA0303C0E704F13F030B4A2846FD +:102DF000214605EB83035A60FFF7A2FE05EB49105D +:102E0000D0F8003923F40043C0F80039D5F81C3855 +:102E100023EA0707D7E700BF008000100004000284 +:102E2000026F12684267FFF721BE00005831C36E7F +:102E300049015B5813F4004004D013F4001F0CBF89 +:102E400002200120704700004831C36E49015B58E1 +:102E500013F4004004D013F4001F0CBF0220012023 +:102E60007047000000EB8101CB68196A0B681360A2 +:102E70004B6853607047000000EB810330B5DD689C +:102E8000AA691368D36019B9402B84BF402313602B +:102E90006B8A1468C26E1C4402EB4110013C09B2FB +:102EA000B4FBF3F46343033323F0030343EAC44363 +:102EB00043F0C043C0F8103B2B6803F00303012B21 +:102EC0000ED1D2F8083802EB411013F4807FD0F80D +:102ED000003B14BF43F0805343F00053C0F8003B65 +:102EE00002EB4112D2F8003B43F00443C2F8003B2E +:102EF00030BD00002DE9F041244D0446EE6E06EB96 +:102F00004013D3F8087B3807C3F8087B0AD5D6F8F6 +:102F10001438190706D505EB840321462846DB68DB +:102F20005B689847FA071FD5D6F81438DB071BD51E +:102F300005EB8403D968CCB98B69488A5A68B2FB1F +:102F4000F0F600FB16228AB91868DA6890420DD2B2 +:102F5000121AC3E90024202383F311880B48214669 +:102F6000FFF78AFF84F31188BDE8F081012303FA9B +:102F700004F26B8923EA02036B81CB68002BF3D048 +:102F800021460248BDE8F041184700BF4038022002 +:102F900000EB81034A0170B5DD68C36E6C69266879 +:102FA000E66056BB1A444FF40020C2F810092A68A4 +:102FB00002F00302012A0AB20ED1D3F8080803EB8B +:102FC000421410F4807FD4F8000914BF40F0805000 +:102FD00040F00050C4F8000903EB4212D2F8000997 +:102FE00040F00440C2F800090122D3F8340802FA84 +:102FF00001F10143C3F8341870BD19B9402E84BFE4 +:103000004020206020681A442E8A8419013CB4FBB9 +:10301000F6F440EAC44040F00050C6E7F8B5044674 +:103020001E48C56E05EB4413D3F80869F107C3F8D1 +:10303000086917D5D5F81038DA0713D500EB8403E3 +:10304000D9684B691F68DA68974218D2D21B0027EB +:103050001A605F60202383F311882146FFF798FFF1 +:1030600087F31188330617D50123D5F83428A340F8 +:10307000134211D02046BDE8F840FFF723BD0123DD +:1030800003FA04F2038923EA020303818B68002B0D +:10309000E8D021469847E5E7F8BD00BF4038022058 +:1030A0002DE9F74FA24CE66E7569B3691D4015F422 +:1030B0008058756107D02046FEF7C8FC03B0BDE814 +:1030C000F04FFFF74BBC002D12DAD6F8003E9F07F9 +:1030D00005D0D6F8003E23F00303C6F8003ED6F82C +:1030E0000438934823F00103C6F80438FEF7D8FCEF +:1030F000280505D58E48FFF7B9FC8D48FEF7C0FCC2 +:10310000A9040CD5D6F8083813F0060FF36823F499 +:1031100070530CBF43F4105343F4A053F3602A07D9 +:1031200004D56368DB680BB181489847EB0200F176 +:103130008A80AF0227D5D4F86C9000274FF0010A9F +:10314000DFF8ECB109EB4712D2F8003B03F440235F +:10315000B3F5802F11D1D2F8003B002B0DDA628934 +:103160000AFA07F322EA0303638104EB8703DB68AF +:10317000DB6813B13946584698470137236FFFB2D1 +:103180009B689F42DED9E80618D5E76E3A6AC2F31B +:103190000A1002F00F0302F4F012B2F5802F00F0D3 +:1031A0009C80B2F5402F09D104EB8303002207F580 +:1031B0008057DB681B6A904240F082802B03D6F870 +:1031C00018481DD5E70302D50020FFF793FEA6039C +:1031D00002D50120FFF78EFE600302D50220FFF723 +:1031E00089FE210302D50320FFF784FEE20202D507 +:1031F0000420FFF77FFEA30202D50520FFF77AFE29 +:103200006F037FF55BAFE60702D50020FFF706FFEF +:10321000A50702D50120FFF701FF600702D50220B4 +:10322000FFF7FCFE210702D50320FFF7F7FEE206B9 +:1032300002D50420FFF7F2FEA3067FF53FAF05207D +:10324000FFF7ECFE3AE7E36E00274FF0010ADFF8E4 +:10325000E0B00193236F5FFA87F99B6899453FF6C9 +:1032600068AF019B03EB4913D3F8002902F4402215 +:10327000B2F5802F22D1D3F80029002A1EDAD3F824 +:10328000002942F09042C3F80029D3F80029002A0F +:10329000FBDB4946E06EFFF753FC22890AFA09F38B +:1032A00022EA0303238104EB8903DB689B6813B1E3 +:1032B0004946584698474846FFF704FC0137C9E796 +:1032C000910701D1D7F80080072A02F101029CBFC3 +:1032D00003F8018B4FEA18286DE7023307F5805792 +:1032E00004EB83025268D2F818C0DCF80820DCE94D +:1032F000001CA1EB0C0C002188420AD104EB8304D2 +:1033000063689B699A6802449A605A6802445A60EA +:1033100054E711F0030F01D1D7F800808C4501F17B +:10332000010184BF02F8018B4FEA1828E4E700BFCF +:1033300040380220C36E03EB4111D1F8003B43F447 +:103340000013C1F8003B7047C36E03EB4111D1F885 +:10335000003943F40013C1F800397047C36E03EB22 +:103360004111D1F8003B23F40013C1F8003B704732 +:10337000C36E03EB4111D1F8003923F40013C1F8F7 +:1033800000397047090100F16043012203F56143F0 +:10339000C9B283F8001300F01F039A4043099B0051 +:1033A00003F1604303F56143C3F880211A6070475D +:1033B00030B50433039C0172002104FB0325C16076 +:1033C000C0E90653049B0363059BC0E90000C0E904 +:1033D0000422C0E90842C0E90A11436330BD00007D +:1033E0000022416AC260C0E90411C0E90A226FF0FC +:1033F0000101FEF7B3BE0000D0E90432934201D1CF +:10340000C2680AB9181D7047002070470369196027 +:103410000021C2680132C260C269134482699342CA +:10342000036124BF436A0361FEF78CBE38B50446CE +:103430000D46E3683BB162690020131D1268A36268 +:103440001344E36207E0237A33B929462046FEF7A6 +:1034500069FE0028EDDA38BD6FF00100FBE70000DF +:10346000C368C269013BC3604369134482699342E4 +:10347000436124BF436A436100238362036B03B14A +:103480001847704770B52023044683F31188866A75 +:103490003EB9FFF7CBFF054618B186F311882846E1 +:1034A00070BDA36AE26A13F8015B9342A36202D380 +:1034B0002046FFF7D5FF002383F31188EFE70000D4 +:1034C0002DE9F84F04460E46174698464FF020095E +:1034D00089F311880025AA46D4F828B0BBF1000F63 +:1034E00009D141462046FFF7A1FF20B18BF3118897 +:1034F0002846BDE8F88FD4E90A12A7EB050B521A4B +:10350000934528BF9346BBF1400F1BD9334601F1C9 +:10351000400251F8040B914243F8040BF9D1A36A1D +:10352000403640354033A362D4E90A239A4202D39D +:103530002046FFF795FF8AF31188BD42D8D289F360 +:103540001188C9E730465A46FDF702FCA36A5E447B +:103550005D445B44A362E7E710B5029C043301724B +:1035600004FB0321C460C0E906130023C0E90A3349 +:10357000039B0363049BC0E90000C0E90422C0E987 +:103580000842436310BD0000026A6FF00101C2608F +:10359000426AC0E904220022C0E90A22FEF7DEBD29 +:1035A000D0E904239A4201D1C26822B9184650F8E2 +:1035B000043B0B607047002070470000C368002187 +:1035C000C2690133C3604369134482699342436112 +:1035D00024BF436A4361FEF7B5BD000038B5044619 +:1035E0000D46E3683BB1236900201A1DA262E2691F +:1035F0001344E36207E0237A33B929462046FEF7F5 +:1036000091FD0028EDDA38BD6FF00100FBE7000006 +:1036100003691960C268013AC260C26913448269D1 +:103620009342036124BF436A036100238362036BF7 +:1036300003B118477047000070B520230D460446BB +:10364000114683F31188866A2EB9FFF7C7FF10B1C0 +:1036500086F3118870BDA36A1D70A36AE26A013304 +:103660009342A36204D3E16920460439FFF7D0FFF7 +:10367000002080F31188EDE72DE9F84F04460D4650 +:10368000904699464FF0200A8AF311880026B346E7 +:10369000A76A4FB949462046FFF7A0FF20B187F33C +:1036A00011883046BDE8F88FD4E90A073A1AA8EB2A +:1036B0000607974228BF1746402F1BD905F1400344 +:1036C00055F8042B9D4240F8042BF9D1A36A4036EB +:1036D0004033A362D4E90A239A4204D3E169204625 +:1036E0000439FFF795FF8BF311884645D9D28AF349 +:1036F0001188CDE729463A46FDF72AFBA36A3D44E7 +:103700003E443B44A362E5E7D0E904239A4217D143 +:10371000C3689BB1836A8BB1043B9B1A0ED01360C4 +:10372000C368013BC360C3691A4483699A4202615A +:1037300024BF436A03610023836201231846704754 +:103740000023FBE700F094B84FF080430022586359 +:103750001A610222DA6070474FF080430022DA607B +:10376000704700004FF08043586370474FF080432C +:10377000586A70474B6843608B688360CB68C3604E +:103780000B6943614B6903628B6943620B68036099 +:103790007047000008B52C4B40F2FF712B481A69A6 +:1037A0000A431A611A6922F4FF6222F007021A61C1 +:1037B0001A691A6B0A431A631A6D0A431A65244A76 +:1037C0001B6D1146FFF7D6FF00F5806002F11C016A +:1037D000FFF7D0FF00F5806002F13801FFF7CAFF64 +:1037E00000F5806002F15401FFF7C4FF00F580602E +:1037F00002F17001FFF7BEFF00F5806002F18C015D +:10380000FFF7B8FF00F5806002F1A801FFF7B2FFF3 +:1038100000F5806002F1C401FFF7ACFF00F58060A5 +:1038200002F1E001FFF7A6FF00F5806002F1FC0164 +:10383000FFF7A0FF02F58C7100F58060FFF79AFF9B +:10384000BDE8084000F08AB800380240000002409D +:103850003C3F000808B500F01FFAFEF7D3FBFFF766 +:103860002FF8BDE80840FEF7F5BD000070470000E6 +:103870000F4B1A6C42F001021A641A6E42F00102F8 +:103880001A660C4A1B6E936843F0010393604FF075 +:1038900080436B229A624FF0FF32DA6200229A6113 +:1038A0005A63DA605A6001225A611A60704700BF99 +:1038B00000380240002004E04FF0804208B5116952 +:1038C000D3680B40D9B29B076FEA0101116107D59C +:1038D000202383F31188FEF7B5FB002383F31188BF +:1038E00008BD00001B4B4FF0FF3000211A696FEA42 +:1038F00042526FEA52521A611A69C2F30A021A61FD +:103900001A695A6958615A6959615A691A6A62F0A2 +:1039100080521A621A6A02F080521A621A6A5A6A4D +:1039200058625A6A59625A6A0B4A106840F48070A9 +:103930001060186F00F44070B0F5007F03D04FF4B2 +:10394000803018671967536823F40073536000F0E0 +:1039500073B900BF0038024000700040364B4FF48E +:103960004041364A1A64364A11601A6842F0010230 +:103970001A601A689207FCD59A6822F003029A60CE +:103980002D4B9A6812F00C02FBD1196801F0F90175 +:1039900019609A601A6842F480321A601A689003BB +:1039A000FCD55A6F42F001025A67234B5A6F9107B8 +:1039B000FCD5244A5A601A6842F080721A60204B83 +:1039C0005A685204FCD51A6842F480321A605A6868 +:1039D000D003FCD51A6842F400321A60184A5368C2 +:1039E0009903FCD5144B1A689201FCD5164A9A60CB +:1039F00040F20112C3F88C200022C3F8902040F25C +:103A00000733124A1360136803F00F03072BFAD130 +:103A1000094B9A6842F002029A609A6802F00C021E +:103A2000082AFAD15A6C42F480425A645A6E42F41F +:103A300080425A665B6E70470038024000040010F6 +:103A400000700040186C400900948838003C024027 +:103A5000074A08B5536903F00103536123B1054ACE +:103A600013680BB150689847BDE80840FEF776BF71 +:103A7000003C0140D0380220074A08B5536903F0E2 +:103A80000203536123B1054A93680BB1D06898478C +:103A9000BDE80840FEF762BF003C0140D03802207C +:103AA000074A08B5536903F00403536123B1054A7B +:103AB00013690BB150699847BDE80840FEF74EBF47 +:103AC000003C0140D0380220074A08B5536903F092 +:103AD0000803536123B1054A93690BB1D069984734 +:103AE000BDE80840FEF73ABF003C0140D038022054 +:103AF000074A08B5536903F01003536123B1054A1F +:103B0000136A0BB1506A9847BDE80840FEF726BF1C +:103B1000003C0140D0380220164B10B55C6904F41B +:103B200078725A61A30604D5134A936A0BB1D06A1E +:103B30009847600604D5104A136B0BB1506B984739 +:103B4000210604D50C4A936B0BB1D06B9847E20564 +:103B500004D5094A136C0BB1506C9847A30504D5E2 +:103B6000054A936C0BB1D06C9847BDE81040FEF746 +:103B7000F5BE00BF003C0140D0380220194B10B503 +:103B80005C6904F47C425A61620504D5164A136DDF +:103B90000BB1506D9847230504D5134A936D0BB1B3 +:103BA000D06D9847E00404D50F4A136E0BB1506EE8 +:103BB0009847A10404D50C4A936E0BB1D06E984778 +:103BC000620404D5084A136F0BB1506F9847230461 +:103BD00004D5054A936F0BB1D06F9847BDE81040EC +:103BE000FEF7BCBE003C0140D038022008B50348B7 +:103BF000FDF7DAFABDE80840FEF7B0BED423022094 +:103C000008B50348FDF7D0FABDE80840FEF7A6BEA8 +:103C10004024022008B50348FDF7C6FABDE8084075 +:103C2000FEF79CBEAC24022008B5FFF745FEBDE8B8 +:103C30000840FEF793BE0000062108B50846FFF7CE +:103C4000A1FB06210720FFF79DFB06210820FFF7B7 +:103C500099FB06210920FFF795FB06210A20FFF7B3 +:103C600091FB06211720FFF78DFB06212820FFF787 +:103C700089FB07211C20FFF785FB0C212620FFF77D +:103C800081FB0C212720FFF77DFB0C215220BDE892 +:103C90000840FFF777BB000008B5FFF723FE00F0F0 +:103CA0000DF8FDF793FCFDF763FEFDF73BFDFFF715 +:103CB000DDFDBDE80840FFF745BD00000023054AD3 +:103CC00019460133102BC2E9001102F10802F8D1A4 +:103CD000704700BFD0380220034611F8012B03F8CB +:103CE000012B002AF9D1704753544D3332463F3FE0 +:103CF0003F3F3F3F0053544D333246375B347C35B2 +:103D00005D780053544D333246375B367C375D78EF +:103D100000000000D02C0220D423022040240220E6 +:103D2000AC2402200096000000000000000000000B +:103D30000000000000000000000000000000000083 +:103D40009515000881150008BD150008A915000883 +:103D5000B5150008A11500088D1500087915000893 +:103D6000C915000800000000A11600088D16000803 +:103D7000C9160008B5160008C1160008AD160008DF +:103D80009916000885160008D516000800000000E6 +:103D900001000000000000006D61696E000000007D +:103DA00069646C6500000000A03D0008582B0220EB +:103DB000D02C0220010000000120000800000000BB +:103DC0004865782F50726F6669434E430025424F15 +:103DD000415244252D424C002553455249414C2522 +:103DE000000000000200000000000000BD180008F4 +:103DF000291900084000400078350220883502204B +:103E000002000000000000000300000000000000AD +:103E10006D19000800000000100000009835022015 +:103E200000000000010000000000000040380220F7 +:103E300001010200F1230008012300089D2300086E +:103E400081230008430000004C3E000809024300A3 +:103E5000020100C032090400000102020100052431 +:103E600000100105240100010424020205240600BB +:103E700001070582030800FF09040100020A00008F +:103E80000007050102400000070581024000000014 +:103E900012000000983E00081201100102000040CC +:103EA000AE2D021000020102030100000403090408 +:103EB00025424F41524425004375626559656C6C3B +:103EC0006F772D626473686F74003031323334352C +:103ED00036373839414243444546000000800000EF +:103EE0000080000000800000008000000000020050 +:103EF00000000400000004000000040000000400B2 +:103F000000000400000004000000040000000000A5 +:103F1000B51A00086D1D0008191E00084000400079 +:103F2000B8380220B838022001000000C83802204A +:103F30008000000040010000050000000000802A11 +:103F400000000000AAAAAAAA00000024FFFF0000A7 +:103F50000000000000A00A000001000000000000B6 +:103F6000AAAAAAAA00000000FFFF000000000000AB +:103F7000000000001400005400000000AAAAAAAA31 +:103F800014000054FFFF00000000000000000000CB +:103F900080699A0100000000AAAA8AAA405555012A +:103FA000FFFF0000007070077770000000810200C2 +:103FB00000000000AAAAAAAA00410100FFFF000019 +:103FC0000000008008000000000000000000000069 +:103FD000AAAAAAAA00000000FFFF0000000000003B +:103FE000000000000000000000000000AAAAAAAA29 +:103FF00000000000FFFF00000000000000000000C3 +:104000000000000000000000AAAAAAAA0000000008 +:10401000FFFF0000000000000000000000000000A2 +:1040200000000000AAAAAAAA00000000FFFF0000EA +:104030000000000000000000000000000000000080 +:10404000AAAAAAAA00000000FFFF000000000000CA +:10405000000000000000000000000000AAAA00000C +:1040600000000000FF000000000000000000000051 +:10407000780000000000000000801E00000000002A +:10408000FF00000000000000E83C00083F000000C6 +:1040900049040000F53C00083F0000005104000006 +:1040A000033D00083F0000000096000000000800EB +:1040B000960000000008000004000000AC3E00086C +:1040C00000000000000000000000000000000000F0 +:0840D0000000000000000000E8 :00000001FF diff --git a/Tools/bootloaders/Durandal_bl.bin b/Tools/bootloaders/Durandal_bl.bin index 08f2b85b692..c8f5384e920 100755 Binary files a/Tools/bootloaders/Durandal_bl.bin and b/Tools/bootloaders/Durandal_bl.bin differ diff --git a/Tools/bootloaders/Durandal_bl.elf b/Tools/bootloaders/Durandal_bl.elf index c1fc3c3dd08..cdb1826ab2f 100755 Binary files a/Tools/bootloaders/Durandal_bl.elf and b/Tools/bootloaders/Durandal_bl.elf differ diff --git a/Tools/bootloaders/Durandal_bl.hex b/Tools/bootloaders/Durandal_bl.hex index b31832dc6fa..8afcec9f9e5 100644 --- a/Tools/bootloaders/Durandal_bl.hex +++ b/Tools/bootloaders/Durandal_bl.hex @@ -1,34 +1,34 @@ :020000040800F2 -:1000000000040020A1020008791000087D100008FB -:10001000D11000087D100008A5100008A3020008F8 -:10002000A3020008A3020008A3020008FD2800089C +:1000000000060020A10200088D1000080D10000855 +:10001000651000080D10000839100008A302000840 +:10002000A3020008A3020008A3020008CD290008CB :10003000A3020008A3020008A3020008A30200080C :10004000A3020008A3020008A3020008A3020008FC -:10005000A3020008A3020008413E00086D3E00080C -:10006000993E0008C53E0008F13E0008A3020008C2 +:10005000A3020008A3020008553E0008813E0008E4 +:10006000AD3E0008D93E0008053F0008A302000885 :10007000A3020008A3020008A3020008A3020008CC :10008000A3020008A3020008A3020008A3020008BC -:10009000A3020008A3020008A30200081D3F0008F5 +:10009000A3020008A3020008A3020008313F0008E1 :1000A000A3020008A3020008A3020008A30200089C :1000B000A3020008A3020008A3020008A30200088C :1000C000A3020008A3020008A3020008A30200087C :1000D000A3020008A3020008A3020008A30200086C -:1000E000853F0008A3020008A3020008A30200083D +:1000E000953F0008A3020008A3020008A30200082D :1000F000A3020008A3020008A3020008A30200084C -:10010000A3020008A3020008BD3A0008A3020008E9 +:10010000A3020008A30200081D400008A302000883 :10011000A3020008A3020008A3020008A30200082B :10012000A3020008A3020008A3020008A30200081B :10013000A3020008A3020008A3020008A30200080B :10014000A3020008A3020008A3020008A3020008FB :10015000A3020008A3020008A3020008A3020008EB :10016000A3020008A3020008A3020008A3020008DB -:10017000A302000835340008A3020008A302000807 -:10018000A3020008A302000861110008A3020008EE +:10017000A302000839350008A3020008A302000802 +:10018000A3020008A302000809400008A302000817 :10019000A3020008A3020008A3020008A3020008AB :1001A000A3020008A3020008A3020008A30200089B :1001B000A3020008A3020008A3020008A30200088B :1001C000A3020008A3020008A3020008A30200087B -:1001D000A302000821340008A3020008A3020008BB +:1001D000A302000825350008A3020008A3020008B6 :1001E000A3020008A3020008A3020008A30200085B :1001F000A3020008A3020008A3020008A30200084B :10020000A3020008A3020008A3020008A30200083A @@ -41,1053 +41,1059 @@ :10027000A3020008A3020008A3020008A3020008CA :10028000A3020008A3020008A3020008A3020008BA :10029000A3020008A3020008A3020008A3020008AA -:1002A00002E000F000F8FEE772B6394880F30888F3 -:1002B000384880F3098838484EF60851CEF20001DC -:1002C000086040F20000CCF200004EF63471CEF22D -:1002D00000010860BFF34F8FBFF36F8F40F2000043 -:1002E000C0F2F0004EF68851CEF200010860BFF374 -:1002F0004F8FBFF36F8F4FF00000E1EE100A4EF604 -:100300003C71CEF200010860062080F31488BFF330 -:100310006F8F02F031FB03F04FFB4FF055301F4958 -:100320001B4A91423CBF41F8040BFAE71C49194AA9 -:1003300091423CBF41F8040BFAE71A491A4A1B4B99 -:100340009A423EBF51F8040B42F8040BF8E7002034 -:100350001749184A91423CBF41F8040BFAE702F0F2 -:100360004FFB03F09DFB144C144DAC4203DA54F8E0 -:10037000041B8847F9E700F03FF8114C114DAC42DF -:1003800003DA54F8041B8847F9E702F037BB000092 -:1003900000040020002400200000000800000020CD -:1003A00000040020E843000800240020442400202A -:1003B0004824002060350020A0020008A0020008A8 -:1003C000A0020008A00200082DE9F04F2DED108AD0 -:1003D000C1F80CD0D0F80CD0BDEC108ABDE8F08F7D -:1003E000002383F311882846A047002001F0E4FE93 -:1003F00001F094FE00DFFEE738B51F4C6FF0740388 -:10040000002523701E236570A570E5702571657148 -:10041000A571E57125726572A372E57200F046FD63 -:1004200020B10E2325726572A372E57202F028FADC -:10043000044602F05DFA0546D0B9104B9C4219D033 -:1004400001339C4241F2883412BF05460024012545 -:10045000002002F01FFA0DB100F0B6F800F0B2FD76 -:1004600000F07CFC204600F06FF900F0ADF8F9E7F1 -:100470000024EDE70446EBE748240020010007B024 -:1004800008B500F0E9FBA0F120035842584108BD2F -:10049000054B07B51B88022101A8ADF8043000F018 -:1004A00047FC03B05DF804FB8C400008064991F856 -:1004B000243033B100230822086A81F8243000F088 -:1004C00071BC0120704700BF682400202DE9F84F5F -:1004D000234C05468846174694F824308BBB2E469D -:1004E000DFF87C90002F38D094F824A0BAF1000FE8 -:1004F00005D12022FF214846266200F051FDCAF1B5 -:100500000805414604EB8A00BD4228BF3D465FFA1C -:1005100085FBAD00A7EB0B072A462E4400F018FD23 -:1005200094F82430A844FFB29B445FFA8BFBBBF1E4 -:10053000080F84F824B0D5D1FFF7B8FF0028D1D137 -:1005400008E0266A06EB8306B042C9D0FFF7AEFF8B -:100550000028C4D10020BDE8F88F0120BDE8F88F45 -:100560006824002010B5202383F311881248C36843 -:100570000BB101F0A7FE0023104A4FF47A710E4828 -:1005800001F064FE002383F311880D4C236813B13E -:100590002368013B2360636813B16368013B6360B8 -:1005A000084B1B7833B9636823B9022000F0BEFC06 -:1005B0003223636010BD00BF54240020650500088D -:1005C0009825002090240020554B56492DE9F041F4 -:1005D00053F8042F013201D1BDE8F0818B42F7D1ED -:1005E000514C524B22689A4240F29880504B9B6883 -:1005F00003F1006303F500339A4280F08F800020FE -:1006000000F0C8FB02204B4B187000F083FC4A4BF3 -:10061000D3F8E8200022C3F8E820D3F81011C3F87B -:100620001021D3F81011D3F8EC10C3F8EC20D3F854 -:100630001411C3F81421D3F81411D3F8F010C3F82F -:10064000F020D3F81811C3F81821D3F81811D3F8F3 -:10065000801041F00061C3F88010D3F8801021F0C1 -:100660000061C3F88010D3F88010D3F8801041F0F7 -:100670000071C3F88010D3F8801021F00071C3F826 -:100680008010D3F8803072B62C4B2D490B601D685A -:100690002468BFF34F8FBFF36F8F2A4BC3F88420BA -:1006A000BFF34F8F5A6922F480325A61BFF34F8FE4 -:1006B000D3F8802043F6E07EC2F3C906C2F34E327F -:1006C000B707520102EA0E0838463146013948EAB6 -:1006D000000C00F14040B1F1FF3FC3F874C2F5D106 -:1006E000203A12F1200FEDD1BFF34F8FBFF36F8F80 -:1006F000BFF34F8FBFF36F8F5A6922F400325A61F4 -:100700000022C3F85022BFF34F8FBFF36F8F202317 -:1007100083F31188AD4685F308882047BDE8F08152 -:10072000FCFF01081C00020804000208FFFF01088A -:1007300048240020902400200044025800000208B1 -:1007400008ED00E000ED00E02DE9F04F99B0B34C6A -:100750002022FF21019010A8A66800F021FCB04AD9 -:10076000A3461378A3B90121AE481170C3602023BA -:1007700083F31188C3680BB101F0A4FD0023AA4ADA -:100780004FF47A71A74801F061FD002383F31188CB -:10079000019B13B1A54B019A1A600023A44AA349F7 -:1007A000019F99461C461D46984613704B60029265 -:1007B000012000F0AFFB002F00F012829B4B1B6862 -:1007C000002B40F00D8219B0BDE8F08F0220FFF73A -:1007D00057FE002840F0FB81019BB9F1000F08BFD4 -:1007E0001F46944B1B8802210BA8ADF82C3000F05B -:1007F0009FFADDE74FF47A7000F02EFA031E0393A0 -:10080000EADB0220FFF73CFE82460028E4D0039B8F -:10081000581E042800F2DD81DFE800F0030E1114F9 -:10082000170018A80523042140F8343D00F080FA91 -:1008300054464FF0000856E004217848F6E70421BA -:100840007D48F3E704217D48F0E71C24204604346A -:1008500000F0A2FA04210B900BA800F069FA2C2CEE -:10086000F4D1E5E7002DB7D0002CB5D00220FFF77A -:1008700007FE0546002800F0AF8101206C4C00F017 -:1008800089FA4FF000090220207000F043FB5FFA64 -:1008900089FA504600F08EFA074658B1504609F1E1 -:1008A000010900F097FA0028F1D12C46A94600274B -:1008B000634B97E701233E460220237000F01CFBA8 -:1008C000DBF808309E4206D2304600F065FA01306F -:1008D000EBD10436F4E70026029BA9462C461E7095 -:1008E0003746524B5E6000F063FB15B1002C18BF19 -:1008F0000027FFF7CDFD5BE7002D3FF46DAF002C27 -:100900003FF46AAF0220029B187000F003FB322014 -:1009100000F0A2F9B0F1000AC0F25E811AF00305FE -:1009200040F05A8106EB0A03DBF80820934200F2FC -:100930005381BAF5807F00F24F8155450DDA4FF4AF -:100940007A7000F089F90490049B002BC0F2448176 -:10095000049B3C4AAB540135EFE7C820FFF790FDFC -:100960000546002800F038811F2E11D8C6F120045A -:1009700010AB26F0030033495445184428BF5446B1 -:10098000224600F0E5FA2246FF212E4800F008FB3F -:100990004FEAAA0A2B4930465FFA8AF2FFF796FD22 -:1009A0000446002800F01A8106EB8A0605469AE7FD -:1009B0000220FFF765FD00283FF40EAFFFF776FD3C -:1009C00000283FF409AF4FF0000A5346DBF8082037 -:1009D00092451CD2BAF11F0F12D8109A01320FD0D3 -:1009E0002AF0030218A90A4452F8202C0B92184648 -:1009F00004220BA90AF1040A00F07EFB0346E5E796 -:100A00005046039300F0C8F9039B0B90EFE718A83A -:100A1000042140F84C3D00F08BF964E748240020A5 -:100A20009425002054240020650500089825002006 -:100A3000902400208E4000084C24002050240020E8 -:100A4000904000089424002018A80023642140F856 -:100A5000343D00F039F900287FF4BEAE0220FFF7E4 -:100A60000FFD00283FF4B8AE0B9800F0C5F918ABA5 -:100A700043F8480D04211846CDE718A80023642147 -:100A800040F8343D00F020F900287FF4A5AE0220A4 -:100A9000FFF7F6FC00283FF49FAE0B9800F0AEF98C -:100AA00018AB43F8440DE5E70220FFF7E9FC002806 -:100AB0003FF492AE00F0A8F918AB43F8400DD9E727 -:100AC0000220FFF7DDFC00283FF486AE0BA91420BE -:100AD00000F0A0F9824618A8042140F83CAD00F0CF -:100AE00027F951460BA896E7322000F0B5F8B0F18F -:100AF000000AFFF671AE1AF0030F7FF46DAE0AEB39 -:100B00000803DBF8082093423FF666AE0220FFF7A9 -:100B1000B7FC00283FF460AE2AF0030AC244D04577 -:100B20003FF4E1AE404608F1040800F035F9042135 -:100B30000A900AA800F0FCF8F1E74FF47A70FFF78A -:100B40009FFC00283FF448AEFFF7B0FC00283FF4BC -:100B5000AFAE109B01330CD0082210A90020FFF784 -:100B6000B5FC00283FF4A4AE2022FF2110A800F01D -:100B700017FAFFF78DFC374801F024FB23E6002D20 -:100B80003FF42AAE002C3FF427AE18A800236421BE -:100B900040F8343D00F098F8824600287FF41CAEFF -:100BA0000220FFF76DFC00283FF416AE0390FFF71C -:100BB0006FFC41F28830574601F004FB0B9800F0BF -:100BC0003BFA00F0F5F9039B1C461D46F0E505468F -:100BD00089E64FF00008FFE52546FDE52C4667E66F -:100BE000002000F039F80490049B002BFFF6E3ADE1 -:100BF000012000F081F9049B213B122B3FF6D8AD78 -:100C000001A252F823F000BFCD070008F507000845 -:100C100065080008B1070008B1070008B10700081F -:100C2000F9080008E90A0008B1090008490A0008A3 -:100C30007B0A0008A90A0008B1070008C10A0008D9 -:100C4000B10700083B0B0008E7080008B1070008DF -:100C50007F0B0008A08601002DE9F3474FF47A7559 -:100C6000002402AE154F4543DFF8588006F8014DC9 -:100C700097F900305FFA84F95A1C01D0A34212D1CF -:100C800058F82400012231460368D3F820A02B46EF -:100C9000D047012807D10A4B9DF8070083F8009040 -:100CA00002B0BDE8F0870134022CE1D14FF4FA70B4 -:100CB00001F088FA4FF0FF30F2E700BF0024002077 -:100CC000BC250020A44000082DE9F0474FF47A75B8 -:100CD00006460024134F4D43DFF8508097F900304B -:100CE0005FFA84F95A1C01D0A34210D158F82400AD -:100CF000042231460368D3F820A02B46D0470428AD -:100D000005D1094B002083F80090BDE8F08701343D -:100D1000022CE3D14FF4FA7001F054FA4FF0FF3097 -:100D2000BDE8F08700240020BC250020A440000876 -:100D3000074B30B41A78074B53F822400A46014655 -:100D400023682046DD69044BAC4630BC604700BFD9 -:100D5000BC250020A4400008A0860100F8B50A4C7C -:100D600000250A4E01F074FC094F2070306823788A -:100D7000834207D901F068FC336805440133BD4262 -:100D80003360F3D9F8BD00BFBD250020A0250020A9 -:100D9000FFFF010001F028BD00F1006000F5003008 -:100DA0000068704700F10060920000F5003001F02B -:100DB000ABBC0000054B1A68054B1B789B1A83429D -:100DC00002D9104401F040BC00207047A02500204B -:100DD000BD25002038B5074D04462868204401F0A1 -:100DE00039FC28B928682044BDE8384001F044BCEB -:100DF00038BD00BFA025002000207047014BC0581F -:100E0000704700BF00E8F11F014B1868704700BF32 -:100E10000010005C234BF0B5234C1B682788C3F3FC -:100E20000B0665681B0C94F90820BE4228D0A789E0 -:100E3000BE4206D101220C2505FB0244656894F9E7 -:100E4000082041F20104A3421CD041F20304A34252 -:100E50001AD042F20104A34218D042F20304A34282 -:100E600008BF5622441E013D0B460C44A34217D234 -:100E700015F9016F581C5EB1034600F8016CF5E7E7 -:100E80000022D8E75A22EDE75922EBE75822E9E79A -:100E90002C2584421D7001D9981C5A70401AF0BD4F -:100EA0001846FBE70010005C04240020104B41F2C0 -:100EB00001015B888B429AB211D041F203018B424F -:100EC0000FD042F201039A420DD042F203039A423C -:100ED0000BD10323074A02EB8303D8787047002322 -:100EE000F8E70123F6E70223F4E70020704700BF8C -:100EF0000010005C94400008022804D14FF4000266 -:100F0000034B9A6170470128FCD14FF48002F7E748 -:100F100000080258022803D18022034B9A617047CF -:100F20000128FCD14022F8E700080258022805D128 -:100F3000064A536983F08003536170470128FCD14E -:100F4000024A536983F04003F6E700BF00080258E5 -:100F5000002310B5934203D0CC5CC4540133F9E7AD -:100F600010BD000030B5441E14F9010F0B4658B1F6 -:100F700093F900500131854206D11AB993F9002046 -:100F8000801A30BD013AEFE7002AF7D1104630BD94 -:100F900002460346981A13F9011B0029FAD170473B -:100FA00002440346934202D003F8011BFAE770475C -:100FB000024B1A78024B1A70704700BFBC25002004 -:100FC0000024002038B5164C164D204600F02CFCAD -:100FD0002946204600F054FC2D681348D5F890208F -:100FE000D2F8043843F00203C2F8043801F0EAF8FA -:100FF0000E49284600F054FDD5F890200C48D2F850 -:1010000004380C49A04223F00203C2F804384FF41C -:10101000E1330B6003D0BDE8384000F063BB38BD5E -:10102000EC2A00208441000840420F00AC41000837 -:1010300040260020A425002038B50B4B05461A7821 -:101040000A4B53F822400A4B9C420CD0094B00211A -:1010500018221846FFF7A4FF056001462046BDE8A8 -:10106000384000F03FBB38BDBC250020A44000083C -:10107000EC2A0020A4250020FEE7000000B59BB06C -:10108000EFF3098168226846FFF762FFEFF30583FB -:10109000034B9A6B9A6A9A6A9A6A9A6A9B6AFEE703 -:1010A00000ED00E000B59BB0EFF3098168226846CF -:1010B000FFF74EFFEFF30583044B9A6B9A6A9A6A27 -:1010C0009A6A9A6A9A6A9B6AFEE700BF00ED00E09E -:1010D00000B59BB0EFF3098168226846FFF738FF3F -:1010E000EFF30583034B5A6B9A6A9A6A9A6A9A6A73 -:1010F0009B6AFEE700ED00E030B50A44074D9142DF -:101100000BD011F8013B09245840013CF7D040F3C3 -:1011100000032B4083EA5000F7E730BD2083B8ED91 -:10112000002304491A465A50C81808334260802BDD -:10113000F9D17047C0250020024A136843F0C0036C -:101140001360704700780040044B5A6810439A6857 -:1011500058600AB1181D1047704700BF4026002094 -:101160002DE9F84F414EF56D2F68EC6921072C628F -:1011700019D014F0080F0CBF00208020E20748BFF0 -:1011800040F02000A3074FF0200348BF40F040008C -:10119000610748BF40F4807083F31188FFF7D4FFE4 -:1011A000002383F31188E20509D5202383F31188F6 -:1011B0004FF40070FFF7C8FF002383F311884FF04E -:1011C0002009DFF8A8A04FF0000B14F0200832D15E -:1011D0003B0615D54FF02009DFF894A020060FD567 -:1011E00089F31188504600F0F1F9002830DA082020 -:1011F000FFF7AAFF27F080032B60002383F31188F9 -:1012000079060DD562060BD5202383F31188F26C85 -:10121000336D9A4201D1336C03BB002383F31188F1 -:10122000E30604D5B26E13690BB150699847BDE867 -:10123000F84F01F073BB89F31188AB8C504696F8D8 -:101240006410194000F05CFA8BF31188EC69BCE77C -:1012500080B2288588F31188EC69BFE727F0400742 -:101260001020FFF771FF2F60D7E700BF4026002056 -:101270007826002013B5104C204600F027FA04F120 -:101280001400009400234FF400720C4900F0E8F8B9 -:1012900004F1380000944FF40072094B094900F042 -:1012A00061F9094B0C215220E365084B236602B01B -:1012B000BDE8104000F05EB840260020AC260020BB -:1012C00039110008AC2800200078004000E1F50545 -:1012D000254B002908BF1946037C012B816630B5D8 -:1012E00011D1224B98420ED1214BD3F8E82042F085 -:1012F0008042C3F8E820D3F8102142F08042C3F8BE -:101300001021D3F810310A68036EC46D03EB520349 -:10131000B3FBF2F34A68150442BF23F0070503F05C -:10132000070343EA4503E3608B6843F040036360CF -:10133000CB68510543F00103A36042F4967343F078 -:10134000010323604FF0FF33236205D512F0102212 -:1013500005D0B2F1805F04D080F8643030BD7F23C7 -:10136000FAE73F23F8E700BFC84000084026002006 -:101370000044025800F1604300F01F0209014009D7 -:1013800003F56143C9B2800083F80013012300F123 -:101390006040934000F56140C0F8803103607047C1 -:1013A000F8B51546826804460B46AA4200D2856805 -:1013B000A1692669761AB54207D218462A46FFF770 -:1013C000C7FDA3692B44A3610DE011D9AF1B3246C1 -:1013D0001846FFF7BDFD3A46E1683044FFF7B8FD17 -:1013E000E2683A44A261A36828465B1BA360F8BD8B -:1013F00018462A46FFF7ACFDE368E4E783689342AA -:101400002DE9F04104460F46154600D28568606913 -:101410002669361AB54207D22A463946FFF798FDA3 -:1014200063692B4463610EE013D9A5EB06083246CD -:101430003946FFF78DFD4246B919E068FFF788FD90 -:10144000E26842446261A36828465B1BA360BDE872 -:10145000F0812A463946FFF77BFDE368E2E70000AA -:1014600010B50A440024C361029B006040608460A0 -:10147000C160816141610261036210BD08B582698A -:101480004369934201D1826882B9826801328260E5 -:101490005A1C42611970426903699A4201D3C368B8 -:1014A0004361002100F0AAFE002008BD4FF0FF308C -:1014B00008BD000070B5202304460E4683F3118852 -:1014C000A568A5B1A368A269013BA360531CA361F1 -:1014D00015782269934224BFE368A361E3690BB1E5 -:1014E00020469847002383F31188284670BD314673 -:1014F000204600F073FE0028E2DA85F3118870BD03 -:101500002DE9F74F05460F4690469A46D0F81C90B5 -:10151000202686F311884FF0000B144664B1224652 -:1015200039462846FFF73CFF034668B9514628462E -:1015300000F054FE0028F1D0002383F31188A8EBBB -:10154000040003B0BDE8F08FB9F1000F03D00190A3 -:101550002846C847019B8BF31188E41A1F4486F381 -:101560001188DBE7C160816141611144C361009B67 -:10157000006040608260016103627047F8B5044614 -:101580000E461746202383F31188A568A5B1A368EA -:10159000013BA36063695A1C62611E702369626922 -:1015A0009A4224BFE3686361E3690BB12046984720 -:1015B000002080F31188F8BD3946204600F00EFE69 -:1015C0000028E2DA85F31188F8BD000083694269DA -:1015D0009A4210B501D182687AB98268013282607C -:1015E0005A1C82611C7803699A4201D3C3688361E3 -:1015F000002100F003FE204610BD4FF0FF3010BD6B -:101600002DE9F74F05460F4690469A46D0F81C90B4 -:10161000202686F311884FF0000B144664B1224651 -:1016200039462846FFF7EAFE034668B95146284680 -:1016300000F0D4FD0028F1D0002383F31188A8EB3B -:10164000040003B0BDE8F08FB9F1000F03D00190A2 -:101650002846C847019B8BF31188E41A1F4486F380 -:101660001188DBE7026843681143016003B1184742 -:10167000704700001430FFF743BF00004FF0FF3306 -:101680001430FFF73DBF00003830FFF7B9BF00004E -:101690004FF0FF333830FFF7B3BF00001430FFF7CF -:1016A00009BF00004FF0FF311430FFF703BF000007 -:1016B0003830FFF763BF00004FF0FF323830FFF7DC -:1016C0005DBF000000207047FFF7D4BD044B0360EE -:1016D000002343608360C36001230374704700BF2D -:1016E000E040000810B52023044683F31188FFF77B -:1016F000EFFD02232374002383F3118810BD000043 -:1017000038B5C36904460D461BB904210844FFF7E8 -:10171000A9FF294604F11400FFF7B0FE002806DAFD -:10172000201D4FF48061BDE83840FFF79BBF38BDF6 -:10173000026843681143016003B118477047000015 -:1017400013B5446BD4F894341A681178042915D170 -:10175000217C022912D11979012312898B4013426D -:101760000CD101A904F14C0001F096FFD4F8944487 -:101770000246019B2179206800F0EAF902B010BD11 -:10178000143001F019BF00004FF0FF33143001F0A6 -:1017900013BF00004C3001F0EBBF00004FF0FF33EF -:1017A0004C3001F0E5BF0000143001F0E7BE00004E -:1017B0004FF0FF31143001F0E1BE00004C3001F079 -:1017C000B7BF00004FF0FF324C3001F0B1BF000056 -:1017D000D0F8942438B5136805461978042901D047 -:1017E000012038BD017C0229FAD1127901205C89DF -:1017F00090400440F4D105F1140001F079FE024656 -:101800000028EDD0D5F894544FF480732868697996 -:1018100000F08CF9204638BD406BFFF7D9BF0000BF -:1018200000207047704700007FB5124B012502264B -:10183000044603600023057400F1840243602946D6 -:101840008360C3600C4B0290143001934FF480739B -:10185000009601F029FE094B04F5237229460193F5 -:1018600004F14C004FF480730294009601F0F0FEF6 -:1018700004B070BD0841000819180008411700089D -:101880000A68202383F311880B790B3342F8230075 -:101890004B79133342F823008B7913B10B3342F8A1 -:1018A00023000223C0F894140374002383F31188E7 -:1018B0007047000038B5037F044613B190F85430E8 -:1018C000ABB90125201D0221FFF732FF04F11400FE -:1018D00025776FF0010100F09DFC84F8545004F16D -:1018E0004C006FF00101BDE8384000F093BC38BDFA -:1018F00010B5012104460430FFF71AFF00232377B7 -:1019000084F8543010BD000038B50446002514306A -:1019100001F0E2FD04F14C00257701F0B1FE201D3D -:1019200084F854500121FFF703FF2046BDE83840FA -:10193000FFF74EBF90F8803003F06003202B19D1E1 -:1019400090F88120212A0AD0222A4FF000030ED0DD -:10195000202A0FD1084A42670722826704E0064B1B -:101960004367072383670023C367012070474367EA -:101970008367F9E7002070471C240020D0F89434D6 -:1019800037B51A680446117804291AD1017C022956 -:1019900017D11979012312898B40134211D100F11B -:1019A0004C05284601F02CFF58B101A9284601F04A -:1019B00073FED4F894440246019B2179206800F01C -:1019C000C7F803B030BD000001F10B03F7B550F8C4 -:1019D000234005460E46F4B1202383F3118805EB1E -:1019E0008607201D08214C34FFF7A2FEFB685B69C7 -:1019F0001B6813B1204601F05DFE01A9204601F0ED -:101A00004BFE024648B1019B3146284600F0A0F843 -:101A1000002383F3118803B0F0BDFB685A69126894 -:101A2000002AF5D01B8A013B1340F1D105F1800259 -:101A3000EAE70000133138B550F82140DCB120232B -:101A400083F31188D4F894241368527903EB82034A -:101A5000DB689B695D6845B104216018FFF768FE8B -:101A6000294604F1140001F04DFD2046FFF7B0FEB9 -:101A7000002383F3118838BD7047000001F048B897 -:101A8000012300F1300200F1500103700023436094 -:101A900042F8043B8A42D361FAD103814381704703 -:101AA00038B50446202383F31188002500F10C0388 -:101AB00000F13002416043F8045B9342FBD12046C1 -:101AC00001F048F80223237085F3118838BD000027 -:101AD00070B500EB8103054650690E461446DA6086 -:101AE00018B110220021FFF75BFAA06918B110228B -:101AF0000021FFF755FA31462846BDE8704001F055 -:101B00003BB90000038900F13002002103F001031A -:101B10000381438903F00103438100F1100343F87B -:101B2000041B9342FBD101F0BFB90000F0B40125C2 -:101B300000EB810447898D40E4683D43A4694581F9 -:101B400023600023A2606360F0BC01F0DBB90000F9 -:101B5000F0B4012500EB810407898D40E4683D4322 -:101B60006469058123600023A2606360F0BC01F01A -:101B700053BA0000022300F10C0200F1300110B54D -:101B8000037004460023A0F8883080F88A3080F87B -:101B90008B300381438142F8043B8A42FBD184F8B5 -:101BA0007030204601F07CF863681B6823B1204642 -:101BB0000021BDE81040184710BD000002784368BE -:101BC00080F88C2005221B6802700BB10421184795 -:101BD00070470000436890F88C201B6802700BB1BE -:101BE000052118477047000090F8703070B5044622 -:101BF00013B1002380F8703004F18002204601F018 -:101C000077F963689B6863BB94F8805015F06006B1 -:101C100015D194F8813005F07F0545EA032540F29F -:101C200002339D4200F00E815BD8022D00F0DC8073 -:101C30003FD8002D00F08780012D00F0CF800021DB -:101C4000204601F00DFC0021204601F0FDFB6368F9 -:101C50001B6813B1062120469847062384F870308C -:101C600070BD204698470028CED094F8872094F87D -:101C7000863043EA0223A26F934238BFA36794F9E8 -:101C80008030A56F002B4FF0200380F2FD80002DE7 -:101C900000F0EC80092284F8702083F31188002181 -:101CA000A36F626F2046FFF753FF002383F3118871 -:101CB00070BDB5F5817F00F0B180B5F5407F49D0AA -:101CC000B5F5807FBBD194F88230012BB7D1B4F841 -:101CD000883023F00203A4F888306667A667E667B9 -:101CE000C3E740F201639D421ED8B5F5C06F3BD2F9 -:101CF000B5F5A06FA3D1B4F88030B3F5A06F0ED1C5 -:101D000094F88230204684F88A3001F027F863681E -:101D10001B6813B101212046984703232370002339 -:101D20006367A367E367A0E7B5F5106F32D040F6AD -:101D300002439D4252D0B5F5006F80D104F18B0370 -:101D40006367012324E004F18803E56763670223E6 -:101D5000A3678AE794F88230012B7FF470AFB4F860 -:101D6000883043F00203B6E794F885202046616886 -:101D700094F884304D6843EA022394F8831094F871 -:101D80008220A84700283FF45AAF4368636703687E -:101D9000A367A4E72378042B10D1202383F31188B1 -:101DA0002046FFF7AFFE86F311886368032184F8AD -:101DB0008B601B6821700BB12046984794F88230E5 -:101DC000002BACD084F88B300423237063681B682D -:101DD000002BA4D0022120469847A0E7374B636729 -:101DE0000223A36700239DE794F88410204611F096 -:101DF000800F01F00F010ED001F06CF8012806D021 -:101E000002287FF41CAF2E4BA067636767E72D4B5A -:101E1000A567636763E701F04FF8EFE794F8823056 -:101E2000002B7FF40CAF94F8843013F00F013FF4D3 -:101E300076AF1A06204602D501F02AFB6FE701F0C3 -:101E40001BFB6CE794F88230002B7FF4F8AE94F81B -:101E5000843013F00F013FF462AF1B06204602D519 -:101E600001F0FEFA5BE701F0EFFA58E7142284F87C -:101E7000702083F311882B462A4629462046FFF717 -:101E800055FE85F3118870BD5DB1152284F8702070 -:101E900083F311880021A36F626F2046FFF746FE8F -:101EA00003E70B2284F8702083F311882B462A461F -:101EB00029462046FFF74CFEE3E700BF3841000803 -:101EC000304100083441000838B590F870300446BD -:101ED000152B29D8DFE803F03E28282828283E289B -:101EE000280B293928282828282828283E3E90F819 -:101EF000871090F88620836F42EA01229A4214D913 -:101F0000C268128AB3FBF2F502FB15356DB92023C6 -:101F100083F311882B462A462946FFF719FE85F3DD -:101F200011880A2384F8703038BD142384F8703087 -:101F3000202383F31188002320461A461946FFF711 -:101F4000F5FD002383F3118838BDC36F03B19847B3 -:101F50000023E7E7002101F083FA0021204601F089 -:101F600073FA63681B6813B106212046984706235D -:101F7000D8E7000090F87020152A38B5044622D81A -:101F80000123934040F6416213421DD113F48015A2 -:101F90000FD19B0217D50B2380F87030202383F3D9 -:101FA00011882B462A462946FFF7D2FD85F3118872 -:101FB00038BDC3689B695B682BB9C36F03B1984791 -:101FC000002384F8703038BD002101F049FA002167 -:101FD000204601F039FA63681B6813B106212046D8 -:101FE00098470623EDE70000024B00221B605B6070 -:101FF0009A607047AC2A0020002382680374054B66 -:102000001B6899689142FBD25A6803604260106075 -:1020100058607047AC2A002008B5202383F311884C -:10202000037C032B05D0042B0DD02BB983F311882F -:1020300008BD436900221A604FF0FF334361FFF788 -:10204000DBFF0023F2E790E80C001A60026853609F -:10205000F2E70000002382680374054B1B6899684F -:102060009142FBD85A680360426010605860704724 -:10207000AC2A0020054B196908741868026853607F -:102080001A60186101230374FEF79EB9AC2A002080 -:102090004B1C30B5054687B00A4C10D0236901A807 -:1020A000094A00F0D3F82846FFF7E4FF049B13B178 -:1020B00001A800F007F92369586907B030BDFFF7A0 -:1020C000D9FFF8E7AC2A00201920000838B50C4DDC -:1020D000044641612B6981689A68914203D8BDE842 -:1020E0003840FFF789BF1846FFF786FF01232C61B0 -:1020F000014623742046BDE83840FEF765B900BFAD -:10210000AC2A0020044B1A681B6990689B689842AF -:1021100094BF002001207047AC2A002010B5084C65 -:10212000236820691A6854602260012223611A74AE -:10213000FFF790FF01462069BDE81040FEF744B963 -:10214000AC2A00208260022202740022427470478E -:102150008368A3F17C0243F80C2C026943F83C2C01 -:10216000426943F8382C074A43F81C2CC268A3F193 -:10217000180043F8102C022203F8082C002203F860 -:10218000072C7047E103000810B5202383F3118862 -:10219000FFF7DEFF00210446FFF798FF002383F3DB -:1021A0001188204610BD0000024B1B6958610F20AA -:1021B000FFF760BFAC2A0020202383F31188FFF7CC -:1021C000F3BF000008B50146202383F311880820DF -:1021D000FFF75EFF002383F3118808BD49B1064B6A -:1021E00042681B6918605A60136043600420FFF75F -:1021F0004FBF4FF0FF307047AC2A00200368984271 -:1022000006D01A680260506018465961FFF7F4BEA4 -:102210007047000038B504460D462068844200D15E -:1022200038BD036823605C604561FFF7E5FEF4E7B5 -:10223000054B03F114025A619A614FF0FF32DA61E3 -:1022400000221A62704700BFAC2A0020F8B5036173 -:1022500002291A4B0646C26038BF02215C6A184B3D -:102260001A461F4652F8145F95420AD15861986188 -:102270001C620560456081600819BDE8F84001F006 -:10228000E1BA186AAB68241A0C1902D3E41A2D6853 -:1022900004E09C4202D2204401F0E4FAAB689C4284 -:1022A000F4D86B68356073601E604FF0FF336E606A -:1022B000B460A968091BA960FB61F8BD000C00406F -:1022C000AC2A002010B41A4C234653F8141F814244 -:1022D00010D0416802680A60026851609A424FF06B -:1022E0000001C16003D0936881680B4493605DF87E -:1022F000044B70470A6800209A4262615360C860CC -:1023000003D15DF8044B01F0A7BA936888680344D1 -:10231000206A9360074A526A121A9342E7D9991ABF -:102320005DF8044B012998BF931C184401F09ABA38 -:10233000AC2A0020000C004000207047FEE700009F -:10234000704700004FF0FF3070470000022906D0B0 -:10235000032906D00129064818BF00207047054808 -:102360007047032A9ABF044800EBC2000020704760 -:1023700008420008BC4100082424002070B59AB02F -:1023800006460846144601AD294600F095F8284651 -:10239000FEF7FEFDC0B2431C5B0086E81800237008 -:1023A0000323023404F8013C00231946DAB2023454 -:1023B000904201D81AB070BDEA5C013304F8011CE8 -:1023C00004F8022CF2E7000008B5202383F31188FB -:1023D0000348FFF7D3FA002383F3118808BD00BF39 -:1023E000EC2A002010B50446052916D8DFE801F0D4 -:1023F00016150316161D202383F311880E4A01219A -:10240000FFF766FB20460D4A0221FFF761FB0C48EF -:10241000FFF77AFA002383F3118810BD202383F39A -:1024200011880748FFF746FAF4E7202383F3118861 -:102430000348FFF75DFAEDE73C4100086041000802 -:10244000EC2A002038B50C4D0C4C2A460C4904F1FE -:102450000800FFF793FF05F1CA0204F110000949D3 -:10246000FFF78CFF05F5CA7204F118000649BDE8B4 -:102470003840FFF783BF00BFB42F00202424002082 -:102480008C41000894410008A041000870B5044642 -:1024900008460D46FEF77CFDC6B22046013403789F -:1024A0000BB9184670BD32462946FEF75BFD002881 -:1024B000F3D1012070BD00002DE9F84F05460C4610 -:1024C000FEF766FD2A49C6B22846FFF7DFFF08B1CE -:1024D0000136F6B227492846FFF7D8FF08B1103673 -:1024E000F6B2632E0DD8DFF88890DFF888A0224F6F -:1024F000DFF88CB0DFF88C802E7846B92670BDE806 -:10250000F88F29462046BDE8F84F01F0B7BD252ECB -:102510002AD1072249462846FEF724FD50B9D8F8AB -:1025200000300735083444F8083CD8F8043044F843 -:10253000043CE1E7082251462846FEF713FD98B90E -:10254000A21C0E4B13F8011F023209095B45C95D3D -:1025500002F8041C197801F00F01C95D02F8031C90 -:10256000F0D118340835C7E7267001350134C3E7C8 -:1025700028420008A041000839420008FFE7F11F87 -:102580000BE8F11F30420008BFF34F8F044B1A696C -:102590005107FCD1D3F810215207F8D1704700BF82 -:1025A0000020005208B50D4B1B78ABB9FFF7ECFFCC -:1025B0000B4BDA68D10704D50A4A5A6002F1883217 -:1025C0005A60D3F80C21D20706D5064AC3F8042175 -:1025D00002F18832C3F8042108BD00BF1232002086 -:1025E000002000522301674508B5114B1B78F3B951 -:1025F000104B1A69510703D5DA6842F04002DA60DD -:10260000D3F81021520705D5D3F80C2142F040022F -:10261000C3F80C21FFF7B8FF064BDA6842F001025D -:10262000DA60D3F80C2142F00102C3F80C2108BD96 -:1026300012320020002000520F289ABF00F580605F -:1026400040040020704700004FF400307047000045 -:10265000102070470F2808B50BD8FFF7EDFF00F5E5 -:1026600000330268013204D104308342F9D10120E1 -:1026700008BD002008BD00000F2810B504463FD853 -:10268000FFF782FFFFF78EFF1E484FF0FF33072C46 -:102690004361C0F814311DD80361FFF775FF2302B1 -:1026A00043F02403C360C36843F08003C36003693D -:1026B0005A07FCD4FFF768FF2046FFF7BDFF4FF431 -:1026C000003100F0F7F8FFF78FFF2046BDE810401B -:1026D000FFF7C0BFC0F81031FFF756FFA4F10803A1 -:1026E0001B0243F02403C0F80C31D0F80C3143F046 -:1026F0008003C0F80C31D0F810315B07FBD4D9E768 -:10270000002010BD002000522DE9F84F40EA0203DE -:1027100005460E461746DB0656D13446DFF8C09014 -:10272000DFF8C0A0FFF73EFF3B1B33441F2B04D84C -:10273000FFF75AFF0120BDE8F88F202221462846E6 -:1027400001F08CFC002837D005F17843214A22485B -:102750009342224B98BF984603F5827392BFD346AB -:10276000C8469B46A3F1080388BF1846FFF70CFF35 -:102770004FF0FF3304F11C01A5EB040ECBF8003041 -:10278000036843F002030360231FD8F8002012F00F -:10279000050FFAD153F8042F99424EF80320F4D1D3 -:1027A000BFF34F8FFFF7F0FE4FF0FF33CBF8003051 -:1027B000036823F00203036020222146284601F02B -:1027C0004DFC20B1FFF710FF0020BDE8F88F203549 -:1027D0002034A9E7FFFF0F000C2000521020005208 -:1027E000102100521420005210B5084C237828B153 -:1027F00053B9FFF7D7FE0123237010BD23B120701A -:10280000BDE81040FFF7F0BE10BD00BF123200203F -:1028100002440439064BD2B210B5904200D110BD2B -:10282000441C00B253F8200041F8040FE0B2F4E772 -:10283000504000580F4B30B51C6F240405D41C6F5A -:102840001C671C6F44F400441C670B4C02440439A1 -:102850002368D2B243F480732360084B904200D1C6 -:1028600030BD441C51F8045F00B243F82050E0B280 -:10287000F4E700BF00440258004802585040005896 -:1028800007B5012201A90020FFF7C2FF019803B09C -:102890005DF804FB13B50446FFF7F2FFA04206D033 -:1028A00002A90122002041F8044DFFF7C3FF02B046 -:1028B00010BD00000144BFF34F8F064B884204D384 -:1028C000BFF34F8FBFF36F8F7047C3F85C022030A8 -:1028D000F4E700BF00ED00E0034B1B685B0142BF63 -:1028E0000122024B1A707047D04402581332002064 -:1028F000014B1878704700BF13320020064A536816 -:1029000023F001035360EFF30983683383F30988ED -:10291000002383F31188704730EF00E010B52023C7 -:1029200083F31188104B5B6813F4006318D0F1EE49 -:10293000103AEFF309844FF0807344F84C3C0B4B92 -:10294000DB6844F8083CA4F1680383F30988FFF7C7 -:10295000D9FB18B1064B44F8503C10BD054BFAE7C3 -:1029600083F3118810BD00BF00ED00E030EF00E000 -:10297000F1030008F4030008F0B5BFF34F8FBFF375 -:102980006F8F1D4B0021C3F85012BFF34F8FBFF361 -:102990006F8F5A6942F400325A61BFF34F8FBFF311 -:1029A0006F8FC3F88410BFF34F8FD3F8802043F6A6 -:1029B000E076C2F3C904C2F34E32A507520102EA1F -:1029C000060E284621464EEA0007013900F1404034 -:1029D000C3F860724F1CF6D1203A12F1200FEED1ED -:1029E000BFF34F8F5A6942F480325A61BFF34F8F61 -:1029F000BFF36F8FF0BD00BF00ED00E0FEE7000009 -:102A0000084A094B09498B4204D3094A00219342E1 -:102A100005D3704752F8040F43F8040BF3E743F86B -:102A2000041BF4E7284400086035002060350020CE -:102A300060350020D0F89430002230B51146D0F82F -:102A400090409D684FF0FF3004EB421301329542F5 -:102A5000C3F80019C3F81019C3F80809C3F8001B1C -:102A6000C3F8101BC3F8080BEED24FF00113C4F8E3 -:102A70001C3830BD00EB81032DE9F04FD3F80CE09A -:102A80004F1C4FEA4118DEF814403F03D4F800C051 -:102A90006568D0F8902065450AD30120D2F8343813 -:102AA00000FA01F123EA0101C2F83418BDE8F08F01 -:102AB000ACEB0503BEF81060B34228BF334602EB0F -:102AC0000806D6F81869B6B2B3EB860F13D8A66815 -:102AD0003A449946A6F1040A5AF804BFB9F1040F22 -:102AE000C2F800B002D9A9F10409F5E71E442B444D -:102AF000A6606360CCE70020BDE8F08F890141F05B -:102B00002001016103699B06FCD4122000F03ABF4A -:102B100010B50A4C2046FEF7B3FF094BC4F89030BD -:102B2000084BC4F89430084C2046FEF7A9FF074B29 -:102B3000C4F89030064BC4F8943010BD1432002015 -:102B40000000084070420008B0320020000004403D -:102B50007C4200080378012B70B505465DD1494BD6 -:102B6000D0F89040984259D1474B0E216520D3F8B8 -:102B7000D82042F00062C3F8D820D3F8002142F0F8 -:102B80000062C3F80021D3F80021D3F8802042F07E -:102B90000062C3F88020D3F8802022F00062C3F8DE -:102BA0008020D3F88030FEF7E5FB384BE360384BEC -:102BB000C4F800380023D5F89060C4F8003EC02364 -:102BC00023604FF40413A3633369002BFCDA012361 -:102BD0000C20336100F0D6FE3369DB07FCD41220F1 -:102BE00000F0D0FE3369002BFCDA00262846A660F0 -:102BF000FFF720FF6B68C4F81068DB68C4F814683E -:102C0000C4F81C68002B3AD1224BA3614FF0FF336C -:102C10006361A36843F00103A36070BD1E4B98423B -:102C2000C8D1194B0E214D20D3F8D82042F00072A4 -:102C3000C3F8D820D3F8002142F00072C3F8002175 -:102C4000D3F80021D3F8802042F00072C3F880202E -:102C5000D3F8802022F00072C3F88020D3F88020BF -:102C6000D3F8D82022F08062C3F8D820D3F800210E -:102C700022F08062C3F80021D3F8003193E7074BBC -:102C8000C3E700BF14320020004402584014004043 -:102C900003002002003C30C0B0320020083C30C0AD -:102CA000F8B5D0F89040054600214FF00066204668 -:102CB000FFF724FFD5F8941000234FF001128F681E -:102CC0004FF0FF30C4F83438C4F81C2804EB43122A -:102CD00001339F42C2F80069C2F8006BC2F80809CC -:102CE000C2F8080BF2D20B68D5F89020C5F89830DE -:102CF000636210231361166916F01006FBD11220CF -:102D000000F040FED4F8003823F4FE63C4F8003825 -:102D1000A36943F4402343F01003A3610923C4F8DB -:102D20001038C4F814380B4BEB604FF0C043C4F8B4 -:102D3000103B094BC4F8003BC4F81069C4F80039D3 -:102D4000D5F8983003F1100243F48013C5F89820A9 -:102D5000A362F8BD4C42000840800010D0F89020DB -:102D600090F88A10D2F8003823F4FE6343EA011386 -:102D7000C2F80038704700002DE9F0410EB20D4650 -:102D800000EB8608D8F80C100F6807F00303022B3D -:102D900053D0032B53D03F4A3F4F012B18BF174648 -:102DA000D0F890404FEA451E002205F1100C04EBCC -:102DB0000E03C3F8102B8A69002A42D04A8A05F113 -:102DC00058033A435B01E2500123D4F81C2803FA6C -:102DD0000CF31343C4F81C38A64400234A69CEF808 -:102DE000103905F13F03002A3BD00A8A04EB830324 -:102DF000898B9208012988BF4A43D0F89810561849 -:102E000041EA02422946C0F8986020465A60FFF71E -:102E100075FED8F80C301B8A43EA85531F4305F131 -:102E200048035B01E7500123D4F81C2803FA05F599 -:102E30001543C4F81C58BDE8F081184FB0E7184F8F -:102E4000AEE704EB4613D3F8002B22F40042C3F89C -:102E5000002B0123D4F81C2803FA0CF322EA030305 -:102E6000B8E704EB83030F4A04EB461629465A6081 -:102E70002046FFF743FED6F80039012223F4004331 -:102E800002FA05F5C6F80039D4F81C3823EA05051E -:102E9000CFE700BF00800010008004100080081001 -:102EA00000800C1000040002D0F894201268C0F8D2 -:102EB0009820FFF7BFBD00005831D0F8903049018D -:102EC0005B5813F4004004D013F4001F14BF01201A -:102ED000022070474831D0F8903049015B5813F414 -:102EE000004004D013F4001F14BF012002207047DB -:102EF00000EB8101CB68196A0B6813604B68536063 -:102F00007047000000EB810330B5DD68AA691368E3 -:102F1000D36019B9402B84BF402313606B8A1468B7 -:102F2000D0F890201C4402EB4110013C09B2B4FBE4 -:102F3000F3F46343033323F0030343EAC44343F04E -:102F4000C043C0F8103B2B6803F00303012B0ED1E4 -:102F5000D2F8083802EB411013F4807FD0F8003B20 -:102F600014BF43F0805343F00053C0F8003B02EB22 -:102F70004112D2F8003B43F00443C2F8003B30BD9D -:102F80002DE9F041D0F8906005460C4606EB411360 -:102F9000D3F8087B3A07C3F8087B08D5D6F814386D -:102FA0001B0704D500EB8103DB685B689847FA07D1 -:102FB0002FD5D6F81438DB072BD505EB8403D96859 -:102FC000CCB98B69488A5E68B6FBF0F200FB1262EE -:102FD0008AB91868DA6890420DD2121A83E8140090 -:102FE000202383F3118821462846FFF78BFF84F3C3 -:102FF0001188BDE8F081012303FA04F26B8923EA0A -:1030000002036B81CB6823B121462846BDE8F0411D -:103010001847BDE8F081000000EB81034A0170B55C -:10302000DD68D0F890306C692668E66056BB1A44BB -:103030004FF40020C2F810092A6802F00302012AA6 -:103040000AB20ED1D3F8080803EB421410F4807FC3 -:10305000D4F8000914BF40F0805040F00050C4F88C -:10306000000903EB4212D2F8000940F00440C2F814 -:1030700000090122D3F8340802FA01F10143C3F830 -:10308000341870BD19B9402E84BF402020602068DC -:103090001A442E8A841940F00050013CB4FBF6F427 -:1030A00040EAC440C6E700002DE9F041D0F8906046 -:1030B00004460D4606EB4113D3F80879C3F80879A6 -:1030C000FB071CD5D6F81038DA0718D500EB8103BA -:1030D000D3F80CE0DEF81430D3F800C0DA68944579 -:1030E0001BD2A2EB0C024FF000081A60C3F8048058 -:1030F000202383F31188FFF78FFF88F311883B06A5 -:1031000018D50123D6F83428AB40134212D02946F3 -:103110002046BDE8F041FFF7ADBC012303FA01F200 -:10312000038923EA02030381DEF80830002BE6D08E -:103130009847E4E7BDE8F0812DE9F047D0F89050DA -:1031400004466E69AB691E40F1046E6103D5BDE8AB -:10315000F047FEF70FBD002E12DAD5F8003E9A07B1 -:1031600005D0D5F8003E23F00303C5F8003ED5F89E -:103170000438204623F00103C5F80438FEF72AFD81 -:10318000330502D52046FEF719FDB7040CD5D5F856 -:10319000083813F0060FEB6823F470530CBF43F4A8 -:1031A000105343F4A053EB60300704D56368DB6829 -:1031B0000BB120469847F10200F1A180B2020BD575 -:1031C000D4F8908000274FF00109D4F89430F9B278 -:1031D0009B688B4280F0D280F3061AD5D4F8901009 -:1031E0000A6AC2F30A1702F00F0302F4F012B2F5F2 -:1031F000802F00F0EB80B2F5402F0AD104EB83035F -:1032000001F58051DB68186A00231A469F4240F09E -:10321000D1803003D5F8185835D5E90303D50021FE -:103220002046FFF7ADFEAA0303D501212046FFF794 -:10323000A7FE6B0303D502212046FFF7A1FE2F0353 -:1032400003D503212046FFF79BFEE80203D50421A6 -:103250002046FFF795FEA90203D505212046FFF77A -:103260008FFE6A0203D506212046FFF789FE2B0256 -:1032700003D507212046FFF783FEEF0103D5082180 -:103280002046FFF77DFE700340F1C780E90703D5B4 -:1032900000212046FFF708FFAA0703D50121204699 -:1032A000FFF702FF6B0703D502212046FFF7FCFE64 -:1032B0002F0703D503212046FFF7F6FEEE0603D5C0 -:1032C00004212046FFF7F0FEA80603D5052120467D -:1032D000FFF7EAFE690603D506212046FFF7E4FE64 -:1032E0002A0603D507212046FFF7DEFEEB0540F155 -:1032F000948020460821BDE8F047FFF7D5BED4F8FA -:1033000090904FF000084FF0010AD4F894305FFA23 -:1033100088F79B68BB42FFF451AF09EB4713D3F822 -:10332000002902F44022B2F5802F24D1D3F80029DD -:10333000002A20DAD3F8002942F09042C3F800298D -:10334000D3F80029002AFBDB3946D4F89000FFF7B8 -:10335000D5FB22890AFA07F322EA0303238104EB4F -:103360008703DB689B6813B1394620469847394686 -:103370002046FFF77FFB08F10108C6E708EB411282 -:10338000D2F8003B03F44023B3F5802F10D1D2F8DC -:10339000003B002B0CDA628909FA01F322EA0303ED -:1033A000638104EB8103DB68DB680BB1204698473F -:1033B00001370AE713F0030F00D10A68072B03F166 -:1033C00001039EBF0270120A01301FE704EB830362 -:1033D00001F58051DA6890690268D0F808C0406849 -:1033E000A2EB000E00221046974208D1DB689B69D1 -:1033F0009A683A449A605A6817445F6009E712F085 -:10340000030F00D10868964502F1010282BF8CF8D3 -:103410000000000A0CF1010CE6E7BDE8F0870000AF -:1034200008B50348FFF788FEBDE80840FFF776BA05 -:103430001432002008B50348FFF77EFEBDE80840BF -:10344000FFF76CBAB0320020D0F8903003EB411196 -:10345000D1F8003B43F40013C1F8003B7047000073 -:10346000D0F8903003EB4111D1F8003943F4001348 -:10347000C1F8003970470000D0F8903003EB4111DB -:10348000D1F8003B23F40013C1F8003B7047000063 -:10349000D0F8903003EB4111D1F8003923F4001338 -:1034A000C1F800397047000030B50433039C017245 -:1034B000002104FB0325C361049B00600363059B9B -:1034C0004060C16042610261856104624262816262 -:1034D000C162436330BD00000022416AC2604161A5 -:1034E00001616FF001018262C262FEF793BE0000CB -:1034F00003694269934203D1C2680AB10020704750 -:10350000181D7047036919600021C2680132C2604A -:10351000C269134482699342036124BF436A036111 -:10352000FEF76CBE38B504460D46E3683BB16269F0 -:103530000020131D1268A3621344E36238BD237A8E -:1035400033B929462046FEF749FE0028EDDA38BD9A -:103550006FF00100FBE70000C368C269013BC36074 -:103560004369134482699342436124BF436A4361C0 -:1035700000238362036B03B11847704770B52023A3 -:10358000044683F31188866A3EB9FFF7CBFF0546F0 -:1035900018B186F31188284670BDA36AE26A13F851 -:1035A000015B9342A36202D32046FFF7D5FF0023BD -:1035B00083F31188EFE700002DE9F84F04460E462B -:1035C00090469946202787F311880025AA46D4F80B -:1035D00028B0BBF1000F09D149462046FFF7A2FFF2 -:1035E00020B18BF311882846BDE8F88FA16AA8EBBB -:1035F000050BE36A5B1A9B4528BF9B46BBF1400F56 -:103600001BD9334601F1400251F8040B914243F8B3 -:10361000040BF9D1A36A403640354033A362A26A55 -:10362000E36A9A4202D32046FFF796FF8AF3118895 -:103630004545D8D287F31188C9E730465A46FDF789 -:1036400087FCA36A5E445D445B44A362E7E7000035 -:1036500010B5029C04330172C36103FB04210023F3 -:1036600000608362C362039B40600363049BC46089 -:1036700042610261816104624262436310BD0000E5 -:10368000026A6FF00101C260426A42610261002277 -:103690008262C262FEF7BEBD436902699A4203D1EB -:1036A000C2680AB100207047184650F8043B0B600E -:1036B00070470000C3680021C2690133C3604369D9 -:1036C000134482699342436124BF436A4361FEF716 -:1036D00095BD000038B504460D46E3683BB123694B -:1036E00000201A1DA262E2691344E36238BD237A06 -:1036F00033B929462046FEF771FD0028EDDA38BDC2 -:103700006FF00100FBE7000003691960C268013A2D -:10371000C260C269134482699342036124BF436A51 -:10372000036100238362036B03B1184770470000F5 -:1037300070B5202304460E4683F31188856A35B997 -:103740001146FFF7C7FF10B185F3118870BDA36A5A -:103750001E70A36AE26A01339342A36204D3E16953 -:1037600020460439FFF7D0FF002080F3118870BD98 -:103770002DE9F84F04460D4691469A464FF0200831 -:1037800088F311880026B346A76A4FB951462046F0 -:10379000FFF7A0FF20B187F311883046BDE8F88F0E -:1037A000A06AA9EB0603E76A3F1A9F4228BF1F469B -:1037B000402F1BD905F1400355F8042B9D4240F8DA -:1037C000042BF9D1A36A40364033A362A26AE36AAC -:1037D0009A4204D3E16920460439FFF795FF8BF341 -:1037E00011884E45D9D288F31188CDE729463A464B -:1037F000FDF7AEFBA36A3D443E443B44A362E5E7CC -:10380000026943699A4203D1C3681BB918467047DD -:103810000023FBE7836A002BF8D0043B9B1AF5D00A -:103820001360C368013BC360C3691A4483699A4249 -:10383000026124BF436A0361002383620123E5E739 -:1038400000F050B9034B002258631A610222DA607B -:10385000704700BF000C00400022014BDA60704747 -:10386000000C0040014B5863704700BF000C004043 -:10387000FEE7000010B5194CFEF7B6FBFEF7D8FCCA -:10388000802217492046FEF75DFC012344F8180CFE -:103890000374144B144AD96821F4E0610904090C3B -:1038A0000A431249DA60CA6842F08072CA60104A5C -:1038B0001049C2F8B01F116841F0010111601022D7 -:1038C000DA77202283F82220002383F3118862B65E -:1038D0000948BDE81040FEF757BC00BFD42A0020BD -:1038E0008842000800ED00E00003FA05F0ED00E07A -:1038F000001000E055CEACC5904200082DE9F84F0D -:103900001E4C4FF00008DFF87890656904F1140749 -:10391000D9F82430266AAA689E1B96421CD34FF021 -:10392000200AAA68236AD5F80CB0B61A1344236299 -:103930002B68BB425F606361C5F80C8001D1FFF763 -:103940008BFF88F311882869D8478AF31188656945 -:10395000AB689E42E5D2DBE76269BA420CD091685F -:1039600023628E1B9660A86802282CBF1818981C2A -:10397000BDE8F84FFFF776BFBDE8F88FAC2A00200E -:10398000000C0040034B59685A68521A9042FBD809 -:10399000704700BF001000E04B6843608B68836095 -:1039A000CB68C3600B6943614B6903628B694362F7 -:1039B0000B6803607047000008B52C4B40F2FF71A4 -:1039C0002B48D3F888200A43C3F88820D3F88820EE -:1039D00022F4FF6222F00702C3F88820D3F888207F -:1039E000D3F8E0200A43C3F8E020D3F808210A43C3 -:1039F000C3F808211F4AD3F808311146FFF7CCFF5E -:103A00001D4802F11C01FFF7C7FF1C4802F13801F5 -:103A1000FFF7C2FF1A4802F15401FFF7BDFF194832 -:103A200002F17001FFF7B8FF174802F18C01FFF7B0 -:103A3000B3FF164802F1A801FFF7AEFF144802F1E8 -:103A4000C401FFF7A9FF134802F1E001FFF7A4FF4B -:103A5000114802F1FC01FFF79FFF104802F58C713D -:103A6000FFF79AFFBDE8084000F016B9004402587D -:103A700000000258B0420008000402580008025832 -:103A8000000C025800100258001402580018025886 -:103A9000001C025800200258002402580028025836 -:103AA00008B500F0C9FAFFF7E5FEFEF715FFBDE81F -:103AB0000840FEF7C7BC000070470000084B1A69B9 -:103AC000920710B508D500241C61202383F31188C8 -:103AD000FFF714FF84F31188BDE81040FEF71EBF06 -:103AE000000C0040124B08213220D3F8E82042F0AD -:103AF0000802C3F8E820D3F8102142F00802C3F806 -:103B000010210C4AD3F81031D36B43F00803D36370 -:103B1000C722094B9A624FF0FF32DA6200229A61A3 -:103B20005A63DA605A6001225A611A60FDF722BCBA -:103B3000004402580010005C000C0040F8B5514BE6 -:103B40000024D3F880204FF0FF32C3F88020D3F850 -:103B50008010C3F88040D3F88010D3F88410C3F8E5 -:103B60008420D3F88410C3F88440D3F88410D96F2C -:103B700041F0FF4141F4FF0141F4DF4141F07F0199 -:103B8000D967D96F21F0FF4121F4FF0121F4DF4112 -:103B900021F07F01D967D96FD3F888106FEA4151BE -:103BA0006FEA5151C3F88810D3F88810C1F30A01A5 -:103BB000C3F88810D3F88810D3F89010C3F8902079 -:103BC000D3F89010C3F89040D3F89010D3F8941025 -:103BD000C3F89420D3F89410C3F89440D3F8941009 -:103BE000D3F89810C3F89820D3F89810C3F89840E9 -:103BF000D3F89810D3F88C10C3F88C20D3F88C101D -:103C0000C3F88C40D3F88C10D3F89C10C3F89C20D8 -:103C1000D3F89C20C3F89C40D3F89C3000F0ECF91A -:103C2000194B07229A60194ADA60194A1A6105226B -:103C30005A60184A536A43F480335362C2F884408E -:103C4000BFF34F8FD2F8803043F6E076C3F3C90458 -:103C5000C3F34E33A5075B0103EA060E284621464F -:103C60004EEA0007013900F14040C2F874724F1C5F -:103C7000F6D1203B13F1200FEED1BFF34F8FBFF3EE -:103C80006F8FF8BD0044025890ED00E00000043052 -:103C90001B00080300ED00E001225B4B5B491A604A -:103CA0005B4B19609A605B4ADA6000221A614FF43C -:103CB00040429A619A699204FCD51A6842F4807273 -:103CC0001A60554B1A6F12F4407F04D04FF48032C3 -:103CD0001A6700221A671A6842F001021A604E4AF7 -:103CE000134611684807FCD5002111611A6912F0CA -:103CF0003802FBD1012119604FF0804159605A67A9 -:103D0000464ADA62464A1A611A6842F480321A60F8 -:103D1000414A134611688903FCD5116841F08001BE -:103D200011601A68D205FCD53E4A3F499A620022CA -:103D30005A631963A1F58021DA634B3999635A6498 -:103D40003A4A1A643A4ADA621A6842F0A8521A6089 -:103D5000314B1A6802F02852B2F1285FF9D148229B -:103D600022219A614FF48862DA6140221A624FF090 -:103D70000052DA641A652F4A5A652F4A9A652F4A0B -:103D800011601A6942F003021A61234B1A6902F0AA -:103D90003802182AFAD1D3F8DC2042F00052C3F8D6 -:103DA000DC20D3F8042142F00052C3F80421D3F8F8 -:103DB0000421D3F8DC2042F08042C3F8DC20D3F8A1 -:103DC000042142F08042C3F80421D3F80421D3F83F -:103DD000DC2042F00042C3F8DC20D3F8042142F09A -:103DE0000042C3F80421D3F80421D3F8F42042F0B0 -:103DF0000202C3F8F420D3F81C2142F00202C3F8F7 -:103E00001C21D3F81C3170470881005100C000F01C -:103E10000048025802000001004402580000FF015F -:103E2000008890082220400063020701470405082B -:103E3000FD0BFF010010E000000101000020005216 -:103E4000084A08B5936811680B4003F001039360BA -:103E500023B1054A13680BB150689847BDE8084084 -:103E6000FEF75CBD80000058C0250020084A08B558 -:103E7000936811680B4003F00203936023B1054A75 -:103E800093680BB1D0689847BDE80840FEF746BD7F -:103E900080000058C0250020084A08B593681168C2 -:103EA0000B4003F00403936023B1054A13690BB17F -:103EB00050699847BDE80840FEF730BD80000058C3 -:103EC000C0250020084A08B5936811680B4003F02C -:103ED0000803936023B1054A93690BB1D0699847F1 -:103EE000BDE80840FEF71ABD80000058C02500203C -:103EF000084A08B5936811680B4003F010039360FB -:103F000023B1054A136A0BB1506A9847BDE80840CF -:103F1000FEF704BD80000058C0250020174B10B5E7 -:103F20009C681A68144004F478729A60A30604D559 -:103F3000134A936A0BB1D06A9847600604D5104AB9 -:103F4000136B0BB1506B9847210604D50C4A936B49 -:103F50000BB1D06B9847E20504D5094A136C0BB13D -:103F6000506C9847A30504D5054A936C0BB1D06CEF -:103F70009847BDE81040FEF7D1BC00BF8000005854 -:103F8000C02500201A4B10B59C681A68144004F430 -:103F90007C429A60620504D5164A136D0BB1506DD0 -:103FA0009847230504D5134A936D0BB1D06D9847FC -:103FB000E00404D50F4A136E0BB1506E9847A1046C -:103FC00004D50C4A936E0BB1D06E9847620404D5A9 -:103FD000084A136F0BB1506F9847230404D5054A64 -:103FE000936F0BB1D06F9847BDE81040FEF796BCB9 -:103FF00080000058C0250020062108B50846FDF7BE -:10400000B9F906210720FDF7B5F906210820FDF7CB -:10401000B1F906210920FDF7ADF906210A20FDF7C7 -:10402000A9F906211720FDF7A5F906212820BDE8EA -:104030000840FDF79FB9000008B5FFF77FFDFDF7C9 -:104040006FF8FDF741FBFDF719FDFDF7EBFBFFF7FF -:1040500033FDBDE80840FFF7F3BB000010B50139A0 -:104060000244904201D1002010BD10F8013B11F82C -:10407000014FA342F5D0181B10BD0000034611F8F4 -:10408000012B03F8012B002AF9D1704712101213EB -:104090001211000001105A000310590001205800AD -:1040A00003205600EC2A00204026002053544D33B4 -:1040B0003248373F3F3F0053544D33324837343353 -:1040C0002F3735330000000000960000000000008C -:1040D00000000000000000000000000000000000E0 -:1040E00000000000911600087D160008B9160008AF -:1040F000A5160008B11600089D16000889160008CC -:1041000075160008C5160008000000009D1700087D -:1041100089170008C5170008B1170008BD17000867 -:10412000A917000895170008811700082118000832 -:10413000000000000100000000000000020000007C -:1041400000000000C9190008351A000840004000AE -:10415000842F0020942F00200200000000000000A7 -:104160000300000000000000791A000800000000B1 -:1041700010000000A42F002000000000010000003B -:10418000000000001432002001010200486F6C7929 -:1041900062726F00447572616E64616C2D424C00F6 -:1041A0002553455249414C2500000000E5230008F5 -:1041B0004D23000835190008C923000843000000FA -:1041C000C441000809024300020100C03209040092 -:1041D0000001020201000524001001052401000174 -:1041E000042402020524060001070582030800FFDB -:1041F00009040100020A0000000705010240000056 -:104200000705810240000000120000001042000873 -:10421000120110010200004062314B000002010255 -:10422000030100000403090425424F4152442500C4 -:10423000447572616E64616C0030313233343536EE -:104240003738394142434445460000000000000031 -:10425000E91B0008C91E0008751F00084000400047 -:104260004C3300204C330020010000005C33002060 -:104270008000000040010000080000000001000074 -:1042800000040000080000006D61696E000000007D -:10429000A8420008683300206035002001000000BB -:1042A000713800080000000069646C6500000000BF -:1042B0000000802A00000000AAAAAAAA00000000AC -:1042C000FFFF00000000000000A00A000400000042 -:1042D00000000000AAAAAAAA00000000FDFF00003A -:1042E000000000000000000000500000000000007E -:1042F000AAAAAAAA000000003FFF000000000000D8 -:10430000000000000000000000000000AAAAAAAA05 -:1043100000000000FFFF000000000000000000009F -:104320000004020000000000AAAAAAAA00080100D6 -:10433000DFFF000000000000070000005025100013 -:10434000000000000AA2AAAA50151000FFFF0000FA -:104350000000000700000000000010000000000046 -:10436000AAAAAAAA00001000FFFF00000000000097 -:10437000000000000004000000000000AAAAAAAA91 -:1043800000040000FFFF000000000000000000002B -:104390000051110000000000AAAAAAAA00511100B1 -:1043A000FFFF00000000000000000000000000000F -:1043B00000000000AAAAAAAA00000000FFFF000057 -:1043C00000000000000000000000000000000000ED -:1043D000AAAAAAAA00000000FFFF00000000000037 -:1043E0000000000000000000FF00000000000000CE -:1043F000AC4000083F00000050040000B740000837 -:104400003F000000009600000000080004000000CB -:10441000244200080000000000000000000000002E -:0C44200000000000000000000000000090 +:1002A00002E000F000F8FEE73B48804772B63B48AA +:1002B00080F308883A4880F309883A484EF6085196 +:1002C000CEF20001086040F20000CCF200004EF6D1 +:1002D0003471CEF200010860BFF34F8FBFF36F8F10 +:1002E00040F20000C0F2F0004EF68851CEF200015C +:1002F0000860BFF34F8FBFF36F8F4FF00000E1EE48 +:10030000100A4EF63C71CEF200010860062080F320 +:100310001488BFF36F8F02F017FC02F0B9FB03F0F3 +:1003200053FB4FF0553020491C4A91423CBF41F8E5 +:10033000040BFAE71D491A4A91423CBF41F8040BED +:10034000FAE71B491B4A1C4B9A423EBF51F8040B6B +:1003500042F8040BF8E700201849194A91423CBFC3 +:1003600041F8040BFAE702F0D1FB03F0B1FB154CA6 +:10037000154DAC4203DA54F8041B8847F9E700F046 +:1003800043F8124C124DAC4203DA54F8041B884770 +:10039000F9E702F0B9BB0000911000080006002048 +:1003A00000220020000000080000002000060020BD +:1003B00030440008002200205C220020602200203F +:1003C000FC460020A0020008A0020008A0020008CD +:1003D000A00200082DE9F04F2DED108AC1F80CD0D5 +:1003E000D0F80CD0BDEC108ABDE8F08F002383F369 +:1003F00011882846A047002001F0C4FEFEE701F066 +:100400003FFE00DFFEE7000038B500F0F7FC30B13A +:10041000164B00220E211A725A729972DA7202F089 +:1004200089FA054602F0BCFA0446D0B9104B9D4249 +:1004300019D001339D4241F2883512BF0446002590 +:100440000124002002F080FA0CB100F079F800F0ED +:1004500083FD00F019FC284600F020F900F070F848 +:10046000F9E70025EDE70546EBE700BF0022002095 +:10047000010007B008B500F0D3FBA0F120035842FB +:10048000584108BD07B541F21203022101A8ADF899 +:10049000043000F0E3FB03B05DF804FB38B5202323 +:1004A00083F311881748C3680BB101F0F1FE0023F4 +:1004B000154A4FF47A71134801F0AEFE002383F31E +:1004C0001188124C236813B12368013B23606368D1 +:1004D00013B16368013B63600D4D2B7833B96368DA +:1004E0007BB9022000F0AAFC322363602B78032B37 +:1004F00007D163682BB9022000F0A0FC4FF47A7397 +:10050000636038BD602200209D0400087C23002029 +:1005100074220020084B187003280CD8DFE800F084 +:1005200008050208022000F07BBC022000F068BC35 +:10053000024B00225A607047742200207C23002066 +:10054000F8B5504B504A1C461968013100F09980AB +:1005500004339342F8D162684C4B9A4240F2918046 +:100560004B4B9B6803F1006303F500339A4280F024 +:100570008880002000F0A2FB0220FFF7CBFF454B54 +:100580000021D3F8E820C3F8E810D3F81021C3F80D +:100590001011D3F81021D3F8EC20C3F8EC10D3F8E5 +:1005A0001421C3F81411D3F81421D3F8F020C3F8A0 +:1005B000F010D3F81821C3F81811D3F81821D3F884 +:1005C000802042F00062C3F88020D3F8802022F01F +:1005D0000062C3F88020D3F88020D3F8802042F056 +:1005E0000072C3F88020D3F8802022F00072C3F894 +:1005F0008020D3F8803072B64FF0E023C3F8084D66 +:10060000D4E90004BFF34F8FBFF36F8F224AC2F8C3 +:100610008410BFF34F8F536923F480335361BFF3CA +:100620004F8FD2F8803043F6E076C3F3C905C3F3A9 +:100630004E335B0103EA060C29464CEA8177013907 +:10064000C2F87472F9D2203B13F1200FF2D1BFF33C +:100650004F8FBFF36F8FBFF34F8FBFF36F8F536910 +:1006600023F4003353610023C2F85032BFF34F8F9D +:10067000BFF36F8F202383F31188854680F30888AA +:100680002047F8BD0000020820000208FFFF010813 +:10069000002200200044025800ED00E02DE9F04F58 +:1006A00093B0A84B2022FF2100900AA89D6800F07B +:1006B000FDFBA54A1378A3B90121A4481170C360BA +:1006C000202383F31188C3680BB101F0E1FD0023FF +:1006D0009F4A4FF47A719D4801F09EFD002383F3F9 +:1006E0001188009B13B19B4B009A1A609A4A1378A9 +:1006F000032B03D000231370964A53604FF0000A77 +:10070000009CD3465646D146012000F089FB24B117 +:10071000904B1B68002B00F00E82002000F080FA46 +:100720000390039B002BF2DB012000F069FB039B8D +:10073000213B162BE8D801A252F823F099070008B4 +:10074000C107000855080008090700080907000844 +:1007500009070008DD080008AB0A0008C509000801 +:10076000270A00084F0A0008750A00080907000850 +:10077000870A000809070008F90A00083908000874 +:10078000090700083D0B0008A50700083908000804 +:1007900009070008270A00080220FFF76BFE00285F +:1007A00040F0F381009B022105A8BAF1000F08BFB9 +:1007B0001C4641F21233ADF8143000F04FFAA3E7B3 +:1007C0004FF47A7000F02CFA071EEBDB0220FFF7E3 +:1007D00051FE0028E6D0013F052F00F2D881DFE866 +:1007E00007F0030A0D1013360523042105A805930D +:1007F00000F034FA17E004215248F9E70421574881 +:10080000F6E704215648F3E74FF01C08404608F18C +:10081000040800F055FA0421059005A800F01EFA1E +:10082000B8F12C0FF2D101204FF0000900FA07F7C0 +:1008300047EA0B0B5FFA8BFB00F084FB26B10BF051 +:100840000B030B2B08BF0024FFF71CFE5CE7042101 +:100850004448CDE7002EA5D00BF00B030B2BA1D104 +:100860000220FFF707FE074600289BD00120002644 +:1008700000F024FA0220FFF74DFE5FFA86F84046AA +:1008800000F02CFA044688B14046013600F036FAF2 +:100890000028F2D1BA46044641F21213022105A8FB +:1008A0003E46ADF8143000F0D9F92DE72546012079 +:1008B000FFF730FE234B9B68AB4207D9284600F078 +:1008C000FFF9013040F066810435F3E70025224B43 +:1008D000BA463E461D701F4B5D60ADE7002E3FF4EB +:1008E00061AF0BF00B030B2B7FF45CAF0220FFF723 +:1008F00011FE322000F094F9B0F10008FFF652AF7B +:1009000018F003077FF44EAF0E4A08EB0503926818 +:1009100093423FF647AFB8F5807F3FF743AF124BA6 +:10092000B845019322DD4FF47A7000F079F9039015 +:10093000039A002AFFF636AF039A0137019B03F8AA +:10094000012BEDE700220020782300206022002008 +:100950009D0400087C230020742200200422002033 +:10096000082200200C22002078220020C820FFF757 +:1009700081FD074600283FF415AF1F2D11D8C5F1A2 +:1009800020020AAB25F0030084494245184428BFE1 +:100990004246019200F064FA019AFF217F4800F07C +:1009A00085FA4FEAA803C8F387027C4928460193D9 +:1009B00000F084FA064600283FF46EAF019B05EB79 +:1009C000830539E70220FFF755FD00283FF4EAAE22 +:1009D00000F0B0F900283FF4E5AE0027B846704BB0 +:1009E0009B68BB4218D91F2F11D80A9B01330ED028 +:1009F00027F0030312AA134453F8203C0593404602 +:100A0000042205A9043700F061FB8046E7E7384679 +:100A100000F056F90590F2E7CDF81480042105A8FE +:100A200000F01CF908E70023642104A8049300F0F7 +:100A30000BF900287FF4B6AE0220FFF71BFD00285B +:100A40003FF4B0AE049800F06BF90590E6E70023A0 +:100A5000642104A8049300F0F7F800287FF4A2AE04 +:100A60000220FFF707FD00283FF49CAE049800F039 +:100A700059F9EAE70220FFF7FDFC00283FF492AEA7 +:100A800000F068F9E1E70220FFF7F4FC00283FF4EA +:100A900089AE05A9142000F063F9074604210490EB +:100AA00004A800F0DBF83946B9E7322000F0B8F8C6 +:100AB000071EFFF677AEBB077FF474AE384A07EB2C +:100AC0000903926893423FF66DAE0220FFF7D2FC15 +:100AD00000283FF467AE27F003074F44B9453FF4C1 +:100AE000ABAE484609F1040900F0EAF8042105908C +:100AF00005A800F0B3F8F1E74FF47A70FFF7BAFCFD +:100B000000283FF44FAE00F015F9002844D00A9BAE +:100B100001330BD008220AA9002000F0CFF90028E9 +:100B20003AD02022FF210AA800F0C0F9FFF7AAFC62 +:100B30001C4801F02DFB13B0BDE8F08F002E3FF4F0 +:100B400031AE0BF00B030B2B7FF42CAE0023642192 +:100B500005A8059300F078F8074600287FF422AE38 +:100B60000220FFF787FC804600283FF41BAEFFF70A +:100B700089FC41F2883001F00BFB059800F026FA61 +:100B800046463C4600F0DEF9BEE5064654E64FF028 +:100B9000000907E6BA467FE637467DE67822002060 +:100BA00000220020A0860100F7B50C46184E4FF435 +:100BB0007A71054602FB01F396F90020501C0BD117 +:100BC0001448294601930268176A2246B8478442AE +:100BD000019B03D1002310E0002AF1D096F90020F8 +:100BE000511C01D0012A0DD10B4829460268166A12 +:100BF0002246B047844205D10123084A01201370E0 +:100C000003B0F0BD4FF4FA7001F0C2FA0020F7E72C +:100C100010220020F0290020CC230020C82300202F +:100C2000002307B5024601210DF107008DF80730BA +:100C3000FFF7BAFF20B19DF8070003B05DF804FB91 +:100C40004FF0FF30F9E700000A46042108B5FFF72E +:100C5000ABFF80F00100C0B2404208BD074B0A461E +:100C600030B41978064B53F82140014623682046DA +:100C7000DD69044BAC4630BC604700BFC823002090 +:100C800010410008A086010070B50A4E00240A4DEC +:100C900001F028FD308028683388834208D901F0AC +:100CA0001DFD2B6804440133B4F5003F2B60F2D3E3 +:100CB00070BD00BFCA2300208423002001F0F0BDD6 +:100CC00000F1006000F500300068704700F100603E +:100CD000920000F5003001F067BD0000054B1A6876 +:100CE000054B1B889B1A834202D9104401F0F6BCC5 +:100CF0000020704784230020CA23002038B5074D08 +:100D000004462868204401F0EFFC28B928682044F4 +:100D1000BDE8384001F0FABC38BD00BF8423002094 +:100D20000020704700F1FF5000F58F10D0F8000848 +:100D300070470000064991F8243033B1002308229F +:100D4000086A81F82430FFF7C1BF0120704700BF57 +:100D500088230020014B1868704700BF0010005C1A +:100D6000244BF0B51A680446234BC2F30B06120C51 +:100D70001F885868BE4293F9085028D09F89BE4208 +:100D800006D101200C2505FB0033586893F9085063 +:100D900041F201039A421CD041F203039A421AD055 +:100DA00042F201039A4218D042F203039A4208BF6A +:100DB0005625621E0B46441E0A4493420FD214F974 +:100DC000016F581C6EB1034600F8016CF5E7002076 +:100DD000D8E75A25EDE75925EBE75825E9E7184606 +:100DE00005E02C2482421C7001D9981C5D70401AC9 +:100DF000F0BD00BF0010005C1422002000207047EE +:100E0000022804D1054B4FF400029A617047012873 +:100E1000FCD1024B4FF48002F7E700BF00080258F4 +:100E2000022803D1044B80229A6170470128FCD12B +:100E3000014B4022F8E700BF00080258022805D104 +:100E4000064A536983F08003536170470128FCD13F +:100E5000024A536983F04003F6E700BF00080258D6 +:100E6000002310B5934203D0CC5CC4540133F9E79E +:100E700010BD0000013810B510F9013F3BB191F9E8 +:100E800000409C4203D11AB10131013AF4E71AB192 +:100E900091F90020981A10BD1046FCE7034602465F +:100EA000D01A12F9011B0029FAD1704702440346F7 +:100EB000934202D003F8011BFAE770472DE9F8438B +:100EC0001F4D14460746884695F8242052BBDFF88C +:100ED00070909CB395F824302BB92022FF2148460E +:100EE0002F62FFF7E3FF95F824004146C0F10802A6 +:100EF00005EB8000A24228BF2246D6B29200FFF73F +:100F0000AFFF95F82430A41B17441E449044E4B26C +:100F1000F6B2082E85F82460DBD1FFF70BFF00281E +:100F2000D7D108E02B6A03EB82038342CFD0FFF7CF +:100F300001FF0028CBD10020BDE8F8830120FBE7AA +:100F400088230020024B1A78024B1A70704700BFAA +:100F5000C82300201022002038B5164C164D20461C +:100F600000F018FC2946204600F040FC2D6813488C +:100F7000D5F89020D2F8043843F00203C2F80438C0 +:100F800001F006F90E49284600F03EFDD5F8902004 +:100F90000C48D2F804380C49A04223F00203C2F8EE +:100FA00004384FF4E1330B6003D0BDE8384000F063 +:100FB0004FBB38BDF02900201842000840420F0006 +:100FC00020420008CC230020B023002038B50B4B72 +:100FD00004461A780A4B53F822500A4B9D420CD013 +:100FE000094B002118221846FFF760FF04600146F4 +:100FF0002846BDE8384000F02BBB38BDC823002090 +:1010000010410008F0290020B023002000B59BB05B +:10101000EFF3098168226846FFF722FFEFF30583AB +:10102000044B9A6BDA6A9A6A9A6A9A6A9A6A9A6A14 +:101030009B6AFEE700ED00E000B59BB0EFF309818D +:1010400068226846FFF70CFFEFF30583044B9A6BA9 +:101050009A6A9A6A9A6A9A6A9A6A9B6AFEE700BFD3 +:1010600000ED00E000B59BB0EFF30981682268460F +:10107000FFF7F6FEEFF30583034B5A6B9A6A9A6A01 +:101080009A6A9A6A9B6AFEE700ED00E0FEE70000BC +:1010900000B595B0132101A801F092FC9DF84F30E6 +:1010A0007BB10023132101A88DF84F3001F082FCA1 +:1010B000054BD3F8002882F30888D3F80438984702 +:1010C000FEE715B05DF804FB0090F01F30B50A4450 +:1010D000084D91420DD011F8013B5840082340F3D0 +:1010E0000004013B2C4013F0FF0384EA5000F6D1CA +:1010F000EFE730BD2083B8ED02684368114301601B +:1011000003B1184770470000024A136843F0C00358 +:10111000136070470078004013B50E4C204600F075 +:101120008BFA04F1140000234FF400720A49009472 +:1011300000F04CF9094B4FF40072094904F13800F2 +:10114000009400F0C5F9074A074BC4E9172302B021 +:1011500010BD00BFCC230020382400200911000856 +:10116000382600200078004000E1F505037C30B50A +:10117000244C002918BF0C46012B11D1224B984258 +:101180000ED1224BD3F8E82042F08042C3F8E82089 +:10119000D3F8102142F08042C3F81021D3F8103167 +:1011A0002268036EC16D03EB52038466B3FBF2F356 +:1011B0006268150442BF23F0070503F0070343EA02 +:1011C0004503CB60A36843F040034B60E36843F002 +:1011D00001038B6042F4967343F001030B604FF000 +:1011E000FF330B62510505D512F0102205D0B2F184 +:1011F000805F04D080F8643030BD7F23FAE73F235E +:10120000F8E700BF18410008CC2300200044025832 +:101210002DE9F047C66D05463768F4692107346249 +:1012200019D014F0080118BF8021E20748BF41F02F +:101230002001A3074FF0200348BF41F040016007A1 +:1012400048BF41F4807183F31188281DFFF754FFD4 +:10125000002383F31188E2050AD5202383F3118844 +:101260004FF40071281DFFF747FF002383F3118817 +:101270004FF020094FF0000A14F0200838D13B0647 +:1012800016D54FF0200905F1380A200610D589F34C +:101290001188504600F050F9002836DA0821281D40 +:1012A000FFF72AFF27F080033360002383F31188C0 +:1012B000790614D5620612D5202383F31188D5E967 +:1012C00013239A4208D12B6C33B127F04007102129 +:1012D000281DFFF711FF3760002383F31188E30611 +:1012E00018D5AA6E1369ABB15069BDE8F04718472D +:1012F00089F31188736A284695F86410194000F044 +:10130000B5F98AF31188F469B6E7B06288F31188F9 +:10131000F469BAE7BDE8F087F8B515468268044677 +:101320000B46AA4200D28568A1692669761AB542A1 +:101330000BD218462A46FFF793FDA3692B44A361FD +:101340002846A3685B1BA360F8BD0CD9AF1B1846E9 +:101350003246FFF785FD3A46E1683044FFF780FDED +:10136000E3683B44EBE718462A46FFF779FDE3685C +:10137000E5E7000083689342F7B50446154600D2BE +:101380008568D4E90460361AB5420BD22A46FFF7C5 +:1013900067FD63692B4463612846A3685B1BA360F8 +:1013A00003B0F0BD0DD93246AF1B0191FFF758FDD8 +:1013B00001993A46E0683144FFF752FDE3683B4447 +:1013C000E9E72A46FFF74CFDE368E4E710B50A4475 +:1013D0000024C361029B8460C16002610362C0E9B2 +:1013E0000000C0E9051110BD08B5D0E905329342EF +:1013F00001D1826882B98268013282605A1C4261DE +:1014000019700021D0E904329A4224BFC3684361B5 +:1014100000F0DAFE002008BD4FF0FF30FBE70000CF +:1014200070B5202304460E4683F31188A568A5B144 +:10143000A368A269013BA360531CA36115782269CC +:10144000934224BFE368A361E3690BB12046984748 +:10145000002383F31188284607E03146204600F038 +:10146000A3FE0028E2DA85F3118870BD2DE9F74F5D +:1014700004460E4617469846D0F81C904FF0200AB6 +:101480008AF311884FF0000B154665B12A463146A4 +:101490002046FFF741FF034660B94146204600F071 +:1014A00083FE0028F1D0002383F31188781B03B05A +:1014B000BDE8F08FB9F1000F03D001902046C84776 +:1014C000019B8BF31188ED1A1E448AF31188DCE727 +:1014D000C160C361009B82600362C0E905111144D1 +:1014E000C0E9000001617047F8B504460D46164694 +:1014F000202383F31188A768A7B1A368013BA360E9 +:1015000063695A1C62611D70D4E904329A4224BF97 +:10151000E3686361E3690BB120469847002080F3DC +:10152000118807E03146204600F03EFE0028E2DA4E +:1015300087F31188F8BD0000D0E9052310B59A4261 +:1015400001D182687AB982680021013282605A1C16 +:1015500082611C7803699A4224BFC368836100F0EA +:1015600033FE204610BD4FF0FF30FBE72DE9F74F6B +:1015700004460E4617469846D0F81C904FF0200AB5 +:101580008AF311884FF0000B154665B12A463146A3 +:101590002046FFF7EFFE034660B94146204600F0C3 +:1015A00003FE0028F1D0002383F31188781B03B0D9 +:1015B000BDE8F08FB9F1000F03D001902046C84775 +:1015C000019B8BF31188ED1A1E448AF31188DCE726 +:1015D000026843681143016003B118477047000077 +:1015E0001430FFF743BF00004FF0FF331430FFF714 +:1015F0003DBF00003830FFF7B9BF00004FF0FF33A8 +:101600003830FFF7B3BF00001430FFF709BF000008 +:101610004FF0FF311430FFF703BF00003830FFF701 +:1016200063BF00004FF0FF323830FFF75DBF0000AE +:1016300000207047FFF770BD044B03600023436038 +:10164000C0E9023301230374704700BF3041000832 +:1016500010B52023044683F31188FFF787FD02238A +:101660002374002383F3118810BD000038B5C369CB +:1016700004460D461BB904210844FFF7A9FF29467B +:1016800004F11400FFF7B0FE002806DA201D4FF425 +:101690008061BDE83840FFF79BBF38BD02684368F2 +:1016A0001143016003B118477047000013B5406B48 +:1016B00000F58054D4F8A4381A681178042914D19C +:1016C000017C022911D11979012312898B4013421F +:1016D0000BD101A94C3002F077F8D4F8A4480246A7 +:1016E000019B2179206800F0DFF902B010BD0000F5 +:1016F000143001F0F9BF00004FF0FF33143001F057 +:10170000F3BF00004C3002F0CBB800004FF0FF33C5 +:101710004C3002F0C5B80000143001F0C7BF000023 +:101720004FF0FF31143001F0C1BF00004C3002F027 +:1017300097B800004FF0FF324C3002F091B8000033 +:101740000020704710B500F58054D4F8A4381A680A +:101750001178042917D1017C022914D15979012368 +:1017600052898B4013420ED1143001F059FF0246CA +:1017700048B1D4F8A4484FF4407361792068BDE8BB +:10178000104000F07FB910BD406BFFF7DBBF0000D9 +:10179000704700007FB5124B012504260446036004 +:1017A0000023057400F1840243602946C0E9023336 +:1017B0000C4B0290143001934FF44073009601F0EB +:1017C0000BFF094B04F69442294604F14C000294A5 +:1017D000CDE900634FF4407301F0D2FF04B070BD57 +:1017E0005841000889170008AD1600080A68202330 +:1017F00083F311880B790B3342F823004B791333B1 +:1018000042F823008B7913B10B3342F8230000F523 +:101810008053C3F8A41802230374002383F31188B0 +:101820007047000038B5037F044613B190F8543078 +:10183000ABB90125201D0221FFF730FF04F1140090 +:101840006FF00101257700F0CBFC04F14C0084F827 +:1018500054506FF00101BDE8384000F0C1BC38BD04 +:1018600010B5012104460430FFF718FF0023237749 +:1018700084F8543010BD000038B5044600251430FB +:1018800001F0C2FE04F14C00257701F091FF201D0C +:1018900084F854500121FFF701FF2046BDE838408D +:1018A000FFF750BF90F8803003F06003202B06D183 +:1018B00090F881200023212A03D81F2A06D800206F +:1018C0007047222AFBD1C0E91D3303E0034A426777 +:1018D00007228267C3670120704700BF2C220020C7 +:1018E00037B500F58055D5F8A4381A681178042961 +:1018F0001AD1017C022917D11979012312898B4051 +:10190000134211D100F14C04204602F011F858B1F5 +:1019100001A9204601F058FFD5F8A4480246019BD2 +:101920002179206800F0C0F803B030BD01F10B034D +:10193000F0B550F8236085B004460D46FEB1202373 +:1019400083F3118804EB8507301D0821FFF7A6FEFD +:10195000FB6806F14C005B691B681BB1019001F04C +:1019600041FF019803A901F02FFF024648B1039BF4 +:101970002946204600F098F8002383F3118805B02B +:10198000F0BDFB685A691268002AF5D01B8A013B3A +:101990001340F1D104F18002EAE70000133138B5B9 +:1019A00050F82140ECB1202383F3118804F58053D3 +:1019B000D3F8A4281368527903EB8203DB689B6990 +:1019C0005D6845B104216018FFF768FE294604F1FF +:1019D000140001F02FFE2046FFF7B4FE002383F32E +:1019E000118838BD7047000001F022B90123402260 +:1019F000002110B5044600F8303BFFF757FA0023EA +:101A0000C4E9013310BD000010B52023044683F360 +:101A100011882422416000210C30FFF747FA20464C +:101A200001F028F902232370002383F3118810BDED +:101A300070B500EB8103054650690E461446DA6026 +:101A400018B110220021FFF731FAA06918B1102255 +:101A50000021FFF72BFA31462846BDE8704001F01F +:101A60001BBA000083682022002103F0011310B587 +:101A7000044683601030FFF719FA2046BDE8104095 +:101A800001F096BAF0B4012500EB810447898D403E +:101A9000E4683D43A469458123600023A26063603C +:101AA000F0BC01F0B3BA0000F0B4012500EB8104F2 +:101AB00007898D40E4683D43646905812360002304 +:101AC000A2606360F0BC01F029BB000070B5022386 +:101AD00000250446242203702946C0F888500C30A3 +:101AE00040F8045CFFF7E2F9204684F8705001F0FA +:101AF00067F963681B6823B129462046BDE870403A +:101B0000184770BD037880F88C3005230370436854 +:101B10001B6810B504460BB1042198470023A3604D +:101B200010BD000090F88C20436802701B680BB158 +:101B3000052118477047000070B590F870300446D2 +:101B400013B1002380F8703004F18002204601F0C8 +:101B500053FA63689B68B3B994F8803013F060055A +:101B600035D00021204601F0FDFC0021204601F087 +:101B7000EDFC63681B6813B10621204698470623D5 +:101B800084F8703070BD204698470028E4D0B4F83F +:101B90008630A26F9A4288BFA36794F98030A56F00 +:101BA000002B4FF0200380F20381002D00F0F28023 +:101BB000092284F8702083F3118800212046D4E99B +:101BC0001D23FFF771FF002383F31188DAE794F8F0 +:101BD000812003F07F0343EA022340F20232934262 +:101BE00000F0C58021D8B3F5807F48D00DD8012BF7 +:101BF0003FD0022B00F09380002BB2D104F1880279 +:101C000062670222A267E367C1E7B3F5817F00F054 +:101C10009B80B3F5407FA4D194F88230012BA0D1F2 +:101C2000B4F8883043F0020332E0B3F5006F4DD0D2 +:101C300017D8B3F5A06F31D0A3F5C063012B90D8AE +:101C40006368204694F882205E6894F88310B4F8A4 +:101C50008430B047002884D0436863670368A36773 +:101C60001AE0B3F5106F36D040F6024293427FF48B +:101C700078AF5C4B63670223A3670023C3E794F844 +:101C80008230012B7FF46DAFB4F8883023F002036B +:101C9000A4F88830C4E91D55E56778E7B4F88030CA +:101CA000B3F5A06F0ED194F88230204684F88A30C4 +:101CB00001F0E4F863681B6813B1012120469847DE +:101CC000032323700023C4E91D339CE704F18B0335 +:101CD00063670123C3E72378042B10D1202383F308 +:101CE00011882046FFF7BEFE85F311880321636843 +:101CF00084F88B5021701B680BB12046984794F8EC +:101D00008230002BDED084F88B300423237063688C +:101D10001B68002BD6D0022120469847D2E794F8C2 +:101D2000843020461D0603F00F010AD501F056F954 +:101D3000012804D002287FF414AF2B4B9AE72B4BD9 +:101D400098E701F03DF9F3E794F88230002B7FF437 +:101D500008AF94F8843013F00F01B3D01A06204670 +:101D600002D501F017FCADE701F008FCAAE794F8F2 +:101D70008230002B7FF4F5AE94F8843013F00F011D +:101D8000A0D01B06204602D501F0ECFB9AE701F03B +:101D9000DDFB97E7142284F8702083F311882B462B +:101DA0002A4629462046FFF76DFE85F31188E9E6AD +:101DB0005DB1152284F8702083F31188002120463C +:101DC000D4E91D23FFF75EFEFDE60B2284F87020A8 +:101DD00083F311882B462A4629462046FFF764FEE6 +:101DE000E3E700BF88410008804100088441000803 +:101DF00038B590F870300446002B3ED0063BDAB27E +:101E00000F2A34D80F2B32D8DFE803F037313108EE +:101E1000223231313131313131313737856FB0F8DC +:101E200086309D4214D2C3681B8AB5FBF3F203FBD4 +:101E300012556DB9202383F311882B462A46294673 +:101E4000FFF732FE85F311880A2384F870300EE024 +:101E5000142384F87030202383F311880023204654 +:101E60001A461946FFF70EFE002383F3118838BD8A +:101E7000C36F03B198470023E7E70021204601F034 +:101E800071FB0021204601F061FB63681B6813B100 +:101E90000621204698470623D7E7000010B590F8A2 +:101EA00070300446142B29D017D8062B05D001D842 +:101EB0001BB110BD093B022BFBD80021204601F0CD +:101EC00051FB0021204601F041FB63681B6813B100 +:101ED000062120469847062319E0152BE9D10B234C +:101EE00080F87030202383F3118800231A461946A6 +:101EF000FFF7DAFD002383F31188DAE7C3689B69F3 +:101F00005B68002BD5D1C36F03B19847002384F8D9 +:101F10007030CEE7024B0022C3E900339A6070476D +:101F200038280020002382680374054B1B689968D9 +:101F30009142FBD25A68036042601060586070475B +:101F40003828002008B5202383F31188037C032B55 +:101F500005D0042B0DD02BB983F3118808BD43693C +:101F600000221A604FF0FF334361FFF7DBFF0023CD +:101F7000F2E7D0E9003213605A60F3E70023826889 +:101F80000374054B1B6899689142FBD85A6803603B +:101F9000426010605860704738280020054B19696E +:101FA00008741868026853601A601861012303748A +:101FB000FEF710BA382800204B1C30B5044687B015 +:101FC0000A4D10D02B6901A8094A00F025F92046D6 +:101FD000FFF7E4FF049B13B101A800F059F92B6946 +:101FE000586907B030BDFFF7D9FFF8E7382800205F +:101FF000451F000838B50C4D044641612B698168C6 +:102000009A68914203D8BDE83840FFF78BBF184665 +:10201000FFF7B4FF01232C61014623742046BDE87D +:102020003840FEF7D7B900BF38280020044B1A68A3 +:102030001B6990689B68984294BF002001207047FC +:102040003828002010B5084C236820691A685460AD +:102050002260012223611A74FFF790FF0146206974 +:10206000BDE81040FEF7B6B93828002008B5FFF7E4 +:10207000DDFF18B1BDE80840FFF7E4BF08BD000070 +:10208000FFF7E0BFFEE7000010B50C4CFFF742FF82 +:1020900000F0B4F880220A49204600F03BF8012302 +:1020A00044F8180C037400F0A1FC002383F311889A +:1020B00062B60448BDE8104000F04CB8602800202B +:1020C0008C4100089C41000800F01CB9EFF311801E +:1020D00020B9EFF30583202282F3118870470000B6 +:1020E00010B530B9EFF30584C4F3080414B180F3DC +:1020F000118810BDFFF7BAFF84F31188F9E70000DB +:10210000034A516853685B1A9842FBD8704700BF76 +:10211000001000E082600222028270478368A3F10F +:102120007C0243F80C2C026943F83C2C426943F8CA +:10213000382C074A43F81C2CC268A3F1180043F856 +:10214000102C022203F8082C002203F8072C7047F9 +:10215000ED03000810B5202383F31188FFF7DEFF9D +:1021600000210446FFF746FF002383F31188204631 +:1021700010BD0000024B1B6958610F20FFF70EBF16 +:1021800038280020202383F31188FFF7F3BF0000D5 +:1021900008B50146202383F311880820FFF70CFFC0 +:1021A000002383F3118808BD49B1064B42681B69BF +:1021B00018605A60136043600420FFF7FDBE4FF0C3 +:1021C000FF307047382800200368984206D01A680C +:1021D0000260506018465961FFF7A4BE70470000C6 +:1021E00038B504460D462068844200D138BD0368E6 +:1021F00023605C604561FFF795FEF4E7054B4FF007 +:10220000FF3103F11402C3E905220022C3E90712DA +:10221000704700BF3828002070B51C4E05460C469C +:10222000C0E9032301F0BAFB334653F8142F9A4256 +:102230000DD130620A2C2CBF00190A302A60C5E982 +:102240000124C6E90555BDE8704001F091BB316A33 +:10225000431AE31838BF1C469368A34202D90819F1 +:1022600001F096FB73699A6894420CD85A68AC6086 +:102270002B606A6015609A685D60121B9A604FF06F +:10228000FF33F36170BDA41A1B68ECE73828002007 +:1022900038B51B4C636998420DD08168D0E9003293 +:1022A00013605A600022C2609A680A449A604FF034 +:1022B000FF33E36138BD03682246002142F8143F32 +:1022C00093425A60C16003D1BDE8384001F05ABB67 +:1022D0009A688168256A0A449A6001F05FFB636925 +:1022E000411B9A688A42E5D9AB181D1A206A092D4C +:1022F00098BF01F10A02BDE83840104401F048BB24 +:10230000382800202DE9F041184C002704F114066C +:10231000656901F043FB236AAA68C11A8A4215D88D +:102320001344D5F80C802362D5E9003213605A605B +:102330006369EF60B34201D101F024FB87F3118898 +:102340002869C047202383F31188E1E76169B1421E +:1023500009D013441B1ABDE8F0410A2B2CBFC0184A +:102360000A3001F015BBBDE8F08100BF382800201D +:1023700000207047FEE70000704700004FF0FF307C +:102380007047000002290CD0032904D00129074816 +:1023900018BF00207047032A05D8054800EBC2008B +:1023A0007047044870470020704700BF7C42000817 +:1023B0003C2200203042000870B59AB0054608461D +:1023C000144601A900F0C2F801A8FEF767FD431CFE +:1023D0000022C6B25B001046C5E900342370032317 +:1023E000023404F8013C01ABD1B202348E4201D870 +:1023F0001AB070BD13F8011B013204F8010C04F887 +:10240000021CF1E708B5202383F311880348FFF786 +:1024100067FA002383F3118808BD00BFF02900206C +:1024200090F8803003F01F02012A07D190F8812034 +:102430000B2A03D10023C0E91D3315E003F060032C +:10244000202B08D1B0F884302BB990F88120212AB4 +:1024500003D81F2A04D8FFF725BA222AEBD0FAE7BF +:10246000034A426707228267C3670120704700BFA3 +:102470003322002007B5052917D8DFE801F0191627 +:1024800003191920202383F31188104A0121019098 +:10249000FFF7CEFA019802210D4AFFF7C9FA0D485D +:1024A000FFF7EAF9002383F3118803B05DF804FB1A +:1024B000202383F311880748FFF7B4F9F2E72023BC +:1024C00083F311880348FFF7CBF9EBE7D04100080D +:1024D000F4410008F029002038B50C4D0C4C2A4678 +:1024E0000C4904F10800FFF767FF05F1CA0204F187 +:1024F00010000949FFF760FF05F5CA7204F11800E2 +:102500000649BDE83840FFF757BF00BFC84200206A +:102510003C220020B4410008BC410008C74100082B +:1025200070B5044608460D46FEF7B8FCC6B2204614 +:10253000013403780BB9184670BD32462946FEF7C0 +:1025400099FC0028F3D10120F6E700002DE9F84FAF +:1025500005460C46FEF7A2FC2A49C6B22846FFF7FC +:10256000DFFF08B10136F6B227492846FFF7D8FF4A +:1025700008B11036F6B2632E0DD8DFF88890DFF878 +:1025800088A0224FDFF88CB0DFF88C802E7846B917 +:102590002670BDE8F88F29462046BDE8F84F01F0C7 +:1025A000A1BD252E2AD1072249462846FEF762FC06 +:1025B00050B9D8F800300735083444F8083CD8F84A +:1025C000043044F8043CE1E7082251462846FEF76F +:1025D00051FC98B9A21C0E4B197802320909C95D49 +:1025E00002F8041C13F8011B01F00F015B45C95DE3 +:1025F00002F8031CF0D118340835C7E7013504F898 +:10260000016BC3E79C420008C7410008AD420008C7 +:1026100000E8F11F0CE8F11FA4420008BFF34F8F40 +:10262000044B1A695107FCD1D3F810215207F8D195 +:10263000704700BF0020005208B50D4B1B78ABB9A6 +:10264000FFF7ECFF0B4BDA68D10704D50A4A5A6052 +:1026500002F188325A60D3F80C21D20706D5064A17 +:10266000C3F8042102F18832C3F8042108BD00BF79 +:1026700026450020002000522301674508B5114B74 +:102680001B78F3B9104B1A69510703D5DA6842F089 +:102690004002DA60D3F81021520705D5D3F80C2197 +:1026A00042F04002C3F80C21FFF7B8FF064BDA688E +:1026B00042F00102DA60D3F80C2142F00102C3F8C3 +:1026C0000C2108BD26450020002000520F289ABF8B +:1026D00000F5806040040020704700004FF4003097 +:1026E00070470000102070470F2808B50BD8FFF77F +:1026F000EDFF00F500330268013204D1043083425B +:10270000F9D1012008BD0020FCE700000F2870B5BA +:10271000054645D8FFF7DAFC224CFFF77FFF064657 +:10272000FFF78AFF4FF0FF33072D6361C4F81431C0 +:1027300020D82361FFF772FF2B0243F02403E360EC +:10274000E36843F08003E36023695A07FCD428461A +:10275000FFF764FF4FF40031FFF7B8FF00F002F914 +:102760003046FFF78BFFFFF7BBFC2846BDE8704003 +:10277000FFF7BABFC4F81031FFF750FFA5F1080307 +:102780001B0243F02403C4F80C31D4F80C3143F09D +:102790008003C4F80C31D4F810315B07FBD4D6E7C2 +:1027A000002070BD002000522DE9F84F40EA0203DE +:1027B00005460C461746D80602D00020BDE8F88F23 +:1027C00027F01F07DFF8D4B0FFF736FF2744BC42DD +:1027D00003D10120FFF752FFF0E7202229462046CF +:1027E00001F070FC10B920352034F0E72B4605F1DC +:1027F00020021E68711CE0D104339A42F9D1FFF720 +:1028000065FC05F17843234AB3F5801F224B28BFAE +:102810009A4603F1040338BF9046A2F1080228BF8C +:102820009846A3F108033ABF9146DA469946FFF766 +:10283000F5FEC8F80060A5EB040CD9F8002004F1FF +:102840001C0142F00202C9F80020221FDAF80060E1 +:1028500016F00506FAD152F8043F8A424CF80230CD +:10286000F4D1BFF34F8FFFF7D9FE4FF0FF32C8F816 +:102870000020D9F8002022F00202C9F80020FFF75A +:102880002FFC20222146284601F01CFC0028AAD05B +:1028900030469FE7142000521021005210200052B1 +:1028A00010B5084C237828B11BB9FFF7C5FE0123EA +:1028B000237010BD002BFCD02070BDE81040FFF746 +:1028C000DDBE00BF264500200244074BD2B210B542 +:1028D000904200D110BD441C00B253F8200041F8D2 +:1028E000040BE0B2F4E700BF504000580E4B30B587 +:1028F0001C6F240405D41C6F1C671C6F44F4004437 +:102900001C670A4C02442368D2B243F480732360EC +:10291000074B904200D130BD441C51F8045B00B21B +:1029200043F82050E0B2F4E700440258004802584F +:102930005040005807B5012201A90020FFF7C4FF4D +:10294000019803B05DF804FB13B50446FFF7F2FFEE +:10295000A04205D0012201A900200194FFF7C6FF83 +:1029600002B010BD0144BFF34F8F064B884204D321 +:10297000BFF34F8FBFF36F8F7047C3F85C022030F7 +:10298000F4E700BF00ED00E0034B1A681AB9034AF0 +:10299000D2F8D0241A607047284500200040025821 +:1029A00008B5FFF7F1FF024B1868C0F3806008BD5F +:1029B00028450020CAB201460120FFF797BF00005A +:1029C000CAB201460120FFF77FBF0000EFF3098381 +:1029D000054968334A6B22F001024A6383F3098890 +:1029E000002383F31188704700EF00E0202080F37C +:1029F000118862B60D4B0E4AD96821F4E0610904D2 +:102A0000090C0A430B49DA60D3F8FC2042F08072CB +:102A1000C3F8FC20084AC2F8B01F116841F0010158 +:102A200011601022DA7783F82200704700ED00E091 +:102A30000003FA0555CEACC5001000E0202310B508 +:102A400083F311880E4B5B6813F4006314D0F1EE2E +:102A5000103AEFF309844FF08073683CE361094B4F +:102A6000DB6B236684F30988FFF7E0FA10B1064BAD +:102A7000A36110BD054BFBE783F31188F9E700BFA5 +:102A800000ED00E000EF00E0FF0300080204000892 +:102A900070B5BFF34F8FBFF36F8F1A4A0021C2F892 +:102AA0005012BFF34F8FBFF36F8F536943F400335E +:102AB0005361BFF34F8FBFF36F8FC2F88410BFF322 +:102AC0004F8FD2F8803043F6E074C3F3C900C3F3EC +:102AD0004E335B0103EA0406014646EA817501397B +:102AE000C2F86052F9D2203B13F1200FF2D1BFF3AC +:102AF0004F8F536943F480335361BFF34F8FBFF35C +:102B00006F8F70BD00ED00E0FEE700000A4B0B4840 +:102B10000B4A90420BD30B4BC11EDA1C121A22F047 +:102B200003028B4238BF00220021FEF7BFB953F8E1 +:102B3000041B40F8041BECE78C440008FC46002012 +:102B4000FC460020FC4600207047000070B5D0E92C +:102B5000244300224FF0FF359E6804EB42135101DD +:102B6000D3F80009002805DAD3F8000940F08040C6 +:102B7000C3F80009D3F8000B002805DAD3F8000BDE +:102B800040F08040C3F8000B013263189642C3F84E +:102B90000859C3F8085BE0D24FF00113C4F81C38A1 +:102BA00070BD000000EB8103D3F80CC02DE9F043A9 +:102BB000DCF814204E1CD0F89050D2F800E005EB61 +:102BC000063605EB4118506870450AD30122D5F846 +:102BD000343802FA01F123EA0101C5F83418BDE8DE +:102BE000F083AEEB0003BCF81040A34228BF23469D +:102BF000D8F81849A4B2B3EB840FF0D89468A4F1C4 +:102C0000040959F8047F3760A4EB09071F44042F17 +:102C1000F7D81C44034494605360D4E7890141F021 +:102C20002001016103699B06FCD41220FFF768BAFA +:102C300010B50A4C2046FEF7D9FE094BC4F8903077 +:102C4000084BC4F89430084C2046FEF7CFFE074BE3 +:102C5000C4F89030064BC4F8943010BD2C450020C9 +:102C600000000840E4420008C8450020000004407D +:102C7000F042000870B503780546012B5DD1494B41 +:102C8000D0F89040984259D1474B0E216520D3F897 +:102C9000D82042F00062C3F8D820D3F8002142F0D7 +:102CA0000062C3F80021D3F80021D3F8802042F05D +:102CB0000062C3F88020D3F8802022F00062C3F8BD +:102CC0008020D3F8803000F071FC384BE360384B43 +:102CD000C4F800380023D5F89060C4F8003EC02343 +:102CE00023604FF40413A3633369002BFCDA012340 +:102CF0000C203361FFF704FA3369DB07FCD41220A0 +:102D0000FFF7FEF93369002BFCDA00262846A6609F +:102D1000FFF71CFF6B68C4F81068DB68C4F8146820 +:102D2000C4F81C68002B3AD1224BA3614FF0FF334B +:102D30006361A36843F00103A36070BD1E4B98421A +:102D4000C8D1194B0E214D20D3F8D82042F0007283 +:102D5000C3F8D820D3F8002142F00072C3F8002154 +:102D6000D3F80021D3F8802042F00072C3F880200D +:102D7000D3F8802022F00072C3F88020D3F880209E +:102D8000D3F8D82022F08062C3F8D820D3F80021ED +:102D900022F08062C3F80021D3F8003193E7074B9B +:102DA000C3E700BF2C4500200044025840140040F7 +:102DB00003002002003C30C0C8450020083C30C061 +:102DC000F8B5D0F89040054600214FF00066204647 +:102DD000FFF724FFD5F8941000234FF001128F68FD +:102DE0004FF0FF30C4F83438C4F81C2804EB431209 +:102DF00001339F42C2F80069C2F8006BC2F80809AB +:102E0000C2F8080BF2D20B68D5F89020C5F89830BC +:102E1000636210231361166916F01006FBD11220AD +:102E2000FFF76EF9D4F8003823F4FE63C4F80038D5 +:102E3000A36943F4402343F01003A3610923C4F8BA +:102E40001038C4F814380B4BEB604FF0C043C4F893 +:102E5000103B094BC4F8003BC4F81069C4F80039B2 +:102E6000D5F8983003F1100243F48013C5F8982088 +:102E7000A362F8BDC042000840800010D0F8902046 +:102E800090F88A10D2F8003823F4FE6343EA011365 +:102E9000C2F80038704700002DE9F84300EB8103C9 +:102EA000D0F890500C468046DA680FFA81F9480154 +:102EB000166806F00306731E022B05EB41134FF054 +:102EC000000194BFB604384EC3F8101B4FF0010147 +:102ED00004F1100398BF06F1805601FA03F39169DB +:102EE00098BF06F5004600293AD0578A04F15801E8 +:102EF000374349016F50D5F81C180B430021C5F822 +:102F00001C382B180127C3F81019A7405369611EFC +:102F10009BB3138A928B9B08012A88BF5343D8F82E +:102F20009820981842EA034301F140022146C8F86C +:102F30009800284605EB82025360FFF76FFE08EB0E +:102F40008900C3681B8A43EA845348341E436401E2 +:102F50002E51D5F81C381F43C5F81C78BDE8F883FE +:102F600005EB4917D7F8001B21F40041C7F8001BF7 +:102F7000D5F81C1821EA0303C0E704F13F030B4A0C +:102F80002846214605EB83035A60FFF747FE05EB11 +:102F90004910D0F8003923F40043C0F80039D5F8BF +:102FA0001C3823EA0707D7E700800010000400025E +:102FB000D0F894201268C0F89820FFF7C7BD000031 +:102FC0005831D0F8903049015B5813F4004004D0D8 +:102FD00013F4001F0CBF0220012070474831D0F8C5 +:102FE000903049015B5813F4004004D013F4001FE3 +:102FF0000CBF02200120704700EB8101CB68196AE9 +:103000000B6813604B6853607047000000EB81034E +:1030100030B5DD68AA691368D36019B9402B84BF45 +:10302000402313606B8A1468D0F890201C4402EB94 +:103030004110013C09B2B4FBF3F46343033323F0C2 +:10304000030343EAC44343F0C043C0F8103B2B687A +:1030500003F00303012B0ED1D2F8083802EB411024 +:1030600013F4807FD0F8003B14BF43F0805343F04B +:103070000053C0F8003B02EB4112D2F8003B43F092 +:103080000443C2F8003B30BD2DE9F041D0F8906018 +:1030900005460C4606EB4113D3F8087B3A07C3F804 +:1030A000087B08D5D6F814381B0704D500EB81033C +:1030B000DB685B689847FA071FD5D6F81438DB073A +:1030C0001BD505EB8403D968CCB98B69488A5A684B +:1030D000B2FBF0F600FB16228AB91868DA68904253 +:1030E0000DD2121AC3E90024202383F3118821464C +:1030F0002846FFF78BFF84F31188BDE8F081012398 +:1031000003FA04F26B8923EA02036B81CB68002B7C +:10311000F3D021462846BDE8F041184700EB810373 +:103120004A0170B5DD68D0F890306C692668E660B9 +:1031300056BB1A444FF40020C2F810092A6802F066 +:103140000302012A0AB20ED1D3F8080803EB421495 +:1031500010F4807FD4F8000914BF40F0805040F094 +:103160000050C4F8000903EB4212D2F8000940F005 +:103170000440C2F800090122D3F8340802FA01F130 +:103180000143C3F8341870BD19B9402E84BF4020E4 +:10319000206020681A442E8A8419013CB4FBF6F49E +:1031A00040EAC44040F00050C6E700002DE9F0417D +:1031B000D0F8906004460D4606EB4113D3F8087929 +:1031C000C3F80879FB071CD5D6F81038DA0718D5EC +:1031D00000EB8103D3F80CC0DCF81430D3F800E026 +:1031E000DA6896451BD2A2EB0E024FF000081A6077 +:1031F000C3F80480202383F31188FFF78FFF88F33F +:1032000011883B0618D50123D6F83428AB40134269 +:1032100012D029462046BDE8F041FFF7C3BC012388 +:1032200003FA01F2038923EA02030381DCF8083080 +:10323000002BE6D09847E4E7BDE8F0812DE9F84F90 +:10324000D0F8905004466E69AB691E4016F4805861 +:103250006E6103D0BDE8F84FFEF738BC002E12DADD +:10326000D5F8003E9F0705D0D5F8003E23F00303B4 +:10327000C5F8003ED5F80438204623F00103C5F810 +:103280000438FEF74FFC300505D52046FFF75EFCFD +:103290002046FEF737FCB1040CD5D5F8083813F0FA +:1032A000060FEB6823F470530CBF43F4105343F440 +:1032B000A053EB60320704D56368DB680BB120468E +:1032C0009847F30200F1BA80B70226D5D4F890905F +:1032D00000274FF0010A09EB4712D2F8003B03F434 +:1032E0004023B3F5802F11D1D2F8003B002B0DDA2B +:1032F00062890AFA07F322EA0303638104EB870376 +:10330000DB68DB6813B13946204698470137D4F8AB +:103310009430FFB29B689F42DDD9F00619D5D4F8EE +:103320009000026AC2F30A1702F00F0302F4F012CF +:10333000B2F5802F00F0CC80B2F5402F09D104EB1C +:103340008303002200F58050DB681B6A974240F03F +:10335000B2803003D5F8185835D5E90303D50021DC +:103360002046FFF791FEAA0303D501212046FFF76F +:103370008BFE6B0303D502212046FFF785FE2F034A +:1033800003D503212046FFF77FFEE80203D5042181 +:103390002046FFF779FEA90203D505212046FFF755 +:1033A00073FE6A0203D506212046FFF76DFE2B024D +:1033B00003D507212046FFF767FEEF0103D508215B +:1033C0002046FFF761FE700340F1A980E90703D5AD +:1033D00000212046FFF7EAFEAA0703D50121204677 +:1033E000FFF7E4FE6B0703D502212046FFF7DEFE60 +:1033F0002F0703D503212046FFF7D8FEEE0603D59D +:1034000004212046FFF7D2FEA80603D50521204659 +:10341000FFF7CCFE690603D506212046FFF7C6FE5E +:103420002A0603D507212046FFF7C0FEEB0576D517 +:1034300020460821BDE8F84FFFF7B8BED4F89090B9 +:1034400000274FF0010AD4F894305FFA87FB9B689D +:103450009B453FF639AF09EB4B13D3F8002902F433 +:103460004022B2F5802F24D1D3F80029002A20DA97 +:10347000D3F8002942F09042C3F80029D3F800297C +:10348000002AFBDB5946D4F89000FFF7C7FB2289DE +:103490000AFA0BF322EA0303238104EB8B03DB68B4 +:1034A0009B6813B159462046984759462046FFF776 +:1034B00079FB0137C7E7910701D1D0F80080072ACF +:1034C00002F101029CBF03F8018B4FEA18283DE787 +:1034D00004EB830300F58050DA68D2F818C0DCF8FA +:1034E0000820DCE9001CA1EB0C0C00218F4208D164 +:1034F000DB689B699A683A449A605A683A445A6011 +:1035000027E711F0030F01D1D0F800808C4501F1BD +:10351000010184BF02F8018B4FEA1828E6E7BDE8F5 +:10352000F88F000008B50348FFF788FEBDE80840A3 +:10353000FFF784BA2C45002008B50348FFF77EFE4C +:10354000BDE80840FFF77ABAC8450020D0F89030AF +:1035500003EB4111D1F8003B43F40013C1F8003BE9 +:1035600070470000D0F8903003EB4111D1F80039DA +:1035700043F40013C1F8003970470000D0F89030D0 +:1035800003EB4111D1F8003B23F40013C1F8003BD9 +:1035900070470000D0F8903003EB4111D1F80039AA +:1035A00023F40013C1F8003970470000090100F14D +:1035B0006043012203F56143C9B283F8001300F0B0 +:1035C0001F039A4043099B0003F1604303F56143E5 +:1035D000C3F880211A60704730B50433039C017230 +:1035E000002104FB0325C160C0E90653049B03636B +:1035F000059BC0E90000C0E90422C0E90842C0E917 +:103600000A11436330BD00000022416AC260C0E974 +:103610000411C0E90A226FF00101FEF7E1BD0000CC +:10362000D0E90432934201D1C2680AB9181D70472B +:1036300000207047036919600021C2680132C2602E +:10364000C269134482699342036124BF436A0361E0 +:10365000FEF7BABD38B504460D46E3683BB1626972 +:103660000020131D1268A3621344E36207E0237A6B +:1036700033B929462046FEF797FD0028EDDA38BD1C +:103680006FF00100FBE70000C368C269013BC36043 +:103690004369134482699342436124BF436A43618F +:1036A00000238362036B03B11847704770B5202372 +:1036B000044683F31188866A3EB9FFF7CBFF0546BF +:1036C00018B186F31188284670BDA36AE26A13F820 +:1036D000015B9342A36202D32046FFF7D5FF00238C +:1036E00083F31188EFE700002DE9F84F04460E46FA +:1036F000174698464FF0200989F311880025AA46FD +:10370000D4F828B0BBF1000F09D141462046FFF79D +:10371000A1FF20B18BF311882846BDE8F88FD4E9CA +:103720000A12A7EB050B521A934528BF9346BBF12B +:10373000400F1BD9334601F1400251F8040B91426E +:1037400043F8040BF9D1A36A403640354033A362F5 +:10375000D4E90A239A4202D32046FFF795FF8AF361 +:103760001188BD42D8D289F31188C9E730465A463C +:10377000FDF776FBA36A5E445D445B44A362E7E722 +:1037800010B5029C0433017204FB0321C460C0E93C +:1037900006130023C0E90A33039B0363049BC0E9BB +:1037A0000000C0E90422C0E90842436310BD0000E4 +:1037B000026A6FF00101C260426AC0E9042200227D +:1037C000C0E90A22FEF70CBDD0E904239A4201D1D8 +:1037D000C26822B9184650F8043B0B6070470020BD +:1037E00070470000C3680021C2690133C3604369A8 +:1037F000134482699342436124BF436A4361FEF7E5 +:10380000E3BC000038B504460D46E3683BB12369CC +:1038100000201A1DA262E2691344E36207E0237AE2 +:1038200033B929462046FEF7BFFC0028EDDA38BD43 +:103830006FF00100FBE7000003691960C268013AFC +:10384000C260C269134482699342036124BF436A20 +:10385000036100238362036B03B1184770470000C4 +:1038600070B520230D460446114683F31188866AFD +:103870002EB9FFF7C7FF10B186F3118870BDA36A98 +:103880001D70A36AE26A01339342A36204D3E16923 +:1038900020460439FFF7D0FF002080F31188EDE7C0 +:1038A0002DE9F84F04460D46904699464FF0200A00 +:1038B0008AF311880026B346A76A4FB949462046C5 +:1038C000FFF7A0FF20B187F311883046BDE8F88FDD +:1038D000D4E90A073A1AA8EB0607974228BF174609 +:1038E000402F1BD905F1400355F8042B9D4240F8A9 +:1038F000042BF9D1A36A40364033A362D4E90A23EA +:103900009A4204D3E16920460439FFF795FF8BF30F +:1039100011884645D9D28AF31188CDE729463A461F +:10392000FDF79EFAA36A3D443E443B44A362E5E7AB +:10393000D0E904239A4217D1C3689BB1836A8BB143 +:10394000043B9B1A0ED01360C368013BC360C3697C +:103950001A4483699A42026124BF436A03610023C7 +:1039600083620123184670470023FBE700F0DAB8B2 +:10397000034B002258631A610222DA60704700BFCD +:10398000000C0040014B0022DA607047000C004040 +:10399000014B5863704700BF000C0040014B586A50 +:1039A000704700BF000C00404B6843608B68836029 +:1039B000CB68C3600B6943614B6903628B694362E7 +:1039C0000B6803607047000008B53C4B40F2FF7184 +:1039D0003B48D3F888200A43C3F88820D3F88820CE +:1039E00022F4FF6222F00702C3F88820D3F888206F +:1039F000D3F8E0200A43C3F8E020D3F808210A43B3 +:103A0000C3F808212F4AD3F808311146FFF7CCFF3D +:103A100000F5806002F11C01FFF7C6FF00F5806031 +:103A200002F13801FFF7C0FF00F5806002F1540198 +:103A3000FFF7BAFF00F5806002F17001FFF7B4FFF5 +:103A400000F5806002F18C01FFF7AEFF00F58060A9 +:103A500002F1A801FFF7A8FF00F5806002F1C401A0 +:103A6000FFF7A2FF00F5806002F1E001FFF79CFF85 +:103A700000F5806002F1FC01FFF796FF02F58C7102 +:103A800000F58060FFF790FF00F000F90E4BD3F8CF +:103A9000902242F00102C3F89022D3F8942242F01F +:103AA0000102C3F894220522C3F898204FF0605217 +:103AB000C3F89C20054AC3F8A02008BD0044025862 +:103AC00000000258FC42000800ED00E01F0008035F +:103AD00008B500F0D7FAFEF7D7FA0F4BD3F8DC2081 +:103AE00042F04002C3F8DC20D3F8042122F0400267 +:103AF000C3F80421D3F80431084B1A6842F00802D5 +:103B00001A601A6842F004021A60FEF73DFFBDE831 +:103B10000840FEF7E1BC00BF00440258001802480C +:103B200070470000114BD3F8E82042F00802C3F8B8 +:103B3000E820D3F8102142F00802C3F810210C4A03 +:103B4000D3F81031D36B43F00803D363C722094B7A +:103B50009A624FF0FF32DA6200229A615A63DA60A9 +:103B60005A6001225A611A60704700BF004402582F +:103B70000010005C000C0040094A08B51169D368C8 +:103B80000B40D9B29B076FEA0101116107D52023D1 +:103B900083F31188FEF798FA002383F3118808BD98 +:103BA000000C0040384B4FF0FF31D3F88020C3F8B1 +:103BB0008010D3F880200022C3F88020D3F8800042 +:103BC000D3F88400C3F88410D3F88400C3F88420A9 +:103BD000D3F88400D86F40F0FF4040F4FF0040F479 +:103BE0003F5040F03F00D867D86F20F0FF4020F4EE +:103BF000FF0020F43F5020F03F00D867D86FD3F883 +:103C000088006FEA40506FEA5050C3F88800D3F83C +:103C10008800C0F30A00C3F88800D3F88800D3F8FE +:103C20009000C3F89010D3F89000C3F89020D3F818 +:103C30009000D3F89400C3F89410D3F89400C3F81C +:103C40009420D3F89400D3F89800C3F89810D3F8D0 +:103C50009800C3F89820D3F89800D3F88C00C3F8E4 +:103C60008C10D3F88C00C3F88C20D3F88C00D3F8D8 +:103C70009C00C3F89C10D3F89C10C3F89C20D3F888 +:103C80009C3000F0D3B900BF00440258614B0122C0 +:103C9000C3F80821604BD3F8F42042F00202C3F8C5 +:103CA000F420D3F81C2142F00202C3F81C210222A6 +:103CB000D3F81C31594BDA605A689104FCD5584A44 +:103CC0001A6001229A60574ADA6000221A614FF4A2 +:103CD00040429A61514B9A699204FCD51A6842F4A9 +:103CE00080721A604C4B1A6F12F4407F04D04FF46C +:103CF00080321A6700221A671A6842F001021A60BD +:103D0000454B1A685007FCD500221A611A6912F057 +:103D10003802FBD1012119604FF0804159605A6788 +:103D2000414ADA62414A1A611A6842F480321A60E2 +:103D3000394B1A689103FCD51A6842F480521A6014 +:103D40001A689204FCD53A4A3A499A6200225A63A8 +:103D500019633949DA6399635A64384A1A64384AEC +:103D6000DA621A6842F0A8521A602B4B1A6802F005 +:103D70002852B2F1285FF9D148229A614FF4886243 +:103D8000DA6140221A622F4ADA644FF080521A65D3 +:103D90002D4A5A652D4A9A6532232D4A13601368BD +:103DA00003F00F03022BFAD11B4B1A6942F00302F6 +:103DB0001A611A6902F03802182AFAD1D3F8DC2005 +:103DC00042F00052C3F8DC20D3F8042142F0005244 +:103DD000C3F80421D3F80421D3F8DC2042F0804258 +:103DE000C3F8DC20D3F8042142F08042C3F8042158 +:103DF000D3F80421D3F8DC2042F00042C3F8DC20E1 +:103E0000D3F8042142F00042C3F80421D3F804316E +:103E1000704700BF0080005100440258004802581B +:103E200000C000F0020000010000FF0100889008BF +:103E300022204000630209012C0204004704050807 +:103E4000FD0BFF01200000200010E0000001010038 +:103E5000002000524FF0B04208B5D2F8883003F08D +:103E60000103C2F8883023B1044A13680BB15068CB +:103E70009847BDE80840FEF7E1BD00BF7C46002042 +:103E80004FF0B04208B5D2F8883003F00203C2F810 +:103E9000883023B1044A93680BB1D0689847BDE8D5 +:103EA0000840FEF7CBBD00BF7C4600204FF0B0427B +:103EB00008B5D2F8883003F00403C2F8883023B183 +:103EC000044A13690BB150699847BDE80840FEF7F2 +:103ED000B5BD00BF7C4600204FF0B04208B5D2F817 +:103EE000883003F00803C2F8883023B1044A93698C +:103EF0000BB1D0699847BDE80840FEF79FBD00BFF1 +:103F00007C4600204FF0B04208B5D2F8883003F06C +:103F10001003C2F8883023B1044A136A0BB1506A07 +:103F20009847BDE80840FEF789BD00BF7C460020E9 +:103F30004FF0B04310B5D3F8884004F47872C3F85A +:103F40008820A30604D5124A936A0BB1D06A984719 +:103F5000600604D50E4A136B0BB1506B98472106CF +:103F600004D50B4A936B0BB1D06B9847E20504D58F +:103F7000074A136C0BB1506C9847A30504D5044A4B +:103F8000936C0BB1D06C9847BDE81040FEF756BD5E +:103F90007C4600204FF0B04310B5D3F8884004F4BD +:103FA0007C42C3F88820620504D5164A136D0BB114 +:103FB000506D9847230504D5124A936D0BB1D06D0F +:103FC0009847E00404D50F4A136E0BB1506E984722 +:103FD000A10404D50B4A936E0BB1D06E98476204CE +:103FE00004D5084A136F0BB1506F9847230404D5CA +:103FF000044A936F0BB1D06F9847BDE81040FEF7AD +:104000001DBD00BF7C46002008B50348FDF700F940 +:10401000BDE80840FEF712BDCC23002008B5FFF72D +:10402000ABFDBDE80840FEF709BD0000062108B55C +:104030000846FFF7BBFA06210720FFF7B7FA06216B +:104040000820FFF7B3FA06210920FFF7AFFA06218F +:104050000A20FFF7ABFA06211720FFF7A7FA06217F +:104060002820FFF7A3FA09217A20FFF79FFA0721FA +:104070003220FFF79BFA0C215220BDE80840FFF7E1 +:1040800095BA000008B5FFF78DFD00F00DF8FDF7BB +:10409000D1FAFDF7A9FCFDF77BFBFFF741FDBDE879 +:1040A0000840FFF763BC00000023054A19460133AE +:1040B000102BC2E9001102F10802F8D1704700BFCD +:1040C0007C46002010B501390244904201D1002005 +:1040D00005E0037811F8014FA34201D0181B10BD71 +:1040E0000130F2E7034611F8012B03F8012B002AF7 +:1040F000F9D1704753544D333248373F3F3F005357 +:10410000544D3332483734332F37353300000000F5 +:10411000F0290020CC2300200096000000000000C1 +:10412000000000000000000000000000000000008F +:1041300000000000FD150008E9150008251600081C +:10414000111600081D16000809160008F5150008CC +:10415000E115000831160008000000000D170008E6 +:10416000F916000835170008211700082D17000858 +:104170001917000805170008F11600084117000874 +:104180000000000001000000000000006D61696E89 +:104190000000000069646C650000000094410008A4 +:1041A00078280020F0290020010000008520000868 +:1041B00000000000486F6C7962726F0025424F4129 +:1041C0005244252D424C002553455249414C25006F +:1041D00002000000000000002D1900089D190008D1 +:1041E0004000400098420020A84200200200000049 +:1041F000000000000300000000000000E5190008B6 +:104200000000000010000000B84200200000000084 +:1042100001000000000000002C4500200101020008 +:1042200075240008852300082124000805240008BF +:10423000430000003842000809024300020100C0A8 +:1042400032090400000102020100052400100105EA +:10425000240100010424020205240600010705824E +:10426000030800FF09040100020A0000000705011D +:10427000024000000705810240000000120000001B +:1042800084420008120110010200004062314B001C +:1042900000020102030100000403090425424F410A +:1042A00052442500447572616E64616C0030313295 +:1042B00033343536373839414243444546000000EF +:1042C00000000000391B0008F11D00089D1E0008B9 +:1042D00040004000644600206446002001000000C9 +:1042E000744600208000000040010000080000002B +:1042F0000001000000040000080000000000802A07 +:1043000000000000AAAAAAAA00000024FFFF0000E3 +:104310000000000000A00A000400000000000000EF +:10432000AAAAAAAA00000000FDFF000000000000E9 +:10433000000000000050000000000000AAAAAAAA85 +:10434000000000003FFF000000000000000000002F +:104350000000000000000000AAAAAAAA00000000B5 +:10436000FFFF000000000000000000000004020049 +:1043700000000000AAAAAAAA00080100DFFF0000AE +:1043800000000000070000005025100000000000A1 +:104390000AA2AAAA50151000FFFF000000000007A3 +:1043A000000000000000100000000000AAAAAAAA55 +:1043B00000001000FFFF00000000000000000000EF +:1043C0000004000000000000AAAAAAAA000400003D +:1043D000FFFF00000000000000000000005111007D +:1043E00000000000AAAAAAAA00511100FFFF0000C5 +:1043F00000000000000000000000000000000000BD +:10440000AAAAAAAA00000000FFFF00000000000006 +:10441000000000000000000000000000AAAAAAAAF4 +:1044200000000000FFFF000000000000000000008E +:104430008B0000000000000000001E0000000000D3 +:10444000FF00000000000000F44000083F000000F2 +:1044500050040000FF4000083F00000000960000EC +:1044600000000800960000000008000004000000A2 +:10447000984200080000000000000000000000005A +:0C44800000000000000000000000000030 :00000001FF diff --git a/Tools/bootloaders/FlyingMoonF407_bl.bin b/Tools/bootloaders/FlyingMoonF407_bl.bin new file mode 100755 index 00000000000..7506663e95d Binary files /dev/null and b/Tools/bootloaders/FlyingMoonF407_bl.bin differ diff --git a/Tools/bootloaders/FlyingMoonF427_bl.bin b/Tools/bootloaders/FlyingMoonF427_bl.bin new file mode 100755 index 00000000000..3b3eef5e5d4 Binary files /dev/null and b/Tools/bootloaders/FlyingMoonF427_bl.bin differ diff --git a/Tools/bootloaders/FlywooF745Nano_bl.bin b/Tools/bootloaders/FlywooF745Nano_bl.bin old mode 100644 new mode 100755 index b8c9213a9af..2db555e4153 Binary files a/Tools/bootloaders/FlywooF745Nano_bl.bin and b/Tools/bootloaders/FlywooF745Nano_bl.bin differ diff --git a/Tools/bootloaders/FlywooF745Nano_bl.hex b/Tools/bootloaders/FlywooF745Nano_bl.hex index 3f87fab8630..7613e3d8726 100644 --- a/Tools/bootloaders/FlywooF745Nano_bl.hex +++ b/Tools/bootloaders/FlywooF745Nano_bl.hex @@ -1,25 +1,25 @@ :020000040800F2 -:1000000000060120010200080D0F0008110F000872 -:10001000690F0008110F00083D0F000803020008D7 -:100020000302000803020008030200080128000878 +:100000000006012001020008A90F0008290F0008BE +:10001000810F0008290F0008550F0008030200088F +:100020000302000803020008030200084928000830 :10003000030200080302000803020008030200088C :10004000030200080302000803020008030200087C -:100050000302000803020008A9390008D13900088A -:10006000F9390008213A0008493A0008030200085B +:100050000302000803020008BD390008E539000862 +:100060000D3A0008353A00085D3A0008030200081E :10007000030200080302000803020008030200084C :10008000030200080302000803020008030200083C -:10009000030200080302000803020008713A000886 +:10009000030200080302000803020008853A000872 :1000A000030200080302000803020008030200081C -:1000B000593B00080302000803020008030200087D +:1000B0006D3B000803020008030200080302000869 :1000C00003020008030200080302000803020008FC -:1000D00003020008453B0008030200080302000871 -:1000E000D53A0008030200080302000803020008D2 +:1000D00003020008593B000803020008030200085D +:1000E000E93A0008030200080302000803020008BE :1000F00003020008030200080302000803020008CC :1001000003020008030200080302000803020008BB :1001100003020008030200080302000803020008AB :10012000030200080302000803020008030200089B :10013000030200080302000803020008030200088B -:10014000030200080302000803020008E12F000870 +:100140000302000803020008030200080930000847 :10015000030200080302000803020008030200086B :10016000030200080302000803020008030200085B :10017000030200080302000803020008030200084B @@ -38,987 +38,988 @@ :10024000C0F2F0004EF68851CEF200010860BFF314 :100250004F8FBFF36F8F4FF00000E1EE100A4EF6A4 :100260003C71CEF200010860062080F31488BFF3D1 -:100270006F8F02F089FB02F029FB03F02BFA4FF09D +:100270006F8F02F0A9FB02F04BFB03F041FA4FF045 :1002800055301F491B4A91423CBF41F8040BFAE725 :100290001C49194A91423CBF41F8040BFAE71A493C :1002A0001A4A1B4B9A423EBF51F8040B42F8040B0A :1002B000F8E700201749184A91423CBF41F8040B67 -:1002C000FAE702F047FB03F06FFA144C144DAC420E +:1002C000FAE702F063FB03F07BFA144C144DAC42E6 :1002D00003DA54F8041B8847F9E700F041F8114CA1 :1002E000114DAC4203DA54F8041B8847F9E702F0D9 -:1002F0002FBB0000000601200022012000000008A2 -:100300000000012000060120783F000800220120A3 -:1003100064220120682201205430012000020008DC +:1002F0004BBB000000060120002201200000000886 +:100300000000012000060120883F00080022012093 +:1003100068220120682201205830012000020008D4 :100320000002000800020008000200082DE9F04F5A :100330002DED108AC1F80CD0D0F80CD0BDEC108A8D :10034000BDE8F08F002383F311882846A0470020E2 -:1003500001F072FEFEE701F0EFFD00DFFEE70000B6 -:1003600038B502F00FFA044602F044FA0546D8B94F -:100370000F4B9C421AD001339C4218BF054641F2F4 -:10038000883404BF01250024002002F005FA0DB1D5 -:1003900000F05AF800F062FD00F0FCFB204600F08F -:1003A000F5F800F051F8F9E70024EDE70446EBE733 -:1003B000010007B008B500F0B9FBA0F120035842D6 -:1003C000584108BD07B5054B02211B88ADF8043024 -:1003D00001A800F0C9FB03B05DF804FB043C000871 -:1003E00010B572B6202383F3118862B61248C36831 -:1003F0000BB101F0ABFE0023104A0F484FF47A71A5 -:1004000001F066FE002383F311880D4C236813B1BD -:100410002368013B2360636813B16368013B636039 -:10042000084B1B7833B9636823B9022000F084FCC1 -:100430003223636010BD00BF68220120E103000881 -:10044000842301207C2201202DE9F041454B4649BF -:1004500053F8042F013201D1BDE8F0818B42F7D16E -:10046000424C434B22689A427AD9424B9B6803F133 -:10047000006303F5C0339A4272D2002000F0A6FB5D -:100480003D4B0220187000F04DFC3C4B1A6C0022D2 -:100490001A64196E1A66196E596C5A64596E5A6646 -:1004A000596E596941F080015961596921F0800103 -:1004B00059615969196941F000511961196921F0AF -:1004C000005119611B6972B62D492E4B0B601D68D6 -:1004D0002468BFF34F8FBFF36F8F2B4BC3F884207B -:1004E000BFF34F8F5A6922F480325A61BFF34F8FA6 -:1004F000D3F88020C2F3C906C2F34E325201B707C7 -:1005000043F6E07E02EA0E0838463146013948EAF1 -:10051000000CB1F1FF3FC3F874C200F14040F5D1C7 -:10052000203A12F1200FEDD1BFF34F8FBFF36F8F41 -:10053000BFF34F8FBFF36F8F5A6922F400325A61B5 -:100540000022C3F85022BFF34F8FBFF36F8F72B6F4 -:10055000202383F3118862B6AD4685F308882047CF -:10056000BDE8F081FC7F01081C80010804800108BF -:10057000FF7F0108002201207C2201200038024078 -:1005800008ED00E00080010800ED00E02DE9F04FEB -:1005900099B0BA4D00902022FF2110A8AC6800F05D -:1005A000FFFBB74A01951378B3B9B6480121117022 -:1005B000C36072B6202383F3118862B6C3680BB19F -:1005C00001F0C4FD0023B04AAE484FF47A7101F047 -:1005D0007FFD002383F31188009BAC4A03B11360B5 -:1005E000AB4B009D029300261E705660B246374604 -:1005F000B146012000F096FB002D00F02582A34BB0 -:100600001B68002B40F0208219B0BDE8F08F02205B -:10061000FFF7D0FE002840F01082009B002E08BF9C -:100620001D469C4B02211B88ADF82C300BA800F016 -:100630009BFADEE74FF47A7000F078FAB0F1000828 -:10064000EBDB0220FFF7B6FE0028E6D008F1FF380A -:10065000B8F1040F00F2F381DFE808F0031E212453 -:10066000270018A8052340F8343D042100F07CFA47 -:10067000012303FA08F848EA0A0A5FFA8AFA4FF0F7 -:10068000000900F0E1FB27B10AF00B030B2B08BFB8 -:100690000025FFF797FEACE704217848E6E7042140 -:1006A0007D48E3E704217D48E0E74FF01C09484618 -:1006B00000F08EFA09F104090B9004210BA800F058 -:1006C00053FAB9F12C0FF2D1D2E7002FA5D00AF0DE -:1006D0000B030B2BA1D10220FFF76CFE80460028F4 -:1006E0009BD001206A4E00F071FA0220307000F0B9 -:1006F00019FB00275FFA87FB584600F077FA05469A -:1007000088B1584600F082FA01370028F2D14646F7 -:100710000025634B02211B88ADF82C300BA800F09C -:1007200023FA474665E701230220337000F0F0FA10 -:100730002C46019B9B689C4206D2204600F048FA5A -:100740000130E4D10434F4E7029B00241C704F4BC9 -:1007500046465C604746254693E7002F3FF45DAF71 -:100760000AF00B030B2B7FF458AF029B022018708A -:1007700000F0D8FA322000F0D9F9B0F1000BFFF602 -:100780004CAF1BF003087FF448AF019B996804EB62 -:100790000B028A423FF641AFBBF5807F3FF63DAF8B -:1007A000404A0392D8450FDA4FF47A7000F0BEF950 -:1007B000049004990029FFF630AF039A049908F8D1 -:1007C000021008F10108ECE7C820FFF7F3FD8046AE -:1007D00000283FF422AF1F2C11D8C4F120075F4539 -:1007E00028BF5F4610AB24F003003A462D49184459 -:1007F00000F0ACFA3A46FF212A4800F0D1FA4FEA5D -:10080000AB03DAB227490393204600F0D1FA07463A -:1008100000283FF47EAF039B04EB830431E7022002 -:10082000FFF7C8FD00283FF4F8AE00F015FA0028E5 -:100830003FF4F3AE4FF000084346019A92689045AA -:1008400032D2B8F11F0F12D8109A01320FD028F00F -:10085000030218A90A4452F8202C0B9218460422CD -:100860000BA900F095FB08F104080346E5E74046B4 -:10087000039300F0ADF9039B0B90EFE700220120FA -:100880008023012068220120E10300088423012045 -:100890007C220120063C00080422012008220120BD -:1008A000083C00088022012018A8042140F84C3D93 -:1008B00000F05AF9E5E618A8002340F8343D642119 -:1008C00000F048F900287FF4A8AE0220FFF772FD7F -:1008D00000283FF4A2AE0B9800F0AAF918AB43F839 -:1008E000480D04211846E3E718A8002340F8343DDA -:1008F000642100F02FF900287FF48FAE0220FFF76B -:1009000059FD00283FF489AE0B9800F09FF918AB11 -:1009100043F8440DE5E70220FFF74CFD00283FF4C3 -:100920007CAE00F0A9F918AB43F8400DD9E70220DE -:10093000FFF740FD00283FF470AE0BA9142000F033 -:10094000A1F9804618A8042140F83C8D00F00CF96C -:1009500041460BA8ACE7322000F0E8F8B0F10008FF -:10096000FFF65BAE18F0030F7FF457AE019A926862 -:1009700008EB090393423FF650AE0220FFF71AFD41 -:1009800000283FF44AAE28F00308C844C1453FF4AC -:1009900078AE484600F01CF904210A900AA800F03D -:1009A000E3F809F10409F1E74FF47A70FFF702FD6B -:1009B00000283FF432AE00F04FF9002842D0109BDF -:1009C00001330BD0082210A9002000F0F1F9002813 -:1009D00038D02022FF2110A800F0E2F9FFF7F2FC46 -:1009E000364801F031FB0FE6002F3FF416AE0AF057 -:1009F0000B030B2B7FF411AE18A8002340F8343DF5 -:100A0000642100F0A7F8804600287FF406AE02209B -:100A1000FFF7D0FC00283FF400AE0390FFF7D2FCB4 -:100A200041F2883001F010FB0B9800F04FFA00F013 -:100A30000BFA039B45461F46DBE5074621E64FF0D0 -:100A40000009EAE5B84664E6002000F06FF804907B -:100A5000049B002BFFF6D0AD012000F059F9049B58 -:100A6000213B122B3FF6C5AD01A252F823F000BF87 -:100A70000F06000835060008CB060008F30500083D -:100A8000F3050008F30500085B0700085709000894 -:100A90001F080008B7080008E9080008170900083F -:100AA000F30500082F090008F3050008A90900084C -:100AB00083060008F3050008E9090008A086010084 -:100AC0002DE9F84F4FF47A75DFF85880DFF8589029 -:100AD00007460E465543002498F900305A1C5FFA29 -:100AE00084FA01D0A34210D159F824000368324699 -:100AF000D3F820B039462B46D847864205D1084B5B -:100B000083F800A00120BDE8F88F0134022CE3D166 -:100B10004FF4FA7001F098FA0020BDE8F88F00BF9A -:100B2000D02301200C2201200C3C000807B502ABA9 -:100B3000002203F8012D012102461846FFF7C0FFED -:100B400020B19DF8070003B05DF804FB4FF0FF30C3 -:100B5000F9E700000A4608B50421FFF7B1FF80F06D -:100B60000100C0B2404208BD30B4074B1A78074BB1 -:100B700053F822402368DD69054B0A46AC4601461E -:100B8000204630BC604700BFD02301200C3C000849 -:100B9000A0860100F8B501F0F9FC094C094E0A4F96 -:100BA0002080002530682388834207D901F0E8FCC3 -:100BB000336805440133BD423360F3D9F8BD00BF4B -:100BC000D22301208C230120FF7F010001F08CBD86 -:100BD00000F1006000F5C0300068704700F100606F -:100BE000920000F5C03001F017BD0000054B1A68F7 -:100BF000054B1B889B1A834202D9104401F0C0BCEC -:100C0000002070478C230120D223012038B5074DE6 -:100C100004462868204401F0BBFC28B92868204419 -:100C2000BDE8384001F0CCBC38BD00BF8C230120AA -:100C300010F0030308D1B0F5846F05D200F1005025 -:100C4000A0F571200068704700207047014BC05824 -:100C5000704700BF20F4F01F064991F8243033B1EB -:100C600000230822086A81F82430FFF7B7BF01206B -:100C7000704700BF90230120014B1868704700BFE8 -:100C8000002004E0F0B5204B1E68204B1F885D68F3 -:100C900093F90840C6F30B02BA424FEA164622D037 -:100CA0009F89BA4221D01F8BBA4206D102220C245E -:100CB00004FB02335D6893F90840B6F5805F16D0F7 -:100CC00041F201039E4208BF5A24421E0A44013DDC -:100CD0000B46934215D215F9016F581C4EB10346CD -:100CE00000F8016CF5E70022E1E70122DFE741248B -:100CF000EBE72C2582421D7001D9981C5C70401ACC -:100D0000F0BD1846FBE700BF002004E010220120E0 -:100D1000022802BF024B4FF000529A61704700BF99 -:100D200000080240022802BF024B4FF400529A61B1 -:100D3000704700BF00080240022801BF024A536901 -:100D400083F40053536170470008024010B500233C -:100D5000934203D0CC5CC4540133F9E710BD0000CA -:100D600030B5441E14F9010F0B4660B193F90050E1 -:100D7000854201F1010106D11AB993F90020801AC8 -:100D800030BD013AEEE7002AF7D1104630BD000031 -:100D900002460346981A13F9011B0029FAD170473D -:100DA00002440346934202D003F8011BFAE770475E -:100DB0002DE9F047234C94F8243005468846174621 -:100DC00083BB2E46DFF87C90C7B394F824302BB950 -:100DD0002022FF2148462662FFF7E2FF94F8240014 -:100DE000C0F10805BD4228BF3D465FFA85FAAD0057 -:100DF00041462A4604EB8000FFF7A8FF94F8243010 -:100E0000A7EB0A079A445FFA8AFABAF1080F2E4450 -:100E1000A844FFB284F824A0D6D1FFF71DFF002814 -:100E2000D2D108E0266A06EB8306B042CAD0FFF7AB -:100E300013FF0028C5D10020BDE8F0870120BDE8E0 -:100E4000F08700BF90230120024B1A78024B1A70E2 -:100E5000704700BFD02301200C22012038B5154C6B -:100E6000154D204600F0F8FB2946204600F020FCF6 -:100E70002D681248EA6ED2F8043843F00203C2F833 -:100E8000043801F0E1F80E49284600F025FDEA6E2D -:100E90000C48D2F804380C4923F00203C2F8043895 -:100EA000A0424FF4E1330B6003D0BDE8384000F0BE -:100EB0002DBB38BDF8270120243D000840420F001B -:100EC0004C3D0008D4230120B823012038B50B4B3A -:100ED0001A780B4B53F822400A4B9C4205460CD023 -:100EE000094B002118461822FFF75AFF05600146FA -:100EF0002046BDE8384000F009BB38BDD0230120B2 -:100F00000C3C0008F8270120B8230120FEE7000070 -:100F100000B59BB0EFF3098168226846FFF716FF22 -:100F2000EFF30583044B9A6BDA6A9A6A9A6A9A6AB3 -:100F30009A6A9A6A9B6AFEE700ED00E000B59BB0F2 -:100F4000EFF3098168226846FFF700FFEFF305839E -:100F5000044B9A6B9A6A9A6A9A6A9A6A9A6A9B6A24 -:100F6000FEE700BF00ED00E000B59BB0EFF30981A4 -:100F700068226846FFF7EAFEEFF30583034B5A6BDE -:100F80009A6A9A6A9A6A9A6A9B6AFEE700ED00E09A -:100F900030B5084D0A4491420BD011F8013B0924A9 -:100FA0005840013CF7D040F300032B4083EA500047 -:100FB000F7E730BD2083B8ED72B6202383F31188A4 -:100FC00062B67047026843681143016003B1184775 -:100FD00070470000024A136843F0C0031360704773 -:100FE0000010014013B50E4C204600F083FA04F1C6 -:100FF0001400009400234FF480720A4900F048F96D -:101000000094094B09494FF4807204F1380000F054 -:10101000BDF9074BE365074B236602B010BD00BF67 -:10102000D423012040240120D50F000840250120B1 -:101030000010014000F36F06224B002908BF19463B -:10104000037C012B30B50CD11F4B984209D11F4BAB -:101050005A6C42F010025A645A6E42F010025A66FC -:101060005B6E0A68036EC46D816603EB5203B3FBCB -:10107000F2F34A68150442BF23F0070503F00703A3 -:1010800043EA4503E3608B6843F040036360CB6849 -:1010900043F00103A36042F4967343F0010323601D -:1010A00051054FF0FF33236205D512F0102205D011 -:1010B000B2F1805F04D080F8643030BD7F23FAE75E -:1010C0003F23F8E7403C0008D423012000380240C9 -:1010D0002DE9F047C66D3768F4693462054620078C -:1010E00018D014F0080F0CBF00218021E20748BF80 -:1010F00041F02001A30748BF41F04001600748BF0D -:1011000041F48071FFF758FF281DFFF75BFF0023B4 -:1011100083F31188E20509D5FFF74EFF4FF4007104 -:10112000281DFFF74FFF002383F311884FF00009BC -:1011300014F020082ED13B0614D505F138092006FD -:1011400010D5FFF739FF484600F052F900282EDA93 -:101150000821281DFFF736FF27F0800333600023A6 -:1011600083F3118879060CD562060AD5FFF724FFB0 -:10117000EA6C2B6D9A4201D12B6CEBB9002383F3FF -:101180001188E30620D5AA6E1369EBB15069BDE85A -:10119000F0471847FFF710FF736A95F86410284668 -:1011A000194000F0BFF989F31188F469C0E7B06213 -:1011B00088F31188F469C2E71021281D27F0400741 -:1011C000FFF700FF3760D9E7BDE8F08772B620234C -:1011D00083F3118862B67047F8B5154682680669D0 -:1011E000AA420B46816938BF8568761AB542044623 -:1011F00007D218462A46FFF7A9FDA3692B44A3612D -:101200000DE011D932461846FFF7A0FDAF1B3A4654 -:10121000E1683044FFF79AFDE2683A44A261A368AE -:101220005B1BA3602846F8BD18462A46FFF78EFDD3 -:10123000E368E4E783682DE9F041044693421546EC -:10124000266938BF85684069361AB5420F4606D20E -:101250002A46FFF77BFD63692B4463610DE012D9D9 -:101260003246A5EB0608FFF771FD4246B919E06862 -:10127000FFF76CFDE26842446261A3685B1BA360F8 -:101280002846BDE8F0812A46FFF760FDE368E4E701 -:1012900010B50A440024C361029B00604060846072 -:1012A000C160816141610261036210BD08B582695C -:1012B0004369934201D1826882B9826801328260B7 -:1012C0005A1C42611970426903699A4201D3C3688A -:1012D0004361002100F0D4FE002008BD4FF0FF3034 -:1012E00008BD000070B504460E46FFF76FFFA56805 -:1012F000A5B1A368A269013BA360531CA361157843 -:101300002269934224BFE368A361E3690BB12046DD -:101310009847002383F31188284670BD3146204644 -:1013200000F09EFE0028E2DA85F3118870BD00000F -:101330002DE9F84F05460E4690469A46D0F81C9087 -:10134000FFF744FF4FF0000B144664B122463146CC -:101350002846FFF741FF074660B95146284600F08E -:101360007FFE0028F1D0002383F31188A8EB04004E -:10137000BDE8F88FB9F1000F01D02846C8478BF3BC -:101380001188E41B3E44FFF721FFDEE7C160816165 -:101390004161C3611144009B006040608260016153 -:1013A00003627047F8B504460E461746FFF70EFF76 -:1013B000A568A5B1A368013BA36063695A1C62617B -:1013C0001E70236962699A4224BFE3686361E3691E -:1013D0000BB120469847002080F31188F8BD3946AC -:1013E000204600F03DFE0028E2DA85F31188F8BDC2 -:1013F000836942699A4210B501D182687AB98268DC -:10140000013282605A1C82611C7803699A4201D3BE -:10141000C3688361002100F033FE204610BD4FF009 -:10142000FF3010BD2DE9F84F05460E4690469A460E -:10143000D0F81C90FFF7CAFE4FF0000B144664B1C1 -:10144000224631462846FFF7F5FE074660B9514669 -:10145000284600F005FE0028F1D0002383F3118810 -:10146000A8EB0400BDE8F88FB9F1000F01D02846C1 -:10147000C8478BF31188E41B3E44FFF7A7FEDEE765 -:1014800072B6202383F3118862B6704702684368FE -:101490001143016003B11847704700001430FFF793 -:1014A00047BF00004FF0FF331430FFF741BF00008B -:1014B0003830FFF7B7BF00004FF0FF333830FFF789 -:1014C000B1BF00001430FFF70DBF00004FF0FF3137 -:1014D0001430FFF707BF00003830FFF763BF00008C -:1014E0004FF0FF323830FFF75DBF0000002070473B -:1014F000FFF778BD044B0360002343608360C36043 -:1015000001230374704700BF583C000810B504461F -:10151000FFF7B6FFFFF790FD02232374002383F348 -:10152000118810BD38B5C36904460D461BB90421A6 -:101530000844FFF7ABFF294604F11400FFF7B6FE9D -:10154000002806DA201D4FF48061BDE83840FFF71F -:101550009DBF38BD72B6202383F3118862B67047F1 -:10156000026843681143016003B1184770470000E7 -:1015700013B5446BD4F894341A681178042915D142 -:10158000217C022912D11979128901238B4013423F -:101590000CD101A904F14C0001F0A2FFD4F894444D -:1015A000019B21790246206800F0E6F902B010BDE7 -:1015B000143001F027BF00004FF0FF33143001F06A -:1015C00021BF00004C3001F0F7BF00004FF0FF33A7 -:1015D0004C3001F0F1BF0000143001F0F7BE000004 -:1015E0004FF0FF31143001F0F1BE00004C3001F03B -:1015F000C3BF00004FF0FF324C3001F0BDBF000010 -:10160000D0F8942438B5136819780429054601D018 -:10161000012038BD017C0229FAD152795C89012070 -:1016200090400440F4D105F1140001F089FE024617 -:101630000028EDD0D5F894544FF480732868697968 -:1016400000F088F9204638BD406BFFF7D9BF000095 -:1016500000207047704700007FB5124B03600023E5 -:1016600043608360C360012502260F4B0574044666 -:101670000290019300F18402294600964FF4807392 -:10168000143001F039FE094B0193029400964FF497 -:10169000807304F52372294604F14C0001F0FCFE2E -:1016A00004B070BD803C00084916000871150008A0 -:1016B00008B50A68FFF74EFF0B7902EB8303186247 -:1016C0004B790D3342F823008B7913B102EB83027F -:1016D000106202230374C0F89414002383F311886A -:1016E00008BD000038B5037F044613B190F85430AC -:1016F000ABB9201D01250221FFF732FF04F11400D0 -:1017000025776FF0010100F0C7FC84F8545004F114 -:101710004C006FF00101BDE8384000F0BDBC38BDA1 -:1017200010B5012104460430FFF71AFF0023237788 -:1017300084F8543010BD000038B50446002514303C -:1017400001F0F2FD04F14C00257701F0BDFE201DF3 -:1017500084F854500121FFF703FF2046BDE83840CC -:10176000FFF74EBF90F85C3003F06003202B19D1D7 -:1017700090F85D20212A0AD0222A4FF000030ED0D3 -:10178000202A0FD1084A02650722426504E0064B71 -:1017900003650723436500238365012070470365C4 -:1017A0004365F9E70020704734220120D0F89434D3 -:1017B00037B51A681178042904461AD1017C022928 -:1017C00017D11979128901238B40134211D100F1ED -:1017D0004C05284601F036FF58B101A9284601F012 -:1017E0007FFED4F89444019B21790246206800F0E2 -:1017F000C3F803B030BD000000EB8103F7B51C6AED -:1018000005460E46ECB105EB8607FFF7A3FE201D4B -:101810000821FFF7A5FEFB685B691B684C3413B118 -:10182000204601F06BFE01A9204601F059FE024658 -:1018300048B1019B3146284600F09EF8002383F30F -:10184000118803B0F0BDFB685A691268002AF5D010 -:101850001B8A013B1340F1D105F15C02EAE700006D -:101860000D3138B550F82140D4B1FFF773FED4F8EC -:1018700094241368527903EB8203DB689B695D68EB -:1018800045B104216018FFF76BFE294604F11400EE -:1018900001F060FD2046FFF7B3FE002383F31188BB -:1018A00038BD00007047000072B6202383F3118812 -:1018B00062B6704701F0E2B8012303700023436071 -:1018C00000F1240200F1380142F8043B8A4213611E -:1018D000FAD103814381704738B50446FFF7E4FF2E -:1018E00000254160C560056145618561C56105628E -:1018F00001F0D4F80223237085F3118838BD00006D -:1019000070B500EB810305465069DA600E46144657 -:1019100018B110220021FFF743FAA06918B1102274 -:101920000021FFF73DFA31462846BDE8704001F03E -:101930007FB90000028902F001020281428902F0AF -:10194000010242810022026142618261C26102623F -:1019500001F002BAF0B400EB81044789E468012584 +:1003500001F080FEFEE701F0F5FD00DFFEE70000A2 +:1003600038B502F031FA054602F064FA0446D8B90D +:100370000F4B9D421AD001339D4218BF044641F2F3 +:10038000883504BF01240025002002F027FA0CB1B3 +:1003900000F078F800F070FD00F012FC284600F044 +:1003A000FDF800F06FF8F9E70025EDE70546EBE70B +:1003B000010007B008B500F0CFFBA0F120035842C0 +:1003C000584108BD07B541F21203022101A8ADF85A +:1003D000043000F0DFFB03B05DF804FB38B572B603 +:1003E000202383F3118862B61748C3680BB101F06C +:1003F000B9FE164A144800234FF47A7101F076FED4 +:10040000002383F31188124C236813B12368013B46 +:100410002360636813B16368013B63600D4D2B7803 +:1004200033B963687BB9022000F0A0FC322363601B +:100430002B78032B07D163682BB9022000F096FCC0 +:100440004FF47A73636038BD68220120DD03000831 +:10045000842301207C220120084B187003280CD82B +:10046000DFE800F008050208022000F075BC022059 +:1004700000F068BC024B00225A6070477C220120C9 +:1004800084230120F8B5404B404A1C4619680131CD +:1004900079D004339342F9D16268A24273D33C4BC2 +:1004A0009B6803F1006303F5C0339A426BD20020CE +:1004B00000F0A0FB0220FFF7CFFF364B00211A6CA3 +:1004C00019641A6E19661A6E5A6C59645A6E596616 +:1004D0005A6E5A6942F080025A615A6922F08002CB +:1004E0005A615A691A6942F000521A611A6922F077 +:1004F00000521A611B6972B64FF0E023C3F8084D31 +:10050000D4E90004BFF34F8FBFF36F8F224AC2F8C4 +:100510008410BFF34F8F536923F480335361BFF3CB +:100520004F8FD2F88030C3F3C905C3F34E335B015C +:1005300043F6E07603EA060C29464CEA8177013956 +:10054000C2F87472F9D2203B13F1200FF2D1BFF33D +:100550004F8FBFF36F8FBFF34F8FBFF36F8F536911 +:1005600023F4003353610023C2F85032BFF34F8F9E +:10057000BFF36F8F72B6202383F3118862B685466E +:1005800080F308882047F8BD00800108208001081A +:10059000002201200038024000ED00E02DE9F04F7C +:1005A00093B0B64B00902022FF210AA89D6800F06E +:1005B0000DFCB34A1378B3B9B24801211170C3607E +:1005C00072B6202383F3118862B6C3680BB101F0C1 +:1005D000C9FDAD4AAB4800234FF47A7101F086FDA6 +:1005E000002383F31188009B13B1A84B009A1A6073 +:1005F000A74A009C1378032B1EBF00231370A34A45 +:100600004FF0000A18BF5360D3465646D14601202A +:1006100000F0A2FB24B19D4B1B68002B00F0278249 +:10062000002000F099FA0390039B002BF2DB0120DD +:1006300000F088FB039B213B1F2BE8D801A252F856 +:1006400023F000BFC5060008ED060008810700087A +:100650000F0600080F0600080F0600081308000820 +:10066000E3090008FD0800085F0900088709000881 +:10067000AD0900080F060008BF0900080F060008B2 +:10068000310A0008650700080F060008750A00080F +:10069000D1060008650700080F0600085F0900087A +:1006A0000F0600080F0600080F0600080F060008D6 +:1006B0000F0600080F0600080F0600080F060008C6 +:1006C000810700080220FFF775FE002840F0F9813D +:1006D000009B0221BAF1000F08BF1C4605A841F299 +:1006E0001233ADF8143000F055FA90E74FF47A70F9 +:1006F00000F032FA071EEBDB0220FFF75BFE00285A +:10070000E6D0013F052F00F2DE81DFE807F0030AA3 +:100710000D10133605230593042105A800F03AFABD +:1007200017E056480421F9E75A480421F6E75A48E9 +:100730000421F3E74FF01C08404600F05DFA08F191 +:1007400004080590042105A800F024FAB8F12C0F44 +:10075000F2D1012000FA07F747EA0B0B5FFA8BFB97 +:100760004FF0000900F07EFB26B10BF00B030B2BC2 +:1007700008BF0024FFF726FE49E748480421CDE7DB +:10078000002EA5D00BF00B030B2BA1D10220FFF7FD +:1007900011FE074600289BD0012000F02BFA022012 +:1007A000FFF75AFE00265FFA86F8404600F032FA5C +:1007B0000446B0B10399A1F1400251425141404673 +:1007C00000F038FA01360028EDD1BA46044641F26D +:1007D0001213022105A8ADF814303E4600F0DAF9F4 +:1007E00015E70120FFF738FE2546244B9B68AB42F6 +:1007F00007D9284600F000FA013040F0678104353F +:10080000F3E7234B00251D70204BBA465D603E4642 +:10081000A8E7002E3FF45CAF0BF00B030B2B7FF42B +:1008200057AF0220FFF718FE322000F095F9B0F123 +:100830000008FFF64DAF18F003077FF449AF0F4AE9 +:10084000926808EB050393423FF642AFB8F5807F0C +:100850003FF73EAF124B0193B84523DD4FF47A705A +:1008600000F07AF90390039A002AFFF631AF019B5A +:10087000039A03F8012B0137EDE700BF00220120A6 +:100880008023012068220120DD0300088423012049 +:100890007C22012004220120082201200C220120B8 +:1008A00080220120C820FFF785FD074600283FF47D +:1008B0000FAF1F2D11D8C5F1200242450AAB25F01C +:1008C000030028BF424683490192184400F058FAB9 +:1008D000019A8048FF2100F079FA4FEAA8037D4988 +:1008E0000193C8F38702284600F078FA06460028EC +:1008F0003FF46DAF019B05EB830533E70220FFF763 +:1009000059FD00283FF4E4AE00F0C0F900283FF4A0 +:10091000DFAE0027B846704B9B68BB4218D91F2F2B +:1009200011D80A9B01330ED027F0030312AA1344F7 +:1009300053F8203C05934046042205A900F036FBFD +:1009400004378046E7E7384600F056F90590F2E7AD +:10095000CDF81480042105A800F01CF902E700235B +:10096000642104A8049300F00BF900287FF4B0AED2 +:100970000220FFF71FFD00283FF4AAAE049800F004 +:100980006DF90590E6E70023642104A8049300F0C4 +:10099000F7F800287FF49CAE0220FFF70BFD00283B +:1009A0003FF496AE049800F069F9EAE70220FFF7F9 +:1009B00001FD00283FF48CAE00F078F9E1E7022059 +:1009C000FFF7F8FC00283FF483AE05A9142000F0DF +:1009D00073F904210746049004A800F0DBF83946B7 +:1009E000B9E7322000F0B8F8071EFFF671AEBB077A +:1009F0007FF46EAE384A926807EB090393423FF6E4 +:100A000067AE0220FFF7D6FC00283FF461AE27F066 +:100A100003074F44B9453FF4A5AE484600F0ECF853 +:100A20000421059005A800F0B5F809F10409F1E7E3 +:100A30004FF47A70FFF7BEFC00283FF449AE00F097 +:100A400025F9002844D00A9B01330BD008220AA9BB +:100A5000002000F0C3F900283AD02022FF210AA884 +:100A600000F0B4F9FFF7AEFC1C4801F0FBFA13B03C +:100A7000BDE8F08F002E3FF42BAE0BF00B030B2BD9 +:100A80007FF426AE0023642105A8059300F078F8D2 +:100A9000074600287FF41CAE0220FFF78BFC80463F +:100AA00000283FF415AEFFF78DFC41F2883001F0CD +:100AB000D9FA059800F018FA464600F0D3F93C46FA +:100AC000A5E506464EE64FF0000901E6BA467EE689 +:100AD00037467CE68022012000220120A08601000A +:100AE000F7B5194E0C464FF47A7102FB01F396F9F3 +:100AF00000200546501C0BD114480193026829467A +:100B0000176A2246B8478442019B03D1002310E0B4 +:100B1000002AF1D096F90020511C01D0012A0DD1F4 +:100B20000B4802682946166A2246B047844205D11E +:100B30000123084A0120137003B0F0BD4FF4FA708E +:100B400001F090FA0020F7E710220120F827012099 +:100B5000D4230120D023012007B500230246012120 +:100B60000DF107008DF80730FFF7BAFF20B19DF8AF +:100B7000070003B05DF804FB4FF0FF30F9E7000019 +:100B80000A4608B50421FFF7ABFF80F00100C0B2B0 +:100B9000404208BD30B4074B0A461978064B53F85B +:100BA00021402368DD69054B0146AC46204630BC38 +:100BB000604700BFD0230120483C0008A086010008 +:100BC00070B501F0F3FC094E094D3080002428680F +:100BD0003388834208D901F0E3FC2B6804440133D5 +:100BE000B4F5C03F2B60F2D370BD00BFD22301200B +:100BF0008C23012001F09CBD00F1006000F5C030A5 +:100C00000068704700F10060920000F5C03001F00C +:100C10001BBD0000054B1A68054B1B889B1A8342BD +:100C200002D9104401F0BCBC002070478C23012085 +:100C3000D223012038B5084D044629B12868204444 +:100C4000BDE8384001F0CCBC2868204401F0B0FC7D +:100C50000028F3D038BD00BF8C23012010F003031F +:100C600009D1B0F5846F04D200F10050A0F57120D5 +:100C70000368184670470023FBE7000000F10050AE +:100C8000A0F57120D0F8200470470000064991F8C3 +:100C9000243033B10023086A81F824300822FFF79A +:100CA000B1BF0120704700BF90230120014B18689D +:100CB000704700BF002004E0F0B5204B02461868E2 +:100CC0001F4B1F885D6893F90840C0F30B06BE42B6 +:100CD0004FEA104022D09F89BE4221D01F8BBE42D6 +:100CE00006D102240C2505FB04335D6893F9084006 +:100CF000B0F5805F16D041F20103984208BF5A2434 +:100D0000013A0A44013D0B4693420DD215F9016F99 +:100D1000581C5EB100F8016C0346F5E70024E1E7DA +:100D20000124DFE74124EBE7184605E02C2590423B +:100D30001D7001D2981C5C70401AF0BD002004E0C8 +:100D400014220120022802BF024B4FF000529A6188 +:100D5000704700BF00080240022802BF024B4FF458 +:100D600000529A61704700BF00080240022801BF8C +:100D7000024A536983F400535361704700080240EC +:100D800010B50023934203D0CC5CC4540133F9E77F +:100D900010BD000010B5013810F9013F3BB191F9C9 +:100DA00000409C4203D11AB10131013AF4E71AB173 +:100DB00091F90020981A10BD1046FCE70346024640 +:100DC000D01A12F9011B0029FAD1704702440346D8 +:100DD000934202D003F8011BFAE770472DE9F8436C +:100DE0001F4D144695F824200746884652BBDFF86D +:100DF00070909CB395F824302BB92022FF214846EF +:100E00002F62FFF7E3FF95F82400C0F10802A24229 +:100E100028BF2246D6B24146920005EB8000FFF77C +:100E2000AFFF95F82430A41B1E44F6B2082E1744D9 +:100E30009044E4B285F82460DBD1FFF727FF002857 +:100E4000D7D108E02B6A03EB82038342CFD0FFF7B0 +:100E50001DFF0028CBD10020BDE8F8830120FBE76F +:100E600090230120024B1A78024B1A70704700BF82 +:100E7000D02301201022012038B5154C154D2046F5 +:100E800000F0F4FB2946204600F01CFC2D681248B7 +:100E9000EA6ED2F8043843F00203C2F8043801F0D5 +:100EA000E1F80E49284600F01BFDEA6E0C48D2F826 +:100EB00004380C4923F00203C2F80438A0424FF46E +:100EC000E1330B6003D0BDE8384000F02BBB38BDE8 +:100ED000F8270120543D000840420F005C3D000807 +:100EE000D4230120B823012038B50B4B1A780B4BC3 +:100EF00053F822500A4B9D4204460CD0094B002166 +:100F000018461822FFF762FF046001462846BDE834 +:100F1000384000F007BB38BDD0230120483C000812 +:100F2000F8270120B823012000B59BB0EFF3098119 +:100F300068226846FFF724FFEFF30583044B9A6BA2 +:100F4000DA6A9A6A9A6A9A6A9A6A9A6A9B6AFEE75F +:100F500000ED00E000B59BB0EFF309816822684620 +:100F6000FFF70EFFEFF30583044B9A6B9A6A9A6AB8 +:100F70009A6A9A6A9A6A9B6AFEE700BF00ED00E0EF +:100F800000B59BB0EFF3098168226846FFF7F8FED1 +:100F9000EFF30583034B5A6B9A6A9A6A9A6A9A6AC4 +:100FA0009B6AFEE700ED00E0FEE7000030B5094D6A +:100FB0000A4491420DD011F8013B5840082340F3F8 +:100FC0000004013B2C4013F0FF0384EA5000F6D1EB +:100FD000EFE730BD2083B8ED72B6202383F311888C +:100FE00062B67047026843681143016003B1184755 +:100FF00070470000024A136843F0C0031360704753 +:101000000010014013B50E4C204600F07FFA04F1A9 +:1010100014000C49009400234FF4807200F044F94E +:10102000094B0A4900944FF4807204F1380000F033 +:10103000B9F9074A074BC4E9172302B010BD00BF36 +:10104000D423012040240120F50F00084025012071 +:101050000010014000F36F0630B5037C214C0029DD +:1010600018BF0C46012B0CD11F4B984209D11F4BC6 +:101070005A6C42F010025A645A6E42F010025A66DC +:101080005B6E2268036EC16D846603EB5203B3FB93 +:10109000F2F36268150442BF23F0070503F007036B +:1010A00043EA4503CB60A36843F040034B60E36829 +:1010B00043F001038B6042F4967343F001030B602D +:1010C0004FF0FF330B62510505D512F0102205D009 +:1010D000B2F1805F04D080F8643030BD7F23FAE73E +:1010E0003F23F8E7503C0008D42301200038024099 +:1010F0002DE9F047C66D3768F4693462210705466B +:1011000017D014F0080118BF8021E20748BF41F052 +:101110002001A30748BF41F04001600748BF41F4E8 +:101120008071281DFFF758FFFFF75CFF002383F352 +:101130001188E20509D54FF40071281DFFF74CFF17 +:10114000FFF750FF002383F311884FF0000914F0DC +:10115000200835D13B0614D505F13809200610D5F5 +:101160004846FFF739FF00F04FF9002835DA08212B +:10117000281DFFF737FF27F080033360002383F338 +:101180001188790613D5620611D5FFF725FFD5E939 +:1011900013239A4208D12B6C33B11021281D27F05C +:1011A0004007FFF71FFF3760002383F31188E30632 +:1011B00018D5AA6E1369ABB1BDE8F047506918475E +:1011C000FFF70AFF736A95F864102846194000F08B +:1011D000B5F989F31188F469B9E7B06288F3118829 +:1011E000F469BBE7BDE8F08772B6202383F311886A +:1011F00062B67047F8B5154682680669AA420B4682 +:10120000816938BF8568761AB54204460BD2184604 +:101210002A46FFF7B5FDA3692B44A361A3685B1BB6 +:10122000A3602846F8BD0CD918463246FFF7A8FD42 +:10123000AF1BE1683A463044FFF7A2FDE3683B4448 +:10124000EBE718462A46FFF79BFDE368E5E7000059 +:1012500083689342F7B51546044638BF8568D0E9E0 +:101260000460361AB5420BD22A46FFF789FD63693E +:101270002B446361A36828465B1BA36003B0F0BDE9 +:101280000DD932460191FFF77BFD0199E068AF1B54 +:101290003A463144FFF774FDE3683B44E9E72A46E8 +:1012A000FFF76EFDE368E4E710B50A440024C3616C +:1012B000029B8460C0E90000C0E90511C1600261C1 +:1012C000036210BD08B5D0E90532934201D18268AE +:1012D00082B98268013282605A1C42611970D0E979 +:1012E00004329A4224BFC3684361002100F0D6FE55 +:1012F000002008BD4FF0FF30FBE7000070B504464A +:101300000D46FFF771FFA668A6B1A368A269013B6D +:10131000A360531CA36115782269934224BFE3683C +:10132000A361E3690BB120469847002383F311883A +:10133000284607E02946204600F0A0FE0028E2DA11 +:1013400086F3118870BD00002DE9F84FD0F81CA07D +:101350009946FFF749FF04460E46904615464FF062 +:10136000000B65B12A4631462046FFF743FF07468A +:1013700060B94946204600F081FE0028F1D00023E4 +:1013800083F31188A8EB0500BDE8F88FBAF1000FD0 +:1013900001D02046D0478BF31188ED1B3E44FFF768 +:1013A00023FFDEE7C0E90511C160C3611144009B62 +:1013B0008260C0E90000016103627047F8B504462D +:1013C0000D461646FFF710FFA768A7B1A368013BBB +:1013D000A36063695A1C62611D70D4E904329A42A9 +:1013E00024BFE3686361E3690BB12046984700209E +:1013F00080F3118807E03146204600F03FFE0028C8 +:10140000E2DA87F31188F8BDD0E905239A4210B5D6 +:1014100001D182687AB98268013282605A1C826185 +:101420001C7803699A4224BFC3688361002100F0DD +:1014300035FE204610BD4FF0FF30FBE72DE9F84F99 +:10144000D0F81CA09946FFF7CFFE04460E46904602 +:1014500015464FF0000B65B12A4631462046FFF78E +:10146000F7FE074660B94946204600F007FE00280F +:10147000F1D0002383F31188A8EB0500BDE8F88FB5 +:10148000BAF1000F01D02046D0478BF31188ED1B35 +:101490003E44FFF7A9FEDEE772B6202383F31188EE +:1014A00062B67047026843681143016003B1184790 +:1014B000704700001430FFF747BF00004FF0FF33C4 +:1014C0001430FFF741BF00003830FFF7B7BF00000E +:1014D0004FF0FF333830FFF7B1BF00001430FFF793 +:1014E0000DBF00004FF0FF311430FFF707BF0000C1 +:1014F0003830FFF763BF00004FF0FF323830FFF79E +:101500005DBF000000207047FFF77CBD044B036007 +:101510000023C0E90233436001230374704700BF16 +:10152000683C000810B50446FFF7B6FFFFF794FDCE +:1015300002232374002383F3118810BD38B5C369D7 +:1015400004460D461BB904210844FFF7ABFF2946AA +:1015500004F11400FFF7B6FE002806DA201D4FF450 +:101560008061BDE83840FFF79DBF38BD72B62023CB +:1015700083F3118862B670470268436811430160C3 +:1015800003B118477047000013B5446BD4F8943486 +:101590001A681178042915D1217C022912D11979F0 +:1015A000128901238B4013420CD101A904F14C0094 +:1015B00001F0AEFFD4F89444019B217902462068E3 +:1015C00000F0DAF902B010BD143001F033BF0000B2 +:1015D0004FF0FF33143001F02DBF00004C3002F00B +:1015E00003B800004FF0FF334C3001F0FDBF0000A6 +:1015F000143001F003BF00004FF0FF31143001F050 +:10160000FDBE00004C3001F0CFBF00004FF0FF32B4 +:101610004C3001F0C9BF00000020704710B5D0F871 +:1016200094341A6811780429044617D1017C0229E0 +:1016300014D15979528901238B4013420ED11430B1 +:1016400001F096FE024648B1D4F894444FF48073FA +:1016500061792068BDE8104000F07CB910BD000041 +:10166000406BFFF7DBBF0000704700007FB5124BF7 +:10167000036000234360C0E90233012502260F4BBB +:10168000057404460290019300F1840229460096F5 +:101690004FF48073143001F047FE094B0294CDE9FA +:1016A000006304F523724FF48073294604F14C0063 +:1016B00001F00AFF04B070BD903C000861160008FC +:1016C0008915000808B50A68FFF750FF0B7902EB8F +:1016D000830318624B790D3342F823008B7913B1E1 +:1016E00002EB8302106202230374C0F894140023F7 +:1016F00083F3118808BD000038B5037F044613B199 +:1017000090F85430ABB9201D01250221FFF734FFBA +:1017100004F1140025776FF0010100F0CBFC84F890 +:10172000545004F14C006FF00101BDE8384000F066 +:10173000C1BC38BD10B5012104460430FFF71CFFC1 +:101740000023237784F8543010BD000038B50446D8 +:101750000025143001F000FE04F14C00257701F063 +:10176000CBFE201D84F854500121FFF705FF2046D1 +:10177000BDE83840FFF752BF90F85C3003F06003DB +:10178000202B07D190F85D20212A4FF0000303D8C9 +:101790001F2A06D800207047222AFBD1C0E9143343 +:1017A00003E0034A02650722426583650120704712 +:1017B0003822012037B5D0F894341A6811780429FA +:1017C00004461AD1017C022917D119791289012303 +:1017D0008B40134211D100F14C05284601F04AFF1D +:1017E00058B101A9284601F093FED4F89444019B16 +:1017F00021790246206800F0BFF803B030BD000038 +:10180000F0B500EB810385B01E6A04460D46F6B1C3 +:1018100004EB8507301D0821FFF7A8FEFFF7ACFE9B +:10182000FB685B691B6806F14C001BB1019001F07D +:101830007DFE019803A901F06BFE024648B1039BAF +:101840002946204600F098F8002383F3118805B05C +:10185000F0BDFB685A691268002AF5D01B8A013B6B +:101860001340F1D104F15C02EAE700000D3138B514 +:1018700050F82140D4B1FFF779FED4F894241368CE +:10188000527903EB8203DB689B695D6845B10421F3 +:101890006018FFF771FE294604F1140001F072FD93 +:1018A0002046FFF7BBFE002383F3118838BD0000FC +:1018B0007047000072B6202383F3118862B6704728 +:1018C00001F0F8B810B501230446282200F8243BA3 +:1018D0000021FFF77BFA0023C4E9013310BD0000AB +:1018E00038B50025FFF7E6FF0446C0E90355C0E917 +:1018F0000555C0E90755416001F0ECF8022323705B +:1019000085F3118838BD000070B500EB81030546F2 +:101910005069DA600E46144618B110220021FFF714 +:1019200055FAA06918B110220021FFF74FFA31468D +:101930002846BDE8704001F097B90000826802F0C7 +:10194000011282600022C0E90422C0E9062202627C +:1019500001F016BAF0B400EB81044789E468012570 :10196000A4698D403D43458123600023A2606360EC -:10197000F0BC01F01DBA0000F0B400EB810407894F +:10197000F0BC01F031BA0000F0B400EB810407893B :10198000E468012564698D403D430581236000239F -:10199000A2606360F0BC01F099BA000070B5022348 -:1019A000002504460370A0F8645080F8665080F863 -:1019B000675005814581C560056145618561C561E7 -:1019C000056280F84C5001F0CFF863681B6823B1C2 -:1019D00029462046BDE87040184770BD037880F85E -:1019E00068300523037043681B6810B504460BB1CB -:1019F0000421984700232381638110BD436890F838 -:101A000068201B6802700BB1052118477047000061 -:101A100090F84C3070B5044613B1002380F84C3078 -:101A200004F15C02204601F0B9F963689B6863BB6E -:101A300094F85C5015F0600615D194F85D3005F00F -:101A40007F0545EA032540F202339D4200F00B81F9 -:101A500059D8022D00F0D9803DD8002D00F08580A6 -:101A6000012D00F0CC800021204601F00BFC00216C -:101A7000204601F0FDFB63681B6813B10621204678 -:101A80009847062384F84C3070BD204698470028BC -:101A9000CED094F8632094F8623043EA0223626D5A -:101AA000934238BF636594F95C30656D002B80F21A -:101AB000FC80002D00F0EB80092384F84C30FFF708 -:101AC000F3FE636D226D00212046FFF755FF0023D2 -:101AD00083F3118870BDB5F5817F00F0B080B5F556 -:101AE000407F49D0B5F5807FBDD194F85E30012BA1 -:101AF000B9D1B4F8643023F00203A4F86430266549 -:101B00006665A665C5E740F201639D421ED8B5F53E -:101B1000C06F3BD2B5F5A06FA5D1B4F85C30B3F57A -:101B2000A06F0ED194F85E3084F86630204601F044 -:101B300073F863681B6813B101212046984703239B -:101B40002370002323656365A365A2E7B5F5106FD5 -:101B500032D040F602439D4251D0B5F5006F82D19C -:101B600004F167032365012324E004F16403236582 -:101B700002236365A5658CE794F85E30012B7FF442 -:101B800072AFB4F8643043F00203B6E794F8612012 -:101B9000616894F860304D6894F85F1043EA02235E -:101BA000204694F85E20A84700283FF45CAF4368C5 -:101BB000236503686365A4E72378042B0FD1FFF73F -:101BC00073FE2046FFF7B6FE86F31188636884F83B -:101BD00067601B68032121700BB12046984794F879 -:101BE0005E30002BADD084F8673004232370636827 -:101BF0001B68002BA5D0022120469847A1E7374B50 -:101C000023650223636500239EE794F8601011F0BA -:101C1000800F204601F00F010ED001F0B1F801282D -:101C200006D002287FF41FAF2D4B2365606568E75F -:101C30002C4B2365656564E701F094F8EFE794F8B1 -:101C40005E30002B7FF40FAF94F8603013F00F017B -:101C50003FF477AF1A06204602D501F027FB70E764 -:101C600001F01AFB6DE794F85E30002B7FF4FBAEB9 -:101C700094F8603013F00F013FF463AF1B06204669 -:101C800002D501F0FFFA5CE701F0F2FA59E71423FC -:101C900084F84C30FFF708FE2B462A46294620469A -:101CA000FFF758FE85F3118870BD5DB1152384F8E8 -:101CB0004C30FFF7F9FD636D226D00212046FFF7E0 -:101CC00049FE04E70B2384F84C30FFF7EDFD2B466B -:101CD0002A4629462046FFF74FFEE3E7B03C0008BE -:101CE000A83C0008AC3C000838B590F84C300446DD -:101CF000152B28D8DFE803F03C27272727273C2788 -:101D0000270B283727272727272727273C3C90F80A -:101D1000631090F86220436D42EA01229A4213D97F -:101D2000C268128AB3FBF2F502FB153565B9FFF7FD -:101D3000BBFD2B462A462946FFF71EFE85F3118878 -:101D40000A2384F84C3038BD142384F84C30FFF754 -:101D5000ABFD00231A4619462046FFF7FBFD002382 -:101D600083F3118838BD836D03B198470023E8E7FA -:101D7000002101F087FA0021204601F079FA63681A -:101D80001B6813B10621204698470623D9E70000B7 -:101D900090F84C20152A38B5044621D801239340E9 -:101DA00040F6416213421CD113F480150ED19B0200 -:101DB00016D50B2380F84C30FFF776FD2B462A46CC -:101DC0002946FFF7D9FD85F3118838BDC3689B69A3 -:101DD0005B682BB9836D03B19847002384F84C30BE -:101DE00038BD002101F04EFA0021204601F040FAF2 -:101DF00063681B6813B10621204698470623EDE768 -:101E0000024B00221B605B609A60704740260120F5 -:101E1000002303748268054B1B6899689142FBD2CA -:101E20005A68036042601060586070474026012085 -:101E300008B572B6202383F3118862B6037C032BA6 -:101E400005D0042B0DD02BB983F3118808BD43694D -:101E500000221A604FF0FF334361FFF7D9FF0023E0 -:101E6000F2E790E80C001A6002685360F2E70000A5 -:101E7000002303748268054B1B6899689142FBD864 -:101E80005A68036042601060586070474026012025 -:101E9000054B19690874186802681A605360186164 -:101EA00001230374FEF742BA4026012030B54B1CD3 -:101EB00087B005460A4C10D023690A4A01A800F0F1 -:101EC00007F92846FFF7E4FF049B13B101A800F0CF -:101ED0003DF92369586907B030BDFFF7D9FFF8E72E -:101EE00040260120311E000838B50C4D41612B6998 -:101EF00081689A689142044603D8BDE83840FFF7EC -:101F000087BF1846FFF7B4FF01232C6101462374F5 -:101F10002046BDE83840FEF709BA00BF4026012040 -:101F2000044B1A681B6990689B68984294BF002014 -:101F3000012070474026012010B5084C2368206915 -:101F40001A6822605460012223611A74FFF790FF1F -:101F500001462069BDE81040FEF7E8B9402601209F -:101F6000FEE7000010B50C4CFFF74AFF00F0A2F8A6 -:101F700080220A49204600F027F8012344F8180C73 -:101F8000037400F04DFC002383F3118862B604480B -:101F9000BDE8104000F03AB868260120B43C0008C3 -:101FA000BC3C000800F00EB9034B59685A68521A3D -:101FB0009042FBD8704700BF001000E072B62023AB -:101FC00083F3118862B67047826002220274002295 -:101FD000427470478368A3F17C0243F80C2C0269B9 -:101FE00043F83C2C426943F8382C074A43F81C2C30 -:101FF000C26843F8102C022203F8082C002203F8D0 -:10200000072CA3F1180070474503000810B5FFF72F -:10201000D5FFFFF7DFFF00210446FFF765FF002330 -:1020200083F31188204610BD024B1B6958610F20B5 -:10203000FFF72EBF4026012008B5FFF7BFFFBDE820 -:102040000840FFF7F1BF000008B50146FFF7B6FFF3 -:102050000820FFF72BFF002383F3118808BD000041 -:1020600049B1064B42681B6918605A6013604360AF -:102070000420FFF71BBF4FF0FF30704740260120C0 -:102080000368984206D01A68026050605961184689 -:10209000FFF7BEBE7047000038B504460D46206805 -:1020A000844200D138BD036823605C604561FFF75E -:1020B000AFFEF4E7054B03F114025A619A614FF049 -:1020C000FF32DA6100221A62704700BF4026012009 -:1020D000F8B50361C2600E46054601F0E7FA1A4BF7 -:1020E00019461F4651F8142F8A420DD11862AE606E -:1020F0006A602A60022E2CBF801902309D615D61EA -:10210000BDE8F84001F0C0BA1B6A9268C41A3419DD -:1021100028BF3446A24202D9181901F0C3FA7B69DC -:102120009A6894420CD8AC6098685A682B60041B7B -:102130006A6015605D609C604FF0FF33FB61F8BD25 -:10214000A41A1B68ECE700BF4026012038B51C4BE1 -:1021500001685A6990421D460DD0446821600268AA -:1021600000215460C16091688068014491604FF023 -:10217000FF32DA6138BD1A4642F8141F4A605B69C3 -:1021800000219342C16003D1BDE8384001F084BA18 -:102190009A6881680A449A602C6A01F087FA6A6931 -:1021A0009268001B824209D9111A012998BF821C2A -:1021B000286ABDE83840104401F074BA38BD00BF49 -:1021C000402601202DE9F041194D002705F11406A4 -:1021D0006C6901F06BFA2A6AA368811A8B4218D8DD -:1021E00013442B6294E80C001A602268D4F80C8027 -:1021F00053606B69E760B34201D101F04DFA87F398 -:1022000011882069C04772B6202383F3118862B613 -:10221000DEE76A69B24208D05B1A022B2CBFC018F5 -:102220000230BDE8F04101F03DBABDE8F08100BFE9 -:102230004026012000207047FEE7000070470000A4 -:102240004FF0FF307047000072B6202383F31188EF -:1022500062B67047022906D0032906D00129064834 -:1022600018BF0020704705487047032A9ABF0448EA -:1022700000EBC20000207047A83D00085C3D00084C -:102280004422012070B59AB001AD064608462946A1 -:10229000144600F0B9F82846FEF77AFDC0B2431C98 -:1022A0005B0086E818002370032363700023023468 -:1022B0001946DAB2904204F1020401D81AB070BD96 -:1022C000EA5C04F8022C04F8011C0133F1E7000079 -:1022D00008B5FFF7B9FF0348FFF768FA002383F357 -:1022E000118808BDF827012090F85C3003F01F0228 -:1022F000012A07D190F85D200B2A03D10023036542 -:10230000436512E003F06003202B11D1B0F8603078 -:1023100073B990F85D20212A03D0222AEFD0202A19 -:1023200006D1044A02650722426583650120704791 -:10233000FFF718BA3B22012010B50446052915D82D -:10234000DFE801F015140315151BFFF77DFF0E4A9A -:102350000121FFF7D5FA20460C4A0221FFF7D0FAF7 -:102360000B48FFF7E9F9002383F3118810BDFFF74D -:102370006BFF0748FFF7B6F9F5E7FFF765FF04487D -:10238000FFF7CEF9EFE700BFDC3C0008003D000896 -:10239000F827012038B50C4D0C4C0D492A4604F1A4 -:1023A0000800FFF76FFF05F1CA0204F110000949A8 -:1023B000FFF768FF05F5CA7204F118000649BDE889 -:1023C0003840FFF75FBF00BFC02C0120442201202E -:1023D0002C3D0008363D0008413D000870B504461C -:1023E00008460D46FEF7D4FCC6B2204601340378F9 -:1023F0000BB9184670BD32462946FEF7B1FC0028DD -:10240000F3D1012070BD00002DE9F04704460D46D0 -:10241000FEF7BEFC2C49C6B22046FFF7DFFF08B12D -:102420000736F6B229492046FFF7D8FF08B1103623 -:10243000F6B2632E0BD8DFF89080DFF89090244F2F -:10244000DFF898A0267846B92E70BDE8F0872146BF -:102450002846BDE8F04701F0CDBB252E2FD107223D -:1024600041462046FEF77CFC70B91A4B2A4603F120 -:102470000C0153F8040B42F8040B8B42F9D11B8872 -:10248000138007340E35DDE7082249462046FEF763 -:1024900067FCA0B9104BAA1C13F8011F090953458A -:1024A000C95D02F8021C197801F00F0102F1020265 -:1024B000C95D02F8031CEFD118350834C2E72E704D -:1024C00001340135BEE700BFC83D0008413D0008AA -:1024D000DF3D0008D03D00081FF4F01F2BF4F01F73 -:1024E000BFF34F8F024AD368DB03FCD4704700BFB1 -:1024F000003C024008B5074B1B7853B9FFF7F0FFCB -:10250000054B1A69002ABFBF044A5A6002F188329B -:102510005A6008BD1E2F0120003C02402301674580 -:1025200008B5054B1B7833B9FFF7DAFF034A136987 -:1025300043F00043136108BD1E2F0120003C024000 -:10254000072870B513D80B4A0B4C137863B90B4EA0 -:102550004FF0006144F8231056F823500133082B44 -:102560002944F7D10123137054F8200070BD0020D6 -:1025700070BD00BF402F0120202F0120F03D00083A -:10258000014B53F820007047F03D000808207047C9 -:10259000072810B5044601D9002010BDFFF7D0FF71 -:1025A000064B53F824301844C21A0BB9012010BD51 -:1025B00012680132F0D1043BF6E700BFF03D00089D -:1025C000072810B5044621D8FFF78AFFFFF792FFCE -:1025D0000F4AF323D360C300DBB243F4007343F02C -:1025E00002031361136943F480331361FFF778FF2B -:1025F000FFF7A6FF074B53F8241000F0DDF8FFF7B4 -:102600008FFF2046BDE81040FFF7C2BF002010BD7D -:10261000003C0240F03D00082DE9F84312F00103B0 -:10262000154640D18218B2F1016F3CD22C4B1B6889 -:1026300013F0010337D02B4CFFF75CFFF323E3606B -:10264000FFF74EFF40F20127032D01D9830713D076 -:10265000244C0F46401A40F20118EB1B0B44012B8F -:1026600000EB0706236924D823F001032361FFF759 -:1026700057FF0120BDE8F883236923F440732361E9 -:1026800023693B43236151F8046B0660BFF34F8F0E -:10269000FFF726FF03689E4208D0236923F0010359 -:1026A0002361FFF73DFF0020BDE8F883043D0430BF -:1026B000CAE723F440732361236943EA08032361D3 -:1026C000B94637F8023B3380BFF34F8FFFF708FF5F -:1026D0003688B9F80030B6B2B342BED0DDE700BFED -:1026E00000380240003C0240084908B50B7828B188 -:1026F00053B9FFF7FFFE01230B7008BD23B1BDE8FE -:1027000008400870FFF70CBF08BD00BF1E2F012056 -:1027100010B50244064B0439D2B2904200D110BD2C -:10272000441C00B253F8200041F8040FE0B2F4E773 -:1027300050280040104B30B51C6F240407D41C6F88 -:1027400044F400741C671C6F44F400441C670B4C79 -:10275000236843F4807323600244094B0439D2B2E6 -:10276000904200D130BD441C00B251F8045F43F8E0 -:102770002050E0B2F4E700BF003802400070004093 -:102780005028004007B5012201A90020FFF7C0FF33 -:10279000019803B05DF804FB13B50446FFF7F2FFA0 -:1027A000A04206D002A9012241F8044D0020FFF703 -:1027B000C1FF02B010BD00000144BFF34F8F064BB4 -:1027C000884204D3BFF34F8FBFF36F8F7047C3F8B6 -:1027D0005C022030F4E700BF00ED00E0034B1B6813 -:1027E0009B0042BF024B01221A70704774380240AE -:1027F000412F0120014B1878704700BF412F012065 -:10280000EFF3098305494A6822F001024A60683300 -:1028100083F30988002383F31188704730EF00E0C9 -:10282000202080F3118862B60D4B0E4AD96821F43E -:10283000E0610904090C0A430B49DA60CA6842F0F6 -:102840008072CA60094A0A49C2F8B01F116841F093 -:10285000010111601022DA7783F82200704700BF6F -:1028600000ED00E00003FA05F0ED00E0001000E0EC -:1028700055CEACC510B572B6202383F3118862B66D -:102880000E4B5B6813F4006314D0F1EE103AEFF3D3 -:102890000984683C4FF08073E361094BDB68236671 -:1028A00084F30988FFF73CFB10B1064BA36110BD10 -:1028B000054BFBE783F3118810BD00BF00ED00E07E -:1028C00030EF00E0570300085A030008F0B5BFF3EB -:1028D0004F8FBFF36F8F1D4B0021C3F85012BFF312 -:1028E0004F8FBFF36F8F5A6942F400325A61BFF3C2 -:1028F0004F8FBFF36F8FC3F88410BFF34F8FD3F8A0 -:102900008020C2F3C904C2F34E325201A50743F638 -:10291000E07602EA060E284621464EEA0007013913 -:10292000C3F860724F1C00F14040F6D1203A12F11A -:10293000200FEED1BFF34F8F5A6942F480325A61B3 -:10294000BFF34F8FBFF36F8FF0BD00BF00ED00E00E -:10295000FEE70000084A094B09498B4204D3094AA3 -:102960000021934205D3704752F8040F43F8040B3B -:10297000F3E743F8041BF4E7D83F00085430012084 -:10298000543001205430012070470000036F70B5AF -:10299000C46E9E6800214FF0FF354A01A318013133 -:1029A000D3F800090028BEBFD3F8000940F08040EA -:1029B000C3F80009D3F8000B0028BEBFD3F8000B02 -:1029C00040F08040C3F8000BA3188E42C3F80859AA -:1029D000C3F8085BE1D24FF00113C4F81C3870BD96 -:1029E000890141F02001016103699B06FCD412209A -:1029F000FFF7DABA204B03EB80022DE9F047D2F85B -:102A00000CE0DD6EDEF81420461CD2F800C005EBA9 -:102A1000063605EB4018516861450BD3D5F83428CC -:102A2000012303FA00F022EA0000C5F83408184632 -:102A3000BDE8F087BEF81040ACEB0103A34228BF0D -:102A40002346D8F81849A4B2B3EB840F10D8946881 -:102A50001F46A4F1040959F804AFC6F800A0042FDA -:102A600001D9043FF7E71C440B4494605360D2E75C -:102A70000020BDE8F08700BF442F012010B5054CB1 -:102A80002046FEF719FF4FF0A043E366024B236791 -:102A900010BD00BF442F0120343E00080378012BF5 -:102AA00070B5054650D12A4BC46E98421BD1294BB4 -:102AB0005A6B42F080025A635A6D42F080025A65A6 -:102AC0005A6D5A6942F080025A615A6922F08002B6 -:102AD0005A610E2143205B6900F0F2FB1E4BE3605C -:102AE0001E4BC4F800380023C4F8003EC023236006 -:102AF000EE6E4FF40413A3633369002BFCDA012359 -:102B000033610C20FFF750FA3369DB07FCD4122045 -:102B1000FFF74AFA3369002BFCDA0026A660284644 -:102B2000FFF734FF6B68C4F81068DB68C4F81468FA -:102B3000C4F81C684BB90A4BA3614FF0FF336361C3 -:102B4000A36843F00103A36070BD064BF4E700BF28 -:102B5000442F0120003802404014004003002002AE -:102B6000003C30C0083C30C0F8B5C46E05460021BA -:102B70002046FFF735FF296F00234FF001128F68C1 -:102B8000C4F834384FF00066C4F81C284FF0FF300A -:102B900004EB431201339F42C2F80069C2F8006B94 -:102BA000C2F80809C2F8080BF2D20B68EA6E6B672C -:102BB000636210231361166916F01006FBD1122010 -:102BC000FFF7F2F9D4F8003823F4FE63C4F80038B4 -:102BD000A36943F4402343F01003A3610923C4F81D -:102BE0001038C4F814380A4BEB604FF0C043C4F8F7 -:102BF000103B084BC4F8003BC4F81069C4F8003916 -:102C00006B6F03F1100243F480136A67A362F8BD8F -:102C1000103E000840800010C26E90F86610D2F896 -:102C2000003823F4FE6343EA0113C2F8003870470A -:102C30002DE9F0410EB200EB86080D46D8F80C10D5 -:102C40000F6807F00303022B50D0032B50D03D4AEE -:102C50003D4F012B18BF1746C46E4FEA451E04EBCB -:102C60000E030022C3F8102B8A6905F1100C002A0C -:102C700040D04A8A05F158035B013A43E2500123F0 -:102C8000D4F81C2803FA0CF31343A6444A69C4F889 -:102C90001C380023CEF8103905F13F03002A39D043 -:102CA0000A8A898B9208012988BF4A43416F04EB45 -:102CB0008303561841EA0242466729465A60204675 -:102CC000FFF78EFED8F80C301B8A43EA85531F436A -:102CD00005F148035B01E7500123D4F81C2803FAEF -:102CE00005F51543C4F81C58BDE8F081174FB3E74C -:102CF000174FB1E704EB4613D3F8002B22F4004240 -:102D0000C3F8002BD4F81C28012303FA0CF322EAA1 -:102D10000303BAE704EB83030E4A5A6004EB46163A -:102D200029462046FFF75CFED6F8003923F400431D -:102D3000C6F80039D4F81C38012202FA05F523EA56 -:102D40000505CFE700800010008004100080081007 -:102D500000800C1000040002026F12684267FFF747 -:102D600015BE00005831C36E49015B5813F4004092 -:102D700004D013F4001F14BF01200220704700008C -:102D80004831C36E49015B5813F4004004D013F47A -:102D9000001F14BF012002207047000000EB8101DA -:102DA000CB68196A0B6813604B685360704700006A -:102DB00000EB810330B5DD68AA691368D36019B9E7 -:102DC000402B84BF402313606B8A1468C26E1C447E -:102DD000013CB4FBF3F46343033323F0030302EB3E -:102DE000411043EAC44343F0C043C0F8103B2B6892 -:102DF00003F00303012B09B20ED1D2F8083802EB1D -:102E0000411013F4807FD0F8003B14BF43F080538F -:102E100043F00053C0F8003B02EB4112D2F8003BF4 -:102E200043F00443C2F8003B30BD00002DE9F041FF -:102E3000254DEE6E06EB40130446D3F8087BC3F82D -:102E4000087B38070AD5D6F81438190706D505EBDC -:102E500084032146DB6828465B689847FA0731D52A -:102E6000D6F81438DB072DD505EB8403D968DCB917 -:102E70008B69488A5E68B6FBF0F200FB12629AB971 -:102E80001868DA6890420FD2121A83E8140072B6FA -:102E9000202383F3118862B60B482146FFF788FF91 -:102EA00084F31188BDE8F081012303FA04F26B89F1 -:102EB00023EA02036B81CB6823B121460248BDE8B7 -:102EC000F0411847BDE8F081442F012000EB810359 -:102ED00070B5DD68C36E6C692668E6604A0156BB52 -:102EE0001A444FF40020C2F810092A6802F00302C5 -:102EF000012A0AB20ED1D3F8080803EB421410F4E9 -:102F0000807FD4F8000914BF40F0805040F000509A -:102F1000C4F8000903EB4212D2F8000940F0044063 -:102F2000C2F80009D3F83408012202FA01F1014382 -:102F3000C3F8341870BD19B9402E84BF40202060FA -:102F400020682E8A841940F00050013C1A44B4FBDA -:102F5000F6F440EAC440C6E7F8B504461F48C56E1B -:102F600005EB4413D3F80869C3F80869F10719D5CC -:102F7000D5F81038DA0715D500EB8403D9684B690A -:102F80001F68DA6897421AD2D21B00271A605F6066 -:102F900072B6202383F3118862B62146FFF796FFAD -:102FA00087F31188330617D5D5F834280123A340B9 -:102FB000134211D02046BDE8F840FFF71BBD0123A6 -:102FC00003FA04F2038923EA020303818B68002BCE -:102FD000E8D021469847E5E7F8BD00BF442F01201F -:102FE000A2482DE9F84FC56E6E69AB691E4016F414 -:102FF000805F6E61044605D0FEF7D0FCBDE8F84F57 -:10300000FFF738BC002E12DAD5F8003E97489B0730 -:103010001EBFD5F8003E23F00303C5F8003ED5F8E7 -:10302000043823F00103C5F80438FEF7E7FC370540 -:1030300005D58E48FFF7AAFC8C48FEF7CFFCB004FC -:103040000CD5D5F8083813F0060FEB6823F470534D -:103050000CBF43F4105343F4A053EB60310704D585 -:103060006368DB680BB181489847F2026FD4B30202 -:103070000CD5D4F86C80DFF8F4A100274FF00109DB -:10308000236F9B68F9B28B4280F09C80F70619D5BC -:10309000E16E0A6AC2F30A1702F00F0302F4F0129B -:1030A000B2F5802F00F0B680B2F5402F0AD104EBC4 -:1030B000830301F58051DB68186A00231A469F429A -:1030C00040F09C803303D5F818481DD5E70302D59E -:1030D0000020FFF7ABFEA50302D50120FFF7A6FEF7 -:1030E000600302D50220FFF7A1FE210302D50320D1 -:1030F000FFF79CFEE20202D50420FFF797FEA30231 -:1031000002D50520FFF792FE77037FF577AFE6073C -:1031100002D50020FFF720FFA50702D50120FFF709 -:103120001BFF600702D50220FFF716FF210702D51B -:103130000320FFF711FFE20602D50420FFF70CFF82 -:10314000A3067FF55BAF0520FFF706FF56E7D4F82F -:103150006C80DFF818A100274FF00109236F9B68EE -:103160005FFA87FB5B4582D308EB4B13D3F800294A -:1031700002F44022B2F5802F22D1D3F80029002A90 -:103180001EDAD3F8002942F09042C3F80029D3F8A0 -:103190000029002AFBDB5946E06EFFF721FC22895B -:1031A00009FA0BF322EA0303238104EB8B03DB68A8 -:1031B0009B6813B15946504698475846FFF71AFC8A -:1031C0000137CBE708EB4112D2F8003B03F4402370 -:1031D000B3F5802F10D1D2F8003B002B0CDA6289B6 -:1031E00009FA01F322EA0303638104EB8103DB683C -:1031F000DB680BB150469847013741E79C0708BF91 -:103200000A68072B98BF027003F101039CBF120AE2 -:10321000013054E7023304EB830201F58051526818 -:1032200090690268D0F808C04068A2EB000E002246 -:10323000104697420AD104EB830463689B699A683D -:103240003A449A605A6817445F603BE712F0030FF4 -:1032500008BF0868964588BF8CF8000002F101029B -:1032600084BF000A0CF1010CE3E700BF442F0120EA -:10327000C36E03EB4111D1F8003B43F40013C1F8D6 -:10328000003B7047C36E03EB4111D1F8003943F4A2 -:103290000013C1F800397047C36E03EB4111D1F838 -:1032A000003B23F40013C1F8003B7047C36E03EBEF -:1032B0004111D1F8003923F40013C1F800397047E7 -:1032C00000F1604300F01F02400903F5614309016A -:1032D0008000C9B200F1604083F8001300F561403E -:1032E00001239340C0F880310360704772B62023F9 -:1032F00083F3118862B6704730B5039C01720433C2 -:1033000004FB0325C361049B03630021059B00604C -:103310004060C16042610261856104624262816213 -:10332000C162436330BD00000022416A4161016116 -:10333000C2608262C2626FF00101FEF7ADBE0000A2 -:1033400003694269934203D1C2680AB10020704701 -:10335000181D704703691960C2680132C260C269F2 -:10336000134482690361934224BF436A03610021CD -:10337000FEF786BE38B504460D46E3683BB1626988 -:10338000131D1268A3621344E362002038BD237A40 -:1033900033B929462046FEF763FE0028EDDA38BD32 -:1033A0006FF00100FBE70000C368C269013BC36026 -:1033B0004369134482694361934224BF436A436172 -:1033C00000238362036B03B11847704770B504464E -:1033D000FFF78CFF866A3EB9FFF7CCFF054618B1B0 -:1033E00086F31188284670BDA36AE26A13F8015B70 -:1033F000A362934202D32046FFF7D6FF002383F354 -:103400001188EFE72DE9F04704460E461746984627 -:10341000FFF76CFF0025A946D4F828A0BAF1000FE9 -:1034200009D141462046FFF7A5FF20B18AF3118854 -:103430002846BDE8F087A16AE36AA7EB050A5B1A94 -:103440009A4528BF9A46BAF1400F1BD9334601F17D -:10345000400251F8040B43F8040B9142F9D1A36ADE -:1034600040334036A3624035A26AE36A9A4202D3EF -:103470002046FFF799FF89F31188BD42D8D2FFF7A4 -:1034800035FFC9E730465246FDF760FCA36A534456 -:103490005644A3625544E7E710B5029C0172043319 -:1034A00003FB0421C36100238362C362039B0363A4 -:1034B000049B00604060C4604261026181610462FB -:1034C0004262436310BD0000026AC260426A426108 -:1034D000026100228262C2626FF00101FEF7DCBD70 -:1034E000436902699A4203D1C2680AB10020704759 -:1034F000184650F8043B0B6070470000C368C2696F -:103500000133C3604369134482694361934224BF1A -:10351000436A43610021FEF7B3BD000038B504469D -:103520000D46E3683BB123691A1DA262E2691344A8 -:10353000E362002038BD237A33B929462046FEF7DE -:103540008FFD0028EDDA38BD6FF00100FBE70000C9 -:1035500003691960C268013AC260C2691344826992 -:103560000361934224BF436A036100238362036BB8 -:1035700003B118477047000070B504460E46FFF7C8 -:10358000B5FE856A35B91146FFF7C8FF10B185F35E -:10359000118870BDA36A1E70A36AE26A0133934268 -:1035A000A36204D3E16920460439FFF7D1FF00206C -:1035B00080F3118870BD00002DE9F04704460D46E8 -:1035C00090469946FFF792FE0026B246A76A4FB989 -:1035D00049462046FFF7A2FF20B187F31188304605 -:1035E000BDE8F087A06AE76AA8EB06033F1A9F428E -:1035F00028BF1F46402F1BD905F1400355F8042B67 -:1036000040F8042B9D42F9D1A36A4033A3624036AF -:10361000A26AE36A9A4204D3E16920460439FFF7BB -:1036200097FF8AF311884645D9D2FFF75FFECDE7B1 -:1036300029463A46FDF78AFBA36A3B443D44A36210 -:103640003E44E5E7026943699A4203D1C3681BB966 -:10365000184670470023FBE7836A002BF8D0043B31 -:103660009B1AF5D01360C368013BC360C3691A4459 -:10367000836902619A4224BF436A03610023836223 -:103680000123E5E700F09EB84FF080430022586325 -:103690001A610222DA6070474FF080430022DA603C -:1036A000704700004FF08043586370474FF08043ED -:1036B000586A70474B6843608B688360CB68C3600F -:1036C0000B6943614B6903628B6943620B6803605A -:1036D0007047000008B5274B27481A6940F2FF7170 -:1036E0000A431A611A6922F4FF6222F007021A6182 -:1036F0001A691A6B0A431A631A6D0A431A651F4A3C -:103700001B6D1146FFF7D6FF1D4802F11C01FFF7A4 -:10371000D1FF1C4802F13801FFF7CCFF1A4802F133 -:103720005401FFF7C7FF194802F17001FFF7C2FF0C -:10373000174802F18C01FFF7BDFF164802F1A801FE -:10374000FFF7B8FF144802F1C401FFF7B3FF1348B5 -:1037500002F1E001FFF7AEFF114802F1FC01FFF7B3 -:10376000A9FF104802F58C71FFF7A4FFBDE80840DF -:1037700000F09EB80038024000000240403E0008C1 -:103780000004024000080240000C02400010024009 -:103790000014024000180240001C024000200240B9 -:1037A000002402400028024008B500F005FAFEF7A8 -:1037B000D9FBFFF713F8BDE80840FEF7EBBD0000AA -:1037C000704700000F4B1A6C42F001021A641A6E27 -:1037D00042F001021A660C4A1B6E936843F0010323 -:1037E00093604FF080436B229A624FF0FF32DA62AF -:1037F00000229A615A63DA605A6001225A611A60A3 -:10380000704700BF00380240002004E04FF08042C3 -:1038100008B51369D1680B40D9B2C9439B07116140 -:1038200009D572B6202383F3118862B6FEF7BAFB7E -:10383000002383F3118808BD1B4B1A696FEA4252BB -:103840006FEA52521A611A69C2F30A021A614FF002 -:10385000FF301A695A69586100215A6959615A69D9 -:103860001A6A62F080521A621A6A02F080521A6270 -:103870001A6A5A6A58625A6A59625A6A0B4A106836 -:1038800040F480701060186F00F44070B0F5007F55 -:103890001EBF4FF4803018671967536823F4007314 -:1038A000536000F061B900BF003802400070004072 -:1038B000384B4FF080521A64374A4FF44041116040 -:1038C0001A6842F001021A601A689207FCD59A68D9 -:1038D00022F003029A602F4B19469A6812F00C02EC -:1038E000FBD1186800F0F90018609A601A6842F479 -:1038F00080321A600B689B03FCD54B6F43F00103C9 -:103900004B67244B5A6F9007FCD5244A5A601A68BB -:1039100042F080721A60204B1A4659684904FCD55F -:10392000196841F4803119605368D803FCD51368D5 -:1039300043F400331360184A53689903FCD5154BC0 -:103940001A689201FCD5164A9A6040F20112C3F837 -:103950008C200022C3F89020124B40F207321A60EC -:103960001A6802F00F02072AFAD10A4B9A6842F04D -:1039700002029A609A6802F00C02082AFAD15A6C84 -:1039800042F480425A645A6E42F480425A665B6E38 -:10399000704700BF0038024000700040086C4009CA -:1039A00000948838003C0240074A08B5536903F088 -:1039B0000103536123B1054A13680BB1506898475E -:1039C000BDE80840FEF756BF003C0140D42F01205F -:1039D000074A08B5536903F00203536123B1054A4E -:1039E00093680BB1D0689847BDE80840FEF742BF26 -:1039F000003C0140D42F0120074A08B5536903F069 -:103A00000403536123B1054A13690BB15069984708 -:103A1000BDE80840FEF72EBF003C0140D42F012036 -:103A2000074A08B5536903F00803536123B1054AF7 -:103A300093690BB1D0699847BDE80840FEF71ABFFB -:103A4000003C0140D42F0120074A08B5536903F018 -:103A50001003536123B1054A136A0BB1506A9847AA -:103A6000BDE80840FEF706BF003C0140D42F01200E -:103A7000164B10B55C6904F478725A61A30604D53C -:103A8000134A936A0BB1D06A9847600604D5104A6E -:103A9000136B0BB1506B9847210604D50C4A936BFE -:103AA0000BB1D06B9847E20504D5094A136C0BB1F2 -:103AB000506C9847A30504D5054A936C0BB1D06CA4 -:103AC0009847BDE81040FEF7D5BE00BF003C01405E -:103AD000D42F0120194B10B55C6904F47C425A6163 -:103AE000620504D5164A136D0BB1506D9847230536 -:103AF00004D5134A936D0BB1D06D9847E00404D5FB -:103B00000F4A136E0BB1506E9847A10404D50C4AAE -:103B1000936E0BB1D06E9847620404D5084A136FB8 -:103B20000BB1506F9847230404D5054A936F0BB12E -:103B3000D06F9847BDE81040FEF79CBE003C0140A6 -:103B4000D42F012008B50348FDF7C2FABDE80840AC -:103B5000FEF790BED423012008B5FFF757FEBDE85D -:103B60000840FEF787BE0000062108B50846FFF7AB -:103B7000A7FB06210720FFF7A3FB06210820FFF77C -:103B80009FFB06210920FFF79BFB06210A20FFF778 -:103B900097FB06211720FFF793FB06212820FFF74C -:103BA0008FFB07211C20FFF78BFB0C212520BDE894 -:103BB0000840FFF785BB000008B5FFF73DFE00F0A9 -:103BC0000DF8FDF795FCFDF775FEFDF743FDFFF7DA -:103BD000F7FDBDE80840FFF755BD0000002304498C -:103BE0001A465A50C8180833802B4260F9D17047E2 -:103BF000D42F0120034611F8012B03F8012B002AD2 -:103C0000F9D170471210121312110000F827012089 -:103C1000D423012053544D3332463F3F3F3F3F3F73 -:103C20000053544D333246375B347C355D78005356 -:103C3000544D333246375B367C375D7800000000E8 -:103C400000960000000000000000000000000000DE -:103C5000000000000000000000000000B91400088F -:103C6000A5140008E1140008CD140008D9140008B8 -:103C7000C5140008B11400089D140008ED140008D4 -:103C800000000000CD150008B9150008F515000862 -:103C9000E1150008ED150008D9150008C515000844 -:103CA000B1150008511600080000000001000000D6 -:103CB000000000006D61696E00000000D43C000847 -:103CC00080260120F827012001000000611F000864 -:103CD0000000000069646C65000000000200000044 -:103CE00000000000F91700086118000840004000BB -:103CF000902C0120A02C01200200000000000000F8 -:103D00000300000000000000A518000800000000EB -:103D100010000000B02C0120000000000100000095 -:103D200000000000442F012001010200417264756F -:103D300050696C6F740025424F415244252D424C0E -:103D4000002553455249414C250000003923000805 -:103D500055220008E9220008D12200084300000093 -:103D6000643D000809024300020100C0320904005A -:103D700000010202010005240010010524010001D8 -:103D8000042402020524060001070582030800FF3F -:103D900009040100020A00000007050102400000BA -:103DA000070581024000000012000000B03D00083D -:103DB00012011001020000400912415700020102E5 -:103DC000030100000403090425424F415244250029 -:103DD000466C79776F6F463734354E616E6F0030C1 -:103DE0003132333435363738394142434445460061 -:103DF00000800000008000000080000000800000C3 -:103E000000000200000004000000040000000400A4 -:103E100000000000111A0008E91C0008911D0008AC -:103E200040004000BC2F0120BC2F012001000000F9 -:103E3000CC2F0120800000004001000005000000A0 -:103E40000001A82A00000000AAAAAAAA00011400E2 -:103E5000FFFF00000000000070A70A000000000142 -:103E600000000000AAAAAAAA00000001FFFF0000AB -:103E7000000000000000000000000004000000003E -:103E8000AAAAAAAA00000000FFDF000000000000AC -:103E9000000000000000000000000000AAAAAAAA7A -:103EA00000000000FFFF0000000000000000000014 -:103EB0000001000000000000AAAAAAAA0001000058 -:103EC000FFFF0000000000000000000000000000F4 -:103ED00000000000AAAAAAAA00000000FFFF00003C -:103EE00000000000000000000000000000000000D2 -:103EF000AAAAAAAA00000000FFFF0000000000001C -:103F00000000000000000000000000000A000000A7 -:103F1000000000000300000000000000000000009E -:103F20000000000000000000000000000000000091 +:10199000A2606360F0BC01F0ADBA000070B5022334 +:1019A000002504460370C0E90255C0E90455C0E9AA +:1019B00006554566056280F84C5001F0F1F8636801 +:1019C0001B6823B129462046BDE87040184770BD0A +:1019D000037880F868300523037043681B6810B5EE +:1019E00004460BB1042198470023A36010BD0000FA +:1019F00090F86820436802701B680BB105211847F6 +:101A00007047000070B590F84C30044613B10023C5 +:101A100080F84C3004F15C02204601F0D3F9636891 +:101A20009B68B3B994F85C3013F0600533D00021A3 +:101A3000204601F03FFC0021204601F031FC6368A4 +:101A40001B6813B1062120469847062384F84C30C2 +:101A500070BD204698470028E4D0B4F86230626D2B +:101A60009A4288BF636594F95C30656D002B80F203 +:101A70000281002D00F0F180092384F84C30FFF73B +:101A800019FF0021D4E914232046FFF775FF002336 +:101A900083F31188DCE794F85D2003F07F0343EAC9 +:101AA000022340F20232934200F0C48021D8B3F501 +:101AB000807F48D00DD8012B3FD0022B00F09280C0 +:101AC000002BB4D104F16402226502226265A36591 +:101AD000C3E7B3F5817F00F09A80B3F5407FA6D1CC +:101AE00094F85E30012BA2D1B4F8643043F00203C5 +:101AF00032E0B3F5006F4DD017D8B3F5A06F31D0F9 +:101B0000A3F5C063012B92D8636894F85E205E68E9 +:101B100094F85F10B4F860302046B047002886D0B3 +:101B200043682365036863651AE0B3F5106F36D028 +:101B300040F6024293427FF47AAF5B4B2365022367 +:101B400063650023C3E794F85E30012B7FF46FAF29 +:101B5000B4F8643023F00203C4E91455A4F86430E7 +:101B6000A5657AE7B4F85C30B3F5A06F0ED194F8B0 +:101B70005E3084F86630204601F06AF863681B68BE +:101B800013B1012120469847032323700023C4E9A1 +:101B900014339CE704F1670323650123C3E723782B +:101BA000042B0FD12046FFF785FEFFF7C7FE85F314 +:101BB00011880321636884F8675021701B680BB19A +:101BC0002046984794F85E30002BDFD084F86730C9 +:101BD0000423237063681B68002BD7D002212046A2 +:101BE0009847D3E794F860301D0603F00F012046B4 +:101BF0000AD501F0D9F8012804D002287FF417AFE4 +:101C00002A4B9BE72A4B99E701F0C0F8F3E794F8D9 +:101C10005E30002B7FF40BAF94F8603013F00F01AF +:101C2000B4D01A06204602D501F058FBAEE701F009 +:101C30004BFBABE794F85E30002B7FF4F8AE94F8E2 +:101C4000603013F00F01A1D01B06204602D501F031 +:101C500031FB9BE701F024FB98E7142384F84C3018 +:101C6000FFF728FE2A462B4629462046FFF772FE3C +:101C700085F31188ECE65DB1152384F84C30FFF74D +:101C800019FE0021D4E914232046FFF763FEFEE687 +:101C90000B2384F84C30FFF70DFE2A462B462946CD +:101CA0002046FFF769FEE3E7C03C0008B83C0008A7 +:101CB000BC3C000838B590F84C300446002B3CD0B2 +:101CC000063BDAB20F2A32D80F2B30D8DFE803F008 +:101CD000352F2F0821302F2F2F2F2F2F2F2F353536 +:101CE000456DB0F862309D4213D2C3681B8AB5FBC4 +:101CF000F3F203FB125565B9FFF7DCFD2A462B46CC +:101D00002946FFF739FE85F311880A2384F84C3001 +:101D10000DE0142384F84C30FFF7CCFD00231A4665 +:101D200019462046FFF716FE002383F3118838BDBD +:101D3000836D03B198470023E8E70021204601F0B6 +:101D4000B9FA0021204601F0ABFA63681B6813B1B1 +:101D50000621204698470623D8E7000010B590F8E2 +:101D60004C30142B044628D017D8062B05D001D8A8 +:101D70001BB110BD093B022BFBD80021204601F00E +:101D800099FA0021204601F08BFA63681B6813B1B1 +:101D9000062120469847062318E0152BE9D10B238E +:101DA00080F84C30FFF786FD00231A461946FFF7EE +:101DB000E3FD002383F31188DBE7C3689B695B685D +:101DC000002BD6D1836D03B19847002384F84C30A3 +:101DD000CFE70000024B0022C3E900339A6070474E +:101DE00040260120002303748268054B1B68996814 +:101DF0009142FBD25A68036042601060586070479D +:101E00004026012008B572B6202383F3118862B6FC +:101E1000037C032B05D0042B0DD02BB983F3118841 +:101E200008BD436900221A604FF0FF334361FFF79A +:101E3000D9FF0023F2E7D0E9003213605A60F3E7DC +:101E4000002303748268054B1B6899689142FBD894 +:101E50005A68036042601060586070474026012055 +:101E6000054B19690874186802681A605360186194 +:101E700001230374FEF75ABA4026012030B54B1CEB +:101E80000B4D87B0044610D02B690A4A01A800F018 +:101E90002DF92046FFF7E4FF049B13B101A800F0E1 +:101EA00061F92B69586907B030BDFFF7D9FFF8E732 +:101EB00040260120051E000838B50C4D41612B69F4 +:101EC00081689A689142044603D8BDE83840FFF71C +:101ED00089BF1846FFF7B4FF01232C610146237424 +:101EE0002046BDE83840FEF721BA00BF4026012059 +:101EF000044B1A681B6990689B68984294BF002045 +:101F0000012070474026012010B5084C2368206945 +:101F10001A6822605460012223611A74FFF790FF4F +:101F200001462069BDE81040FEF700BA40260120B6 +:101F300008B5FFF7DDFF18B1BDE80840FFF7E4BFC3 +:101F400008BD0000FFF7E0BFFEE7000010B50C4C35 +:101F5000FFF740FF00F0BCF80A498022204600F05D +:101F600043F8012344F8180C037400F07DFC0023AF +:101F700083F3118862B60448BDE8104000F054B8FD +:101F800068260120C43C0008D43C000800F024B9B5 +:101F9000EFF3118030B9EFF30583202272B682F39C +:101FA000118862B67047000010B530B9EFF30584B0 +:101FB000C4F3080414B180F3118810BDFFF7B8FF13 +:101FC00084F31188F9E70000034A516853685B1AEB +:101FD0009842FBD8704700BF001000E072B6202383 +:101FE00083F3118862B670478260022202827047D2 +:101FF0008368A3F17C0243F80C2C026943F83C2C63 +:10200000426943F8382C074A43F81C2CC26843F84D +:10201000102C022203F8082C002203F8072CA3F14D +:10202000180070474503000810B5FFF7D7FFFFF70A +:10203000DFFF00210446FFF73FFF002383F31188F1 +:10204000204610BD024B1B6958610F20FFF708BFE7 +:102050004026012008B5FFF7C1FFBDE80840FFF7A3 +:10206000F1BF000008B501460820FFF7B7FFFFF7F2 +:1020700005FF002383F3118808BD000049B1064B1A +:1020800042681B6918605A60136043600420FFF7C0 +:10209000F5BE4FF0FF30704740260120036898429C +:1020A00006D01A680260506059611846FFF79ABE60 +:1020B0007047000038B504460D462068844200D1C0 +:1020C00038BD036823605C604561FFF78BFEF4E771 +:1020D000054B03F11402C3E905224FF0FF31002242 +:1020E000C3E90712704700BF4026012070B51C4E9F +:1020F000C0E9032305460C4601F0EEFA334653F8D7 +:10210000142F9A420DD13062C5E901242A600A2CAD +:102110002CBF00190A30C6E90555BDE8704001F032 +:10212000C9BA316A431AE31838BF1C469368A34200 +:1021300002D9081901F0CCFA73699A6894420CD854 +:102140005A68AC602B606A6015609A685D60121B0B +:102150009A604FF0FF33F36170BD1B68A41AECE77F +:102160004026012038B51B4C636998420DD0D0E958 +:10217000003213605A6000228168C2609A680A4483 +:102180009A604FF0FF33E36138BD2246036842F89E +:10219000143F002193425A60C16003D1BDE838402A +:1021A00001F090BA9A688168256A0A449A6001F041 +:1021B00093FA63699A68411B8A42E5D9AB181D1AE4 +:1021C000092D206A98BF01F10A02BDE83840104489 +:1021D00001F07EBA402601202DE9F041194C00277C +:1021E00004F11406656901F077FA236AAA68C11A36 +:1021F0008A4217D813442362D5E9003213605A602B +:102200006369D5F80C80EF60B34201D101F05AFA4E +:1022100087F311882869C04772B6202383F3118899 +:1022200062B6DFE76169B14209D013441B1ABDE809 +:10223000F0410A2B2CBFC0180A3001F049BABDE8A2 +:10224000F08100BF4026012000207047FEE700001B +:10225000704700004FF0FF307047000072B6202337 +:1022600083F3118862B6704702290CD0032904D089 +:102270000129074818BF00207047032A05D80548E0 +:1022800000EBC2007047044870470020704700BF51 +:10229000B83D0008482201206C3D000870B59AB096 +:1022A0000546084601A9144600F0BEF801A8FEF74D +:1022B00085FD431C5B00C5E9003400222370032325 +:1022C0006370C6B201AB02341046D1B28E4204F143 +:1022D000020401D81AB070BD13F8011B04F8021CE7 +:1022E00004F8010C0132F0E708B50448FFF7B6FF27 +:1022F000FFF760FA002383F3118808BDF827012057 +:1023000090F85C3003F01F02012A07D190F85D209D +:102310000B2A03D10023C0E9143315E003F0600356 +:10232000202B08D1B0F860302BB990F85D20212A1D +:1023300003D81F2A04D8FFF71FBA222AEBD0FAE7E6 +:10234000034A02650722426583650120704700BF8A +:102350003F22012007B5052916D8DFE801F018153E +:102360000318181E104A0121FFF778FF0190FFF7AC +:10237000CBFA01980D4A0221FFF7C6FA0C48FFF785 +:10238000E5F9002383F3118803B05DF804FB0848E6 +:10239000FFF764FFFFF7B0F9F3E70548FFF75EFFCB +:1023A000FFF7C8F9EDE700BF0C3D0008303D00081D +:1023B000F827012038B50C4D0C4C0D492A4604F184 +:1023C0000800FFF76BFF05F1CA0204F1100009498C +:1023D000FFF764FF05F5CA7204F118000649BDE86D +:1023E0003840FFF75BBF00BFC02C0120482201200E +:1023F000EC3C0008F63C0008013D000870B50446BE +:1024000008460D46FEF7DAFCC6B2204601340378D2 +:102410000BB9184670BD32462946FEF7BBFC0028B2 +:10242000F3D10120F6E700002DE9F04705460C4600 +:10243000FEF7C4FC2B49C6B22846FFF7DFFF08B100 +:102440000736F6B228492846FFF7D8FF08B11036FC +:10245000F6B2632E0BD8DFF88C80DFF88C90234F18 +:10246000DFF894A02E7846B92670BDE8F08729469B +:102470002046BDE8F04701F0C9BB252E2ED107222A +:1024800041462846FEF786FC70B9194B224603F1F7 +:102490000C0153F8040B42F8040B8B42F9D11B8852 +:1024A000138007350E34DDE7082249462846FEF73B +:1024B00071FC98B90F4BA21C197809090232C95D49 +:1024C00002F8041C13F8011B01F00F015345C95D0C +:1024D00002F8031CF0D118340835C3E704F8016B87 +:1024E0000135BFE7D83D0008013D0008EF3D000879 +:1024F000E03D000820F4F01F2CF4F01FBFF34F8FD5 +:10250000024AD368DB03FCD4704700BF003C0240A2 +:1025100008B5074B1B7853B9FFF7F0FF054B1A6955 +:10252000002ABFBF044A5A6002F188325A6008BDCF +:102530001E2F0120003C02402301674508B5054BD2 +:102540001B7833B9FFF7DAFF034A136943F00043FE +:10255000136108BD1E2F0120003C02400728F0B582 +:1025600016D80C4C0C4923787BB90C4D0E46082329 +:102570004FF0006255F8047B46F8042B013B13F042 +:10258000FF033A44F6D10123237051F82000F0BD37 +:102590000020FCE7402F0120202F0120003E0008F2 +:1025A000014B53F820007047003E00080820704798 +:1025B000072810B5044601D9002010BDFFF7CEFF53 +:1025C000064B53F824301844C21A0BB90120F4E723 +:1025D00012680132F0D1043BF6E700BF003E00086C +:1025E000072838B5044628D8FFF7D2FCFFF786FF46 +:1025F000FFF78EFF124AF323D360E300DBB243F40C +:10260000007343F002031361136943F480331361D1 +:1026100005462046FFF772FFFFF7A0FF094B53F86E +:10262000241000F0E9F82846FFF788FFFFF7BCFC0C +:102630002046BDE83840FFF7BBBF002038BD00BFD3 +:10264000003C0240003E000812F001032DE9F04179 +:1026500005460E4614464BD18218B2F1016F61D87F +:10266000314B1B6813F001035CD0304FFFF790FC37 +:10267000FFF74EFFF323FB60FFF740FF314640F2C8 +:102680000128032C18D824F00104284E0C446D1A9C +:1026900040F20118A142336905EB01072AD123F06A +:1026A00001033361FFF74AFFFFF77EFC0120BDE81D +:1026B000F081043C0435E4E7AB07E4D13B6923F443 +:1026C00040733B613B6943EA08033B6151F8046B8B +:1026D0002E60BFF34F8FFFF711FF2B689E42E8D0AB +:1026E0003B6923F001033B61FFF728FFFFF75CFC28 +:1026F0000020DCE723F440733361336943EA0803C5 +:1027000033610B883B80BFF34F8FFFF7F7FE3F88A5 +:1027100031F8023BBFB2BB42BCD0336923F00103A6 +:102720003361E1E71846C2E700380240003C02404E +:10273000084908B50B7828B11BB9FFF7E9FE01235A +:102740000B7008BD002BFCD0BDE808400870FFF7F7 +:10275000F5BE00BF1E2F012010B50244064BD2B2B9 +:10276000904200D110BD441C00B253F8200041F843 +:10277000040BE0B2F4E700BF502800400F4B30B527 +:102780001C6F240407D41C6F44F400741C671C6F76 +:1027900044F400441C670A4C236843F480732360AC +:1027A0000244084BD2B2904200D130BD441C00B26A +:1027B00051F8045B43F82050E0B2F4E700380240DF +:1027C000007000405028004007B5012201A90020F8 +:1027D000FFF7C2FF019803B05DF804FB13B5044690 +:1027E000FFF7F2FFA04205D0012201A900200194C9 +:1027F000FFF7C4FF02B010BD0144BFF34F8F064B7B +:10280000884204D3BFF34F8FBFF36F8F7047C3F875 +:102810005C022030F4E700BF00ED00E0034B1A68D3 +:102820001AB9034AD2F874281A607047442F01205D +:102830000030024008B5FFF7F1FF024B1868C0F303 +:10284000407008BD442F0120EFF3098305494A6B0E +:1028500022F001024A63683383F30988002383F37B +:102860001188704700EF00E0202080F3118862B6E5 +:102870000D4B0E4AD96821F4E0610904090C0A43A2 +:10288000DA60D3F8FC200A4942F08072C3F8FC20D9 +:10289000084AC2F8B01F116841F00101116010220E +:1028A000DA7783F82200704700ED00E00003FA05B4 +:1028B00055CEACC5001000E010B572B6202383F3EE +:1028C000118862B60E4B5B6813F4006314D0F1EE0E +:1028D000103AEFF30984683C4FF08073E361094BD1 +:1028E000DB6B236684F30988FFF702FB10B1064B0C +:1028F000A36110BD054BFBE783F31188F9E700BF27 +:1029000000ED00E000EF00E0570300085A03000864 +:1029100070B5BFF34F8FBFF36F8F1A4A0021C2F813 +:102920005012BFF34F8FBFF36F8F536943F40033DF +:102930005361BFF34F8FBFF36F8FC2F88410BFF3A3 +:102940004F8FD2F88030C3F3C900C3F34E335B011D +:1029500043F6E07403EA0406014646EA817501394C +:10296000C2F86052F9D2203B13F1200FF2D1BFF32D +:102970004F8F536943F480335361BFF34F8FBFF3DD +:102980006F8F70BD00ED00E0FEE700000A4B0B48C2 +:102990000B4A90420BD30B4BDA1C121AC11E22F0C9 +:1029A00003028B4238BF00220021FEF70FBA53F812 +:1029B000041B40F8041BECE7F03F000858300120EE +:1029C00058300120583001207047000070B5D0E920 +:1029D0001B439E6800224FF0FF3504EB4213510168 +:1029E000D3F800090028BEBFD3F8000940F08040AA +:1029F000C3F80009D3F8000B0028BEBFD3F8000BC2 +:102A000040F08040C3F8000B013263189642C3F8CF +:102A10000859C3F8085BE0D24FF00113C4F81C3822 +:102A200070BD00001D4B03EB80022DE9F043D2F88E +:102A30000CC0DD6EDCF81420461CD2F800E005EB7B +:102A4000063605EB4018516871450AD3D5F834387D +:102A5000012202FA00F023EA0000C5F83408BDE8BC +:102A6000F083BCF81040AEEB0103A34228BF23461D +:102A7000D8F81849A4B2B3EB840FF0D89468A4F145 +:102A8000040959F8047F3760A4EB09071F44042F99 +:102A9000F7D81C440B4494605360D4E7482F0120BE +:102AA000890141F02001016103699B06FCD41220D9 +:102AB000FFF78ABA10B5054C2046FEF703FF4FF02A +:102AC000A043E366024B236710BD00BF482F0120DF +:102AD000443E000870B50378012B054650D12A4BBF +:102AE000C46E98421BD1294B5A6B42F080025A6344 +:102AF0005A6D42F080025A655A6D5A6942F080025E +:102B00005A615A6922F080025A610E2143205B69A2 +:102B100000F0EEFB1E4BE3601E4BC4F800380023B0 +:102B2000C4F8003EC0232360EE6E4FF40413A36389 +:102B30003369002BFCDA012333610C20FFF744FAE0 +:102B40003369DB07FCD41220FFF73EFA3369002B10 +:102B5000FCDA0026A6602846FFF738FF6B68C4F849 +:102B60001068DB68C4F81468C4F81C684BB90A4BD9 +:102B7000A3614FF0FF336361A36843F00103A360D7 +:102B800070BD064BF4E700BF482F0120003802401B +:102B90004014004003002002003C30C0083C30C01C +:102BA000F8B5C46E054600212046FFF779FF296F6E +:102BB00000234FF001128F68C4F834384FF00066DC +:102BC000C4F81C284FF0FF3004EB431201339F423E +:102BD000C2F80069C2F8006BC2F80809C2F8080B15 +:102BE000F2D20B68EA6E6B67636210231361166999 +:102BF00016F01006FBD11220FFF7E6F9D4F80038E2 +:102C000023F4FE63C4F80038A36943F4402343F07F +:102C10001003A3610923C4F81038C4F814380A4B10 +:102C2000EB604FF0C043C4F8103B084BC4F8003BC6 +:102C3000C4F81069C4F800396B6F03F1100243F453 +:102C400080136A67A362F8BD203E00084080001030 +:102C5000C26E90F86610D2F8003823F4FE6343EA9F +:102C60000113C2F8003870472DE9F84300EB8103E7 +:102C7000C56EDA68166806F00306731E022B05EBB4 +:102C800041130C4680460FFA81F94FEA41104FF08C +:102C90000001C3F8101B4FF0010104F1100398BFAD +:102CA000B60401FA03F391698EBF334E06F18056E4 +:102CB00006F5004600293AD0578A04F15801490127 +:102CC00037436F50D5F81C180B43C5F81C382B1828 +:102CD0000021C3F8101953690127611EA7409BB357 +:102CE000138A928B9B08012A88BF5343D8F874201B +:102CF000981842EA034301F1400205EB8202C8F84A +:102D00007400214653602846FFF7CAFE08EB89008D +:102D1000C3681B8A43EA8453483464011E432E511E +:102D2000D5F81C381F43C5F81C78BDE8F88305EBBF +:102D30004917D7F8001B21F40041C7F8001BD5F84C +:102D40001C1821EA0303C0E704F13F0305EB8303EA +:102D50000A4A5A6028462146FFF7A2FE05EB4910B1 +:102D6000D0F8003923F40043C0F80039D5F81C38F6 +:102D700023EA0707D7E700BF008000100004000225 +:102D8000026F12684267FFF721BE00005831C36E20 +:102D900049015B5813F4004004D013F4001F0CBF2A +:102DA00002200120704700004831C36E49015B5882 +:102DB00013F4004004D013F4001F0CBF02200120C4 +:102DC0007047000000EB8101CB68196A0B68136043 +:102DD0004B6853607047000000EB810330B5DD683D +:102DE000AA691368D36019B9402B84BF40231360CC +:102DF0006B8A1468C26E1C44013CB4FBF3F4634359 +:102E0000033323F0030302EB411043EAC44343F0CE +:102E1000C043C0F8103B2B6803F00303012B09B239 +:102E20000ED1D2F8083802EB411013F4807FD0F8AD +:102E3000003B14BF43F0805343F00053C0F8003B05 +:102E400002EB4112D2F8003B43F00443C2F8003BCE +:102E500030BD00002DE9F041254DEE6E06EB40132C +:102E60000446D3F8087BC3F8087B38070AD5D6F8A0 +:102E70001438190706D505EB84032146DB6828467C +:102E80005B689847FA0721D5D6F81438DB071DD5BB +:102E900005EB8403D968DCB98B69488A5A68B2FBB0 +:102EA000F0F600FB16229AB91868DA6890420FD241 +:102EB000121AC3E9002472B6202383F3118862B684 +:102EC0000B482146FFF788FF84F31188BDE8F081A5 +:102ED000012303FA04F26B8923EA02036B81CB68B6 +:102EE000002BF3D021460248BDE8F041184700BF4F +:102EF000482F012000EB810370B5DD68C36E6C695B +:102F00002668E6604A0156BB1A444FF40020C2F816 +:102F100010092A6802F00302012A0AB20ED1D3F87E +:102F2000080803EB421410F4807FD4F8000914BFA2 +:102F300040F0805040F00050C4F8000903EB42120A +:102F4000D2F8000940F00440C2F80009D3F8340870 +:102F5000012202FA01F10143C3F8341870BD19B916 +:102F6000402E84BF4020206020682E8A8419013CB6 +:102F7000B4FBF6F440EAC44040F000501A44C6E7FF +:102F8000F8B504461F48C56E05EB4413D3F808692D +:102F9000C3F80869F10719D5D5F81038DA0715D53F +:102FA00000EB8403D9684B691F68DA6897421AD22C +:102FB000D21B00271A605F6072B6202383F311884A +:102FC00062B62146FFF796FF87F31188330617D5BF +:102FD000D5F834280123A340134211D02046BDE880 +:102FE000F840FFF71FBD012303FA04F2038923EA27 +:102FF000020303818B68002BE8D021469847E5E760 +:10300000F8BD00BF482F01202DE9F74FA34CE66E15 +:103010007569B3691D4015F48058756107D0204665 +:10302000FEF7BCFC03B0BDE8F04FFFF745BC002D38 +:1030300012DAD6F8003E99489F071EBFD6F8003E28 +:1030400023F00303C6F8003ED6F8043823F001034A +:10305000C6F80438FEF7CCFC280505D58F48FFF7E5 +:10306000B5FC8E48FEF7B4FCA9040CD5D6F8083898 +:1030700013F0060FF36823F470530CBF43F410539E +:1030800043F4A053F3602A0704D56368DB680BB1EF +:1030900082489847EB0200F18A80AF0227D5D4F826 +:1030A0006C90DFF8F8B100274FF0010A09EB4712E6 +:1030B000D2F8003B03F44023B3F5802F11D1D2F8AE +:1030C000003B002B0DDA62890AFA07F322EA0303B8 +:1030D000638104EB8703DB68DB6813B1394658462C +:1030E0009847236F01379B68FFB29F42DED9E806FD +:1030F00018D5E76E3A6AC2F30A1002F00F0302F421 +:10310000F012B2F5802F00F09D80B2F5402F09D16A +:1031100004EB83030022DB681B6A07F580579042AB +:1031200040F082802B03D6F818481DD5E70302D55E +:103130000020FFF78FFEA60302D50120FFF78AFECD +:10314000600302D50220FFF785FE210302D503208C +:10315000FFF780FEE20202D50420FFF77BFEA30208 +:1031600002D50520FFF776FE6F037FF55BAFE6071C +:1031700002D50020FFF704FFA50702D50120FFF7C5 +:10318000FFFE600702D50220FFF7FAFE210702D5F5 +:103190000320FFF7F5FEE20602D50420FFF7F0FE5C +:1031A000A3067FF53FAF0520FFF7EAFE3AE7E36E9F +:1031B000DFF8E8B0019300274FF0010A236F9B6806 +:1031C0005FFA87F999453FF668AF019B03EB491316 +:1031D000D3F8002902F44022B2F5802F22D1D3F88F +:1031E0000029002A1EDAD3F8002942F09042C3F8E1 +:1031F0000029D3F80029002AFBDBE06E4946FFF7DF +:103200004FFC22890AFA09F322EA0303238104EB23 +:103210008903DB689B6813B149465846984748467E +:10322000FFF700FC0137C9E7910708BFD7F8008016 +:10323000072A98BF03F8018B02F1010298BF4FEAF9 +:1032400018286CE7023304EB830207F580575268B5 +:10325000D2F818C0DCF80820DCE9001CA1EB0C0C4B +:10326000002188420AD104EB830463689B699A6851 +:1032700002449A605A6802445A6053E711F0030FFF +:1032800008BFD7F800808C4588BF02F8018B01F198 +:10329000010188BF4FEA1828E3E700BF482F01204B +:1032A000C36E03EB4111D1F8003B43F40013C1F8A6 +:1032B000003B7047C36E03EB4111D1F8003943F472 +:1032C0000013C1F800397047C36E03EB4111D1F808 +:1032D000003B23F40013C1F8003B7047C36E03EBBF +:1032E0004111D1F8003923F40013C1F800397047B7 +:1032F00000F1604303F561430901C9B283F800138B +:10330000012200F01F039A4043099B0003F1604330 +:1033100003F56143C3F880211A60704772B6202319 +:1033200083F3118862B6704730B5039C0172043391 +:1033300004FB0325C0E90653049B03630021059B9E +:10334000C160C0E90000C0E90422C0E90842C0E948 +:103350000A11436330BD0000416A0022C0E9041134 +:10336000C0E90A22C2606FF00101FEF7A3BE0000AF +:10337000D0E90432934201D1C2680AB9181D7047DE +:103380000020704703691960C2680132C260C269D7 +:10339000134482690361934224BF436A036100219D +:1033A000FEF77CBE38B504460D46E3683BB1626962 +:1033B000131D1268A3621344E362002007E0237A1E +:1033C00033B929462046FEF759FE0028EDDA38BD0C +:1033D0006FF00100FBE70000C368C269013BC360F6 +:1033E0004369134482694361934224BF436A436142 +:1033F00000238362036B03B11847704770B5FFF772 +:103400008DFF866A04463EB9FFF7CCFF054618B12A +:1034100086F31188284670BDA36AE26A13F8015B3F +:10342000A362934202D32046FFF7D6FF002383F323 +:103430001188EFE72DE9F0479846FFF76FFF002569 +:1034400004460E461746A946D4F828A0BAF1000F44 +:1034500009D141462046FFF7A5FF20B18AF3118824 +:103460002846BDE8F087D4E90A12A7EB050A521AEC +:10347000924528BF9246BAF1400F1BD9334601F15D +:10348000400251F8040B43F8040B9142F9D1A36AAE +:1034900040334036A3624035D4E90A239A4202D32E +:1034A0002046FFF799FF89F31188BD42D8D2FFF774 +:1034B00035FFC9E730465246FDF762FCA36A534424 +:1034C0005644A3625544E7E710B5029C01720433E9 +:1034D00004FB0321C0E906130023C0E90A33039B60 +:1034E0000363049BC460C0E90000C0E90422C0E992 +:1034F0000842436310BD0000026AC260426AC0E92C +:1035000004220022C0E90A226FF00101FEF7D2BDB9 +:10351000D0E904239A4201D1C26822B9184650F872 +:10352000043B0B607047002070470000C368C2690D +:103530000133C3604369134482694361934224BFEA +:10354000436A43610021FEF7A9BD000038B5044677 +:103550000D46E3683BB123691A1DA262E269134478 +:10356000E362002007E0237A33B929462046FEF7BC +:1035700085FD0028EDDA38BD6FF00100FBE70000A3 +:1035800003691960C268013AC260C2691344826962 +:103590000361934224BF436A036100238362036B88 +:1035A00003B118477047000070B5FFF7B7FE866A91 +:1035B0000D46044611462EB9FFF7C8FF10B186F339 +:1035C000118870BDA36A1D70A36AE26A0133934239 +:1035D000A36204D3E16920460439FFF7D1FF00203C +:1035E00080F31188EDE700002DE9F0479946FFF7D9 +:1035F00095FE002604460D469046B246A76A4FB98E +:1036000049462046FFF7A2FF20B187F311883046D4 +:10361000BDE8F087D4E90A073A1AA8EB06079742F3 +:1036200028BF1746402F1BD905F1400355F8042B3E +:1036300040F8042B9D42F9D1A36A4033A36240367F +:10364000D4E90A239A4204D3E16920460439FFF7FA +:1036500097FF8AF311884645D9D2FFF75FFECDE781 +:1036600029463A46FDF78CFBA36A3B443D44A362DE +:103670003E44E5E7D0E904239A4217D1C3689BB1E1 +:10368000836A8BB1043B9B1A0ED01360C368013B65 +:10369000C360C3691A44836902619A4224BF436AC2 +:1036A0000361002383620123184670470023FBE770 +:1036B00000F094B84FF08043002258631A61022250 +:1036C000DA6070474FF080430022DA6070470000F4 +:1036D0004FF08043586370474FF08043586A7047FB +:1036E0004B6843608B688360CB68C3600B69436140 +:1036F0004B6903628B6943620B680360704700008B +:1037000008B52C4B2C481A6940F2FF710A431A6124 +:103710001A6922F4FF6222F007021A611A691A6B11 +:103720000A431A631A6D0A431A65244A1B6D11462F +:10373000FFF7D6FF02F11C0100F58060FFF7D0FF14 +:1037400002F1380100F58060FFF7CAFF02F1540171 +:1037500000F58060FFF7C4FF02F1700100F58060A2 +:10376000FFF7BEFF02F18C0100F58060FFF7B8FFA4 +:1037700002F1A80100F58060FFF7B2FF02F1C40179 +:1037800000F58060FFF7ACFF02F1E00100F580601A +:10379000FFF7A6FF02F1FC0100F58060FFF7A0FF34 +:1037A00002F58C7100F58060FFF79AFFBDE80840D4 +:1037B00000F08AB80038024000000240503E000885 +:1037C00008B500F003FAFEF7C1FBFFF727F8BDE8E4 +:1037D0000840FEF7EFBD0000704700000F4B1A6C69 +:1037E00042F001021A641A6E42F001021A660C4A93 +:1037F0001B6E936843F0010393604FF080436B228C +:103800009A624FF0FF32DA6200229A615A63DA60FC +:103810005A6001225A611A60704700BF00380240A6 +:10382000002004E04FF0804208B51169D3680B40D6 +:10383000D9B2C9439B07116109D572B6202383F31E +:10384000118862B6FEF7A2FB002383F3118808BD3E +:103850001B4B1A696FEA42526FEA52521A611A6997 +:10386000C2F30A021A614FF0FF301A695A695861AF +:1038700000215A6959615A691A6A62F080521A62C3 +:103880001A6A02F080521A621A6A5A6A58625A6AAE +:1038900059625A6A0B4A106840F480701060186FC1 +:1038A00000F44070B0F5007F1EBF4FF48030186701 +:1038B0001967536823F40073536000F05FB900BFC9 +:1038C0000038024000700040374B4FF080521A64BD +:1038D000364A4FF4404111601A6842F001021A6002 +:1038E0001A689207FCD59A6822F003029A602E4B60 +:1038F0009A6812F00C02FBD1196801F0F901196005 +:103900009A601A6842F480321A601A689003FCD5F3 +:103910005A6F42F001025A67234B5A6F9107FCD548 +:10392000234A5A601A6842F080721A601F4B5A6824 +:103930005204FCD51A6842F480321A605A68D003E7 +:10394000FCD51A6842F400321A60184A5368990389 +:10395000FCD5154B1A689201FCD5164A9A6040F2C4 +:103960000112C3F88C200022C3F89020124A40F2C2 +:1039700007331360136803F00F03072BFAD10A4BC8 +:103980009A6842F002029A609A6802F00C02082AD1 +:10399000FAD15A6C42F480425A645A6E42F4804220 +:1039A0005A665B6E704700BF0038024000700040EE +:1039B000086C400900948838003C0240074A08B56A +:1039C000536903F00103536123B1054A13680BB136 +:1039D00050689847BDE80840FEF76EBF003C0140C4 +:1039E000D82F0120074A08B5536903F00203536139 +:1039F00023B1054A93680BB1D0689847BDE80840E9 +:103A0000FEF75ABF003C0140D82F0120074A08B5F5 +:103A1000536903F00403536123B1054A13690BB1E1 +:103A200050699847BDE80840FEF746BF003C01409A +:103A3000D82F0120074A08B5536903F008035361E2 +:103A400023B1054A93690BB1D0699847BDE8084096 +:103A5000FEF732BF003C0140D82F0120074A08B5CD +:103A6000536903F01003536123B1054A136A0BB184 +:103A7000506A9847BDE80840FEF71EBF003C014071 +:103A8000D82F0120164B10B55C6904F478725A6186 +:103A9000A30604D5134A936A0BB1D06A984760060F +:103AA00004D5104A136B0BB1506B9847210604D50F +:103AB0000C4A936B0BB1D06B9847E20504D5094AC9 +:103AC000136C0BB1506C9847A30504D5054A936C51 +:103AD0000BB1D06C9847BDE81040FEF7EDBE00BFBB +:103AE000003C0140D82F0120194B10B55C6904F44B +:103AF0007C425A61620504D5164A136D0BB1506DB4 +:103B00009847230504D5134A936D0BB1D06D9847A0 +:103B1000E00404D50F4A136E0BB1506E9847A10410 +:103B200004D50C4A936E0BB1D06E9847620404D54D +:103B3000084A136F0BB1506F9847230404D5054A08 +:103B4000936F0BB1D06F9847BDE81040FEF7B4BE3D +:103B5000003C0140D82F012008B50348FDF7C8FA02 +:103B6000BDE80840FEF7A8BED423012008B5FFF742 +:103B700059FEBDE80840FEF79FBE0000062108B5CB +:103B80000846FFF7B5FB06210720FFF7B1FB06212A +:103B90000820FFF7ADFB06210920FFF7A9FB06214E +:103BA0000A20FFF7A5FB06211720FFF7A1FB06213E +:103BB0002820FFF79DFB07211C20FFF799FBBDE89C +:103BC00008400C212520FFF793BB000008B5FFF744 +:103BD0003FFE00F00DF8FDF797FCFDF771FEFDF7D5 +:103BE00043FDFFF7F9FDBDE80840FFF761BD0000A8 +:103BF0000023054A19460133102BC2E9001102F1D6 +:103C00000802F8D1704700BFD82F0120034611F8F1 +:103C1000012B03F8012B002AF9D1704753544D337F +:103C200032463F3F3F3F3F3F0053544D33324637CC +:103C30005B347C355D780053544D333246375B3608 +:103C40007C375D7800000000F8270120D423012094 +:103C500000960000000000000000000000000000CE +:103C6000000000000000000000000000D114000867 +:103C7000BD140008F9140008E5140008F114000848 +:103C8000DD140008C9140008B51400080515000863 +:103C900000000000E5150008D11500080D16000809 +:103CA000F915000805160008F1150008DD150008D3 +:103CB000C9150008191600080000000001000000E6 +:103CC000000000006D61696E0000000069646C65B1 +:103CD00000000000CC3C000880260120F8270120CD +:103CE00001000000491F00080000000041726475D7 +:103CF00050696C6F740025424F415244252D424C4F +:103D0000002553455249414C2500000002000000A7 +:103D100000000000011800086D1800084000400075 +:103D2000902C0120A02C01200200000000000000C7 +:103D30000300000000000000B118000800000000AF +:103D400010000000B02C0120000000000100000065 +:103D500000000000482F0120010102005523000847 +:103D60006922000801230008E9220008430000003E +:103D7000743D000809024300020100C0320904003A +:103D800000010202010005240010010524010001C8 +:103D9000042402020524060001070582030800FF2F +:103DA00009040100020A00000007050102400000AA +:103DB000070581024000000012000000C03D00081D +:103DC00012011001020000400912415700020102D5 +:103DD000030100000403090425424F415244250019 +:103DE000466C79776F6F463734354E616E6F0030B1 +:103DF0003132333435363738394142434445460051 +:103E000000800000008000000080000000800000B2 +:103E10000000020000000400000004000000040094 +:103E200000000000051A0008B51C00085D1D000810 +:103E300040004000C02F0120C02F012001000000E1 +:103E4000D02F01208000000040010000050000008C +:103E50000001A82A00000000AAAAAAAA00011424AE +:103E6000FFFF00000000000070A70A000000000132 +:103E700000000000AAAAAAAA00000001FFFF00009B +:103E8000000000000000000000000004000000002E +:103E9000AAAAAAAA00000000FFDF0000000000009C +:103EA000000000000000000000000000AAAAAAAA6A +:103EB00000000000FFFF0000000000000000000004 +:103EC0000001000000000000AAAAAAAA0001000048 +:103ED000FFFF0000000000000000000000000000E4 +:103EE00000000000AAAAAAAA00000000FFFF00002C +:103EF00000000000000000000000000000000000C2 +:103F0000AAAAAAAA00000000FFFF0000000000000B +:103F10000000000000000000000000000A00000097 +:103F2000000000000300000000000000000000008E :103F30000000000000000000000000000000000081 :103F40000000000000000000000000000000000071 :103F50000000000000000000000000000000000061 :103F60000000000000000000000000000000000051 -:103F7000000000000000000012040000000000002B -:103F800000800E00FF00000000000000143C00084C -:103F90003F00000049040000213C00083F000000F1 -:103FA000510400002F3C00083F0000000096000074 -:103FB0000000080096000000000800000400000057 -:103FC000C43D0008000000000000000000000000E8 -:0C3FD000000000000000000000000000E5 +:103F70000000000000000000000000000000000041 +:103F8000000000000000000012040000000000001B +:103F900000800E0000000000FF0000000000000094 +:103FA0001C3C00083F00000049040000293C0008B8 +:103FB0003F00000051040000373C00083F000000B3 +:103FC00000960000000008009600000000080000B5 +:103FD00004000000D43D00080000000000000000C4 +:103FE00000000000000000000000000000000000D1 :00000001FF diff --git a/Tools/bootloaders/FreeflyRTK_bl.bin b/Tools/bootloaders/FreeflyRTK_bl.bin index 887758b8935..823020ff3c3 100755 Binary files a/Tools/bootloaders/FreeflyRTK_bl.bin and b/Tools/bootloaders/FreeflyRTK_bl.bin differ diff --git a/Tools/bootloaders/FreeflyRTK_bl.elf b/Tools/bootloaders/FreeflyRTK_bl.elf index 702aaa1fb48..2d04211b44b 100755 Binary files a/Tools/bootloaders/FreeflyRTK_bl.elf and b/Tools/bootloaders/FreeflyRTK_bl.elf differ diff --git a/Tools/bootloaders/FreeflyRTK_bl.hex b/Tools/bootloaders/FreeflyRTK_bl.hex index f5b8e657972..24cd13692fe 100644 --- a/Tools/bootloaders/FreeflyRTK_bl.hex +++ b/Tools/bootloaders/FreeflyRTK_bl.hex @@ -1,1518 +1,1509 @@ :020000040800F2 -:100000000007002041050008F11E0008711E0008CD -:10001000C91E0008711E00089D1E00084305000847 -:10002000430500084305000843050008A5460008ED -:100030004305000843050008430500084305000880 -:100040004305000843050008430500084305000870 -:100050004305000843050008F55700081D5800082F -:10006000455800086D5800089558000843050008D9 -:100070004305000843050008430500084305000840 -:10008000430500084305000843050008652E0008E5 -:10009000D12E0008252F0008792F0008BD58000830 -:1000A0004305000843050008430500084305000810 -:1000B000915900084305000843050008430500085E -:1000C00043050008430500084305000843050008F0 -:1000D00043050008430500084305000843050008E0 -:1000E000215900084305000843050008430500089E -:1000F00043050008430500084305000843050008C0 -:1001000043050008430500084305000843050008AF -:10011000430500084305000843050008430500089F -:10012000430500084305000843050008430500088F -:10013000430500084305000843050008430500087F -:10014000430500084305000843050008794E0008F0 -:10015000430500084305000843050008430500085F -:10016000430500084305000843050008430500084F -:10017000430500084305000843050008430500083F -:10018000430500084305000843050008430500082F -:10019000430500084305000843050008430500081F -:1001A000430500084305000843050008430500080F -:1001B00043050008430500084305000843050008FF -:1001C00043050008430500084305000843050008EF -:1001D00043050008430500084305000843050008DF -:1001E00043050008430500084305000843050008CF -:1001F00043050008430500084305000843050008BF -:10020000D0400B1CD1409C46203AD3401843524268 -:1002100063469340184370479140031C90409C46AE -:10022000203A9340194352426346D34019437047E2 -:1002300053B94AB9002908BF00281CBF4FF0FF314D -:100240004FF0FF3000F07AB9ADF1080C6DE904CE43 -:1002500000F006F8DDF804E0DDE9022304B07047A1 -:100260002DE9F0478C460D460446089E002B51D1DF -:100270008A4217466DD9B2FA82FEBEF1000F0BD04A -:10028000CEF1200C01FA0EF520FA0CFC02FA0EF762 -:100290004CEA050C00FA0EF44FEA174A250CBCFB99 -:1002A000FAF81FFA87F90AFB18CC45EA0C4508FB57 -:1002B00009F3AB420AD9ED1908F1FF3280F023812E -:1002C000AB4240F22081A8F102083D44ED1AA4B2ED -:1002D000B5FBFAF00AFB105544EA054400FB09F9A6 -:1002E000A14509D9E41900F1FF3380F00A81A14545 -:1002F00040F2078102383C44A4EB090440EA08407C -:100300000021002E61D024FA0EF4002334607360C3 -:10031000BDE8F0878B4207D9002E54D0002186E833 -:1003200021000846BDE8F087B3FA83F1002940F0C8 -:100330008E80AB4202D3824200F2FA80841A65EBCF -:1003400003050120AC46002E3FD086E81010BDE822 -:10035000F08712B90127B7FBF2F7B7FA87FEBEF1B3 -:10036000000F34D1EB1B3A0C1FFA87FC0121B3FBC1 -:10037000F2F8250C02FB183345EA03450CFB08F3A1 -:10038000AB4207D9ED1908F1FF3002D2AB4200F2BF -:10039000D1808046ED1AA3B2B5FBF2F002FB1055F6 -:1003A00043EA05440CFB00FCA44507D9E41900F11D -:1003B000FF3302D2A44500F2B8801846A4EB0C0427 -:1003C00040EA08409DE731463046BDE8F087CEF16F -:1003D000200405FA0EF307FA0EF720FA04F83A0C97 -:1003E00025FA04F448EA0308B4FBF2F14FEA184591 -:1003F00002FB11441FFA87FC45EA044501FB0CF39C -:10040000AB4200FA0EF409D9ED1901F1FF3080F08A -:100410008A80AB4240F2878002393D44EB1A1FFAD2 -:1004200088F5B3FBF2F002FB103345EA034500FB0D -:100430000CF3AB4207D9ED1900F1FF386FD2AB4294 -:100440006DD902383D44EB1A40EA01418FE7C1F112 -:10045000200722FA07F88B4005FA01F448EA030363 -:1004600020FA07FE4FEA134CFD404EEA040EB5FB9E -:10047000FCF94FEA1E440CFB19551FFA83F844EAB5 -:10048000054509FB08F4AC4202FA01F200FA01FA50 -:1004900008D9ED1809F1FF3043D2AC4241D9A9F196 -:1004A00002091D442D1B1FFA8EFEB5FBFCF00CFB50 -:1004B00010554EEA054400FB08F8A04507D9E4189A -:1004C00000F1FF3529D2A04527D902381C4440EA63 -:1004D0000940A4EB0804A0FB02894C45C6464D46E2 -:1004E00015D312D056B1BAEB0E0364EB050404FA2F -:1004F00007F7CB401F43CC40376074600021BDE854 -:10050000F0871846F8E69046E0E6C245EAD2B8EB36 -:10051000020E69EB03050138E4E72846D7E74046B9 -:1005200091E78146BEE7014678E702383C4445E75B -:10053000084608E7A8F102083D442BE7704700BFD2 -:1005400002E000F000F8FEE772B63A4880F308884F -:10055000394880F3098839484EF60851CEF2000137 -:10056000086040F20000CCF200004EF63471CEF28A -:1005700000010860BFF34F8FBFF36F8F40F20000A0 -:10058000C0F2F0004EF68851CEF200010860BFF3D1 -:100590004F8FBFF36F8F4FF00000E1EE100A4EF661 -:1005A0003C71CEF200010860062080F31488BFF38E -:1005B0006F8F04F039F904F0D9F804F0C1FF4FF05F -:1005C00055301F491B4A91423CBF41F8040BFAE7E2 -:1005D0001C49194A91423CBF41F8040BFAE71A49F9 -:1005E0001A4A1B4B9A423EBF51F8040B42F8040BC7 -:1005F000F8E700201749184A91423CBF41F8040B24 -:10060000FAE704F0F7F804F0F7FF144C144DAC428D -:1006100003DA54F8041B8847F9E700F041F8114C5D -:10062000114DAC4203DA54F8041B8847F9E704F093 -:10063000DFB80000000700200023002000000008B1 -:100640000001002000070020385E00080023002081 -:100650007C2300208023002050400020000200085E -:100660000002000800020008000200082DE9F04F17 -:100670002DED108AC1F80CD0D0F80CD0BDEC108A4A -:10068000BDE8F08F002383F311882846A04700209F -:1006900003F0C0FBFEE703F01DFB00DFFEE70000F8 -:1006A000F8B503F08BFF074603F0E8FF0646C0BB32 -:1006B000224B9F4235D001339F4235D0204B27F04B -:1006C000FF029A4233D1F8B200F086FD354642F27D -:1006D000107400F09BFF08B10024254600F082FD55 -:1006E00008B90546044636B1164B9F4203D003F0C5 -:1006F000BDFF00242546002003F06AFF124B1B6952 -:100700005B0418D40DB100F069F801F081FB00F032 -:10071000D5FF01F01DFA204600F004F900F05EF864 -:10072000F9E735460024D4E704460125D1E705461C -:100730004FF47A74CDE70024E7E700BF010007B06B -:10074000000008B0263A09B00008024008B501F0E0 -:10075000D1F9A0F120035842584108BD07B5054B17 -:1007600002211B88ADF8043001A801F0E1F903B0C3 -:100770005DF804FB905A000810B5202383F311881C -:100780001248C3680BB103F0CDFB0023104A0F4899 -:100790004FF47A7103F088FB002383F311880D4C2A -:1007A000236813B12368013B2360636813B1636856 -:1007B000013B6360084B1B7833B9636823B902209F -:1007C00001F094FA3223636010BD00BF8023002043 -:1007D000790700089C240020942300202DE9F04193 -:1007E000464B474953F8042F013201D1BDE8F0814F -:1007F0008B42F7D1434C444B22689A427CD9434BFD -:100800009B6803F1006303F580339A4274D203F0CE -:1008100001FF03F013FF002001F0B4F93C4B02206C -:10082000187001F05BFA3B4B1A6C00221A64196EC7 -:100830001A66196E596C5A64596E5A66596E59691E -:1008400041F080015961596921F08001596159696C -:10085000196941F000511961196921F000511961BC -:100860001B6972B62C492D4B0B601D682468BFF3C1 -:100870004F8FBFF36F8F2A4BC3F88420BFF34F8F86 -:100880005A6922F480325A61BFF34F8FD3F8802027 -:10089000C2F3C906C2F34E325201B70743F6E07EF7 -:1008A00002EA0E0838463146013948EA000CB1F137 -:1008B000FF3FC3F874C200F14040F5D1203A12F175 -:1008C000200FEDD1BFF34F8FBFF36F8FBFF34F8F6B -:1008D000BFF36F8F5A6922F400325A610022C3F8C5 -:1008E0005022BFF34F8FBFF36F8F202383F3118804 -:1008F000AD4685F308882047BDE8F081FCFF00087D -:100900001C00010804000108FFFF0008002300206C -:10091000942300200038024008ED00E000000108A8 -:1009200000ED00E02DE9F04F99B0BB4D0090202282 -:10093000FF2110A8AC6801F00DFAB84A01951378B0 -:10094000A3B9B7480121C3601170202383F3118834 -:10095000C3680BB103F0E6FA0023B24AB0484FF483 -:100960007A7103F0A1FA002383F31188009BAE4A49 -:1009700003B11360AD4B009D029300261E705660BC -:10098000B2463746B146012001F0A8F9002D00F02B -:100990002B82A54B1B68002B40F0268219B0BDE8C6 -:1009A000F08F0220FFF7D2FE002840F01682009B55 -:1009B000002E08BF1D469E4B02211B88ADF82C302F -:1009C0000BA801F0B5F8DEE74FF47A7001F092F869 -:1009D000B0F10008EBDB0220FFF7B8FE0028E6D0FC -:1009E00008F1FF38B8F1050F00F2F981DFE808F0EF -:1009F000030B0E11143718A8052340F8343D0421C9 -:100A000001F096F817E004218348F9E704218948AA -:100A1000F6E704218848F3E74FF01C09484601F047 -:100A2000B3F809F104090B9004210BA801F080F838 -:100A3000B9F12C0FF2D1012303FA08F848EA0A0AA7 -:100A40005FFA8AFA4FF0000901F0D8F927B10AF0ED -:100A50000B030B2B08BF0025FFF780FE93E7042153 -:100A60007648CDE7002FA2D00AF00B030B2B9ED1C6 -:100A70000220FFF76BFE8046002898D001206B4EC5 -:100A800001F080F80220307001F028F900275FFAA9 -:100A900087FB584601F086F8054688B1584601F0B4 -:100AA00091F801370028F2D146460025644B022117 -:100AB0001B88ADF82C300BA801F03AF8474662E7E6 -:100AC00001230220337001F0FFF82C46019B9B6844 -:100AD0009C4206D2204601F057F80130E4D104349C -:100AE000F4E7029B00241C704F4B46465C6047466F -:100AF0002546A9E7002F3FF45AAF0AF00B030B2B52 -:100B00007FF455AF029B0220187001F0E7F8322005 -:100B100000F0F0FFB0F1000BFFF649AF1BF0030847 -:100B20007FF445AF019B996804EB0B028A423FF6C4 -:100B30003EAFBBF5807F3FF63AAF424A0392D845BD -:100B40000FDA4FF47A7000F0D5FF04900499002971 -:100B5000FFF62DAF039A049908F8021008F1010876 -:100B6000ECE7C820FFF7F2FD804600283FF41FAFF6 -:100B70001F2C11D8C4F120075F4528BF5F4610AB7A -:100B800024F003003A462F49184401F0B9F83A46D8 -:100B9000FF212C4801F0DEF84FEAAB03DAB2294915 -:100BA0000393204601F0DEF8074600283FF47EAFAD -:100BB000039B04EB830447E70220FFF7C7FD0028EF -:100BC0003FF4F5AE01F024F800283FF4F0AE4FF00A -:100BD00000084346019A9268904535D2B8F11F0F3C -:100BE00012D8109A01320FD028F0030218A90A4433 -:100BF00052F8202C0B92184604220BA901F07EF922 -:100C000008F104080346E5E74046039300F0BCFF03 -:100C1000039B0B90EFE700BF0023002098240020E7 -:100C200080230020790700089C24002094230020C2 -:100C3000925A000804230020082300200C230020DF -:100C4000945A00089823002018A8042140F84C3D2D -:100C500000F06EFFF8E618A8002340F8343D642148 -:100C600000F05CFF00287FF4A2AE0220FFF76EFDCB -:100C700000283FF49CAE0B9800F0B6FF18AB43F889 -:100C8000480D04211846E3E718A8002340F8343D36 -:100C9000642100F043FF00287FF489AE0220FFF7B3 -:100CA00055FD00283FF483AE0B9800F0ABFF18AB66 -:100CB00043F8440DE5E70220FFF748FD00283FF424 -:100CC00076AE00F0B5FF18AB43F8400DD9E702202F -:100CD000FFF73CFD00283FF46AAE0BA9142000F09A -:100CE000ADFF804618A8042140F83C8D00F020FF9D -:100CF00041460BA8ACE7322000F0FCFEB0F1000842 -:100D0000FFF655AE18F0030F7FF451AE019A9268CA -:100D100008EB090393423FF64AAE0220FFF716FDA7 -:100D200000283FF444AE28F00308C844C1453FF40E -:100D30008BAE484600F028FF04210A900AA800F074 -:100D4000F7FE09F10409F1E74FF47A70FFF7FEFCB2 -:100D500000283FF42CAE00F05BFF002842D0109B2F -:100D600001330BD0082210A9002000F0FBFF00285F -:100D700038D02022FF2110A800F0ECFFFFF7EEFC96 -:100D80003C4803F04DF809E6002F3FF410AE0AF09E -:100D90000B030B2B7FF40BAE18A8002340F8343D57 -:100DA000642100F0BBFE804600287FF400AE0220E4 -:100DB000FFF7CCFC00283FF4FAAD0390FFF7CEFC20 -:100DC00041F2883003F02CF80B9801F04BF801F059 -:100DD00015F8039B45461F46D5E5074634E64FF018 -:100DE0000009E4E5B84661E6002000F083FE0490C7 -:100DF000049B002B01DA00F011FD049B002BFFF691 -:100E0000C5AD012000F060FF049B213B162B3FF68F -:100E1000BAAD01A252F823F0A3090008C9090008DD -:100E2000650A000887090008870900088709000883 -:100E3000F50A0008F70C0008B90B0008570C000869 -:100E4000890C0008B70C000887090008CF0C0008BF -:100E500087090008490D0008490A000887090008A9 -:100E6000890D0008AF090008490A00088709000831 -:100E7000570C0008A086010009490B6849F2690077 -:100E80009AB21B0C00FB0233064A0B60136844F253 -:100E9000506198B21B0C01FB0030106080B27047AB -:100EA000202300201C23002010B50021102204461E -:100EB00000F050FF034B03CB206061601868A06016 -:100EC00010BD00BF107AF01FF0B51F4CBBB001F091 -:100ED00011F8A368C31AF92B30D906AD2346A060D8 -:100EE00028220021284601F0C3FC04F10E0000F086 -:100EF00029FF0023C6B2591D5F1CDBB2B3424FEA83 -:100F0000C10107DA0E3323440822284601F0B0FC61 -:100F10003B46F0E7012303930823207B02930B4B0E -:100F20000193C1F3CF01302305910093014604954D -:100F300003A3D3E90023064801F0D4FA3BB0F0BD87 -:100F400078F6339F93CACD8DE0340020ED34002035 -:100F5000BC34002070B50D4614461E4601F06AFAF6 -:100F600050B9022E0ED1012C0CD112A3D3E90023CB -:100F7000C5E90023012070BD052C14D003D8012C35 -:100F800009D0002070BD282C09D0302CF9D10BA33A -:100F9000D3E90023ECE70BA3D3E90023E8E70BA395 -:100FA000D3E90023E4E70BA3D3E90023E0E700BF84 -:100FB000AFF30080401DA12026812A0B78F6339FD5 -:100FC00093CACD8D9E6AC421818A46EE26417272F3 -:100FD000DF25D7B7F017304A39059E5638B5044695 -:100FE0000D46034620222846002101F041FC2279CB -:100FF0002346032A28BF032203F8042F284602228F -:10100000202101F035FC62792346072A28BF0722F8 -:1010100003F8052F28460322222101F029FCA2799A -:101020002346072A28BF072203F8062F2846032253 -:10103000252101F01DFC284604F108031022282177 -:1010400001F016FC382038BD2DE9F04FADF5017DDB -:1010500021AE0EAD40F2791280460F463046002197 -:1010600000F078FE48220021284600F073FE00F0D0 -:1010700041FF574B4FF47A72B0FBF2F0186093E8DF -:101080000700012385E807002B740DF15A000023A7 -:101090006B74FFF709FF042385F8203085F82130B1 -:1010A00007AB18464B4904F0EBFC18222864314684 -:1010B000284685F83C20FFF791FF12AB0446014615 -:1010C0000822304601F0D4FB0822A1180DF1490393 -:1010D000304601F0CDFB0DF14A03082204F1100166 -:1010E000304601F0C5FB13AB202204F11801304655 -:1010F00001F0BEFB14AB402204F13801304601F090 -:10110000B7FB16AB082204F17801304601F0B0FBC2 -:101110000DF15903082204F18001304601F0A8FBCB -:1011200004F1880A0DF15A0904F5847B4B465146B7 -:10113000082230460AF1080A01F09AFBD34509F16A -:101140000109F3D11BAB08225946304601F090FB50 -:1011500004F588744FF0000995F834304B4510D8E9 -:101160004FF0000995F83C304B4515D92B6C2146C2 -:101170004B440822304601F07BFB083409F1010999 -:10118000F0E7AB6B21464B440822304601F070FB80 -:10119000083409F10109DFE7E31DC3F3CF03F97E4A -:1011A0000593002304960393BB7E02931937012312 -:1011B0000093019704A3D3E90023404601F092F97C -:1011C0000DF5017DBDE8F08F9E6AC421818A46EE4F -:1011D000A4240020345B0008014B1870704700BF46 -:1011E000B02400202DE9FF41344B1F7B27B1344B45 -:1011F0000E221A81002630E0324A1068516802AB94 -:1012000003C308230DEB03022F49304804F01AFCF6 -:10121000044630B92A4B2E480A221A8100F024FED7 -:10122000E8E70169B1F5E02F06D9254B29480B22E3 -:101230001A8100F019FEDDE7438B40F20442552B82 -:1012400018BF93420CBF012600260AD01C490C206F -:1012500008811946204800F007FE304604B0BDE87A -:10126000F0811E4A024402F11003994204D2144B49 -:101270001B4810221A81DCE710398D1A38461349B1 -:1012800000F03CFE2A46804604F11801384600F082 -:1012900035FEA368984502D1E36898420AD0084B0E -:1012A0000D221A8100904346E268A1680D4800F0C3 -:1012B000DBFD9FE70C4800F0D7FDCEE7E0340020CF -:1012C000A4240020985A0008DCFF06000000010852 -:1012D000A05A0008AC5A0008BE5A00080800FFF7E0 -:1012E000DC5A0008F95A0008225B00082DE9F04F8B -:1012F000ADB006AF80460C4601F09CF806460028CB -:101300005BD1237E022B19D1E38A012B16D100F089 -:10131000F1FD0546FFF7B0FD4FF4C873B54AB0FBC9 -:10132000F3F105F5167501FB1300E37E15FA80F065 -:101330001060914633B9B04B00221A709C37BD46FD -:10134000BDE8F08FA38AF5B2013BAB4206F101067E -:101350000CD93B1D691CC9001D44009500230822BF -:1013600001F0F801204601F055F9EBE707F1140010 -:10137000FFF79AFD2A4607F11401381D04F052FBCD -:1013800003460028D7D10F2D08D89B4B1D70D9F8E4 -:101390000030A3F51673C9F80030CFE707F19802C3 -:1013A000014602F8950D20460092072201F032F91D -:1013B000F978404601F036F8C0E7E38A052B00F0E3 -:1013C000068106D8012BB9D121464046FFF73CFEE5 -:1013D000B4E7282B3DD0302BB0D1637E874D01334D -:1013E0006A7BDBB29342E94640F0EF80E27E2B7BE2 -:1013F0009A4240F0EA8007F19803002623F8846DB2 -:101400001022009331460123204601F003F9B4F87D -:101410001480A8F102081FFA88F808F1030323F0EA -:1014200003030A3323F00703ADEB030D0DF1180A94 -:1014300033469BB2B11C98454FEAC10106F1010643 -:101440006CDD5344009308220023204601F0E2F8AB -:10145000EEE7A38A013B9BB2C92B3FF66FAF674E05 -:10146000357B4DBB06F10C03009308222B46294621 -:10147000204601F0CFF8A38A05F10109013BEDB246 -:101480009D424FEAC90109DA0E3535440095002323 -:101490000822204601F0BEF84D46ECE7002300226A -:1014A000C6E900230023B36086F8D730C6F8D830E9 -:1014B000337B0BB9E37E3373002507F114063B1D24 -:1014C0000822294630467D60BD60FD6001F0D0F9FC -:1014D0003B7A05F10109AB424FEAC90107D9FB6824 -:1014E00008222B44304601F0C3F94D46F0E7C1F322 -:1014F000CF010023E07E059104960393A37E02931F -:101500001934282301460093019438A3D3E900231A -:10151000404600F0E7FFFFF7D7FC0FE795F8D7004C -:1015200000F040FBD5F8D83006461BB995F8D70037 -:1015300000F048FBD5F8D83043449E4204D295F8D9 -:10154000D700013000F03EFB4FEA980B0024A0B218 -:10155000584504F1010408DA2B6880000AEB000109 -:101560000122184400F0FEFBF1E7D5E90023D5F88D -:10157000D84095F8D70012EB080243F10003444429 -:10158000C5E90023C5F8D84000F00CFB844209D31C -:1015900095F8D730013385F8D730D5F8D8309E1B71 -:1015A000C5F8D860B8F1FF0F08DC00232B7300F0FA -:1015B0002FFBFFF717FE08B1FFF710F92B68104A51 -:1015C0009B0A013313810023AB60CD46B6E6BFF31F -:1015D0004F8F0C490C4BCA6802F4E0621343CB6096 -:1015E000BFF34F8F00BFFDE7AFF30080264172725B -:1015F000DF25D7B7B8340020B5340020E034002010 -:10160000A424002000ED00E00400FA0537B54FF0F7 -:101610000054214B22689A4229D1204B627D1A70D6 -:101620001F48237D0373C9221E490E3000F068FB5A -:10163000E0220021204600F08DFB0125284603B062 -:1016400030BD0321184800F06DFC8DE8030063688D -:1016500083421ED1236899424FF0000319D1A36041 -:101660000E4B22691A70114BE2681A60E6E703F02C -:101670000FF8054668B10E4A0E4C136C43F0007328 -:101680001364A2680C4B9A4203D12369013B7E2B61 -:10169000D7D90025D2E700BF9AAD44C5B0240020B9 -:1016A000E034002016000020586600401823002077 -:1016B00000380240506600405041A0B0F0B54B4A9F -:1016C0004B4C176885B002236371B7F57A7F4FF0F2 -:1016D00000030293ADF80C304BD3464B464AB2FBA5 -:1016E000F7F29F4294BF10230923591CB2FBF1F675 -:1016F00001FB162121B1022B3BDD013BDBB2F4E7FC -:10170000721EB2F5806F34D2C3EBC305EA1CC2F37C -:10171000C702991A02F1010EC9B24FF47A7000FBA8 -:101720000EF08E44B0FBFEF080B2B0F5617F06D9BA -:101730006A1E082592FBF5F2D2B29B1AD9B2531E4B -:101740000F2B51D84B1E072B8CBF002301235018A1 -:1017500000FB06652848B0FBF5F0874209D143B18C -:101760000123ADF808608DF80C308DF80A208DF853 -:101770000B109DF80B30214921485A1E9DF80A3064 -:10178000013B1B0443EA0253BDF80820013A13430E -:101790004B6001F053FD002301931A4B00931A494B -:1017A0001A4B1B484FF4805200F014FE194B197865 -:1017B00011B1174800F036FE00F09CFB0546FFF71C -:1017C0005BFB4FF4C87305F51675B0FBF3F202FB33 -:1017D0001300114B15FA80F0186002F04FFF08B1AA -:1017E0000F23238105B0F0BD0023B0E718230020AC -:1017F000A42400203F420F0080F93703102300206B -:10180000F8350020550F0008B4240020ED12000820 -:10181000BC340020B0240020B83400202DE9F04F63 -:1018200096A7D7E900670FF25C29D9E900898F4CA8 -:1018300093B0DFF858B2DFF858A2204600F09CFEC3 -:101840000CAD079098B310220021284600F082FAD0 -:10185000079B197B4FF0000261F3030219468DF8D4 -:10186000302051F8040F49680EAA03C21B680D9A74 -:1018700063F31C029DF830300D9243F020038DF885 -:10188000303000232A461946584601F0E7FC0790FD -:1018900030B9204600F074FE079B8AF80030CCE790 -:1018A0009AF80030072B40DC01338AF80030182208 -:1018B0000021284600F04EFADFF8D0B1DFF8D4A1BD -:1018C000002319462A46584601F0F0FC014680BB29 -:1018D000102208A800F03EFADAF8143083F0400332 -:1018E000CAF8143000F008FB0B4612A9024611E9B1 -:1018F00003000DF1240E8EE803009DF83410C1F3AF -:10190000030089064CBF0E99BDF838108DF82C00E5 -:1019100046BFC1F31C0141F00041C1F30A01089127 -:10192000204608A900F0ECFFCAE7204600F028FE98 -:10193000BDE7204600F07EFD824600284AD1DFF850 -:1019400058B100F0D7FADBF80030984242D300F0EB -:10195000D1FA0790FFF790FA079A8DF820A04FF47C -:10196000C87302F51672B0FBF3F101FB130012FA13 -:1019700080F0CBF80000DFF824B19BF8001011B91B -:1019800001238DF8203028460791FFF78DFA07993B -:10199000C1F1100A5FFA8AFABAF1060F28BF4FF0B8 -:1019A000060A524629440DF1210000F0A9F90AF176 -:1019B0000103049308AB0393182302932C4B019368 -:1019C0000123009332463B46204600F035FD0023BC -:1019D0008BF8003000F08EFA264ADFF8C4A01368B6 -:1019E000C31AB3F57A7F32D3106000F085FA02464D -:1019F0000B46204600F0CEFD204600F01BFD30B324 -:101A00009AF80C30DFF89CB0002B14BF032302239C -:101A10008BF8053000F06EFA4FF47A732946B0FB6C -:101A2000F3F0CBF800005846FFF7D8FA1823073038 -:101A30000293114B0193C0F3CF0040F25513049071 -:101A40000093039542464B46204600F0F5FC9AF879 -:101A50000C300BB1FFF738FA9AF80C30002B7FF4FA -:101A6000E8AE13B0BDE8F08FAFF30080BC340020C7 -:101A7000B4340020C0350020C4350020401DA12012 -:101A800026812A0BF1C6A7C1D068080FF8350020BF -:101A9000C535002000000240B8340020B5340020D5 -:101AA000E0340020A424002070B50F4B0C461978B8 -:101AB0000131C9B2012906460FD80C4803681D6AD6 -:101AC0004FF47A73534331462246A847844204D1E7 -:101AD000074B00221A70012070BD4FF4FA7002F01B -:101AE0009FF9002070BD00BF24230020E0370020B4 -:101AF000F435002007B502AB002203F8012D0121C7 -:101B000002461846FFF7D0FF20B19DF8070003B04A -:101B10005DF804FB4FF0FF30F9E700000A4608B516 -:101B20000421FFF7C1FF80F00100C0B2404208BDB0 -:101B300030B4054C2368DD69044B0A46AC460146C7 -:101B4000204630BC604700BFE0370020A08601007F -:101B500070B502F001FC094C094E20800025306868 -:101B60002388834208D902F0F1FB3368054401332E -:101B7000B5F5803F3360F2D370BD00BFF63500206D -:101B8000C835002002F098BC00F1006000F58030FC -:101B90000068704700F10060920000F5803002F0AC -:101BA00021BC0000054B1A68054B1B889B1A834219 -:101BB00002D9104402F0CABB00207047C83500208B -:101BC000F635002038B5074D04462868204402F059 -:101BD000C5FB28B928682044BDE8384002F0D6BBD0 -:101BE00038BD00BFC835002010F0030305D1B0F5A3 -:101BF000047F02D2024BC05870470020704700BFDC -:101C00000078F01F014BC058704700BF107AF01FDA -:101C1000064991F8243033B100230822086A81F87C -:101C20002430FFF7B7BF0120704700BFCC3500203C -:101C3000014B1868704700BF002004E0F0B5204B4E -:101C40001E68204B1F885D6893F90840C6F30B029D -:101C5000BA424FEA164622D09F89BA4221D01F8B42 -:101C6000BA4206D102220C2404FB02335D6893F9C8 -:101C70000840B6F5805F16D041F201039E4208BFCE -:101C80005A24421E0A44013D0B46934215D215F9CF -:101C9000016F581C4EB1034600F8016CF5E70022B5 -:101CA000E1E70122DFE74124EBE72C2582421D70AA -:101CB00001D9981C5C70401AF0BD1846FBE700BFC4 -:101CC000002004E028230020022802BF024B4FF42A -:101CD00080029A61704700BF00000240022802BFE4 -:101CE000014B40229A61704700000240022801BF68 -:101CF000024A536983F04003536170470000024079 -:101D000010B50023934203D0CC5CC4540133F9E7EF -:101D100010BD000030B5441E14F9010F0B4660B130 -:101D200093F90050854201F1010106D11AB993F9E6 -:101D30000020801A30BD013AEEE7002AF7D11046A4 -:101D400030BD000002460346981A13F9011B002912 -:101D5000FAD1704702440346934202D003F8011BB4 -:101D6000FAE770472DE9F047234C94F824300546F4 -:101D70008846174683BB2E46DFF87C90C7B394F89D -:101D800024302BB92022FF2148462662FFF7E2FFCC -:101D900094F82400C0F10805BD4228BF3D465FFA13 -:101DA00085FAAD0041462A4604EB8000FFF7A8FF04 -:101DB00094F82430A7EB0A079A445FFA8AFABAF13A -:101DC000080F2E44A844FFB284F824A0D6D1FFF710 -:101DD0001FFF0028D2D108E0266A06EB8306B04236 -:101DE000CAD0FFF715FF0028C5D10020BDE8F08755 -:101DF0000120BDE8F08700BFCC350020024B1A78E7 -:101E0000024B1A70704700BFF435002024230020D5 -:101E100038B5104D104C284601F0ECFA2146284602 -:101E200001F014FB24680D48E26ED2F8043843F048 -:101E30000203C2F8043801F0F3FF0949204601F01B -:101E400013FCE26ED2F8043823F00203C2F804381F -:101E500038BD00BFE0370020205C000840420F0082 -:101E6000485C0008704700000FB4002004B07047C1 -:101E700000B59BB0EFF3098168226846FFF740FF89 -:101E8000EFF30583044B9A6BDA6A9A6A9A6A9A6A44 -:101E90009A6A9A6A9B6AFEE700ED00E000B59BB083 -:101EA000EFF3098168226846FFF72AFFEFF3058305 -:101EB000044B9A6B9A6A9A6A9A6A9A6A9A6A9B6AB5 -:101EC000FEE700BF00ED00E000B59BB0EFF3098135 -:101ED00068226846FFF714FFEFF30583034B5A6B44 -:101EE0009A6A9A6A9A6A9A6A9B6AFEE700ED00E02B -:101EF000FEE7000002F01EBB02F008BB30B5084D43 -:101F00000A4491420BD011F8013B09245840013C8E -:101F1000F7D040F300032B4083EA5000F7E730BDD1 -:101F20002083B8ED2DE9F7431AA7D7E9006700EB46 -:101F300081014FF0FF324FF0FF330DF1040C884266 -:101F400023D050F804EBCDF804E04FF0000E1EF85B -:101F50000C8000244FEA086562406B404FF009088E -:101F6000B8F101080BD0002A73F1000904DA9218C5 -:101F70005B4172407B40F3E792185B41F0E70EF162 -:101F8000010EBEF1040FE2D1D9E7D043D94303B02B -:101F9000BDE8F0839336EAA9EBE1F0422DE9F04782 -:101FA000089E01F007054FEAD60C2A4406F0070602 -:101FB00000EBD1004FF47F49954201D1BDE8F08795 -:101FC00005F0070E06F0070AD64577464FEAD50416 -:101FD00038BF5746C7F10807511B0CEBD6088F4294 -:101FE000045D28BF0F4604FA0EF413F8081029FA0E -:101FF00007FE24FA0AF45FFA8EFE4C404EFA0AFEFF -:1020000004EA0E04614003F808103D443E44D3E75F -:102010000246006848B103681360D3881189013310 -:102020009BB29942D38038BF1381704770B588B096 -:102030000D460446202200216846FFF78BFE20460D -:102040000495FFF7E5FF054658B16B46044608AE18 -:102050001A4603CAB24220606160134604F10804C4 -:10206000F6D1284608B070BD2DE9F041056885B964 -:102070000160BDE8F081002B29DA930CB34229D12D -:10208000A54201D10D60F3E7C8F800100C60BDE86F -:10209000F0814B6823F06047BE0C4FEAD37EC3F358 -:1020A000807C16EA230638BF3E46A8462C46636865 -:1020B000BEEBD37F23F06042DDD1974203D1C3F35F -:1020C00080739C450AD1974205E01C46EFE7B24277 -:1020D00006D013469E422CBF00230123002BCFD1F4 -:1020E0002368A046002BF0D12160BDE8F0810000FC -:1020F0002DE9F04106460F4600254FF6FF7441F2E8 -:1021000021082A4630463946FEF77AF8C0B284EAFA -:102110000024082314F4004F4FEA4404A4B203F14E -:10212000FF3318BF84EA080413F0FF03F2D1083527 -:10213000402DE6D12046BDE8F081000010B54B6887 -:1021400033B9CA8A63F30902CA820020002110BD94 -:10215000C4681A681C60C360438A013B43824A60BA -:10216000EDE7000010B50A4441F22104914200D18C -:1021700010BD11F8013B80EA0320082310F4004F42 -:102180004FEA400080B203F1FF3318BF604013F004 -:10219000FF03F3D1EAE700002DE9F04F85B0814657 -:1021A0008DE80A00BDF83C409346002A00F0838089 -:1021B00024B10E9B002B7ED0072C2AD809F10C00ED -:1021C000FFF726FF054628B96FF00205284605B03F -:1021D000BDE8F08F14220021FFF7BCFD22460E99C6 -:1021E00005F10800FFF78CFD631C2B749BF8003091 -:1021F0002C4403F01F0363F03F032372009B43F062 -:1022000000436B60294609F11C00FFF72DFF0125F3 -:10221000DCE7019B1B0A4FF00008029300F10C035E -:102220004FF0800A4646454603930398FFF7F0FEB9 -:1022300007460028C8D014220021FFF78BFDC6BB3B -:102240009DF804303B729DF808307B7202220E9B91 -:10225000711E1944B4420AD9B8180132D2B211F829 -:1022600001EF80F808E00136072AB6B2F2D19BF8F8 -:10227000001001F01F01B44208BF4FF0400AB81827 -:1022800041EA48114AEA01030372009B013243F01C -:1022900000437B603A74394609F11C00FFF7E4FE05 -:1022A0000135B4422DB288F001084FF0000ABCD1CC -:1022B0008CE70022CBE76FF0010587E72DE9F047B7 -:1022C0001E46CB8A9146C3F30902062A80460F4672 -:1022D00019D013460021B0B28DB25A1992B2052A14 -:1022E00009D9A84210D8FA8A034463F30902FA8292 -:1022F0000120BDE8F087A842F3D93A4419F801401B -:1023000094760131E8E70025FB8A7C68C3F3090075 -:10231000821F1C23B2FBF3FA03FB1A2A1FFA8AF26C -:102320007CB301212368002B39D1B31F03441C2047 -:10233000B3FBF0F301339BB299420CD2BAF1000F18 -:1023400009D14046FFF764FE08B1C0F800A0206044 -:1023500008B304460022B6B24FF0000AB54230D2AC -:10236000691E49441346E01801339BB211F801EF8E -:1023700080F804E001351C2BADB214D0AE42F2D887 -:10238000ECE74046FFF744FE044608B10023036033 -:102390007C60002CDED16FF00200BDE8F0870131D7 -:1023A00089B21C46BEE7AE42D8D94046FFF730FEA0 -:1023B00008B1C0F800A020600028ECD0044600223C -:1023C000CCE7FB8AC3F30902164466F30903FB82D8 -:1023D0008EE70000F8B5044615460E46242200217B -:1023E0001F46FFF7B7FC069B6360079B23626A09E1 -:1023F0004FF6FF739A424FF0000028BF1A46A760BD -:10240000207097B204F10C0503469A4205D10023CF -:102410002B6027826382A382F8BD2E60013335468C -:102420002036F2E703781BB94BB2002BC8BF01700E -:1024300070470000007870472DE9F7430D9EBDF806 -:1024400028900B9D9DF83040BDF83880074619460E -:10245000104616B9B8F1000F40D11F2C3ED83B787A -:10246000D3B9B8F1070F36D839F0030336D1424655 -:1024700031464FF6FF70FFF775FE4FEA092920F04D -:10248000010009F44079400449EA0464400C44EA3C -:1024900040244FF6FF730DE043EA0923B8F1070F1C -:1024A00043EA0464F5D9FFF723FE42463146FFF7BD -:1024B00059FE03468DE840012A4621463846FFF77B -:1024C0006BFE2B780133DBB21F2B88BF00232B70F0 -:1024D00003B0BDE8F0836FF00300F9E76FF001008F -:1024E000F6E700002DE9F7430E9F0B9D9DF8348021 -:1024F000BDF83C6081469DF8300007B9AEBB1F288F -:1025000033D899F800E0BEF1000F31D00C0244F04E -:1025100080049DF8281044EAC83444EA014444EA9F -:102520000E04072E44EA00641CD919461046FFF732 -:10253000DFFD32463946FFF715FE03460196009748 -:102540002A4621464846FFF727FEB8F1010F06D17B -:102550002B780133DBB21F2B88BF00232B7003B015 -:10256000BDE8F0834FF6FF73E8E76FF00100F6E790 -:102570006FF00300F3E70000C06900B1043070475A -:10258000C3691A68C261C2681A60C360438A013BAA -:10259000438270472DE9F047D0F818A0DFF870802B -:1025A000054616461F4654464FF000090CB9BDE8D3 -:1025B000F087D4E90223B21A67EB0303994508BFF9 -:1025C000904523D2AB699C42214628460FD1FFF7A4 -:1025D000B5FDAB691B68AB61EB6823606B8AEC608F -:1025E000AC69013B6B822346A2461C46DEE7FFF73F -:1025F000A5FD2368CAF80030EB6823606B8AEC60A5 -:10260000013B6B82DAF800305446EDE72368EBE7D4 -:1026100080841E002DE9F04F8BB00E4614460793C0 -:10262000DDF850808346002800F01081B8F1000FDB -:1026300000F00C81531E3F2B00F20881012A03D1C8 -:10264000079B002B40F00281BBF81450ED000023E3 -:10265000AE420893099304D3002630460BB0BDE880 -:10266000F08F33199D42DBF80C303ABFAD1BEDB251 -:10267000254623B9DBF81030002B00F093802F2E75 -:1026800065D8C6F13007BD424FF000032CBFFFB242 -:102690002F460093314608AB3A46DBF80800FFF7B7 -:1026A0007DFCA5EB07093E445FFA89F9BBF81430BD -:1026B00003F10053063BDB000493DBF80C3003937B -:1026C0003021039B13B1B9F1000F43D1DBF81000A7 -:1026D00040B1B9F1000F05D0009708AB4A46711A16 -:1026E000FFF75CFC2EB2002DB6D060070AD00AAB13 -:1026F00003EBD401624211F8083C02F007021341D7 -:1027000001F8083C082C54D9102C54D9202C8CBF2B -:1027100008230423079A002A00F09E80B4EBC30F1D -:1027200000F09D80082C48D89DF82030621E23FAC6 -:1027300002F2D10706D54FF0FF3202FA04F4234328 -:102740008DF820309DF8203088F8003085E7A946C4 -:102750000027ABE7049BE02B28BFE02306930B4444 -:10276000B342059315D9A3EB060AD1450398009708 -:102770002CBF5FFA8AFACA46711A08AB5246043077 -:10278000FFF70CFC5744A9EB0A095644FFB25FFA65 -:1027900089F9049B069A05999B1A0493039B1B686D -:1027A00003938EE700932A4608AB3146DBF8080016 -:1027B00096E70123AEE70223ACE7102C12D8BDF850 -:1027C0002030621E23FA02F2D20706D54FF0FF3204 -:1027D00002FA04F42343ADF82030BDF82030A8F805 -:1027E00000303AE7202C0FD8089A631E22FA03F330 -:1027F000DB0705D54FF0FF3303FA04F414430894C4 -:10280000089BC8F8003028E7402C22D0DDE908AB4F -:10281000621E50465946FDF7F3FC002100F001000E -:1028200050EA01030DD0224601200021FDF7F4FCFF -:10283000404261EB410140EA0A0041EA0B01CDE967 -:102840000801DDE90823C8E9002306E76FF0010667 -:1028500003E76FF0080600E7012C3FF473AF082C84 -:102860007FF670AF102CB8D9202CEAD8C8E700004A -:1028700030B5402A85B01FD8002A08BF01220024A5 -:10288000012A0294039419D11B788DF8083053075C -:102890000AD004AB03EBD205544215F8083C04F00F -:1028A0000704A34005F8083C00910346002102A854 -:1028B000FFF774FB05B030BD4022E0E7082AE3D9FA -:1028C000102A03D81B88ADF80830E0E7202A02D888 -:1028D0001B680293DBE7D3E90045CDE90245D6E763 -:1028E00010B5CB681BB98B600B618B8210BDC468BF -:1028F0001A681C60C360438A013B4382CA60F0E7E8 -:102900002DE9F04FD1F800908FB0C9F3C0160446FE -:102910000D46CDE90223002E50D0C9F3C03AC9F3C9 -:102920000626B9F1000F80F2CB8119F0C04F40F0BC -:10293000C7812B7B002B00F0C381BAF1020F03D0BB -:102940002278B24240F0BF8109F07F02BAF1020F53 -:10295000059236D119F07F0FC9F30F2B01D10BF07F -:10296000030B2B447606059A93F8038046EA0A4641 -:1029700046EA82465FEAD81346EA0B06049300F063 -:10298000A180002200230EA961E90823059B009382 -:10299000676853465A462046B847002800F08F80A3 -:1029A000A7698FB9314604F10C00FFF73FFB0746DA -:1029B000D0B96FF002000FB0BDE8F08F4FF0020AFF -:1029C000AFE7C9F3074BCCE73B699E420DD03F68A8 -:1029D000002FF9D1314604F10C00FFF727FB074621 -:1029E0000028E6D0A3693B60A761DDE90601FFF797 -:1029F0007FFBB882F97D08F01F06C1F38401711ACC -:102A000089B20FFA81FED7E90223BEF1000FBCBFE5 -:102A100001F1200E0FFA8EFE52EA0301C9F3046998 -:102A200000F05D81DDE90201801A61EB03010246DD -:102A30000B46B6480021994208BF9042C0F04F8132 -:102A4000049B002B48D0BEF1010F00F3488118F021 -:102A5000400F41D0DDE902230021C7E9022306A887 -:102A60002022FFF777F9DDE90223CDE906232B1DAC -:102A700008932B7BADF82EB0013BDBB2ADF82C30C8 -:102A80009DF814308DF833308DF830A0A3688DF8A0 -:102A900031608DF8329006A920469847FB7DC3F33C -:102AA0008402013262F38603FB75FB8A6FF309032C -:102AB000FB821B0A6FF3C713FB7500207BE76FF0E7 -:102AC0000B0078E7A76917B96FF00C0073E73B6953 -:102AD0009E428FD03F68F6E7FB7DC8F34012B2EB11 -:102AE000D31F40F0F380C3F38403B34240F0F1807E -:102AF00004992B7B4FEA981200293BD012F0010871 -:102B00005CD1032B40F2E880DDE90223C7E9022310 -:102B10002B7BAE1D033BDBB23246394604F10C0081 -:102B2000FFF7CCFB002814DA39462046FFF706FBF6 -:102B3000FB7DC3F38402013262F38603FB75FB8ADB -:102B400068F30903FB821B0A68F3C713FB750320B4 -:102B500031E7AB883B832A7B033AD2B2B88A31464D -:102B6000FFF700FBFB7DB882DA43C2F3C01262F3C9 -:102B7000C713A1E712BB2E1D013BDBB2324639461B -:102B800004F10C00FFF79AFB002814DA39462046BE -:102B9000FFF7D4FAFB7DC3F38402013262F38603AC -:102BA000FB75049AFB8A62F30903FB82049A1B0AF1 -:102BB00062F3C713CAE72A7B013ACEE7F98AC1F369 -:102BC0000901013B0529DAB25AD8281D00239A428F -:102BD0000AD907EB010E013110F801CB8EF81AC0AB -:102BE00001330629DBB2F2D1DDE902019342CDE9DE -:102BF000060107F11A01089138BF04337968099179 -:102C000034BF5B1900230A93FB8AADF82EB0C3F3DF -:102C100009031A449DF814308DF833300023ADF8C1 -:102C20002C208DF830A08DF831608DF832907B60CB -:102C30002A7BB88A013A291DFFF794FA3B8BB882A8 -:102C4000834203D1A36806A920469847204606A9D7 -:102C5000FFF746FEFB7DB88AC3F38402013262F3BC -:102C60008603FB75FB8A6FF30903FB821B0A6FF374 -:102C7000C713FB753B8B984214BF112000209AE6C6 -:102C8000D7F804E0BEF1000F18D00623DEF80000EC -:102C900088B9C91A05F1040800EB010CBCF11B0F3F -:102CA000C3B2A1D893429FD2F44418F8013B8CF8E8 -:102CB00004300130F0E71C338646E7E7734693E7BC -:102CC0006FF0090077E66FF00A0074E66FF00D0010 -:102CD00071E66FF00E006EE66FF00F006BE6FB7DA5 -:102CE00068F386036FF3C713FB7539462046FFF779 -:102CF00025FA049B002B7FF4AAAEFB7DC3F384026C -:102D0000013262F38603FB75DEE600BF80841E009D -:102D10002DE9F041504EB04240F089804F4CDFF831 -:102D200040E1256C45F000752564256E45F0007581 -:102D30002566246E846AD4F8007207EA0E0747F00D -:102D40000107C4F80072D4F8005205EA0E0545F0F8 -:102D5000010545EA0121C4F80012002A69D00021CA -:102D6000C4F81C120F46C4F80412C4F80C12C4F8BC -:102D7000141204EBC10501311C29C5F84072C5F8D5 -:102D80004472F6D14FF0000E4FF0010C964514D16D -:102D9000826AD2F80032B04223F00103C2F8003256 -:102DA00057D12E4B1A6C22F000721A641A6E22F060 -:102DB00000721A661B6EBDE8F0819F781D8817F0BF -:102DC000010F18BFD4F804820CFA05F11CBF41EAC8 -:102DD0000808C4F8048217F0020F1EBFD4F80C8252 -:102DE00041EA0808C4F80C827F0742BFD4F8147285 -:102DF0000F43C4F8147204EBC5055F68C5F8407250 -:102E00009F68C5F84472D4F81C522943C4F81C12B8 -:102E10000C330EF1010EB9E7846A0021C4F81C12CC -:102E2000C4F80412C4F80C12C4F81412AAE7002A59 -:102E3000F2D1836A0022C3F84022C3F84422C3F8C7 -:102E40000422C3F814220122C3F80C22C3F81C2266 -:102E50009EE7BDE8F08100BFF83500200038024051 -:102E60000000FFFF184A916A08B58B688B6013F069 -:102E7000010105D013F00C0F14BF4FF48031012174 -:102E8000D80506D513F4406F14BF41F4003141F06A -:102E90000201D80306D513F4402F14BF41F480215A -:102EA00041F00401D3690BB107489847202383F30D -:102EB00011880021054800F0DBFF002383F311880F -:102EC000BDE8084001F028BCF8350020003600209D -:102ED00038B5124CA36ADD68AA0712D05A6922F0ED -:102EE00002025A61A36913B10121204698472023A9 -:102EF00083F3118800210A4800F0BAFF002383F30E -:102F00001188EB0606D5A36A1021D960236A0BB19C -:102F100002489847BDE8384001F0FEBBF835002074 -:102F20000836002038B5124CA36A1D69AA0712D0D2 -:102F30005A6922F010025A61A36913B10221204696 -:102F40009847202383F3118800210A4800F090FF5E -:102F5000002383F31188EB0606D5A36A10211961BB -:102F6000236A0BB102489847BDE8384001F0D4BB52 -:102F7000F83500200836002038B50F4CA36A5D688C -:102F80005D602A070AD5042222701A6822F0020224 -:102F90001A60636A13B10021204698476B0706D573 -:102FA000A36A9969236A13B1090403489847BDE8E5 -:102FB000384001F0B1BB00BFF835002010B50F4C10 -:102FC000204600F029F90E4BA3620B21132000F0DC -:102FD0000BF90B21142000F007F90B21152000F04C -:102FE00003F90B21162000F0FFF8002320461A46B3 -:102FF0001C21BDE81040FFF78BBE00BFF835002054 -:1030000000640040114B984210B5044609D1104BA2 -:103010001A6C42F000721A641A6E42F000721A665C -:103020001B6EA36A01221A60A36A5A68D20707D5E9 -:10303000626851681268D9611A60064A5A6110BD07 -:103040000121082000F000FEEEE700BFF835002067 -:10305000003802405B87010003291AD8DFE801F03D -:10306000020A0F14836A9B6813F0E05F14BF01200B -:1030700000207047836A9868C0F380607047836A55 -:103080009868C0F3C0607047836A9868C0F30070A6 -:10309000704700207047000010B503291FD8DFE8F3 -:1030A00001F0021F2327816A8B68C3F30163183381 -:1030B00001EB0313107881061ED55468C0F300118C -:1030C000490041EAC40141F0040100F00F005860DA -:1030D00090689860D268DA6041F00101196010BD13 -:1030E000836A03F5C073E5E7836A03F5C873E1E714 -:1030F000836A03F5D073DDE79488C0F300114900BB -:1031000041EA4451E1E7000001290CD003D3022930 -:1031100010D000207047836ADA68920701D11869DD -:1031200003E001207047836AD86810F0030018BFDD -:1031300001207047836AF2E710B539B9836AD9680C -:1031400089071BD11B699B0704D110BD012915D02C -:10315000022948D1816AD1F8C031D1F8C401D1F82F -:10316000C8411461D1F8CC41546120240C610C6930 -:10317000A40717D14C6944F0100412E0816AD1F819 -:10318000B031D1F8B401D1F8B8411461D1F8BC41E3 -:1031900054612024CC60CC68A40703D14C6944F06E -:1031A00002044C6111795C0864F304119C0864F317 -:1031B0004511117189064BBF91681189DB085B0DC0 -:1031C0004CBF63F31C0163F30A01137948BF91609C -:1031D00060F3030313714FEA10234FEA104058BF06 -:1031E00011811370508010BD00F1604300F01F0288 -:1031F000400903F5614309018000C9B200F1604054 -:1032000083F8001300F5614001239340C0F880313A -:1032100003607047FFF7D2BE00F10802012303707C -:1032200082600023C26000F11002436002614261CB -:103230008361C361036243627047000010B52023BD -:10324000044683F31188022303704160FFF7DAFE1E -:1032500004232370002383F3118810BD2DE9F0416E -:103260001F4604460D461646202383F3118800F1BD -:1032700008082378052B0ED029462046FFF7ECFEE0 -:1032800048B1204632462946FFF706FF002080F36A -:103290001188BDE8F0813946404600F0CDFD002898 -:1032A000E7D0002383F31188BDE8F0812DE9F041D8 -:1032B0001F4604460D461646202383F3118800F16D -:1032C00010082378052B0ED029462046FFF71CFF57 -:1032D00048B1204632462946FFF72EFF002080F3F2 -:1032E0001188BDE8F0813946404600F0A5FD002870 -:1032F000E7D0002383F31188BDE8F08102684368BA -:103300001143016003B118477047000013B5446BC7 -:10331000D4F894341A681178042915D1217C022933 -:1033200012D11979128901238B4013420CD101A9C2 -:1033300004F14C0002F008F8D4F89444019B217980 -:103340000246206800F0E0F902B010BD143001F030 -:103350008BBF00004FF0FF33143001F085BF000039 -:103360004C3002F05DB800004FF0FF334C3002F0FB -:1033700057B80000143001F059BF00004FF0FF3182 -:10338000143001F053BF00004C3002F029B80000A7 -:103390004FF0FF324C3002F023B80000D0F89424F4 -:1033A00038B5136819780429054601D0012038BDC5 -:1033B000017C0229FAD152795C89012090400440B5 -:1033C000F4D105F1140001F0EBFE02460028EDD027 -:1033D000D5F894544FF480732868697900F082F925 -:1033E000204638BD406BFFF7D9BF00000020704772 -:1033F000704700007FB5124B036000234360836079 -:10340000C360012502260F4B057404460290019308 -:1034100000F18402294600964FF48073143001F0C5 -:103420009BFE094B0193029400964FF4807304F5C0 -:103430002372294604F14C0001F062FF04B070BD14 -:103440007C5B0008E53300080D3300080B68202280 -:1034500082F311880A7903EB820210624A790D32F5 -:1034600043F822008A7912B103EB82031862022327 -:103470000374C0F89414002383F31188704700008C -:1034800038B5037F044613B190F85430ABB9201D12 -:1034900001250221FFF732FF04F1140025776FF0B8 -:1034A000010100F0E5FC84F8545004F14C006FF089 -:1034B0000101BDE8384000F0DBBC38BD10B501218A -:1034C00004460430FFF71AFF0023237784F85430B2 -:1034D00010BD000038B504460025143001F054FE3C -:1034E00004F14C00257701F023FF201D84F854508F -:1034F0000121FFF703FF2046BDE83840FFF74EBF2C -:1035000090F85C3003F06003202B19D190F85D2017 -:10351000212A0AD0222A4FF000030ED0202A0FD1F0 -:10352000084A02650722426504E0064B036507234B -:103530004365002383650120704703654365F9E710 -:10354000002070474C230020D0F8943437B51A6817 -:103550001178042904461AD1017C022917D119795E -:10356000128901238B40134211D100F14C052846EA -:1035700001F09EFF58B101A9284601F0E5FED4F8FC -:103580009444019B21790246206800F0BDF803B005 -:1035900030BD000000EB8103F7B51C6A05460E46FE -:1035A000F4B1202383F3118805EB8607201D082141 -:1035B000FFF7A4FEFB685B691B684C3413B120461F -:1035C00001F0D0FE01A9204601F0BEFE024648B13E -:1035D000019B3146284600F097F8002383F31188B9 -:1035E00003B0F0BDFB685A691268002AF5D01B8A47 -:1035F000013B1340F1D105F15C02EAE70D3138B52A -:1036000050F82140DCB1202383F31188D4F89424AE -:103610001368527903EB8203DB689B695D6845B1EF -:1036200004216018FFF76AFE294604F1140001F036 -:10363000C1FD2046FFF7B2FE002383F3118838BD99 -:103640007047000001F06AB9012303700023436052 -:1036500000F1240200F1380142F8043B8A42136170 -:10366000FAD103814381704738B50446202383F3A0 -:10367000118800254160C560056145618561C561AE -:10368000056201F05BF90223237085F3118838BDD0 -:1036900070B500EB810305465069DA600E461446AA -:1036A00018B110220021FEF755FBA06918B11022B5 -:1036B0000021FEF74FFB31462846BDE8704001F07F -:1036C00007BA0000028902F001020281428902F079 -:1036D000010242810022026142618261C261026292 -:1036E00001F08ABAF0B400EB81044789E46801254F -:1036F000A4698D403D43458123600023A26063603F -:10370000F0BC01F0A5BA0000F0B400EB8104078919 -:10371000E468012564698D403D43058123600023F1 -:10372000A2606360F0BC01F01FBB000070B5022313 -:10373000002504460370A0F8645080F8665080F8B5 -:10374000675005814581C560056145618561C56139 -:10375000056280F84C5001F057F963681B6823B18B -:1037600029462046BDE87040184770BD037880F8B0 -:1037700068300523037043681B6810B504460BB11D -:103780000421984700232381638110BD436890F88A -:1037900068201B6802700BB10521184770470000B4 -:1037A00090F84C3070B5044613B1002380F84C30CB -:1037B00004F15C02204601F041FA63689B6863BB38 -:1037C00094F85C5015F0600615D194F85D3005F062 -:1037D0007F0545EA032540F202339D4200F00E8149 -:1037E0005BD8022D00F0DC803FD8002D00F08780F0 -:1037F000012D00F0CF800021204601F08FFC002138 -:10380000204601F081FC63681B6813B10621204645 -:103810009847062384F84C3070BD2046984700280E -:10382000CED094F8632094F8623043EA0223626DAC -:10383000934238BF636594F95C30656D002B4FF09F -:10384000200380F2FD80002D00F0EC80092284F836 -:103850004C2083F311880021636D226D2046FFF711 -:1038600053FF002383F3118870BDB5F5817F00F00D -:10387000B180B5F5407F49D0B5F5807FBBD194F8D4 -:103880005E30012BB7D1B4F8643023F00203A4F802 -:10389000643026656665A665C3E740F201639D4214 -:1038A0001ED8B5F5C06F3BD2B5F5A06FA3D1B4F863 -:1038B0005C30B3F5A06F0ED194F85E3084F86630BA -:1038C000204601F0F9F863681B6813B10121204616 -:1038D000984703232370002323656365A365A0E74E -:1038E000B5F5106F32D040F602439D4252D0B5F587 -:1038F000006F80D104F167032365012324E004F104 -:103900006403236502236365A5658AE794F85E3046 -:10391000012B7FF470AFB4F8643043F00203B6E7D4 -:1039200094F86120616894F860304D6894F85F10F5 -:1039300043EA0223204694F85E20A84700283FF47B -:103940005AAF4368236503686365A4E72378042BB3 -:1039500010D1202383F311882046FFF7B3FE86F3AE -:103960001188636884F867601B68032121700BB1BC -:103970002046984794F85E30002BACD084F867302E -:103980000423237063681B68002BA4D00221204607 -:103990009847A0E7374B23650223636500239DE723 -:1039A00094F8601011F0800F204601F00F010ED046 -:1039B00001F036F9012806D002287FF41CAF2E4B07 -:1039C0002365606567E72D4B2365656563E701F057 -:1039D00019F9EFE794F85E30002B7FF40CAF94F800 -:1039E000603013F00F013FF476AF1A06204602D57F -:1039F00001F0A8FB6FE701F09BFB6CE794F85E30E9 -:103A0000002B7FF4F8AE94F8603013F00F013FF410 -:103A100062AF1B06204602D501F080FB5BE701F098 -:103A200073FB58E7142284F84C2083F311882B464B -:103A30002A4629462046FFF755FE85F3118870BDBA -:103A40005DB1152284F84C2083F311880021636D49 -:103A5000226D2046FFF746FE03E70B2284F84C2038 -:103A600083F311882B462A4629462046FFF74CFE51 -:103A7000E3E700BFAC5B0008A45B0008A85B00089C -:103A800038B590F84C300446152B29D8DFE803F000 -:103A90003E28282828283E28280B29392828282885 -:103AA000282828283E3E90F8631090F86220436D45 -:103AB00042EA01229A4214D9C268128AB3FBF2F593 -:103AC00002FB15356DB9202383F311882B462A4656 -:103AD0002946FFF719FE85F311880A2384F84C3034 -:103AE00038BD142384F84C30202383F3118800233D -:103AF0001A4619462046FFF7F5FD002383F3118887 -:103B000038BD836D03B198470023E7E7002101F03A -:103B100005FB0021204601F0F7FA63681B6813B12A -:103B20000621204698470623D8E7000090F84C204D -:103B3000152A38B5044622D80123934040F6416245 -:103B400013421DD113F480150FD19B0217D50B23FF -:103B500080F84C30202383F311882B462A462946CF -:103B6000FFF7D2FD85F3118838BDC3689B695B6898 -:103B70002BB9836D03B19847002384F84C3038BDCE -:103B8000002101F0CBFA0021204601F0BDFA636864 -:103B90001B6813B10621204698470623EDE7000075 -:103BA000024B00221B605B609A6070472436002045 -:103BB000002303748268054B1B6899689142FBD20D -:103BC0005A680360426010605860704724360020D5 -:103BD00008B5202383F31188037C032B05D0042B25 -:103BE0000DD02BB983F3118808BD436900221A60F8 -:103BF0004FF0FF334361FFF7DBFF0023F2E790E86C -:103C00000C001A6002685360F2E70000002303749E -:103C10008268054B1B6899689142FBD85A6803601B -:103C2000426010605860704724360020054B1969C7 -:103C30000874186802681A605360186101230374DD -:103C4000FCF714BD2436002030B54B1C87B0054668 -:103C50000A4C10D023690A4A01A800F025F9284629 -:103C6000FFF7E4FF049B13B101A800F05BF923699F -:103C7000586907B030BDFFF7D9FFF8E724360020B8 -:103C8000D13B000838B50C4D41612B6981689A68B9 -:103C90009142044603D8BDE83840FFF789BF184673 -:103CA000FFF7B4FF01232C61014623742046BDE8D1 -:103CB0003840FCF7DBBC00BF24360020044B1A68F8 -:103CC0001B6990689B68984294BF00200120704750 -:103CD0002436002010B5084C236820691A68226039 -:103CE0005460012223611A74FFF790FF0146206996 -:103CF000BDE81040FCF7BABC2436002008B5FFF739 -:103D0000DDFF18B1BDE80840FFF7E4BF08BD0000C3 -:103D1000FEE7000010B50C4CFFF742FF00F0B6F8CC -:103D200080220A49204600F03BF8012344F8180C91 -:103D3000037400F0C7FC002383F3118862B60448C3 -:103D4000BDE8104000F04EB84C360020B05B0008D3 -:103D5000B85B000800F022B9EFF3118020B9EFF34F -:103D60000583202282F311887047000010B558B9EE -:103D7000EFF30584C4F3080414B180F3118810BD77 -:103D8000FFF7BCFF84F3118810BD0000034B596896 -:103D90005A68521A9042FBD8704700BF001000E0EA -:103DA0008260022202740022427470478368A3F189 -:103DB0007C0243F80C2C026943F83C2C426943F81E -:103DC000382C074A43F81C2CC26843F8102C0222F6 -:103DD00003F8082C002203F8072CA3F11800704701 -:103DE0008506000810B5202383F31188FFF7DEFF56 -:103DF00000210446FFF746FF002383F31188204685 -:103E000010BD0000024B1B6958610F20FFF70EBF69 -:103E100024360020202383F31188FFF7F3BF00002E -:103E200008B50146202383F311880820FFF70CFF13 -:103E3000002383F3118808BD49B1064B42681B6912 -:103E400018605A60136043600420FFF7FDBE4FF016 -:103E5000FF307047243600200368984206D01A6865 -:103E60000260506059611846FFF7A2BE704700001B -:103E700038B504460D462068844200D138BD036839 -:103E800023605C604561FFF793FEF4E7054B03F1A7 -:103E900014025A619A614FF0FF32DA6100221A620D -:103EA000704700BF24360020F8B50361C2600E469B -:103EB000054601F031FB1A4B19461F4651F8142FE5 -:103EC0008A420DD11862AE606A602A600A2E2CBF49 -:103ED00080190A309D615D61BDE8F84001F00ABBC0 -:103EE0001B6A9268C41A341928BF3446A24202D908 -:103EF000181901F00DFB7B699A6894420CD8AC60EC -:103F000098685A682B60041B6A6015605D609C604D -:103F10004FF0FF33FB61F8BDA41A1B68ECE700BF4C -:103F20002436002038B51C4B01685A6990421D4662 -:103F30000DD044682160026800215460C16091681E -:103F40008068014491604FF0FF32DA6138BD1A4653 -:103F500042F8141F4A605B6900219342C16003D19B -:103F6000BDE8384001F0CEBA9A6881680A449A6088 -:103F70002C6A01F0D1FA6A699268001B82420AD960 -:103F8000111A092998BF00F10A02286ABDE83840D1 -:103F9000104401F0BDBA38BD243600202DE9F041AF -:103FA000184D002705F114066C6901F0B5FA2A6A6C -:103FB000A368811A8B4216D813442B6294E80C0034 -:103FC0001A602268D4F80C8053606B69E760B342D2 -:103FD00001D101F097FA87F311882069C0472023A7 -:103FE00083F31188E0E76A69B24208D05B1A0A2BB2 -:103FF0002CBFC0180A30BDE8F04101F089BABDE815 -:10400000F08100BF2436002000207047FEE700004A -:10401000704700004FF0FF3070470000022906D0C3 -:10402000032906D00129064818BF0020704705481B -:104030007047032A9ABF044800EBC2000020704773 -:10404000A45C0008585C00085C23002070B59AB09E -:1040500001AD064608462946144600F0BDF828463C -:10406000FDF770FEC0B2431C5B0086E818002370A9 -:1040700003236370002302341946DAB2904204F13C -:10408000020401D81AB070BDEA5C04F8022C04F8EE -:10409000011C0133F1E7000008B5202383F31188E8 -:1040A0000348FFF751FA002383F3118808BD00BFCE -:1040B000E037002090F85C3003F01F02012A07D19E -:1040C00090F85D200B2A03D100230365436512E0BD -:1040D00003F06003202B11D1B0F8603073B990F871 -:1040E0005D20212A03D0222AEFD0202A06D1044ABB -:1040F000026507224265836501207047FFF700BA19 -:104100005323002010B50446052916D8DFE801F036 -:1041100016150316161D202383F311880E4A01215C -:10412000FFF7B6FA20460D4A0221FFF7B1FA0C4814 -:10413000FFF7D0F9002383F3118810BD202383F308 -:1041400011880748FFF79CF9F4E7202383F31188CF -:104150000348FFF7B3F9EDE7D85B0008FC5B000804 -:10416000E037002038B50C4D0C4C0D492A4604F1BF -:104170000800FFF76BFF05F1CA0204F110000949BE -:10418000FFF764FF05F5CA7204F118000649BDE89F -:104190003840FFF75BBF00BFA83C00205C23002035 -:1041A000285C0008325C00083D5C000870B50446DD -:1041B00008460D46FDF7C6FDC6B220460134037819 -:1041C0000BB9184670BD32462946FDF7A3FD0028FD -:1041D000F3D1012070BD00002DE9F84F05460C46D3 -:1041E000FDF7B0FD2B49C6B22846FFF7DFFF08B147 -:1041F0000336F6B228492846FFF7D8FF08B1103633 -:10420000F6B2632E0DD8DFF88C80DFF88C90234F48 -:10421000DFF890A0DFF890B02E7846B92670BDE8A0 -:10422000F88F29462046BDE8F84F01F029BC252E1D -:104230002CD1072241462846FDF76CFD58B9DBF822 -:1042400000302360DBF804306360BBF80830238162 -:1042500007350A34E0E7082249462846FDF75AFDAB -:10426000A0B90F4BA21C13F8011F09095345C95DE2 -:1042700002F8021C197801F00F0102F10202C95D77 -:1042800002F8031CEFD118340835C5E72670013554 -:104290000134C1E7C45C00083D5C0008CC5C000848 -:1042A0000F7AF01F1B7AF01F425B0008BFF34F8F9D -:1042B000024AD368DB03FCD4704700BF003C0240D5 -:1042C00008B5074B1B7853B9FFF7F0FF054B1A6988 -:1042D000002ABFBF044A5A6002F188325A6008BD02 -:1042E000063F0020003C02402301674508B5054B0E -:1042F0001B7833B9FFF7DAFF034A136943F0004331 -:10430000136108BD063F0020003C0240072870B53D -:1043100013D80B4A0B4C137863B90B4E4FF0006166 -:1043200044F8231056F823500133082B2944F7D1C1 -:104330000123137054F8200070BD002070BD00BF31 -:10434000283F0020083F0020E05C0008014B53F8A4 -:1043500020007047E05C000808207047072810B56F -:10436000044601D9002010BDFFF7D0FF064B53F8DB -:1043700024301844C21A0BB9012010BD1268013252 -:10438000F0D1043BF6E700BFE05C0008072810B559 -:10439000044621D8FFF78AFFFFF792FF0F4AF32365 -:1043A000D360C300DBB243F4007343F00203136134 -:1043B000136943F480331361FFF778FFFFF7A6FF1B -:1043C000074B53F8241000F013F9FFF78FFF204636 -:1043D000BDE81040FFF7C2BF002010BD003C024006 -:1043E000E05C00082DE9F84312F00103154640D1C6 -:1043F00084182E4A94423CD82D4B1B6813F00103BD -:1044000037D02C4CFFF75CFFF323E360FFF74EFF40 -:1044100040F20127032D01D9830713D0254C0F4605 -:10442000401A40F20118EB1B0B44012B00EB07066E -:10443000236924D823F001032361FFF757FF0120EC -:10444000BDE8F883236923F44073236123693B4368 -:10445000236151F8046B0660BFF34F8FFFF726FF0F -:1044600003689E4208D0236923F001032361FFF70C -:104470003DFF0020BDE8F883043D0430CAE723F483 -:1044800040732361236943EA08032361B94637F87F -:10449000023B3380BFF34F8FFFF708FF3688B9F830 -:1044A0000030B6B2B342BED0DDE700BF000008085E -:1044B00000380240003C0240084908B50B7828B19A -:1044C00053B9FFF7FDFE01230B7008BD23B1BDE812 -:1044D00008400870FFF70ABF08BD00BF063F002074 -:1044E00038B501F019F8074B1A68824207D9064A15 -:1044F000D2E90045003445F10105C2E900451860E4 -:1045000038BD00BF2C3F0020303F002070B5FFF7C2 -:1045100023FC0646FFF7E4FF054BD3E900452418CA -:1045200045F100053046FFF721FC2046294670BDC5 -:10453000303F002008B5FFF7E9FF4FF47A720023FF -:10454000FBF776FE08BD00BF10B50244064B0439E8 -:10455000D2B2904200D110BD441C00B253F82000EA -:1045600041F8040FE0B2F4E750280040104B30B59A -:104570001C6F240407D41C6F44F400741C671C6F68 -:1045800044F400441C670B4C236843F4807323609D -:104590000244094B0439D2B2904200D130BD441CD0 -:1045A00000B251F8045F43F82050E0B2F4E700BFD6 -:1045B00000380240007000405028004007B501223A -:1045C00001A90020FFF7C0FF019803B05DF804FBCC -:1045D00013B50446FFF7F2FFA04206D002A901225C -:1045E00041F8044D0020FFF7C1FF02B010BD0000EC -:1045F0000144BFF34F8F064B884204D3BFF34F8F64 -:10460000BFF36F8F7047C3F85C022030F4E700BF40 -:1046100000ED00E0074B45F255521A6002225A6045 -:1046200040F6FF729A604CF6CC421A60024B0122AF -:104630001A707047003000403C3F0020034B1B784D -:104640001BB1034B4AF6AA221A6070473C3F002078 -:1046500000300040034B1A6812B9034A12681A600E -:10466000704700BF383F002074380240024B4FF0C3 -:1046700080721A60704700BF7438024008B5FFF7B7 -:10468000E9FF024B1868C0F3407008BD383F0020B6 -:1046900008B5FFF7DFFF024B1868C0F3007008BDD4 -:1046A000383F0020EFF3098305494A6822F00102F0 -:1046B0004A60683383F30988002383F311887047C5 -:1046C00030EF00E0202080F3118862B60D4B0E4AD7 -:1046D000D96821F4E0610904090C0A430B49DA6046 -:1046E000CA6842F08072CA60094A0A49C2F8B01F1B -:1046F000116841F0010111601022DA7783F822007D -:10470000704700BF00ED00E00003FA05F0ED00E0A7 -:10471000001000E055CEACC510B5202383F31188FE -:104720000E4B5B6813F4006314D0F1EE103AEFF314 -:104730000984683C4FF08073E361094BDB682366B2 -:1047400084F30988FFF7BAFA10B1064BA36110BDD4 -:10475000054BFBE783F3118810BD00BF00ED00E0BF -:1047600030EF00E0970600089A060008F0B5BFF3A6 -:104770004F8FBFF36F8F1D4B0021C3F85012BFF353 -:104780004F8FBFF36F8F5A6942F400325A61BFF303 -:104790004F8FBFF36F8FC3F88410BFF34F8FD3F8E1 -:1047A0008020C2F3C904C2F34E325201A50743F67A -:1047B000E07602EA060E284621464EEA0007013955 -:1047C000C3F860724F1C00F14040F6D1203A12F15C -:1047D000200FEED1BFF34F8F5A6942F480325A61F5 -:1047E000BFF34F8FBFF36F8FF0BD00BF00ED00E050 -:1047F000FEE70000084A094B09498B4204D3094AE5 -:104800000021934205D3704752F8040F43F8040B7C -:10481000F3E743F8041BF4E7B05E000850400020C3 -:10482000504000205040002070470000036F70B5DA -:10483000C46E9E6800214FF0FF354A01A318013174 -:10484000D3F800090028BEBFD3F8000940F080402B -:10485000C3F80009D3F8000B0028BEBFD3F8000B43 -:1048600040F08040C3F8000BA3188E42C3F80859EB -:10487000C3F8085BE1D24FF00113C4F81C3870BDD7 -:10488000890141F02001016103699B06FCD41220DB -:10489000FFF77CBA204B03EB80022DE9F047D2F8FA -:1048A0000CE0DD6EDEF81420461CD2F800C005EBEB -:1048B000063605EB4018516861450BD3D5F834280E -:1048C000012303FA00F022EA0000C5F83408184674 -:1048D000BDE8F087BEF81040ACEB0103A34228BF4F -:1048E0002346D8F81849A4B2B3EB840F10D89468C3 -:1048F0001F46A4F1040959F804AFC6F800A0042F1C -:1049000001D9043FF7E71C440B4494605360D2E79D -:104910000020BDE8F08700BF403F002010B5054CE7 -:104920002046FEF791FE4FF0A043E366024B23675B -:1049300010BD00BF403F0020245D00080378012B1C -:1049400070B5054650D12A4BC46E98421BD1294BF5 -:104950005A6B42F080025A635A6D42F080025A65E7 -:104960005A6D5A6942F080025A615A6922F08002F7 -:104970005A610E2143205B69FEF736FC1E4BE36053 -:104980001E4BC4F800380023C4F8003EC023236047 -:10499000EE6E4FF40413A3633369002BFCDA01239A -:1049A00033610C20FFF7F2F93369DB07FCD41220E6 -:1049B000FFF7ECF93369002BFCDA0026A6602846E5 -:1049C000FFF734FF6B68C4F81068DB68C4F814683C -:1049D000C4F81C684BB90A4BA3614FF0FF33636105 -:1049E000A36843F00103A36070BD064BF4E700BF6A -:1049F000403F0020003802404014004003002002E5 -:104A0000003C30C0083C30C0F8B5C46E05460021FB -:104A10002046FFF735FF296F00234FF001128F6802 -:104A2000C4F834384FF00066C4F81C284FF0FF304B -:104A300004EB431201339F42C2F80069C2F8006BD5 -:104A4000C2F80809C2F8080BF2D20B68EA6E6B676D -:104A5000636210231361166916F01006FBD1122051 -:104A6000FFF794F9D4F8003823F4FE63C4F8003853 -:104A7000A36943F4402343F01003A3610923C4F85E -:104A80001038C4F814380A4BEB604FF0C043C4F838 -:104A9000103B084BC4F8003BC4F81069C4F8003957 -:104AA0006B6F03F1100243F480136A67A362F8BDD1 -:104AB000005D000840800010C26E90F86610D2F8C9 -:104AC000003823F4FE6343EA0113C2F8003870474C -:104AD0002DE9F0410EB200EB86080D46D8F80C1017 -:104AE0000F6807F00303022B50D0032B50D03D4A30 -:104AF0003D4F012B18BF1746C46E4FEA451E04EB0D -:104B00000E030022C3F8102B8A6905F1100C002A4D -:104B100040D04A8A05F158035B013A43E250012331 -:104B2000D4F81C2803FA0CF31343A6444A69C4F8CA -:104B30001C380023CEF8103905F13F03002A39D084 -:104B40000A8A898B9208012988BF4A43416F04EB86 -:104B50008303561841EA0242466729465A602046B6 -:104B6000FFF78EFED8F80C301B8A43EA85531F43AB -:104B700005F148035B01E7500123D4F81C2803FA30 -:104B800005F51543C4F81C58BDE8F081174FB3E78D -:104B9000174FB1E704EB4613D3F8002B22F4004281 -:104BA000C3F8002BD4F81C28012303FA0CF322EAE3 -:104BB0000303BAE704EB83030E4A5A6004EB46167C -:104BC00029462046FFF75CFED6F8003923F400435F -:104BD000C6F80039D4F81C38012202FA05F523EA98 -:104BE0000505CFE700800010008004100080081049 -:104BF00000800C1000040002026F12684267FFF789 -:104C000015BE00005831C36E49015B5813F40040D3 -:104C100004D013F4001F14BF0120022070470000CD -:104C20004831C36E49015B5813F4004004D013F4BB -:104C3000001F14BF012002207047000000EB81011B -:104C4000CB68196A0B6813604B68536070470000AB -:104C500000EB810330B5DD68AA691368D36019B928 -:104C6000402B84BF402313606B8A1468C26E1C44BF -:104C7000013CB4FBF3F46343033323F0030302EB7F -:104C8000411043EAC44343F0C043C0F8103B2B68D3 -:104C900003F00303012B09B20ED1D2F8083802EB5E -:104CA000411013F4807FD0F8003B14BF43F08053D1 -:104CB00043F00053C0F8003B02EB4112D2F8003B36 -:104CC00043F00443C2F8003B30BD00002DE9F04141 -:104CD000244DEE6E06EB40130446D3F8087BC3F870 -:104CE000087B38070AD5D6F81438190706D505EB1E -:104CF00084032146DB6828465B689847FA072FD56E -:104D0000D6F81438DB072BD505EB8403D968CCB96A -:104D10008B69488A5E68B6FBF0F200FB12628AB9C2 -:104D20001868DA6890420DD2121A83E81400202322 -:104D300083F311880B482146FFF78AFF84F311881B -:104D4000BDE8F081012303FA04F26B8923EA020330 -:104D50006B81CB6823B121460248BDE8F04118477A -:104D6000BDE8F081403F002000EB810370B5DD68B5 -:104D7000C36E6C692668E6604A0156BB1A444FF45C -:104D80000020C2F810092A6802F00302012A0AB2C0 -:104D90000ED1D3F8080803EB421410F4807FD4F846 -:104DA000000914BF40F0805040F00050C4F80009E2 -:104DB00003EB4212D2F8000940F00440C2F80009A7 -:104DC000D3F83408012202FA01F10143C3F8341880 -:104DD00070BD19B9402E84BF4020206020682E8A03 -:104DE000841940F00050013C1A44B4FBF6F440EA48 -:104DF000C440C6E7F8B504461E48C56E05EB44132B -:104E0000D3F80869C3F80869F10717D5D5F8103841 -:104E1000DA0713D500EB8403D9684B691F68DA6899 -:104E2000974218D2D21B00271A605F60202383F3B9 -:104E300011882146FFF798FF87F31188330617D5AD -:104E4000D5F834280123A340134211D02046BDE8F1 -:104E5000F840FFF71FBD012303FA04F2038923EA98 -:104E6000020303818B68002BE8D021469847E5E7D1 -:104E7000F8BD00BF403F0020A2482DE9F84FC56EA5 -:104E80006E69AB691E4016F4805F6E61044605D002 -:104E9000FEF74CFCBDE8F84FFFF73EBC002E12DADF -:104EA000D5F8003E97489B071EBFD5F8003E23F07B -:104EB0000303C5F8003ED5F8043823F00103C5F814 -:104EC0000438FEF763FC370505D58E48FFF7AEFCC6 -:104ED0008C48FEF74BFCB0040CD5D5F8083813F01D -:104EE000060FEB6823F470530CBF43F4105343F4E4 -:104EF000A053EB60310704D56368DB680BB18148D0 -:104F00009847F2026FD4B3020CD5D4F86C80DFF866 -:104F1000F4A100274FF00109236F9B68F9B28B427F -:104F200080F09C80F70619D5E16E0A6AC2F30A1771 -:104F300002F00F0302F4F012B2F5802F00F0B680F9 -:104F4000B2F5402F0AD104EB830301F58051DB68F1 -:104F5000186A00231A469F4240F09C803303D5F81C -:104F600018481DD5E70302D50020FFF7AFFEA503C3 -:104F700002D50120FFF7AAFE600302D50220FFF749 -:104F8000A5FE210302D50320FFF7A0FEE20202D511 -:104F90000420FFF79BFEA30202D50520FFF796FE33 -:104FA00077037FF577AFE60702D50020FFF722FFF2 -:104FB000A50702D50120FFF71DFF600702D50220DB -:104FC000FFF718FF210702D50320FFF713FFE206C2 -:104FD00002D50420FFF70EFFA3067FF55BAF052087 -:104FE000FFF708FF56E7D4F86C80DFF818A1002718 -:104FF0004FF00109236F9B685FFA87FB5B4582D303 -:1050000008EB4B13D3F8002902F44022B2F5802FAD -:1050100022D1D3F80029002A1EDAD3F8002942F061 -:105020009042C3F80029D3F80029002AFBDB594637 -:10503000E06EFFF725FC228909FA0BF322EA03034D -:10504000238104EB8B03DB689B6813B15946504600 -:1050500098475846FFF71EFC0137CBE708EB411293 -:10506000D2F8003B03F44023B3F5802F10D1D2F8DF -:10507000003B002B0CDA628909FA01F322EA0303F0 -:10508000638104EB8103DB68DB680BB15046984712 -:10509000013741E79C0708BF0A68072B98BF0270D9 -:1050A00003F101039CBF120A013054E7023304EB01 -:1050B000830201F58051526890690268D0F808C0F7 -:1050C0004068A2EB000E0022104697420AD104EB82 -:1050D000830463689B699A683A449A605A681744E3 -:1050E0005F603BE712F0030F08BF0868964588BF72 -:1050F0008CF8000002F1010284BF000A0CF1010CDF -:10510000E3E700BF403F0020C36E03EB4111D1F83D -:10511000003B43F40013C1F8003B7047C36E03EB40 -:105120004111D1F8003943F40013C1F80039704738 -:10513000C36E03EB4111D1F8003B23F40013C1F817 -:10514000003B7047C36E03EB4111D1F8003923F4E3 -:105150000013C1F80039704730B5039C0172043365 -:1051600004FB0325C361049B03630021059B0060CE -:105170004060C16042610261856104624262816295 -:10518000C162436330BD00000022416A4161016198 -:10519000C2608262C2626FF00101FEF769BE000068 -:1051A00003694269934203D1C2680AB10020704783 -:1051B000181D704703691960C2680132C260C26974 -:1051C000134482690361934224BF436A036100214F -:1051D000FEF742BE38B504460D46E3683BB162694E -:1051E000131D1268A3621344E362002038BD237AC2 -:1051F00033B929462046FEF71FFE0028EDDA38BDF8 -:105200006FF00100FBE70000C368C269013BC360A7 -:105210004369134482694361934224BF436A4361F3 -:1052200000238362036B03B11847704770B52023D6 -:10523000044683F31188866A3EB9FFF7CBFF054623 -:1052400018B186F31188284670BDA36AE26A13F884 -:10525000015BA362934202D32046FFF7D5FF0023F0 -:1052600083F31188EFE700002DE9F84F04460E465E -:1052700090469946202787F311880025AA46D4F83E -:1052800028B0BBF1000F09D149462046FFF7A2FF25 -:1052900020B18BF311882846BDE8F88FA16AE36A34 -:1052A000A8EB050B5B1A9B4528BF9B46BBF1400F43 -:1052B0001BD9334601F1400251F8040B43F8040BAB -:1052C0009142F9D1A36A40334036A3624035A26AC5 -:1052D000E36A9A4202D32046FFF796FF8AF31188C9 -:1052E0004545D8D287F31188C9E730465A46FCF7BE -:1052F00007FDA36A5B445E44A3625D44E7E70000E8 -:1053000010B5029C0172043303FB0421C361002326 -:105310008362C362039B0363049B00604060C460BC -:1053200042610261816104624262436310BD000018 -:10533000026AC260426A4261026100228262C26203 -:105340006FF00101FEF794BD436902699A4203D1EF -:10535000C2680AB100207047184650F8043B0B6041 -:1053600070470000C368C2690133C36043691344D6 -:1053700082694361934224BF436A43610021FEF77F -:105380006BBD000038B504460D46E3683BB12369A8 -:105390001A1DA262E2691344E362002038BD237A39 -:1053A00033B929462046FEF747FD0028EDDA38BD1F -:1053B0006FF00100FBE7000003691960C268013A61 -:1053C000C260C269134482690361934224BF436A85 -:1053D000036100238362036B03B118477047000029 -:1053E00070B5202304460E4683F31188856A35B9CB -:1053F0001146FFF7C7FF10B185F3118870BDA36A8E -:105400001E70A36AE26A01339342A36204D3E16986 -:1054100020460439FFF7D0FF002080F3118870BDCB -:105420002DE9F84F04460D4691469A464FF0200864 -:1054300088F311880026B346A76A4FB95146204623 -:10544000FFF7A0FF20B187F311883046BDE8F88F41 -:10545000A06AE76AA9EB06033F1A9F4228BF1F46CE -:10546000402F1BD905F1400355F8042B40F8042BBD -:105470009D42F9D1A36A4033A3624036A26AE36A2F -:105480009A4204D3E16920460439FFF795FF8BF374 -:1054900011884E45D9D288F31188CDE729463A467E -:1054A000FCF72EFCA36A3B443D44A3623E44E5E77F -:1054B000026943699A4203D1C3681BB91846704711 -:1054C0000023FBE7836A002BF8D0043B9B1AF5D03E -:1054D0001360C368013BC360C3691A4483690261F6 -:1054E0009A4224BF436A0361002383620123E5E7F4 -:1054F00000F090B84FF08043002258631A610222F6 -:10550000DA6070474FF080430022DA607047000095 -:105510004FF08043586370474FF08043586A70479C -:105520004B6843608B688360CB68C3600B694361E1 -:105530004B6903628B6943620B680360704700002C -:1055400008B5224B22481A6940F2FF110A431A613A -:105550001A6922F4FF7222F001021A611A691A6BA9 -:105560000A431A631A6D0A431A651A4A1B6D1146DB -:10557000FFF7D6FF184802F11C01FFF7D1FF1748CB -:1055800002F13801FFF7CCFF154802F15401FFF793 -:10559000C7FF144802F17001FFF7C2FF124802F181 -:1055A0008C01FFF7BDFF114802F1A801FFF7B8FF1A -:1055B0000F4802F1C401FFF7B3FF0E4802F1E0010A -:1055C000FFF7AEFFBDE8084000F098B80038024091 -:1055D00000000240305D0008000402400008024064 -:1055E000000C02400010024000140240001802406B -:1055F000001C02400020024008B500F0F5F9FEF75B -:1056000089FBFFF727F8BDE80840FEF7ABBD0000B7 -:10561000704700000F4B1A6C42F001021A641A6EB8 -:1056200042F001021A660C4A1B6E936843F00103B4 -:1056300093604FF080436B229A624FF0FF32DA6240 -:1056400000229A615A63DA605A6001225A611A6034 -:10565000704700BF00380240002004E04FF0804255 -:1056600008B51369D1680B40D9B2C9439B071161D2 -:1056700007D5202383F31188FEF76CFB002383F307 -:10568000118808BD1B4B1A696FEAC2526FEAD252E9 -:105690001A611A69C2F308021A614FF0FF301A69E1 -:1056A0005A69586100215A6959615A691A6A62F047 -:1056B00080521A621A6A02F080521A621A6A5A6A90 -:1056C00058625A6A59625A6A0B4A106840F48070EC -:1056D0001060186F00F44070B0F5007F1EBF4FF4EB -:1056E000803018671967536823F40073536000F023 -:1056F00057B900BF0038024000700040374B384AAD -:105700001A64384A4FF4404111601A6842F00102AD -:105710001A601A689207FCD59A6822F003029A6010 -:105720002E4B19469A6812F00C02FBD1186800F053 -:10573000F90018609A601A6842F480321A600B68A7 -:105740009B03FCD54B6F43F001034B67234B5A6F10 -:105750009007FCD5244A5A601A6842F080721A6099 -:10576000204B1A4659684904FCD5196841F4803128 -:1057700019605368D803FCD5136843F400331360F1 -:10578000184A53689903FCD5144B1A689201FCD54A -:10579000164A9A6040F20112C3F88C200022C3F826 -:1057A0009020134B40F207321A601A6802F00F0281 -:1057B000072AFAD1094B9A6842F002029A609A6865 -:1057C00002F00C02082AFAD15A6C42F480425A6460 -:1057D0005A6E42F480425A665B6E7047003802404F -:1057E0000004001000700040106C400900948838DC -:1057F000003C0240074A08B5536903F001035361B6 -:1058000023B1054A13680BB150689847BDE80840BA -:10581000FEF782BF003C0140D03F0020074A08B598 -:10582000536903F00203536123B1054A93680BB136 -:10583000D0689847BDE80840FEF76EBF003C0140C5 -:10584000D03F0020074A08B5536903F004035361B1 -:1058500023B1054A13690BB150699847BDE8084068 -:10586000FEF75ABF003C0140D03F0020074A08B570 -:10587000536903F00803536123B1054A93690BB1DF -:10588000D0699847BDE80840FEF746BF003C01409C -:10589000D03F0020074A08B5536903F01003536155 -:1058A00023B1054A136A0BB1506A9847BDE8084016 -:1058B000FEF732BF003C0140D03F0020164B10B530 -:1058C0005C6904F478725A61A30604D5134A936A9A -:1058D0000BB1D06A9847600604D5104A136B0BB120 -:1058E000506B9847210604D50C4A936B0BB1D06BD3 -:1058F0009847E20504D5094A136C0BB1506C9847E0 -:10590000A30504D5054A936C0BB1D06C9847BDE84C -:105910001040FEF701BF00BF003C0140D03F002017 -:10592000194B10B55C6904F47C425A61620504D5D8 -:10593000164A136D0BB1506D9847230504D5134AD1 -:10594000936D0BB1D06D9847E00404D50F4A136EE8 -:105950000BB1506E9847A10404D50C4A936E0BB15D -:10596000D06E9847620404D5084A136F0BB1506F8C -:105970009847230404D5054A936F0BB1D06F98471D -:10598000BDE81040FEF7C8BE003C0140D03F0020FB -:1059900008B5FFF763FEBDE80840FEF7BDBE000096 -:1059A000062108B50846FDF71FFC06210720FDF774 -:1059B0001BFC06210820FDF717FC06210920FDF736 -:1059C00013FC06210A20FDF70FFC06211720FDF726 -:1059D0000BFC06212820FDF707FC07211C20BDE851 -:1059E0000840FDF701BC000008B5FFF74BFE00F0D2 -:1059F0000DF8FDF70FFCFDF725FEFDF7F9FCFFF7AD -:105A000007FEBDE80840FFF773BD0000002304490E -:105A10001A465A50C8180833802B4260F9D1704793 -:105A2000D03F002010B501390244904201D100203E -:105A300010BD10F8013B11F8014FA342F5D0181B1F -:105A400010BD00002DE9F8430746884691461E46E2 -:105A50008BB10D46A8EB0500B54207EB000402D25E -:105A60000020BDE8F883324649462046FFF7DAFFBA -:105A700018B1013DEEE7BDE8F8832046BDE8F883A4 -:105A8000034611F8012B03F8012B002AF9D17047C6 -:105A9000121012131211000040A2E4F16468910682 -:105AA0004E6F20617070207369670A004261642044 -:105AB0006677206C656E6774682025750A00426100 -:105AC0006420626F6172645F696420257520736869 -:105AD0006F756C642062652025750A004261642040 -:105AE00066772064657363726970746F72206C6589 -:105AF0006E6774682025750A0042616420617070C9 -:105B000020435243203078253038783A3078253099 -:105B10003878203078253038783A30782530387821 -:105B20000A00476F6F64206669726D776172650A5B -:105B3000000000006F72672E6172647570696C6F8F -:105B4000742E46726565666C7952544B00000000F5 -:105B500053544D3332463F3F3F3F3F3F0053544D38 -:105B6000333246375B347C355D780053544D3332E5 -:105B700046375B367C375D7800000000000000008F -:105B80006933000855330008913300087D3300085D -:105B90008933000875330008613300084D3300086D -:105BA000ED330008000000000100000000000000CC -:105BB0006D61696E00000000D05B0008683600204F -:105BC000E037002001000000113D00080000000047 -:105BD00069646C6500000000020000000000000025 -:105BE00095350008FD35000840004000783C002055 -:105BF000883C0020020000000000000003000000BC -:105C00000000000041360008000000001000000005 -:105C1000983C00200000000001000000000000008F -:105C2000403F0020010102004172647550696C6FB1 -:105C3000740025424F415244252D424C00255345C6 -:105C40005249414C25000000054100081D40000854 -:105C5000B54000089940000843000000605C00085F -:105C600009024300020100C03209040000010202DF -:105C70000100052400100105240100010424020292 -:105C80000524060001070582030800FF090401003E -:105C9000020A00000007050102400000070581021A -:105CA0004000000012000000AC5C0008120110016E -:105CB00002000040091241570002010203010000E6 -:105CC0000403090425424F41524425003031323348 -:105CD00034353637383941424344454600000000E8 -:105CE00000400000004000000040000000400000B4 -:105CF000000001000000020000000200000002009D -:105D000000000000A1370008813A00082D3B000880 -:105D100040004000B83F0020B83F002001000000D4 -:105D2000C83F002080000000400100000500000086 -:105D30000010806A00000000AAAAAAAA000000645D -:105D4000FFFF00000000000000A00A0000000A00A1 -:105D500000000000AAAAAAAA00000000FFFF00009D -:105D6000000000009900000000400000000000005A -:105D7000AAAAAAAA00000020FFFF0000000000005D -:105D8000000000000000000000000000AAAAAAAA6B -:105D900000000000FFFF0000000000000000000005 -:105DA0000000000000000000AAAAAAAA000000004B -:105DB000FFFF0000000000000000000000000000E5 -:105DC00000000000AAAAAAAA00000000FFFF00002D -:105DD00000000000000000000000000000000000C3 -:105DE000AAAAAAAA00000000FFFF0000000000000D -:105DF0000000000000000000000000000A00000099 -:105E0000000000000300000000000000000000008F +:100000000007002005050008351E0008B51D000882 +:100010000D1E0008B51D0008E11D000807050008B9 +:100020000705000807050008070500084146000805 +:100030000705000807050008070500080705000870 +:100040000705000807050008070500080705000860 +:1000500007050008070500086157000889570008D0 +:10006000B1570008D95700080158000807050008D3 +:100070000705000807050008070500080705000830 +:10008000070500080705000807050008ED2D000812 +:10009000592E0008AD2E0008012F0008295800082D +:1000A0000705000807050008070500080705000800 +:1000B000FD580008070500080705000807050008A7 +:1000C00007050008070500080705000807050008E0 +:1000D00007050008070500080705000807050008D0 +:1000E0008D580008070500080705000807050008E7 +:1000F00007050008070500080705000807050008B0 +:10010000070500080705000807050008070500089F +:10011000070500080705000807050008070500088F +:10012000070500080705000807050008070500087F +:10013000070500080705000807050008070500086F +:10014000070500080705000807050008F54D000829 +:10015000070500080705000807050008070500084F +:10016000070500080705000807050008070500083F +:10017000070500080705000807050008070500082F +:10018000070500080705000807050008070500081F +:10019000070500080705000807050008070500080F +:1001A00007050008070500080705000807050008FF +:1001B00007050008070500080705000807050008EF +:1001C00007050008070500080705000807050008DF +:1001D00007050008070500080705000807050008CF +:1001E00007050008070500080705000807050008BF +:1001F00007050008070500080705000807050008AF +:1002000053B94AB9002908BF00281CBF4FF0FF317D +:100210004FF0FF3000F074B9ADF1080C6DE904CE79 +:1002200000F006F8DDF804E0DDE9022304B07047D1 +:100230002DE9F047089D04468E46002B4DD18A4299 +:10024000944669D9B2FA82F252B101FA02F3C2F1CC +:10025000200120FA01F10CFA02FC41EA030E94405D +:100260004FEA1C48210CBEFBF8F61FFA8CF708FB7E +:1002700016E341EA034306FB07F199420AD91CEB56 +:10028000030306F1FF3080F01F81994240F21C8188 +:10029000023E63445B1AA4B2B3FBF8F008FB1033D0 +:1002A00044EA034400FB07F7A7420AD91CEB040405 +:1002B00000F1FF3380F00A81A74240F207816444D5 +:1002C000023840EA0640E41B00261DB1D44000235A +:1002D000C5E900433146BDE8F0878B4209D9002DBE +:1002E00000F0EF800026C5E9000130463146BDE848 +:1002F000F087B3FA83F6002E4AD18B4202D38242B2 +:1003000000F2F980841A61EB030301209E46002D60 +:10031000E0D0C5E9004EDDE702B9FFDEB2FA82F2B5 +:10032000002A40F09280A1EB0C014FEA1C471FFA13 +:100330008CFE0126200CB1FBF7F307FB131140EAFA +:1003400001410EFB03F0884208D91CEB010103F1C7 +:10035000FF3802D2884200F2CB804346091AA4B289 +:10036000B1FBF7F007FB101144EA01440EFB00FE5D +:10037000A64508D91CEB040400F1FF3102D2A645C2 +:1003800000F2BB800846A4EB0E0440EA03409CE761 +:10039000C6F12007B34022FA07FC4CEA030C20FA0E +:1003A00007F401FA06F31C43F9404FEA1C4900FA2E +:1003B00006F3B1FBF9F8200C1FFA8CFE09FB1811AB +:1003C00040EA014108FB0EF0884202FA06F20BD91E +:1003D0001CEB010108F1FF3A80F08880884240F26E +:1003E0008580A8F102086144091AA4B2B1FBF9F0B2 +:1003F00009FB101144EA014100FB0EFE8E4508D9AD +:100400001CEB010100F1FF346CD28E456AD9023831 +:10041000614440EA0840A0FB0294A1EB0E01A14216 +:10042000C846A64656D353D05DB1B3EB080261EB84 +:100430000E0101FA07F722FA06F3F1401F43C5E95E +:10044000007100263146BDE8F087C2F12003D84094 +:100450000CFA02FC21FA03F3914001434FEA1C47D6 +:100460001FFA8CFEB3FBF7F007FB10360B0C43EAC8 +:10047000064300FB0EF69E4204FA02F408D91CEB78 +:10048000030300F1FF382FD29E422DD90238634476 +:100490009B1B89B2B3FBF7F607FB163341EA034116 +:1004A00006FB0EF38B4208D91CEB010106F1FF3865 +:1004B00016D28B4214D9023E6144C91A46EA00465C +:1004C00038E72E46284605E70646E3E61846F8E6EE +:1004D0004B45A9D2B9EB020864EB0C0E0138A3E737 +:1004E0004646EAE7204694E74046D1E7D0467BE718 +:1004F000023B614432E7304609E76444023842E790 +:10050000704700BF02E000F000F8FEE772B63A481C +:1005100080F30888394880F3098839484EF6085135 +:10052000CEF20001086040F20000CCF200004EF66E +:100530003471CEF200010860BFF34F8FBFF36F8FAD +:1005400040F20000C0F2F0004EF68851CEF20001F9 +:100550000860BFF34F8FBFF36F8F4FF00000E1EEE5 +:10056000100A4EF63C71CEF200010860062080F3BE +:100570001488BFF36F8F04F021F904F0C3F804F07E +:100580009FFF4FF055301F491B4A91423CBF41F835 +:10059000040BFAE71C49194A91423CBF41F8040B8D +:1005A000FAE71A491A4A1B4B9A423EBF51F8040B0C +:1005B00042F8040BF8E700201749184A91423CBF63 +:1005C00041F8040BFAE704F0DBF804F0CDFF144C1B +:1005D000144DAC4203DA54F8041B8847F9E700F0E5 +:1005E00041F8114C114DAC4203DA54F8041B884712 +:1005F000F9E704F0C3B80000000700200023002042 +:10060000000000080001002000070020A85D00088D +:10061000002300207C23002080230020584000205D +:1006200000020008000200080002000800020008A2 +:100630002DE9F04F2DED108AC1F80CD0D0F80CD078 +:10064000BDEC108ABDE8F08F002383F311882846A3 +:10065000A047002003F07CFBFEE703F0F7FA00DF81 +:10066000FEE70000F8B503F079FF074603F0D4FF7A +:100670000546C0BB224B9F4235D001339F4235D047 +:10068000204B27F0FF029A4233D1F8B200F064FD0C +:100690002E4642F2107400F06DFF08B10024264689 +:1006A00000F060FD08B90646044635B1164B9F427E +:1006B00003D003F0A9FF00242646002003F058FFD2 +:1006C000124B1B695B0418D40EB100F067F801F0FF +:1006D00043FB00F0ADFF01F0E7F9204600F0F4F82D +:1006E00000F05CF8F9E72E460024D4E70446012622 +:1006F000D1E706464FF47A74CDE70024E7E700BF60 +:10070000010007B0000008B0263A09B00008024016 +:1007100008B501F09BF9A0F120035842584108BDEB +:1007200007B541F21203022101A8ADF8043001F02F +:10073000ABF903B05DF804FB10B5202383F31188F7 +:100740001248C3680BB103F089FB114A0F4800231C +:100750004FF47A7103F046FB002383F311880D4CAC +:10076000236813B12368013B2360636813B1636896 +:10077000013B6360084B1B7833B9636823B90220DF +:1007800001F064FA3223636010BD00BF80230020B3 +:10079000390700089C24002094230020F8B5434B1F +:1007A000434A1C46196801317ED004339342F9D183 +:1007B0006268404B9A4277D93F4B9B6803F10063D4 +:1007C00003F580339A426FD203F0F2FE03F004FF88 +:1007D000002001F083F9394B0220187001F02EFA45 +:1007E000374B00211A6C19641A6E19661A6E5A6C0E +:1007F00059645A6E59665A6E5A6942F080025A61BB +:100800005A6922F080025A615A691A6942F000520C +:100810001A611A6922F000521A611B6972B64FF010 +:10082000E023C3F8084DD4E90004BFF34F8FBFF3B2 +:100830006F8F244AC2F88410BFF34F8F536923F49B +:1008400080335361BFF34F8FD2F88030C3F3C905B3 +:10085000C3F34E335B0143F6E07603EA060C294608 +:100860004CEA81770139C2F87472F9D2203B13F156 +:10087000200FF2D1BFF34F8FBFF36F8FBFF34F8FB6 +:10088000BFF36F8F536923F4003353610023C2F821 +:100890005032BFF34F8FBFF36F8F202383F3118844 +:1008A000854680F308882047F8BD00BF0000010896 +:1008B00020000108FFFF00080023002094230020EF +:1008C0000038024000ED00E02DE9F04F93B0AC4B52 +:1008D00000902022FF210AA89D6801F0E7F9A94AAB +:1008E0001378A3B9A8480121C3601170202383F3B2 +:1008F0001188C3680BB103F0B1FAA44AA2480023DF +:100900004FF47A7103F06EFA002383F31188009B91 +:100910009F4A03B113609F49009C00230B705360F2 +:1009200098469B461E469A46012001F087F924B15D +:10093000974B1B68002B00F01C82002001F086F80A +:100940000390039B002B01DA00F024FF039B002B94 +:10095000EDDB012001F068F9039B213B162BE3D866 +:1009600001A252F823F000BFC5090008ED090008F4 +:10097000810A000829090008290900082909000836 +:10098000150B0008E70C0008010C0008630C0008B8 +:100990008B0C0008B10C000829090008C30C0008E2 +:1009A00029090008350D0008650A00082909000812 +:1009B000790D0008D1090008650A00082909000816 +:1009C000630C00080220FFF7A3FE002840F0FB8123 +:1009D000009B0221B8F1000F08BF1C4605A841F298 +:1009E0001233ADF8143001F04FF89DE74FF47A70F0 +:1009F00001F02CF8071EEBDB0220FFF789FE002830 +:100A0000E6D0013F052F00F2E081DFE807F0030A9E +:100A10000D10133605230593042105A801F034F8C1 +:100A200017E057480421F9E75B480421F6E75B48E3 +:100A30000421F3E74FF01C09484601F051F809F191 +:100A400004090590042105A801F01EF8B9F12C0F46 +:100A5000F2D1012000FA07F747EA0B0B5FFA8BFB94 +:100A60004FF0000A01F06EF926B10BF00B030B2BCF +:100A700008BF0024FFF754FE56E749480421CDE79C +:100A8000002EA5D00BF00B030B2BA1D10220FFF7FA +:100A90003FFE074600289BD001203E4E01F01EF885 +:100AA0000220307001F0CAF84FF000085FFA88F9B0 +:100AB000484601F023F8044690B1484601F02EF86C +:100AC00008F101080028F1D1B846044641F212139A +:100AD000022105A8ADF814303E4600F0D5FF23E70B +:100AE00001230220337001F09FF82546244B9B68B8 +:100AF000AB4207D9284600F0F3FF013040F068818F +:100B00000435F3E7234B00251D70214BB8465D608B +:100B10003E46A7E7002E3FF45BAF0BF00B030B2B19 +:100B20007FF456AF1B4B0220187001F087F832207B +:100B300000F08CFFB0F10009FFF64AAF19F003078F +:100B40007FF446AF0E4A926809EB050393423FF6E5 +:100B50003FAFB9F5807F3FF73BAF124B0193B945EB +:100B600022DD4FF47A7000F071FF0390039A002A9F +:100B7000FFF62EAF019B039A03F8012B0137EDE737 +:100B8000002300209824002080230020390700083B +:100B90009C2400209423002004230020082300200C +:100BA0000C23002098230020C820FFF7B1FD074642 +:100BB00000283FF40DAF1F2D11D8C5F120024A4582 +:100BC0000AAB25F0030028BF4A4683490192184426 +:100BD00001F046F8019A8048FF2101F067F84FEADA +:100BE000A9037D490193C9F38702284601F066F8FD +:100BF000064600283FF46AAF019B05EB830531E709 +:100C00000220FFF785FD00283FF4E2AE00F0B0FFC0 +:100C100000283FF4DDAE0027B946704B9B68BB420D +:100C200018D91F2F11D80A9B01330ED027F00303C8 +:100C300012AA134453F8203C05934846042205A900 +:100C400001F0FEF804378146E7E7384600F048FF38 +:100C50000590F2E7CDF81490042105A800F014FFE8 +:100C600000E70023642104A8049300F003FF002898 +:100C70007FF4AEAE0220FFF74BFD00283FF4A8AE94 +:100C8000049800F05DFF0590E6E70023642104A8C6 +:100C9000049300F0EFFE00287FF49AAE0220FFF7E5 +:100CA00037FD00283FF494AE049800F059FFEAE7BE +:100CB0000220FFF72DFD00283FF48AAE00F068FF08 +:100CC000E1E70220FFF724FD00283FF481AE05A9EB +:100CD000142000F063FF04210746049004A800F0EC +:100CE000D3FE3946B9E7322000F0B0FE071EFFF60A +:100CF0006FAEBB077FF46CAE384A926807EB0A030D +:100D000093423FF665AE0220FFF702FD00283FF454 +:100D10005FAE27F003075744BA453FF4A3AE5046F1 +:100D200000F0DEFE0421059005A800F0ADFE0AF1FA +:100D3000040AF1E74FF47A70FFF7EAFC00283FF469 +:100D400047AE00F015FF002844D00A9B01330BD0BA +:100D500008220AA9002000F0B1FF00283AD0202282 +:100D6000FF210AA800F0A2FFFFF7DAFC1C4802F0FE +:100D7000F5FF13B0BDE8F08F002E3FF429AE0BF065 +:100D80000B030B2B7FF424AE0023642105A80593ED +:100D900000F070FE074600287FF41AAE0220FFF72D +:100DA000B7FC814600283FF413AEFFF7B9FC41F2CF +:100DB000883002F0D3FF059800F0F6FF4E4600F0B1 +:100DC000C1FF3C46B0E506464CE64FF0000AFFE5A1 +:100DD000B8467BE6374679E69823002000230020BA +:100DE000A0860100094A136849F2690099B21B0CF8 +:100DF00000FB01331360064B186844F2506182B265 +:100E0000000C01FB0200186080B270472023002014 +:100E10001C23002010B500211022044600F046FFDC +:100E2000034B03CB206061601868A06010BD00BF59 +:100E3000107AF01F2DE9F043224DBBB000F0FCFF0B +:100E4000AB6840F2ED22C31A934232D906AFA860D4 +:100E50002B4628220021384601F0FCFC05F10E004B +:100E600000F01CFF002604465FFA80F905F10E0829 +:100E7000F3B2F100994501F1280107D908EB060307 +:100E80000822384601F0E6FC0136F1E7082301228A +:100E9000CDE9023205340C4B0193A4B23023009308 +:100EA000CDE9047405A3D3E90023297B074801F0A9 +:100EB000E9FA3BB0BDE8F083AFF3008078F6339FEA +:100EC00093CACD8DE8340020F5340020BC340020D6 +:100ED00070B50D4614461E4601F06AFA50B9022E4E +:100EE00010D1012C0ED112A3D3E90023C5E90023B0 +:100EF000012007E0282C10D005D8012C09D0052CA2 +:100F00000FD0002070BD302CFBD10BA3D3E9002300 +:100F1000ECE70BA3D3E90023E8E70BA3D3E9002315 +:100F2000E4E70BA3D3E90023E0E700BFAFF30080C1 +:100F3000401DA12026812A0B78F6339F93CACD8DC0 +:100F40009E6AC421818A46EE26417272DF25D7B798 +:100F5000F017304A39059E5613B504462346084615 +:100F600020220021019001F075FC22790198032ACA +:100F7000234628BF032203F8042F2021022201F078 +:100F800069FC62790198072A234628BF072203F8E3 +:100F9000052F2221032201F05DFCA2790198072A86 +:100FA000234628BF072203F8062F2521032201F03C +:100FB00051FC019804F108031022282101F04AFC99 +:100FC000382002B010BD00002DE9F04FADF5017DD5 +:100FD00021AD0EAE40F2751280460F4622A80021C8 +:100FE000296000F063FE48220021304600F05EFEDA +:100FF00000F022FF564B4FF47A72B0FBF2F018600B +:1010000093E80700012386E807000DF15A003382B8 +:10101000FFF700FF40F20443338407AB18464D4905 +:1010200004F0EAFC182230642946304686F83C2059 +:10103000FFF792FF12AB044601460822284601F052 +:1010400009FC0822A1180DF14903284601F002FC11 +:101050000DF14A03082204F11001284601F0FAFBC1 +:1010600013AB202204F11801284601F0F3FB14AB66 +:10107000402204F13801284601F0ECFB16AB0822AF +:1010800004F17801284601F0E5FB0DF1590308222F +:1010900004F18001284601F0DDFB04F1880A0DF11E +:1010A0005A0904F5847B4B465146082228460AF12A +:1010B000080A01F0CFFBD34509F10109F3D11BABBD +:1010C00008225946284601F0C5FB04F588744FF004 +:1010D000000996F834304B450AD9B36B21464B448E +:1010E0000822284601F0B6FB083409F10109F0E7AF +:1010F0004FF0000996F83C304B4504EBC90108D984 +:10110000336C08224B44284601F0A4FB09F1010985 +:10111000F0E700230393BB7E0293073107F1190325 +:101120000193C1F3CF010123CDE904510093F97E6E +:1011300005A3D3E90023404601F0A4F90DF5017D94 +:10114000BDE8F08FAFF300809E6AC421818A46EE2D +:10115000A4240020085A0008014B1870704700BFF3 +:10116000B02400202DE9FF41344B1F7B27B1344BC5 +:101170000E221A81002630E0324A1068516802AB14 +:1011800003C30823304931480DEB030204F012FC7D +:10119000044630B92A4B2E480A221A8100F006FE76 +:1011A000E8E70169B1F5E02F06D9254B29480B2264 +:1011B0001A8100F0FBFDDDE7438B40F20442552B22 +:1011C00018BF93420CBF012600260AD01C490C20F0 +:1011D00008812148194600F0E9FD304604B0BDE819 +:1011E000F0811E4A024402F11003994204D2144BCA +:1011F0001B4810221A81DCE710398D1A3846134932 +:1012000000F01EFE2A46804604F11801384600F020 +:1012100017FEA368984502D1E36898420AD0084BAC +:101220000D221A810090D4E9021243460D4800F0C5 +:10123000BDFD9FE70C4800F0B9FDCEE7E834002083 +:10124000A4240020B55A0008DCFF060000000108B5 +:10125000245A0008305A0008425A00080800FFF7D4 +:10126000605A00087D5A0008A65A00082DE9F04F80 +:10127000ADB006AF80460C4601F09AF8054600284E +:101280005AD1237E022B1BD1E38A012B18D100F007 +:10129000D3FD0646FFF7A6FD03464FF4C870DFF8FE +:1012A000D092B3FBF0F206F5167602FB103316FA75 +:1012B00083F3C9F80030E37E33B9A84B00221A70DB +:1012C0009C37BD46BDE8F08FA38AEEB2013BB34226 +:1012D00005F101050BD93B1D1E44E90000960023D2 +:1012E000082201F0F801204601F078F9ECE707F157 +:1012F0001400FFF78FFD324607F11401381D04F08A +:1013000049FB0028D9D10F2E08D8944B1E70D9F86C +:101310000030A3F51673C9F80030D1E7FB1CF87054 +:101320000146009307220346204601F057F9F97859 +:10133000404601F035F8C3E7E38A282B26D010D8C1 +:10134000012B1ED0052BBBD1BFF34F8F8449854B9A +:10135000CA6802F4E0621343CB60BFF34F8F00BF53 +:10136000FDE7302BACD1637E7F4D01336A7BDBB26E +:101370009342E94603D1E27E2B7B9A4265D0CD466B +:101380009EE721464046FFF71FFE99E7A38A013BEF +:101390009BB2C92B94D8744D2E7B26BB05F10C0350 +:1013A0000093082233463146204601F017F9731C9A +:1013B000F2B2D9001E46A38A013B9A4205DA0E32E8 +:1013C0002A44009200230822EEE700230022C5E908 +:1013D00000230023AB6085F8D730C5F8D8302B7BCD +:1013E0000BB9E37E2B73002507F114093B1D08227E +:1013F00029464846C7E90155FD6001F02BFA3B7AC2 +:1014000005F1010AAB424FEACA0608D9FB68082277 +:101410002B443146484601F01DFA5546EFE7C6F326 +:10142000CF06E17ECDE9049600230393A37E0293C9 +:10143000193428230093019446A3D3E9002340469E +:1014400001F020F8FFF7F6FC3AE74FF0000807F14B +:101450001403A7F81480102200934146012320466C +:1014600001F0BCF8A68A023EB6B2F31C9B109B00AA +:101470000733DB08A9EBC3039D460DF1180A1FFAD9 +:1014800088F34FEAC801B34201F110010AD20AEB16 +:101490000803009308220023204601F09FF808F17A +:1014A0000108ECE795F8D70000F028FBD5F8D83014 +:1014B00004461BB995F8D70000F030FBD5F8D830BA +:1014C00033449C4204D295F8D700013000F026FB4B +:1014D0004FEA960B4FF000081FFA88F18B45D5E9CB +:1014E000003209D90AEB880103EB8800012200F0E1 +:1014F000E5FB08F10108EFE7F31842F10002C5E946 +:101500000032D5F8D83095F8D70006EB0308C5F8B7 +:10151000D88000F0F3FA804509D395F8D730D5F894 +:10152000D8000133001B85F8D730C5F8D800FF2E4E +:1015300008D800232B7300F01BFBFFF713FE08B144 +:10154000FFF72CF92B68094A9B0A0133138100230A +:10155000AB6014E726417272DF25D7B7B53400209F +:1015600000ED00E00400FA05E8340020A424002087 +:10157000B834002030B54FF00054244B22689A4212 +:1015800085B007D003F052F80446A8B900242046DD +:1015900005B030BD1E4B627D1A701E48237D03735B +:1015A0001D49C9220E3000F05BFB2046E0220021DD +:1015B00000F07CFB0124EAE7184A194D136C43F054 +:1015C00000731364AA6D174B9A42DFD12B6E013B57 +:1015D0007E2BDBD8144A07CA01AB83E80700184604 +:1015E000032100F043FC6B6D83424FF00003CDD12B +:1015F0002A6D8A4201BFAB65054B2A6E1A7003BF84 +:101600000A4BEA6D1A601C46C1E700BF9AAD44C59B +:10161000B0240020E83400201600002000380240EA +:10162000006600405041A0B05866004018230020DA +:101630002DE9F0434B4C022385B0637100230293E4 +:10164000494B1F68B7F57A7F12D3484B4848B0FB27 +:10165000F7F09F428CBF0A2311235E1EB0FBF3F507 +:1016600003FB1502F1B2002A3ED0022E3346F4D815 +:101670009DF80B303F4940485A1E9DF80A30013B07 +:101680001B0443EA0253BDF80820013A13434B60A0 +:1016900001F098FD00230193384B394900933948F4 +:1016A000394B4FF4805200F055FE384B197811B188 +:1016B000344800F075FE00F0BFFB0546FFF792FBD3 +:1016C0004FF4C873B0FBF3F202FB130305F5167079 +:1016D00010FA83F02E4B186002F09EFF08B10F2322 +:1016E000238105B0BDE8F0836B1EB3F5806FBFD2D8 +:1016F000C1EBC10C0CF103034FEAE308C3F3C703CA +:10170000A1EB030E08F101094FF47A705FFA8EF62F +:1017100008FB000059FA8EFEB0FBFEF0B0F5617FC9 +:1017200008D90CF1FF33C3F3C703C91ACEB2591E4F +:101730000F2915D8721E072A8CBF00220122991981 +:1017400001FB05500A49B1FBF0F18F4290D1002A0C +:101750008ED0ADF808508DF80A308DF80B6087E711 +:101760001346ECE7A4240020182300203F420F007A +:1017700080F937031023002000360020D10E000826 +:10178000B4240020BC3400206D120008B0240020D6 +:10179000B83400202DE9F04F91A7D7E900670FF288 +:1017A0004829D9E90089874D93B0DFF844B2864CC7 +:1017B000284600F0CBFE0DF1300A079070B31022DE +:1017C0000021504600F072FA079B197B4FF000028F +:1017D00061F303028DF83020586899680EAA03C29D +:1017E0001B680D9A63F31C029DF830300D9243F094 +:1017F00020038DF83030002352461946584601F038 +:10180000F1FC079028B9284600F0A4FE079B23703E +:10181000CEE72378072B3CD8013323701822002110 +:10182000504600F043FADFF8C8B1684C002319466F +:101830005246584601F0FEFC014670BB102208A833 +:1018400000F034FA636983F04003636100F0F6FA54 +:101850000B4612A9024611E903000DF1240C8CE895 +:1018600003009DF83410C1F3030089064CBF0E99A4 +:10187000BDF838C08DF82C0046BFC1F31C0C4CF0ED +:101880000041CCF30A010891284608A901F02AF882 +:10189000CCE7284600F05EFEC0E7284600F088FD51 +:1018A0000446002848D1DFF84CB100F0C5FADBF857 +:1018B0000030984240D300F0BFFA0790FFF792FA49 +:1018C000079A8DF8204003464FF4C87002F516724F +:1018D000B3FBF0F101FB103312FA83F3CBF80030C5 +:1018E000DFF814B19BF8001011B901238DF82030F6 +:1018F00050460791FFF78EFA0799C1F11004E4B240 +:10190000062C28BF0624224651440DF1210000F088 +:10191000A7F908AB03931823029301342C4B0193CE +:10192000E4B20123009304943B463246284600F07B +:1019300041FD00238BF8003000F07EFA254A264C4A +:101940001368C31AB3F57A7F31D3106000F076FACA +:1019500002460B46284600F007FE284600F028FD08 +:1019600028B3237BDFF894B0002B14BF032302239A +:101970008BF8053000F060FA4FF47A735146B0FBF3 +:10198000F3F0CBF800005846FFF7E6FA18230730CB +:101990000293124B0193C0F3CF0040F25513CDE9EF +:1019A00003A0009342464B46284600F003FD237BEC +:1019B0002BB1FFF73FFA237B002B7FF4F6AE13B079 +:1019C000BDE8F08FBC340020CD350020000002407F +:1019D000B4340020C8350020E8340020CC35002085 +:1019E000401DA12026812A0BF1C6A7C1D068080F8F +:1019F00000360020B8340020B5340020A424002094 +:101A000070B50F4B1B780133DBB2012B0C4611D89C +:101A10000C4D29684FF47A730E6AA2FB033201461B +:101A200022462846B047844204D1074B00221A7050 +:101A3000012070BD4FF4FA7002F090F90020F8E731 +:101A400024230020E8370020FC35002007B50023C0 +:101A5000024601210DF107008DF80730FFF7D0FF96 +:101A600020B19DF8070003B05DF804FB4FF0FF3094 +:101A7000F9E700000A4608B50421FFF7C1FF80F02E +:101A80000100C0B2404208BD30B4054C2368DD6996 +:101A9000044B0A46AC460146204630BC604700BFB6 +:101AA000E8370020A086010070B502F0F7FB094E70 +:101AB000094D3080002428683388834208D902F019 +:101AC000E7FB2B6804440133B4F5803F2B60F2D36D +:101AD00070BD00BFFE350020D035002002F0A2BC52 +:101AE00000F1006000F580300068704700F1006090 +:101AF000920000F5803002F01FBC0000054B1A6810 +:101B0000054B1B889B1A834202D9104402F0C0BBCC +:101B100000207047D0350020FE35002038B5074D35 +:101B200004462868204402F0BBFB28B928682044FA +:101B3000BDE8384002F0CCBB38BD00BFD035002036 +:101B400010F003030AD1B0F5047F05D200F1005074 +:101B5000A0F57920D0F80038184670470023FBE73D +:101B600000F10050A0F57920D0F8100A704700006D +:101B7000064991F8243033B10023086A81F82430F3 +:101B80000822FFF7B3BF0120704700BFD435002003 +:101B9000014B1868704700BF002004E0F0B5204BEF +:101BA000024618681F4B1F885D6893F90840C0F310 +:101BB0000B06BE424FEA104022D09F89BE4221D080 +:101BC0001F8BBE4206D102240C2505FB04335D6841 +:101BD00093F90840B0F5805F16D041F201039842B6 +:101BE00008BF5A24013A0A44013D0B4693420DD2E4 +:101BF00015F9016F581C5EB100F8016C0346F5E75A +:101C00000024E1E70124DFE74124EBE7184605E083 +:101C10002C2590421D7001D2981C5C70401AF0BDBA +:101C2000002004E028230020022802BF024B4FF4CA +:101C300080029A61704700BF00000240022802BF84 +:101C4000014B40229A61704700000240022801BF08 +:101C5000024A536983F04003536170470000024019 +:101C600010B50023934203D0CC5CC4540133F9E790 +:101C700010BD000010B5013810F9013F3BB191F9DA +:101C800000409C4203D11AB10131013AF4E71AB184 +:101C900091F90020981A10BD1046FCE70346024651 +:101CA000D01A12F9011B0029FAD1704702440346E9 +:101CB000934202D003F8011BFAE770472DE9F8437D +:101CC0001F4D144695F824200746884652BBDFF87E +:101CD00070909CB395F824302BB92022FF21484600 +:101CE0002F62FFF7E3FF95F82400C0F10802A2423B +:101CF00028BF2246D6B24146920005EB8000FFF78E +:101D0000AFFF95F82430A41B1E44F6B2082E1744EA +:101D10009044E4B285F82460DBD1FFF729FF002866 +:101D2000D7D108E02B6A03EB82038342CFD0FFF7C1 +:101D30001FFF0028CBD10020BDE8F8830120FBE77E +:101D4000D4350020024B1A78024B1A70704700BF3E +:101D5000FC3500202423002010B50F4C0F4801F063 +:101D60000BFB21460D4801F033FB24680C48E26E62 +:101D7000D2F8043843F00203C2F8043801F0EEFF51 +:101D80000849204601F02CFCE26ED2F8043823F01A +:101D90000203C2F8043810BDB05B0008E837002029 +:101DA00040420F00B85B0008704700000FB40020ED +:101DB00004B0704700B59BB0EFF309816822684614 +:101DC000FFF74EFFEFF30583044B9A6BDA6A9A6ACA +:101DD0009A6A9A6A9A6A9A6A9B6AFEE700ED00E03C +:101DE00000B59BB0EFF3098168226846FFF738FF22 +:101DF000EFF30583044B9A6B9A6A9A6A9A6A9A6A15 +:101E00009A6A9B6AFEE700BF00ED00E000B59BB058 +:101E1000EFF3098168226846FFF722FFEFF305839D +:101E2000034B5A6B9A6A9A6A9A6A9A6A9B6AFEE7A5 +:101E300000ED00E0FEE7000002F02EBB02F006BB62 +:101E400030B5094D0A4491420DD011F8013B58407C +:101E5000082340F30004013B2C4013F0FF0384EA05 +:101E60005000F6D1EFE730BD2083B8EDF7B54FF065 +:101E7000FF33DFF854C0DFF854E000EB81011A466D +:101E800088421CD050F8044B019401AF042417F889 +:101E9000015B82EA05620825DB18164605F1FF356D +:101EA0005241002EBCBF83EA0C0382EA0E0215F0F9 +:101EB000FF05F1D1013C14F0FF04E8D1E0E7D8437D +:101EC000D14303B0F0BD00BF9336EAA9EBE1F04285 +:101ED0002DE9F041C56915B9C161BDE8F0814B68D4 +:101EE00023F06047C3F38A464FEAD37EC3F380787A +:101EF00016EA230638BF3E46AC462B465A68BEEB70 +:101F0000D27F22F060440AD0002A18DAA40CB4422E +:101F100017D19D420FD10D60DEE71346EEE7A742D1 +:101F200007D102F08044C2F3807242450BD054B115 +:101F3000EFE708D2EDE7CCF800100B60CDE7B44234 +:101F400001D0B442E5D81A689C46002AE5D1196050 +:101F5000C3E700002DE9F047089D01F007044FEAB0 +:101F6000D508224405F0070500EBD1004FF47F4966 +:101F7000944201D1BDE8F08704F0070705F0070A95 +:101F800057453E4638BF5646C6F10806111B8E42DD +:101F900028BF0E46E10808EBD50E415C13F80EC0D1 +:101FA000B94029FA06F721FA0AF1FFB28CEA0101D9 +:101FB00047FA0AF739408CEA010C03F80EC03444A2 +:101FC0003544D5E780EA0120082341F2210201B21D +:101FD0004000002980B203F1FF33B8BF504013F036 +:101FE000FF03F4D17047000038B50C468D18A542A8 +:101FF00000D138BD14F8011BFFF7E4FFF7E700003C +:1020000002684AB113680360C388018901339BB237 +:102010009942C38038BF03811046704770B588B0BD +:10202000202204460D4668460021FFF73FFE204669 +:102030000495FFF7E5FF024658B16B46054608AE2A +:102040001C4603CCB44228606960234605F10805AC +:10205000F6D1104608B070BD082817D909280CD051 +:102060000A280CD00B280CD00C280CD00D280CD032 +:102070000E2814BF4020302070470C2070471020DD +:1020800070471420704718207047202070470000C8 +:10209000082817D90C280CD910280CD914280CD9C9 +:1020A00018280CD920280CD930288CBF0F200E20DE +:1020B0007047092070470A2070470B2070470C209A +:1020C00070470D207047000010B54B6823B9CA8ACD +:1020D00063F30902CA8210BDC4681A681C60C36039 +:1020E000438A013B43824A60EFE700002DE9F84F45 +:1020F0001D46CB8A0F46C3F3090106298146924645 +:102100000B4630D00020AAB207F119049EB2052E6A +:102110001FFA80F80FD8904503F1010306D3FB8A1C +:102120000A4462F30903FB8201201AE01AF80060F6 +:10213000E6540130EAE79045F1D2A1F1060B1C23E9 +:102140007C68BBFBF3F203FB12BB1FFA8BF6002C7F +:1021500045D14846FFF754FF044638B978606FF020 +:102160000200BDE8F88F4FF00008E6E700260660A1 +:102170007860ADB24FF0000B454510D90AEB08036B +:10218000221D13F8011B9155B1B208F101081B295A +:102190001FFA88F82BD0454506F10106F1D8FB8AD5 +:1021A000C3F30902154465F30903BCE7013292B297 +:1021B0001C462368002BF9D1AB1F0B441C21B3FB39 +:1021C000F1F301339BB29A42D3D2BBF1000FD0D1CD +:1021D0004846FFF715FF20B9C4F800B0BFE7012259 +:1021E000E7E7C0F800B05E4620600446C1E7454519 +:1021F000D5D94846FFF704FF08B92060AFE7C0F81B +:1022000000B0002620600446B6E700002DE9F04F3C +:102210002DED028B83B0CDE90013BDF83C5007468D +:102220009146002A00F092802DB10E9B002B00F009 +:102230008D80072D32D807F10C00FFF7E1FE044630 +:1022400038B96FF00204204603B0BDEC028BBDE844 +:10225000F08F14220021FFF729FD0E992A4604F180 +:102260000800FFF7FDFC681CC0B2FFF711FFFFF785 +:10227000F3FE207499F80030013814FA80F003F06E +:102280001F0363F03F030372009B43F00041616052 +:1022900038462146FFF71CFE0124D4E700F10C0369 +:1022A0004FF0000808EE103A4FF0800A46464446C8 +:1022B00018EE100AFFF7A4FE83460028C1D01422AE +:1022C0000021FFF7F3FCC6BB019BABF808300220EE +:1022D0000E9B00F1080299195BFA82F20130C0B23C +:1022E000082801D0AE422AD3FFF7D2FEFFF7B4FE92 +:1022F00099F80020009B411E02F01F0242EA48129A +:10230000AE4208BF4FF0400A5BFA81F14AEA020A86 +:1023100043F0004281F808A08BF81000CBF80420AD +:1023200059463846FFF7D4FD0134AE4224B288F056 +:1023300001084FF0000ABBD185E70020C8E711F87B +:1023400001CB02F801CB0136B6B2C7E76FF001044A +:1023500079E70000F8B515460E462822002104460C +:102360001F46FFF7A3FC069B6360B5F5001F079BA4 +:10237000A76034BF6A094FF6FF72236204F10C00B4 +:1023800097B200239A4205D8002303602782638214 +:10239000A382F8BD0660013330462036F2E7000024 +:1023A00003781BB94BB2002BC8BF01707047000007 +:1023B000007870472DE9F74FDDF83C90BDF83050BC +:1023C0000D9E9DF83840BDF84070804692469B4671 +:1023D000B9F1000F01D1002F51D11F2C4FD898F81F +:1023E0000000B0B9072F47D835F0030347D13A466C +:1023F00049464FF6FF70FFF7F7FD20F001002D0270 +:10240000400445EA0464400C44EA40244FF6FF735C +:1024100021E040EA0520072F40EA0464F6D90025B0 +:102420004FF6FF73C5F12000A5F120022AFA05F14D +:102430000BFA00F001432BFA02F211431846C9B21D +:10244000FFF7C0FD0835402D0346EBD13A4649461B +:10245000FFF7CAFD0346CDE90097324621464046C4 +:10246000FFF7D4FE33780133DBB21F2B88BF002384 +:10247000337003B0BDE8F08F6FF00300F9E76FF041 +:102480000100F6E72DE9F04F85B09246DDF848806F +:102490000F9D9DF840209DF84490BDF84C70064675 +:1024A0009B46B8F1000F01D1002F48D11F2A46D812 +:1024B0003378002B46D00C0244EA02649DF83810B1 +:1024C00044EAC93444EA01441C43072F44F0800421 +:1024D00032D900234FF6FF72C3F1200CA3F1200084 +:1024E0002AFA03F10BFA0CFC41EA0C012BFA00F07A +:1024F0000143C9B210460393FFF764FD039B083301 +:10250000402B0246E8D13A464146FFF76DFD0346AF +:10251000CDE900872A4621463046FFF777FEB9F11C +:10252000010F06D12B780133DBB21F2B88BF0023AC +:102530002B7005B0BDE8F08F4FF6FF73E8E76FF042 +:102540000100F6E76FF00300F3E70000C06900B197 +:1025500004307047C3691A68C261C2681A60C360F8 +:10256000438A013B438270472DE9F041D0F818803F +:10257000194E14461D464146002709B9BDE8F081B1 +:10258000D1E90223A21A65EB0303964277EB03031A +:102590001ED283698B420DD1FFF796FD83691B68BC +:1025A0008361C3680B60438AC1608169013B4382D8 +:1025B0008846E2E7FFF788FD0B68C8F80030C3687B +:1025C0000B60438AC160013B4382D8F80010D4E716 +:1025D00088460968D1E700BF80841E002DE9F04FCE +:1025E0008BB00D46DDF8509014469B46804600287F +:1025F00000F01981B9F1000F00F01581531E3F2B37 +:1026000000F21181012A03D1BBF1000F40F00B81D0 +:102610000023CDE90833B8F81430B5EBC30F4FEA07 +:10262000C30703D300200BB0BDE8F08F2B199F42E6 +:10263000D8F80C303ABF7F1BFFB227461BB9D8F839 +:102640001030002B7AD02F2D4ED8C5F13006B7426E +:102650004FF000032CBFF6B23E4600932946D8F84F +:10266000080008AB3246FFF775FCA7EB060A3544B5 +:102670005FFA8AFAB8F8143003F10053063BDB0026 +:102680000493D8F80C3003933021039B13B1BAF1B3 +:10269000000F2CD1D8F8100040B1BAF1000F05D0CE +:1026A000009608AB5246691AFFF754FC38B2002F67 +:1026B000B8D066070AD00AAB03EBD401624211F826 +:1026C000083C02F00702134101F8083C082C3CD9F1 +:1026D000102C40F2B580202C40F2B780BBF1000FE7 +:1026E00000F09C80082334E0BA460026C2E7049B31 +:1026F000E02B28BFE02306930B44AB42059314D98B +:102700005A1B03980096924534BF5246D2B2691ABA +:1027100008AB04300792FFF71DFC079A1644AAEB9A +:10272000020A1544F6B25FFA8AFA049B069A0599E2 +:102730009B1A0493039B1B680393A6E70093D8F8A6 +:10274000080008AB3A462946AEE7BBF1000F13D0AC +:102750000123B4EBC30F6CD0082C12D89DF82030A5 +:10276000621E23FA02F2D50706D54FF0FF3202FAB5 +:1027700004F423438DF820309DF8203089F8003090 +:1027800051E7102C12D8BDF82030621E23FA02F255 +:10279000D10706D54FF0FF3202FA04F42343ADF817 +:1027A0002030BDF82030A9F800303CE7202C0FD8AD +:1027B0000899631E21FA03F3DA0705D54FF0FF32BB +:1027C00002FA04F40C430894089BC9F800302AE785 +:1027D000402C2BD0DDE90865611EC4F12102A4F173 +:1027E000210326FA01F105FA02F225FA03F3114357 +:1027F0001943CB0712D50122A4F12003C4F1200113 +:1028000002FA03F322FA01F1A240524243EA010321 +:1028100063EB430332432B43CDE90823DDE908236F +:10282000C9E90023FFE66FF00100FCE66FF0080045 +:10283000F9E6082CA0D9102CB3D9202CEED8C3E788 +:10284000BBF1000FADD0022383E7BBF1000FBBD07B +:1028500004237EE730B5012A144638BF0124402CFA +:1028600085B028BF40240025012ACDE9025518D89B +:102870001B788DF8083063070AD004AB03EBD4054E +:10288000624215F8083C02F00702934005F8083C44 +:10289000009103462246002102A8FFF75BFB05B02A +:1028A00030BD082AE4D9102A03D81B88ADF80830B7 +:1028B000E1E7202A8DBFD3E900231B680293CDE90D +:1028C0000223D8E710B5CB681BB98B600B618B82F4 +:1028D00010BDC4681A681C60C360438A013B438210 +:1028E000CA60F0E72DE9F04FD1F8008093B018F0FE +:1028F000800FCDE90323C8F3C01219BFC8F3C03B52 +:10290000C8F306264FF0020B1646B8F1000F044636 +:102910000D4680F2D18118F0C043059340F0CC8180 +:102920000B7B002B00F0C881BBF1020F03D00178B4 +:10293000B14240F0C48108F07F0106916AB3C8F348 +:10294000074A2B44069A93F80390760646EA0B460C +:1029500046EA82465FEAD91346EA0A06079300F080 +:10296000908000220023CDE90A23069B009367682C +:102970005B4652460AA92046B84700287ED0A76980 +:102980009FB9314604F10C00FFF748FB0746E0B958 +:102990006FF0020013B0BDE8F08FC8F30F2A18F0F3 +:1029A0007F0F08BF0AF0030ACBE73B699E420DD0B8 +:1029B0003F68002FF9D1314604F10C00FFF72EFBE0 +:1029C00007460028E4D0A3693B60A761DDE90A233C +:1029D00000264FF6FF70C6F1200E22FA06F103FA28 +:1029E0000EFEA6F1200C23FA0CFC41EA0E0141EA8E +:1029F0000C01C9B2083609920893FFF7E3FA402E9A +:102A0000DDE90832E7D1B882FB7D09F01F06C3F388 +:102A100084039B1BD7E9022198B2002BBCBF00F1B5 +:102A200020031BB252EA0100C8F304680FD00398D8 +:102A3000821A049860EB0101A74890424FF000020F +:102A40008A4104D3079A002A5BD0012B23DDFA7D4B +:102A50004FEA890302F0030203F07C031343FB7582 +:102A600039462046FFF730FB079BA3B9FB7DC3F334 +:102A70008402013262F38603FB7504E06FF00B0001 +:102A800088E7A76917B96FF00C0083E73B699E429E +:102A9000BAD03F68F6E719F0400F32D0039BBB6015 +:102AA000049BFB60142200210DA8FFF7FFF8039B95 +:102AB0000A93049B0B932B1D0C932B7BADF83EA02C +:102AC000013BDBB2ADF83C30069B8DF8433094F807 +:102AD00024308DF840B083F001038DF844308DF838 +:102AE0004160A3688DF842800AA920469847FB7D83 +:102AF000C3F38403013303F01F039B02FB82002016 +:102B000048E7FB7DC9F34012B2EBD31F40F0DA80F7 +:102B1000C3F38403B34240F0D88007992B7B4FEA7C +:102B20009912002934D0D20741D4032B40F2D0802F +:102B3000039BBB60049BFB602B7BAE1D033BDBB2A6 +:102B40003246394604F10C00FFF7D0FA00280DDABE +:102B500020463946FFF7B8FAFB7DC3F384030133FF +:102B600003F01F039B02FB82032013E7AB883B8328 +:102B70002A7B033AB88AD2B23146FFF735FAFB7D99 +:102B8000B882DA43C2F3C01262F3C713FB75B6E72B +:102B90006AB92E1D013BDBB23246394604F10C0006 +:102BA000FFF7A4FA0028D3DB2A7B013AE2E7F98A8F +:102BB000C1F30901013B0529DAB259D8281D0023C8 +:102BC00007F11A0C9A4208D910F801EB0CF801E051 +:102BD000013101330629DBB2F4D103990A9104993A +:102BE0000B91934207F11A010C9138BF04337968B5 +:102BF0000D9134BF55FA83F300230E93FB8AADF891 +:102C00003EA0C3F309031A44069B8DF8433094F8A1 +:102C10002430ADF83C2083F001038DF844300023CC +:102C20008DF840B08DF841608DF842807B602A7B42 +:102C3000B88A013A291DFFF7D7F93B8BB882834246 +:102C400003D1A3680AA92046984720460AA9FFF79E +:102C500039FEFB7DB88AC3F38403013303F01F03FD +:102C60009B02FB823B8B984214BF1120002091E60F +:102C70007B68002BB1D0062001E01C306346D3F8FE +:102C800000C0BCF1000FF8D1091A081D05F1040CB1 +:102C900000EB030905989DF8143001EB000EBEF11E +:102CA0001B0F9AD89A4298D91CF8013B09F8013BAE +:102CB000059B01330593EDE76FF009006AE66FF0BD +:102CC0000A0067E66FF00D0064E66FF00E0061E643 +:102CD0006FF00F005EE600BF80841E00404BF0B531 +:102CE0001C6C404E44F000741C641D6E45F0007571 +:102CF0001D661B6E3C4B9B6AD3F80052354045F075 +:102D00000105C3F80052D3F80042344044EA0020E1 +:102D100040F00100C3F80002002952D00020C3F89F +:102D20001C020546C3F80402C3F80C02C3F81402DF +:102D300003EBC00401301C28C4F84052C4F84452CC +:102D4000F6D100254FF0010C96781488F70748BF9C +:102D5000D3F804720CFA04F044BF0743C3F80472BA +:102D6000B70742BFD3F80C720743C3F80C7276075B +:102D700042BFD3F814620643C3F8146203EBC404E1 +:102D80005668C4F840629668C4F84462D3F81C429E +:102D900001352043A942C3F81C0202F10C02D3D131 +:102DA000D3F8002222F00102C3F800220C4B1A6C67 +:102DB00022F000721A641A6E22F000721A661B6EFC +:102DC000F0BD0122C3F84012C3F84412C3F8041244 +:102DD000C3F81412C3F80C22C3F81C22E0E700BFAA +:102DE000003802400000FFFF00360020184A916AB8 +:102DF00008B58B688B6013F0010104D013F00C0F41 +:102E000018BF4FF48031D80506D513F4406F14BFB6 +:102E100041F4003141F00201D80306D513F4402FEC +:102E200014BF41F4802141F00401D3690BB108487B +:102E30009847202383F311880648002100F0B6FF4D +:102E4000002383F31188BDE8084001F031BC00BFC6 +:102E5000003600200836002038B5124CA36ADD6821 +:102E6000AA0712D05A6922F002025A61A36913B16B +:102E7000012120469847202383F311880A48002126 +:102E800000F094FF002383F31188EB0606D5A36AB4 +:102E90001021D960236A0BB102489847BDE8384039 +:102EA00001F006BC003600201036002038B5124C68 +:102EB000A36A1D69AA0712D05A6922F010025A614A +:102EC000A36913B1022120469847202383F3118878 +:102ED0000A48002100F06AFF002383F31188EB0603 +:102EE00006D5A36A10211961236A0BB102489847DD +:102EF000BDE8384001F0DCBB003600201036002071 +:102F000038B50F4CA36A5D685D602A070AD50422B4 +:102F100022701A6822F002021A60636A13B100215B +:102F2000204698476B0706D5A36A9969236A13B1AF +:102F3000034809049847BDE8384001F0B9BB00BF19 +:102F40000036002010B50E4C204600F029F90D4B3C +:102F5000A3620B21132000F00BF90B21142000F0C9 +:102F600007F90B21152000F003F90B21162000F0C2 +:102F7000FFF80022BDE8104011461C20FFF7AEBE4E +:102F80000036002000640040114B984210B5044602 +:102F900009D1104B1A6C42F000721A641A6E42F09A +:102FA00000721A661B6EA36A01221A60A36A5A682D +:102FB000D20707D5626851681268D9611A60064A5B +:102FC0005A6110BD0121082000F0DCFDEEE700BFD2 +:102FD00000360020003802405B87010003291AD820 +:102FE000DFE801F0020A0F14836A9B6813F0E05FC8 +:102FF00014BF012000207047836A9868C0F3806086 +:103000007047836A9868C0F3C0607047836A9868A5 +:10301000C0F30070704700207047000010B503290E +:1030200025D8DFE801F00225292D836A9968C1F3CC +:103030000161183103EB0113107884064CBF54680A +:103040009488C0F300114FEA410148BF41EAC4012E +:1030500000F00F004CBF41F0040141EA44515860B8 +:1030600041F001019068D2689860DA60196010BD83 +:10307000836A03F5C073DFE7836A03F5C873DBE790 +:10308000836A03F5D073D7E701290AD002290FD04C +:1030900081B9836ADA68920701D1186903E00120D7 +:1030A0007047836AD86810F0030018BF012070478A +:1030B000836AF2E70020704710B539B9836AD9688E +:1030C00089071BD11B699C0704D110BD012915D0AC +:1030D0000229FAD1816AD1F8C031D1F8C441D1F8BE +:1030E000C8011061D1F8CC01506120200861086945 +:1030F000800717D1486940F0100012E0816AD1F8CA +:10310000B031D1F8B441D1F8B8011061D1F8BC01A7 +:1031100050612020C860C868800703D1486940F02A +:1031200002004861C3F34000C3F38001000140EA9C +:103130004111107920F030000143117189064BBF15 +:1031400091681189DB085B0D4CBF63F31C0163F3CD +:103150000A01137948BF916064F3030313714FEAC6 +:1031600014234FEA144458BF118113705480ACE704 +:1031700000F1604303F561430901C9B283F800130C +:10318000012200F01F039A4043099B0003F16043B2 +:1031900003F56143C3F880211A607047FFF7D2BE80 +:1031A000012300F10802C0E90222037000F11002BD +:1031B0000023C0E90422C0E90633C0E908334360B4 +:1031C0007047000010B52023044683F311880223C2 +:1031D00003704160FFF7D8FE04232370002383F3BC +:1031E000118810BD2DE9F0411F4604460D461646D4 +:1031F000202383F3118800F108082378052B0DD0D4 +:1032000029462046FFF7EAFE40B1204632462946CD +:10321000FFF704FF002080F3118808E0394640469C +:1032200000F0A8FD0028E8D0002383F31188BDE852 +:10323000F08100002DE9F0411F4604460D46164678 +:10324000202383F3118800F110082378052B0DD07B +:1032500029462046FFF718FF40B12046324629464E +:10326000FFF72AFF002080F3118808E03946404626 +:1032700000F080FD0028E8D0002383F31188BDE82A +:10328000F0810000026843681143016003B11847F0 +:103290007047000013B5446BD4F894341A68117861 +:1032A000042915D1217C022912D11979128901230F +:1032B0008B4013420CD101A904F14C0002F006F836 +:1032C000D4F89444019B21790246206800F0D4F997 +:1032D00002B010BD143001F089BF00004FF0FF3381 +:1032E000143001F083BF00004C3002F05BB80000E6 +:1032F0004FF0FF334C3002F055B80000143001F0AD +:1033000057BF00004FF0FF31143001F051BF0000F3 +:103310004C3002F027B800004FF0FF324C3002F082 +:1033200021B800000020704710B5D0F894341A6816 +:1033300011780429044617D1017C022914D1597946 +:10334000528901238B4013420ED1143001F0EAFE62 +:10335000024648B1D4F894444FF4807361792068F0 +:10336000BDE8104000F076B910BD0000406BFFF7DB +:10337000DBBF0000704700007FB5124B03600023E5 +:103380004360C0E90233012502260F4B0574044651 +:103390000290019300F18402294600964FF4807355 +:1033A000143001F09BFE094B0294CDE9006304F553 +:1033B00023724FF48073294604F14C0001F062FF40 +:1033C00004B070BDEC5A00086D3300089532000857 +:1033D0000B68202282F311880A7903EB82021062C3 +:1033E0004A790D3243F822008A7912B103EB820345 +:1033F000186202230374C0F89414002383F3118825 +:103400007047000038B5037F044613B190F854307C +:10341000ABB9201D01250221FFF734FF04F1140090 +:1034200025776FF0010100F0C1FC84F8545004F1DD +:103430004C006FF00101BDE8384000F0B7BC38BD6A +:1034400010B5012104460430FFF71CFF0023237749 +:1034500084F8543010BD000038B5044600251430FF +:1034600001F054FE04F14C00257701F023FF201DEC +:1034700084F854500121FFF705FF2046BDE838408D +:10348000FFF752BF90F85C3003F06003202B07D1A8 +:1034900090F85D20212A4FF0000303D81F2A06D898 +:1034A00000207047222AFBD1C0E9143303E0034A0D +:1034B0000265072242658365012070474C23002086 +:1034C00037B5D0F894341A681178042904461AD113 +:1034D000017C022917D11979128901238B401342EB +:1034E00011D100F14C05284601F0A4FF58B101A903 +:1034F000284601F0EBFED4F89444019B2179024662 +:10350000206800F0B9F803B030BD0000F0B500EB62 +:10351000810385B01E6A04460D46FEB1202383F365 +:10352000118804EB8507301D0821FFF7ABFEFB680F +:103530005B691B6806F14C001BB1019001F0D4FEE1 +:10354000019803A901F0C2FE024648B1039B294637 +:10355000204600F091F8002383F3118805B0F0BDF8 +:10356000FB685A691268002AF5D01B8A013B134098 +:10357000F1D104F15C02EAE70D3138B550F8214091 +:10358000DCB1202383F31188D4F894241368527992 +:1035900003EB8203DB689B695D6845B10421601819 +:1035A000FFF770FE294604F1140001F0C5FD204626 +:1035B000FFF7BAFE002383F3118838BD704700007F +:1035C00001F072B910B501230446282200F8243B0B +:1035D0000021FEF76BFB0023C4E9013310BD00009E +:1035E00038B50446202383F311880025C0E903552C +:1035F000C0E90555C0E90755416001F065F90223AE +:10360000237085F3118838BD70B500EB8103054642 +:103610005069DA600E46144618B110220021FEF7F8 +:1036200045FBA06918B110220021FEF73FFB31468F +:103630002846BDE8704001F011BA0000826802F02F +:10364000011282600022C0E90422C0E9062202625F +:1036500001F090BAF0B400EB81044789E4680125D9 +:10366000A4698D403D43458123600023A2606360CF +:10367000F0BC01F0ABBA0000F0B400EB81040789A4 +:10368000E468012564698D403D4305812360002382 +:10369000A2606360F0BC01F025BB000070B502239E +:1036A000002504460370C0E90255C0E90455C0E98D +:1036B00006554566056280F84C5001F06BF9636869 +:1036C0001B6823B129462046BDE87040184770BDED +:1036D000037880F868300523037043681B6810B5D1 +:1036E00004460BB1042198470023A36010BD0000DD +:1036F00090F86820436802701B680BB105211847D9 +:103700007047000070B590F84C30044613B10023A8 +:1037100080F84C3004F15C02204601F04DFA6368F9 +:103720009B68B3B994F85C3013F0600535D0002184 +:10373000204601F0B5FC0021204601F0A7FC63689B +:103740001B6813B1062120469847062384F84C30A5 +:1037500070BD204698470028E4D0B4F86230626D0E +:103760009A4288BF636594F95C30656D002B4FF019 +:10377000200380F20381002D00F0F280092284F8FA +:103780004C2083F311880021D4E914232046FFF74D +:1037900073FF002383F31188DAE794F85D2003F0C8 +:1037A0007F0343EA022340F20232934200F0C580D5 +:1037B00021D8B3F5807F48D00DD8012B3FD0022B04 +:1037C00000F09380002BB2D104F164022265022242 +:1037D0006265A365C1E7B3F5817F00F09B80B3F517 +:1037E000407FA4D194F85E30012BA0D1B4F86430AE +:1037F00043F0020332E0B3F5006F4DD017D8B3F5B4 +:10380000A06F31D0A3F5C063012B90D8636894F802 +:103810005E205E6894F85F10B4F860302046B047D0 +:10382000002884D043682365036863651AE0B3F514 +:10383000106F36D040F6024293427FF478AF5C4B73 +:103840002365022363650023C3E794F85E30012BF0 +:103850007FF46DAFB4F8643023F00203C4E914556B +:10386000A4F86430A56578E7B4F85C30B3F5A06FD0 +:103870000ED194F85E3084F86630204601F0E2F80C +:1038800063681B6813B10121204698470323237006 +:103890000023C4E914339CE704F167032365012383 +:1038A000C3E72378042B10D1202383F3118820460B +:1038B000FFF7C4FE85F311880321636884F867501D +:1038C00021701B680BB12046984794F85E30002B9E +:1038D000DED084F867300423237063681B68002BF4 +:1038E000D6D0022120469847D2E794F860301D06D2 +:1038F00003F00F0120460AD501F050F9012804D049 +:1039000002287FF414AF2B4B9AE72B4B98E701F07A +:1039100037F9F3E794F85E30002B7FF408AF94F8A2 +:10392000603013F00F01B3D01A06204602D501F023 +:10393000CBFBADE701F0BEFBAAE794F85E30002BAD +:103940007FF4F5AE94F8603013F00F01A0D01B06A1 +:10395000204602D501F0A4FB9AE701F097FB97E718 +:10396000142284F84C2083F311882B462A462946DA +:103970002046FFF76FFE85F31188E9E65DB1152259 +:1039800084F84C2083F311880021D4E914232046C5 +:10399000FFF760FEFDE60B2284F84C2083F31188CC +:1039A0002B462A4629462046FFF766FEE3E700BF7E +:1039B0001C5B0008145B0008185B000838B590F821 +:1039C0004C300446002B3ED0063BDAB20F2A34D8E6 +:1039D0000F2B32D8DFE803F0373131082232313192 +:1039E0003131313131313737456DB0F862309D4278 +:1039F00014D2C3681B8AB5FBF3F203FB12556DB9F1 +:103A0000202383F311882B462A462946FFF734FEEC +:103A100085F311880A2384F84C300EE0142384F8CF +:103A20004C30202383F3118800231A461946204680 +:103A3000FFF710FE002383F3118838BD836D03B1B7 +:103A400098470023E7E70021204601F029FB0021E9 +:103A5000204601F01BFB63681B6813B1062120465A +:103A600098470623D7E7000010B590F84C30142B88 +:103A7000044629D017D8062B05D001D81BB110BD9C +:103A8000093B022BFBD80021204601F009FB002155 +:103A9000204601F0FBFA63681B6813B1062120463B +:103AA0009847062319E0152BE9D10B2380F84C30F9 +:103AB000202383F3118800231A461946FFF7DCFD03 +:103AC000002383F31188DAE7C3689B695B68002BE6 +:103AD000D5D1836D03B19847002384F84C30CEE7ED +:103AE000024B0022C3E900339A6070472C36002055 +:103AF000002303748268054B1B6899689142FBD2CE +:103B00005A68036042601060586070472C3600208D +:103B100008B5202383F31188037C032B05D0042BE5 +:103B20000DD02BB983F3118808BD436900221A60B8 +:103B30004FF0FF334361FFF7DBFF0023F2E7D0E9EB +:103B4000003213605A60F3E7002303748268054B68 +:103B50001B6899689142FBD85A6803604260106004 +:103B6000586070472C360020054B19690874186896 +:103B700002681A605360186101230374FCF758BD92 +:103B80002C36002030B54B1C0B4D87B0044610D0AE +:103B90002B690A4A01A800F025F92046FFF7E4FF47 +:103BA000049B13B101A800F059F92B69586907B0BB +:103BB00030BDFFF7D9FFF8E72C360020113B000895 +:103BC00038B50C4D41612B6981689A689142044671 +:103BD00003D8BDE83840FFF78BBF1846FFF7B4FFA6 +:103BE00001232C61014623742046BDE83840FCF7D0 +:103BF0001FBD00BF2C360020044B1A681B6990685B +:103C00009B68984294BF0020012070472C3600200A +:103C100010B5084C236820691A682260546001229C +:103C200023611A74FFF790FF01462069BDE8104038 +:103C3000FCF7FEBC2C36002008B5FFF7DDFF18B1FD +:103C4000BDE80840FFF7E4BF08BD0000FFF7E0BF94 +:103C5000FEE7000010B50C4CFFF742FF00F0B4F88F +:103C60000A498022204600F03BF8012344F8180C52 +:103C7000037400F0F5FC002383F3118862B6044856 +:103C8000BDE8104000F04CB854360020205B00081E +:103C9000305B000800F01CB9EFF3118020B9EFF39E +:103CA0000583202282F311887047000010B530B9D7 +:103CB000EFF30584C4F3080414B180F3118810BD38 +:103CC000FFF7BAFF84F31188F9E70000034A51684F +:103CD00053685B1A9842FBD8704700BF001000E0A1 +:103CE00082600222028270478368A3F17C0243F85B +:103CF0000C2C026943F83C2C426943F8382C074AE3 +:103D000043F81C2CC26843F8102C022203F8082C3C +:103D1000002203F8072CA3F1180070474906000899 +:103D200010B5202383F31188FFF7DEFF002104463E +:103D3000FFF746FF002383F31188204610BD0000E3 +:103D4000024B1B6958610F20FFF70EBF2C36002075 +:103D5000202383F31188FFF7F3BF000008B5014665 +:103D6000202383F311880820FFF70CFF002383F33F +:103D7000118808BD49B1064B42681B6918605A603A +:103D8000136043600420FFF7FDBE4FF0FF30704723 +:103D90002C3600200368984206D01A6802605060F2 +:103DA00059611846FFF7A4BE7047000038B50446B5 +:103DB0000D462068844200D138BD036823605C60F2 +:103DC0004561FFF795FEF4E7054B03F11402C3E9E3 +:103DD00005224FF0FF310022C3E90712704700BFF0 +:103DE0002C36002070B51C4EC0E9032305460C4656 +:103DF00001F052FB334653F8142F9A420DD1306232 +:103E0000C5E901242A600A2C2CBF00190A30C6E932 +:103E10000555BDE8704001F02DBB316A431AE31827 +:103E200038BF1C469368A34202D9081901F030FB41 +:103E300073699A6894420CD85A68AC602B606A60C7 +:103E400015609A685D60121B9A604FF0FF33F36152 +:103E500070BD1B68A41AECE72C36002038B51B4C4B +:103E6000636998420DD0D0E9003213605A60002295 +:103E70008168C2609A680A449A604FF0FF33E36138 +:103E800038BD2246036842F8143F002193425A602D +:103E9000C16003D1BDE8384001F0F4BA9A68816886 +:103EA000256A0A449A6001F0F7FA63699A68411B2F +:103EB0008A42E5D9AB181D1A092D206A98BF01F175 +:103EC0000A02BDE83840104401F0E2BA2C36002066 +:103ED0002DE9F041184C002704F11406656901F042 +:103EE000DBFA236AAA68C11A8A4215D813442362EE +:103EF000D5E9003213605A606369D5F80C80EF6031 +:103F0000B34201D101F0BEFA87F311882869C04796 +:103F1000202383F31188E1E76169B14209D013449A +:103F20001B1ABDE8F0410A2B2CBFC0180A3001F063 +:103F3000AFBABDE8F08100BF2C36002000207047EA +:103F4000FEE70000704700004FF0FF3070470000B0 +:103F500002290CD0032904D00129074818BF0020EA +:103F60007047032A05D8054800EBC2007047044893 +:103F700070470020704700BF145C00085C230020DD +:103F8000C85B000870B59AB00546084601A91446FA +:103F900000F0C2F801A8FDF781FE431C5B00C5E9F3 +:103FA00000340022237003236370C6B201AB0234D5 +:103FB0001046D1B28E4204F1020401D81AB070BD8D +:103FC00013F8011B04F8021C04F8010C0132F0E79D +:103FD00008B5202383F311880348FFF771FA002303 +:103FE00083F3118808BD00BFE837002090F85C30EB +:103FF00003F01F02012A07D190F85D200B2A03D19C +:104000000023C0E9143315E003F06003202B08D12E +:10401000B0F860302BB990F85D20212A03D81F2A10 +:1040200004D8FFF72FBA222AEBD0FAE7034A026539 +:104030000722426583650120704700BF532300209B +:1040400007B5052917D8DFE801F01916031919205B +:10405000202383F31188104A01900121FFF7D4FA3D +:1040600001980E4A0221FFF7CFFA0D48FFF7F4F945 +:10407000002383F3118803B05DF804FB202383F34E +:1040800011880748FFF7BEF9F2E7202383F3118870 +:104090000348FFF7D5F9EBE7685B00088C5B000885 +:1040A000E837002038B50C4D0C4C0D492A4604F178 +:1040B0000800FFF767FF05F1CA0204F11000094983 +:1040C000FFF760FF05F5CA7204F118000649BDE864 +:1040D0003840FFF757BF00BFB03C00205C230020F2 +:1040E000485B0008525B00085D5B000870B5044641 +:1040F00008460D46FDF7D2FDC6B2204601340378CE +:104100000BB9184670BD32462946FDF7B3FD0028AD +:10411000F3D10120F6E700002DE9F84F05460C46E3 +:10412000FDF7BCFD2B49C6B22846FFF7DFFF08B1FB +:104130000336F6B228492846FFF7D8FF08B11036F3 +:10414000F6B2632E0DD8DFF88C80DFF88C90234F09 +:10415000DFF890A0DFF890B02E7846B92670BDE861 +:10416000F88F29462046BDE8F84F01F045BC252EC2 +:104170002BD1072241462846FDF77CFD58B9DBF8D4 +:1041800000302360DBF804306360BBF80830238123 +:1041900007350A34E0E7082249462846FDF76AFD5C +:1041A00098B90F4BA21C197809090232C95D02F8AF +:1041B000041C13F8011B01F00F015345C95D02F8FF +:1041C000031CF0D118340835C6E704F8016B01353B +:1041D000C2E700BF345C00085D5B00083C5C00087F +:1041E000107AF01F1C7AF01F165A0008BFF34F8F89 +:1041F000024AD368DB03FCD4704700BF003C024096 +:1042000008B5074B1B7853B9FFF7F0FF054B1A6948 +:10421000002ABFBF044A5A6002F188325A6008BDC2 +:104220000E3F0020003C02402301674508B5054BC6 +:104230001B7833B9FFF7DAFF034A136943F00043F1 +:10424000136108BD0E3F0020003C02400728F0B576 +:1042500016D80C4C0C4923787BB90C4D0E4608231C +:104260004FF0006255F8047B46F8042B013B13F035 +:10427000FF033A44F6D10123237051F82000F0BD2A +:104280000020FCE7303F0020103F0020505C000879 +:10429000014B53F820007047505C0008082070471D +:1042A000072810B5044601D9002010BDFFF7CEFF46 +:1042B000064B53F824301844C21A0BB90120F4E716 +:1042C00012680132F0D1043BF6E700BF505C0008F1 +:1042D000072838B5044628D8FFF7DEFCFFF786FF2D +:1042E000FFF78EFF124AF323D360E300DBB243F4FF +:1042F000007343F002031361136943F480331361C5 +:1043000005462046FFF772FFFFF7A0FF094B53F861 +:10431000241000F03BF92846FFF788FFFFF7C6FCA2 +:104320002046BDE83840FFF7BBBF002038BD00BFC6 +:10433000003C0240505C000812F001032DE9F041FE +:1043400005460E4614464BD18118334A914261D836 +:10435000324B1B6813F001035CD0314FFFF79CFC1C +:10436000FFF74EFFF323FB60FFF740FF314640F2BB +:104370000128032C18D824F00104294E0C446D1A8E +:1043800040F20118A142336905EB01072AD123F05D +:1043900001033361FFF74AFFFFF788FC0120BDE806 +:1043A000F081043C0435E4E7AB07E4D13B6923F436 +:1043B00040733B613B6943EA08033B6151F8046B7E +:1043C0002E60BFF34F8FFFF711FF2B689E42E8D09E +:1043D0003B6923F001033B61FFF728FFFFF766FC11 +:1043E0000020DCE723F440733361336943EA0803B8 +:1043F00033610B883B80BFF34F8FFFF7F7FE3F8899 +:1044000031F8023BBFB2BB42BCD0336923F0010399 +:104410003361E1E71846C2E70000080800380240AF +:10442000003C0240084908B50B7828B11BB9FFF7DA +:10443000E7FE01230B7008BD002BFCD0BDE808404F +:104440000870FFF7F3BE00BF0E3F002070B582B0CA +:10445000FFF722FC0E4E054601F01EF8326890422E +:1044600037BF0C4A0B49516814682EBFD1E900418F +:10447000013151600419034641F1000128460191C0 +:104480003360FFF713FC0199204602B070BD00BFF6 +:10449000343F0020383F002070B582B0FFF7FCFBAE +:1044A000104E054600F0F8FF3268904237BF0E4AC2 +:1044B0000D49516814682EBFD1E9004101315160A6 +:1044C000041941F100010346284601913360FFF7CA +:1044D000EDFB01994FF47A7200232046FBF790FE22 +:1044E00002B070BD343F0020383F002010B50244B8 +:1044F000064BD2B2904200D110BD441C00B253F81A +:10450000200041F8040BE0B2F4E700BF502800405F +:104510000F4B30B51C6F240407D41C6F44F4007497 +:104520001C671C6F44F400441C670A4C236843F466 +:10453000807323600244084BD2B2904200D130BD58 +:10454000441C00B251F8045B43F82050E0B2F4E799 +:1045500000380240007000405028004007B501229A +:1045600001A90020FFF7C2FF019803B05DF804FB2A +:1045700013B50446FFF7F2FFA04205D0012201A9BE +:1045800000200194FFF7C4FF02B010BD0144BFF347 +:104590004F8F064B884204D3BFF34F8FBFF36F8F0B +:1045A0007047C3F85C022030F4E700BF00ED00E084 +:1045B000074B45F255521A6002225A6040F6FF72CC +:1045C0009A604CF6CC421A60024B01221A70704776 +:1045D00000300040443F0020034B1B781BB1034BCD +:1045E0004AF6AA221A607047443F0020003000407B +:1045F000034B1A681AB9034AD2F874281A60704734 +:10460000403F002000300240024B4FF08072C3F860 +:10461000742870470030024008B5FFF7E9FF024BED +:104620001868C0F3407008BD403F002008B5FFF790 +:10463000DFFF024B1868C0F3007008BD403F002048 +:10464000EFF3098305494A6B22F001024A6368339C +:1046500083F30988002383F31188704700EF00E09B +:10466000202080F3118862B60D4B0E4AD96821F4E0 +:10467000E0610904090C0A43DA60D3F8FC200A4916 +:1046800042F08072C3F8FC20084AC2F8B01F1168DB +:1046900041F0010111601022DA7783F8220070479F +:1046A00000ED00E00003FA0555CEACC5001000E0B7 +:1046B00010B5202383F311880E4B5B6813F400635D +:1046C00014D0F1EE103AEFF30984683C4FF0807398 +:1046D000E361094BDB6B236684F30988FFF78CFAEF +:1046E00010B1064BA36110BD054BFBE783F31188A6 +:1046F000F9E700BF00ED00E000EF00E05B06000816 +:104700005E06000870B5BFF34F8FBFF36F8F1A4A74 +:104710000021C2F85012BFF34F8FBFF36F8F536960 +:1047200043F400335361BFF34F8FBFF36F8FC2F871 +:104730008410BFF34F8FD2F88030C3F3C900C3F3A6 +:104740004E335B0143F6E07403EA0406014646EA91 +:1047500081750139C2F86052F9D2203B13F1200F64 +:10476000F2D1BFF34F8F536943F480335361BFF3EA +:104770004F8FBFF36F8F70BD00ED00E0FEE70000CC +:104780000A4B0B480B4A90420BD30B4BDA1C121A04 +:10479000C11E22F003028B4238BF00220021FDF728 +:1047A00085BA53F8041B40F8041BECE7245E0008AC +:1047B000584000205840002058400020704700001A +:1047C00070B5D0E91B439E6800224FF0FF3504EB23 +:1047D00042135101D3F800090028BEBFD3F80009E5 +:1047E00040F08040C3F80009D3F8000B0028BEBF9A +:1047F000D3F8000B40F08040C3F8000B013263187F +:104800009642C3F80859C3F8085BE0D24FF0011391 +:10481000C4F81C3870BD00001D4B03EB80022DE96D +:10482000F043D2F80CC0DD6EDCF81420461CD2F840 +:1048300000E005EB063605EB4018516871450AD3D8 +:10484000D5F83438012202FA00F023EA0000C5F856 +:104850003408BDE8F083BCF81040AEEB0103A3427E +:1048600028BF2346D8F81849A4B2B3EB840FF0D878 +:104870009468A4F1040959F8047F3760A4EB090790 +:104880001F44042FF7D81C440B4494605360D4E7B2 +:10489000483F0020890141F02001016103699B0626 +:1048A000FCD41220FFF712BA10B5054C2046FEF7D3 +:1048B00089FE4FF0A043E366024B236710BD00BFA3 +:1048C000483F0020945C000870B50378012B054632 +:1048D00050D12A4BC46E98421BD1294B5A6B42F0DF +:1048E00080025A635A6D42F080025A655A6D5A69C5 +:1048F00042F080025A615A6922F080025A610E2108 +:1049000043205B69FEF734FC1E4BE3601E4BC4F88A +:1049100000380023C4F8003EC0232360EE6E4FF43D +:104920000413A3633369002BFCDA012333610C20E9 +:10493000FFF7CCF93369DB07FCD41220FFF7C6F987 +:104940003369002BFCDA0026A6602846FFF738FF03 +:104950006B68C4F81068DB68C4F81468C4F81C6895 +:104960004BB90A4BA3614FF0FF336361A36843F077 +:104970000103A36070BD064BF4E700BF483F002071 +:10498000003802404014004003002002003C30C0C8 +:10499000083C30C0F8B5C46E054600212046FFF73C +:1049A00079FF296F00234FF001128F68C4F8343863 +:1049B0004FF00066C4F81C284FF0FF3004EB4312A0 +:1049C00001339F42C2F80069C2F8006BC2F80809BF +:1049D000C2F8080BF2D20B68EA6E6B6763621023B1 +:1049E0001361166916F01006FBD11220FFF76EF95D +:1049F000D4F8003823F4FE63C4F80038A36943F404 +:104A0000402343F01003A3610923C4F81038C4F80D +:104A100014380A4BEB604FF0C043C4F8103B084B0E +:104A2000C4F8003BC4F81069C4F800396B6F03F197 +:104A3000100243F480136A67A362F8BD705C00083B +:104A400040800010C26E90F86610D2F8003823F44F +:104A5000FE6343EA0113C2F8003870472DE9F843BA +:104A600000EB8103C56EDA68166806F00306731E54 +:104A7000022B05EB41130C4680460FFA81F94FEAF1 +:104A800041104FF00001C3F8101B4FF0010104F179 +:104A9000100398BFB60401FA03F391698EBF334E39 +:104AA00006F1805606F5004600293AD0578A04F1EF +:104AB0005801490137436F50D5F81C180B43C5F80E +:104AC0001C382B180021C3F8101953690127611EE7 +:104AD000A7409BB3138A928B9B08012A88BF53433C +:104AE000D8F87420981842EA034301F1400205EB1C +:104AF0008202C8F87400214653602846FFF7CAFEB8 +:104B000008EB8900C3681B8A43EA84534834640174 +:104B10001E432E51D5F81C381F43C5F81C78BDE83C +:104B2000F88305EB4917D7F8001B21F40041C7F8BB +:104B3000001BD5F81C1821EA0303C0E704F13F036A +:104B400005EB83030A4A5A6028462146FFF7A2FE76 +:104B500005EB4910D0F8003923F40043C0F80039C0 +:104B6000D5F81C3823EA0707D7E700BF00800010FC +:104B700000040002026F12684267FFF721BE0000C6 +:104B80005831C36E49015B5813F4004004D013F44C +:104B9000001F0CBF02200120704700004831C36E87 +:104BA00049015B5813F4004004D013F4001F0CBFFC +:104BB000022001207047000000EB8101CB68196AD8 +:104BC0000B6813604B6853607047000000EB810373 +:104BD00030B5DD68AA691368D36019B9402B84BF6A +:104BE000402313606B8A1468C26E1C44013CB4FB02 +:104BF000F3F46343033323F0030302EB411043EA6E +:104C0000C44343F0C043C0F8103B2B6803F00303D8 +:104C1000012B09B20ED1D2F8083802EB411013F47F +:104C2000807FD0F8003B14BF43F0805343F0005323 +:104C3000C0F8003B02EB4112D2F8003B43F00443C2 +:104C4000C2F8003B30BD00002DE9F041244DEE6E6E +:104C500006EB40130446D3F8087BC3F8087B3807FB +:104C60000AD5D6F81438190706D505EB8403214672 +:104C7000DB6828465B689847FA071FD5D6F81438D2 +:104C8000DB071BD505EB8403D968CCB98B69488A4F +:104C90005A68B2FBF0F600FB16228AB91868DA6887 +:104CA00090420DD2121AC3E90024202383F3118805 +:104CB0000B482146FFF78AFF84F31188BDE8F08195 +:104CC000012303FA04F26B8923EA02036B81CB68A8 +:104CD000002BF3D021460248BDE8F041184700BF41 +:104CE000483F002000EB810370B5DD68C36E6C693E +:104CF0002668E6604A0156BB1A444FF40020C2F809 +:104D000010092A6802F00302012A0AB20ED1D3F870 +:104D1000080803EB421410F4807FD4F8000914BF94 +:104D200040F0805040F00050C4F8000903EB4212FC +:104D3000D2F8000940F00440C2F80009D3F8340862 +:104D4000012202FA01F10143C3F8341870BD19B908 +:104D5000402E84BF4020206020682E8A8419013CA8 +:104D6000B4FBF6F440EAC44040F000501A44C6E7F1 +:104D7000F8B504461E48C56E05EB4413D3F8086920 +:104D8000C3F80869F10717D5D5F81038DA0713D535 +:104D900000EB8403D9684B691F68DA68974218D220 +:104DA000D21B00271A605F60202383F311882146FD +:104DB000FFF798FF87F31188330617D5D5F8342805 +:104DC0000123A340134211D02046BDE8F840FFF76D +:104DD00023BD012303FA04F2038923EA02030381BA +:104DE0008B68002BE8D021469847E5E7F8BD00BF67 +:104DF000483F00202DE9F74FA34CE66E7569B36973 +:104E00001D4015F48058756107D02046FEF746FC1A +:104E100003B0BDE8F04FFFF74BBC002D12DAD6F817 +:104E2000003E99489F071EBFD6F8003E23F00303BB +:104E3000C6F8003ED6F8043823F00103C6F804385B +:104E4000FEF756FC280505D58F48FFF7B9FC8E48BC +:104E5000FEF73EFCA9040CD5D6F8083813F0060F6F +:104E6000F36823F470530CBF43F4105343F4A0537E +:104E7000F3602A0704D56368DB680BB18248984762 +:104E8000EB0200F18A80AF0227D5D4F86C90DFF8EE +:104E9000F8B100274FF0010A09EB4712D2F8003BA6 +:104EA00003F44023B3F5802F11D1D2F8003B002B3F +:104EB0000DDA62890AFA07F322EA0303638104EB3D +:104EC0008703DB68DB6813B1394658469847236F80 +:104ED00001379B68FFB29F42DED9E80618D5E76E1E +:104EE0003A6AC2F30A1002F00F0302F4F012B2F5AC +:104EF000802F00F09D80B2F5402F09D104EB830391 +:104F00000022DB681B6A07F58057904240F08280E0 +:104F10002B03D6F818481DD5E70302D50020FFF76C +:104F200093FEA60302D50120FFF78EFE600302D593 +:104F30000220FFF789FE210302D50320FFF784FE3C +:104F4000E20202D50420FFF77FFEA30202D505206E +:104F5000FFF77AFE6F037FF55BAFE60702D500200F +:104F6000FFF706FFA50702D50120FFF701FF600745 +:104F700002D50220FFF7FCFE210702D50320FFF730 +:104F8000F7FEE20602D50420FFF7F2FEA3067FF546 +:104F90003FAF0520FFF7ECFE3AE7E36EDFF8E8B03D +:104FA000019300274FF0010A236F9B685FFA87F98E +:104FB00099453FF668AF019B03EB4913D3F80029ED +:104FC00002F44022B2F5802F22D1D3F80029002A22 +:104FD0001EDAD3F8002942F09042C3F80029D3F832 +:104FE0000029002AFBDBE06E4946FFF753FC2289CB +:104FF0000AFA09F322EA0303238104EB8903DB683D +:105000009B6813B14946584698474846FFF704FC49 +:105010000137C9E7910708BFD7F80080072A98BF72 +:1050200003F8018B02F1010298BF4FEA18286CE7E0 +:10503000023304EB830207F580575268D2F818C098 +:10504000DCF80820DCE9001CA1EB0C0C00218842F4 +:105050000AD104EB830463689B699A6802449A60EE +:105060005A6802445A6053E711F0030F08BFD7F89B +:1050700000808C4588BF02F8018B01F1010188BFD7 +:105080004FEA1828E3E700BF483F0020C36E03EB58 +:105090004111D1F8003B43F40013C1F8003B7047C5 +:1050A000C36E03EB4111D1F8003943F40013C1F88A +:1050B00000397047C36E03EB4111D1F8003B23F474 +:1050C0000013C1F8003B7047C36E03EB4111D1F8E8 +:1050D000003923F40013C1F80039704730B5039C40 +:1050E0000172043304FB0325C0E90653049B0363E8 +:1050F0000021059BC160C0E90000C0E90422C0E9AD +:105100000842C0E90A11436330BD0000416A002231 +:10511000C0E90411C0E90A22C2606FF00101FEF784 +:1051200045BE0000D0E90432934201D1C2680AB9F9 +:10513000181D70470020704703691960C26801326A +:10514000C260C269134482690361934224BF436A07 +:1051500003610021FEF71EBE38B504460D46E36824 +:105160003BB16269131D1268A3621344E36200201D +:1051700007E0237A33B929462046FEF7FBFD0028D5 +:10518000EDDA38BD6FF00100FBE70000C368C269CB +:10519000013BC3604369134482694361934224BF66 +:1051A000436A436100238362036B03B1184770476E +:1051B00070B52023044683F31188866A3EB9FFF751 +:1051C000CBFF054618B186F31188284670BDA36A47 +:1051D000E26A13F8015BA362934202D32046FFF711 +:1051E000D5FF002383F31188EFE700002DE9F84F86 +:1051F00004460E46174698464FF0200989F3118859 +:105200000025AA46D4F828B0BBF1000F09D14146C9 +:105210002046FFF7A1FF20B18BF311882846BDE897 +:10522000F88FD4E90A12A7EB050B521A934528BF51 +:105230009346BBF1400F1BD9334601F1400251F8B0 +:10524000040B43F8040B9142F9D1A36A4033403672 +:10525000A3624035D4E90A239A4202D32046FFF7DD +:1052600095FF8AF31188BD42D8D289F31188C9E726 +:1052700030465A46FCF7F4FCA36A5B445E44A362E2 +:105280005D44E7E710B5029C0172043304FB03217F +:10529000C0E906130023C0E90A33039B0363049BA0 +:1052A000C460C0E90000C0E90422C0E908424363C9 +:1052B00010BD0000026AC260426AC0E904220022F6 +:1052C000C0E90A226FF00101FEF770BDD0E90423A6 +:1052D0009A4201D1C26822B9184650F8043B0B60CB +:1052E0007047002070470000C368C2690133C36083 +:1052F0004369134482694361934224BF436A436113 +:105300000021FEF747BD000038B504460D46E368AE +:105310003BB123691A1DA262E2691344E3620020D3 +:1053200007E0237A33B929462046FEF723FD0028FB +:10533000EDDA38BD6FF00100FBE70000036919608A +:10534000C268013AC260C269134482690361934230 +:1053500024BF436A036100238362036B03B11847D0 +:105360007047000070B520230D460446114683F3B4 +:105370001188866A2EB9FFF7C7FF10B186F311882E +:1053800070BDA36A1D70A36AE26A01339342A362EF +:1053900004D3E16920460439FFF7D0FF002080F3F1 +:1053A0001188EDE72DE9F84F04460D4690469946E1 +:1053B0004FF0200A8AF311880026B346A76A4FB936 +:1053C00049462046FFF7A0FF20B187F311883046F9 +:1053D000BDE8F88FD4E90A073A1AA8EB0607974206 +:1053E00028BF1746402F1BD905F1400355F8042B61 +:1053F00040F8042B9D42F9D1A36A4033A3624036A2 +:10540000D4E90A239A4204D3E16920460439FFF71C +:1054100095FF8BF311884645D9D28AF31188CDE7E1 +:1054200029463A46FCF71CFCA36A3B443D44A36270 +:105430003E44E5E7D0E904239A4217D1C3689BB103 +:10544000836A8BB1043B9B1A0ED01360C368013B87 +:10545000C360C3691A44836902619A4224BF436AE4 +:105460000361002383620123184670470023FBE792 +:1054700000F088B84FF08043002258631A6102227E +:10548000DA6070474FF080430022DA607047000016 +:105490004FF08043586370474FF08043586A70471D +:1054A0004B6843608B688360CB68C3600B69436162 +:1054B0004B6903628B6943620B68036070470000AD +:1054C00008B5264B26481A6940F2FF110A431A61B3 +:1054D0001A6922F4FF7222F001021A611A691A6B2A +:1054E0000A431A631A6D0A431A651E4A1B6D114658 +:1054F000FFF7D6FF02F11C0100F58060FFF7D0FF37 +:1055000002F1380100F58060FFF7CAFF02F1540193 +:1055100000F58060FFF7C4FF02F1700100F58060C4 +:10552000FFF7BEFF02F18C0100F58060FFF7B8FFC6 +:1055300002F1A80100F58060FFF7B2FF02F1C4019B +:1055400000F58060FFF7ACFF02F1E00100F580603C +:10555000FFF7A6FFBDE8084000F088B80038024019 +:1055600000000240A05C000808B500F0F3F9FEF767 +:1055700071FBFFF73DF8BDE80840FEF793BD000062 +:10558000704700000F4B1A6C42F001021A641A6E49 +:1055900042F001021A660C4A1B6E936843F0010345 +:1055A00093604FF080436B229A624FF0FF32DA62D1 +:1055B00000229A615A63DA605A6001225A611A60C5 +:1055C000704700BF00380240002004E04FF08042E6 +:1055D00008B51169D3680B40D9B2C9439B07116163 +:1055E00007D5202383F31188FEF754FB002383F3B0 +:1055F000118808BD1B4B1A696FEAC2526FEAD2527A +:105600001A611A69C2F308021A614FF0FF301A6971 +:105610005A69586100215A6959615A691A6A62F0D7 +:1056200080521A621A6A02F080521A621A6A5A6A20 +:1056300058625A6A59625A6A0B4A106840F480707C +:105640001060186F00F44070B0F5007F1EBF4FF47B +:10565000803018671967536823F40073536000F0B3 +:1056600055B900BF0038024000700040364B374A41 +:105670001A64374A4FF4404111601A6842F001023F +:105680001A601A689207FCD59A6822F003029A60A1 +:105690002D4B9A6812F00C02FBD1196801F0F90148 +:1056A00019609A601A6842F480321A601A6890038E +:1056B000FCD55A6F42F001025A67234B5A6F91078B +:1056C000FCD5244A5A601A6842F080721A60204B56 +:1056D0005A685204FCD51A6842F480321A605A683B +:1056E000D003FCD51A6842F400321A60184A536895 +:1056F0009903FCD5144B1A689201FCD5164A9A609E +:1057000040F20112C3F88C200022C3F89020134A03 +:1057100040F207331360136803F00F03072BFAD12D +:10572000094B9A6842F002029A609A6802F00C02F1 +:10573000082AFAD15A6C42F480425A645A6E42F4F2 +:1057400080425A665B6E70470038024000040010C9 +:1057500000700040106C400900948838003C024002 +:10576000074A08B5536903F00103536123B1054AA1 +:1057700013680BB150689847BDE80840FEF798BF22 +:10578000003C0140D83F0020074A08B5536903F0A8 +:105790000203536123B1054A93680BB1D06898475F +:1057A000BDE80840FEF784BF003C0140D83F002020 +:1057B000074A08B5536903F00403536123B1054A4E +:1057C00013690BB150699847BDE80840FEF770BFF8 +:1057D000003C0140D83F0020074A08B5536903F058 +:1057E0000803536123B1054A93690BB1D069984707 +:1057F000BDE80840FEF75CBF003C0140D83F0020F8 +:10580000074A08B5536903F01003536123B1054AF1 +:10581000136A0BB1506A9847BDE80840FEF748BFCD +:10582000003C0140D83F0020164B10B55C6904F4E1 +:1058300078725A61A30604D5134A936A0BB1D06AF1 +:105840009847600604D5104A136B0BB1506B98470C +:10585000210604D50C4A936B0BB1D06B9847E20537 +:1058600004D5094A136C0BB1506C9847A30504D5B5 +:10587000054A936C0BB1D06C9847BDE81040FEF719 +:1058800017BF00BF003C0140D83F0020194B10B5A6 +:105890005C6904F47C425A61620504D5164A136DB2 +:1058A0000BB1506D9847230504D5134A936D0BB186 +:1058B000D06D9847E00404D50F4A136E0BB1506EBB +:1058C0009847A10404D50C4A936E0BB1D06E98474B +:1058D000620404D5084A136F0BB1506F9847230434 +:1058E00004D5054A936F0BB1D06F9847BDE81040BF +:1058F000FEF7DEBE003C0140D83F002008B5FFF7B0 +:1059000065FEBDE80840FEF7D3BE0000062108B5DD +:105910000846FDF72DFC06210720FDF729FC06218E +:105920000820FDF725FC06210920FDF721FC0621B2 +:105930000A20FDF71DFC06211720FDF719FC0621A2 +:105940002820FDF715FCBDE8084007211C20FDF7C5 +:105950000FBC000008B5FFF74DFE00F00DF8FDF795 +:105960001DFCFDF72DFEFDF705FDFFF709FEBDE867 +:105970000840FFF77DBD00000023054A19460133AA +:10598000102BC2E9001102F10802F8D1704700BFE4 +:10599000D83F002010B501390244904201D10020C7 +:1059A00005E0037811F8014FA34201D0181B10BD88 +:1059B0000130F2E72DE9F041A3B1C91A177801448B +:1059C000044603F1FF3C8C42204601D9002009E047 +:1059D0000578BD4204F10104F5D10CEB0405D6189D +:1059E000A54201D1BDE8F08115F8018D16F801ED51 +:1059F000F045F5D0E7E70000034611F8012B03F866 +:105A0000012B002AF9D170476F72672E617264759D +:105A100070696C6F742E46726565666C7952544B72 +:105A2000000000004E6F20617070207369670A00EB +:105A3000426164206677206C656E67746820257506 +:105A40000A0042616420626F6172645F69642025AC +:105A5000752073686F756C642062652025750A0077 +:105A60004261642066772064657363726970746F45 +:105A700072206C656E6774682025750A0042616447 +:105A80002061707020435243203078253038783AB6 +:105A9000307825303878203078253038783A3078AA +:105AA000253038780A00476F6F64206669726D7719 +:105AB0006172650A0040A2E4F1646891060000008A +:105AC00053544D3332463F3F3F3F3F3F0053544DC9 +:105AD000333246375B347C355D780053544D333276 +:105AE00046375B367C375D78000000000000000020 +:105AF000F1320008DD3200081933000805330008D0 +:105B000011330008FD320008E9320008D5320008E0 +:105B10002533000800000000010000000000000024 +:105B20006D61696E0000000069646C650000000032 +:105B3000285B000870360020E837002001000000D4 +:105B4000513C0008000000004172647550696C6FA0 +:105B5000740025424F415244252D424C00255345A7 +:105B60005249414C250000000200000000000000E6 +:105B70000D3500087935000840004000803C0020C9 +:105B8000903C002002000000000000000300000024 +:105B900000000000BD3500080000000010000000FB +:105BA000A03C0020000000000100000000000000F8 +:105BB000483F00200101020041400008513F000819 +:105BC000ED3F0008D13F000843000000D05B000813 +:105BD00009024300020100C0320904000001020270 +:105BE0000100052400100105240100010424020223 +:105BF0000524060001070582030800FF09040100CF +:105C0000020A0000000705010240000007058102AA +:105C100040000000120000001C5C0008120110018E +:105C20000200004009124157000201020301000076 +:105C30000403090425424F415244250030313233D8 +:105C40003435363738394142434445460000000078 +:105C50000040000000400000004000000040000044 +:105C6000000001000000020000000200000002002D +:105C70000000000005370008BD390008693A000837 +:105C800040004000C03F0020C03F00200100000055 +:105C9000D03F00208000000040010000050000000F +:105CA0000010806A00000000AAAAAAAA00000064EE +:105CB000FFFF00000000000000A00A0000000A0032 +:105CC00000000000AAAAAAAA00000000FFFF00002E +:105CD00000000000990000000040000000000000EB +:105CE000AAAAAAAA00000020FFFF000000000000EE +:105CF000000000000000000000000000AAAAAAAAFC +:105D000000000000FFFF0000000000000000000095 +:105D10000000000000000000AAAAAAAA00000000DB +:105D2000FFFF000000000000000000000000000075 +:105D300000000000AAAAAAAA00000000FFFF0000BD +:105D40000000000000000000000000000000000053 +:105D5000AAAAAAAA00000000FFFF0000000000009D +:105D60000000000000000000000000000A00000029 +:105D70000000000003000000000000000000000020 +:105D80000000000000000000000000000000000013 +:105D900000000000000000000000000094A4FF7F4D +:105DA00001000000000000000404000000000000EA +:105DB0000000070000000000640000000000000078 +:105DC00040420F00FE2A0100D2040000FF00000044 +:105DD00000000000C05A00083F0000004904000015 +:105DE000CD5A00083F00000051040000DB5A0008B3 +:105DF0003F00000000960000000008009600000030 +:105E00000008000004000000305C000800000000F2 :105E10000000000000000000000000000000000082 -:105E200000000000000000000000000034A4FF7F1C -:105E30000100000000000000040400000000000059 -:105E400000000700000000006400000000000000E7 -:105E500040420F00FE2A0100D2040000FF000000B3 -:105E600000000000505B00083F00000049040000F3 -:105E70005D5B00083F000000510400006B5B000800 -:105E80003F0000000096000000000800960000009F -:105E90000008000004000000C05C000800000000D2 -:105EA00000000000000000000000000000000000F2 -:045EB00000000000EE +:045E2000000000007E :00000001FF diff --git a/Tools/bootloaders/HitecMosaic_bl.bin b/Tools/bootloaders/HitecMosaic_bl.bin index 709ade6b30e..e9e621277e7 100755 Binary files a/Tools/bootloaders/HitecMosaic_bl.bin and b/Tools/bootloaders/HitecMosaic_bl.bin differ diff --git a/Tools/bootloaders/HitecMosaic_bl.elf b/Tools/bootloaders/HitecMosaic_bl.elf index b71c2a32a2c..8bb8d21632c 100755 Binary files a/Tools/bootloaders/HitecMosaic_bl.elf and b/Tools/bootloaders/HitecMosaic_bl.elf differ diff --git a/Tools/bootloaders/HitecMosaic_bl.hex b/Tools/bootloaders/HitecMosaic_bl.hex index 1042558c864..3b44f38eaa5 100644 --- a/Tools/bootloaders/HitecMosaic_bl.hex +++ b/Tools/bootloaders/HitecMosaic_bl.hex @@ -1,1099 +1,979 @@ :020000040800F2 -:1000000000090020E9040008E1140008E5140008D4 -:1000100039150008E51400080D150008EB04000868 -:10002000EB040008EB040008EB040008A537000807 -:10003000EB040008EB040008EB040008493C00084E -:10004000EB040008EB040008EB040008EB040008D4 -:10005000EB040008EB0400082D3A0008593A0008A8 -:10006000853A0008B13A0008DD3A0008EB040008C0 -:10007000EB040008EB040008EB040008EB040008A4 -:10008000EB040008EB040008EB040008512600080C -:10009000BD2600081127000865270008093B000855 -:1000A000EB040008EB040008EB040008EB04000874 -:1000B000EB040008EB040008EB040008EB04000864 -:1000C000EB040008EB040008EB040008EB04000854 -:1000D000EB040008EB040008212B0008352B000876 -:1000E000713B0008EB040008EB040008EB04000877 -:1000F000EB040008EB040008EB040008EB04000824 -:10010000EB040008EB040008EB040008EB04000813 -:10011000EB040008EB040008EB040008EB04000803 -:10012000EB040008EB040008EB040008EB040008F3 -:10013000EB040008EB040008EB040008EB040008E3 -:10014000EB040008EB040008EB040008EB040008D3 -:10015000EB040008EB040008EB040008EB040008C3 -:10016000EB040008EB040008EB040008EB040008B3 -:10017000EB040008EB040008EB040008EB040008A3 -:10018000EB040008EB040008EB040008EB04000893 -:10019000EB040008EB040008EB040008EB04000883 -:1001A0008D14000800000000D0400B1CD1409C467C -:1001B000203AD34018435242634693401843704755 -:1001C0009140031C90409C46203A93401943524270 -:1001D0006346D3401943704753B94AB9002908BF51 -:1001E00000281CBF4FF0FF314FF0FF3000F07AB90C -:1001F000ADF1080C6DE904CE00F006F8DDF804E07E -:10020000DDE9022304B070472DE9F0478C460D4626 -:100210000446089E002B51D18A4217466DD9B2FA86 -:1002200082FEBEF1000F0BD0CEF1200C01FA0EF5CC -:1002300020FA0CFC02FA0EF74CEA050C00FA0EF458 -:100240004FEA174A250CBCFBFAF81FFA87F90AFB9C -:1002500018CC45EA0C4508FB09F3AB420AD9ED1965 -:1002600008F1FF3280F02381AB4240F22081A8F1F7 -:1002700002083D44ED1AA4B2B5FBFAF00AFB105592 -:1002800044EA054400FB09F9A14509D9E41900F144 -:10029000FF3380F00A81A14540F2078102383C44D7 -:1002A000A4EB090440EA08400021002E61D024FAA2 -:1002B0000EF4002334607360BDE8F0878B4207D9E9 -:1002C000002E54D0002186E821000846BDE8F087C2 -:1002D000B3FA83F1002940F08E80AB4202D3824210 -:1002E00000F2FA80841A65EB03050120AC46002E6B -:1002F0003FD086E81010BDE8F08712B90127B7FBA0 -:10030000F2F7B7FA87FEBEF1000F34D1EB1B3A0CBF -:100310001FFA87FC0121B3FBF2F8250C02FB18330E -:1003200045EA03450CFB08F3AB4207D9ED1908F188 -:10033000FF3002D2AB4200F2D1808046ED1AA3B268 -:10034000B5FBF2F002FB105543EA05440CFB00FC40 -:10035000A44507D9E41900F1FF3302D2A44500F205 -:10036000B8801846A4EB0C0440EA08409DE73146EB -:100370003046BDE8F087CEF1200405FA0EF307FA07 -:100380000EF720FA04F83A0C25FA04F448EA0308B8 -:10039000B4FBF2F14FEA184502FB11441FFA87FC47 -:1003A00045EA044501FB0CF3AB4200FA0EF409D90F -:1003B000ED1901F1FF3080F08A80AB4240F2878076 -:1003C00002393D44EB1A1FFA88F5B3FBF2F002FB49 -:1003D000103345EA034500FB0CF3AB4207D9ED1996 -:1003E00000F1FF386FD2AB426DD902383D44EB1AB1 -:1003F00040EA01418FE7C1F1200722FA07F88B405C -:1004000005FA01F448EA030320FA07FE4FEA134C09 -:10041000FD404EEA040EB5FBFCF94FEA1E440CFB0E -:1004200019551FFA83F844EA054509FB08F4AC4264 -:1004300002FA01F200FA01FA08D9ED1809F1FF30C9 -:1004400043D2AC4241D9A9F102091D442D1B1FFA28 -:100450008EFEB5FBFCF00CFB10554EEA054400FB8C -:1004600008F8A04507D9E41800F1FF3529D2A045C6 -:1004700027D902381C4440EA0940A4EB0804A0FB39 -:1004800002894C45C6464D4615D312D056B1BAEB3B -:100490000E0364EB050404FA07F7CB401F43CC407E -:1004A000376074600021BDE8F0871846F8E6904692 -:1004B000E0E6C245EAD2B8EB020E69EB030501386B -:1004C000E4E72846D7E7404691E78146BEE7014684 -:1004D00078E702383C4445E7084608E7A8F10208F7 -:1004E0003D442BE7704700BF02E000F000F8FEE754 -:1004F00072B6394880F30888384880F3098838484C -:100500004EF60851CEF20001086040F20000CCF235 -:1005100000004EF63471CEF200010860BFF34F8F39 -:10052000BFF36F8F40F20000C0F2F0004EF688512A -:10053000CEF200010860BFF34F8FBFF36F8F4FF013 -:100540000000E1EE100A4EF63C71CEF200010860A8 -:10055000062080F31488BFF36F8F03F061F903F076 -:100560008DF94FF055301F491B4A91423CBF41F86D -:10057000040BFAE71C49194A91423CBF41F8040BAD -:10058000FAE71A491A4A1B4B9A423EBF51F8040B2C -:1005900042F8040BF8E700201749184A91423CBF83 -:1005A00041F8040BFAE703F03FF903F0A9F9144C02 -:1005B000144DAC4203DA54F8041B8847F9E700F005 -:1005C0003FF8114C114DAC4203DA54F8041B884734 -:1005D000F9E703F027B9000000090020001100200E -:1005E0000000000800010020000900201844000855 -:1005F000001100207411002078110020C82600206E -:10060000A0010008A4010008A4010008A40100083A -:100610002DE9F04F2DED108AC1F80CD0C3689D462E -:10062000BDEC108ABDE8F08F002383F311882846C3 -:10063000A047002002F090FE02F0BAFD00DFFEE7C6 -:10064000394B6FF007022DE9F0416FF0670100248C -:100650001A7003225A709C70DC701C715C719C7162 -:10066000DC711C7259729A72DC7203F045F807460D -:1006700003F092F80546D0BB2C4B9F4239D0013392 -:100680009F4239D02A4B27F0FF029A4238D1F8B264 -:1006900000F052FAA84642F2107400F07BFC00F021 -:1006A00051FA064680B38CBB464635B1214B9F427A -:1006B00003D003F069F800242646002003F026F852 -:1006C0004FF090431B6913F0200322D00EB100F0CD -:1006D00033F800F081FC00F015FE00F041FF054604 -:1006E000CCB900F0CFFC012002F03CFEF8E78046D8 -:1006F000D3E780460446D0E704464FF00108CCE734 -:1007000080464FF47A74C8E70446CEE74FF47A7413 -:10071000CBE71C46DDE700F023FF401BA042E0D9F9 -:1007200000F00AF8D9E700BF78110020010007B0F7 -:10073000000008B0263A09B010B51C4B1C4953F80C -:10074000042F013200D110BD8B42F8D1194C1A4B45 -:1007500022689A4228D9194B9B6803F1006303F57C -:10076000D0439A4220D202F0E3FF02F0F5FF0020CE -:1007700000F0E2FD124B0220187000F019FE114B40 -:10078000DA690022DA61D96999699A619B6972B65E -:100790000D4A0E4B13601B682268202181F31188DB -:1007A0009D4683F30888104710BD00BFFC67000812 -:1007B0001C68000804680008FF6700087811002022 -:1007C000841100200010024008ED00E000680008DD -:1007D00009490B6849F269009AB21B0C00FB02330D -:1007E000064A0B60136844F2506198B21B0C01FB7F -:1007F0000030106080B270470C11002008110020FA -:1008000010B500211022044600F0ECFD034B03CB91 -:10081000206061601868A06010BD00BFACF7FF1FCA -:10082000F0B51F4CBBB000F09BFEA368C31AF92BB8 -:1008300030D906AD2346A06028220021284601F0C9 -:100840001DFC04F10E0000F0C5FD0023C6B2591DC9 -:100850005F1CDBB2B3424FEAC10107DA0E33234417 -:100860000822284601F00AFC3B46F0E701230393E7 -:100870000823207B02930B4B0193C1F3CF0130235C -:10088000059100930146049503A3D3E9002306488C -:1008900001F0C4F93BB0F0BD78F6339F93CACD8D1B -:1008A000C8210020D5210020A021002070B50D46D0 -:1008B00014461E4601F058F950B9022E0ED1012CF3 -:1008C0000CD112A3D3E90023C5E90023012070BD98 -:1008D000052C14D003D8012C09D0002070BD282C81 -:1008E00009D0302CF9D10BA3D3E90023ECE70BA3FB -:1008F000D3E90023E8E70BA3D3E90023E4E70BA344 -:10090000D3E90023E0E700BFAFF30080401DA12042 -:1009100026812A0B78F6339F93CACD8D9E6AC42117 -:10092000818A46EE26417272DF25D7B7F017304A2A -:1009300039059E5638B504460D4603462022284602 -:10094000002101F09BFB22792346032A28BF0322C2 -:1009500003F8042F28460222202101F08FFB627940 -:100960002346072A28BF072203F8052F284603221B -:10097000222101F083FBA2792346072A28BF072200 -:1009800003F8062F28460322252101F077FB28468D -:1009900004F108031022282101F070FB382038BD33 -:1009A0002DE9F04FADF5017D21AE0EAD40F279128B -:1009B00080460F463046002100F014FD48220021F9 -:1009C000284600F00FFD00F0CBFD594B4FF47A7232 -:1009D000B0FBF2F0186093E80700012385E80700F8 -:1009E0002B740DF15A0000236B74FFF709FF0323EA -:1009F00085F82030F82385F8213007AB18464D499B -:100A000003F0D8F9192228643146284685F83C209D -:100A1000FFF790FF12AB044601460822304601F072 -:100A20002DFB0822A1180DF14903304601F026FBE9 -:100A30000DF14A03082204F11001304601F01EFBBB -:100A400013AB202204F11801304601F017FB14AB60 -:100A5000402204F13801304601F010FB16AB0822A9 -:100A600004F17801304601F009FB0DF15903082229 -:100A700004F18001304601F001FB04F1880A0DF118 -:100A80005A0904F5847B4B465146082230460AF148 -:100A9000080A01F0F3FAD34509F10109F3D11BABC0 -:100AA00008225946304601F0E9FA04F588744FF0FF -:100AB000000995F834304B4510D84FF0000995F8EF -:100AC0003C304B4515D92B6C21464B44082230460F -:100AD00001F0D4FA083409F10109F0E7AB6B2146C3 -:100AE0004B440822304601F0C9FA083409F10109E3 -:100AF000DFE7E31DC3F3CF03F97E059300230496DC -:100B00000393BB7E0293193701230093019706A339 -:100B1000D3E90023404601F081F80DF5017DBDE8E1 -:100B2000F08F00BFAFF300809E6AC421818A46EE39 -:100B300088110020F43E0008014B1870704700BF78 -:100B400094110020F0B5334B1C7B85B034B1324B8F -:100B50000E221A810024204605B0F0BD2F4A1068ED -:100B6000516802AB03C308230DEB03022C492D4847 -:100B700003F0BEF8054630B9274B2B480A221A81EC -:100B800000F0A4FCE6E70169B1F5663F06D9224B07 -:100B900026480B221A8100F099FCDCE7438BB3F561 -:100BA0007E7F09D01C4A22480C2111814FF47E72AD -:100BB000194600F08BFCCEE71E4A024402F11003F6 -:100BC000994204D2144B1C4810221A81E3E71039D1 -:100BD0008E1A2046134900F0C7FC3246074605F13D -:100BE0001801204600F0C0FCAB689F4202D1EB68C0 -:100BF00098420AD0084B0D221A8100903B46EA68C1 -:100C0000A9680E4800F062FCA4E70D4800F05EFC05 -:100C10000124A0E7C821002088110020C43D00085D -:100C2000DC97030000680008CC3D0008D83D0008B0 -:100C3000EA3D00080898FFF7083E0008253E000836 -:100C40004E3E00082DE9F04FADB006AF80460C4691 -:100C500000F08AFF054600286AD1237E022B18D1B6 -:100C6000E38A012B15D100F07BFC8146FFF7B0FD34 -:100C70004FF4C873BD4EB0FBF3F209F5167902FBD1 -:100C80001300E37E19FA80F030608BB9B84B002274 -:100C90001A709C37BD46BDE8F08F3B1D1D44009582 -:100CA000002308224FEAC901204601F04BF84D46C7 -:100CB000A38A013BAB425FFA85F90BD905F1010923 -:100CC000B9F1110FE9D1AB4BAB4A40F23911AB4846 -:100CD00002F0E0FF07F11400FFF792FD2A4607F14A -:100CE0001401381D02F0F4FF03460028CED1B9F1FB -:100CF000100F07D09E4B83F800903368A3F516734E -:100D00003360C6E707F19802014602F8950D2046C8 -:100D10000092072201F016F8F9787F2904DD984B3C -:100D2000954A4FF4A871D2E7404600F001FFB0E7C2 -:100D3000E38A052B00F0068106D8012BA9D12146B4 -:100D40004046FFF72DFEA4E7282B3DD0302BA0D145 -:100D5000637E8C4D01336A7BDBB29342E94640F0FF -:100D6000EF80E27E2B7B9A4240F0EA8007F1980305 -:100D7000002623F8846D102200933146012320467B -:100D800000F0E0FFB4F81480A8F102081FFA88F818 -:100D900008F1030323F003030A3323F00703ADEB49 -:100DA000030D0DF1180A33469BB2B11C98454FEA6A -:100DB000C10106F101066CDD5344009308220023B3 -:100DC000204600F0BFFFEEE7A38A013B9BB2C92B90 -:100DD0003FF65FAF6B4E357B4DBB06F10C030093C6 -:100DE00008222B462946204600F0ACFFA38A05F1D5 -:100DF0000109013BEDB29D424FEAC90109DA0E3506 -:100E00003544009500230822204600F09BFF4D4604 -:100E1000ECE700230022C6E900230023B36086F834 -:100E2000D730C6F8D830337B0BB9E37E3373002557 -:100E300007F114063B1D0822294630467D60BD603F -:100E4000FD6001F01BF93B7A05F10109AB424FEA65 -:100E5000C90107D9FB6808222B44304601F00EF97E -:100E60004D46F0E7C1F3CF010023E07E05910496E3 -:100E70000393A37E0293193428230146009301941F -:100E800038A3D3E90023404600F0C8FEFFF7C8FCB2 -:100E9000FFE695F8D70000F059FAD5F8D8300646A5 -:100EA0001BB995F8D70000F061FAD5F8D830434463 -:100EB0009E4204D295F8D700013000F057FA4FEA6D -:100EC000980B0024A0B2584504F1010408DA2B68FD -:100ED00080000AEB00010122184400F08BFAF1E7D0 -:100EE000D5E90023D5F8D84095F8D70012EB0802D1 -:100EF00043F100034444C5E90023C5F8D84000F09D -:100F000025FA844209D395F8D730013385F8D730D4 -:100F1000D5F8D8309E1BC5F8D860B8F1FF0F08DCB3 -:100F200000232B7300F034FAFFF70CFE08B1FFF733 -:100F300003FC2B68144A9B0A013313810023AB6026 -:100F4000CD46A6E6BFF34F8F1049114BCA6802F495 -:100F5000E0621343CB60BFF34F8F00BFFDE700BFDC -:100F6000AFF3008026417272DF25D7B79C210020A5 -:100F700099210020603E0008103F0008B93E00089B -:100F8000DB3E0008C82100208811002000ED00E0B1 -:100F90000400FA0508B54FF000530B4A1968914256 -:100FA0000AD10A4A597D117009481B7D0373C92271 -:100FB00008490E3000F004FAE02200214FF0005002 -:100FC000BDE8084000F00EBA9AAD44C59411002067 -:100FD000C82100201600002030B5204C20492148AF -:100FE00085B00223637104230025ADF80830012386 -:100FF000ADF80C5007228DF80C308DF80B301A4BE1 -:101000004B608DF80A2001F023FE184B01950093E8 -:101010001749184B18484FF4805200F053FD174BF6 -:101020001978254611B1144800F082FD00F098FAB5 -:101030000446FFF7CDFB4FF4C87304F51674B0FBFC -:10104000F3F202FB13000E4B14FA80F0186002F06A -:10105000A3FB08B10F232B8105B030BD8811002000 -:10106000001100201823002003000600AD0800082E -:1010700098110020450C0008A021002094110020A8 -:101080009C2100202DE9F04F94A7D7E900670FF2CB -:101090005429D9E900898D4C93B0DFF850B2DFF8BC -:1010A00050A2204600F006FE0CAD079098B3102227 -:1010B0000021284600F096F9079B197B4FF00002AB -:1010C00061F3030219468DF8302051F8040F496886 -:1010D0000EAA03C21B680D9A63F31C029DF8303000 -:1010E0000D9243F020038DF8303000232A46194634 -:1010F000584601F0BDFD079030B9204600F0DEFDF6 -:10110000079B8AF80030CCE79AF80030072B3EDCCA -:1011100001338AF8003018220021284600F062F9D5 -:10112000DFF8C8A1002319462A46504601F0C8FD41 -:10113000014680BB102208A800F054F94FF09042FD -:10114000536983F04003536100F00CFA0B4612A977 -:10115000024611E903000DF1240E8EE803009DF80C -:101160003410C1F3030089064CBF0E99BDF8381046 -:101170008DF82C0046BFC1F31C0141F00041C1F3C2 -:101180000A010891204608A900F0DEFFCAE72046C0 -:1011900000F094FDBFE7204600F0E6FC8246002800 -:1011A0004AD1DFF850B100F0DBF9DBF800309842AB -:1011B00042D300F0D5F90790FFF70AFB079A8DF8A4 -:1011C00020A04FF4C87302F51672B0FBF3F101FBD7 -:1011D000130012FA80F0CBF80000DFF81CB19BF886 -:1011E000001011B901238DF8203028460791FFF730 -:1011F00007FB0799C1F1100A5FFA8AFABAF1060FE4 -:1012000028BF4FF0060A524629440DF1210000F094 -:10121000D7F80AF10103049308AB03931823029350 -:101220002B4B01930123009332463B46204600F0AE -:101230009DFC00238BF8003000F092F9254ADFF87E -:10124000BCA01368C31AB3F57A7F32D3106000F0E4 -:1012500089F902460B46204600F036FD204600F094 -:1012600083FC30B39AF80C30DFF894B0002B14BF35 -:10127000032302238BF8053000F072F94FF47A73E0 -:101280002946B0FBF3F0CBF800005846FFF752FBBD -:10129000182307300293104B0193C0F3CF0040F2A4 -:1012A000551304900093039542464B46204600F0A8 -:1012B0005DFC9AF80C300BB1FFF7B2FA9AF80C30DB -:1012C000002B7FF4EAAE13B0BDE8F08FA021002020 -:1012D00098210020A8220020AC220020401DA1203F -:1012E00026812A0BF1C6A7C1D068080F1823002059 -:1012F000AD2200209C21002099210020C82100203F -:101300008811002070B502F0E3F8094C094E2070F6 -:10131000002530682378834208D902F0D5F8336875 -:1013200005440133B5F5D04F3360F2D370BD00BF33 -:10133000DC220020B022002002F062B900F100603F -:10134000920000F5D04002F007B90000054B1A6882 -:10135000054B1B789B1A834202D9104402F0B4B8A3 -:1013600000207047B0220020DC22002038B5074D55 -:1013700004462868204402F0ADF828B928682044C3 -:10138000BDE8384002F0B8B838BD00BFB022002038 -:10139000064991F8243033B100230822086A81F805 -:1013A0002430FFF7CBBF0120704700BFB4220020DC -:1013B000022802BF4FF090434FF480029A617047B9 -:1013C00010B50023934203D0CC5CC4540133F9E739 -:1013D00010BD000002460346981A13F9011B0029AC -:1013E000FAD1704702440346934202D003F8011B2E -:1013F000FAE770472DE9F047234C94F8243005466E -:101400008846174683BB2E46DFF87C90C7B394F816 -:1014100024302BB92022FF2148462662FFF7E2FF45 -:1014200094F82400C0F10805BD4228BF3D465FFA8C -:1014300085FAAD0041462A4604EB8000FFF7C0FF65 -:1014400094F82430A7EB0A079A445FFA8AFABAF1B3 -:10145000080F2E44A844FFB284F824A0D6D1FFF789 -:1014600097FF0028D2D108E0266A06EB8306B04237 -:10147000CAD0FFF78DFF0028C5D10020BDE8F08756 -:101480000120BDE8F08700BFB422002070B50C4CED -:101490001C26324600212046FFF7A4FF4823237074 -:1014A0000125084B6360657032460021A019FFF7E3 -:1014B00099FF49232377044B6577236270BD00BFF2 -:1014C000E022002002040048060400480FB4002077 -:1014D00004B070470FB44FF0FF3004B07047000005 -:1014E000FEE7000000B59BB0EFF309816822684673 -:1014F000FFF766FFEFF30583034B9A6B9A6A9A6ACC -:101500009A6A9A6A9B6AFEE700ED00E000B59BB01C -:10151000EFF3098168226846FFF752FFEFF3058376 -:10152000044B9A6B9A6A9A6A9A6A9A6A9A6A9B6A4E -:10153000FEE700BF00ED00E000B59BB0EFF30981CE -:1015400068226846FFF73CFFEFF30583034B5A6BB5 -:101550009A6A9A6A9A6A9A6A9B6AFEE700ED00E0C4 -:1015600002F086B802F060B830B5084D0A449142E6 -:101570000BD011F8013B09245840013CF7D040F34F -:1015800000032B4083EA5000F7E730BD2083B8ED1D -:101590000246006848B103681360D388118901339B -:1015A0009BB29942D38038BF1381704770B588B021 -:1015B0000D460446202200216846FFF713FF20460F -:1015C0000495FFF7E5FF054658B16B46044608AEA3 -:1015D0001A4603CAB24220606160134604F108044F -:1015E000F6D1284608B070BD2DE9F04130B9274B3F -:1015F000274A40F2C531274802F04CFB0B7C23B947 -:10160000254B234A40F2C631F5E7C66986B9C16168 -:10161000BDE8F081002B29DA930CAB4229D1B4420A -:1016200001D10C60F3E7C8F800100C60BDE8F08150 -:101630004B6823F06047BD0C4FEAD37EC3F3807C38 -:1016400015EA230538BF3D46B04634466368BEEB15 -:10165000D37F23F06042DDD1974203D1C3F380737F -:101660009C450AD1974205E01C46EFE7AA4206D006 -:1016700013469D422CBF00230123002BCFD12368AA -:10168000A046002BF0D12160BDE8F081E4410008C4 -:10169000D83F00089C420008BD42000808B5034A34 -:1016A000034B044840F25E3102F0F4FAB43F000804 -:1016B0005C4200089C42000808B503680B60C388C0 -:1016C000016033B9044B054A05484FF4C76102F085 -:1016D000E1FA013BC38008BD2C4200082840000805 -:1016E0009C42000870B50C4600F10C05616831B9E8 -:1016F000E38A61F30903E3820020002170BD0E68D4 -:101700002846FFF7D9FF6660F0E7000008B5426899 -:1017100032B10B4B0B4A0C4840F22F4102F0BAFA9F -:10172000C37DC3F38401013161F38603C375C38AAA -:1017300062F30903C3821B0A62F3C713C37508BDB2 -:1017400078420008E43F00089C4200082DE9F04779 -:10175000089E32B91F4B204A204840F2395102F00E -:1017600099FA01F007054FEAD6082A4406F0070661 -:1017700000EBD1004FF47F49954201D1BDE8F087DD -:1017800005F0070E06F0070AD645774638BF5746DC -:10179000C7F10807511BEC088F4228BF0F46045DB4 -:1017A00008EBD60104FA0EF413F801C029FA07FE7B -:1017B00024FA0AF45FFA8EFE8CEA04044EFA0AFE5A -:1017C00004EA0E048CEA040C03F801C03D443E44D4 -:1017D000D2E700BFF8410008FC3F00089C42000827 -:1017E0002DE9F04106460F4600254FF6FF7441F201 -:1017F00021082A4630463946FEF7D6FCC0B284EAB4 -:101800000024082314F4004F4FEA4404A4B203F167 -:10181000FF3318BF84EA080413F0FF03F2D1083540 -:10182000402DE6D12046BDE8F081000010B50A4405 -:1018300041F22104914200D110BD11F8013B80EA30 -:101840000320082310F4004F4FEA400080B203F158 -:10185000FF3318BF604013F0FF03F3D1EAE7000045 -:101860002DE9F04F85B08A468DE80C00BDF83C406C -:10187000814630B9494B4A4A40F26E31494802F03C -:1018800009FA11F0604F04D0474B454A40F26F31DE -:10189000F4E7009B002B7ED024B10E9B002B7AD066 -:1018A000072C28D809F10C00FFF772FE054628B96D -:1018B0006FF00205284605B0BDE8F08F1422002124 -:1018C000FFF790FD22460E9905F10800FFF778FD1D -:1018D000631C2B74009B1B782C4403F01F0363F0E4 -:1018E0003F0323724AF000436B6029464846FFF7E6 -:1018F0007BFE0125DEE7019B1B0A4FF000080293E7 -:1019000000F10C034FF0800B4646454603930398C5 -:10191000FFF73EFE07460028CAD014220021FFF739 -:1019200061FDB6BB9DF804303B729DF808307B72B8 -:1019300002220E9B711E1944B4420AD9B818013212 -:10194000D2B211F801EF80F808E00136072AB6B2EA -:10195000F2D1009B197801F01F01B44208BF4FF08B -:10196000400BB81841EA48114BEA010303720132F7 -:101970004AF000437B603A7439464846FFF734FE2C -:101980000135B4422DB288F001084FF0000BBED1F2 -:1019900090E70022CDE76FF001058BE7E4410008F6 -:1019A000C83F00089C420008084200082DE9F047A3 -:1019B0001E46CB8A9146C3F30902062A80460F468B -:1019C00019D013460021B0B28DB25A1992B2052A2D -:1019D00009D9A84210D8FA8A034463F30902FA82AB -:1019E0000120BDE8F087A842F3D93A4419F8014034 -:1019F00094760131E8E70025FB8A7C68C3F309008F -:101A0000821F1C23B2FBF3FA03FB1A2A1FFA8AF285 -:101A10007CB301212368002B39D1B31F03441C2060 -:101A2000B3FBF0F301339BB299420CD2BAF1000F31 -:101A300009D14046FFF7ACFD08B1C0F800A0206016 -:101A400008B304460022B6B24FF0000AB54230D2C5 -:101A5000691E49441346E01801339BB211F801EFA7 -:101A600080F804E001351C2BADB214D0AE42F2D8A0 -:101A7000ECE74046FFF78CFD044608B10023036005 -:101A80007C60002CDED16FF00200BDE8F0870131F0 -:101A900089B21C46BEE7AE42D8D94046FFF778FD72 -:101AA00008B1C0F800A020600028ECD00446002255 -:101AB000CCE7FB8AC3F30902164466F30903FB82F1 -:101AC0008EE70000F8B50E4615461F46044628B9B5 -:101AD000144B154A15484F2102F0DCF8242200214E -:101AE000FFF780FC069B6360079B23626A094FF641 -:101AF000FF739A424FF0000028BF1A46A76020707B -:101B0000A061E06197B204F10C05824205D1002387 -:101B10002B6027826382A382F8BD2E600130354698 -:101B20002036F2E7E0410008543F00089C420008DC -:101B300008B528B9084B094A7321094802F0AAF8E8 -:101B4000037823B94BB2002B01DD017008BD054BB2 -:101B5000024A7D21F1E700BFE4410008603F000830 -:101B60009C42000828410008007870472DE9F7439F -:101B70000D9EBDF828900B9D9DF83040BDF8388033 -:101B800007461946104616B9B8F1000F43D11F2C6D -:101B900041D83B78D3B9B8F1070F39D839F00303EE -:101BA00039D1424631464FF6FF70FFF73FFE4FEA0C -:101BB000092920F0010009F44079400449EA04644D -:101BC000400C44EA40244FF6FF730DE043EA09233A -:101BD000B8F1070F43EA0464F5D9FFF701FE424666 -:101BE0003146FFF723FE03468DE840012A46214691 -:101BF0003846FFF735FE0DB9FFF750FD2B7801335E -:101C0000DBB21F2B88BF00232B7003B0BDE8F0832D -:101C10006FF00300F9E76FF00100F6E72DE9F743F5 -:101C20000E9F0B9D9DF83480BDF83C6081469DF869 -:101C3000300007B9C6BB1F2836D899F800E0BEF1BE -:101C4000000F34D00C0244F080049DF8281044EAC0 -:101C5000C83444EA014444EA0E04072E44EA00640E -:101C600015D919461046FFF7BBFD32463946FFF736 -:101C7000DDFD0346019600972A4621464846FFF7B8 -:101C8000EFFDB8F1010F0CD125B9FFF707FD4FF6B5 -:101C9000FF73EFE72B780133DBB21F2B88BF0023E4 -:101CA0002B7003B0BDE8F0836FF00100F9E76FF02F -:101CB0000300F6E7C06900B104307047C1690B68E2 -:101CC000C3610C30FFF7F8BC2DE9F84FD0F818A02D -:101CD000DFF86C80054616461F4654464FF0000953 -:101CE00000F10C0B0CB9BDE8F88FD4E90223B21A4D -:101CF00067EB0303994508BF90451FD2AB699C422F -:101D0000214628460DD1FFF7EDFCAB691B68AB619E -:101D100021465846FFF7D0FCAC692346A2461C4634 -:101D2000E0E7FFF7DFFC2368CAF800302146584699 -:101D3000FFF7C2FC5446DAF80030EFE72368EDE71E -:101D400080841E002DE9F04F8BB00D46144607939A -:101D5000DDF850908246002800F06481B9F1000F50 -:101D600000F06081531E3F2B00F25C81012A03D1F9 -:101D7000079B002B40F05681BAF81460F600002350 -:101D8000B5420893099380F053812B199E420AD2E1 -:101D9000761B16F0FF0607D1AB4BAC4A40F26751F9 -:101DA000AB4801F077FF2646DAF80C3023B9DAF8B1 -:101DB0001030002B00F0A5802F2D31D8C5F1300850 -:101DC00046454FF000032CBF5FFA88F8B0460093F9 -:101DD000294608AB4246DAF80800FFF7B7FCA6EB45 -:101DE00008074544FFB2BAF8143003F10053063B2C -:101DF000DB000293DAF80C3005934FF0300B059BB3 -:101E0000002B51D087B9DAF81000002861D0002FDC -:101E10005FD0AB4550D98F4B8C4A40F2A651BFE7FB -:101E200037464FF00008DEE7029B23B98A4B874A0A -:101E30004FF4B161B4E7029BE02B28BFE023069387 -:101E40005B44AB4204931DD95B1B9F4226BFDBB2B0 -:101E500003930397AB4504D97E4B7C4A40F29151E2 -:101E60009EE70598CDF8008008ABA5EB0B01039A1F -:101E70000430FFF76BFC039B9844FF1A1D445FFA84 -:101E800088F8FFB2049B9B4504D3744B6F4A40F221 -:101E90009B5185E7029B069ADDF810B09B1A0293CE -:101EA000059B1B680593AAE7029BBB42ABD26C4B18 -:101EB000664A40F2A15173E7CDF800803A46A5EB9F -:101EC0000B0108ABFFF742FCB8443D445FFA88F8C9 -:101ED0000027BAF81430B5EBC30F04D9614B5B4A45 -:101EE00040F2B1515CE7B8F1400F04D95E4B574A5C -:101EF00040F2B25154E767B15C4B544A40F2B351DF -:101F00004EE70093324608AB2946DAF80800FFF79F -:101F10001DFC731E3F2B35B201D8A64204DD544B85 -:101F2000544A40F235213BE760070AD00AAB03EB85 -:101F3000D401624211F8083C02F00702134101F893 -:101F4000083C082C21D9102C21D9202C8CBF082327 -:101F50000423079A002A6DD0B4EBC30F6CD0082C71 -:101F600004F1FF3215D89DF8203023FA02F2D10790 -:101F700006D54FF0FF3202FA04F423438DF82030E7 -:101F80009DF8203089F800304EE00123E1E702237C -:101F9000DFE7102C11D8BDF8203023FA02F2D20767 -:101FA00006D54FF0FF3202FA04F42343ADF8203097 -:101FB000BDF82030A9F8003036E0202C0ED8089962 -:101FC00021FA02F2D30705D54FF0FF3303FA04F4E8 -:101FD0000C430894089BC9F8003025E0402C1CD025 -:101FE000DDE9086730463946FEF7DEF8002100F0EB -:101FF000010050EA01030BD0224601200021FEF728 -:10200000DFF8404261EB410106430F43CDE9086729 -:10201000DDE90823C9E9002306E0174B154A4FF410 -:102020002071BDE66FF0010528460BB0BDE8F08FCA -:102030001D46F9E7012CA3D0082CA1D9102CB7D943 -:10204000202CE5D8C6E700BF344000080C4000084B -:102050009C42000856400008434000087B400008AE -:10206000A3400008CA400008F840000810410008DA -:102070002A4100088C3F00082841000830B585B08F -:1020800030B9244B244A40F2B121244801F002FE29 -:1020900023B9234B204A40F2B221F6E7402A04D963 -:1020A000204B1D4A40F2B621EFE722B91D4B1A4AD8 -:1020B0004FF42F71E9E70024012A0294039417D109 -:1020C0001B788DF8083053070AD004AB03EBD2031A -:1020D000554213F8084C05F00705AC4003F8084CCE -:1020E00000910346002102A8FFF730FB05B030BD88 -:1020F000082AE5D9102A03D81B88ADF80830E2E792 -:10210000202A02D81B680293DDE7D3E90045CDE918 -:102110000245D8E764410008A03F00089C4200083F -:102120007F4100082841000870B50C4600F10C05FD -:10213000E16819B9A1602161A18270BD0E682846CD -:10214000FFF7BAFAE660F3E72DE9F04FD1F8009017 -:1021500091B0C9F3C01604460D46CDE90223002E06 -:1021600050D0C9F3C03BC9F30626B9F1000F80F285 -:102170009F8119F0C04F40F09B812B7B002B00F01A -:102180009781BBF1020F03D02278B24240F09381D5 -:1021900009F07F02BBF1020F059236D119F07F0FD3 -:1021A000C9F30F2A01D10AF0030A2B447606059AD7 -:1021B00093F8038046EA0B4646EA82465FEAD81364 -:1021C00046EA0A06069300F09A800022002310A92E -:1021D00061E90823059B009367685B4652462046E9 -:1021E000B847002800F08880A7698FB9314604F10C -:1021F0000C00FFF7DBF90746D0B96FF0020011B011 -:10220000BDE8F08F4FF0020BAFE7C9F3074ACCE708 -:102210003B699E420DD03F68002FF9D1314604F151 -:102220000C00FFF7C3F907460028E6D0A3693B601E -:10223000A761DDE90801FFF7D3FAB882F97D08F05C -:102240001F06C1F38401711A89B20FFA81FED7E922 -:102250000223BEF1000FB8BF01F1200EC9F30461E3 -:10226000B8BF0FFA8EFE079152EA030100F02F81EA -:10227000DDE90201801A61EB030102460B469F482B -:102280000021994208BF9042C0F02181069B002B9B -:102290003FD0BEF1010F00F31A8118F0400F38D083 -:1022A000DDE90223C7E90223202200210DEB020011 -:1022B000FFF798F8DDE90223CDE908232B1D0A93E7 -:1022C0002B7BADF836A0013BDBB2ADF834309DF886 -:1022D0001C308DF83A309DF814308DF83B30204694 -:1022E0008DF838B08DF83960A36808A9984738464A -:1022F000FFF70CFA002082E76FF00B007FE7A76979 -:1023000017B96FF00C007AE73B699E4296D03F68A0 -:10231000F6E7FB7DC8F34012B2EBD31F40F0CE804E -:10232000C3F38403B34240F0CC8006992B7B4FEA81 -:10233000981279B3D2073CD4032B40F2C580DDE973 -:102340000223C7E902232B7BAE1D033BDBB23246DF -:10235000394604F10C00FFF729FB002808DA39465A -:102360002046FFF7BFF93846FFF7D0F9032046E7CC -:10237000AB883B832A7B033AD2B2B88A3146FFF757 -:1023800055FAFB7DB882DA43C2F3C01262F3C71379 -:10239000FB75AFE76AB92E1D013BDBB23246394609 -:1023A00004F10C00FFF702FB0028D8DB2A7B013A7E -:1023B000E2E7FA8AC2F30902013B052AD9B250D8F2 -:1023C000281D002399420AD907EB020E013210F8AA -:1023D00001CB8EF81AC00133062ADBB2F2D1DDE957 -:1023E00002898B4207F11A02CDE908890A9238BFA7 -:1023F00004337A680B9234BF5B1900230C93FB8A79 -:10240000ADF836A0C3F3090319449DF81C308DF8CC -:102410003A309DF814308DF83B300023ADF834107D -:102420008DF838B08DF839607B602A7BB88A013A24 -:10243000291DFFF7FBF93B8BB882834203D1A368C8 -:1024400008A92046984708A92046FFF76DFE3846A0 -:10245000FFF75CF9B88A3B8B984214BF112000202B -:10246000CDE6786810B34FF0060E03689BB9A2EB77 -:102470000E021B2A13D80332024405F1040E1F304A -:102480009942ACD91EF801CB02F801CF013390423A -:10249000DBB2F5D1A3E70EF11C0E1846E5E7184BA9 -:1024A000184A194840F2B31101F0F4FB034696E7CD -:1024B0006FF00900A3E66FF00A00A0E66FF00D00D0 -:1024C0009DE66FF00E009AE66FF00F0097E6FB7D39 -:1024D00068F386036FF3C713FB7539462046FFF791 -:1024E00001F9069B002B7FF4D8AEFB7DC3F3840279 -:1024F000013262F38603FB7503E700BF80841E0090 -:1025000094410008783F00089C4200082DE9F04102 -:102510004C4EB04240F081804B4CDFF830E1E56931 -:1025200045F00075E561E469846AD4F8007207EA51 -:102530000E0747F00107C4F80072D4F8005205EA0C -:102540000E0545F0010545EA0121C4F80012002AF4 -:1025500065D00021C4F81C120F46C4F80412C4F858 -:102560000C12C4F8141204EBC10501310E29C5F890 -:102570004072C5F84472F6D14FF0000E4FF0010CD6 -:10258000964510D1826AD2F80032B04223F001039E -:10259000C2F8003253D12C4BDA6922F00072DA61B2 -:1025A000DB69BDE8F0819F781D8817F0010F18BF27 -:1025B000D4F804820CFA05F11CBF41EA0808C4F8FB -:1025C000048217F0020F1EBFD4F80C8241EA0808FB -:1025D000C4F80C827F0742BFD4F814720F43C4F8CA -:1025E000147204EBC5055F68C5F840729F68C5F8B2 -:1025F0004472D4F81C522943C4F81C120C330EF157 -:10260000010EBDE7846A0021C4F81C12C4F804124C -:10261000C4F80C12C4F81412AEE7002AF2D1836A8F -:102620000022C3F84022C3F84422C3F80422C3F8AE -:1026300014220122C3F80C22C3F81C22A2E7BDE831 -:10264000F08100BF18230020001002400000FFFFAF -:10265000184A916A08B58B688B6013F0010105D0A8 -:1026600013F00C0F14BF4FF480310121D80506D5AB -:1026700013F4406F14BF41F4003141F00201D8035C -:1026800006D513F4402F14BF41F4802141F004011A -:10269000D3690BB107489847202383F311880021A1 -:1026A000054800F087FE002383F31188BDE8084049 -:1026B00001F088B8182300202023002038B5124CE0 -:1026C000A36ADD68AA0712D05A6922F002025A6191 -:1026D000A36913B1012120469847202383F3118871 -:1026E00000210A4800F066FE002383F31188EB0600 -:1026F00006D5A36A1021D960236A0BB10248984716 -:10270000BDE8384001F05EB81823002028230020DF -:1027100038B5124CA36A1D69AA0712D05A6922F073 -:1027200010025A61A36913B1022120469847202361 -:1027300083F3118800210A4800F03CFE002383F354 -:102740001188EB0606D5A36A10211961236A0BB123 -:1027500002489847BDE8384001F034B818230020FB -:102760002823002038B50F4CA36A5D685D602A07F6 -:102770000AD5032222701A6822F002021A60636AE4 -:1027800013B10021204698476B0706D5A36A9969C3 -:10279000236A13B1090403489847BDE8384001F0A3 -:1027A00011B800BF1823002010B50F4C204600F0D0 -:1027B0003DFA0E4BA3620B21132000F017FA0B21F8 -:1027C000142000F013FA0B21152000F00FFA0B2152 -:1027D000162000F00BFA002320461A460E21BDE811 -:1027E0001040FFF793BE00BF182300200064004094 -:1027F0000F4B984210B5044605D10E4BDA6942F0F2 -:102800000072DA61DB69A36A01221A60A36A5A685E -:10281000D20707D5626851681268D9611A60064A02 -:102820005A6110BD0121082000F07CFCEEE700BFDA -:1028300018230020001002405B87010003291AD8EA -:10284000DFE801F0020A0F14836A9B6813F0E05F6F -:1028500014BF012000207047836A9868C0F380602D -:102860007047836A9868C0F3C0607047836A98684D -:10287000C0F30070704700207047000010B50329B6 -:102880001FD8DFE801F0021F2327816A8B68C3F39A -:102890000163183301EB0313107881061ED55468C9 -:1028A000C0F30011490041EAC40141F0040100F005 -:1028B0000F00586090689860D268DA6041F00101BA -:1028C000196010BD836A03F5C073E5E7836A03F5F9 -:1028D000C873E1E7836A03F5D073DDE79488C0F33A -:1028E0000011490041EA4451E1E7000001290CD000 -:1028F00003D3022910D000207047836ADA68920758 -:1029000001D1186903E001207047836AD86810F08C -:10291000030018BF01207047836AF2E710B539B988 -:10292000836AD96889071BD11B699B0704D110BD35 -:10293000012915D0022948D1816AD1F8C031D1F8D6 -:10294000C401D1F8C8411461D1F8CC4154612024AC -:102950000C610C69A40717D14C6944F0100412E013 -:10296000816AD1F8B031D1F8B401D1F8B84114611D -:10297000D1F8BC4154612024CC60CC68A40703D1B9 -:102980004C6944F002044C6111795C0864F3041151 -:102990009C0864F34511117189064BBF9168118938 -:1029A000DB085B0D4CBF63F31C0163F30A01137971 -:1029B00048BF916060F3030313714FEA10234FEA9D -:1029C000104058BF11811370508010BD002304497E -:1029D0001A465A50C8180833802B4260F9D1704704 -:1029E00044230020026843681143016003B1184783 -:1029F00070470000024A136843F0C0031360704739 -:102A000000440040024A136843F0C003136070475B -:102A1000004800402DE9F047C66D3768F46934621C -:102A20000546200719D014F0080F0CBF00218021A3 -:102A3000E20748BF41F02001A30748BF41F0400131 -:102A4000600748BF41F48071202383F31188281D5B -:102A5000FFF7C8FF002383F31188E2050AD520237E -:102A600083F311884FF40071281DFFF7BBFF00238B -:102A700083F311884FF020094FF0000A14F020086A -:102A800031D13B0616D54FF0200905F1380A200652 -:102A900010D589F31188504600F04CFA00282FDA3F -:102AA0000821281DFFF79EFF27F0800333600023D5 -:102AB00083F3118879060DD562060BD5202383F3A5 -:102AC0001188EA6C2B6D9A4201D12B6CF3B900236B -:102AD00083F31188E30621D5AA6E1369F3B1506917 -:102AE000BDE8F047184789F31188B38C95F8641056 -:102AF0002846194000F0AAFA8AF31188F469BDE764 -:102B000080B2308588F31188F469C0E71021281D50 -:102B100027F04007FFF766FF3760D8E7BDE8F0878A -:102B200008B50348FFF776FFBDE8084000F04ABE4D -:102B3000C423002008B50348FFF76CFFBDE8084038 -:102B400000F040BE3024002037B51D4C1D4D2046FE -:102B500000F070FA009404F11400002320221A49B6 -:102B600000F032F92022009404F13800174B184984 -:102B700000F0ACF9174BE3652566174C0C212620B5 -:102B800000F034F8204600F055FA04F114000094E7 -:102B900000232022114900F017F904F138000094B5 -:102BA0000F4B1049202200F091F90F4BE3650C21E7 -:102BB0002720256603B0BDE8304000F017B800BFFD -:102BC000C4230020005125029C240020F529000880 -:102BD000DC2400200044004030240020BC240020DD -:102BE000052A0008FC2400200048004000F1604352 -:102BF00000F01F02400903F5614309018000C9B2DA -:102C000000F1604083F8001300F561400123934018 -:102C1000C0F880310360704700F16040090100F5A1 -:102C20006D40C9B201767047FFF7BEBD00F10802E2 -:102C30000123037082600023C26000F11002436030 -:102C4000026142618361C3610362436270470000B5 -:102C500010B52023044683F31188022303704160DA -:102C6000FFF7C6FD03232370002383F3118810BDF3 -:102C70002DE9F0411F4604460D461646202383F3F6 -:102C8000118800F108082378042B0ED0294620462D -:102C9000FFF7D4FD48B1204632462946FFF7EEFD46 -:102CA000002080F31188BDE8F0813946404600F0ED -:102CB00065FB0028E7D0002383F31188BDE8F0818D -:102CC0002DE9F0411F4604460D461646202383F3A6 -:102CD000118800F110082378042B0ED029462046D5 -:102CE000FFF704FE48B1204632462946FFF716FE9C -:102CF000002080F31188BDE8F0813946404600F09D -:102D00003DFB0028E7D0002383F31188BDE8F08164 -:102D1000F8B5154682680669AA420B46816938BF34 -:102D20008568761AB542044607D218462A46FEF749 -:102D300047FBA3692B44A3610DE011D93246184625 -:102D4000FEF73EFBAF1B3A46E1683044FEF738FB26 -:102D5000E2683A44A261A3685B1BA3602846F8BD01 -:102D600018462A46FEF72CFBE368E4E783682DE962 -:102D7000F041044693421546266938BF856840698C -:102D8000361AB5420F4606D22A46FEF719FB63698A -:102D90002B4463610DE012D93246A5EB0608FEF71D -:102DA0000FFB4246B919E068FEF70AFBE2684244AD -:102DB0006261A3685B1BA3602846BDE8F0812A46D8 -:102DC000FEF7FEFAE368E4E710B50A440024C361A5 -:102DD000029B006040608460C1608161416102616A -:102DE000036210BD08B582694369934201D18268CC -:102DF00082B98268013282605A1C4261197042694C -:102E000003699A4201D3C3684361002100F0C6FA06 -:102E1000002008BD4FF0FF3008BD000070B5202332 -:102E200004460E4683F31188A568A5B1A368A2697C -:102E3000013BA360531CA36115782269934224BF10 -:102E4000E368A361E3690BB120469847002383F34D -:102E50001188284670BD3146204600F08FFA0028C0 -:102E6000E2DA85F3118870BD2DE9F74F05460F466C -:102E700090469A46D0F81C90202686F311884FF091 -:102E8000000B144664B1224639462846FFF740FF3E -:102E9000034668B95146284600F070FA0028F1D080 -:102EA000002383F31188A8EB040003B0BDE8F08F82 -:102EB000B9F1000F03D001902846C847019B8BF35E -:102EC0001188E41A1F4486F31188DBE7C160816131 -:102ED0004161C3611144009B0060406082600161F8 -:102EE00003627047F8B504460E461746202383F365 -:102EF0001188A568A5B1A368013BA36063695A1C4A -:102F000062611E70236962699A4224BFE36863614B -:102F1000E3690BB120469847002080F31188F8BD83 -:102F20003946204600F02AFA0028E2DA85F31188B3 -:102F3000F8BD0000836942699A4210B501D18268E8 -:102F40007AB98268013282605A1C82611C780369F6 -:102F50009A4201D3C3688361002100F01FFA204622 -:102F600010BD4FF0FF3010BD2DE9F74F05460F465D -:102F700090469A46D0F81C90202686F311884FF090 -:102F8000000B144664B1224639462846FFF7EEFE90 -:102F9000034668B95146284600F0F0F90028F1D000 -:102FA000002383F31188A8EB040003B0BDE8F08F81 -:102FB000B9F1000F03D001902846C847019B8BF35D -:102FC0001188E41A1F4486F31188DBE7026843681E -:102FD0001143016003B11847704700001430FFF738 -:102FE00043BF00004FF0FF331430FFF73DBF000038 -:102FF0003830FFF7B9BF00004FF0FF333830FFF72C -:10300000B3BF00001430FFF709BF00004FF0FF31DD -:103010001430FFF703BF00003830FFF763BF000034 -:103020004FF0FF323830FFF75DBF000000207047DF -:10303000FFF78ABD044B0360002343608360C360D5 -:1030400001230374704700BFD842000838B5C36934 -:1030500004460D461BB904210844FFF7B7FF294673 -:1030600004F11400FFF7BEFE002806DA201D4FF41D -:103070008061BDE83840FFF7A9BF38BD024B002290 -:103080001B605B609A6070471C250020002303745E -:103090008268054B1B6899689142FBD25A680360AD -:1030A00042601060586070471C25002008B520233E -:1030B00083F31188037C032B05D0042B0DD02BB98F -:1030C00083F3118808BD436900221A604FF0FF3373 -:1030D0004361FFF7DBFF0023F2E790E80C001A6082 -:1030E00002685360F2E70000002303748268054B16 -:1030F0001B6899689142FBD85A680360426010606F -:10310000586070471C250020054B19690874186821 -:1031100002681A605360186101230374FDF778BADE -:103120001C25002030B54B1C87B005460A4C10D03A -:1031300023690A4A01A800F059F92846FFF7E4FF7D -:10314000049B13B101A800F06BF92369586907B01B -:1031500030BDFFF7D9FFF8E71C250020AD3000088F -:1031600038B50C4D41612B6981689A6891420446DB -:1031700003D8BDE83840FFF789BF1846FFF786FF40 -:1031800001232C61014623742046BDE83840FDF739 -:103190003FBA00BF1C250020044B1A681B699068C9 -:1031A0009B68984294BF0020012070471C25002096 -:1031B00010B5084C236820691A6822605460012207 -:1031C00023611A74FFF790FF01462069BDE81040A3 -:1031D000FDF71EBA1C25002008B5FFF7DDFF18B16A -:1031E000BDE80840FFF7E4BF08BD0000FEE70000AF -:1031F00010B5174CFFF742FF00F0EAF8802215499E -:10320000204600F06FF8012344F8180C0374124BA9 -:10321000124AD96821F4E0610904090C0A431049F3 -:10322000DA60CA6842F08072CA600E490A6842F0E9 -:1032300001020A601022DA77202283F8222000237C -:1032400083F3118862B60848BDE8104000F06CB8FE -:10325000442500200043000800ED00E00003FA05CB -:10326000F0ED00E0001000E008430008F8B50F4C56 -:10327000226A01322262224652F8141F91421546F8 -:1032800006D08B68013B8B60202663699A6802B187 -:10329000F8BD1968DF68DA604D60616182F31188FA -:1032A0001869B84786F31188EFE700BF1C25002096 -:1032B000EFF3118020B9EFF30583202282F3118808 -:1032C0007047000010B558B9EFF30584C4F3080443 -:1032D00014B180F3118810BDFFF77EFF84F31188CD -:1032E00010BD000082600222027400224274704706 -:1032F0008368A3F17C0243F80C2C026943F83C2C50 -:10330000426943F8382C074A43F81C2CC26843F83A -:10331000102C022203F8082C002203F8072CA3F13A -:10332000180070472906000810B5202383F3118880 -:10333000FFF7DEFF00210446FFF712FF002383F3AF -:103340001188204610BD0000024B1B6958610F20F8 -:10335000FFF7DABE1C250020202383F31188FFF736 -:10336000F3BF000008B50146202383F3118808202D -:10337000FFF7D8FE002383F3118808BD49B1064B3F -:1033800042681B6918605A60136043600420FFF7AD -:10339000C9BE4FF0FF3070471C25002003689842DB -:1033A00006D01A680260506059611846FFF76EBE79 -:1033B0007047000038B504460D462068844200D1AD -:1033C00038BD036823605C604561FFF75FFEF4E78A -:1033D000054B03F114025A619A614FF0FF32DA6132 -:1033E00000221A62704700BF1C25002010B5C26081 -:1033F0000A4A036153699C68A1420CD85C68036067 -:1034000044602060586081609868411A99604FF06C -:10341000FF33D36110BD091B1B68ECE71C2500209E -:10342000036881689A680A449A6042681360036876 -:103430005A600023C360024B4FF0FF32DA617047DD -:103440001C25002000207047FEE7000070470000A8 -:103450004FF0FF3070470000BFF34F8F024AD36830 -:10346000DB07FCD4704700BF0020024008B5074BC3 -:103470001B7853B9FFF7F0FF054B1A69120641BFDD -:10348000044A5A6002F188325A6008BDA82600201A -:10349000002002402301674508B5054B1B7833B96E -:1034A000FFF7DAFF034A136943F08003136108BD95 -:1034B000A8260020002002407F289ABF00F5803017 -:1034C000C0020020704700004FF400607047000009 -:1034D000802070477F2808B50BD8FFF7EDFF00F577 -:1034E00000630268013204D104308342F9D1012023 -:1034F00008BD002008BD00007F2838B5044624D848 -:1035000000F0B6F8124D2860FFF7A6FFFFF7AEFFF8 -:10351000104BF322DA6002221A612046FFF7CCFF3B -:1035200058611A6942F040021A61FFF795FF4FF4A3 -:10353000006100F0FBF8FFF7AFFF00F099F828609A -:103540002046BDE83840FFF7C5BF002038BD00BFAA -:10355000AC260020002002402DE9F84312F00103C0 -:10356000144606D0204B40F24B221A600020BDE8E2 -:10357000F88385181D4A954204D91B4A4FF41471EB -:103580001160F3E7FFF772FFFFF766FFDFF86C806B -:10359000451A4FF00109012C05EB01060F4604D82E -:1035A000FFF77AFF0120BDE8F883C8F8109031F8E2 -:1035B000023B3380FFF750FF0020C8F8100033882B -:1035C0003A889BB29A420DD0074B40F267221A60AC -:1035D000074B1E60074B1C60074B1F60FFF75CFF2B -:1035E000BDE8F883023CD6E7A4260020FFFF0308CD -:1035F00098260020A02600209C26002000200240C3 -:10360000084908B50B7828B153B9FFF72FFF0123FC -:103610000B7008BD23B1BDE808400870FFF73CBF40 -:1036200008BD00BFA826002038B5FFF741FE0D4BAE -:103630000D4A1C6A11684FF47A7303FB04F38B4242 -:103640000A49D1E9004504D2003445F10105C1E938 -:103650000045E41845F100051360FFF733FE2046EE -:10366000294638BD1C250020B0260020B8260020A1 -:1036700008B5FFF7D9FF4FF47A720023FCF7ACFDD1 -:1036800008BD00BF10B50244064B0439D2B29042C7 -:1036900000D110BD441C00B253F8200041F8040FC3 -:1036A000E0B2F4E750280040104B30B51C6A240407 -:1036B00007D41C6A44F440741C621C6A44F400443D -:1036C0001C620B4C236843F4807323600244094B53 -:1036D0000439D2B2904200D130BD441C00B251F83E -:1036E000045F43F82050E0B2F4E700BF001002404E -:1036F000007000405028004007B5012201A90020B9 -:10370000FFF7C0FF019803B05DF804FB13B5044652 -:10371000FFF7F2FFA04206D002A9012241F8044DB2 -:103720000020FFF7C1FF02B010BD0000704700008D -:10373000074B45F255521A6002225A6040F6FF725A -:103740009A604CF6CC421A60024B01221A70704704 -:1037500000300040C1260020034B1B781BB1034BF7 -:103760004AF6AA221A607047C126002000300040A5 -:10377000034B1B689B0042BF024B01221A7070472B -:1037800024100240C0260020024B4FF080721A60C5 -:10379000704700BF24100240014B1878704700BFEB -:1037A000C0260020064A536823F001035360EFF35C -:1037B0000983683383F30988002383F311887047F2 -:1037C00030EF00E010B5202383F31188104B5B68C5 -:1037D00013F4006318D0F1EE103AEFF309844FF0C0 -:1037E000807344F84C3C0B4BDB6844F8083CA4F174 -:1037F000680383F30988FFF7CFFC18B1064B44F840 -:10380000503C10BD054BFAE783F3118810BD00BF93 -:1038100000ED00E030EF00E0390600083C0600084B -:1038200070470000FEE70000084A094B09498B4237 -:1038300004D3094A0021934205D3704752F8040F7C -:1038400043F8040BF3E743F8041BF4E7884400084B -:10385000C8260020C8260020C82600204B684360E8 -:103860008B688360CB68C3600B6943614B690362FB -:103870008B6943620B6803607047000008B5194B01 -:103880009A6A42F4FC029A629A6A22F4FC029A62F0 -:103890009A6A5A6942F4FC025A61134A5B691146FA -:1038A0004FF09040FFF7DAFF104802F11C01FFF7DC -:1038B000D5FF0F4802F13801FFF7D0FF0D4802F1A4 -:1038C0005401FFF7CBFF0C4802F17001FFF7C6FF70 -:1038D0000A4802F18C01FFF7C1FFBDE8084000F083 -:1038E00065B800BF001002402843000800040048EB -:1038F00000080048000C0048001000480014004870 -:1039000008B500F08FF9FFF773FCBDE80840FFF73A -:103910002FBF00007047000010B5214CA26A62F46E -:10392000FC02A262A26A02F4FC02A2624FF0FF3122 -:10393000A26A226921612269002222612069E0686D -:10394000E160E168E260E168E169164841F08051B8 -:10395000E161E169016841F480710160216A01F46B -:103960004071B1F5407F1EBF4FF480332362226265 -:10397000236A1B0407D4236A43F440732362236A37 -:1039800043F40043236200F02DF9A369064A43F093 -:103990000103A361A369136843F02003136010BD02 -:1039A0000010024000700040000001401C4B1A68EB -:1039B00042F001021A601A689007FCD55A6822F09A -:1039C00003025A605A6812F00C02FBD1196801F028 -:1039D000F90119605A601A6842F480321A601A6854 -:1039E0009103FCD50F4A5A604FF40452DA62302238 -:1039F0001A631A6842F080721A601A689201FCD544 -:103A0000094A122111605A6842F002025A605A684B -:103A100002F00C02082AFAD11A6B1A63704700BF31 -:103A2000001002400024050000200240084A08B5AA -:103A3000536911680B4003F00103536123B1054A38 -:103A400013680BB150689847BDE80840FFF7BABE4D -:103A50000004014044230020084A08B55369116856 -:103A60000B4003F00203536123B1054A93680BB185 -:103A7000D0689847BDE80840FFF7A4BE00040140A5 -:103A800044230020084A08B5536911680B4003F02D -:103A90000403536123B1054A13690BB15069984778 -:103AA000BDE80840FFF78EBE00040140442300201B -:103AB000084A08B5536911680B4003F008035361C5 -:103AC00023B1054A93690BB1D0699847BDE8084016 -:103AD000FFF778BE0004014044230020084A08B5DF -:103AE000536911680B4003F01003536123B1054A79 -:103AF000136A0BB1506A9847BDE80840FFF762BEF1 -:103B00000004014044230020174B10B55C691A687B -:103B1000144004F478725A61A30604D5134A936AD8 -:103B20000BB1D06A9847600604D5104A136B0BB1ED -:103B3000506B9847210604D50C4A936B0BB1D06BA0 -:103B40009847E20504D5094A136C0BB1506C9847AD -:103B5000A30504D5054A936C0BB1D06C9847BDE81A -:103B60001040FFF72FBE00BF000401404423002097 -:103B70001A4B10B55C691A68144004F47C425A610F -:103B8000620504D5164A136D0BB1506D9847230595 -:103B900004D5134A936D0BB1D06D9847E00404D55A -:103BA0000F4A136E0BB1506E9847A10404D50C4A0E -:103BB000936E0BB1D06E9847620404D5084A136F18 -:103BC0000BB1506F9847230404D5054A936F0BB18E -:103BD000D06F9847BDE81040FFF7F4BD00040140E6 -:103BE00044230020062108B50846FEF7FFFF062102 -:103BF0000720FEF7FBFF06210820FEF7F7FF06214E -:103C00000920FEF7F3FF06210A20FEF7EFFF062149 -:103C10001720FEF7EBFF06212820BDE80840FEF73D -:103C2000E5BF000008B5FFF777FEFEF7CFFEFEF711 -:103C3000FBFFFFF7FDF9FFF76DFEBDE8084000F060 -:103C400001B8000000F00EB808B5202383F31188F6 -:103C5000FFF70CFB002383F31188BDE80840FFF752 -:103C6000B1BD0000054B064A5A6000229A60072247 -:103C70001A6008210B20FEF7CFBF00BF10E000E064 -:103C80003F19010008B5062000F078F80120FFF781 -:103C9000DBFB00001FB51C46094B1B680546D868B6 -:103CA00052B1084B02928DE80A0022462B46064983 -:103CB000FDF710FCFFF7E6FF044B1A46F2E700BFE2 -:103CC00010110020D0430008DD4300085C3E0008CE -:103CD00010B501390244904201D1002010BD10F806 -:103CE000013B11F8014FA342F5D0181B10BD000095 -:103CF0002DE9F8430746884691461E468BB10D468E -:103D0000A8EB0500B54207EB000402D20020BDE895 -:103D1000F883324649462046FFF7DAFF18B1013DE5 -:103D2000EEE7BDE8F8832046BDE8F8831F2938B5E3 -:103D300004460D4604D9162303604FF0FF3038BD0A -:103D4000426C12B152F821304BB9204600F030F8E5 -:103D50002A4601462046BDE8384000F017B8012B3E -:103D60000AD0591C03D116230360012038BD00245A -:103D700042F8254028469847002038BD024B0146AE -:103D80001868FFF7D3BF00BF1011002038B5074CEB -:103D900000230546084611462360FFF759FB431CE4 -:103DA00002D1236803B12B6038BD00BFC4260020B8 -:103DB000FFF748BB034611F8012B03F8012B002A3B -:103DC000F9D1704740A2E4F1646891064E6F20611A -:103DD0007070207369670A00426164206677206C06 -:103DE000656E6774682025750A0042616420626F01 -:103DF0006172645F69642025752073686F756C64F7 -:103E00002062652025750A0042616420667720647F -:103E1000657363726970746F72206C656E67746825 -:103E20002025750A0042616420617070204352436E -:103E3000203078253038783A30782530387820307E -:103E400078253038783A3078253038780A00476F4E -:103E50006F64206669726D776172650A0000000008 -:103E600072656365697665645F756E697175655FB6 -:103E700069645F6C656E203C2055415643414E5F3E -:103E800050524F544F434F4C5F44594E414D49435C -:103E90005F4E4F44455F49445F414C4C4F43415452 -:103EA000494F4E5F554E495155455F49445F4D411D -:103EB000585F4C454E475448002E2E2F2E2E2F541F -:103EC0006F6F6C732F41505F426F6F746C6F6164E2 -:103ED00065722F63616E2E63707000616C6C6F632E -:103EE000617465645F6E6F64655F6964203C3D204A -:103EF000313237006F72672E6172647570696C6F52 -:103F0000742E48697465634D6F73616963000000C6 -:103F1000766F69642068616E646C655F616C6C6F5C -:103F2000636174696F6E5F726573706F6E7365281D -:103F300043616E617264496E7374616E63652A2CAD -:103F40002043616E61726452785472616E7366656B -:103F5000722A290063616E617264496E697400009F -:103F600063616E6172645365744C6F63616C4E6F14 -:103F7000646549440000000063616E6172644861D9 -:103F80006E646C6552784672616D650063616E6146 -:103F900072644465636F64655363616C61720000B1 -:103FA00063616E617264456E636F64655363616CD7 -:103FB00061720000696E6372656D656E7454726142 -:103FC0006E73666572494400656E717565756554FA -:103FD000784672616D6573007075736854785175B9 -:103FE0006575650070726570617265466F724E65C9 -:103FF00078745472616E736665720000636F7079D5 -:1040000042697441727261790000000064657363F3 -:1040100061747465725472616E7366657250617911 -:104020006C6F61640000000066726565426C6F63CE -:104030006B0000006269745F6C656E677468203E97 -:1040400020300072656D61696E696E675F626974C8 -:1040500073203E203000696E7075745F6269745F12 -:104060006F6666736574203E3D20626C6F636B5FA4 -:104070006269745F6F666673657400626C6F636B10 -:104080005F656E645F6269745F6F666673657420F6 -:104090003E20626C6F636B5F6269745F6F6666730C -:1040A00065740072656D61696E696E675F626974DF -:1040B0005F6C656E677468203C3D2072656D616958 -:1040C0006E696E675F6269747300696E7075745FA4 -:1040D0006269745F6F6666736574203C3D2074721C -:1040E000616E736665722D3E7061796C6F61645F9D -:1040F0006C656E202A2038006F75747075745F626D -:1041000069745F6F6666736574203C3D20363400C9 -:1041100072656D61696E696E675F6269745F6C6517 -:104120006E677468203D3D20300028726573756CA1 -:1041300074203E2030292026262028726573756C55 -:1041400074203C3D203634292026262028726573B1 -:10415000756C74203C3D206269745F6C656E677499 -:104160006829000064657374696E6174696F6E20FC -:10417000213D202828766F6964202A29302900767D -:10418000616C756520213D202828766F6964202A9E -:10419000293029006F66667365745F776974686992 -:1041A0006E5F626C6F636B203C2028333255202D8C -:1041B000205F5F6275696C74696E5F6F66667365B8 -:1041C000746F66202843616E61726442756666652D -:1041D00072426C6F636B2C2064617461292900004A -:1041E0006F75745F696E7320213D202828766F6992 -:1041F00064202A29302900007372635F6C656E2089 -:104200003E203055000000002863616E5F69642025 -:104210002620307831464646464646465529203DBA -:104220003D2063616E5F696400000000616C6C6F2B -:104230006361746F722D3E73746174697374696322 -:10424000732E63757272656E745F75736167655FF7 -:10425000626C6F636B73203E203000007472616E7D -:10426000736665725F696420213D202828766F6936 -:1042700064202A293029000073746174652D3E6220 -:1042800075666665725F626C6F636B73203D3D207F -:104290002828766F6964202A293029002E2E2F2E97 -:1042A0002E2F6D6F64756C65732F6C696263616E20 -:1042B0006172642F63616E6172642E63006974655C -:1042C0006D2D3E6672616D652E646174615F6C6513 -:1042D0006E203E203000000000000000F92F000892 -:1042E000E52F0008213000080D30000819300008C3 -:1042F00005300008F12F0008DD2F00082D300008E0 -:104300006D61696E000000002043000860250020F8 -:104310009826002001000000ED3100080000000098 -:1043200069646C6500000000A0100000000000003F -:10433000FAAAAAAA50040000BFFF000000770000FC -:10434000000000001410AA0000000000AAAAFAAAA7 -:1043500004005000FBFF00000000000099770000FF -:104360000000000000000000AAAAAAAA00000000A5 -:10437000FFFF00000000000000000000000000003F -:1043800000000000AAAAAAAA00000000FFFF000087 -:10439000000000000000000000000000000000001D -:1043A000AAAAAAAA00000000FFFF00000000000067 -:1043B000000000000000000000000000AAAAAAAA55 -:1043C00000000000FFFF00000000000000000000EF -:1043D0002C2066756E6374696F6E3A20006173738A -:1043E000657274696F6E2022257322206661696C84 -:1043F00065643A2066696C6520222573222C206C46 -:10440000696E65202564257325730A00FCBDFF7F56 -:104410000100000000000000640000000000000037 -:10442000FE2A0100D2040000141100200000000048 -:10443000000000000000000000000000000000007C -:10444000000000000000000000000000000000006C -:10445000000000000000000000000000000000005C -:10446000000000000000000000000000000000004C -:10447000000000000000000000000000000000003C -:0C44800000000000000000000000000030 +:1000000000090020A5040008DD1400085D140008A4 +:10001000B51400085D14000889140008A70400083E +:10002000A7040008A7040008A70400087D350008FD +:10003000A7040008A7040008A7040008B53A0008B0 +:10004000A7040008A7040008A7040008A7040008E4 +:10005000A7040008A70400084D38000879380008F4 +:10006000A5380008D1380008FD380008A7040008AA +:10007000A7040008A7040008A7040008A7040008B4 +:10008000A7040008A7040008A70400082524000806 +:1000900091240008E52400083925000829390008C2 +:1000A000A7040008A7040008A7040008A704000884 +:1000B000A7040008A7040008A7040008A704000874 +:1000C000A7040008A7040008A7040008A704000864 +:1000D000A7040008A70400087D290008912900084A +:1000E00091390008A7040008A7040008A704000825 +:1000F000A7040008A7040008A7040008A704000834 +:10010000A7040008A7040008A7040008A704000823 +:10011000A7040008A7040008A7040008A704000813 +:10012000A7040008A7040008A7040008A704000803 +:10013000A7040008A7040008A7040008A7040008F3 +:10014000A7040008A7040008A7040008A7040008E3 +:10015000A7040008A7040008A7040008A7040008D3 +:10016000A7040008A7040008A7040008A7040008C3 +:10017000A7040008A7040008A7040008A7040008B3 +:10018000A7040008A7040008A7040008A7040008A3 +:10019000A7040008A7040008A7040008A704000893 +:1001A00053B94AB9002908BF00281CBF4FF0FF31DE +:1001B0004FF0FF3000F074B9ADF1080C6DE904CEDA +:1001C00000F006F8DDF804E0DDE9022304B0704732 +:1001D0002DE9F047089D04468E46002B4DD18A42FA +:1001E000944669D9B2FA82F252B101FA02F3C2F12D +:1001F000200120FA01F10CFA02FC41EA030E9440BE +:100200004FEA1C48210CBEFBF8F61FFA8CF708FBDE +:1002100016E341EA034306FB07F199420AD91CEBB6 +:10022000030306F1FF3080F01F81994240F21C81E8 +:10023000023E63445B1AA4B2B3FBF8F008FB103330 +:1002400044EA034400FB07F7A7420AD91CEB040465 +:1002500000F1FF3380F00A81A74240F20781644435 +:10026000023840EA0640E41B00261DB1D4400023BA +:10027000C5E900433146BDE8F0878B4209D9002D1E +:1002800000F0EF800026C5E9000130463146BDE8A8 +:10029000F087B3FA83F6002E4AD18B4202D3824212 +:1002A00000F2F980841A61EB030301209E46002DC1 +:1002B000E0D0C5E9004EDDE702B9FFDEB2FA82F216 +:1002C000002A40F09280A1EB0C014FEA1C471FFA74 +:1002D0008CFE0126200CB1FBF7F307FB131140EA5B +:1002E00001410EFB03F0884208D91CEB010103F128 +:1002F000FF3802D2884200F2CB804346091AA4B2EA +:10030000B1FBF7F007FB101144EA01440EFB00FEBD +:10031000A64508D91CEB040400F1FF3102D2A64522 +:1003200000F2BB800846A4EB0E0440EA03409CE7C1 +:10033000C6F12007B34022FA07FC4CEA030C20FA6E +:1003400007F401FA06F31C43F9404FEA1C4900FA8E +:1003500006F3B1FBF9F8200C1FFA8CFE09FB18110B +:1003600040EA014108FB0EF0884202FA06F20BD97E +:100370001CEB010108F1FF3A80F08880884240F2CE +:100380008580A8F102086144091AA4B2B1FBF9F012 +:1003900009FB101144EA014100FB0EFE8E4508D90D +:1003A0001CEB010100F1FF346CD28E456AD9023892 +:1003B000614440EA0840A0FB0294A1EB0E01A14277 +:1003C000C846A64656D353D05DB1B3EB080261EBE5 +:1003D0000E0101FA07F722FA06F3F1401F43C5E9BF +:1003E000007100263146BDE8F087C2F12003D840F5 +:1003F0000CFA02FC21FA03F3914001434FEA1C4737 +:100400001FFA8CFEB3FBF7F007FB10360B0C43EA28 +:10041000064300FB0EF69E4204FA02F408D91CEBD8 +:10042000030300F1FF382FD29E422DD902386344D6 +:100430009B1B89B2B3FBF7F607FB163341EA034176 +:1004400006FB0EF38B4208D91CEB010106F1FF38C5 +:1004500016D28B4214D9023E6144C91A46EA0046BC +:1004600038E72E46284605E70646E3E61846F8E64E +:100470004B45A9D2B9EB020864EB0C0E0138A3E797 +:100480004646EAE7204694E74046D1E7D0467BE778 +:10049000023B614432E7304609E76444023842E7F0 +:1004A000704700BF02E000F000F8FEE772B63A487D +:1004B00080F30888394880F3098839484EF6085196 +:1004C000CEF20001086040F20000CCF200004EF6CF +:1004D0003471CEF200010860BFF34F8FBFF36F8F0E +:1004E00040F20000C0F2F0004EF68851CEF200015A +:1004F0000860BFF34F8FBFF36F8F4FF00000E1EE46 +:10050000100A4EF63C71CEF200010860062080F31E +:100510001488BFF36F8F03F0B1F803F08DF803F088 +:10052000BFF84FF055301F491B4A91423CBF41F87C +:10053000040BFAE71C49194A91423CBF41F8040BED +:10054000FAE71A491A4A1B4B9A423EBF51F8040B6C +:1005500042F8040BF8E700201749184A91423CBFC3 +:1005600041F8040BFAE703F06BF803F0D5F8144CEC +:10057000144DAC4203DA54F8041B8847F9E700F045 +:1005800041F8114C114DAC4203DA54F8041B884772 +:10059000F9E703F053B80000000900200011002023 +:1005A000000000080001002000090020F03C0008C5 +:1005B00000110020201100202011002028260020FA +:1005C000A0010008A0010008A0010008A001000887 +:1005D0002DE9F04F2DED108AC1F80CD0C3689D466F +:1005E000BDEC108ABDE8F08F002383F31188284604 +:1005F000A047002002F04AFDFEE702F0CFFC00DF3A +:10060000FEE700002DE9F04102F060FF074602F02E +:10061000ABFF054600283FD12B4B9F423CD0013316 +:100620009F423CD0294B27F0FF029A423BD1F8B2BF +:1006300000F052FAA84642F2107400F057FC08B1DC +:100640000024A04600F04EFA064680B38CBB464616 +:1006500035B11F4B9F4203D002F07EFF0024264697 +:10066000002002F03DFF4FF090431B6913F0200380 +:1006700022D00EB100F02EF800F05CFC00F02EFE4F +:1006800000F02EFF0546CCB100F02AFF401BA0422F +:1006900014D900F01FF8F3E7A8460024CDE704467C +:1006A0004FF00108C9E780464FF47A74C5E7044665 +:1006B000CEE74FF47A74CBE71C46DDE700F0DAFCB6 +:1006C000012002F0E9FCDEE7010007B0000008B0FD +:1006D000263A09B038B51D4A1D4B1968013134D08E +:1006E00004339342F9D11B4C194DD4F80428AA4283 +:1006F0002BD3194B9B6803F1006303F5D0439A4257 +:1007000023D202F0FDFE02F00FFF002000F000FEF9 +:10071000124B0220187000F037FE114BDA690022EC +:10072000DA61D96999699A619B6972B64FF0E023E1 +:100730002021C3F8085DD4F80038D4F8042881F3E8 +:1007400011889D4683F30888104738BD206800084B +:10075000006800080060000800110020201100203F +:1007600000100240094A136849F2690099B21B0C53 +:1007700000FB01331360064B186844F2506182B2EB +:10078000000C01FB0200186080B270471C110020B1 +:100790001811002010B500211022044600F00EFEB2 +:1007A000034B03CB206061601868A06010BD00BFE0 +:1007B000ACF7FF1F2DE9F043224DBBB000F090FED7 +:1007C000AB6840F2ED22C31A934232D906AFA8605B +:1007D0002B4628220021384601F05EFB05F10E0071 +:1007E00000F0E4FD002604465FFA80F905F10E08EA +:1007F000F3B2F100994501F1280107D908EB06038E +:100800000822384601F048FB0136F1E708230122AF +:10081000CDE9023205340C4B0193A4B2302300938E +:10082000CDE9047405A3D3E90023297B074801F02F +:100830004BF93BB0BDE8F083AFF3008078F6339F0F +:1008400093CACD8D68210020752100203C21002015 +:1008500070B50D4614461E4601F0CCF850B9022E74 +:1008600010D1012C0ED112A3D3E90023C5E9002336 +:10087000012007E0282C10D005D8012C09D0052C28 +:100880000FD0002070BD302CFBD10BA3D3E9002387 +:10089000ECE70BA3D3E90023E8E70BA3D3E900239C +:1008A000E4E70BA3D3E90023E0E700BFAFF3008048 +:1008B000401DA12026812A0B78F6339F93CACD8D47 +:1008C0009E6AC421818A46EE26417272DF25D7B71F +:1008D000F017304A39059E5613B50446234608469C +:1008E00020220021019001F0D7FA22790198032AF1 +:1008F000234628BF032203F8042F2021022201F0FF +:10090000CBFA62790198072A234628BF072203F809 +:10091000052F2221032201F0BFFAA2790198072AAC +:10092000234628BF072203F8062F2521032201F0C2 +:10093000B3FA019804F108031022282101F0ACFA5F +:10094000382002B010BD00002DE9F04FADF5017D5B +:1009500021AD0EAE40F2751280460F4622A800214E +:10096000296000F02BFD48220021304600F026FDD2 +:1009700000F0B6FD564B4FF47A72B0FBF2F01860FF +:1009800093E80700012386E807000DF15A0033823F +:10099000FFF700FF4FF60303338407AB18464D49BA +:1009A00003F0C2F8192230642946304686F83C200C +:1009B000FFF792FF12AB044601460822284601F0D9 +:1009C0006BFA0822A1180DF14903284601F064FAD8 +:1009D0000DF14A03082204F11001284601F05CFAE7 +:1009E00013AB202204F11801284601F055FA14AB8C +:1009F000402204F13801284601F04EFA16AB0822D5 +:100A000004F17801284601F047FA0DF15903082254 +:100A100004F18001284601F03FFA04F1880A0DF143 +:100A20005A0904F5847B4B465146082228460AF1B0 +:100A3000080A01F031FAD34509F10109F3D11BABE2 +:100A400008225946284601F027FA04F588744FF029 +:100A5000000996F834304B450AD9B36B21464B4414 +:100A60000822284601F018FA083409F10109F0E7D4 +:100A70004FF0000996F83C304B4504EBC90108D90A +:100A8000336C08224B44284601F006FA09F10109AB +:100A9000F0E700230393BB7E0293073107F11903AC +:100AA0000193C1F3CF010123CDE904510093F97EF5 +:100AB00005A3D3E90023404601F006F80DF5017DBA +:100AC000BDE8F08FAFF300809E6AC421818A46EEB4 +:100AD00024110020383B0008014B1870704700BFFC +:100AE00030110020F0B5334B1C7B85B034B1324B54 +:100AF0000E221A810024204605B0F0BD2F4A10684E +:100B0000516802AB03C308232D492E480DEB0302A5 +:100B100002F0E8FF054630B9274B2B480A221A811C +:100B200000F098FCE6E70169B1F5663F06D9224B73 +:100B300026480B221A8100F08DFCDCE7438BB3F5CD +:100B40007E7F09D01C4A22480C2111814FF47E720D +:100B5000194600F07FFCCEE71E4A024402F1100362 +:100B6000994204D2144B1C4810221A81E3E7103931 +:100B70008E1A2046134900F0B7FC3246074605F1AD +:100B80001801204600F0B0FCAB689F4202D1EB6830 +:100B900098420AD0084B0D221A810090D5E9021222 +:100BA0003B460E4800F056FCA4E70D4800F052FC0E +:100BB0000124A0E76821002024110020E53B000863 +:100BC000DC97030000680008543B0008603B000805 +:100BD000723B00080898FFF7903B0008AD3B000807 +:100BE000D63B00082DE9F04FADB006AF80460C466D +:100BF00000F000FF054600285AD1237E022B1BD1AE +:100C0000E38A012B18D100F06BFC0646FFF7AAFD22 +:100C100003464FF4C870DFF8D092B3FBF0F206F54C +:100C2000167602FB103316FA83F3C9F80030E37E20 +:100C300033B9A84B00221A709C37BD46BDE8F08F2F +:100C4000A38AEEB2013BB34205F101050BD93B1D6E +:100C50001E44E90000960023082201F0F801204616 +:100C600000F0DEFFECE707F11400FFF793FD3246DA +:100C700007F11401381D02F025FF0028D9D10F2EED +:100C800008D8944B1E70D9F80030A3F51673C9F834 +:100C90000030D1E7FB1CF8700146009307220346A1 +:100CA000204600F0BDFFF978404600F09BFEC3E708 +:100CB000E38A282B26D010D8012B1ED0052BBBD1C0 +:100CC000BFF34F8F8449854BCA6802F4E062134337 +:100CD000CB60BFF34F8F00BFFDE7302BACD1637EFD +:100CE0007F4D01336A7BDBB29342E94603D1E27E5A +:100CF0002B7B9A4265D0CD469EE721464046FFF7C2 +:100D000023FE99E7A38A013B9BB2C92B94D8744D6B +:100D10002E7B26BB05F10C03009308223346314697 +:100D2000204600F07DFF731CF2B2D9001E46A38A54 +:100D3000013B9A4205DA0E322A440092002308222F +:100D4000EEE700230022C5E900230023AB6085F80D +:100D5000D730C5F8D8302B7B0BB9E37E2B73002539 +:100D600007F114093B1D082229464846C7E90155E9 +:100D7000FD6001F091F83B7A05F1010AAB424FEAC0 +:100D8000CA0608D9FB6808222B443146484601F0C0 +:100D900083F85546EFE7C6F3CF06E17ECDE904962A +:100DA00000230393A37E0293193428230093019414 +:100DB00046A3D3E90023404600F086FEFFF7FAFC85 +:100DC0003AE74FF0000807F11403A7F81480102247 +:100DD000009341460123204600F022FFA68A023EEE +:100DE000B6B2F31C9B109B000733DB08A9EBC303CF +:100DF0009D460DF1180A1FFA88F34FEAC801B34265 +:100E000001F110010AD20AEB080300930822002323 +:100E1000204600F005FF08F10108ECE795F8D7003F +:100E200000F080FAD5F8D83004461BB995F8D70001 +:100E300000F088FAD5F8D83033449C4204D295F8B3 +:100E4000D700013000F07EFA4FEA960B4FF0000811 +:100E50001FFA88F18B45D5E9003209D90AEB8801E0 +:100E600003EB8800012200F0B1FA08F10108EFE776 +:100E7000F31842F10002C5E90032D5F8D83095F8F0 +:100E8000D70006EB0308C5F8D88000F04BFA804580 +:100E900009D395F8D730D5F8D8000133001B85F871 +:100EA000D730C5F8D800FF2E08D800232B7300F0E8 +:100EB0005BFAFFF717FE08B1FFF70CFC2B68094A35 +:100EC0009B0A013313810023AB6014E72641727241 +:100ED000DF25D7B73521002000ED00E00400FA053A +:100EE00068210020241100203821002010B54FF087 +:100EF00000540C4B22689A4211D10B4B627D1A7040 +:100F00000A48237D03730A49C9220E3000F044FACF +:100F1000E0220021204600F051FA012010BD0020FF +:100F2000FCE700BF9AAD44C53011002068210020C5 +:100F3000160000202DE9FF41434C0223637100237A +:100F4000029324250A23581EB5FBF3F67343D3F10D +:100F50002402C1B23ED002280346F4D19DF80B30E2 +:100F60003A493B485A1E9DF80A30013B1B0443EAAC +:100F70000253BDF80820013A13434B6001F044FDD1 +:100F800000230193334B344900933448344B4FF4DE +:100F9000805200F001FD334B197811B12F4800F059 +:100FA00021FD00F09DFA0546FFF7DCFB4FF4C87306 +:100FB000B0FBF3F202FB130305F5167010FA83F091 +:100FC000294B186002F0D0FA08B10F23238104B036 +:100FD000BDE8F081C1EBC107FB1C4FEAE30EC3F390 +:100FE000C703A1EB030C0EF101084FF47A705FFA0E +:100FF0008CF50EFB000058FA8CFCB0FBFCF0B0F551 +:10100000617F07D97B1EC3F3C703C91ACDB2591E2E +:101010000F2916D86A1E072A8CBF002201225919EF +:1010200001FB06601149B1FBF0F11148814295D1F5 +:10103000002A93D0ADF808608DF80A308DF80B5077 +:101040008CE71346EBE700BF2411002010110020AD +:101050008022002051080008341100203C2100208B +:10106000E50B000830110020382100200051250236 +:1010700040420F002DE9F04F90A7D7E900670FF22B +:101080004429D9E90089874D93B0DFF840B2864CF6 +:10109000284600F07DFD0DF1300A079070B3102254 +:1010A0000021504600F08AF9079B197B4FF000029F +:1010B00061F303028DF83020586899680EAA03C2C4 +:1010C0001B680D9A63F31C029DF830300D9243F0BB +:1010D00020038DF83030002352461946584601F05F +:1010E000A3FC079028B9284600F056FD079B237003 +:1010F000CEE72378072B3CD8013323701822002138 +:10110000504600F05BF9DFF8C4B10023194652469F +:10111000584601F0B1FC014678BB102208A800F047 +:101120004DF94FF0904209AC536983F0400353618D +:1011300000F0D8F90B4612A9024611E9030084E831 +:1011400003009DF83410C1F3030089064CBF0E9CC8 +:10115000BDF838408DF82C0046BFC4F31C0444F0A1 +:101160000044C4F30A0408A92846089400F0DCFEF1 +:10117000CBE7284600F010FDC0E7284600F03AFC17 +:101180000446002848D1DFF848B100F0A9F9DBF89F +:101190000030984240D300F0A3F90790FFF7E2FA3D +:1011A000079A8DF8204003464FF4C87002F5167276 +:1011B000B3FBF0F101FB103312FA83F3CBF80030EC +:1011C000DFF810B19BF8001011B901238DF8203021 +:1011D00050460791FFF7DEFA0799C1F11004E4B217 +:1011E000062C28BF0624224651440DF1210000F0B0 +:1011F000D3F808AB03931823029301342B4B0193CC +:10120000E4B20123009304943B463246284600F0A2 +:10121000F3FB00238BF8003000F062F9244A254CE0 +:101220001368C31AB3F57A7F31D3106000F05AF90E +:1012300002460B46284600F0B9FC284600F0DAFBCF +:1012400028B3237BDFF890B0002B14BF03230223C5 +:101250008BF8053000F044F94FF47A735146B0FB37 +:10126000F3F0CBF800005846FFF736FB18230730A1 +:101270000293114B0193C0F3CF0040F25513CDE917 +:1012800003A0009342464B46284600F0B5FB237B63 +:101290002BB1FFF78FFA237B002B7FF4F6AE13B050 +:1012A000BDE8F08F3C2100204D2200203421002099 +:1012B00048220020682100204C220020401DA1204F +:1012C00026812A0BF1C6A7C1D068080F8022002012 +:1012D00038210020352100202411002070B501F0B4 +:1012E000B5FF094E094D30800024286833888342B9 +:1012F00008D901F0A7FF2B6804440133B4F5D04F9F +:101300002B60F2D370BD00BF7C2200205022002051 +:1013100002F03AB800F10060920000F5D04001F010 +:10132000D5BF0000054B1A68054B1B889B1A8342EA +:1013300002D9104401F086BF0020704750220020DF +:101340007C22002038B5074D04462868204401F06F +:101350007FFF28B928682044BDE8384001F08ABFE3 +:1013600038BD00BF50220020064991F8243033B127 +:101370000023086A81F824300822FFF7CBBF012040 +:10138000704700BF54220020022802BF4FF0904354 +:101390004FF480029A61704710B50023934203D046 +:1013A000CC5CC4540133F9E710BD0000034602468B +:1013B000D01A12F9011B0029FAD1704702440346E2 +:1013C000934202D003F8011BFAE770472DE9F84376 +:1013D0001F4D144695F824200746884652BBDFF877 +:1013E00070909CB395F824302BB92022FF214846F9 +:1013F0002F62FFF7E3FF95F82400C0F10802A24234 +:1014000028BF2246D6B24146920005EB8000FFF786 +:10141000C3FF95F82430A41B1E44F6B2082E1744CF +:101420009044E4B285F82460DBD1FFF79DFF0028EB +:10143000D7D108E02B6A03EB82038342CFD0FFF7BA +:1014400093FF0028CBD10020BDE8F8830120FBE703 +:10145000542200200FB4002004B0704700B59BB0A8 +:10146000EFF3098168226846FFF796FFEFF30583E3 +:10147000044B9A6BDA6A9A6A9A6A9A6A9A6A9A6AC0 +:101480009B6AFEE700ED00E000B59BB0EFF3098139 +:1014900068226846FFF780FFEFF30583044B9A6BE1 +:1014A0009A6A9A6A9A6A9A6A9A6A9B6AFEE700BF7F +:1014B00000ED00E000B59BB0EFF3098168226846BB +:1014C000FFF76AFFEFF30583034B5A6B9A6A9A6A38 +:1014D0009A6A9A6A9B6AFEE700ED00E0FEE7000068 +:1014E00001F08EBF01F064BF30B5094D0A4491424E +:1014F0000DD011F8013B5840082340F30004013B94 +:101500002C4013F0FF0384EA5000F6D1EFE730BD22 +:101510002083B8ED2DE9F041C56915B9C161BDE879 +:10152000F0814B6823F06047C3F38A464FEAD37ECD +:10153000C3F3807816EA230638BF3E46AC462B46F6 +:101540005A68BEEBD27F22F060440AD0002A18DA33 +:10155000A40CB44217D19D420FD10D60DEE71346B3 +:10156000EEE7A74207D102F08044C2F38072424501 +:101570000BD054B1EFE708D2EDE7CCF800100B60C8 +:10158000CDE7B44201D0B442E5D81A689C46002A9F +:10159000E5D11960C3E700002DE9F047089D01F08F +:1015A00007044FEAD508224405F0070500EBD100F7 +:1015B0004FF47F49944201D1BDE8F08704F007075A +:1015C00005F0070A57453E4638BF5646C6F108069D +:1015D000111B8E4228BF0E46E10808EBD50E415C78 +:1015E00013F80EC0B94029FA06F721FA0AF1FFB242 +:1015F0008CEA010147FA0AF739408CEA010C03F83A +:101600000EC034443544D5E780EA0120082341F276 +:10161000210201B24000002980B203F1FF33B8BFBC +:10162000504013F0FF03F4D17047000038B50C466A +:101630008D18A54200D138BD14F8011BFFF7E4FF57 +:10164000F7E7000002684AB113680360C3880189A4 +:1016500001339BB29942C38038BF03811046704763 +:1016600070B588B0202204460D4668460021FFF779 +:10167000A5FE20460495FFF7E5FF024658B16B46EC +:10168000054608AE1C4603CCB44228606960234678 +:1016900005F10805F6D1104608B070BD082817D925 +:1016A00009280CD00A280CD00B280CD00C280CD000 +:1016B0000D280CD00E2814BF4020302070470C207D +:1016C0007047102070471420704718207047202062 +:1016D00070470000082817D90C280CD910280CD9FD +:1016E00014280CD918280CD920280CD930288CBFE4 +:1016F0000F200E207047092070470A2070470B20EA +:1017000070470C2070470D207047000010B54B68E3 +:1017100023B9CA8A63F30902CA8210BDC4681A6871 +:101720001C60C360438A013B43824A60EFE70000CC +:101730002DE9F84F1D46CB8A0F46C3F30901062950 +:10174000814692460B4630D00020AAB207F1190418 +:101750009EB2052E1FFA80F80FD8904503F10103C1 +:1017600006D3FB8A0A4462F30903FB8201201AE0D4 +:101770001AF80060E6540130EAE79045F1D2A1F191 +:10178000060B1C237C68BBFBF3F203FB12BB1FFAA6 +:101790008BF6002C45D14846FFF754FF044638B974 +:1017A00078606FF00200BDE8F88F4FF00008E6E7C0 +:1017B000002606607860ADB24FF0000B454510D9A9 +:1017C0000AEB0803221D13F8011B9155B1B208F171 +:1017D00001081B291FFA88F82BD0454506F10106A0 +:1017E000F1D8FB8AC3F30902154465F30903BCE78A +:1017F000013292B21C462368002BF9D1AB1F0B4477 +:101800001C21B3FBF1F301339BB29A42D3D2BBF15B +:10181000000FD0D14846FFF715FF20B9C4F800B03B +:10182000BFE70122E7E7C0F800B05E46206004464B +:10183000C1E74545D5D94846FFF704FF08B9206000 +:10184000AFE7C0F800B0002620600446B6E700000D +:101850002DE9F04F2DED028B83B0CDE90013BDF8DB +:101860003C5007469146002A00F092802DB10E9B15 +:10187000002B00F08D80072D32D807F10C00FFF708 +:10188000E1FE044638B96FF00204204603B0BDEC17 +:10189000028BBDE8F08F14220021FFF78FFD0E9917 +:1018A0002A4604F10800FFF777FD681CC0B2FFF775 +:1018B00011FFFFF7F3FE207499F80030013814FA95 +:1018C00080F003F01F0363F03F030372009B43F0BB +:1018D0000041616038462146FFF71CFE0124D4E731 +:1018E00000F10C034FF0000808EE103A4FF0800AA8 +:1018F0004646444618EE100AFFF7A4FE8346002829 +:10190000C1D014220021FFF759FDC6BB019BABF8E3 +:10191000083002200E9B00F1080299195BFA82F24E +:101920000130C0B2082801D0AE422AD3FFF7D2FE60 +:10193000FFF7B4FE99F80020009B411E02F01F0241 +:1019400042EA4812AE4208BF4FF0400A5BFA81F10A +:101950004AEA020A43F0004281F808A08BF810001E +:10196000CBF8042059463846FFF7D4FD0134AE4287 +:1019700024B288F001084FF0000ABBD185E70020AF +:10198000C8E711F801CB02F801CB0136B6B2C7E7C0 +:101990006FF0010479E70000F8B515460E462822DD +:1019A000002104461F46FFF709FD069B6360B5F55D +:1019B000001F079BA76034BF6A094FF6FF722362BE +:1019C00004F10C0097B200239A4205D8002303606B +:1019D00027826382A382F8BD066001333046203639 +:1019E000F2E7000003781BB94BB2002BC8BF0170AF +:1019F00070470000007870472DE9F74FDDF83C9004 +:101A0000BDF830500D9E9DF83840BDF840708046BE +:101A100092469B46B9F1000F01D1002F51D11F2CE6 +:101A20004FD898F80000B0B9072F47D835F0030316 +:101A300047D13A4649464FF6FF70FFF7F7FD20F0D1 +:101A400001002D02400445EA0464400C44EA4024AD +:101A50004FF6FF7321E040EA0520072F40EA0464B7 +:101A6000F6D900254FF6FF73C5F12000A5F120023D +:101A70002AFA05F10BFA00F001432BFA02F21143A6 +:101A80001846C9B2FFF7C0FD0835402D0346EBD11B +:101A90003A464946FFF7CAFD0346CDE9009732466C +:101AA00021464046FFF7D4FE33780133DBB21F2BCB +:101AB00088BF0023337003B0BDE8F08F6FF00300E0 +:101AC000F9E76FF00100F6E72DE9F04F85B0924697 +:101AD000DDF848800F9D9DF840209DF84490BDF8AA +:101AE0004C7006469B46B8F1000F01D1002F48D13B +:101AF0001F2A46D83378002B46D00C0244EA0264F1 +:101B00009DF8381044EAC93444EA01441C43072FC5 +:101B100044F0800432D900234FF6FF72C3F1200C49 +:101B2000A3F120002AFA03F10BFA0CFC41EA0C01A4 +:101B30002BFA00F00143C9B210460393FFF764FD8E +:101B4000039B0833402B0246E8D13A464146FFF753 +:101B50006DFD0346CDE900872A4621463046FFF752 +:101B600077FEB9F1010F06D12B780133DBB21F2BC1 +:101B700088BF00232B7005B0BDE8F08F4FF6FF73D0 +:101B8000E8E76FF00100F6E76FF00300F3E700000D +:101B9000C06900B104307047C3691A68C261C26885 +:101BA0001A60C360438A013B438270472DE9F041CC +:101BB000D0F81880194E14461D464146002709B931 +:101BC000BDE8F081D1E90223A21A65EB0303964236 +:101BD00077EB03031ED283698B420DD1FFF796FD8D +:101BE00083691B688361C3680B60438AC160816934 +:101BF000013B43828846E2E7FFF788FD0B68C8F89F +:101C00000030C3680B60438AC160013B4382D8F84F +:101C10000010D4E788460968D1E700BF80841E0021 +:101C20002DE9F04F8BB00D46DDF8509014469B46E1 +:101C30008046002800F01981B9F1000F00F01581ED +:101C4000531E3F2B00F21181012A03D1BBF1000F7B +:101C500040F00B810023CDE90833B8F81430B5EB20 +:101C6000C30F4FEAC30703D300200BB0BDE8F08FCA +:101C70002B199F42D8F80C303ABF7F1BFFB2274682 +:101C80001BB9D8F81030002B7AD02F2D4ED8C5F1C3 +:101C90003006B7424FF000032CBFF6B23E46009329 +:101CA0002946D8F8080008AB3246FFF775FCA7EBC9 +:101CB000060A35445FFA8AFAB8F8143003F1005383 +:101CC000063BDB000493D8F80C3003933021039BD0 +:101CD00013B1BAF1000F2CD1D8F8100040B1BAF10D +:101CE000000F05D0009608AB5246691AFFF754FC66 +:101CF00038B2002FB8D066070AD00AAB03EBD40184 +:101D0000624211F8083C02F00702134101F8083C56 +:101D1000082C3CD9102C40F2B580202C40F2B78022 +:101D2000BBF1000F00F09C80082334E0BA46002687 +:101D3000C2E7049BE02B28BFE02306930B44AB4291 +:101D4000059314D95A1B03980096924534BF524606 +:101D5000D2B2691A08AB04300792FFF71DFC079A4C +:101D60001644AAEB020A1544F6B25FFA8AFA049BFB +:101D7000069A05999B1A0493039B1B680393A6E795 +:101D80000093D8F8080008AB3A462946AEE7BBF105 +:101D9000000F13D00123B4EBC30F6CD0082C12D862 +:101DA0009DF82030621E23FA02F2D50706D54FF0C7 +:101DB000FF3202FA04F423438DF820309DF82030DE +:101DC00089F8003051E7102C12D8BDF82030621E7F +:101DD00023FA02F2D10706D54FF0FF3202FA04F4DB +:101DE0002343ADF82030BDF82030A9F800303CE79F +:101DF000202C0FD80899631E21FA03F3DA0705D5C2 +:101E00004FF0FF3202FA04F40C430894089BC9F81F +:101E100000302AE7402C2BD0DDE90865611EC4F1B3 +:101E20002102A4F1210326FA01F105FA02F225FAB2 +:101E300003F311431943CB0712D50122A4F1200368 +:101E4000C4F1200102FA03F322FA01F1A240524246 +:101E500043EA010363EB430332432B43CDE90823F9 +:101E6000DDE90823C9E90023FFE66FF00100FCE685 +:101E70006FF00800F9E6082CA0D9102CB3D9202C5B +:101E8000EED8C3E7BBF1000FADD0022383E7BBF16F +:101E9000000FBBD004237EE730B5012A144638BFBB +:101EA0000124402C85B028BF40240025012ACDE91B +:101EB000025518D81B788DF8083063070AD004AB98 +:101EC00003EBD405624215F8083C02F00702934088 +:101ED00005F8083C009103462246002102A8FFF7BE +:101EE0005BFB05B030BD082AE4D9102A03D81B8853 +:101EF000ADF80830E1E7202A8DBFD3E900231B6845 +:101F00000293CDE90223D8E710B5CB681BB98B60EB +:101F10000B618B8210BDC4681A681C60C360438A61 +:101F2000013B4382CA60F0E72DE9F04FD1F8008011 +:101F300093B018F0800FCDE90323C8F3C01219BF86 +:101F4000C8F3C03BC8F306264FF0020B1646B8F1A3 +:101F5000000F04460D4680F2D18118F0C04305936E +:101F600040F0CC810B7B002B00F0C881BBF1020F4D +:101F700003D00178B14240F0C48108F07F0106919E +:101F80006AB3C8F3074A2B44069A93F8039076067F +:101F900046EA0B4646EA82465FEAD91346EA0A0653 +:101FA000079300F0908000220023CDE90A23069BCE +:101FB000009367685B4652460AA92046B847002846 +:101FC0007ED0A7699FB9314604F10C00FFF748FBAA +:101FD0000746E0B96FF0020013B0BDE8F08FC8F318 +:101FE0000F2A18F07F0F08BF0AF0030ACBE73B69FE +:101FF0009E420DD03F68002FF9D1314604F10C000C +:10200000FFF72EFB07460028E4D0A3693B60A761D9 +:10201000DDE90A2300264FF6FF70C6F1200E22FAF2 +:1020200006F103FA0EFEA6F1200C23FA0CFC41EA9D +:102030000E0141EA0C01C9B2083609920893FFF774 +:10204000E3FA402EDDE90832E7D1B882FB7D09F0E2 +:102050001F06C3F384039B1BD7E9022198B2002B10 +:10206000BCBF00F120031BB252EA0100C8F30468B0 +:102070000FD00398821A049860EB0101A7489042A0 +:102080004FF000028A4104D3079A002A5BD0012B4B +:1020900023DDFA7D4FEA890302F0030203F07C039B +:1020A0001343FB7539462046FFF730FB079BA3B966 +:1020B000FB7DC3F38402013262F38603FB7504E007 +:1020C0006FF00B0088E7A76917B96FF00C0083E782 +:1020D0003B699E42BAD03F68F6E719F0400F32D014 +:1020E000039BBB60049BFB60142200210DA8FFF73B +:1020F00065F9039B0A93049B0B932B1D0C932B7B7D +:10210000ADF83EA0013BDBB2ADF83C30069B8DF84C +:10211000433094F824308DF840B083F001038DF8FB +:1021200044308DF84160A3688DF842800AA92046AA +:102130009847FB7DC3F38403013303F01F039B0225 +:10214000FB82002048E7FB7DC9F34012B2EBD31FAE +:1021500040F0DA80C3F38403B34240F0D88007999B +:102160002B7B4FEA9912002934D0D20741D4032B9C +:1021700040F2D080039BBB60049BFB602B7BAE1DB9 +:10218000033BDBB23246394604F10C00FFF7D0FACC +:1021900000280DDA20463946FFF7B8FAFB7DC3F375 +:1021A0008403013303F01F039B02FB82032013E728 +:1021B000AB883B832A7B033AB88AD2B23146FFF719 +:1021C00035FAFB7DB882DA43C2F3C01262F3C7135B +:1021D000FB75B6E76AB92E1D013BDBB232463946C4 +:1021E00004F10C00FFF7A4FA0028D3DB2A7B013AA4 +:1021F000E2E7F98AC1F30901013B0529DAB259D8AE +:10220000281D002307F11A0C9A4208D910F801EB97 +:102210000CF801E0013101330629DBB2F4D1039956 +:102220000A9104990B91934207F11A010C9138BF5E +:10223000043379680D9134BF55FA83F300230E936C +:10224000FB8AADF83EA0C3F309031A44069B8DF840 +:10225000433094F82430ADF83C2083F001038DF82E +:10226000443000238DF840B08DF841608DF84280F5 +:102270007B602A7BB88A013A291DFFF7D7F93B8B8F +:10228000B882834203D1A3680AA920469847204612 +:102290000AA9FFF739FEFB7DB88AC3F38403013333 +:1022A00003F01F039B02FB823B8B984214BF11205B +:1022B000002091E67B68002BB1D0062001E01C30A5 +:1022C0006346D3F800C0BCF1000FF8D1091A081D0D +:1022D00005F1040C00EB030905989DF8143001EB9F +:1022E000000EBEF11B0F9AD89A4298D91CF8013BF8 +:1022F00009F8013B059B01330593EDE76FF00900F9 +:102300006AE66FF00A0067E66FF00D0064E66FF0B2 +:102310000E0061E66FF00F005EE600BF80841E00D5 +:10232000F0B53D4D3D4FEB6943F00073EB61EB6958 +:102330003B4B9B6AD3F800623E4046F00106C3F86F +:102340000062D3F800423C4044EA002040F0010023 +:10235000C3F80002002951D00020C3F81C02064631 +:10236000C3F80402C3F80C02C3F8140203EBC00460 +:1023700001300E28C4F84062C4F84462F6D1002748 +:102380004FF0010C9678148816F0010F18BFD3F89F +:1023900004E20CFA04F01CBF40EA0E0EC3F804E29B +:1023A00016F0020F1EBFD3F80CE240EA0E0EC3F87F +:1023B0000CE2760742BFD3F814620643C3F81462F6 +:1023C00003EBC4045668C4F840629668C4F84462DB +:1023D000D3F81C4201372043B942C3F81C0202F172 +:1023E0000C02CFD1D3F8002222F00102C3F8002260 +:1023F000EB6923F00073EB61EB69F0BD0122C3F8D8 +:102400004012C3F84412C3F80412C3F81412C3F8FC +:102410000C22C3F81C22E5E7001002400000FFFF79 +:1024200080220020184A916A08B58B688B6013F0EF +:10243000010104D013F00C0F18BF4FF48031D80500 +:1024400006D513F4406F14BF41F4003141F002018E +:10245000D80306D513F4402F14BF41F4802141F076 +:102460000401D3690BB108489847202383F31188EE +:102470000648002100F038FE002383F31188BDE8F0 +:10248000084001F0AFB800BF802200208822002061 +:1024900038B5124CA36ADD68AA0712D05A6922F037 +:1024A00002025A61A36913B10121204698472023F3 +:1024B00083F311880A48002100F016FE002383F3FD +:1024C0001188EB0606D5A36A1021D960236A0BB1E7 +:1024D00002489847BDE8384001F084B880220020C7 +:1024E0009022002038B5124CA36A1D69AA0712D0A9 +:1024F0005A6922F010025A61A36913B102212046E1 +:102500009847202383F311880A48002100F0ECFD4E +:10251000002383F31188EB0606D5A36A1021196105 +:10252000236A0BB102489847BDE8384001F05AB819 +:10253000802200209022002038B50F4CA36A5D68ED +:102540005D602A070AD5042222701A6822F002026E +:102550001A60636A13B10021204698476B0706D5BD +:10256000A36A9969236A13B1034809049847BDE82F +:10257000384001F037B800BF8022002010B50E4C63 +:10258000204600F02FFA0D4BA3620B21132000F020 +:1025900009FA0B21142000F005FA0B21152000F098 +:1025A00001FA0B21162000F0FDF90022BDE81040D1 +:1025B00011460E20FFF7B4BE8022002000640040C8 +:1025C0000F4B984210B5044605D10E4BDA6942F024 +:1025D0000072DA61DB69A36A01221A60A36A5A6891 +:1025E000D20707D5626851681268D9611A60064A35 +:1025F0005A6110BD0121082000F06CFCEEE700BF1D +:1026000080220020001002405B87010003291AD8B5 +:10261000DFE801F0020A0F14836A9B6813F0E05FA1 +:1026200014BF012000207047836A9868C0F380605F +:102630007047836A9868C0F3C0607047836A98687F +:10264000C0F30070704700207047000010B50329E8 +:1026500025D8DFE801F00225292D836A9968C1F3A6 +:102660000161183103EB0113107884064CBF5468E4 +:102670009488C0F300114FEA410148BF41EAC40108 +:1026800000F00F004CBF41F0040141EA4451586092 +:1026900041F001019068D2689860DA60196010BD5D +:1026A000836A03F5C073DFE7836A03F5C873DBE76A +:1026B000836A03F5D073D7E701290AD002290FD026 +:1026C00081B9836ADA68920701D1186903E00120B1 +:1026D0007047836AD86810F0030018BF0120704764 +:1026E000836AF2E70020704710B539B9836AD96868 +:1026F00089071BD11B699C0704D110BD012915D086 +:102700000229FAD1816AD1F8C031D1F8C441D1F897 +:10271000C8011061D1F8CC0150612020086108691E +:10272000800717D1486940F0100012E0816AD1F8A3 +:10273000B031D1F8B441D1F8B8011061D1F8BC0181 +:1027400050612020C860C868800703D1486940F004 +:1027500002004861C3F34000C3F38001000140EA76 +:102760004111107920F030000143117189064BBFEF +:1027700091681189DB085B0D4CBF63F31C0163F3A7 +:102780000A01137948BF916064F3030313714FEAA0 +:1027900014234FEA144458BF118113705480ACE7DE +:1027A000026843681143016003B118477047000095 +:1027B000024A136843F0C0031360704700440040AE +:1027C000024A136843F0C00313607047004800409A +:1027D00037B51D4C1D4D204600F006FB009404F15A +:1027E00014001B490023202200F0C8F92022009485 +:1027F00004F13800174B184900F042FA174BC4E9AE +:102800001735174C0C21262000F0CCF8204600F09C +:10281000EBFA04F11400134900940023202200F085 +:10282000ADF904F13800104B10490094202200F05B +:1028300027FA0F4B0C212720C4E9173503B0BDE858 +:10284000304000F0AFB800BFAC220020005125029C +:1028500084230020B1270008C42300200044004046 +:1028600018230020A4230020C1270008E42300200F +:10287000004800402DE9F047C66D3768F4693462BE +:102880002107054618D014F0080118BF8021E2077F +:1028900048BF41F02001A30748BF41F04001600755 +:1028A00048BF41F48071202383F31188281DFFF76E +:1028B00077FF002383F31188E2050AD5202383F3F1 +:1028C00011884FF40071281DFFF76AFF002383F37E +:1028D00011884FF020094FF0000A14F0200838D179 +:1028E0003B0616D54FF0200905F1380A200610D511 +:1028F00089F31188504600F0F7F9002836DA0821EC +:10290000281DFFF74DFF27F080033360002383F37A +:102910001188790614D5620612D5202383F3118815 +:10292000D5E913239A4208D12B6C33B11021281D0D +:1029300027F04007FFF734FF3760002383F3118847 +:10294000E30619D5AA6E1369B3B1BDE8F047506923 +:10295000184789F31188B38C95F8641028461940FC +:1029600000F04EFA8AF31188F469B6E780B2308538 +:1029700088F31188F469B9E7BDE8F08708B5034822 +:10298000FFF778FFBDE8084000F02CBEAC22002025 +:1029900008B50348FFF76EFFBDE8084000F022BE0F +:1029A0001823002000F1604303F561430901C9B217 +:1029B00083F80013012200F01F039A4043099B0093 +:1029C00003F1604303F56143C3F880211A60704747 +:1029D00000F16040090100F56D40C9B20176704711 +:1029E000FFF7CCBD012300F10802C0E90222037009 +:1029F00000F110020023C0E90422C0E90633C0E957 +:102A0000083343607047000010B52023044683F369 +:102A10001188022303704160FFF7D2FD0423237065 +:102A2000002383F3118810BD2DE9F0411F460446B1 +:102A30000D461646202383F3118800F108082378F9 +:102A4000052B0DD029462046FFF7E0FD40B120467A +:102A500032462946FFF7FAFD002080F3118808E08E +:102A60003946404600F024FB0028E8D0002383F3D9 +:102A70001188BDE8F08100002DE9F0411F460446B1 +:102A80000D461646202383F3118800F110082378A1 +:102A9000052B0DD029462046FFF70EFE40B12046FB +:102AA00032462946FFF720FE002080F3118808E017 +:102AB0003946404600F0FCFA0028E8D0002383F3B2 +:102AC0001188BDE8F0810000F8B5154682680669F6 +:102AD000AA420B46816938BF8568761AB54204461A +:102AE0000BD218462A46FEF757FCA3692B44A36174 +:102AF000A3685B1BA3602846F8BD0CD91846324674 +:102B0000FEF74AFCAF1BE1683A463044FEF744FC4E +:102B1000E3683B44EBE718462A46FEF73DFCE368D2 +:102B2000E5E7000083689342F7B51546044638BFD1 +:102B30008568D0E90460361AB5420BD22A46FEF702 +:102B40002BFC63692B446361A36828465B1BA3606D +:102B500003B0F0BD0DD932460191FEF71DFC01997D +:102B6000E068AF1B3A463144FEF716FCE3683B448D +:102B7000E9E72A46FEF710FCE368E4E710B50A44EB +:102B80000024C361029B8460C0E90000C0E9051114 +:102B9000C1600261036210BD08B5D0E905329342FD +:102BA00001D1826882B98268013282605A1C426116 +:102BB0001970D0E904329A4224BFC36843610021EE +:102BC00000F086FA002008BD4FF0FF30FBE7000060 +:102BD00070B5202304460E4683F31188A568A5B17D +:102BE000A368A269013BA360531CA3611578226905 +:102BF000934224BFE368A361E3690BB12046984781 +:102C0000002383F31188284607E03146204600F070 +:102C10004FFA0028E2DA85F3118870BD2DE9F74FED +:102C200004460E4617469846D0F81C904FF0200AEE +:102C30008AF311884FF0000B154665B12A463146DC +:102C40002046FFF741FF034660B94146204600F0A9 +:102C50002FFA0028F1D0002383F31188781B03B0EA +:102C6000BDE8F08FB9F1000F03D001902046C847AE +:102C7000019B8BF31188ED1A1E448AF31188DCE75F +:102C8000C0E90511C160C3611144009B8260C0E9C5 +:102C90000000016103627047F8B504460D46164610 +:102CA000202383F31188A768A7B1A368013BA36021 +:102CB00063695A1C62611D70D4E904329A4224BFD0 +:102CC000E3686361E3690BB120469847002080F315 +:102CD000118807E03146204600F0EAF90028E2DAE0 +:102CE00087F31188F8BD0000D0E905239A4210B59A +:102CF00001D182687AB98268013282605A1C82618D +:102D00001C7803699A4224BFC3688361002100F0E4 +:102D1000DFF9204610BD4FF0FF30FBE72DE9F74FFC +:102D200004460E4617469846D0F81C904FF0200AED +:102D30008AF311884FF0000B154665B12A463146DB +:102D40002046FFF7EFFE034660B94146204600F0FB +:102D5000AFF90028F1D0002383F31188781B03B06A +:102D6000BDE8F08FB9F1000F03D001902046C847AD +:102D7000019B8BF31188ED1A1E448AF31188DCE75E +:102D8000026843681143016003B1184770470000AF +:102D90001430FFF743BF00004FF0FF331430FFF74C +:102DA0003DBF00003830FFF7B9BF00004FF0FF33E0 +:102DB0003830FFF7B3BF00001430FFF709BF000041 +:102DC0004FF0FF311430FFF703BF00003830FFF73A +:102DD00063BF00004FF0FF323830FFF75DBF0000E7 +:102DE00000207047FFF7F4BC044B03600023C0E9E8 +:102DF0000233436001230374704700BFF03B0008B7 +:102E000038B5C36904460D461BB904210844FFF7D1 +:102E1000B7FF294604F11400FFF7BEFE002806DACA +:102E2000201D4FF48061BDE83840FFF7A9BF38BDD1 +:102E3000024B0022C3E900339A607047042400204B +:102E4000002303748268054B1B6899689142FBD28A +:102E50005A68036042601060586070470424002084 +:102E600008B5202383F31188037C032B05D0042BA2 +:102E70000DD02BB983F3118808BD436900221A6075 +:102E80004FF0FF334361FFF7DBFF0023F2E7D0E9A8 +:102E9000003213605A60F3E7002303748268054B25 +:102EA0001B6899689142FBD85A68036042601060C1 +:102EB0005860704704240020054B1969087418688D +:102EC00002681A605360186101230374FDF780BB28 +:102ED0000424002030B54B1C0B4D87B0044610D0A5 +:102EE0002B690A4A01A800F01BF92046FFF7E4FF0E +:102EF000049B13B101A800F02FF92B69586907B0A2 +:102F000030BDFFF7D9FFF8E704240020612E000848 +:102F100038B50C4D41612B6981689A68914204462D +:102F200003D8BDE83840FFF78BBF1846FFF7B4FF62 +:102F300001232C61014623742046BDE83840FDF78B +:102F400047BB00BF04240020044B1A681B6990682B +:102F50009B68984294BF0020012070470424002001 +:102F600010B5084C236820691A6822605460012259 +:102F700023611A74FFF790FF01462069BDE81040F5 +:102F8000FDF726BB0424002008B5FFF7DDFF18B1CC +:102F9000BDE80840FFF7E4BF08BD0000FFF7E0BF51 +:102FA000FEE7000010B50C4CFFF742FF00F0AAF856 +:102FB0000A498022204600F031F8012344F8180C19 +:102FC000037400F0EBFA002383F3118862B604481F +:102FD000BDE8104000F042B82C240020183C000846 +:102FE000283C000800F0CAB8EFF3118020B9EFF3D5 +:102FF0000583202282F311887047000010B530B994 +:10300000EFF30584C4F3080414B180F3118810BDF4 +:10301000FFF7BAFF84F31188F9E70000826002220B +:10302000028270478368A3F17C0243F80C2C02698A +:1030300043F83C2C426943F8382C074A43F81C2CCF +:10304000C26843F8102C022203F8082C002203F86F +:10305000072CA3F118007047E905000810B52023DC +:1030600083F31188FFF7DEFF00210446FFF750FFCE +:10307000002383F31188204610BD0000024B1B691A +:1030800058610F20FFF718BF04240020202383F38A +:103090001188FFF7F3BF000008B50146202383F332 +:1030A00011880820FFF716FF002383F3118808BD5D +:1030B00049B1064B42681B6918605A60136043604F +:1030C0000420FFF707BF4FF0FF30704704240020B3 +:1030D0000368984206D01A68026050605961184629 +:1030E000FFF7AEBE7047000038B504460D462068B5 +:1030F000844200D138BD036823605C604561FFF7FE +:103100009FFEF4E7054B03F11402C3E905224FF0DB +:10311000FF32DA6100221A62704700BF04240020E7 +:1031200010B5C0E903230B4A136A53699C68A14296 +:103130000CD85C68816003604460206058609868C7 +:10314000411A99604FF0FF33D36110BD1B68091B12 +:10315000ECE700BF04240020036881689A680A44F1 +:103160009A60426813605A600023C360024B4FF0BC +:10317000FF32DA61704700BF0424002038B50F4CDD +:10318000236A22460133236252F8143F934206D049 +:103190009A68013A9A60202563699A6802B138BD3D +:1031A000D3E9001001604860D968DA6082F31188C1 +:1031B0001869884785F31188EEE700BF04240020D2 +:1031C00000207047FEE70000704700004FF0FF301E +:1031D00070470000BFF34F8F024AD368DB07FCD46F +:1031E000704700BF0020024008B5074B1B7853B959 +:1031F000FFF7F0FF054B1A69120641BF044A5A60F7 +:1032000002F188325A6008BD90250020002002405B +:103210002301674508B5054B1B7833B9FFF7DAFF83 +:10322000034A136943F08003136108BD9025002011 +:10323000002002407F289ABF00F58030C0020020A5 +:10324000704700004FF40060704700008020704716 +:103250007F2808B50BD8FFF7EDFF00F50063026883 +:10326000013204D104308342F9D1012008BD00208D +:10327000FCE700007F2838B5044623D8FFF7B4FEEA +:10328000FFF7A8FFFFF7B0FF0F4BF322DA6002222F +:103290001A6105462046FFF7CDFF58611A6942F0D2 +:1032A00040021A614FF40061FFF794FF00F026F925 +:1032B0002846FFF7AFFFFFF7A1FE2046BDE83840E4 +:1032C000FFF7C6BF002038BD0020024012F0010306 +:1032D0002DE9F04704460E46154606D0244B40F231 +:1032E000BD221A600020BDE8F0878118214A914272 +:1032F00004D91F4A40F2C2211160F3E7FFF774FEC0 +:10330000FFF772FFFFF766FFDFF8789031464FF066 +:10331000010AA61B012D06EB0107884605D8FFF719 +:1033200079FFFFF76BFE0120DDE7B8F80030C9F840 +:1033300010A03B800024FFF74DFFC9F810403B88E8 +:1033400031F8022B9BB29A420FD0094B40F2D9229E +:103350001A60094B1F60094B1D60094BC3F80080C0 +:10336000FFF758FFFFF74AFEBCE7023DD2E700BF78 +:103370008C250020000004088025002088250020DE +:103380008425002000200240084908B50B7828B1A8 +:103390001BB9FFF729FF01230B7008BD002BFCD0E0 +:1033A000BDE808400870FFF735BF00BF902500203A +:1033B00030B583B0FFF718FE0E4B0F4D1B6A2A681D +:1033C0004FF47A7101FB03F3934237BF0B4A0B4969 +:1033D000516814682B602EBFD1E900410131516062 +:1033E0001C1941F100010191FFF708FE01992046E7 +:1033F00003B030BD0424002094250020982500202F +:1034000030B583B0FFF7F0FD114B124D1B6A2A68EF +:103410004FF47A7101FB03F3934237BF0E4A0E4912 +:10342000516814682B602EBFD1E900410131516011 +:103430001C1941F100010191FFF7E0FD01994FF4E2 +:103440007A7200232046FCF7ABFE03B030BD00BF0C +:1034500004240020942500209825002010B5024463 +:10346000064BD2B2904200D110BD441C00B253F8BA +:10347000200041F8040BE0B2F4E700BF5028004000 +:103480000F4B30B51C6A240407D41C6A44F4407402 +:103490001C621C6A44F400441C620A4C236843F416 +:1034A000807323600244084BD2B2904200D130BDF9 +:1034B000441C00B251F8045B43F82050E0B2F4E73A +:1034C00000100240007000405028004007B5012263 +:1034D00001A90020FFF7C2FF019803B05DF804FBCB +:1034E00013B50446FFF7F2FFA04205D0012201A95F +:1034F00000200194FFF7C4FF02B010BD7047000028 +:10350000074B45F255521A6002225A6040F6FF728C +:103510009A604CF6CC421A60024B01221A70704736 +:1035200000300040A4250020034B1B781BB1034B47 +:103530004AF6AA221A607047A425002000300040F5 +:10354000044B1A682AB902F1804202F50432526A29 +:103550001A607047A0250020024B4FF080725A621B +:10356000704700BF0010024008B5FFF7E9FF024BAB +:103570001868C0F3407008BDA0250020EFF3098350 +:1035800005494A6B22F001024A63683383F30988D4 +:10359000002383F31188704700EF00E0202080F3C0 +:1035A000118862B60C4B0D4AD96821F4E061090418 +:1035B000090C0A43DA60D3F8FC20094942F0807212 +:1035C000C3F8FC200A6842F001020A601022DA7790 +:1035D00083F82200704700BF00ED00E00003FA0509 +:1035E000001000E010B5202383F311880E4B5B68B8 +:1035F00013F4006314D0F1EE103AEFF30984683C41 +:103600004FF08073E361094BDB6B236684F3098819 +:10361000FFF79AFC10B1064BA36110BD054BFBE709 +:1036200083F31188F9E700BF00ED00E000EF00E050 +:10363000FB050008FE05000870470000FEE70000DB +:103640000A4B0B480B4A90420BD30B4BDA1C121A55 +:10365000C11E22F003028B4238BF00220021FDF779 +:10366000ADBE53F8041B40F8041BECE7103D000806 +:103670002826002028260020282600207047000049 +:103680004B6843608B688360CB68C3600B694361A0 +:103690004B6903628B6943620B68036070470000EB +:1036A00008B51B4B9A6A42F4FC029A629A6A22F4A9 +:1036B000FC029A629A6A5A6942F4FC025A61154AFB +:1036C0005B6911464FF09040FFF7DAFF02F11C01F1 +:1036D00000F58060FFF7D4FF02F1380100F580604B +:1036E000FFF7CEFF02F1540100F58060FFF7C8FF3D +:1036F00002F1700100F58060FFF7C2FF02F18C015A +:1037000000F58060FFF7BCFFBDE8084000F05AB844 +:1037100000100240403C000808B500F093F9FFF7A4 +:1037200041FCBDE80840FFF70BBF000070470000F8 +:1037300010B5214CA36A63F4FC03A362A36A03F4EB +:10374000FC03A3624FF0FF32A36A2369226123695D +:10375000002323612169E168E260E268E360E268D6 +:10376000E269164942F08052E261E2690A6842F475 +:1037700080720A60226A02F44072B2F5407F1EBF76 +:103780004FF4803222622362236A1B0407D4236A27 +:1037900043F440732362236A43F40043236200F03E +:1037A00031F9A369064A43F00103A361A3691368D1 +:1037B00043F02003136010BD001002400070004071 +:1037C000000001401E4B1A6842F001021A601A689C +:1037D0009007FCD55A6822F003025A605A6812F02A +:1037E0000C02FBD1196801F0F90119605A601A68DE +:1037F00042F480321A601A689103FCD5114A5A606B +:103800004FF40452DA6230221A631A6842F080726E +:103810001A601A689201FCD50B4912220A600A68E4 +:1038200002F00702022AFAD15A6842F002025A60F4 +:103830005A6802F00C02082AFAD11A6B1A63704710 +:10384000001002400024050000200240084A08B58C +:10385000516913680B4003F00103536123B1054A1A +:1038600013680BB150689847BDE80840FFF7BABE2F +:1038700000040140A8250020084A08B551691368D2 +:103880000B4003F00203536123B1054A93680BB167 +:10389000D0689847BDE80840FFF7A4BE0004014087 +:1038A000A8250020084A08B5516913680B4003F0A9 +:1038B0000403536123B1054A13690BB1506998475A +:1038C000BDE80840FFF78EBE00040140A825002097 +:1038D000084A08B5516913680B4003F008035361A7 +:1038E00023B1054A93690BB1D0699847BDE80840F8 +:1038F000FFF778BE00040140A8250020084A08B55B +:10390000516913680B4003F01003536123B1054A5A +:10391000136A0BB1506A9847BDE80840FFF762BED2 +:1039200000040140A8250020174B10B55A691C68F7 +:10393000144004F478725A61A30604D5134A936ABA +:103940000BB1D06A9847600604D5104A136B0BB1CF +:10395000506B9847210604D50C4A936B0BB1D06B82 +:103960009847E20504D5094A136C0BB1506C98478F +:10397000A30504D5054A936C0BB1D06C9847BDE8FC +:103980001040FFF72FBE00BF00040140A825002013 +:103990001A4B10B55A691C68144004F47C425A61F1 +:1039A000620504D5164A136D0BB1506D9847230577 +:1039B00004D5134A936D0BB1D06D9847E00404D53C +:1039C0000F4A136E0BB1506E9847A10404D50C4AF0 +:1039D000936E0BB1D06E9847620404D5084A136FFA +:1039E0000BB1506F9847230404D5054A936F0BB170 +:1039F000D06F9847BDE81040FFF7F4BD00040140C8 +:103A0000A8250020062108B50846FEF7CBFF0621B1 +:103A10000720FEF7C7FF06210820FEF7C3FF062197 +:103A20000920FEF7BFFF06210A20FEF7BBFF062193 +:103A30001720FEF7B7FFBDE8084006212820FEF753 +:103A4000B1BF000008B5FFF773FE00F00DF8FEF7F8 +:103A5000C7FFFFF7C7F9FFF769FEBDE8084000F0B0 +:103A600001B8000000F00EB80023054A19460133E2 +:103A7000102BC2E9001102F10802F8D1704700BF13 +:103A8000A82500204FF0E023044A5A6100229A61E1 +:103A900007221A6108210B20FEF79ABF3F19010087 +:103AA00008B5202383F31188FFF79CFA002383F3E2 +:103AB000118808BD08B5FFF7F3FFBDE80840FFF720 +:103AC00091BD000010B501390244904201D100209F +:103AD00005E0037811F8014FA34201D0181B10BD77 +:103AE0000130F2E72DE9F041A3B1C91A177801447A +:103AF000044603F1FF3C8C42204601D9002009E036 +:103B00000578BD4204F10104F5D10CEB0405D6188B +:103B1000A54201D1BDE8F08115F8018D16F801ED3F +:103B2000F045F5D0E7E70000034611F8012B03F854 +:103B3000012B002AF9D170476F72672E617264758C +:103B400070696C6F742E48697465634D6F73616939 +:103B5000630000004E6F20617070207369670A0077 +:103B6000426164206677206C656E677468202575F5 +:103B70000A0042616420626F6172645F696420259B +:103B8000752073686F756C642062652025750A0066 +:103B90004261642066772064657363726970746F34 +:103BA00072206C656E6774682025750A0042616436 +:103BB0002061707020435243203078253038783AA5 +:103BC000307825303878203078253038783A307899 +:103BD000253038780A00476F6F64206669726D7708 +:103BE0006172650A0040A2E4F16468910600000079 +:103BF00000000000AD2D0008992D0008D52D00080B +:103C0000C12D0008CD2D0008B92D0008A52D0008F4 +:103C1000912D0008E12D00086D61696E0000000023 +:103C200069646C6500000000203C00084824002006 +:103C30008025002001000000A12F000800000000E6 +:103C4000A010002800000000FAAAAAAA500400242C +:103C5000BFFF000000770000000000001410AA0061 +:103C600000000000AAAAFAAA04005000FBFF00000E +:103C70000000000099770000000000000000000034 +:103C8000AAAAAAAA00000000FFFF0000000000008E +:103C9000000000000000000000000000AAAAAAAA7C +:103CA00000000000FFFF0000000000000000000016 +:103CB0000000000000000000AAAAAAAA000000005C +:103CC000FFFF0000000000000000000000000000F6 +:103CD00000000000AAAAAAAA00000000FFFF00003E +:103CE0000000000000000000E8C4FF7F01000000A9 +:103CF000F80300000000000000980300000000002E +:103D00006400000000000000FE2A0100D204000050 :00000001FF diff --git a/Tools/bootloaders/HolybroG4_GPS_bl.bin b/Tools/bootloaders/HolybroG4_GPS_bl.bin new file mode 100755 index 00000000000..27909f4a594 Binary files /dev/null and b/Tools/bootloaders/HolybroG4_GPS_bl.bin differ diff --git a/Tools/bootloaders/HolybroG4_GPS_bl.elf b/Tools/bootloaders/HolybroG4_GPS_bl.elf new file mode 100755 index 00000000000..c8e5d7c421d Binary files /dev/null and b/Tools/bootloaders/HolybroG4_GPS_bl.elf differ diff --git a/Tools/bootloaders/HolybroG4_GPS_bl.hex b/Tools/bootloaders/HolybroG4_GPS_bl.hex new file mode 100644 index 00000000000..18c169dad9e --- /dev/null +++ b/Tools/bootloaders/HolybroG4_GPS_bl.hex @@ -0,0 +1,1351 @@ +:020000040800F2 +:1000000000070020F5040008212D0008A12C00089D +:10001000F92C0008A12C0008CD2C0008F7040008DA +:10002000F7040008F7040008F7040008753B00080F +:10003000F7040008F7040008F7040008F7040008B4 +:10004000F7040008F7040008F7040008F7040008A4 +:10005000F7040008F7040008A14D0008C94D000886 +:10006000F14D0008194E0008414E0008F704000841 +:10007000F7040008F7040008F7040008F704000874 +:10008000F7040008F7040008F7040008F704000864 +:10009000F7040008ED28000801290008694E00084F +:1000A000F7040008F7040008F7040008F704000844 +:1000B000514F0008F7040008F7040008F70400088F +:1000C000F7040008F7040008F7040008F704000824 +:1000D000F7040008F70400083D4F0008F704000883 +:1000E000CD4E0008F7040008F7040008F7040008E4 +:1000F000F7040008F7040008F7040008F7040008F4 +:10010000F7040008F7040008F7040008F7040008E3 +:10011000F7040008F7040008F7040008F7040008D3 +:10012000F7040008F7040008F7040008F7040008C3 +:10013000F7040008F7040008F7040008F7040008B3 +:10014000F7040008F7040008F7040008F7040008A3 +:10015000F7040008F7040008F7040008F704000893 +:10016000F7040008F7040008F7040008F704000883 +:10017000F7040008F7040008F7040008F704000873 +:10018000F7040008F7040008F7040008F704000863 +:10019000F7040008F70400081529000829290008B9 +:1001A000F7040008F7040008F7040008F704000843 +:1001B000F7040008F7040008F7040008F704000833 +:1001C000F7040008F7040008F7040008F704000823 +:1001D000F7040008F7040008F7040008F704000813 +:1001E000A11800080000000000000000000000004E +:1001F00053B94AB9002908BF00281CBF4FF0FF318E +:100200004FF0FF3000F074B9ADF1080C6DE904CE89 +:1002100000F006F8DDF804E0DDE9022304B07047E1 +:100220002DE9F047089D04468E46002B4DD18A42A9 +:10023000944669D9B2FA82F252B101FA02F3C2F1DC +:10024000200120FA01F10CFA02FC41EA030E94406D +:100250004FEA1C48210CBEFBF8F61FFA8CF708FB8E +:1002600016E341EA034306FB07F199420AD91CEB66 +:10027000030306F1FF3080F01F81994240F21C8198 +:10028000023E63445B1AA4B2B3FBF8F008FB1033E0 +:1002900044EA034400FB07F7A7420AD91CEB040415 +:1002A00000F1FF3380F00A81A74240F207816444E5 +:1002B000023840EA0640E41B00261DB1D44000236A +:1002C000C5E900433146BDE8F0878B4209D9002DCE +:1002D00000F0EF800026C5E9000130463146BDE858 +:1002E000F087B3FA83F6002E4AD18B4202D38242C2 +:1002F00000F2F980841A61EB030301209E46002D71 +:10030000E0D0C5E9004EDDE702B9FFDEB2FA82F2C5 +:10031000002A40F09280A1EB0C014FEA1C471FFA23 +:100320008CFE0126200CB1FBF7F307FB131140EA0A +:1003300001410EFB03F0884208D91CEB010103F1D7 +:10034000FF3802D2884200F2CB804346091AA4B299 +:10035000B1FBF7F007FB101144EA01440EFB00FE6D +:10036000A64508D91CEB040400F1FF3102D2A645D2 +:1003700000F2BB800846A4EB0E0440EA03409CE771 +:10038000C6F12007B34022FA07FC4CEA030C20FA1E +:1003900007F401FA06F31C43F9404FEA1C4900FA3E +:1003A00006F3B1FBF9F8200C1FFA8CFE09FB1811BB +:1003B00040EA014108FB0EF0884202FA06F20BD92E +:1003C0001CEB010108F1FF3A80F08880884240F27E +:1003D0008580A8F102086144091AA4B2B1FBF9F0C2 +:1003E00009FB101144EA014100FB0EFE8E4508D9BD +:1003F0001CEB010100F1FF346CD28E456AD9023842 +:10040000614440EA0840A0FB0294A1EB0E01A14226 +:10041000C846A64656D353D05DB1B3EB080261EB94 +:100420000E0101FA07F722FA06F3F1401F43C5E96E +:10043000007100263146BDE8F087C2F12003D840A4 +:100440000CFA02FC21FA03F3914001434FEA1C47E6 +:100450001FFA8CFEB3FBF7F007FB10360B0C43EAD8 +:10046000064300FB0EF69E4204FA02F408D91CEB88 +:10047000030300F1FF382FD29E422DD90238634486 +:100480009B1B89B2B3FBF7F607FB163341EA034126 +:1004900006FB0EF38B4208D91CEB010106F1FF3875 +:1004A00016D28B4214D9023E6144C91A46EA00466C +:1004B00038E72E46284605E70646E3E61846F8E6FE +:1004C0004B45A9D2B9EB020864EB0C0E0138A3E747 +:1004D0004646EAE7204694E74046D1E7D0467BE728 +:1004E000023B614432E7304609E76444023842E7A0 +:1004F000704700BF02E000F000F8FEE772B63A482D +:1005000080F30888394880F3098839484EF6085145 +:10051000CEF20001086040F20000CCF200004EF67E +:100520003471CEF200010860BFF34F8FBFF36F8FBD +:1005300040F20000C0F2F0004EF68851CEF2000109 +:100540000860BFF34F8FBFF36F8F4FF00000E1EEF5 +:10055000100A4EF63C71CEF200010860062080F3CE +:100560001488BFF36F8F04F0ADFA04F089FA04F039 +:10057000D3FA4FF055301F491B4A91423CBF41F816 +:10058000040BFAE71C49194A91423CBF41F8040B9D +:10059000FAE71A491A4A1B4B9A423EBF51F8040B1C +:1005A00042F8040BF8E700201749184A91423CBF73 +:1005B00041F8040BFAE704F067FA04F0F3FA144C7C +:1005C000144DAC4203DA54F8041B8847F9E700F0F5 +:1005D00041F8114C114DAC4203DA54F8041B884722 +:1005E000F9E704F04FBA00000007002000230020C4 +:1005F000000000080001002000070020B853000898 +:10060000002300208C230020902300207064002011 +:10061000E0010008E4010008E4010008E40100082A +:100620002DE9F04F2DED108AC1F80CD0C3689D461E +:10063000BDEC108ABDE8F08F002383F311882846B3 +:10064000A047002003F010FFFEE703F089FE00DF63 +:10065000FEE70000F8B504F0B5F9074604F006FA25 +:100660000546A0BB1F4B9F4231D001339F4231D082 +:100670001D4B27F0FF029A422FD1F8B200F036FD51 +:100680002E4642F2107400F03BFF08B100242646CB +:1006900000F032FD08B90646044635B1134B9F42BF +:1006A00003D004F0DBF900242646002004F094F97E +:1006B0000EB100F063F801F06FFA00F045FF01F0B1 +:1006C00059F9204600F0A8F800F058F8F9E72E464E +:1006D0000024D8E704460126D5E7064640F6C414B0 +:1006E000D1E700BF010007B0000008B0263A09B00A +:1006F00008B501F011F9A0F120035842584108BD96 +:1007000007B541F21203022101A8ADF8043001F04F +:1007100021F903B05DF804FB10B5202383F31188A1 +:100720001248C3680BB103F017FF114A0F480023AA +:100730004FF47A7103F0D4FE002383F311880D4C3B +:10074000236813B12368013B2360636813B16368B6 +:10075000013B6360084B1B7833B9636823B90220FF +:1007600001F0A8F93223636010BD00BF9023002080 +:1007700019070008AC240020A4230020214B224AA2 +:1007800010B51C46196801313BD004339342F9D1AE +:100790006268A24235D31D4B9B6803F1006303F5E9 +:1007A00010439A422DD204F02BF904F03DF90020B9 +:1007B00001F0FAF8164B0220187001F071F9154B90 +:1007C0009A6D00229A65996F9A67996FD96DDA656B +:1007D000D96FDA67D96F196E1A66D3F88010C3F82B +:1007E0008020D3F8803072B64FF0E0232021C3F888 +:1007F000084DD4E9003281F311889D4683F30888BF +:10080000104710BD00900008209000080023002031 +:10081000A4230020001002402DE9F04F93B0AC4B10 +:1008200000902022FF210AA89D6801F05FF9A94AE3 +:100830001378A3B9A8480121C3601170202383F362 +:100840001188C3680BB103F087FEA44AA2480023B5 +:100850004FF47A7103F044FE002383F31188009B68 +:100860009F4A03B113609F49009C00230B705360A3 +:1008700098469B461E469A46012001F011F924B184 +:10088000974B1B68002B00F01C82002001F044F8FD +:100890000390039B002B01DA00F0A6FE039B002BC4 +:1008A000EDDB012001F0F2F8039B213B162BE3D88E +:1008B00001A252F823F000BF150900083D09000805 +:1008C000D1090008790800087908000879080008AB +:1008D000650A0008370C0008510B0008B30B00082C +:1008E000DB0B0008010C000879080008130C000855 +:1008F00079080008850C0008B50900087908000887 +:10090000C90C000821090008B50900087908000889 +:10091000B30B00080220FFF7EBFE002840F0FB813C +:10092000009B0221B8F1000F08BF1C4605A841F248 +:100930001233ADF8143001F00DF89DE74FF47A70E2 +:1009400000F0EAFF071EEBDB0220FFF7D1FE0028D4 +:10095000E6D0013F052F00F2E081DFE807F0030A4F +:100960000D10133605230593042105A800F0F2FFAE +:1009700017E057480421F9E75B480421F6E75B4894 +:100980000421F3E74FF01C09484601F00FF809F184 +:1009900004090590042105A800F0DCFFB9F12C0F33 +:1009A000F2D1012000FA07F747EA0B0B5FFA8BFB45 +:1009B0004FF0000A01F0E6F826B10BF00B030B2B09 +:1009C00008BF0024FFF79CFE56E749480421CDE705 +:1009D000002EA5D00BF00B030B2BA1D10220FFF7AB +:1009E00087FE074600289BD001203E4E00F0DCFF2A +:1009F0000220307001F054F84FF000085FFA88F9D7 +:100A0000484600F0E1FF044690B1484600F0ECFF94 +:100A100008F101080028F1D1B846044641F212134A +:100A2000022105A8ADF814303E4600F093FF23E7FD +:100A300001230220337001F029F82546244B9B68DE +:100A4000AB4207D9284600F0B1FF013040F0688181 +:100A50000435F3E7234B00251D70214BB8465D603C +:100A60003E46A7E7002E3FF45BAF0BF00B030B2BCA +:100A70007FF456AF1B4B0220187001F011F83220A2 +:100A800000F04AFFB0F10009FFF64AAF19F0030782 +:100A90007FF446AF0E4A926809EB050393423FF696 +:100AA0003FAFB9F5807F3FF73BAF124B0193B9459C +:100AB00022DD4FF47A7000F02FFF0390039A002A92 +:100AC000FFF62EAF019B039A03F8012B0137EDE7E8 +:100AD00000230020A82400209023002019070008EC +:100AE000AC240020A423002004230020082300209D +:100AF0000C230020A8230020C820FFF7F9FD07469B +:100B000000283FF40DAF1F2D11D8C5F120024A4532 +:100B10000AAB25F0030028BF4A46834901921844D6 +:100B200000F0D2FF019A8048FF2100F0DFFF4FEA7A +:100B3000A9037D490193C9F38702284600F0DEFF2F +:100B4000064600283FF46AAF019B05EB830531E7B9 +:100B50000220FFF7CDFD00283FF4E2AE00F060FF79 +:100B600000283FF4DDAE0027B946704B9B68BB42BE +:100B700018D91F2F11D80A9B01330ED027F0030379 +:100B800012AA134453F8203C05934846042205A9B1 +:100B900002F0D4F804378146E7E7384600F006FF54 +:100BA0000590F2E7CDF81490042105A800F0D2FEDC +:100BB00000E70023642104A8049300F0C1FE00288C +:100BC0007FF4AEAE0220FFF793FD00283FF4A8AEFD +:100BD000049800F01BFF0590E6E70023642104A8B9 +:100BE000049300F0ADFE00287FF49AAE0220FFF7D8 +:100BF0007FFD00283FF494AE049800F009FFEAE777 +:100C00000220FFF775FD00283FF48AAE00F018FFC0 +:100C1000E1E70220FFF76CFD00283FF481AE05A953 +:100C2000142000F013FF04210746049004A800F0EC +:100C300091FE3946B9E7322000F06EFE071EFFF63E +:100C40006FAEBB077FF46CAE384A926807EB0A03BD +:100C500093423FF665AE0220FFF74AFD00283FF4BD +:100C60005FAE27F003075744BA453FF4A3AE5046A2 +:100C700000F09CFE0421059005A800F06BFE0AF12F +:100C8000040AF1E74FF47A70FFF732FD00283FF4D1 +:100C900047AE00F0C5FE002844D00A9B01330BD0BC +:100CA00008220AA9002000F029FF00283AD02022BB +:100CB000FF210AA800F01AFFFFF722FD1C4803F0ED +:100CC000D9FB13B0BDE8F08F002E3FF429AE0BF036 +:100CD0000B030B2B7FF424AE0023642105A805939E +:100CE00000F02EFE074600287FF41AAE0220FFF720 +:100CF000FFFC814600283FF413AEFFF701FD41F2EF +:100D0000883003F0B7FB059800F052FF4E4600F024 +:100D100039FF3C46B0E506464CE64FF0000AFFE5D9 +:100D2000B8467BE6374679E6A8230020002300205A +:100D3000A0860100094A136849F2690099B21B0CA8 +:100D400000FB01331360064B186844F2506182B215 +:100D5000000C01FB0200186080B2704714230020D1 +:100D60001023002010B500211022044600F0BEFE22 +:100D7000034B03CB206061601868A06010BD00BF0A +:100D80009075FF1F2DE9F043224DBBB001F0D0FF5D +:100D9000AB6840F2ED22C31A934232D906AFA86085 +:100DA0002B4628220021384602F0A0FC05F10E0057 +:100DB00000F094FE002604465FFA80F905F10E0863 +:100DC000F3B2F100994501F1280107D908EB0603B8 +:100DD0000822384602F08AFC0136F1E70823012296 +:100DE000CDE9023205340C4B0193A4B230230093B9 +:100DF000CDE9047405A3D3E90023297B074802F059 +:100E00008DFA3BB0BDE8F083AFF3008078F6339FF6 +:100E100093CACD8D585E0020655E0020CC34002042 +:100E200070B50D4614461E4602F00EFA50B9022E59 +:100E300010D1012C0ED112A3D3E90023C5E9002360 +:100E4000012007E0282C10D005D8012C09D0052C52 +:100E50000FD0002070BD302CFBD10BA3D3E90023B1 +:100E6000ECE70BA3D3E90023E8E70BA3D3E90023C6 +:100E7000E4E70BA3D3E90023E0E700BFAFF3008072 +:100E8000401DA12026812A0B78F6339F93CACD8D71 +:100E90009E6AC421818A46EE26417272DF25D7B749 +:100EA000F017304A39059E5613B5044623460846C6 +:100EB00020220021019002F019FC22790198032AD6 +:100EC000234628BF032203F8042F2021022202F028 +:100ED0000DFC62790198072A234628BF072203F8F0 +:100EE000052F2221032202F001FCA2790198072A92 +:100EF000234628BF072203F8062F2521032202F0EC +:100F0000F5FB019804F108031022282102F0EEFB02 +:100F1000382002B010BD00002DE9F04FADF5017D85 +:100F200021AD0EAE40F2751280460F4622A8002178 +:100F3000296000F0DBFD48220021304600F0D6FD9C +:100F400001F0F6FE564B4FF47A72B0FBF2F01860E7 +:100F500093E80700012386E807000DF15A00338269 +:100F6000FFF700FF41F60453338407AB18464D49A1 +:100F700004F0D6F81B2230642946304686F83C201F +:100F8000FFF792FF12AB044601460822284602F002 +:100F9000ADFB0822A1180DF14903284602F0A6FB7B +:100FA0000DF14A03082204F11001284602F09EFBCD +:100FB00013AB202204F11801284602F097FB14AB72 +:100FC000402204F13801284602F090FB16AB0822BB +:100FD00004F17801284602F089FB0DF1590308223B +:100FE00004F18001284602F081FB04F1880A0DF12A +:100FF0005A0904F5847B4B465146082228460AF1DB +:10100000080A02F073FBD34509F10109F3D11BABC8 +:1010100008225946284602F069FB04F588744FF00F +:10102000000996F834304B450AD9B36B21464B443E +:101030000822284602F05AFB083409F10109F0E7BA +:101040004FF0000996F83C304B4504EBC90108D934 +:10105000336C08224B44284602F048FB09F1010991 +:10106000F0E700230393BB7E0293073107F11903D6 +:101070000193C1F3CF010123CDE904510093F97E1F +:1010800005A3D3E90023404602F048F90DF5017DA0 +:10109000BDE8F08FAFF300809E6AC421818A46EEDE +:1010A000B424002050510008F8B50E4C0E4F022613 +:1010B000A4F5805343F8307C237E3BB965692DB19C +:1010C000284601F0B3FC284603F094FF204601F0C7 +:1010D000ADFCA4F5A554012EA4F1100400D1F8BD77 +:1010E0000126E5E7D859002040520008014B18704E +:1010F000704700BFC0240020F0B5334B1C7B85B087 +:1011000034B1324B0E221A810024204605B0F0BDC6 +:101110002F4A1068516802AB03C308232D492E489B +:101120000DEB030203F08EFF054630B9274B2B4829 +:101130000A221A8101F002FCE6E70169B1F5EE2FFF +:1011400006D9224B26480B221A8101F0F7FBDCE777 +:10115000438B40F21D42934207D01C490C2008816A +:101160001946204801F0EAFBCFE71F4A024402F18A +:101170001003994204D2154B1C4810221A81E4E74F +:1011800010398E1A2046144901F0D8FD3246074620 +:1011900005F11801204601F0D1FDAB689F4202D154 +:1011A000EB6898420AD0094B0D221A810090D5E9CC +:1011B00002123B460E4801F0C1FBA5E70D4801F0C5 +:1011C000BDFB0124A1E700BF585E0020B42400202D +:1011D000FD510008DC6F0700009000086C5100080A +:1011E000785100088A5100080870FFF7A8510008DC +:1011F000C5510008EE5100082DE9F04FADB006AF23 +:1012000080460C4602F020F8054600285AD1237E7D +:10121000022B1BD1E38A012B18D101F089FD064670 +:10122000FFF788FD03464FF4C870DFF8D092B3FB98 +:10123000F0F206F5167602FB103316FA83F3C9F8BE +:101240000030E37E33B9A84B00221A709C37BD46AC +:10125000BDE8F08FA38AEEB2013BB34205F1010570 +:101260000BD93B1D1E44E90000960023082201F023 +:10127000F801204602F0FEF8ECE707F11400FFF752 +:1012800071FD324607F11401381D03F0CBFE002832 +:10129000D9D10F2E08D8944B1E70D9F80030A3F581 +:1012A0001673C9F80030D1E7FB1CF87001460093B3 +:1012B00007220346204602F0DDF8F978404601F0A7 +:1012C000BBFFC3E7E38A282B26D010D8012B1ED002 +:1012D000052BBBD1BFF34F8F8449854BCA6802F4FD +:1012E000E0621343CB60BFF34F8F00BFFDE7302BAD +:1012F000ACD1637E7F4D01336A7BDBB29342E9461A +:1013000003D1E27E2B7B9A4265D0CD469EE72146F3 +:101310004046FFF701FE99E7A38A013B9BB2C92B28 +:1013200094D8744D2E7B26BB05F10C030093082244 +:1013300033463146204602F09DF8731CF2B2D900C4 +:101340001E46A38A013B9A4205DA0E322A440092D5 +:1013500000230822EEE700230022C5E90023002332 +:10136000AB6085F8D730C5F8D8302B7B0BB9E37E5E +:101370002B73002507F114093B1D08222946484616 +:10138000C7E90155FD6002F0B1F93B7A05F1010AA8 +:10139000AB424FEACA0608D9FB6808222B44314603 +:1013A000484602F0A3F95546EFE7C6F3CF06E17EC3 +:1013B000CDE9049600230393A37E029319342823D6 +:1013C0000093019446A3D3E90023404601F0A6FF11 +:1013D000FFF7D8FC3AE74FF0000807F11403A7F82D +:1013E00014801022009341460123204602F042F867 +:1013F000A68A023EB6B2F31C9B109B000733DB08A3 +:10140000A9EBC3039D460DF1180A1FFA88F34FEAB2 +:10141000C801B34201F110010AD20AEB080300939C +:1014200008220023204602F025F808F10108ECE725 +:1014300095F8D70000F0C8FAD5F8D83004461BB9A3 +:1014400095F8D70000F0D0FAD5F8D83033449C4254 +:1014500004D295F8D700013000F0C6FA4FEA960B97 +:101460004FF000081FFA88F18B45D5E9003209D901 +:101470000AEB880103EB8800012200F03FFB08F132 +:101480000108EFE7F31842F10002C5E90032D5F890 +:10149000D83095F8D70006EB0308C5F8D88000F0DF +:1014A00093FA804509D395F8D730D5F8D8000133A1 +:1014B000001B85F8D730C5F8D800FF2E08D80023C8 +:1014C0002B7300F0ADFAFFF717FE08B1FFF756F9DE +:1014D0002B68094A9B0A013313810023AB6014E790 +:1014E00026417272DF25D7B7C534002000ED00E039 +:1014F0000400FA05585E0020B4240020C8340020FF +:1015000010B54FF000540C4B22689A4211D10B4B8E +:10151000627D1A700A48237D03730A49C9220E307E +:1015200000F0D2FAE0220021204600F0DFFA01208C +:1015300010BD0020FCE700BF9AAD44C5C0240020C8 +:10154000585E00201600002037B51E4C1E4D1F4966 +:1015500002236B712368204604F580545B680122E6 +:101560009847D4F8B03419495B68012204F59660B5 +:10157000984700230193164B164900931648174BC2 +:101580004FF4805201F032FE154B197811B1124818 +:1015900001F052FE01F0CCFB0446FFF7CBFB4FF409 +:1015A000C873B0FBF3F202FB130304F5167010FAD4 +:1015B00083F00C4B186003F059FA08B10F232B810C +:1015C00003B030BDF8340020B424002040420F00A6 +:1015D000210E0008C4240020CC340020F91100089A +:1015E000C0240020C83400202DE9F04F2DED028BDF +:1015F0009F4D93B0DFF8A0A29E4F284601F0F2FE67 +:10160000034600283ED00024CDE90F440E94ADF8E7 +:101610004440027B8DF8442099684068964E0FAA9A +:1016200003C21B6843F000430E93A046A1463368F3 +:10163000D3F810B001F07EFB10EB0A0241F1000379 +:101640003046CDF800900EA9D84704F22C5440F64D +:1016500058230028C8BF48F0010806F5A5569C424B +:1016600006F11006E3D1B8F1000F05D0284601F0CD +:10167000BDFE87F80090C0E73B78072B00F2E780BB +:1016800001333B700DF12C089FED738B0023DFF8C5 +:101690000C920A93ADF834300B93C8F8043000264E +:1016A000754C374601238DF81C3023688DED008B77 +:1016B0004FF0000BD3F808A08DF81DB05B460DF17C +:1016C0001D0207A92046D0479DF81CA0BAF1000FC3 +:1016D00024D0D9F8143083F48063C9F81430102270 +:1016E00059460EA800F002FA236808AA5F690AA901 +:1016F0000DF11E032046B84798E803000FAB83E8BE +:1017000003009DF834308DF844300A9B0E930EA9E7 +:10171000DDE90823284602F031F8574606F22C5638 +:1017200040F6582304F5A5549E4204F11004B9D1A3 +:10173000002FB4D1284601F087FD002840D14F4E3C +:1017400001F0F6FA336898423AD301F0F1FA044610 +:10175000FFF7F0FA4FF4C87304F51674B0FBF3F218 +:1017600002FB130314FA83F33360454E8DF828709F +:10177000377817B901238DF82830C7F11004E4B287 +:101780000EA8FFF7EFFA062C28BF06240EAB224660 +:10179000D9190DF1290000F097F90AAB039318232A +:1017A00002930134374B0193E4B201230093049474 +:1017B0002BA3D3E90023284601F048FD0023337012 +:1017C00001F0B6FA304A314C1368C31AB3F57A7F88 +:1017D00030D3106001F0AEFA02460B46284601F005 +:1017E0000FFE284601F030FD20B3237B284E002B4E +:1017F00014BF03230223737101F09AFA0EAF4FF462 +:101800007A733946B0FBF3F030603046FFF74CFB9B +:101810001823073002931F4B0193C0F3CF0040F20F +:101820005513CDE90370009328460FA3D3E9002395 +:1018300001F00CFD237B2BB1FFF7A4FA237B002BD7 +:101840007FF4D8AE13B0BDEC028BBDE8F08F284614 +:1018500001F0CCFD16E700BF000000000000000012 +:10186000401DA12026812A0BF1C6A7C1D068080F10 +:10187000CC3400203D5F0020F8340020C834002024 +:10188000C5340020C4340020385F0020585E00209A +:10189000B42400203C5F002040420F0000080048B4 +:1018A00008B5064800F096FB054800F093FBBDE83C +:1018B0000840044A0449002003F096BBF834002095 +:1018C000A8490020945F0020A910000870B50F4BB4 +:1018D0001B780133DBB2012B0C4611D80C4D296863 +:1018E0004FF47A730E6AA2FB033201462246284661 +:1018F000B047844204D1074B00221A70012070BD0A +:101900004FF4FA7002F0B6FD0020F8E7182300202B +:10191000985F0020845F002007B500230246012164 +:101920000DF107008DF80730FFF7D0FF20B19DF8CB +:10193000070003B05DF804FB4FF0FF30F9E700004B +:101940000A4608B50421FFF7C1FF80F00100C0B2CC +:10195000404208BD30B4054C2368DD69044B0A469B +:10196000AC460146204630BC604700BF985F00206F +:10197000A086010070B502F0B5FE094E094D308019 +:10198000002428683388834208D902F0A7FE2B6818 +:1019900004440133B4F5104F2B60F2D370BD00BF87 +:1019A000865F0020405F002002F05EBF00F1006013 +:1019B00000F510400068704700F10060920000F5EB +:1019C000104002F0D5BE0000054B1A68054B1B887D +:1019D0009B1A834202D9104402F080BE0020704757 +:1019E000405F0020865F002038B5074D0446286818 +:1019F000204402F07BFE28B928682044BDE8384026 +:101A000002F086BE38BD00BF405F00200020704756 +:101A100000F10050A0F51040D0F89005704700008C +:101A2000064991F8243033B10023086A81F8243044 +:101A30000822FFF7C1BF0120704700BF445F0020AC +:101A4000014B1868704700BF002004E070B50E4BD2 +:101A50005C6893F90860421E0A44013C0B469342BD +:101A600007D214F9015F581C2DB100F8015C034640 +:101A7000F5E7184605E02C2482421C7001D9981C19 +:101A80005E70401A70BD00BF1C230020022802BFF8 +:101A9000024B4FF080629A61704700BF0008004817 +:101AA000022802BF024B4FF480629A61704700BF68 +:101AB00000080048022801BF024A536983F480638A +:101AC000536170470008004810B50023934203D0CB +:101AD000CC5CC4540133F9E710BD00000346024654 +:101AE000D01A12F9011B0029FAD1704702440346AB +:101AF000934202D003F8011BFAE770472DE9F8433F +:101B00001F4D144695F824200746884652BBDFF83F +:101B100070909CB395F824302BB92022FF214846C1 +:101B20002F62FFF7E3FF95F82400C0F10802A242FC +:101B300028BF2246D6B24146920005EB8000FFF74F +:101B4000C3FF95F82430A41B1E44F6B2082E174498 +:101B50009044E4B285F82460DBD1FFF761FF0028F0 +:101B6000D7D108E02B6A03EB82038342CFD0FFF783 +:101B700057FF0028CBD10020BDE8F8830120FBE708 +:101B8000445F0020024B1A78024B1A70704700BF66 +:101B9000845F002018230020034904484FF4614368 +:101BA0000B6002F001BB00BF6C5F0020985F00205B +:101BB000074B10B50021044618221846FFF796FF80 +:101BC00004600146BDE81040024802F0EDBA00BFD3 +:101BD0006C5F0020985F0020202383F3118862B699 +:101BE00070470000002383F3118862B6704700003D +:101BF00001207047704700007047000010B4134682 +:101C0000026814680022A4465DF8044B6047000097 +:101C100000F5805090F859047047000000F580509E +:101C200090F852047047000000F5805090F9580475 +:101C3000704700005020704700F5805208B5FFF74C +:101C4000CBFFD2F89834D2F894041844D2F89034E8 +:101C50001844D2F878341844D2F888341844D2F8AA +:101C600084341844FFF7BEFF08BD00002DE9F74F8C +:101C70000C4600F580511F4691F85234BDF8309063 +:101C8000054690469BB1D1F874340133C1F87434E1 +:101C900023689A0006D4237B082B0BD9627B0AB1F8 +:101CA0000F2B07D9D1F878340133C1F878344FF0CD +:101CB000FF300FE0FFF790FFEB6AD3F8C42012F477 +:101CC000001A0AD0D1F87C340133C1F87C34FFF714 +:101CD00089FF002003B0BDE8F08FD3F8C46022680C +:101CE0006B6AC6F301464FF0480B002A1BFB063B0C +:101CF000B4BF42F080429204CBF8002023685B001E +:101D000044BF42F00052CBF80020227B330643EA66 +:101D10000243CBF80430607B720118B343F44013E4 +:101D2000CBF80430D1F8A4340133C1F8A434AB1893 +:101D300003F58353197B41F020011973207B019235 +:101D400000F058FE019A033080105FFA8AF3834254 +:101D50000AF1010A0DDA04EB83010BEB83034968F6 +:101D60009960F2E7AB1803F58353197B60F34511D3 +:101D7000E3E7EB6A0121B140C3F8CC10AB1803F5DF +:101D80008253C3E9048705EB461303F582532146CA +:101D9000183304F10C0051F804CB43F804CB814212 +:101DA000F9D1098819802A4441F268032846D6509F +:101DB00002F5805209F0030392F86C1043F010030F +:101DC00021F01F010B4382F86C30FFF70BFF4246F6 +:101DD0003B462146CDF8309003B0BDE8F04F00F00F +:101DE000CFBD000038B5C26A936923F00103936147 +:101DF000044600F09DFF0546E36A9B69DB0706D5B4 +:101E000000F096FF431BFA2BF6D9002004E004F5FE +:101E10008054012084F8520438BD000013B500F549 +:101E200080540191606C00F037FE1F280AD9019997 +:101E3000606C202200F0A6FEA0F120035842584119 +:101E400002B010BD0020FBE708B500F58050FFF799 +:101E5000C3FE406C00F0F4FDBDE80840FFF7C2BED1 +:101E600000220260828142608260704710B50022C9 +:101E70000023C0E900230023044603810C30FFF750 +:101E8000EFFF204610BD00002DE9F047074688B05F +:101E900007F5805468469A468846FFF79DFE9146AE +:101EA000FFF7E4FF606C00F0DDFD1F282CD9606CAB +:101EB0002022694600F0E8FE202825D194F852340B +:101EC00013B303AD444605AB2E4603CE9E422060BD +:101ED0006160354604F10804F6D130682060B388AB +:101EE000A380DDE90023C9E90023BDF80830AAF882 +:101EF0000030FFF777FE4A4653464146384608B061 +:101F0000BDE8F04700F02ABDFFF76CFE002008B0E6 +:101F1000BDE8F0872DE9F84F00230646C0E90133FC +:101F2000294B46F8303B00F5815405468846374634 +:101F3000103438462037FFF799FFA742F9D105F54D +:101F400080544FF4805326630026C4E90D3667643D +:101F5000012305F5835705F5A359E66384F840305E +:101F600084F84830103709F110094FF0000A4FF09B +:101F7000000B47E908ABA7F11800FFF771FF203706 +:101F800047F8286C4F45F4D1B8F1010F84F8588414 +:101F9000A4F85A64A4F85C64A4F85E6484F86064ED +:101FA000A4F86264A4F86464A4F8666484F86864BD +:101FB00002D9064800F0B6FE054B53F82830EB6214 +:101FC0002846BDE8F88F00BF4052000814520008B0 +:101FD0003052000810B5044B197804464A1C1A7098 +:101FE000FFF798FF204610BD915F00202DE9F043D8 +:101FF00000295FD03048314BB3FBF1F381428CBFF5 +:102000000A201120451EB3FBF0F700FB1730ECB29D +:1020100020B1022D2846F5D8002037E07D1EB5F509 +:10202000806F33D2C4EBC40808F103034FEAE30E18 +:10203000C3F3C703A4EB030C0EF101094FF47A704C +:102040005FFA8CF60EFB000E59FA8CFCBEFBFCFC12 +:10205000BCF5617F1CDC1FFA8CF4581C56FA80F02A +:1020600047431648B0FBF7F7B942D5D1013BDBB285 +:102070000F2BD1D8711EC9B207294FF0000005D827 +:10208000107114805580537191710120BDE8F08367 +:1020900008F1FF334FEAE30CC3F3C703E41A0CF172 +:1020A000010EE6B20CFB00005EFA84F4B0FBF4F41F +:1020B000A4B2D2E70846E9E73F420F000024F4004B +:1020C00038B500F58053114A93F85834D55C4FF475 +:1020D0005472554305F1804303F52443044600211F +:1020E0001846FFF703FD0A4B60612B44A361094BBF +:1020F0002B44E361084B2B442362084B2B4463625F +:10210000E36A0022C3F8C02038BD00BF285200088F +:1021100070A40040B0A4004088A5004078A600400C +:102120002DE9F04F00F58055994695F85834022B6B +:1021300089B004468A46904604D90027384609B03B +:10214000BDE8F08F9C4A52F8231009B942F82300E9 +:102150009A49C4F80CA00B7884F8109093B9FFF753 +:102160003BFD974B9A6D42F000729A659A6B42F074 +:1021700000729A639A6B22F000729A6301230B70CB +:10218000FFF730FD95F85134BBB9FFF725FD8D4AB7 +:1021900095F85834D65C012E26D0022E2BD03EB9AD +:1021A0000221152001F04EFE0221162001F04AFE08 +:1021B000012385F85134FFF715FDFFF70DFDE26AA5 +:1021C000936923F01003936100F0B2FD0746E36AC0 +:1021D0009E6916F0080615D000F0AAFDC31BFA2B65 +:1021E000F5D9FFF7FFFCA8E70221562001F02AFEEF +:1021F00002215720DAE73146582001F023FE31460C +:102200005920D3E79A6942F001029A6100F090FDEB +:102210000746E36A9A69D00705D400F089FDC31B1D +:10222000FA2BF6D9DDE79A6942F002029A61E36A75 +:1022300000275F65FFF7D6FC686C00F001FC04F531 +:10224000825B0BF1100B202200216846FFF74EFC49 +:1022500002A8FFF705FE06976A460BEB06030DF191 +:10226000180E9446BCE80300F445186059606246B5 +:1022700003F10803F5D1DCF80000186020369CF863 +:1022800004201A71B6F5806FDDD1002304F5A25247 +:1022900085F8503485F853341A3251462046FFF7FA +:1022A000A5FE074690B9E26A936923F001039361A2 +:1022B00000F03EFD0546E36A9B69D9077FF53DAF17 +:1022C00000F036FD431BFA2BF5D936E795F85F642D +:1022D00095F85E24C5F86CA4360246EA426695F885 +:1022E0006024E36A1643B5F85C2446EA0246DE61E0 +:1022F000B8F1000F29D004F5A3520232414620461E +:10230000FFF774FE90B9E26A936923F001039361C9 +:1023100000F00EFD0546E36A9B69DA077FF50DAF15 +:1023200000F006FD431BFA2BF5D906E795F8683453 +:1023300095F86714C5F870841B0143EA0123B5F8CA +:102340006414E26A43EA0143D3602046FFF7B8FE13 +:10235000002385F85934E36A6FF040421A65E36A56 +:10236000194A5A65E36A44229A65E36A0722C3F868 +:10237000DC20E36A0322DA65E26A9369B9F1030FAC +:1023800043F4407393613FF4D9AEE26A936923F05A +:102390000103936100F0CCFC0646E36A9B69DB070E +:1023A00005D500F0C5FC831BFA2BF6D9C5E6012341 +:1023B00085F85234C2E600BF885F0020905F00209D +:1023C00000100240285200089B0008002DE9F04F41 +:1023D000054689B090469946002741F2680A00F503 +:1023E0008056EB6AD3F8D430FB40D8074AD505EBCA +:1023F000471252444FEA471B1379190742D4D6F8C3 +:1024000080340133C6F8803413799A0648BFD6F871 +:10241000A83405EB0B0248BF0133524448BFC6F84D +:10242000A834137943F008031371DB0722D596F81B +:102430005334FBB105F58254183468465C44FFF709 +:1024400015FD03AB04F1080C206861681A4603C24D +:10245000083464451346F7D120681060A2889A803A +:102460000123ADF808302B68CDE900891B6C694663 +:1024700028469847D6F8543423B1D6F89C34013313 +:10248000C6F89C340137202FABD109B0BDE8F08FDE +:102490002DE9F04F8DB004460F4600F04BFC82460C +:1024A0008946002F56D1E36AD3F89020920141BFAC +:1024B00004F58051D1F894240132C1F89424D3F862 +:1024C0009020160703D100200DB0BDE8F08FD3F89F +:1024D0009050E669C5F30125482303FB0566E846ED +:1024E0004046FFF7BDFC326851004ABF22F060430E +:1024F000C2F38A4343F00043920048BF43F0804355 +:102500000093736813F400131FBF04F58052012376 +:102510008DF80D30D2F8AC340EBF8DF80D3001338C +:10252000C2F8AC34F38803F00F038DF80C304FF091 +:10253000000B9DF80C0000F05DFA5FFA8BF39842F7 +:1025400020D9F2180CA90B44127A03F82C2C0BF1A9 +:10255000010BEEE7012FB6D1E36AD3F8982095017D +:1025600041BF04F58051D1F894240132C1F894247C +:10257000D3F898201007A6D0D3F89850266AC5F350 +:102580000125A9E7EFB9E36AC3F8945004A8FFF75F +:102590006DFC98E80F0007AD07C52B800023ADF850 +:1025A000183023682046CDE904A91B6C04A998477C +:1025B00004F5805458B1D4F88C340133C4F88C3409 +:1025C00082E7012F04BFE36AC3F89C50DEE7D4F82A +:1025D00090340133C4F89034012075E7F8B505460E +:1025E0000F4600F58054012639462846FFF750FF74 +:1025F00010B184F85364F7E7D4F8543423B1D4F815 +:102600009C340133C4F89C34F8BD0000F0B5C36AB3 +:102610001A6C12F47F0F2BD000F580541B6CC4F899 +:10262000A03441F26805002347194FF0010C00EB7C +:1026300043122A445E01117911F0020F15D04907A7 +:1026400013D4B959C66AD6F8C8E00CFA01F111EAF8 +:102650000E0F0AD0C6F8D010117941F004011171A3 +:10266000D4F888240132C4F888240133202BDED129 +:10267000F0BD00002B4B70B51E561B5C012B2FD8F4 +:10268000294D2A4A55F8233052F826400BB341B35E +:10269000236D1A060FD58023236500F04BFB50EA0B +:1026A00001020B4602D0013861F10003024655F8E1 +:1026B0002600FFF78BFE236D1B032CD555F8263023 +:1026C0004FF4002203F580532265012283F8592438 +:1026D00021E001232365082323654FF480632365EC +:1026E00070BD236DDA0702D4236D9B0706D5032343 +:1026F00055F8260023650021FFF770FF236D1807AA +:1027000002D4236DD90606D5182355F82600236573 +:102710000121FFF763FF55F82600BDE87040FFF781 +:1027200075BF00BF2C520008885F0020305200089F +:1027300008B5FFF751FAFFF769FFBDE80840FFF75A +:1027400051BA0000C36AD3F8C40080F40010C0F38B +:102750004050704700F5805008B5FFF73DFA406CD7 +:1027600000F080F9FFF73EFA43090CBF012000207A +:1027700008BD000000F5805393F8592462B1C16A86 +:102780008A6922F001028A61D3F898240132C3F8E1 +:102790009824002283F85924704700002DE9F7435C +:1027A00000F5825198461031FFF716FA002541F2E4 +:1027B000680E4FF0010900F5805C00EB451474448D +:1027C00023795E071CD4DB061AD5C36A8E69D3F859 +:1027D000C87009FA06F63E4212D04F6801970F689A +:1027E0009742019F77EB08070AD2C3F8D06023799C +:1027F00043F004032371DCF884340133CCF88434CF +:102800000135202D01F12001D7D103B0BDE8F043FF +:10281000FFF7E8B9F8B51E46002313700F460546CA +:102820001446FFF797FF80F0010038701EB128466C +:10283000FFF788FF2070F8BD2DE9F04F85B099466D +:102840000B7801930E4613780293DDE90EBA8046A9 +:10285000174600F06FFA337804460D4613B93B78FB +:10286000002B41D022462B464046FFF797FFFFF74B +:102870005FFFFFF77FFF4B463A463146FFF7CAFF3F +:1028800033782BB1019B1BB1012005B0BDE8F08F5F +:102890003B7813B1029B002BF6D108F580530393CC +:1028A0005C4575EB0A031FD2039BD3F85404D8B1DF +:1028B0000368BBEB0402D9686AEB050388474B4603 +:1028C0003A4631464046FFF7A5FF337813B1019BE6 +:1028D000002BD9D13B7813B1029B002BD4D100F04F +:1028E00029FA04460D46DBE70020CEE708B50021B3 +:1028F0000846FFF7BFFEBDE8084001F06FB90000D1 +:1029000008B501210020FFF7B5FEBDE8084001F041 +:1029100065B9000008B500210120FFF7ABFEBDE856 +:10292000084001F05BB9000008B501210846FFF737 +:10293000A1FEBDE8084001F051B900000FB400202D +:1029400004B0704713B56C4684E80600031D94E894 +:10295000030083E80500012002B010BD73B585684F +:10296000019155B11B885B0707D4D0E90036DB6BBA +:102970009847019AC1B23046A847012002B070BD05 +:10298000F0B5866889B005460C465EB1BDF83830B2 +:102990005B070AD4D0E90037DB6B98472246C1B207 +:1029A0003846B047012009B0F0BD00220023CDE930 +:1029B00000230023ADF808300A4603AB01F10806F6 +:1029C000106851681C4603C40832B2422346F7D14E +:1029D000106820609288A28000F0AEF90423ADF860 +:1029E00008302B68CDE900011B6C694628469847E2 +:1029F000D8E70000082817D909280CD00A280CD0DD +:102A00000B280CD00C280CD00D280CD00E2814BF8D +:102A10004020302070470C20704710207047142051 +:102A200070471820704720207047000010B5037CC5 +:102A3000044613B9006802F0EDFA204610BD00000C +:102A40000023BFF35B8FC360BFF35B8FBFF35B8F6C +:102A50008360BFF35B8F7047BFF35B8F0068BFF38A +:102A60005B8F704770B505460C30FFF7F5FF05F139 +:102A7000080604463046FFF7EFFFA04206D930466D +:102A80006D68FFF7E9FF2544281A70BD3046FFF74F +:102A9000E3FF201AF9E7000070B50546406898B1D9 +:102AA00005F10800FFF7D8FF05F10C060446304693 +:102AB000FFF7D2FF8442304694BF6D680025FFF7D0 +:102AC000CBFF013C2C44201A70BD000038B50C46E9 +:102AD0000546FFF7C7FFA04210D305F10800FFF736 +:102AE000BBFF04446868B4FBF0F100FB1144BFF382 +:102AF0005B8F0120AC60BFF35B8F38BD0020FCE72B +:102B00002DE9F041144607460D46FFF7C5FF844204 +:102B100028BF0446D4B1B84658F80C6B4046FFF7BE +:102B20009BFF3044286040467E68FFF795FF331ACC +:102B30009C4203D86C600120BDE8F0816B60A41B4F +:102B40003B68AB602044E8600220F5E72046F3E7ED +:102B500038B50C460546FFF79FFFA04210D305F19C +:102B60000C00FFF779FF04446868B4FBF0F100FB48 +:102B70001144BFF35B8F0120EC60BFF35B8F38BD66 +:102B80000020FCE72DE9FF41884669460746FFF72C +:102B9000B7FF6C4606B204EBC6060025B44209D066 +:102BA0006268206808EB0501FEF78EFF6368083451 +:102BB0001D44F3E729463846FFF7CAFF284604B00C +:102BC000BDE8F081F8B505460C300F46FFF744FF2D +:102BD00005F1080604463046FFF73EFFA0423046A6 +:102BE00088BF6C68FFF738FF201A386020B1304684 +:102BF0002C68FFF731FF2044F8BD000073B5144680 +:102C000006460D46FFF72EFF844228BF044601907A +:102C1000DCB101A93046FFF7D5FF019B33B932681B +:102C2000C5E90233C5E9002401200CE09C4238BF0D +:102C300001942860019868608442F5D93368AB60DC +:102C4000241AEC60022002B070BD2046FBE70000B1 +:102C50002DE9FF410F466946FFF7D0FF6C4600B2F1 +:102C600004EBC0050026AC4209D0D4F8048054F827 +:102C7000081BB8194246FEF727FF4644F3E73046E3 +:102C800004B0BDE8F081000038B50546FFF7E0FF6D +:102C9000044601462846FFF719FF204638BD0000CC +:102CA00000B59BB0EFF3098168226846FEF70CFF80 +:102CB000EFF30583044B9A6BDA6A9A6A9A6A9A6A06 +:102CC0009A6A9A6A9B6AFEE700ED00E000B59BB045 +:102CD000EFF3098168226846FEF7F6FEEFF30583FD +:102CE000044B9A6B9A6A9A6A9A6A9A6A9A6A9B6A77 +:102CF000FEE700BF00ED00E000B59BB0EFF30981F7 +:102D000068226846FEF7E0FEEFF30583034B5A6B3B +:102D10009A6A9A6A9A6A9A6A9B6AFEE700ED00E0EC +:102D2000FEE700000FB408B5029801F03DFBFEE796 +:102D300001F0E4BD01F0BCBD01F0BABD30B5094DF4 +:102D40000A4491420DD011F8013B5840082340F34A +:102D50000004013B2C4013F0FF0384EA5000F6D13D +:102D6000EFE730BD2083B8ED2DE9F041C56915B915 +:102D7000C161BDE8F0814B6823F06047C3F38A4628 +:102D80004FEAD37EC3F3807816EA230638BF3E4667 +:102D9000AC462B465A68BEEBD27F22F060440AD084 +:102DA000002A18DAA40CB44217D19D420FD10D604D +:102DB000DEE71346EEE7A74207D102F08044C2F3F4 +:102DC000807242450BD054B1EFE708D2EDE7CCF862 +:102DD00000100B60CDE7B44201D0B442E5D81A68C8 +:102DE0009C46002AE5D11960C3E700002DE9F047B1 +:102DF000089D01F007044FEAD508224405F00705B5 +:102E000000EBD1004FF47F49944201D1BDE8F08737 +:102E100004F0070705F0070A57453E4638BF5646F7 +:102E2000C6F10806111B8E4228BF0E46E10808EBCA +:102E3000D50E415C13F80EC0B94029FA06F721FA05 +:102E40000AF1FFB28CEA010147FA0AF739408CEA2D +:102E5000010C03F80EC034443544D5E780EA012064 +:102E6000082341F2210201B24000002980B203F19F +:102E7000FF33B8BF504013F0FF03F4D17047000098 +:102E800038B50C468D18A54200D138BD14F8011B89 +:102E9000FFF7E4FFF7E7000002684AB11368036038 +:102EA000C388018901339BB29942C38038BF038133 +:102EB0001046704770B588B0202204460D4668461B +:102EC0000021FEF713FE20460495FFF7E5FF0246BA +:102ED00058B16B46054608AE1C4603CCB442286088 +:102EE0006960234605F10805F6D1104608B070BDAB +:102EF000082817D909280CD00A280CD00B280CD088 +:102F00000C280CD00D280CD00E2814BF40203020E7 +:102F100070470C207047102070471420704718200D +:102F20007047202070470000082817D90C280CD9BA +:102F300010280CD914280CD918280CD920280CD901 +:102F400030288CBF0F200E207047092070470A20C0 +:102F500070470B2070470C2070470D207047000011 +:102F600010B54B6823B9CA8A63F30902CA8210BD3F +:102F7000C4681A681C60C360438A013B43824A608C +:102F8000EFE700002DE9F84F1D46CB8A0F46C3F34B +:102F900009010629814692460B4630D00020AAB28C +:102FA00007F119049EB2052E1FFA80F80FD890453C +:102FB00003F1010306D3FB8A0A4462F30903FB828F +:102FC00001201AE01AF80060E6540130EAE7904563 +:102FD000F1D2A1F1060B1C237C68BBFBF3F203FBCF +:102FE00012BB1FFA8BF6002C45D14846FFF754FF61 +:102FF000044638B978606FF00200BDE8F88F4FF0F2 +:103000000008E6E7002606607860ADB24FF0000BDE +:10301000454510D90AEB0803221D13F8011B9155F1 +:10302000B1B208F101081B291FFA88F82BD04545D9 +:1030300006F10106F1D8FB8AC3F30902154465F3D2 +:103040000903BCE7013292B21C462368002BF9D178 +:10305000AB1F0B441C21B3FBF1F301339BB29A422B +:10306000D3D2BBF1000FD0D14846FFF715FF20B9EE +:10307000C4F800B0BFE70122E7E7C0F800B05E4641 +:1030800020600446C1E74545D5D94846FFF704FF0F +:1030900008B92060AFE7C0F800B000262060044601 +:1030A000B6E700002DE9F04F2DED028B83B0CDE99E +:1030B0000013BDF83C5007469146002A00F092806C +:1030C0002DB10E9B002B00F08D80072D32D807F11B +:1030D0000C00FFF7E1FE044638B96FF00204204609 +:1030E00003B0BDEC028BBDE8F08F14220021FEF787 +:1030F000FDFC0E992A4604F10800FEF7E5FC681C69 +:10310000C0B2FFF711FFFFF7F3FE207499F800300B +:10311000013814FA80F003F01F0363F03F030372D9 +:10312000009B43F00041616038462146FFF71CFEDA +:103130000124D4E700F10C034FF0000808EE103A28 +:103140004FF0800A4646444618EE100AFFF7A4FEE8 +:1031500083460028C1D014220021FEF7C7FCC6BB5D +:10316000019BABF8083002200E9B00F10802991970 +:103170005BFA82F20130C0B2082801D0AE422AD3F5 +:10318000FFF7D2FEFFF7B4FE99F80020009B411E26 +:1031900002F01F0242EA4812AE4208BF4FF0400A56 +:1031A0005BFA81F14AEA020A43F0004281F808A082 +:1031B0008BF81000CBF8042059463846FFF7D4FDB1 +:1031C0000134AE4224B288F001084FF0000ABBD1AE +:1031D00085E70020C8E711F801CB02F801CB0136E2 +:1031E000B6B2C7E76FF0010479E70000F8B51546FD +:1031F0000E462822002104461F46FEF777FC069B58 +:103200006360B5F5001F079BA76034BF6A094FF6DE +:10321000FF72236204F10C0097B200239A4205D892 +:103220000023036027826382A382F8BD0660013316 +:1032300030462036F2E7000003781BB94BB2002B72 +:10324000C8BF017070470000007870472DE9F74F44 +:10325000DDF83C90BDF830500D9E9DF83840BDF82B +:103260004070804692469B46B9F1000F01D1002F75 +:1032700051D11F2C4FD898F80000B0B9072F47D86C +:1032800035F0030347D13A4649464FF6FF70FFF742 +:10329000F7FD20F001002D02400445EA0464400CD3 +:1032A00044EA40244FF6FF7321E040EA0520072F4F +:1032B00040EA0464F6D900254FF6FF73C5F12000FB +:1032C000A5F120022AFA05F10BFA00F001432BFACE +:1032D00002F211431846C9B2FFF7C0FD0835402D70 +:1032E0000346EBD13A464946FFF7CAFD0346CDE90E +:1032F0000097324621464046FFF7D4FE337801332B +:10330000DBB21F2B88BF0023337003B0BDE8F08F02 +:103310006FF00300F9E76FF00100F6E72DE9F04FD9 +:1033200085B09246DDF848800F9D9DF840209DF8BD +:103330004490BDF84C7006469B46B8F1000F01D191 +:10334000002F48D11F2A46D83378002B46D00C02D4 +:1033500044EA02649DF8381044EAC93444EA01445E +:103360001C43072F44F0800432D900234FF6FF722C +:10337000C3F1200CA3F120002AFA03F10BFA0CFC94 +:1033800041EA0C012BFA00F00143C9B21046039345 +:10339000FFF764FD039B0833402B0246E8D13A4611 +:1033A0004146FFF76DFD0346CDE900872A462146D9 +:1033B0003046FFF777FEB9F1010F06D12B780133C4 +:1033C000DBB21F2B88BF00232B7005B0BDE8F08F48 +:1033D0004FF6FF73E8E76FF00100F6E76FF00300C8 +:1033E000F3E70000C06900B104307047C3691A6890 +:1033F000C261C2681A60C360438A013B438270475E +:103400002DE9F041D0F81880194E14461D4641466A +:10341000002709B9BDE8F081D1E90223A21A65EBC2 +:103420000303964277EB03031ED283698B420DD1CF +:10343000FFF796FD83691B688361C3680B60438A4D +:10344000C1608169013B43828846E2E7FFF788FD5E +:103450000B68C8F80030C3680B60438AC160013B49 +:103460004382D8F80010D4E788460968D1E700BF46 +:1034700080841E002DE9F04F8BB00D46DDF8509092 +:1034800014469B468046002800F01981B9F1000FD0 +:1034900000F01581531E3F2B00F21181012A03D148 +:1034A000BBF1000F40F00B810023CDE90833B8F8E1 +:1034B0001430B5EBC30F4FEAC30703D300200BB0A2 +:1034C000BDE8F08F2B199F42D8F80C303ABF7F1B14 +:1034D000FFB227461BB9D8F81030002B7AD02F2D19 +:1034E0004ED8C5F13006B7424FF000032CBFF6B2FC +:1034F0003E4600932946D8F8080008AB3246FFF74D +:1035000075FCA7EB060A35445FFA8AFAB8F814305E +:1035100003F10053063BDB000493D8F80C3003930F +:103520003021039B13B1BAF1000F2CD1D8F8100051 +:1035300040B1BAF1000F05D0009608AB5246691AA7 +:10354000FFF754FC38B2002FB8D066070AD00AAB98 +:1035500003EBD401624211F8083C02F00702134168 +:1035600001F8083C082C3CD9102C40F2B580202CE6 +:1035700040F2B780BBF1000F00F09C80082334E0DC +:10358000BA460026C2E7049BE02B28BFE02306933F +:103590000B44AB42059314D95A1B039800969245ED +:1035A00034BF5246D2B2691A08AB04300792FFF713 +:1035B0001DFC079A1644AAEB020A1544F6B25FFAFC +:1035C0008AFA049B069A05999B1A0493039B1B682D +:1035D0000393A6E70093D8F8080008AB3A462946BB +:1035E000AEE7BBF1000F13D00123B4EBC30F6CD0D7 +:1035F000082C12D89DF82030621E23FA02F2D5075B +:1036000006D54FF0FF3202FA04F423438DF8203040 +:103610009DF8203089F8003051E7102C12D8BDF801 +:103620002030621E23FA02F2D10706D54FF0FF3296 +:1036300002FA04F42343ADF82030BDF82030A9F895 +:1036400000303CE7202C0FD80899631E21FA03F3C1 +:10365000DA0705D54FF0FF3202FA04F40C43089460 +:10366000089BC9F800302AE7402C2BD0DDE908651B +:10367000611EC4F12102A4F1210326FA01F105FA29 +:1036800002F225FA03F311431943CB0712D50122A5 +:10369000A4F12003C4F1200102FA03F322FA01F19C +:1036A000A240524243EA010363EB430332432B43FC +:1036B000CDE90823DDE90823C9E90023FFE66FF01F +:1036C0000100FCE66FF00800F9E6082CA0D9102CE8 +:1036D000B3D9202CEED8C3E7BBF1000FADD0022345 +:1036E00083E7BBF1000FBBD004237EE730B5012A8E +:1036F000144638BF0124402C85B028BF4024002543 +:10370000012ACDE9025518D81B788DF808306307D7 +:103710000AD004AB03EBD405624215F8083C02F072 +:103720000702934005F8083C009103462246002119 +:1037300002A8FFF75BFB05B030BD082AE4D9102AC8 +:1037400003D81B88ADF80830E1E7202A8DBFD3E904 +:1037500000231B680293CDE90223D8E710B5CB689C +:103760001BB98B600B618B8210BDC4681A681C602A +:10377000C360438A013B4382CA60F0E72DE9F04F02 +:10378000D1F8008093B018F0800FCDE90323C8F37F +:10379000C01219BFC8F3C03BC8F306264FF0020B96 +:1037A0001646B8F1000F04460D4680F2D18118F09C +:1037B000C043059340F0CC810B7B002B00F0C88107 +:1037C000BBF1020F03D00178B14240F0C48108F090 +:1037D0007F0106916AB3C8F3074A2B44069A93F80F +:1037E0000390760646EA0B4646EA82465FEAD9131C +:1037F00046EA0A06079300F0908000220023CDE9F4 +:103800000A23069B009367685B4652460AA9204636 +:10381000B84700287ED0A7699FB9314604F10C0053 +:10382000FFF748FB0746E0B96FF0020013B0BDE8B0 +:10383000F08FC8F30F2A18F07F0F08BF0AF0030AB1 +:10384000CBE73B699E420DD03F68002FF9D131464E +:1038500004F10C00FFF72EFB07460028E4D0A36913 +:103860003B60A761DDE90A2300264FF6FF70C6F131 +:10387000200E22FA06F103FA0EFEA6F1200C23FA1E +:103880000CFC41EA0E0141EA0C01C9B2083609926A +:103890000893FFF7E3FA402EDDE90832E7D1B8825A +:1038A000FB7D09F01F06C3F384039B1BD7E90221AC +:1038B00098B2002BBCBF00F120031BB252EA0100FA +:1038C000C8F304680FD00398821A049860EB0101D2 +:1038D000A74890424FF000028A4104D3079A002A79 +:1038E0005BD0012B23DDFA7D4FEA890302F003024E +:1038F00003F07C031343FB7539462046FFF730FB8A +:10390000079BA3B9FB7DC3F38402013262F38603F4 +:10391000FB7504E06FF00B0088E7A76917B96FF03B +:103920000C0083E73B699E42BAD03F68F6E719F086 +:10393000400F32D0039BBB60049BFB60142200212C +:103940000DA8FEF7D3F8039B0A93049B0B932B1D42 +:103950000C932B7BADF83EA0013BDBB2ADF83C30C5 +:10396000069B8DF8433094F824308DF840B083F0F6 +:1039700001038DF844308DF84160A3688DF84280D2 +:103980000AA920469847FB7DC3F38403013303F063 +:103990001F039B02FB82002048E7FB7DC9F3401216 +:1039A000B2EBD31F40F0DA80C3F38403B34240F09C +:1039B000D88007992B7B4FEA9912002934D0D2077F +:1039C00041D4032B40F2D080039BBB60049BFB607F +:1039D0002B7BAE1D033BDBB23246394604F10C00B3 +:1039E000FFF7D0FA00280DDA20463946FFF7B8FA7B +:1039F000FB7DC3F38403013303F01F039B02FB82AF +:103A0000032013E7AB883B832A7B033AB88AD2B200 +:103A10003146FFF735FAFB7DB882DA43C2F3C012B4 +:103A200062F3C713FB75B6E76AB92E1D013BDBB223 +:103A30003246394604F10C00FFF7A4FA0028D3DB24 +:103A40002A7B013AE2E7F98AC1F30901013B052922 +:103A5000DAB259D8281D002307F11A0C9A4208D966 +:103A600010F801EB0CF801E0013101330629DBB25B +:103A7000F4D103990A9104990B91934207F11A0129 +:103A80000C9138BF043379680D9134BF55FA83F334 +:103A900000230E93FB8AADF83EA0C3F309031A443A +:103AA000069B8DF8433094F82430ADF83C2083F029 +:103AB00001038DF8443000238DF840B08DF841604B +:103AC0008DF842807B602A7BB88A013A291DFFF776 +:103AD000D7F93B8BB882834203D1A3680AA9204659 +:103AE000984720460AA9FFF739FEFB7DB88AC3F341 +:103AF0008403013303F01F039B02FB823B8B98423C +:103B000014BF1120002091E67B68002BB1D0062065 +:103B100001E01C306346D3F800C0BCF1000FF8D1BF +:103B2000091A081D05F1040C00EB030905989DF81E +:103B3000143001EB000EBEF11B0F9AD89A4298D9AF +:103B40001CF8013B09F8013B059B01330593EDE7A8 +:103B50006FF009006AE66FF00A0067E66FF00D008B +:103B600064E66FF00E0061E66FF00F005EE600BFE6 +:103B700080841E00EFF3098305494A6B22F001029D +:103B80004A63683383F30988002383F311887047FD +:103B900000EF00E0202080F3118862B60C4B0D4A44 +:103BA000D96821F4E0610904090C0A43DA60D3F80A +:103BB000FC20094942F08072C3F8FC200A6842F0F8 +:103BC00001020A601022DA7783F82200704700BFF2 +:103BD00000ED00E00003FA05001000E010B520231E +:103BE00083F311880E4B5B6813F4006314D0F1EE7D +:103BF000103AEFF30984683C4FF08073E361094B9E +:103C0000DB6B236684F3098800F080FB10B1064B60 +:103C1000A36110BD054BFBE783F31188F9E700BFF3 +:103C200000ED00E000EF00E04B0600084E06000843 +:103C3000026843681143016003B1184770470000F0 +:103C4000024A136843F0C003136070470044004009 +:103C500013B50E4C204600F09BFA04F114000C49F9 +:103C6000009400234FF4807200F05CF9094B0A497C +:103C700000944FF4807204F1380000F0D5F9074A3F +:103C8000074BC4E9172302B010BD00BF985F0020A6 +:103C900004600020413C0008046100200044004012 +:103CA000007A030A30B5037C214C002918BF0C466A +:103CB000012B0CD11F4B984209D11F4B9A6D42F436 +:103CC00000329A659A6F42F400329A679B6F2268BD +:103CD000036EC16D846603EB5203B3FBF2F36268BB +:103CE000150442BF23F0070503F0070343EA450329 +:103CF000CB60A36843F040034B60E36843F00103EB +:103D00008B6042F4967343F001030B604FF0FF3376 +:103D10000B62510505D512F0102205D0B2F1805F7B +:103D200004D080F8643030BD7F23FAE73F23F8E702 +:103D300084520008985F0020001002402DE9F047EF +:103D4000C66D3768F46934622107054618D014F04F +:103D5000080118BF8021E20748BF41F02001A307F6 +:103D600048BF41F04001600748BF41F48071202303 +:103D700083F31188281DFFF75BFF002383F311886D +:103D8000E2050AD5202383F311884FF40071281D22 +:103D9000FFF74EFF002383F311884FF020094FF007 +:103DA000000A14F0200838D13B0616D54FF0200940 +:103DB00005F1380A200610D589F31188504600F025 +:103DC00067F9002836DA0821281DFFF731FF27F0B0 +:103DD00080033360002383F31188790614D56206CB +:103DE00012D5202383F31188D5E913239A4208D1F1 +:103DF0002B6C33B11021281D27F04007FFF718FF67 +:103E00003760002383F31188E30618D5AA6E13697F +:103E1000ABB1BDE8F0475069184789F31188736A60 +:103E200095F864102846194000F0CCF98AF31188FF +:103E3000F469B6E7B06288F31188F469BAE7BDE8BF +:103E4000F087000000F1604303F561430901C9B246 +:103E500083F80013012200F01F039A4043099B00DE +:103E600003F1604303F56143C3F880211A60704792 +:103E7000F8B5154682680669AA420B46816938BFC3 +:103E80008568761AB54204460BD218462A46FDF7D5 +:103E90001BFEA3692B44A361A3685B1BA360284698 +:103EA000F8BD0CD918463246FDF70EFEAF1BE1688F +:103EB0003A463044FDF708FEE3683B44EBE718461A +:103EC0002A46FDF701FEE368E5E7000083689342B8 +:103ED000F7B51546044638BF8568D0E90460361A40 +:103EE000B5420BD22A46FDF7EFFD63692B446361AF +:103EF000A36828465B1BA36003B0F0BD0DD9324612 +:103F00000191FDF7E1FD0199E068AF1B3A463144AC +:103F1000FDF7DAFDE3683B44E9E72A46FDF7D4FD07 +:103F2000E368E4E710B50A440024C361029B84609F +:103F3000C0E90000C0E90511C1600261036210BD63 +:103F400008B5D0E90532934201D1826882B982680E +:103F5000013282605A1C42611970D0E904329A42DF +:103F600024BFC3684361002100F0A0FA002008BD0F +:103F70004FF0FF30FBE7000070B5202304460E46EB +:103F800083F31188A568A5B1A368A269013BA3606A +:103F9000531CA36115782269934224BFE368A3618F +:103FA000E3690BB120469847002383F31188284624 +:103FB00007E03146204600F069FA0028E2DA85F38E +:103FC000118870BD2DE9F74F04460E4617469846F6 +:103FD000D0F81C904FF0200A8AF311884FF0000BA4 +:103FE000154665B12A4631462046FFF741FF034694 +:103FF00060B94146204600F049FA0028F1D000237C +:1040000083F31188781B03B0BDE8F08FB9F1000F7E +:1040100003D001902046C847019B8BF31188ED1A0D +:104020001E448AF31188DCE7C0E90511C160C36151 +:104030001144009B8260C0E9000001610362704787 +:10404000F8B504460D461646202383F31188A76869 +:10405000A7B1A368013BA36063695A1C62611D702C +:10406000D4E904329A4224BFE3686361E3690BB187 +:1040700020469847002080F3118807E0314620460B +:1040800000F004FA0028E2DA87F31188F8BD000096 +:10409000D0E905239A4210B501D182687AB98268C5 +:1040A000013282605A1C82611C7803699A4224BFE3 +:1040B000C3688361002100F0F9F9204610BD4FF07C +:1040C000FF30FBE72DE9F74F04460E4617469846AA +:1040D000D0F81C904FF0200A8AF311884FF0000BA3 +:1040E000154665B12A4631462046FFF7EFFE0346E6 +:1040F00060B94146204600F0C9F90028F1D00023FC +:1041000083F31188781B03B0BDE8F08FB9F1000F7D +:1041100003D001902046C847019B8BF31188ED1A0C +:104120001E448AF31188DCE702684368114301608A +:1041300003B11847704700001430FFF743BF000079 +:104140004FF0FF331430FFF73DBF00003830FFF76A +:10415000B9BF00004FF0FF333830FFF7B3BF0000A6 +:104160001430FFF709BF00004FF0FF311430FFF7A4 +:1041700003BF00003830FFF763BF00004FF0FF328D +:104180003830FFF75DBF000000207047FFF760BDCB +:10419000044B03600023C0E902334360012303742E +:1041A000704700BF9C52000810B52023044683F3DB +:1041B0001188FFF777FD02232374002383F311880E +:1041C00010BD000038B5C36904460D461BB9042173 +:1041D0000844FFF7A9FF294604F11400FFF7B0FED9 +:1041E000002806DA201D4FF48061BDE83840FFF753 +:1041F0009BBF38BD024B0022C3E900339A60704771 +:1042000004620020002303748268054B1B689968D0 +:104210009142FBD25A680360426010605860704758 +:104220000462002008B5202383F31188037C032B4C +:1042300005D0042B0DD02BB983F3118808BD436939 +:1042400000221A604FF0FF334361FFF7DBFF0023CA +:10425000F2E7D0E9003213605A60F3E700230374F9 +:104260008268054B1B6899689142FBD85A680360C5 +:10427000426010605860704704620020054B196965 +:104280000874186802681A60536018610123037487 +:10429000FCF7C6B90462002030B54B1C0B4D87B04B +:1042A000044610D02B690A4A01A800F019F92046EB +:1042B000FFF7E4FF049B13B101A800F04DF92B694F +:1042C000586907B030BDFFF7D9FFF8E70462002056 +:1042D0002542000838B50C4D41612B6981689A6808 +:1042E0009142044603D8BDE83840FFF78BBF18461B +:1042F000FFF7B4FF01232C61014623742046BDE87B +:104300003840FCF78DB900BF04620020044B1A68E6 +:104310001B6990689B68984294BF002001207047F9 +:104320000462002010B5084C236820691A682260D6 +:104330005460012223611A74FFF790FF014620693F +:10434000BDE81040FCF76CB90462002008B5FFF727 +:10435000DDFF18B1BDE80840FFF7E4BF08BD00006D +:10436000FFF7E0BFFEE7000010B50C4CFFF742FF7F +:1043700000F0A8F80A498022204600F03DF8012309 +:1043800044F8180C0374FFF705FC002383F311882D +:1043900062B60448BDE8104000F04EB82C62002020 +:1043A000C4520008D452000808B572B6034B5862D4 +:1043B00000F06EFA00F022FBFEE700BF046200206E +:1043C00000F004B9EFF3118020B9EFF30583202248 +:1043D00082F311887047000010B530B9EFF30584FF +:1043E000C4F3080414B180F3118810BDFFF7AEFFC9 +:1043F00084F31188F9E7000082600222028270478C +:104400008368A3F17C0243F80C2C026943F83C2C2E +:10441000426943F8382C074A43F81C2CC26843F819 +:10442000102C022203F8082C002203F8072CA3F119 +:10443000180070473906000810B5202383F311884F +:10444000FFF7DEFF00210446FFF744FF002383F35C +:104450001188204610BD0000024B1B6958610F20D7 +:10446000FFF70CBF04620020202383F31188FFF7BD +:10447000F3BF000008B50146202383F3118808200C +:10448000FFF70AFF002383F3118808BD49B1064BEB +:1044900042681B6918605A60136043600420FFF78C +:1044A000FBBE4FF0FF307047046200200368984263 +:1044B00006D01A680260506059611846FFF7A2BE24 +:1044C00070470000054B03F11402C3E905224FF0C9 +:1044D000FF310022C3E90712704700BF04620020C9 +:1044E00070B51C4EC0E9032305460C4600F000FBE6 +:1044F000334653F8142F9A420DD13062C5E9012496 +:104500002A600A2C2CBF00190A30C6E90555BDE8FF +:10451000704000F0DBBA316A431AE31838BF1C461A +:104520009368A34202D9081900F0DEFA73699A6809 +:1045300094420CD85A68AC602B606A6015609A6827 +:104540005D60121B9A604FF0FF33F36170BD1B6812 +:10455000A41AECE70462002038B51B4C636998424A +:104560000DD0D0E9003213605A6000228168C26029 +:104570009A680A449A604FF0FF33E36138BD2246DF +:10458000036842F8143F002193425A60C16003D18E +:10459000BDE8384000F0A2BA9A688168256A0A44EA +:1045A0009A6000F0A5FA63699A68411B8A42E5D9CE +:1045B000AB181D1A092D206A98BF01F10A02BDE847 +:1045C0003840104400F090BA046200202DE9F04118 +:1045D000184C002704F11406656900F089FA236A73 +:1045E000AA68C11A8A4215D813442362D5E9003259 +:1045F00013605A606369D5F80C80EF60B34201D153 +:1046000000F06CFA87F311882869C047202383F3F0 +:104610001188E1E76169B14209D013441B1ABDE872 +:10462000F0410A2B2CBFC0180A3000F05DBABDE87B +:10463000F08100BF0462002000207047FEE7000008 +:10464000704700004FF0FF3070470000BFF34F8FFE +:10465000024A1369DB03FCD4704700BF002002400C +:1046600008B5094B1B7873B9FFF7F0FF074B5A6980 +:10467000002ABFBF064A9A6002F188329A601A681F +:1046800022F480621A6008BDD0630020002002403E +:104690002301674508B50B4B1B7893B9FFF7D6FF8D +:1046A000094B5A6942F000425A611A6842F480523A +:1046B0001A601A6822F480521A601A6842F4806202 +:1046C0001A6008BDD063002000200240FF289ABF76 +:1046D00000F58030C0020020704700004FF40060F9 +:1046E000704700004FF4807070470000FF2808B545 +:1046F0000BD8FFF7EBFF00F500630268013204D12D +:1047000004308342F9D1012008BD0020FCE70000FD +:10471000FF2838B5044626D8FFF754FEFFF796FF6A +:10472000FFF79EFF114BF3221A6102225A615A6968 +:1047300042EAC4025A615A6942F480325A6105461B +:104740002046FFF783FF4FF40061FFF7BFFF00F043 +:1047500051F92846FFF79EFFFFF73EFE2046BDE8D1 +:104760003840FFF7C3BF002038BD00BF0020024023 +:1047700040EA020313F007032DE9F04705460C4613 +:10478000164606D0324B40F2FB221A600020BDE8EC +:10479000F08781182F4A91420CD92D4A4FF440716D +:1047A0001160F3E72B1D1B686268934208D1083E35 +:1047B00008350834072E19D92A6823689A42F1D09F +:1047C000FFF700FEFFF74CFFFFF740FF04F1080181 +:1047D000214C4FF001084FF00009012EA1F108070C +:1047E00008D8FFF757FFFFF7F7FD01E0002EE7D1EC +:1047F0000120CCE7C4F81480AA4651F8083C4AF8D6 +:10480000043B51F8043C6B60FFF720FFC4F81490A0 +:104810002A6851F8083C9A420ED00D4B40F22632DD +:104820001A600E4B1D600E4B1E600E4B1F60FFF793 +:1048300031FFFFF7D1FDA9E7DAF800A051F8043CF9 +:104840009A4501F10801E8D1083E0835C5E700BFE7 +:10485000CC6300200000080800200240C063002054 +:10486000C8630020C4630020084908B50B7828B14C +:104870001BB9FFF7F5FE01230B7008BD002BFCD020 +:10488000BDE808400870FFF705BF00BFD0630020F7 +:1048900008B54FF4C0314FF0005000F0ADF8BDE85E +:1048A00008404FF400414FF0805000F0A5B80000E0 +:1048B00070B582B0FFF786FD0E4E054600F018F980 +:1048C0003268904237BF0C4A0B49516814682EBFBA +:1048D000D1E90041013151600419034641F1000161 +:1048E000284601913360FFF777FD0199204602B019 +:1048F00070BD00BFD4630020D863002070B582B0C3 +:10490000FFF760FD104E054600F0F2F83268904265 +:1049100037BF0E4A0D49516814682EBFD1E90041D6 +:1049200001315160041941F100010346284601910B +:104930003360FFF751FD01994FF47A72002320464E +:10494000FBF756FC02B070BDD4630020D863002092 +:104950000244D2B2904200D17047431C800000F163 +:10496000804000F51450006841F8040BD8B2F1E71C +:10497000124B10B5D3F89040240409D4D3F89040DA +:10498000C3F89040D3F8904044F40044C3F89040FA +:104990000B4C2368024443F480732360D2B29042EC +:1049A00000D110BD431C800000F1804000F5145080 +:1049B00051F8044B0460D8B2F1E700BF0010024088 +:1049C0000070004007B5012201A90020FFF7C0FFD9 +:1049D000019803B05DF804FB13B50446FFF7F2FF3E +:1049E000A04205D0012201A900200194FFF7C0FFD9 +:1049F00002B010BD70470000704700007047000013 +:104A0000074B45F255521A6002225A6040F6FF7277 +:104A10009A604CF6CC421A60024B01221A70704721 +:104A200000300040E4630020034B1B781BB1034BB4 +:104A30004AF6AA221A607047E46300200030004062 +:104A4000054B1A6832B902F1804202F50432D2F8FD +:104A500094201A60704700BFE0630020024B4FF4BF +:104A60000002C3F8942070470010024008B5FFF719 +:104A7000E7FF024B1868C0F3407008BDE0630020F8 +:104A800070470000FEE700000A4B0B480B4A9042BB +:104A90000BD30B4BDA1C121AC11E22F003028B42FD +:104AA00038BF00220021FDF721B853F8041B40F85D +:104AB000041BECE74454000870640020706400207C +:104AC000706400207047000000F078B84FF0804319 +:104AD000002258631A610222DA6070474FF0804367 +:104AE0000022DA60704700004FF08043586370473F +:104AF0004FF08043586A70474B6843608B6883600F +:104B0000CB68C3600B6943614B6903628B69436285 +:104B10000B6803607047000008B5204BDA6A42F06A +:104B20007F02DA62DA6A22F07F02DA62DA6ADA6C2B +:104B300042F07F02DA64DA6E42F07F02DA66184AE7 +:104B4000DB6E11464FF09040FFF7D6FF02F11C01DB +:104B500000F58060FFF7D0FF02F1380100F58060BA +:104B6000FFF7CAFF02F1540100F58060FFF7C4FFB0 +:104B700002F1700100F58060FFF7BEFF02F18C01C9 +:104B800000F58060FFF7B8FF02F1A80100F5806032 +:104B9000FFF7B2FFBDE8084000F064B80010024023 +:104BA000EC52000808B500F003FAFFF7DDFBBDE8A2 +:104BB0000840FFF745BF0000704700000F4B9A6D9B +:104BC00042F001029A659A6F42F001029A670C4A1C +:104BD0009B6F936843F0010393604FF08043A722DB +:104BE0009A624FF0FF32DA6200229A615A63DA6009 +:104BF0005A6001225A611A60704700BF00100240DB +:104C0000002004E04FF0804208B51169D3680B40E2 +:104C1000D9B2C9439B07116107D5202383F31188BB +:104C2000FFF7CEFB002383F3118808BD08B50B4BBB +:104C3000D3F8902012F4407F1FBF4FF48032C3F8A6 +:104C400090200022C3F89020D3F89020C3F8902041 +:104C500000F086F9024B00225A6008BD00100240A5 +:104C600000700040484B4FF0FF319A6A99629A6A8F +:104C700000229A62986AD86A60F07F00D862D86A87 +:104C800000F07F00D862D86A186B1963186B1A633A +:104C9000186B986B9963986B9A63986BD86BD96310 +:104CA000D86BDA63D86B186C1964196C1A641A6CB7 +:104CB0009A6D42F080529A659A6F22F080529A67FC +:104CC0009A6F324A4FF400711160516911F480619A +:104CD000FBD14FF40040516090604FF48070D16080 +:104CE000C2F88000116251629162D1621163516316 +:104CF0009163D163116451649164D164116551650C +:104D0000D3F8982042F00102C3F89820D3F89820F5 +:104D10009007FBD51A6842F480321A601A68910332 +:104D2000FCD51A490A6842F480720A60184ADA60AF +:104D30001A6842F080721A601A689201FCD500224B +:104D400014499A60C3F888101349C3F89C20134A89 +:104D50000A600A6802F00F02042AFAD19A6842F047 +:104D600003029A609A6802F00C020C2AFAD11A6EB9 +:104D700042F001021A66D3F8802042F00102C3F823 +:104D80008020D3F88030704700100240007000404F +:104D9000132A61015501005000200240040704005D +:104DA000074A08B5536903F00103536123B1054A6B +:104DB00013680BB150689847BDE80840FEF70EBF76 +:104DC00000040140E8630020074A08B5536903F076 +:104DD0000203536123B1054A93680BB1D068984729 +:104DE000BDE80840FEF7FABE00040140E863002079 +:104DF000074A08B5536903F00403536123B1054A18 +:104E000013690BB150699847BDE80840FEF7E6BE4C +:104E100000040140E8630020074A08B5536903F025 +:104E20000803536123B1054A93690BB1D0699847D0 +:104E3000BDE80840FEF7D2BE00040140E863002050 +:104E4000074A08B5536903F01003536123B1054ABB +:104E5000136A0BB1506A9847BDE80840FEF7BEBE22 +:104E600000040140E8630020164B10B55C6904F4AF +:104E700078725A61A30604D5134A936A0BB1D06ABB +:104E80009847600604D5104A136B0BB1506B9847D6 +:104E9000210604D50C4A936B0BB1D06B9847E20501 +:104EA00004D5094A136C0BB1506C9847A30504D57F +:104EB000054A936C0BB1D06C9847BDE81040FEF7E3 +:104EC0008DBE00BF00040140E8630020194B10B5FF +:104ED0005C6904F47C425A61620504D5164A136D7C +:104EE0000BB1506D9847230504D5134A936D0BB150 +:104EF000D06D9847E00404D50F4A136E0BB1506E85 +:104F00009847A10404D50C4A936E0BB1D06E984714 +:104F1000620404D5084A136F0BB1506F98472304FD +:104F200004D5054A936F0BB1D06F9847BDE8104088 +:104F3000FEF754BE00040140E863002008B50348B2 +:104F4000FEF7FCFEBDE80840FEF748BE985F002073 +:104F500008B5FFF757FEBDE80840FEF73FBE00006A +:104F6000062108B50846FEF76DFF06210720FEF76B +:104F700069FF06210820FEF765FF06210920FEF7DC +:104F800061FF06210A20FEF75DFF06211720FEF7CC +:104F900059FF06212820FEF755FF07211C20FEF7A8 +:104FA00051FFBDE808400C212620FEF74BBF000052 +:104FB00008B5FFF73BFE00F009F8FFF7E7F8FFF749 +:104FC000FBFDBDE80840FFF77FBD00000023054A58 +:104FD00019460133102BC2E9001102F10802F8D181 +:104FE000704700BFE86300200B460146184600F0FA +:104FF00003B8000000F00EB810B5054C13462CB1F4 +:105000000A4601460220AFF3008010BD2046FCE7AF +:1050100000000000024B0146186800F035B800BFE0 +:105020002823002010B501390244904201D100200C +:1050300005E0037811F8014FA34201D0181B10BD01 +:105040000130F2E72DE9F041A3B1C91A1778014404 +:10505000044603F1FF3C8C42204601D9002009E0C0 +:105060000578BD4204F10104F5D10CEB0405D61816 +:10507000A54201D1BDE8F08115F8018D16F801EDCA +:10508000F045F5D0E7E7000037B5002944D051F8E6 +:10509000043C0190002BA1F10404B8BFE41800F017 +:1050A00047F81E4A0198136833B96360146003B06F +:1050B000BDE8304000F042B8A34208D92568611924 +:1050C0008B4201BF19685B6849192160EDE71A46F8 +:1050D0005B680BB1A342FAD911685518A5420BD1F0 +:1050E000246821445418A3421160E0D11C685B6815 +:1050F000536021441160DAE702D90C230360D6E73C +:10510000256861198B4204BF19685B68636004BF3E +:10511000491921605460CAE703B030BD68640020BB +:10512000034611F8012B03F8012B002AF9D170472F +:10513000014800F009B800BF6C640020014800F08D +:1051400005B800BF6C640020704700007047000085 +:105150006F72672E6172647570696C6F742E486F20 +:105160006C7962726F47345F475053004E6F206115 +:105170007070207369670A00426164206677206C52 +:10518000656E6774682025750A0042616420626F4D +:105190006172645F69642025752073686F756C6443 +:1051A0002062652025750A004261642066772064CC +:1051B000657363726970746F72206C656E67746872 +:1051C0002025750A004261642061707020435243BB +:1051D000203078253038783A3078253038782030CB +:1051E00078253038783A3078253038780A00476F9B +:1051F0006F64206669726D776172650A0040A2E48F +:10520000F16468910600000053544D333247343F37 +:105210003F0000004261642043414E49666163657E +:1052200020696E6465782E00000100000001FF0017 +:105230000064004000680040000000000000000022 +:1052400021210008FD1B000839280008F11B000877 +:105250006D1C0008891E0008E51D0008351C0008AB +:10526000391C0008F51B0008111C0008F91B000878 +:10527000491E00081D1C000845290008291C0008BB +:105280001D1E000800960000000000000000000045 +:10529000000000000000000000000000000000000E +:1052A00055410008414100087D410008694100085E +:1052B00075410008614100084D410008394100086E +:1052C000894100086D61696E0000000069646C65C9 +:1052D00000000000CC52000848620020C06300209B +:1052E000010000006543000800000000A000802AC3 +:1052F00000000000AAAAAAAA50000024FFFF000094 +:1053000000770000009009000400005A000000002F +:10531000AAAAAA9A04000000FFBF00000000000033 +:10532000000099000011101400000000AAAAAAA60B +:1053300000010010FFDF000000000000000000007E +:105340000000000000000000AAAAAAAA00000000B5 +:10535000FFFF00000000000000000000000000004F +:1053600000000000AAAAAAAA00000000FFFF000097 +:10537000000000000000000000000000000000002D +:10538000AAAAAAAA00000000FFFF00000000000077 +:10539000000000000000000000000000AAAAAAAA65 +:1053A00000000000FFFF00000000000000000000FF +:1053B00070AEFF7F010000001D040000000000002F +:1053C0000070070000000000FE2A0100D204000067 +:1053D000FF00000000000000085200083F0000002D +:1053E0002C2300200000000000000000000000004E +:1053F00000000000000000000000000000000000AD +:10540000000000000000000000000000000000009C +:10541000000000000000000000000000000000008C +:10542000000000000000000000000000000000007C +:10543000000000000000000000000000000000006C +:045440000000000068 +:00000001FF diff --git a/Tools/bootloaders/HolybroGPS_bl.bin b/Tools/bootloaders/HolybroGPS_bl.bin index f5988e31a56..cb050b6bfa9 100755 Binary files a/Tools/bootloaders/HolybroGPS_bl.bin and b/Tools/bootloaders/HolybroGPS_bl.bin differ diff --git a/Tools/bootloaders/HolybroGPS_bl.elf b/Tools/bootloaders/HolybroGPS_bl.elf index a257eb77274..f3c13816d49 100755 Binary files a/Tools/bootloaders/HolybroGPS_bl.elf and b/Tools/bootloaders/HolybroGPS_bl.elf differ diff --git a/Tools/bootloaders/HolybroGPS_bl.hex b/Tools/bootloaders/HolybroGPS_bl.hex index d0c050c7129..f95a809d1fb 100644 --- a/Tools/bootloaders/HolybroGPS_bl.hex +++ b/Tools/bootloaders/HolybroGPS_bl.hex @@ -1,1348 +1,1386 @@ :020000040800F2 -:100000000007002029050008992A00089D2A0008F9 -:10001000F52A00089D2A0008C92A00082B050008B7 -:100020002B0500082B0500082B050008CD3800081B -:100030002B0500082B0500082B0500082B050008E0 -:100040002B0500082B0500082B0500082B050008D0 -:100050002B0500082B050008954B0008C14B000834 -:10006000ED4B0008194C0008454C00082B05000812 -:100070002B0500082B0500082B0500082B050008A0 -:100080002B0500082B0500082B0500085927000840 -:10009000692700087D2700082B050008714C00081F -:1000A0002B0500082B0500082B0500082B05000870 -:1000B000FD4900082B0500082B0500082B0500084A -:1000C0002B0500082B0500082B0500082B05000850 -:1000D0002B0500082B050008C93900082B0500086E -:1000E000D94C00082B0500082B0500082B0500083B -:1000F0002B0500082B0500082B0500082B05000820 -:100100002B0500082B0500082B0500082B0500080F -:100110002B0500082B0500082B0500082B050008FF -:100120002B0500082B0500082B0500082B050008EF -:100130002B0500082B0500082B0500089127000857 -:10014000A1270008B52700082B0500082B0500088B -:100150002B0500082B0500082B0500082B050008BF -:100160002B0500082B0500082B0500082B050008AF -:100170002B0500082B0500082B0500082B0500089F -:100180002B0500082B0500082B0500082B0500088F -:100190002B0500082B0500082B0500082B0500087F -:1001A0002B0500082B0500082B0500082B0500086F -:1001B0002B0500082B0500082B0500082B0500085F -:1001C0002B0500082B0500082B0500082B0500084F -:1001D0002B0500082B0500082B0500082B0500083F -:1001E000F518000800000000D0400B1CD1409C46D0 -:1001F000203AD34018435242634693401843704715 -:100200009140031C90409C46203A9340194352422F -:100210006346D3401943704753B94AB9002908BF10 -:1002200000281CBF4FF0FF314FF0FF3000F07AB9CB -:10023000ADF1080C6DE904CE00F006F8DDF804E03D -:10024000DDE9022304B070472DE9F0478C460D46E6 -:100250000446089E002B51D18A4217466DD9B2FA46 -:1002600082FEBEF1000F0BD0CEF1200C01FA0EF58C -:1002700020FA0CFC02FA0EF74CEA050C00FA0EF418 -:100280004FEA174A250CBCFBFAF81FFA87F90AFB5C -:1002900018CC45EA0C4508FB09F3AB420AD9ED1925 -:1002A00008F1FF3280F02381AB4240F22081A8F1B7 -:1002B00002083D44ED1AA4B2B5FBFAF00AFB105552 -:1002C00044EA054400FB09F9A14509D9E41900F104 -:1002D000FF3380F00A81A14540F2078102383C4497 -:1002E000A4EB090440EA08400021002E61D024FA62 -:1002F0000EF4002334607360BDE8F0878B4207D9A9 -:10030000002E54D0002186E821000846BDE8F08781 -:10031000B3FA83F1002940F08E80AB4202D38242CF -:1003200000F2FA80841A65EB03050120AC46002E2A -:100330003FD086E81010BDE8F08712B90127B7FB5F -:10034000F2F7B7FA87FEBEF1000F34D1EB1B3A0C7F -:100350001FFA87FC0121B3FBF2F8250C02FB1833CE -:1003600045EA03450CFB08F3AB4207D9ED1908F148 -:10037000FF3002D2AB4200F2D1808046ED1AA3B228 -:10038000B5FBF2F002FB105543EA05440CFB00FC00 -:10039000A44507D9E41900F1FF3302D2A44500F2C5 -:1003A000B8801846A4EB0C0440EA08409DE73146AB -:1003B0003046BDE8F087CEF1200405FA0EF307FAC7 -:1003C0000EF720FA04F83A0C25FA04F448EA030878 -:1003D000B4FBF2F14FEA184502FB11441FFA87FC07 -:1003E00045EA044501FB0CF3AB4200FA0EF409D9CF -:1003F000ED1901F1FF3080F08A80AB4240F2878036 -:1004000002393D44EB1A1FFA88F5B3FBF2F002FB08 -:10041000103345EA034500FB0CF3AB4207D9ED1955 -:1004200000F1FF386FD2AB426DD902383D44EB1A70 -:1004300040EA01418FE7C1F1200722FA07F88B401B -:1004400005FA01F448EA030320FA07FE4FEA134CC9 -:10045000FD404EEA040EB5FBFCF94FEA1E440CFBCE -:1004600019551FFA83F844EA054509FB08F4AC4224 -:1004700002FA01F200FA01FA08D9ED1809F1FF3089 -:1004800043D2AC4241D9A9F102091D442D1B1FFAE8 -:100490008EFEB5FBFCF00CFB10554EEA054400FB4C -:1004A00008F8A04507D9E41800F1FF3529D2A04586 -:1004B00027D902381C4440EA0940A4EB0804A0FBF9 -:1004C00002894C45C6464D4615D312D056B1BAEBFB -:1004D0000E0364EB050404FA07F7CB401F43CC403E -:1004E000376074600021BDE8F0871846F8E6904652 -:1004F000E0E6C245EAD2B8EB020E69EB030501382B -:10050000E4E72846D7E7404691E78146BEE7014643 -:1005100078E702383C4445E7084608E7A8F10208B6 -:100520003D442BE7704700BF02E000F000F8FEE713 -:1005300072B6394880F30888384880F3098838480B -:100540004EF60851CEF20001086040F20000CCF2F5 -:1005500000004EF63471CEF200010860BFF34F8FF9 -:10056000BFF36F8F40F20000C0F2F0004EF68851EA -:10057000CEF200010860BFF34F8FBFF36F8F4FF0D3 -:100580000000E1EE100A4EF63C71CEF20001086068 -:10059000062080F31488BFF36F8F04F04FF904F046 -:1005A00093F94FF055301F491B4A91423CBF41F827 -:1005B000040BFAE71C49194A91423CBF41F8040B6D -:1005C000FAE71A491A4A1B4B9A423EBF51F8040BEC -:1005D00042F8040BF8E700201749184A91423CBF43 -:1005E00041F8040BFAE704F02DF904F0C1F9144CBA -:1005F000144DAC4203DA54F8041B8847F9E700F0C5 -:1006000041F8114C114DAC4203DA54F8041B8847F1 -:10061000F9E704F015B900000007002000230020CE -:10062000000000080001002000070020A05300087F -:10063000002300207C23002080230020AC5C0020CD -:10064000E0010008E4010008E4010008E4010008FA -:100650002DE9F04F2DED108AC1F80CD0C3689D46EE -:10066000BDEC108ABDE8F08F002383F31188284683 -:10067000A047002003F0CCFDFEE703F027FD00DFDC -:10068000FEE70000F8B504F07FF8064604F0D0F865 -:10069000044678BB214B9E422CD001339E422CD085 -:1006A0001F4B26F0FF029A422AD1F0B200F04AFD19 -:1006B000274642F2107500F05BFF00F049FD18B3C9 -:1006C00034B1184B9E4203D004F0AAF800252F46FF -:1006D000002004F063F80FB100F06EF801F0D6FAD4 -:1006E00000F068FF01F072F9284600F0B5F800F05C -:1006F00063F8F9E727460025DDE705460127DAE735 -:10070000074640F6C415D6E714B1064B9E42DBD12E -:10071000002004F043F80025E0E700BF010007B027 -:10072000000008B0263A09B008B501F021F9A0F19F -:1007300020035842584108BD07B5054B02211B88CC -:10074000ADF8043001A801F031F903B05DF804FB05 -:10075000AC50000810B5202383F311881248C368F9 -:100760000BB103F0E3FD0023104A0F484FF47A71F8 -:1007700003F08AFD002383F311880D4C236813B125 -:100780002368013B2360636813B16368013B6360C6 -:10079000084B1B7833B9636823B9022001F0FCF9D8 -:1007A0003223636010BD00BF80230020550700087E -:1007B0009C2400209423002010B51E4B1E4953F8A2 -:1007C000042F013200D110BD8B42F8D11B4C1C4BC1 -:1007D00022689A422CD91B4B9B6803F1006303F5F6 -:1007E00080339A4224D203F0EFFF04F001F8002096 -:1007F00001F006F9144B0220187001F0C3F9134BF5 -:100800001A6C00221A64196E1A66196E596C5A64B1 -:10081000596E5A665B6E72B60D4A0E4B13601B68BA -:100820002268202181F311889D4683F308881047B0 -:1008300010BD00BFFCFF00081C00010804000108F7 -:10084000FFFF00080023002094230020003802400E -:1008500008ED00E0000001082DE9F04F99B0B94D16 -:1008600000902022FF2110A8AC6801F0B1F9B64A2F -:1008700001951378A3B9B5480121C36011702023F5 -:1008800083F31188C3680BB103F050FD0023B04A15 -:10089000AE484FF47A7103F0F7FC002383F311881C -:1008A000009BAC4A03B11360AB4B009D0293002642 -:1008B0001E705660B2463746B146012001F062F91B -:1008C000002D00F02582A34B1B68002B40F02082F6 -:1008D00019B0BDE8F08F0220FFF726FF002840F096 -:1008E0001082009B002E08BF1D469C4B02211B88D6 -:1008F000ADF82C300BA801F059F8DEE74FF47A7010 -:1009000001F036F8B0F10008EBDB0220FFF70CFF36 -:100910000028E6D008F1FF38B8F1040F00F2F381A7 -:10092000DFE808F0031E2124270018A8052340F85B -:10093000343D042101F03AF8012303FA08F848EAAB -:100940000A0A5FFA8AFA4FF0000901F095F927B117 -:100950000AF00B030B2B08BF0025FFF7EDFEACE7F9 -:1009600004217848E6E704217D48E3E704217D4837 -:10097000E0E74FF01C09484601F044F809F104098A -:100980000B9004210BA801F011F8B9F12C0FF2D152 -:10099000D2E7002FA5D00AF00B030B2BA1D1022028 -:1009A000FFF7C2FE804600289BD001206A4E01F06E -:1009B00027F80220307001F0E5F800275FFA87FB86 -:1009C000584601F02DF8054688B1584601F038F830 -:1009D00001370028F2D146460025634B02211B88CF -:1009E000ADF82C300BA800F0E1FF474665E7012386 -:1009F0000220337001F0BCF82C46019B9B689C429E -:100A000006D2204600F0FEFF0130E4D10434F4E7C2 -:100A1000029B00241C704F4B46465C6047462546AF -:100A200093E7002F3FF45DAF0AF00B030B2B7FF42D -:100A300058AF029B0220187001F0A4F8322000F099 -:100A400097FFB0F1000BFFF64CAF1BF003087FF4EB -:100A500048AF019B996804EB0B028A423FF641AF15 -:100A6000BBF5807F3FF63DAF404A0392D8450FDA91 -:100A70004FF47A7000F07CFF049004990029FFF68F -:100A800030AF039A049908F8021008F10108ECE766 -:100A9000C820FFF749FE804600283FF422AF1F2CF4 -:100AA00011D8C4F120075F4528BF5F4610AB24F082 -:100AB00003003A462D49184401F078F83A46FF21E0 -:100AC0002A4801F085F84FEAAB03DAB227490393CD -:100AD000204601F085F8074600283FF47EAF039BCF -:100AE00004EB830431E70220FFF71EFE00283FF4E9 -:100AF000F8AE00F0CBFF00283FF4F3AE4FF0000853 -:100B00004346019A9268904532D2B8F11F0F12D82D -:100B1000109A01320FD028F0030218A90A4452F8A3 -:100B2000202C0B92184604220BA902F001F808F1C0 -:100B300004080346E5E74046039300F063FF039B88 -:100B40000B90EFE700230020982400208023002052 -:100B5000550700089C24002094230020AE50000874 -:100B60000423002008230020B05000089823002010 -:100B700018A8042140F84C3D00F018FFE5E618A83D -:100B8000002340F8343D642100F006FF00287FF484 -:100B9000A8AE0220FFF7C8FD00283FF4A2AE0B98D4 -:100BA00000F060FF18AB43F8480D04211846E3E756 -:100BB00018A8002340F8343D642100F0EDFE002821 -:100BC0007FF48FAE0220FFF7AFFD00283FF489AE1F -:100BD0000B9800F055FF18AB43F8440DE5E70220F1 -:100BE000FFF7A2FD00283FF47CAE00F05FFF18ABDA -:100BF00043F8400DD9E70220FFF796FD00283FF4A7 -:100C000070AE0BA9142000F057FF804618A80421ED -:100C100040F83C8D00F0CAFE41460BA8ACE73220FC -:100C200000F0A6FEB0F10008FFF65BAE18F0030F6F -:100C30007FF457AE019A926808EB090393423FF69E -:100C400050AE0220FFF770FD00283FF44AAE28F0B6 -:100C50000308C844C1453FF478AE484600F0D2FED0 -:100C600004210A900AA800F0A1FE09F10409F1E7A5 -:100C70004FF47A70FFF758FD00283FF432AE00F0D1 -:100C800005FF002842D0109B01330BD0082210A989 -:100C9000002000F0A5FF002838D02022FF2110A856 -:100CA00000F096FFFFF748FD384803F0B7FA0FE66B -:100CB000002F3FF416AE0AF00B030B2B7FF411AE9E -:100CC00018A8002340F8343D642100F065FE8046FA -:100CD00000287FF406AE0220FFF726FD00283FF42F -:100CE00000AE0390FFF728FD41F2883003F096FA3A -:100CF0000B9800F0D7FF00F0BFFF039B45461F464F -:100D0000DBE5074621E64FF00009EAE5B84664E670 -:100D1000002000F02DFE0490049B002B01DA00F06F -:100D200099FC049B002BFFF6CBAD012000F020FFC7 -:100D3000049B213B122B3FF6C0AD01A252F823F0D9 -:100D4000D7080008FD08000893090008BB08000840 -:100D5000BB080008BB080008230A00081F0C000895 -:100D6000E70A00087F0B0008B10B0008DF0B000842 -:100D7000BB080008F70B0008BB080008710C00084E -:100D80004B090008BB080008B10C0008A086010050 -:100D900009490B6849F269009AB21B0C00FB023347 -:100DA000064A0B60136844F2506198B21B0C01FBB9 -:100DB0000030106080B27047102300200C23002008 -:100DC00010B500211022044600F002FF034B03CBB4 -:100DD000206061601868A06010BD00BF107AFF1F1E -:100DE000F0B51F4CBBB001F09FFEA368C31AF92BEE -:100DF00030D906AD2346A06028220021284602F003 -:100E000015FB04F10E0000F0DBFE0023C6B2591DF5 -:100E10005F1CDBB2B3424FEAC10107DA0E33234451 -:100E20000822284602F002FB3B46F0E70123039329 -:100E30000823207B02930B4B0193C1F3CF01302396 -:100E4000059100930146049503A3D3E900230648C6 -:100E500002F026F93BB0F0BD78F6339F93CACD8DF2 -:100E6000805600208D560020BC3400202DE9F04132 -:100E70000E4CDFF840800E4FA4F5865646F8108CD5 -:100E800014F8783C43B954F87C5C2DB1284601F045 -:100E9000C3FC284603F0A8FFA4F19000A6F11004BB -:100EA00001F0BAFCA742E7D1BDE8F08180560020EE -:100EB000E03400200052000870B50D4614461E466E -:100EC00002F096F850B9022E0ED1012C0CD112A3CB -:100ED000D3E90023C5E90023012070BD052C14D0FF -:100EE00003D8012C09D0002070BD282C09D0302C4B -:100EF000F9D10BA3D3E90023ECE70BA3D3E900233B -:100F0000E8E70BA3D3E90023E4E70BA3D3E900232D -:100F1000E0E700BFAFF30080401DA12026812A0B2F -:100F200078F6339F93CACD8D9E6AC421818A46EE9E -:100F300026417272DF25D7B7F017304A39059E5621 -:100F400038B504460D46034620222846002102F00B -:100F50006DFA22792346032A28BF032203F8042FBF -:100F600028460222202102F061FA62792346072AEC -:100F700028BF072203F8052F28460322222102F06A -:100F800055FAA2792346072A28BF072203F8062F1D -:100F900028460322252102F049FA284604F10803D5 -:100FA0001022282102F042FA382038BD2DE9F04FF6 -:100FB000ADF5017D21AE0EAD40F2791280460F46AF -:100FC0003046002100F004FE48220021284600F0AF -:100FD000FFFD01F0A9FD594B4FF47A72B0FBF2F01E -:100FE000186093E80700012385E807002B740DF1D2 -:100FF0005A0000236B74FFF7E3FE042385F82030CA -:101000000B2385F8213007AB18464D4904F042F810 -:10101000182228643146284685F83C20FFF790FFC7 -:1010200012AB044601460822304602F0FFF90822BE -:10103000A1180DF14903304602F0F8F90DF14A0309 -:10104000082204F11001304602F0F0F913AB20221F -:1010500004F11801304602F0E9F914AB402204F122 -:101060003801304602F0E2F916AB082204F17801AB -:10107000304602F0DBF90DF15903082204F180013A -:10108000304602F0D3F904F1880A0DF15A0904F54B -:10109000847B4B465146082230460AF1080A02F08A -:1010A000C5F9D34509F10109F3D11BAB0822594613 -:1010B000304602F0BBF904F588744FF0000995F84A -:1010C00034304B4510D84FF0000995F83C304B4573 -:1010D00015D92B6C21464B440822304602F0A6F964 -:1010E000083409F10109F0E7AB6B21464B440822B3 -:1010F000304602F09BF9083409F10109DFE7E31DEE -:10110000C3F3CF03F97E0593002304960393BB7EBC -:101110000293193701230093019706A3D3E9002313 -:10112000404601F0BDFF0DF5017DBDE8F08F00BF29 -:10113000AFF300809E6AC421818A46EEA424002079 -:1011400050510008014B1870704700BFB0240020B8 -:10115000F0B5334B1C7B85B034B1324B0E221A8173 -:101160000024204605B0F0BD2F4A1068516802AB3C -:1011700003C308230DEB03022C492D4803F06CFE3A -:10118000054630B9274B2B480A221A8101F01CFB77 -:10119000E6E70169B1F5E02F06D9224B26480B227C -:1011A0001A8101F011FBDCE7438B40F20B429342C2 -:1011B00007D01C490C2008811946204801F004FB87 -:1011C000CFE71F4A024402F11003994204D2154BA3 -:1011D0001C4810221A81E4E710398E1A204614495F -:1011E00001F0A6FC3246074605F11801204601F041 -:1011F0009FFCAB689F4202D1EB6898420AD0094B32 -:101200000D221A8100903B46EA68A9680E4801F059 -:10121000DBFAA5E70D4801F0D7FA0124A1E700BFEA -:1012200080560020A4240020B4500008DCFF0600F3 -:1012300000000108BC500008C8500008DA5000083F -:101240000800FFF7F8500008155100083E5100084B -:101250002DE9F04FADB006AF80460C4601F0C8FE58 -:10126000064600285BD1237E022B19D1E38A012B8D -:1012700016D101F059FC0546FFF78AFD4FF4C873FB -:10128000B54AB0FBF3F105F5167501FB1300E37EDB -:1012900015FA80F01060914633B9B04B00221A70F5 -:1012A0009C37BD46BDE8F08FA38AF5B2013BAB4247 -:1012B00006F101060CD93B1D691CC9001D440095AF -:1012C0000023082201F0F801204601F081FFEBE73E -:1012D00007F11400FFF774FD2A4607F11401381DC9 -:1012E00003F0AAFD03460028D7D10F2D08D89B4B49 -:1012F0001D70D9F80030A3F51673C9F80030CFE798 -:1013000007F19802014602F8950D20460092072247 -:1013100001F05EFFF978404601F062FEC0E7E38A23 -:10132000052B00F0068106D8012BB9D12146404695 -:10133000FFF73CFEB4E7282B3DD0302BB0D1637EC5 -:10134000874D01336A7BDBB29342E94640F0EF8080 -:10135000E27E2B7B9A4240F0EA8007F19803002658 -:1013600023F8846D1022009331460123204601F0BA -:101370002FFFB4F81480A8F102081FFA88F808F1CA -:10138000030323F003030A3323F00703ADEB030D3C -:101390000DF1180A33469BB2B11C98454FEAC101C2 -:1013A00006F101066CDD5344009308220023204619 -:1013B00001F00EFFEEE7A38A013B9BB2C92B3FF67B -:1013C0006FAF674E357B4DBB06F10C0300930822CF -:1013D0002B462946204601F0FBFEA38A05F10109B0 -:1013E000013BEDB29D424FEAC90109DA0E353544A1 -:1013F000009500230822204601F0EAFE4D46ECE766 -:1014000000230022C6E900230023B36086F8D7300A -:10141000C6F8D830337B0BB9E37E3373002507F170 -:1014200014063B1D0822294630467D60BD60FD60E4 -:1014300001F0FCFF3B7A05F10109AB424FEAC9011B -:1014400007D9FB6808222B44304601F0EFFF4D46D8 -:10145000F0E7C1F3CF010023E07E059104960393EA -:10146000A37E02931934282301460093019438A3E4 -:10147000D3E90023404601F013FEFFF7B1FC0FE76C -:1014800095F8D70000F0CCFAD5F8D83006461BB94D -:1014900095F8D70000F0D4FAD5F8D83043449E42EE -:1014A00004D295F8D700013000F0CAFA4FEA980B41 -:1014B0000024A0B2584504F1010408DA2B6880002A -:1014C0000AEB00010122184400F08AFBF1E7D5E99C -:1014D0000023D5F8D84095F8D70012EB080243F165 -:1014E00000034444C5E90023C5F8D84000F098FA49 -:1014F000844209D395F8D730013385F8D730D5F831 -:10150000D8309E1BC5F8D860B8F1FF0F08DC002367 -:101510002B7300F0BBFAFFF71BFE08B1FFF74CF985 -:101520002B68104A9B0A013313810023AB60CD4620 -:10153000B6E6BFF34F8F0C490C4BCA6802F4E06269 -:101540001343CB60BFF34F8F00BFFDE7AFF30080C5 -:1015500026417272DF25D7B7B8340020B534002099 -:1015600080560020A424002000ED00E00400FA05CD -:1015700008B54FF000530B4A196891420AD10A4A44 -:10158000597D117009481B7D0373C92208490E302B -:1015900000F00CFBE02200214FF00050BDE80840B5 -:1015A00000F016BB9AAD44C5B02400208056002040 -:1015B0001600002037B51D4D1D4C1E490223012287 -:1015C0002846637100F0B6FF41F2D0030122EB58C8 -:1015D00018491B681848984700230193174B00933C -:1015E0001749184B18484FF4805201F0D1FC174BA3 -:1015F0001978254611B1144801F0F2FC01F094FA73 -:101600000446FFF7C5FB4FF4C87304F51674B0FB2E -:10161000F3F202FB13000E4B14FA80F0186003F093 -:1016200007F908B10F232B8103B030BDE03400204F -:10163000A424002040420F00B0450020B90E00084D -:10164000B424002051120008BC340020B024002033 -:10165000B83400202DE9F04F93B0DFF87492994D23 -:10166000484601F067FD0246002840D000240E9451 -:101670008DF844400F941094037B8DF8443001465C -:101680000FAB51F8040F496803C3136812AF43F05E -:10169000004347F8103D2646A0462B59D3F80CA02E -:1016A00001F044FA884ACDF80080121805EB040BCB -:1016B0004FF000034B4158463946D04704F5865455 -:1016C000103442F2A0130028C8BF46F001069C4225 -:1016D000E3D17E4C2EB1484601F030FD84F8008005 -:1016E000BEE72378072B00F3DF80013323700BAFB5 -:1016F0000023DFF8FC910A938DF834300B937B6064 -:101700000024264612AA01234FF0000800200021E1 -:101710008DF81C3002F82B8D2B59CDE9000105EB1B -:10172000040BD3F804A007A943465846D0479DF8B8 -:101730001CA0BAF1000F24D0D9F8143083F4004370 -:10174000C9F81430102241460EA800F041FA2B5976 -:1017500008AA1E690AA90DF11E035846B04797E86A -:1017600003000FAB83E803009DF834308DF844305C -:101770000A9B0E930EA9DDE90823554801F09EFE51 -:10178000564604F58654103442F2A0139C42B9D157 -:10179000002EB5D14E4801F02BFC00283FD14D4C16 -:1017A00001F0C2F92368984239D301F0BDF905462A -:1017B000FFF7EEFA4FF4C87305F51675B0FBF3F2B8 -:1017C00002FB130015FA80F0434D8DF828602E7847 -:1017D000206016B901238DF82830C6F11004E4B258 -:1017E0000EA8FFF7EDFA062C28BF06240EAB224602 -:1017F00099190DF1290000F0D9F90AAB03931823C8 -:101800000293364B0193013401230093049429A3DE -:10181000D3E900232E4801F0EDFB00232B7001F0EB -:1018200083F92F4A2F4C1368C31AB3F57A7F30D34C -:10183000106001F07BF902460B46254801F088FC58 -:10184000234801F0D5FB20B3237B274E002B14BF88 -:1018500003230223737101F067F90EAD4FF47A731D -:101860002946B0FBF3F030603046FFF769FB1823E0 -:10187000073002931D4B0193C0F3CF0040F2551384 -:101880000490009303950DA3D3E90023104801F0C1 -:10189000B1FB237B0BB1FFF7A3FA237B002B7FF473 -:1018A000DCAE13B0BDE8F08F094801F047FC1EE73D -:1018B000AFF30080401DA12026812A0BF1C6A7C1ED -:1018C000D068080FE034002040420F006557002028 -:1018D000BC340020B8340020B5340020B4340020DB -:1018E0006057002080560020A42400206457002068 -:1018F0000004024010B5084C204600F041FB04F5FE -:101900008650103000F03CFB044A05490020BDE839 -:10191000104003F05BBA00BFE0340020B85700204D -:101920006D0E000870B50F4B0C4619780131C9B225 -:10193000012906460FD80C4803681D6A4FF47A73D4 -:10194000534331462246A847844204D1074B002224 -:101950001A70012070BD4FF4FA7002F05FFC002095 -:1019600070BD00BF142300203C580020A857002061 -:1019700007B502AB002203F8012D012102461846EB -:10198000FFF7D0FF20B19DF8070003B05DF804FB1E -:101990004FF0FF30F9E700000A4608B50421FFF7D1 -:1019A000C1FF80F00100C0B2404208BD30B4054C18 -:1019B0002368DD69044B0A46AC460146204630BC2C -:1019C000604700BF3C580020A086010070B502F0BF -:1019D000A3FD094C094E20800025306823888342EE -:1019E00008D902F093FD336805440133B5F5803F13 -:1019F0003360F2D370BD00BFAA57002068570020A3 -:101A000002F03ABE00F1006000F5803000687047D7 -:101A100000F10060920000F5803002F0C3BD0000CC -:101A2000054B1A68054B1B889B1A834202D9104448 -:101A300002F06CBD0020704768570020AA570020B4 -:101A400038B5074D04462868204402F067FD28B9E0 -:101A500028682044BDE8384002F078BD38BD00BF9A -:101A60006857002010F0030308D1B0F5047F05D2B9 -:101A700000F10050A0F50840006870470020704752 -:101A8000014BC058704700BF107AFF1F064991F8FC -:101A9000243033B100230822086A81F82430FFF78C -:101AA000B7BF0120704700BF6C570020014B18687A -:101AB000704700BF002004E070B52A4B1C68C4F3D7 -:101AC0000B03240C63B140F21342934231D040F235 -:101AD000194293422FD040F2214293422DD1032349 -:101AE000214A0C2505FB03235D6893F9082042F287 -:101AF00001039C4224D0B4F5805F23D041F201035E -:101B00009C4221D041F203039C421FD041F20703C3 -:101B10009C4208BF3122441E0C44013D0B46A342A7 -:101B20001ED215F9016F581C96B1034600F8016CDE -:101B3000F5E70123D4E70223D2E73F220B4DD6E796 -:101B40003322E3E74122E1E75A22E4E75922E2E7C0 -:101B50002C2584421D7001D9981C5A70401A70BD02 -:101B60001846FBE7002004E0785100086C5100089B -:101B7000022802BF024B4FF000429A61704700BF3B -:101B800000040240022802BF024B4FF400429A6157 -:101B9000704700BF00040240022801BF024A536997 -:101BA00083F40043536170470004024010B50023E2 -:101BB000934203D0CC5CC4540133F9E710BD00005C -:101BC00002460346981A13F9011B0029FAD17047FF -:101BD00002440346934202D003F8011BFAE7704720 -:101BE0002DE9F047234C94F82430054688461746E3 -:101BF00083BB2E46DFF87C90C7B394F824302BB912 -:101C00002022FF2148462662FFF7E2FF94F82400D5 -:101C1000C0F10805BD4228BF3D465FFA85FAAD0018 -:101C200041462A4604EB8000FFF7C0FF94F82430B9 -:101C3000A7EB0A079A445FFA8AFABAF1080F2E4412 -:101C4000A844FFB284F824A0D6D1FFF71FFF0028D4 -:101C5000D2D108E0266A06EB8306B042CAD0FFF76D -:101C600015FF0028C5D10020BDE8F0870120BDE8A0 -:101C7000F08700BF6C570020024B1A78024B1A7095 -:101C8000704700BFA85700201423002003490448D0 -:101C90004FF461430B6002F059B900BF9457002024 -:101CA0003C580020074B10B500210446142218466A -:101CB000FFF78EFF04600146BDE81040024802F0C5 -:101CC00045B900BF945700203C580020202383F3DF -:101CD000118862B670470000002383F3118862B652 -:101CE00070470000012070470020704700207047B7 -:101CF0007047000070470000002070470E207047BA -:101D000000F586500078C0F340007047F8B51F46D4 -:101D10000B68BDF8185013F00054164669D10B7BC0 -:101D2000082B66DCFFF7D2FFC26893685B015CD4C6 -:101D300093681C0157D4936813F0805357D0022343 -:101D40000C6803F1180E002CB8BFE4004FEA0E1E19 -:101D5000B4BF44F00404640542F80E400C680FFA66 -:101D600083FE14F0804F18BF02EB0E1C02EB0E1E18 -:101D70001EBFDCF8804144F00204CCF880410C7BAB -:101D8000CEF8844102EB03128C68C2F88C414C6897 -:101D9000C2F88841DEF8802142F00102CEF88021AD -:101DA00003F1830200EB4212C2E9006701F10C0467 -:101DB000083251F8046B42F8046BA142F9D100EBF0 -:101DC00043130978117003F5835301201A7F65F3DB -:101DD0000002C5F3400565F341026FF3C3021A77B1 -:101DE000FFF77AFFF8BD0123AAE72346A8E71846C4 -:101DF000F6E74FF0FF30F8BD08B5FFF767FF41F297 -:101E00005403C05800F012FDBDE80840FFF764BF5E -:101E100038B5044600680D4600F032FD1F2809D988 -:101E200020222946206800F0A3FDA0F1200358429B -:101E3000584138BD002038BD002202600273426064 -:101E40008260704710B500220023C0E90023002300 -:101E5000044603810C30FFF7EFFF204610BD000061 -:101E60002DE9F041064688B041F254050C469046F3 -:101E70001F46FFF72BFF6846FFF7E4FF705900F09D -:101E8000E7FC1F2805D80020FFF726FF08B0BDE8B3 -:101E9000F08120226946705900F0F2FD2028F2D12D -:101EA00003AA234605AD144603CCAC421860596022 -:101EB000224603F10803F6D12068186022791A71CE -:101EC000DDE90023C8E90023BDF808303B8001208C -:101ED000DAE70000274B2DE9F047044640F8103BB5 -:101EE0008946FFF7A9FF04F12000FFF7ABFF04F1DB -:101EF0004006354604F5825728462035FFF7A2FFF5 -:101F0000BD42F9D14FF4805341F248026B60002387 -:101F10002E60A35041F24C0241F25401A3506018CC -:101F200001222A7404F5865A655004F5835502711E -:101F300008350AF1080A00260027984645E9026795 -:101F40002846FFF779FF203545F8108C5545F5D127 -:101F500041F2C803B9F1010F04F8039002DD06480D -:101F600000F0DCFD054B53F82930E3602046BDE866 -:101F7000F08700BF00520008E4510008D05100086B -:101F800010B5044B197804464A1C1A70FFF7A2FFDB -:101F9000204610BDB4570020F0B579B1264B274834 -:101FA000B0FBF1F0994294BF102309235C1CB0FBF5 -:101FB000F4F704FB170434B1022B01DC0020F0BD60 -:101FC000013BDBB2F2E77E1EB6F5806FF6D2C3EBC3 -:101FD000C30E0EF10300C010C5B25C1B0130E4B2A9 -:101FE0004FF47A7C0CFB00FC20449CFBF0F080B2A8 -:101FF000B0F5617F08D90EF1FF354FF0080E95FB63 -:10200000FEF5EDB25B1BDCB22B1903FB07770B4B24 -:10201000B3FBF7F7B942D1D1691EC9B20F29CDD8A8 -:10202000631EDBB2072BC9D8002090701680D170D8 -:1020300013710120F0BD00BF3F420F0000366E015A -:1020400070B505460E464FF47A74EB685B6803F092 -:102050000103B34207D04FF47A7002F0DFF8013C7D -:10206000F3D1204670BD012070BD0000F0B50329FA -:1020700089B005460C4647DC00F5865066010378BA -:10208000C3F38001002908BF114661F38203037086 -:10209000AB1903F5835318331B79D80732D5002ABF -:1020A00032D0190723D46846FFF7CCFE05EB441362 -:1020B00003F5835303F1100703AA0833186859681E -:1020C000144603C40833BB422246F7D11868206087 -:1020D0001B792371DDE90E2305F58250CDE900233C -:1020E000694601231430ADF80830FFF791FE3544FE -:1020F00005F5835518352B791A075CBF43F00803A3 -:102100002B7101E0002AF2D109B0F0BD70B5C268B0 -:10211000936913F0700F17D000230C4D936141F2B7 -:10212000780400EB4312224411794E0709D5890740 -:1021300007D5C16855F823608E60117941F004011C -:1021400011710133032BECD170BD00BFD8510008D1 -:10215000D3B51F46C36816469A68D207044609D508 -:102160009A6801219960C2F34002CDE9006700211D -:10217000FFF77CFFE3689A68D1050BD59A684FF4A6 -:1021800080719960C2F34022CDE9006701212046A9 -:10219000FFF76CFFE3689A68D2030BD59A684FF497 -:1021A00080319960C2F34042CDE9006702212046A8 -:1021B000FFF75CFF204602B0BDE8D040FFF7A6BFA6 -:1021C0000C4B10B51C56E3B2012B12D800F0AEFC3C -:1021D00002460B4652EA030103D012F1FF3243F1EB -:1021E000FF33054951F8240018B1BDE81040FFF74E -:1021F000AFBF10BDCC510008AC570020F8B51F464A -:1022000004461646C368002966D1D86803F10C025B -:10221000800765D0106803EB011003EB0111D0F8C3 -:10222000B05115F0040FD0F8B05116BFED086D0D88 -:1022300045F000452561D0F8B051AD0742BF256992 -:1022400045F080452561D0F8B40100F00F002077FB -:10225000D1F8B8312375D1F8B8311B0A6375D1F8BC -:10226000B8311B0CA375D1F8B8311B0EE375D1F84A -:10227000BC312376D1F8BC311B0A6376D1F8BC316E -:102280001B0CA376D1F8BC311B0EE3763823136008 -:1022900004F11C0104F1100304F12C0253F8040BA7 -:1022A00042F8040B8B42F9D11B78137004F582506D -:1022B00000232385C4E9086704F120011430FFF7E7 -:1022C000A7FD04F586522046137843F004031370EB -:1022D000BDE8F840FFF71ABF03F11002186997E74D -:1022E000F8BD00000D4B70B51C56E3B2012B0D4636 -:1022F00013D800F01BFC02460B4652EA030103D040 -:1023000012F1FF3243F1FF33054951F8240020B1A7 -:102310002946BDE87040FFF771BF70BDCC51000881 -:10232000AC5700202DE9F84F99469046FFF7CEFCB8 -:10233000124C00F58356002341F2780700EB43115D -:1023400039440A7955070FD4D2060DD5D6E900AB2A -:10235000CB4508BFC24507D2C26854F823509560E8 -:102360000A7942F004020A710133032B06F12006B8 -:10237000E4D1BDE8F84FFFF7AFBC00BFD85100086B -:1023800008B5FFF7A3FCFFF7C1FEBDE80840FFF763 -:10239000A3BC00002DE9F041C3680646986800F030 -:1023A000E050B0F1E05F0F4619D010B3FFF78EFC9C -:1023B00006F583540834002541F2780806EB4513EE -:1023C00043441B791A070DD45B070BD421463846CA -:1023D00000F0FEF930B9FFF77FFCBDE8F081012085 -:1023E000BDE8F0810135032D04F12004E6D1012080 -:1023F000F1E7BDE8F081000008B5FFF767FC41F2A6 -:102400005403C05800F024FAFFF766FC1F288CBF65 -:102410000020012008BD0000F8B51D460023137000 -:102420000F4606461446FFF7E7FF80F001003870BC -:1024300025B129463046FFF7ADFF2070F8BD0000FA -:10244000F8B50D461F460446164600F06FFB2B7884 -:102450000BB9337873B102460B462046FFF762FF93 -:102460002046FFF78DFF3B46324629462046FFF7C0 -:10247000D3FF01231846F8BD10B5FFF727FC41F242 -:10248000C8032A4AC35CD35CDBB1012B27D0FFF71A -:1024900023FC00F586542378DB0745D4002943D07C -:1024A000FFF714FC41F2C803C35CD35C23B3012BD8 -:1024B0002FD0237843F001032370BDE81040FFF7CD -:1024C0000BBC1B4B1C6C44F000741C641C6A44F075 -:1024D00000741C621C6A24F000741C62D7E7144B61 -:1024E0001C6C44F080641C641C6A44F080641C62B0 -:1024F0001C6A24F08064F0E70221132001F05CFBE9 -:102500000221142001F058FB0221152001F054FB98 -:10251000CFE702213F2001F04FFB0221402001F0D4 -:102520004BFB02214120F1E710BD00BFC85100085C -:10253000003802402DE9F04341F2C80389B0C35C82 -:10254000022B04468846174600F30281814D55F858 -:1025500023200AB945F823002E68C4F804802772A6 -:102560004EB941F2D00002F01FFC31468146FFF720 -:10257000B1FCC5F8009041F2C803E35C012B60D0C8 -:1025800001212046FFF778FFFFF7A0FBE268136800 -:1025900023F002031360E268136843F00103136041 -:1025A000E36800255D61FFF797FB01212046FFF7F7 -:1025B00047FD002800F0868041F254032E46E05883 -:1025C00000F034F9202200216846FFF701FB02A841 -:1025D000FFF732FC0DF1200C05F583534CF8086D24 -:1025E0006A4623449646BEE80300E64518605960F3 -:1025F000724603F10803F5D1DEF8000018602035BB -:102600009EF804201A71602DDCD104F58656002551 -:102610003378ADF800506FF3820333706A46414659 -:1026200020468DF802508DF803508DF80450FFF7C6 -:10263000B3FCE368C0B94FF400421A6009B0BDE8CA -:10264000F083286803681B6B98470146002897D1E0 -:102650002868FFF711FF286803683A461B6841465F -:10266000984700288CD1E9E761221A609DF8023072 -:102670009DF80310E2681B06090401F4702103F0C1 -:1026800040730B43BDF80010C1F309010B439DF8E3 -:102690000410090501F4E001022F43EA01030CBF15 -:1026A0004FF0004100210B43D361E36813225A61CC -:1026B000E268136823F00103136029462046FFF700 -:1026C000BFFC08B9E368B6E741F2C803E15C002942 -:1026D00039D1E268D2F8003243F00103C2F8003287 -:1026E000E268D2F8003223F47C5323F00E03C2F8E0 -:1026F0000032E268D2F8003243F46063C2F800327C -:10270000E368C3F81412E368C3F80412E3686FF0D7 -:102710007842C3F80C22E368C3F84012E368C3F8B8 -:102720004412E368C3F8B012E368C3F8B412E36874 -:1027300044F20102C3F81C22E268D2F8003223F00E -:102740000103C2F80032337843F00203337075E7B7 -:10275000002073E7AC57002008B50020FFF730FDDC -:10276000BDE8084001F0E6B808B500210846FFF7CB -:10277000B9FDBDE8084001F0DDB8000008B5012151 -:102780000020FFF7AFFDBDE8084001F0D3B800001E -:1027900008B50120FFF714FDBDE8084001F0CAB8F4 -:1027A00008B500210120FFF79DFDBDE8084001F0BC -:1027B000C1B8000008B501210846FFF793FDBDE848 -:1027C000084001F0B7B800000FB4002004B0704713 -:1027D00010B509680468C80FB0EBD47F24F06042DC -:1027E00021F060430BD0002CB8BF920C0029B8BF79 -:1027F0009B0C9A420FD034BF0120002010BD9A429A -:1028000005D1C1F38070C4F38074844203D19A422D -:102810002CBF0020012010BD10B5037C044613B965 -:10282000006802F001FB204610BD00000023BFF34A -:102830005B8FC360BFF35B8FBFF35B8F8360BFF3BE -:102840005B8F7047BFF35B8F0068BFF35B8F704790 -:1028500070B506460C30FFF7F5FF06F10805044693 -:102860002846FFF7EFFF844206D228467668FFF736 -:10287000E9FF3444201A70BD2846FFF7E3FFF9E76B -:1028800070B50546406898B105F10800FFF7DAFF1A -:1028900005F10C0604463046FFF7D4FF844230466B -:1028A00094BF6D680025FFF7CDFF013C2C44201A32 -:1028B00070BD000038B50C460546FFF7C9FFA042C1 -:1028C00010D305F10800FFF7BDFF6B68BFF35B8F06 -:1028D0002044B0FBF3F403FB1400A860BFF35B8F4C -:1028E000012038BD002038BD2DE9F0411446804656 -:1028F0000D46FFF7C5FF844228BF0446DCB14746BA -:1029000057F80C6B3846FFF79DFF30442860384677 -:10291000D8F80460FFF796FF301AA0423BBF68600A -:10292000D8F800306C60241A3BBFAB60EC6001202B -:102930000220BDE8F0812046BDE8F08138B50C46A4 -:102940000546FFF79DFFA04210D305F10C00FFF7ED -:1029500079FF6B68BFF35B8F2044B0FBF3F403FB9C -:102960001400E860BFF35B8F012038BD002038BD44 -:102970002DE9F04385B0884669460746FFF7B4FF66 -:102980000026814601AD34464E4505F108050CDAB6 -:1029900008EB040155F8082C55F80C0CFFF706F964 -:1029A00055F8083C01361C44EEE721463846FFF74F -:1029B000C5FF204605B0BDE8F0830000F8B5064627 -:1029C0000C300F46FFF73EFF06F108050446284687 -:1029D000FFF738FF8442284638BF7468FFF732FF9C -:1029E000201A386020B128463468FFF72BFF2044B6 -:1029F000F8BD000073B5144606460D46FFF728FFE4 -:102A0000844228BF04460190DCB101A93046FFF79B -:102A1000D5FF019B33B93268AB6085E81400EB60E9 -:102A200001200CE0A34288BF0194286001986860EF -:102A3000A042F5D23368AB60241AEC60022002B0E9 -:102A400070BD2046FBE700002DE9FF410F466946B7 -:102A5000FFF7D0FF00248046254644450BDA0DEBF6 -:102A6000C4035DF834105E6878193246FFF79EF8AB -:102A700035440134F1E7284604B0BDE8F081000098 -:102A800038B50546FFF7E0FF044601462846FFF744 -:102A900011FF204638BD0000FEE7000000B59BB0E6 -:102AA000EFF3098168226846FFF780F8EFF30583AA -:102AB000044B9A6BDA6A9A6A9A6A9A6A9A6A9A6A6A -:102AC0009B6AFEE700ED00E000B59BB0EFF30981E3 -:102AD00068226846FFF76AF8EFF30583044B9A6BA8 -:102AE0009A6A9A6A9A6A9A6A9A6A9B6AFEE700BF29 -:102AF00000ED00E000B59BB0EFF309816822684665 -:102B0000FFF754F8EFF30583034B5A6B9A6A9A6AFE -:102B10009A6A9A6A9B6AFEE700ED00E00FB408B576 -:102B2000029801F013FBFEE701F0EABD01F0D4BD0D -:102B300030B5084D0A4491420BD011F8013B0924ED -:102B40005840013CF7D040F300032B4083EA50008B -:102B5000F7E730BD2083B8ED2DE9F047089E01F07E -:102B600007054FEAD60C2A4406F0070600EBD10011 -:102B70004FF47F49954201D1BDE8F08705F0070E7B -:102B800006F0070AD64577464FEAD50438BF5746C0 -:102B9000C7F10807511B0CEBD6088F42045D28BF14 -:102BA0000F4604FA0EF413F8081029FA07FE24FA67 -:102BB0000AF45FFA8EFE4C404EFA0AFE04EA0E0456 -:102BC000614003F808103D443E44D3E702460068E4 -:102BD00048B103681360D388118901339BB29942CD -:102BE000D38038BF1381704770B588B00D46044656 -:102BF000202200216846FEF7EBFF20460495FFF7F0 -:102C0000E5FF054658B16B46044608AE1A4603CAAE -:102C1000B24220606160134604F10804F6D12846F0 -:102C200008B070BD2DE9F041056885B90160BDE8C7 -:102C3000F081002B29DA930CB34229D1A54201D1AE -:102C40000D60F3E7C8F800100C60BDE8F0814B6838 -:102C500023F06047BE0C4FEAD37EC3F3807C16EAB4 -:102C6000230638BF3E46A8462C466368BEEBD37F9A -:102C700023F06042DDD1974203D1C3F380739C45BA -:102C80000AD1974205E01C46EFE7B24206D0134650 -:102C90009E422CBF00230123002BCFD12368A046E6 -:102CA000002BF0D12160BDE8F08100002DE9F0415A -:102CB00006460F4600254FF6FF7441F221082A46CA -:102CC00030463946FDF790FAC0B284EA0024082362 -:102CD00014F4004F4FEA4404A4B203F1FF3318BFC9 -:102CE00084EA080413F0FF03F2D10835402DE6D141 -:102CF0002046BDE8F081000010B54B6833B9CA8AA0 -:102D000063F30902CA820020002110BDC4681A685A -:102D10001C60C360438A013B43824A60EDE70000C8 -:102D200010B50A4441F22104914200D110BD11F8BE -:102D3000013B80EA0320082310F4004F4FEA4000D3 -:102D400080B203F1FF3318BF604013F0FF03F3D1EB -:102D5000EAE700002DE9F04F85B081468DE80A00D2 -:102D6000BDF83C409346002A00F0838024B10E9BBE -:102D7000002B7ED0072C2AD809F10C00FFF726FF84 -:102D8000054628B96FF00205284605B0BDE8F08F6A -:102D900014220021FEF71CFF22460E9905F10800BF -:102DA000FEF704FF631C2B749BF800302C4403F0E7 -:102DB0001F0363F03F032372009B43F000436B60EB -:102DC000294609F11C00FFF72DFF0125DCE7019BD7 -:102DD0001B0A4FF00008029300F10C034FF0800A29 -:102DE0004646454603930398FFF7F0FE0746002842 -:102DF000C8D014220021FEF7EBFEC6BB9DF80430BC -:102E00003B729DF808307B7202220E9B711E1944A2 -:102E1000B4420AD9B8180132D2B211F801EF80F8E1 -:102E200008E00136072AB6B2F2D19BF8001001F093 -:102E30001F01B44208BF4FF0400AB81841EA4811D8 -:102E40004AEA01030372009B013243F000437B60B6 -:102E50003A74394609F11C00FFF7E4FE0135B4422B -:102E60002DB288F001084FF0000ABCD18CE7002297 -:102E7000CBE76FF0010587E72DE9F0471E46CB8AC7 -:102E80009146C3F30902062A80460F4619D013461D -:102E90000021B0B28DB25A1992B2052A09D9A842BE -:102EA00010D8FA8A034463F30902FA820120BDE8CC -:102EB000F087A842F3D93A4419F8014094760131D9 -:102EC000E8E70025FB8A7C68C3F30900821F1C2306 -:102ED000B2FBF3FA03FB1A2A1FFA8AF27CB3012130 -:102EE0002368002B39D1B31F03441C20B3FBF0F33C -:102EF00001339BB299420CD2BAF1000F09D140467E -:102F0000FFF764FE08B1C0F800A0206008B30446D3 -:102F10000022B6B24FF0000AB54230D2691E4944D1 -:102F20001346E01801339BB211F801EF80F804E07A -:102F300001351C2BADB214D0AE42F2D8ECE74046BE -:102F4000FFF744FE044608B1002303607C60002CB8 -:102F5000DED16FF00200BDE8F087013189B21C4676 -:102F6000BEE7AE42D8D94046FFF730FE08B1C0F800 -:102F700000A020600028ECD004460022CCE7FB8AA9 -:102F8000C3F30902164466F30903FB828EE70000CF -:102F9000F8B5044615460E46242200211F46FEF7CA -:102FA00017FE069B6360079B23626A094FF6FF7357 -:102FB0009A424FF0000028BF1A46A760207097B2CF -:102FC00004F10C0503469A4205D100232B602782A9 -:102FD0006382A382F8BD2E60013335462036F2E7C6 -:102FE00003781BB94BB2002BC8BF017070470000BB -:102FF000007870472DE9F7430D9EBDF828900B9D92 -:103000009DF83040BDF8388007461946104616B97D -:10301000B8F1000F40D11F2C3ED83B78D3B9B8F19E -:10302000070F36D839F0030336D1424631464FF602 -:10303000FF70FFF775FE4FEA092920F0010009F43F -:103040004079400449EA0464400C44EA40244FF6C5 -:10305000FF730DE043EA0923B8F1070F43EA046464 -:10306000F5D9FFF723FE42463146FFF759FE0346E6 -:103070008DE840012A4621463846FFF76BFE2B7843 -:103080000133DBB21F2B88BF00232B7003B0BDE8D8 -:10309000F0836FF00300F9E76FF00100F6E700003E -:1030A0002DE9F7430E9F0B9D9DF83480BDF83C60E1 -:1030B00081469DF8300007B9AEBB1F2833D899F878 -:1030C00000E0BEF1000F31D00C0244F080049DF806 -:1030D000281044EAC83444EA014444EA0E04072EA6 -:1030E00044EA00641CD919461046FFF7DFFD32465A -:1030F0003946FFF715FE0346019600972A462146FA -:103100004846FFF727FEB8F1010F06D12B780133AF -:10311000DBB21F2B88BF00232B7003B0BDE8F08308 -:103120004FF6FF73E8E76FF00100F6E76FF003007A -:10313000F3E70000C06900B104307047C3691A6842 -:10314000C261C2681A60C360438A013B4382704710 -:103150002DE9F047D0F818A0DFF870800546164634 -:103160001F4654464FF000090CB9BDE8F087D4E97A -:103170000223B21A67EB0303994508BF904523D297 -:10318000AB699C42214628460FD1FFF7B5FDAB69DC -:103190001B68AB61EB6823606B8AEC60AC69013B38 -:1031A0006B822346A2461C46DEE7FFF7A5FD236897 -:1031B000CAF80030EB6823606B8AEC60013B6B82DD -:1031C000DAF800305446EDE72368EBE780841E0010 -:1031D0002DE9F04F8BB00E4614460793DDF8508072 -:1031E0008346002800F01081B8F1000F00F00C8138 -:1031F000531E3F2B00F20881012A03D1079B002BAD -:1032000040F00281BBF81450ED000023AE42089359 -:10321000099304D3002630460BB0BDE8F08F331974 -:103220009D42DBF80C303ABFAD1BEDB2254623B909 -:10323000DBF81030002B00F093802F2E65D8C6F1FC -:103240003007BD424FF000032CBFFFB22F46009362 -:10325000314608AB3A46DBF80800FFF77DFCA5EBEA -:1032600007093E445FFA89F9BBF8143003F10053B3 -:10327000063BDB000493DBF80C3003933021039B07 -:1032800013B1B9F1000F43D1DBF8100040B1B9F12F -:10329000000F05D0009708AB4A46711AFFF75CFC97 -:1032A0002EB2002DB6D060070AD00AAB03EBD401D2 -:1032B000624211F8083C02F00702134101F8083C91 -:1032C000082C54D9102C54D9202C8CBF082304234B -:1032D000079A002A00F09E80B4EBC30F00F09D8097 -:1032E000082C48D89DF82030621E23FA02F2D1073C -:1032F00006D54FF0FF3202FA04F423438DF8203054 -:103300009DF8203088F8003085E7A9460027ABE714 -:10331000049BE02B28BFE02306930B44B3420593A4 -:1033200015D9A3EB060AD145039800972CBF5FFA85 -:103330008AFACA46711A08AB52460430FFF70CFCF1 -:103340005744A9EB0A095644FFB25FFA89F9049B76 -:10335000069A05999B1A0493039B1B6803938EE7B7 -:1033600000932A4608AB3146DBF8080096E70123B4 -:10337000AEE70223ACE7102C12D8BDF82030621E55 -:1033800023FA02F2D20706D54FF0FF3202FA04F414 -:103390002343ADF82030BDF82030A8F800303AE7DC -:1033A000202C0FD8089A631E22FA03F3DB0705D5F9 -:1033B0004FF0FF3303FA04F414430894089BC8F851 -:1033C000003028E7402C22D0DDE908AB621E5046D1 -:1033D0005946FCF709FF002100F0010050EA010303 -:1033E0000DD0224601200021FCF70AFF404261EB8C -:1033F000410140EA0A0041EA0B01CDE90801DDE99B -:103400000823C8E9002306E76FF0010603E76FF021 -:10341000080600E7012C3FF473AF082C7FF670AF6D -:10342000102CB8D9202CEAD8C8E7000030B5402AC3 -:1034300085B01FD8002A08BF01220024012A029467 -:10344000039419D11B788DF8083053070AD004ABC8 -:1034500003EBD205544215F8083C04F00704A340DE -:1034600005F8083C00910346002102A8FFF774FB11 -:1034700005B030BD4022E0E7082AE3D9102A03D87E -:103480001B88ADF80830E0E7202A02D81B680293B9 -:10349000DBE7D3E90045CDE90245D6E710B5CB68B7 -:1034A0001BB98B600B618B8210BDC4681A681C60ED -:1034B000C360438A013B4382CA60F0E72DE9F04FC5 -:1034C000D1F800908FB0C9F3C01604460D46CDE97F -:1034D0000223002E50D0C9F3C03AC9F30626B9F131 -:1034E000000F80F2CB8119F0C04F40F0C7812B7BD9 -:1034F000002B00F0C381BAF1020F03D02278B24250 -:1035000040F0BF8109F07F02BAF1020F059236D177 -:1035100019F07F0FC9F30F2B01D10BF0030B2B44D4 -:103520007606059A93F8038046EA0A4646EA8246FA -:103530005FEAD81346EA0B06049300F0A18000224C -:1035400000230EA961E90823059B00936768534691 -:103550005A462046B847002800F08F80A7698FB9E7 -:10356000314604F10C00FFF73FFB0746D0B96FF07E -:1035700002000FB0BDE8F08F4FF0020AAFE7C9F3C9 -:10358000074BCCE73B699E420DD03F68002FF9D135 -:10359000314604F10C00FFF727FB07460028E6D070 -:1035A000A3693B60A761DDE90601FFF77FFBB882F5 -:1035B000F97D08F01F06C1F38401711A89B20FFA70 -:1035C00081FED7E90223BEF1000FBCBF01F1200E3E -:1035D0000FFA8EFE52EA0301C9F3046900F05D811F -:1035E000DDE90201801A61EB030102460B46B64891 -:1035F0000021994208BF9042C0F04F81049B002BEC -:1036000048D0BEF1010F00F3488118F0400F41D0BF -:10361000DDE902230021C7E9022306A82022FEF7E4 -:10362000D7FADDE90223CDE906232B1D08932B7B76 -:10363000ADF82EB0013BDBB2ADF82C309DF8143064 -:103640008DF833308DF830A0A3688DF831608DF897 -:10365000329006A920469847FB7DC3F384020132CD -:1036600062F38603FB75FB8A6FF30903FB821B0A77 -:103670006FF3C713FB7500207BE76FF00B0078E753 -:10368000A76917B96FF00C0073E73B699E428FD0B2 -:103690003F68F6E7FB7DC8F34012B2EBD31F40F062 -:1036A000F380C3F38403B34240F0F18004992B7B91 -:1036B0004FEA981200293BD012F001085CD1032B8D -:1036C00040F2E880DDE90223C7E902232B7BAE1D2F -:1036D000033BDBB23246394604F10C00FFF7CCFB6A -:1036E000002814DA39462046FFF706FBFB7DC3F3BA -:1036F0008402013262F38603FB75FB8A68F30903D7 -:10370000FB821B0A68F3C713FB75032031E7AB8804 -:103710003B832A7B033AD2B2B88A3146FFF700FBDB -:10372000FB7DB882DA43C2F3C01262F3C713A1E78C -:1037300012BB2E1D013BDBB23246394604F10C00B0 -:10374000FFF79AFB002814DA39462046FFF7D4FA2F -:10375000FB7DC3F38402013262F38603FB75049A96 -:10376000FB8A62F30903FB82049A1B0A62F3C71304 -:10377000CAE72A7B013ACEE7F98AC1F30901013B86 -:103780000529DAB25AD8281D00239A420AD907EB34 -:10379000010E013110F801CB8EF81AC00133062951 -:1037A000DBB2F2D1DDE902019342CDE9060107F176 -:1037B0001A01089138BF04337968099134BF5B1945 -:1037C00000230A93FB8AADF82EB0C3F309031A4411 -:1037D0009DF814308DF833300023ADF82C208DF88F -:1037E00030A08DF831608DF832907B602A7BB88AEA -:1037F000013A291DFFF794FA3B8BB882834203D12B -:10380000A36806A920469847204606A9FFF746FE6A -:10381000FB7DB88AC3F38402013262F38603FB7531 -:10382000FB8A6FF30903FB821B0A6FF3C713FB7557 -:103830003B8B984214BF112000209AE6D7F804E091 -:10384000BEF1000F18D00623DEF8000088B9C91AAF -:1038500005F1040800EB010CBCF11B0FC3B2A1D8A9 -:1038600093429FD2F44418F8013B8CF804300130A5 -:10387000F0E71C338646E7E7734693E76FF00900ED -:1038800077E66FF00A0074E66FF00D0071E66FF0F6 -:103890000E006EE66FF00F006BE6FB7D68F38603AB -:1038A0006FF3C713FB7539462046FFF725FA049BD3 -:1038B000002B7FF4AAAEFB7DC3F38402013262F3D6 -:1038C0008603FB75DEE600BF80841E00EFF30983EC -:1038D00005494A6822F001024A60683383F3098887 -:1038E000002383F31188704730EF00E0202080F33D -:1038F000118862B60B4B0C4AD96821F4E0610904C7 -:10390000090C0A430949DA60CA6842F08072CA6049 -:1039100007490A6842F001020A601022DA7783F848 -:103920002200704700ED00E00003FA05F0ED00E032 -:10393000001000E010B5202383F311880E4B5B6864 -:1039400013F4006314D0F1EE103AEFF30984683CED -:103950004FF08073E361094BDB68236684F30988C9 -:1039600000F0A8FB10B1064BA36110BD054BFBE7AF -:1039700083F3118810BD00BF00ED00E030EF00E0E0 -:103980007B0600087E060008002304491A465A50A8 -:10399000C8180833802B4260F9D17047BC5700200B -:1039A000024AD36843F0C003D3607047004400402C -:1039B000044B5A6810439A6858600AB1181D1047A2 -:1039C000704700BF3C5800202DE9F0413D4ED6F82D -:1039D0005C52EF682B68DA059CB20CD5202383F388 -:1039E00011884FF40070FFF7E3FF6FF480732B60D2 -:1039F000002383F31188202383F31188DFF8C48028 -:103A000014F02F0331D183F31188380613D5210622 -:103A100011D5202383F311882B4800F0F5F90028F5 -:103A200044DA0820FFF7C4FF4FF67F733B40EB609A -:103A3000002383F311887A060DD563060BD5202366 -:103A400083F31188F26C336D9A4201D1336C7BBBE6 -:103A5000002383F31188D6F86422D3680BB1106970 -:103A60009847BDE8F041FFF765BF230712D014F077 -:103A7000080F0CBF00208020E10748BF40F0200065 -:103A8000A20748BF40F04000630748BF40F4807081 -:103A9000FFF78EFFA4066B6805D596F860124046C6 -:103AA000194000F061FA2C68A4B2A9E76860BFE78A -:103AB00027F040073F0410203F0CFFF779FFEF602D -:103AC000C6E700BF3C5800207458002010B5054CD4 -:103AD000054A0021204600F017FA044BC4F85C3276 -:103AE00010BD00BF3C580020A13900080044004030 -:103AF00038B52C4C037C002918BF0C46012B054619 -:103B0000C0F8644210D1284B98420DD1274B1A6C53 -:103B100042F400321A641A6E42F400321A660B2123 -:103B200026201B6E00F048F8214BD5F85C229A4203 -:103B3000236802D01F498A422DD1590801F13771FB -:103B400001F5D841B1FBF3F3A188080442BF23F08B -:103B5000070003F0070343EA40039360E38843F060 -:103B600040039BB21361238943F001039BB253616D -:103B700041F4045343F02C03D36001F4A05100231B -:103B80001360B1F5806F136853680CBF7F23FF2368 -:103B900085F8603238BD590801F1B77101F5585107 -:103BA000D0E700BF345200083C58002000380240E3 -:103BB000001001400014014000F1604300F01F02BA -:103BC000400903F5614309018000C9B200F160407A -:103BD00083F8001300F5614001239340C0F8803161 -:103BE00003607047F8B5154682680669AA420B461D -:103BF000816938BF8568761AB542044607D21846EF -:103C00002A46FDF7D3FFA3692B44A3610DE011D928 -:103C100032461846FDF7CAFFAF1B3A46E16830440A -:103C2000FDF7C4FFE2683A44A261A3685B1BA3608E -:103C30002846F8BD18462A46FDF7B8FFE368E4E7D2 -:103C400083682DE9F041044693421546266938BF42 -:103C500085684069361AB5420F4606D22A46FDF7F6 -:103C6000A5FF63692B4463610DE012D93246A5EBD1 -:103C70000608FDF79BFF4246B919E068FDF796FF7D -:103C8000E26842446261A3685B1BA3602846BDE80A -:103C9000F0812A46FDF78AFFE368E4E710B50A449D -:103CA0000024C361029B006040608460C160816148 -:103CB00041610261036210BD08B5826943699342A4 -:103CC00001D1826882B98268013282605A1C4261E5 -:103CD0001970426903699A4201D3C36843610021A4 -:103CE00000F0B8FA002008BD4FF0FF3008BD00001A -:103CF00070B5202304460E4683F31188A568A5B14C -:103D0000A368A269013BA360531CA36115782269D3 -:103D1000934224BFE368A361E3690BB1204698474F -:103D2000002383F31188284670BD3146204600F0F9 -:103D300081FA0028E2DA85F3118870BD2DE9F74F8A -:103D400005460F4690469A46D0F81C90202686F3EA -:103D500011884FF0000B144664B1224639462846BC -:103D6000FFF740FF034668B95146284600F062FA63 -:103D70000028F1D0002383F31188A8EB040003B0DE -:103D8000BDE8F08FB9F1000F03D001902846C84775 -:103D9000019B8BF31188E41A1F4486F31188DBE73B -:103DA000C16081614161C3611144009B006040605A -:103DB0008260016103627047F8B504460E461746FB -:103DC000202383F31188A568A5B1A368013BA360F4 -:103DD00063695A1C62611E70236962699A4224BF3A -:103DE000E3686361E3690BB120469847002080F3E4 -:103DF0001188F8BD3946204600F01CFA0028E2DAA6 -:103E000085F31188F8BD0000836942699A4210B5B4 -:103E100001D182687AB98268013282605A1C82615B -:103E20001C7803699A4201D3C3688361002100F0C2 -:103E300011FA204610BD4FF0FF3010BD2DE9F74FAD -:103E400005460F4690469A46D0F81C90202686F3E9 -:103E500011884FF0000B144664B1224639462846BB -:103E6000FFF7EEFE034668B95146284600F0E2F936 -:103E70000028F1D0002383F31188A8EB040003B0DD -:103E8000BDE8F08FB9F1000F03D001902846C84774 -:103E9000019B8BF31188E41A1F4486F31188DBE73A -:103EA000026843681143016003B11847704700007E -:103EB0001430FFF743BF00004FF0FF331430FFF71B -:103EC0003DBF00003830FFF7B9BF00004FF0FF33AF -:103ED0003830FFF7B3BF00001430FFF709BF000010 -:103EE0004FF0FF311430FFF703BF00003830FFF709 -:103EF00063BF00004FF0FF323830FFF75DBF0000B6 -:103F000000207047FFF7E2BD37B50F4B0360002379 -:103F100043608360C3600123044603741546009028 -:103F20000B464FF4807200F15C011430FFF7B6FECF -:103F300000942B464FF4807204F5AE7104F1380002 -:103F4000FFF72EFF03B030BD4852000810B5202304 -:103F5000044683F31188FFF7CBFD0223237400236B -:103F600083F3118810BD000038B5C36904460D46BF -:103F70001BB904210844FFF793FF294604F11400FC -:103F8000FFF79AFE002806DA201D4FF48061BDE895 -:103F90003840FFF785BF38BD024B00221B605B60D5 -:103FA0009A607047A45A0020002303748268054B6E -:103FB0001B6899689142FBD25A68036042601060A6 -:103FC00058607047A45A002008B5202383F3118855 -:103FD000037C032B05D0042B0DD02BB983F3118860 -:103FE00008BD436900221A604FF0FF334361FFF7B9 -:103FF000DBFF0023F2E790E80C001A6002685360D0 -:10400000F2E70000002303748268054B1B6899687F -:104010009142FBD85A680360426010605860704754 -:10402000A45A0020054B19690874186802681A60C0 -:104030005360186101230374FCF70ABBA45A0020E3 -:1040400030B54B1C87B005460A4C10D023690A4A8C -:1040500001A800F019F92846FFF7E4FF049B13B10B -:1040600001A800F063F92369586907B030BDFFF774 -:10407000D9FFF8E7A45A0020C93F000838B50C4D15 -:1040800041612B6981689A689142044603D8BDE872 -:104090003840FFF789BF1846FFF7B4FF01232C61B2 -:1040A000014623742046BDE83840FCF7D1BA00BF72 -:1040B000A45A0020044B1A681B6990689B689842B8 -:1040C00094BF002001207047A45A002010B5084C6E -:1040D000236820691A6822605460012223611A74DF -:1040E000FFF790FF01462069BDE81040FCF7B0BA29 -:1040F000A45A002008B5FFF7DDFF18B1BDE808405D -:10410000FFF7E4BF08BD0000FEE7000010B50C4C4F -:10411000FFF742FF00F0AAF880220A49204600F08B -:104120003DF8012344F8180C0374FFF7DFFB00236C -:1041300083F3118862B60448BDE8104000F050B81F -:10414000CC5A0020705200087852000808B572B6A8 -:10415000034B586200F0A4FA00F034FBFEE700BF06 -:10416000A45A002000F01CB9EFF3118020B9EFF33E -:104170000583202282F311887047000010B558B9DA -:10418000EFF30584C4F3080414B180F3118810BD63 -:10419000FFF7B0FF84F3118810BD00008260022297 -:1041A00002740022427470478368A3F17C0243F8D2 -:1041B0000C2C026943F83C2C426943F8382C074A1E -:1041C00043F81C2CC26843F8102C022203F8082C78 -:1041D000002203F8072CA3F11800704769060008B5 -:1041E00010B5202383F31188FFF7DEFF002104467A -:1041F000FFF744FF002383F31188204610BD000021 -:10420000024B1B6958610F20FFF70CBFA45A002016 -:10421000202383F31188FFF7F3BF000008B50146A0 -:10422000202383F311880820FFF70AFF002383F37C -:10423000118808BD49B1064B42681B6918605A6075 -:10424000136043600420FFF7FBBE4FF0FF30704760 -:10425000A45A00200368984206D01A680260506091 -:1042600059611846FFF7A0BE70470000054B03F1E7 -:1042700014025A619A614FF0FF32DA6100221A6229 -:10428000704700BFA45A0020F8B5274F0361C260F1 -:104290000D46044600F004FB3B46022D53F8142F54 -:1042A000294638BF02219A423E461D460AD138624D -:1042B0007C61BC61084422606260A160BDE8F84096 -:1042C00000F0DCBAD7F820E0A0EB0E035F181FD394 -:1042D00000279068834217D8376AAA421F44376282 -:1042E00001D0C01A906073699A68914219D85A68CF -:1042F0002360626014605C60A1609868411A9960F4 -:104300004FF0FF33F361F8BD97601B1A1268E0E7C6 -:1043100093689F4203D20EEB070000F0BDFA3946C6 -:10432000E1E7891A1B68DFE7A45A002038B51B4B68 -:1043300001685A6990421D4603F114020CD044688A -:1043400021600368002193425C60C16025D09A68B7 -:1043500081680A449A6038BD59614A605B690021EE -:104360009342C16003D1BDE8384000F08FBA9A682B -:1043700081680A449A602C6A00F092FA6A6992682D -:10438000001B824209D9111A012998BF821C286A90 -:10439000BDE83840104400F07FBA38BDA45A002070 -:1043A0002DE9F84F204C0027656904F11406B84642 -:1043B00000F076FA236AA0EB030AAB6853451DD8D8 -:1043C0004FF02009236AAA68D5F80CB01344236281 -:1043D000AB68AAEB030A2B68B3425E606361EF60CF -:1043E00001D100F053FA88F311882869D84789F37E -:1043F00011886569AB689A45E4D2D9E76369B3422D -:1044000010D020629A68A2EB0A029A60226AAB6816 -:10441000821A9B1A022B2CBFC0180230BDE8F84F3D -:1044200000F03ABABDE8F88FA45A00200C230360CC -:104430004FF0FF307047000000207047FEE700009B -:10444000704700004FF0FF3070470000BFF34F8F00 -:10445000024AD368DB03FCD4704700BF003C024033 -:1044600008B5094B1B7873B9FFF7F0FF074B1A69C2 -:10447000002ABFBF064A5A6002F188325A601A68A1 -:1044800022F480621A6008BD605C0020003C02409B -:104490002301674508B50B4B1B7893B9FFF7D6FF8F -:1044A000094B1A6942F000421A611A6842F48052BC -:1044B0001A601A6822F480521A601A6842F4806204 -:1044C0001A6008BD605C0020003C0240072870B5FF -:1044D00013D80B4A0B4C137863B90B4E4FF00061A5 -:1044E00044F8231056F823500133082B2944F7D100 -:1044F0000123137054F8200070BD002070BD00BF70 -:10450000845C0020645C002098520008014B53F842 -:10451000200070479852000808207047072810B5FF -:10452000044601D9002010BDFFF7D0FF064B53F819 -:1045300024301844C21A0BB9012010BD1268013290 -:10454000F0D1043BF6E700BF98520008072810B5E9 -:10455000044621D8FFF77AFFFFF782FF0F4AF323C3 -:10456000D360C300DBB243F4007343F00203136172 -:10457000136943F480331361FFF768FFFFF7A6FF69 -:10458000074B53F8241000F019F9FFF783FF20467A -:10459000BDE81040FFF7C2BF002010BD003C024044 -:1045A000985200082DE9F84312F00103154640D156 -:1045B00084182E4A94423CD82D4B1B6813F00103FB -:1045C00037D02C4CFFF74CFFF323E360FFF73EFF9F -:1045D00040F20127032D01D9830713D0254C0F4644 -:1045E000401A40F20118EB1B0B44012B00EB0706AD -:1045F000236924D823F001032361FFF74BFF012037 -:10460000BDE8F883236923F44073236123693B43A6 -:10461000236151F8046B0660BFF34F8FFFF716FF5D -:1046200003689E4208D0236923F001032361FFF74A -:1046300031FF0020BDE8F883043D0430CAE723F4CD -:1046400040732361236943EA08032361B94637F8BD -:10465000023B3380BFF34F8FFFF7F8FE3688B9F87F -:104660000030B6B2B342BED0DDE700BFFFFF07089F -:1046700000380240003C0240084908B50B7828B1D8 -:1046800053B9FFF7EDFE01230B7008BD23B1BDE860 -:1046900008400870FFF7FEBE08BD00BF605C002048 -:1046A0004FF480214FF0005000F08AB838B500F088 -:1046B000F7F8074B1A68824207D9064AD2E9004543 -:1046C000003445F10105C2E90045186038BD00BF5E -:1046D000885C0020905C002070B5FFF745FD064621 -:1046E000FFF7E4FF054BD3E90045241845F1000529 -:1046F0003046FFF743FD2046294670BD905C002000 -:1047000008B5FFF7E9FF4FF47A720023FBF784FD49 -:1047100008BD00BF10B50244064B0439D2B2904226 -:1047200000D110BD441C00B253F8200041F8040F22 -:10473000E0B2F4E750280040104B30B51C6F240461 -:1047400007D41C6F44F400741C671C6F44F40044CD -:104750001C670B4C236843F4807323600244094BAD -:104760000439D2B2904200D130BD441C00B251F89D -:10477000045F43F82050E0B2F4E700BF0038024085 -:10478000007000405028004007B5012201A9002018 -:10479000FFF7C0FF019803B05DF804FB13B50446B2 -:1047A000FFF7F2FFA04206D002A9012241F8044D12 -:1047B0000020FFF7C1FF02B010BD000070470000ED -:1047C0007047000070470000074B45F255521A60D1 -:1047D00002225A6040F6FF729A604CF6CC421A6090 -:1047E000024B01221A70704700300040995C002093 -:1047F000034B1B781BB1034B4AF6AA221A60704781 -:10480000995C002000300040034B1B689B0042BFB6 -:10481000024B01221A70704774380240985C0020E5 -:10482000024B4FF080721A60704700BF743802402C -:10483000014B1878704700BF985C0020704700005B -:10484000FEE70000084A094B09498B4204D3094A94 -:104850000021934205D3704752F8040F43F8040B2C -:10486000F3E743F8041BF4E718540008AC5C00209D -:10487000AC5C0020AC5C002000F086B84FF08043B8 -:10488000002258631A610222DA6070474FF08043B9 -:104890000022DA60704700004FF080435863704791 -:1048A0004FF08043586A70474B6843608B68836061 -:1048B000CB68C3600B6943614B6903628B694362D8 -:1048C0000B6803607047000008B51F4B1F481A694A -:1048D00042F0FF021A611A6922F0FF021A611A6996 -:1048E0001A6B42F0FF021A631A6D42F0FF021A655A -:1048F000174A1B6D1146FFF7D7FF164802F11C013E -:10490000FFF7D2FF144802F13801FFF7CDFF13483B -:1049100002F15401FFF7C8FF114802F17001FFF7DF -:10492000C3FF104802F18C01FFF7BEFF0E4802F1F1 -:10493000A801FFF7B9FF0D4802F1C401FFF7B4FF6A -:10494000BDE8084000F0A4B8003802400000024072 -:10495000B85200080004024000080240000C024067 -:10496000001002400014024000180240001C0240E7 -:1049700008B500F00BFAFFF7C9FBBDE80840FFF7E8 -:1049800043BF000070470000104B1A6C42F0010258 -:104990001A641A6E42F001021A660D4A1B6E936881 -:1049A00043F0010393604FF080432F229A624FF04F -:1049B000FF32DA6200229A615A63DA605A60012299 -:1049C0005A6108211A601C20FFF7F6B8003802402F -:1049D000002004E04FF0804208B51369D1680B4015 -:1049E000D9B2C9439B07116107D5202383F31188EE -:1049F000FFF7B8FB002383F3118808BD08B5FFF764 -:104A0000E9FFBDE80840FEF795BF00001E4B1A699C -:104A100062F0FF021A611A69D2B21A614FF0FF30D8 -:104A20001A695A69586100215A6959615A691A6AA2 -:104A300062F080521A621A6A02F080521A621A6A8E -:104A40005A6A58625A6A59625A6A1A6C42F080521B -:104A50001A641A6E42F080521A661A6E0B4A106877 -:104A600040F480701060186F00F44070B0F5007F63 -:104A70001EBF4FF4803018671967536823F4007322 -:104A8000536000F063B900BF00380240007000407E -:104A9000364B374A1A64374A4FF4404111601A685E -:104AA00042F001021A601A689207FCD59A6822F057 -:104AB00003029A602D4B19469A6812F00C02FBD142 -:104AC000186800F0F90018609A601A6842F48032A1 -:104AD0001A600B689B03FCD54B6F43F001034B67D7 -:104AE000224B5A6F9007FCD5234A5A601A6842F04D -:104AF00080721A601F4A53685904FCD51B4B1A6810 -:104B00009201FCD51D4A9A600322C3F88C20002232 -:104B1000C3F894201A4B1A681A4B9A421A4B21D1A7 -:104B20001A4A11681A4A91421CD140F203121A60C3 -:104B3000154A136803F00F03032BFAD10B4B9A6845 -:104B400042F002029A609A6802F00C02082AFAD136 -:104B50005A6C42F480425A645A6E42F480425A6659 -:104B60005B6E704740F20372E1E700BF003802401D -:104B70000004001000700040106041080094883864 -:104B8000002004E011640020003C024000ED00E041 -:104B900041C20F41084A08B5536911680B4003F040 -:104BA0000103536123B1054A13680BB1506898475C -:104BB000BDE80840FEF7BEBE003C0140BC570020E7 -:104BC000084A08B5536911680B4003F002035361AA -:104BD00023B1054A93680BB1D0689847BDE80840F7 -:104BE000FEF7A8BE003C0140BC570020084A08B5AB -:104BF000536911680B4003F00403536123B1054A64 -:104C000013690BB150699847BDE80840FEF792BEA2 -:104C1000003C0140BC570020084A08B553691168A0 -:104C20000B4003F00803536123B1054A93690BB1AC -:104C3000D0699847BDE80840FEF77CBE003C0140C3 -:104C4000BC570020084A08B5536911680B4003F0AF -:104C50001003536123B1054A136A0BB1506A984798 -:104C6000BDE80840FEF766BE003C0140BC5700208E -:104C7000174B10B55C691A68144004F478725A61D5 -:104C8000A30604D5134A936A0BB1D06A984760060D -:104C900004D5104A136B0BB1506B9847210604D50D -:104CA0000C4A936B0BB1D06B9847E20504D5094AC7 -:104CB000136C0BB1506C9847A30504D5054A936C4F -:104CC0000BB1D06C9847BDE81040FEF733BE00BF73 -:104CD000003C0140BC5700201A4B10B55C691A68B3 -:104CE000144004F47C425A61620504D5164A136DDF -:104CF0000BB1506D9847230504D5134A936D0BB142 -:104D0000D06D9847E00404D50F4A136E0BB1506E76 -:104D10009847A10404D50C4A936E0BB1D06E984706 -:104D2000620404D5084A136F0BB1506F98472304EF -:104D300004D5054A936F0BB1D06F9847BDE810407A -:104D4000FEF7F8BD003C0140BC570020062108B525 -:104D50000846FEF731FF06210720FEF72DFF06214A -:104D60000820FEF729FF06210920FEF725FF06216E -:104D70000A20FEF721FF06211720FEF71DFF06215E -:104D80002820BDE80840FEF717BF000008B5FFF770 -:104D90003DFEFEF7F9FDFFF7B5F8FFF7F3FDBDE8BF -:104DA0000840FFF769BD000010B5002814BF044695 -:104DB0000124204600F030F830B900F00DF808B9B1 -:104DC00000F014F88047F4E710BD00000B460146E0 -:104DD000184600F013B80000024B1868BFF35B8F51 -:104DE000704700BF9C5C002000F01EB808B506208C -:104DF00000F034F90120FFF721FB000010B5054C4D -:104E000013462CB10A4601460220AFF3008010BDC4 -:104E1000204610BD00000000024B0146186800F05B -:104E200087B800BF18230020024B0146186800F025 -:104E300031B800BF1823002010B501390244904258 -:104E400001D1002010BD10F8013B11F8014FA34221 -:104E5000F5D0181B10BD00002DE9F8430746884621 -:104E600091461E468BB10D46A8EB0500B54207EBF7 -:104E7000000402D20020BDE8F883324649462046AD -:104E8000FFF7DAFF18B1013DEEE7BDE8F8832046F1 -:104E9000BDE8F88338B50546002945D051F8043CF3 -:104EA0000C1F002BB8BFE41800F0FCF81F4A136871 -:104EB000104633B9636014602846BDE8384000F0FE -:104EC000F3B8A3420CD921686218934204BF1A6850 -:104ED0005B68636004BF521822600460ECE713460D -:104EE0005A680AB1A242FAD919685818A0420BD1DF -:104EF00020680144581882421960DDD11068526858 -:104F00005A6001441960D7E702D90C232B60D3E71C -:104F1000206821188A4204BF11685268626004BF89 -:104F2000091821605C60C7E738BD00BFA05C0020A5 -:104F300070B5CD1C25F0030508350C2D38BF0C25A8 -:104F4000002D064601DBA94203D90C233360002063 -:104F500070BD00F0A7F8234A1468214691B9224C8D -:104F600023681BB9304600F041F8206029463046DE -:104F700000F03CF8431C26D10C233360304600F08F -:104F800093F8E4E70B685B1B1AD40B2B0FD90B606B -:104F9000CD50CC18304600F087F804F10B00231DEB -:104FA00020F00700C31A1BD05A42E25070BD8C4259 -:104FB0000DBF63684B686360136018BF0C46E9E778 -:104FC0000C464968CAE7C41C24F00304A04205D07B -:104FD000211A304600F00AF80130CDD02560D9E71B -:104FE00070BD00BFA05C0020A45C002038B5064C5A -:104FF0000023054608462360FFF718FA431C02D138 -:10500000236803B12B6038BDA85C00201F2938B588 -:1050100004460D4604D9162303604FF0FF3038BD17 -:10502000426C12B152F821304BB9204600F030F8F2 -:105030002A4601462046BDE8384000F017B8012B4B -:105040000AD0591C03D116230360012038BD002467 -:1050500042F8254028469847002038BD024B0146BB -:105060001868FFF7D3BF00BF1823002038B5074CDE -:1050700000230546084611462360FFF7E3F9431C69 -:1050800002D1236803B12B6038BD00BFA85C0020AB -:10509000FFF7D2B9034611F8012B03F8012B002AC0 -:1050A000F9D17047704700007047000012101213CA -:1050B0001211000040A2E4F1646891064E6F206175 -:1050C0007070207369670A00426164206677206C03 -:1050D000656E6774682025750A0042616420626FFE -:1050E0006172645F69642025752073686F756C64F4 -:1050F0002062652025750A0042616420667720647D -:10510000657363726970746F72206C656E67746822 -:105110002025750A0042616420617070204352436B -:10512000203078253038783A30782530387820307B -:1051300078253038783A3078253038780A00476F4B -:105140006F64206669726D776172650A0000000005 -:105150006F72672E6172647570696C6F742E486F20 -:105160006C7962726F4750530000000053544D3306 -:1051700032463F3F3F000000000000006C51000835 -:105180003F00000013040000A85100083F00000089 -:1051900019040000B25100083F0000002104000083 -:1051A000BC5100083F00000053544D3332463430A8 -:1051B000780053544D3332463432780053544D33D3 -:1051C0003246343436585800000100000001FF0018 -:1051D0000064004000680040800000000080000083 -:1051E000000080004261642043414E49666163656E -:1051F00020696E6465782E00000000000000000049 -:105200003525000841240008E51C00080D1D000894 -:10521000611E0008E91C0008FD1C0008ED1C0008C8 -:10522000F11C0008F91C0008F51C0008F91D000815 -:10523000011D0008009600000000000000000000B2 -:10524000000000000000000000000000CD3E00084B -:10525000B93E0008F53E0008E13E0008ED3E0008BA -:10526000D93E0008C53E0008B13E0008013F0008D5 -:105270006D61696E0000000090520008E85A00203D -:10528000605C0020010000000941000800000000EF -:1052900069646C65000000000040000000400000F0 -:1052A000004000000040000000000100000002007B -:1052B0000000020000000200A001812A000000009E -:1052C000AAA9AAAA50000100EFFF00000077000081 -:1052D000009009001000004A000000009AAAAAAA43 -:1052E00000000000FBFF000000000000000099002B -:1052F0000000000000000000AAAAAAAA0000000006 -:10530000FFFF00000000000000000000000000009F -:1053100000000000AAAAAAAA00000000FFFF0000E7 -:10532000000000000000000000000000000000007D -:10533000AAAAAAAA00000000FFFF000000000000C7 -:10534000000000000000000000000000AAAAAAAAB5 -:1053500000000000FFFF000000000000000000004F -:105360000000000000000000AAAAAAAA0000000095 -:10537000FFFF00000000000000000000000000002F -:10538000000000000A000000000000000300000010 -:105390000000000000000000B0AEFF7F0100000030 -:1053A0000B0400000000000000000700FE2A0100BE -:1053B000D2040000FF0000001C23002000000000B9 -:1053C00000000000000000000000000000000000DD -:1053D00000000000000000000000000000000000CD -:1053E00000000000000000000000000000000000BD -:1053F00000000000000000000000000000000000AD -:10540000000000000000000000000000000000009C -:0C54100000000000000000000000000090 +:1000000000070020F50400080D2C00088D2B0008C7 +:10001000E52B00088D2B0008B92B0008F704000819 +:10002000F7040008F7040008F7040008C53A0008C0 +:10003000F7040008F7040008F7040008F7040008B4 +:10004000F7040008F7040008F7040008F7040008A4 +:10005000F7040008F7040008A94D0008D54D000872 +:10006000014E00082D4E0008594E0008F704000804 +:10007000F7040008F7040008F7040008F704000874 +:10008000F7040008F7040008F7040008A527000893 +:10009000B5270008C9270008F7040008854E0008A6 +:1000A000F7040008F7040008F7040008F704000844 +:1000B000F94B0008F7040008F7040008F7040008EB +:1000C000F7040008F7040008F7040008F704000824 +:1000D000F7040008F7040008A93B0008F70400082B +:1000E000ED4E0008F7040008F7040008F7040008C4 +:1000F000F7040008F7040008F7040008F7040008F4 +:10010000F7040008F7040008F7040008F7040008E3 +:10011000F7040008F7040008F7040008F7040008D3 +:10012000F7040008F7040008F7040008F7040008C3 +:10013000F7040008F7040008F7040008DD270008AA +:10014000ED27000801280008F7040008F70400085C +:10015000F7040008F7040008F7040008F704000893 +:10016000F7040008F7040008F7040008F704000883 +:10017000F7040008F7040008F7040008F704000873 +:10018000F7040008F7040008F7040008F704000863 +:10019000F7040008F7040008F7040008F704000853 +:1001A000F7040008F7040008F7040008F704000843 +:1001B000F7040008F7040008F7040008F704000833 +:1001C000F7040008F7040008F7040008F704000823 +:1001D000F7040008F7040008F7040008F704000813 +:1001E00009190008000000000000000000000000E5 +:1001F00053B94AB9002908BF00281CBF4FF0FF318E +:100200004FF0FF3000F074B9ADF1080C6DE904CE89 +:1002100000F006F8DDF804E0DDE9022304B07047E1 +:100220002DE9F047089D04468E46002B4DD18A42A9 +:10023000944669D9B2FA82F252B101FA02F3C2F1DC +:10024000200120FA01F10CFA02FC41EA030E94406D +:100250004FEA1C48210CBEFBF8F61FFA8CF708FB8E +:1002600016E341EA034306FB07F199420AD91CEB66 +:10027000030306F1FF3080F01F81994240F21C8198 +:10028000023E63445B1AA4B2B3FBF8F008FB1033E0 +:1002900044EA034400FB07F7A7420AD91CEB040415 +:1002A00000F1FF3380F00A81A74240F207816444E5 +:1002B000023840EA0640E41B00261DB1D44000236A +:1002C000C5E900433146BDE8F0878B4209D9002DCE +:1002D00000F0EF800026C5E9000130463146BDE858 +:1002E000F087B3FA83F6002E4AD18B4202D38242C2 +:1002F00000F2F980841A61EB030301209E46002D71 +:10030000E0D0C5E9004EDDE702B9FFDEB2FA82F2C5 +:10031000002A40F09280A1EB0C014FEA1C471FFA23 +:100320008CFE0126200CB1FBF7F307FB131140EA0A +:1003300001410EFB03F0884208D91CEB010103F1D7 +:10034000FF3802D2884200F2CB804346091AA4B299 +:10035000B1FBF7F007FB101144EA01440EFB00FE6D +:10036000A64508D91CEB040400F1FF3102D2A645D2 +:1003700000F2BB800846A4EB0E0440EA03409CE771 +:10038000C6F12007B34022FA07FC4CEA030C20FA1E +:1003900007F401FA06F31C43F9404FEA1C4900FA3E +:1003A00006F3B1FBF9F8200C1FFA8CFE09FB1811BB +:1003B00040EA014108FB0EF0884202FA06F20BD92E +:1003C0001CEB010108F1FF3A80F08880884240F27E +:1003D0008580A8F102086144091AA4B2B1FBF9F0C2 +:1003E00009FB101144EA014100FB0EFE8E4508D9BD +:1003F0001CEB010100F1FF346CD28E456AD9023842 +:10040000614440EA0840A0FB0294A1EB0E01A14226 +:10041000C846A64656D353D05DB1B3EB080261EB94 +:100420000E0101FA07F722FA06F3F1401F43C5E96E +:10043000007100263146BDE8F087C2F12003D840A4 +:100440000CFA02FC21FA03F3914001434FEA1C47E6 +:100450001FFA8CFEB3FBF7F007FB10360B0C43EAD8 +:10046000064300FB0EF69E4204FA02F408D91CEB88 +:10047000030300F1FF382FD29E422DD90238634486 +:100480009B1B89B2B3FBF7F607FB163341EA034126 +:1004900006FB0EF38B4208D91CEB010106F1FF3875 +:1004A00016D28B4214D9023E6144C91A46EA00466C +:1004B00038E72E46284605E70646E3E61846F8E6FE +:1004C0004B45A9D2B9EB020864EB0C0E0138A3E747 +:1004D0004646EAE7204694E74046D1E7D0467BE728 +:1004E000023B614432E7304609E76444023842E7A0 +:1004F000704700BF02E000F000F8FEE772B63A482D +:1005000080F30888394880F3098839484EF6085145 +:10051000CEF20001086040F20000CCF200004EF67E +:100520003471CEF200010860BFF34F8FBFF36F8FBD +:1005300040F20000C0F2F0004EF68851CEF2000109 +:100540000860BFF34F8FBFF36F8F4FF00000E1EEF5 +:10055000100A4EF63C71CEF200010860062080F3CE +:100560001488BFF36F8F04F089FA04F065FA04F081 +:10057000AFFA4FF055301F491B4A91423CBF41F83A +:10058000040BFAE71C49194A91423CBF41F8040B9D +:10059000FAE71A491A4A1B4B9A423EBF51F8040B1C +:1005A00042F8040BF8E700201749184A91423CBF73 +:1005B00041F8040BFAE704F043FA04F0D7FA144CBC +:1005C000144DAC4203DA54F8041B8847F9E700F0F5 +:1005D00041F8114C114DAC4203DA54F8041B884722 +:1005E000F9E704F02BBA00000007002000230020E8 +:1005F000000000080001002000070020F05500085E +:10060000002300208423002088230020C45C0020D5 +:10061000E0010008E4010008E4010008E40100082A +:100620002DE9F04F2DED108AC1F80CD0C3689D461E +:10063000BDEC108ABDE8F08F002383F311882846B3 +:10064000A047002003F0CCFEFEE703F045FE00DFEC +:10065000FEE70000F8B504F089F9074604F0D8F980 +:100660000546A0BB1F4B9F4231D001339F4231D082 +:100670001D4B27F0FF029A422FD1F8B200F032FD55 +:100680002E4642F2107400F037FF08B100242646CF +:1006900000F02EFD08B90646044635B1134B9F42C3 +:1006A00003D004F0ADF900242646002004F068F9D8 +:1006B0000EB100F063F801F0EDFA00F07BFF01F0FD +:1006C0008DF9204600F0A4F800F058F8F9E72E461E +:1006D0000024D8E704460126D5E7064640F6C414B0 +:1006E000D1E700BF010007B0000008B0263A09B00A +:1006F00008B501F045F9A0F120035842584108BD62 +:1007000007B541F21203022101A8ADF8043001F04F +:1007100055F903B05DF804FB10B5202383F311886D +:100720001248C3680BB103F0D3FE114A0F480023EF +:100730004FF47A7103F090FE002383F311880D4C7F +:10074000236813B12368013B2360636813B16368B6 +:10075000013B6360084B1B7833B9636823B90220FF +:1007600001F026FA3223636010BD00BF8823002009 +:1007700019070008A42400209C2300201E4B1F4AB8 +:1007800010B51C461968013134D004339342F9D1B5 +:1007900062681B4B9A422DD91A4B9B6803F1006388 +:1007A00003F580339A4225D204F0FEF804F010F9E4 +:1007B000002001F02DF9144B0220187001F0EEF921 +:1007C000124B1A6C00221A64196E1A66196E596C53 +:1007D0005A64596E5A665B6E72B64FF0E023202160 +:1007E000C3F8084DD4E9003281F311889D4683F3A4 +:1007F0000888104710BD00BF000001082000010854 +:10080000FFFF0008002300209C2300200038024046 +:100810002DE9F04F93B0AC4B00902022FF210AA8A5 +:100820009D6801F0E1F9A94A1378A3B9A84801210C +:10083000C3601170202383F31188C3680BB103F0E8 +:1008400047FEA44AA24800234FF47A7103F004FE45 +:10085000002383F31188009B9F4A03B113609F49D3 +:10086000009C00230B70536098469B461E469A4698 +:10087000012001F093F924B1974B1B68002B00F085 +:100880001C82002001F07CF80390039B002B01DA0E +:1008900000F0DEFE039B002BEDDB012001F074F97C +:1008A000039B213B162BE3D801A252F823F000BF93 +:1008B0000D09000835090008C90900087108000879 +:1008C00071080008710800085D0A00082F0C000874 +:1008D000490B0008AB0B0008D30B0008F90B00080C +:1008E000710800080B0C0008710800087D0C000856 +:1008F000AD09000871080008C10C000819090008BA +:10090000AD09000871080008AB0B00080220FFF7D2 +:10091000EFFE002840F0FB81009B0221B8F1000FA0 +:1009200008BF1C4605A841F21233ADF8143001F09F +:1009300045F89DE74FF47A7001F022F8071EEBDBD3 +:100940000220FFF7D5FE0028E6D0013F052F00F278 +:10095000E081DFE807F0030A0D1013360523059345 +:10096000042105A801F02AF817E057480421F9E707 +:100970005B480421F6E75B480421F3E74FF01C09CC +:10098000484601F047F809F104090590042105A83B +:1009900001F014F8B9F12C0FF2D1012000FA07F799 +:1009A00047EA0B0B5FFA8BFB4FF0000A01F068F986 +:1009B00026B10BF00B030B2B08BF0024FFF7A0FEA2 +:1009C00056E749480421CDE7002EA5D00BF00B03D4 +:1009D0000B2BA1D10220FFF78BFE074600289BD0EE +:1009E00001203E4E01F014F80220307001F0D6F8DC +:1009F0004FF000085FFA88F9484601F019F80446FC +:100A000090B1484601F024F808F101080028F1D11E +:100A1000B846044641F21213022105A8ADF814307D +:100A20003E4600F0CBFF23E701230220337001F0A4 +:100A3000ABF82546244B9B68AB4207D9284600F00B +:100A4000E9FF013040F068810435F3E7234B0025CE +:100A50001D70214BB8465D603E46A7E7002E3FF46F +:100A60005BAF0BF00B030B2B7FF456AF1B4B02203D +:100A7000187001F093F8322000F082FFB0F1000905 +:100A8000FFF64AAF19F003077FF446AF0E4A9268AB +:100A900009EB050393423FF63FAFB9F5807F3FF77F +:100AA0003BAF124B0193B94522DD4FF47A7000F051 +:100AB00067FF0390039A002AFFF62EAF019B039A6B +:100AC00003F8012B0137EDE700230020A0240020CC +:100AD0008823002019070008A42400209C2300205C +:100AE00004230020082300200C230020A023002042 +:100AF000C820FFF7FDFD074600283FF40DAF1F2D6E +:100B000011D8C5F120024A450AAB25F0030028BFE1 +:100B10004A4683490192184401F054F8019A8048EA +:100B2000FF2101F061F84FEAA9037D490193C9F360 +:100B30008702284601F060F8064600283FF46AAFB5 +:100B4000019B05EB830531E70220FFF7D1FD00286B +:100B50003FF4E2AE00F0A6FF00283FF4DDAE002730 +:100B6000B946704B9B68BB4218D91F2F11D80A9BFE +:100B700001330ED027F0030312AA134453F8203C8C +:100B800005934846042205A902F04EF80437814631 +:100B9000E7E7384600F03EFF0590F2E7CDF8149005 +:100BA000042105A800F00AFF00E70023642104A83F +:100BB000049300F0F9FE00287FF4AEAE0220FFF7A8 +:100BC00097FD00283FF4A8AE049800F053FF05906D +:100BD000E6E70023642104A8049300F0E5FE002862 +:100BE0007FF49AAE0220FFF783FD00283FF494AE15 +:100BF000049800F04FFFEAE70220FFF779FD002894 +:100C00003FF48AAE00F05EFFE1E70220FFF770FDDF +:100C100000283FF481AE05A9142000F059FF0421FB +:100C20000746049004A800F0C9FE3946B9E732200F +:100C300000F0A6FE071EFFF66FAEBB077FF46CAE9A +:100C4000384A926807EB0A0393423FF665AE0220EA +:100C5000FFF74EFD00283FF45FAE27F0030757442F +:100C6000BA453FF4A3AE504600F0D4FE04210590EF +:100C700005A800F0A3FE0AF1040AF1E74FF47A7028 +:100C8000FFF736FD00283FF447AE00F00BFF0028C9 +:100C900044D00A9B01330BD008220AA9002000F09F +:100CA000ABFF00283AD02022FF210AA800F09CFFC9 +:100CB000FFF726FD1C4803F099FB13B0BDE8F08F49 +:100CC000002E3FF429AE0BF00B030B2B7FF424AE68 +:100CD0000023642105A8059300F066FE074600285E +:100CE0007FF41AAE0220FFF703FD814600283FF48F +:100CF00013AEFFF705FD41F2883003F077FB05984E +:100D000000F0D4FF4E4600F0BBFF3C46B0E506467F +:100D10004CE64FF0000AFFE5B8467BE6374679E639 +:100D2000A023002000230020A0860100094A1368A8 +:100D300049F2690099B21B0C00FB01331360064BAA +:100D4000186844F2506182B2000C01FB0200186086 +:100D500080B27047182300201423002010B5002112 +:100D60001022044600F040FF034B03CB206061607B +:100D70001868A06010BD00BF107AFF1F2DE9F04376 +:100D8000224DBBB001F04AFFAB6840F2ED22C31A1E +:100D9000934232D906AFA8602B462822002138465C +:100DA00002F04CFC05F10E0000F016FF0026044690 +:100DB0005FFA80F905F10E08F3B2F100994501F1EF +:100DC000280107D908EB06030822384602F036FC52 +:100DD0000136F1E708230122CDE9023205340C4B3C +:100DE0000193A4B230230093CDE9047405A3D3E9A1 +:100DF0000023297B074802F039FA3BB0BDE8F083B5 +:100E0000AFF3008078F6339F93CACD8D90560020C3 +:100E10009D560020C434002070B50D4614461E4671 +:100E200002F0BAF950B9022E10D1012C0ED112A342 +:100E3000D3E90023C5E90023012007E0282C10D0C6 +:100E400005D8012C09D0052C0FD0002070BD302C06 +:100E5000FBD10BA3D3E90023ECE70BA3D3E90023D9 +:100E6000E8E70BA3D3E90023E4E70BA3D3E90023CE +:100E7000E0E700BFAFF30080401DA12026812A0BD0 +:100E800078F6339F93CACD8D9E6AC421818A46EE3F +:100E900026417272DF25D7B7F017304A39059E56C2 +:100EA00013B504462346084620220021019002F093 +:100EB000C5FB22790198032A234628BF032203F8A1 +:100EC000042F2021022202F0B9FB62790198072A3F +:100ED000234628BF072203F8052F2221032202F010 +:100EE000ADFBA2790198072A234628BF072203F801 +:100EF000062F2521032202F0A1FB019804F108032B +:100F00001022282102F09AFB382002B010BD000008 +:100F10002DE9F04FADF5017D21AD0EAE40F2751219 +:100F200080460F4622A80021296000F05DFE48227D +:100F30000021304600F058FE01F070FE564B4FF491 +:100F40007A72B0FBF2F0186093E80700012386E89C +:100F500007000DF15A003382FFF700FF40F604331B +:100F6000338407AB18464D4904F0AAF918223064BF +:100F70002946304686F83C20FFF792FF12AB044624 +:100F800001460822284602F059FB0822A1180DF15B +:100F90004903284602F052FB0DF14A03082204F1EE +:100FA0001001284602F04AFB13AB202204F118017D +:100FB000284602F043FB14AB402204F138012846D6 +:100FC00002F03CFB16AB082204F17801284602F03F +:100FD00035FB0DF15903082204F18001284602F087 +:100FE0002DFB04F1880A0DF15A0904F5847B4B4668 +:100FF0005146082228460AF1080A02F01FFBD34591 +:1010000009F10109F3D11BAB08225946284602F029 +:1010100015FB04F588744FF0000996F834304B4501 +:101020000AD9B36B21464B440822284602F006FB3E +:10103000083409F10109F0E74FF0000996F83C3057 +:101040004B4504EBC90108D9336C08224B442846B0 +:1010500002F0F4FA09F10109F0E700230393BB7EE3 +:101060000293073107F119030193C1F3CF01012363 +:10107000CDE904510093F97E05A3D3E9002340464E +:1010800002F0F4F80DF5017DBDE8F08FAFF30080BC +:101090009E6AC421818A46EEAC240020F0520008EA +:1010A000F8B50E4C0E4F0226A4F5805343F8487C49 +:1010B000237E3BB965692DB1284601F02DFC2846F9 +:1010C00003F090FF204601F027FCA4F58654012E82 +:1010D000A4F1100400D1F8BD0126E5E70856002070 +:1010E0003C540008014B1870704700BFB824002022 +:1010F000F0B5334B1C7B85B034B1324B0E221A81D4 +:101100000024204605B0F0BD2F4A1068516802AB9C +:1011100003C308232D492E480DEB030203F0B4FF4F +:10112000054630B9274B2B480A221A8101F072FB81 +:10113000E6E70169B1F5E02F06D9224B26480B22DC +:101140001A8101F067FBDCE7438B40F20B429342CC +:1011500007D01C490C2008811946204801F05AFB91 +:10116000CFE71F4A024402F11003994204D2154B03 +:101170001C4810221A81E4E710398E1A20461449BF +:1011800001F052FD3246074605F11801204601F0F4 +:101190004BFDAB689F4202D1EB6898420AD0094BE5 +:1011A0000D221A810090D5E902123B460E4801F04B +:1011B00031FBA5E70D4801F02DFB0124A1E700BF9D +:1011C00090560020AC2400209D530008DCFF060050 +:1011D000000001080C530008185300082A530008A7 +:1011E0000800FFF748530008655300088E530008B5 +:1011F0002DE9F04FADB006AF80460C4601F0CCFFB4 +:10120000054600285AD1237E022B1BD1E38A012BED +:1012100018D101F003FD0646FFF788FD03464FF4A1 +:10122000C870DFF8D092B3FBF0F206F5167602FB39 +:10123000103316FA83F3C9F80030E37E33B9A84BB4 +:1012400000221A709C37BD46BDE8F08FA38AEEB22B +:10125000013BB34205F101050BD93B1D1E44E900DA +:1012600000960023082201F0F801204602F0AAF8B7 +:10127000ECE707F11400FFF771FD324607F11401A6 +:10128000381D03F0F1FE0028D9D10F2E08D8944B59 +:101290001E70D9F80030A3F51673C9F80030D1E7F5 +:1012A000FB1CF8700146009307220346204602F01B +:1012B00089F8F978404601F067FFC3E7E38A282BF5 +:1012C00026D010D8012B1ED0052BBBD1BFF34F8FDA +:1012D0008449854BCA6802F4E0621343CB60BFF3D4 +:1012E0004F8F00BFFDE7302BACD1637E7F4D0133C4 +:1012F0006A7BDBB29342E94603D1E27E2B7B9A42C2 +:1013000065D0CD469EE721464046FFF701FE99E7AE +:10131000A38A013B9BB2C92B94D8744D2E7B26BB6C +:1013200005F10C030093082233463146204602F0B3 +:1013300049F8731CF2B2D9001E46A38A013B9A42B7 +:1013400005DA0E322A44009200230822EEE7002339 +:101350000022C5E900230023AB6085F8D730C5F82B +:10136000D8302B7B0BB9E37E2B73002507F11409D2 +:101370003B1D082229464846C7E90155FD6002F099 +:101380005DF93B7A05F1010AAB424FEACA0608D97A +:10139000FB6808222B443146484602F04FF9554677 +:1013A000EFE7C6F3CF06E17ECDE904960023039371 +:1013B000A37E0293193428230093019446A3D3E912 +:1013C0000023404601F052FFFFF7D8FC3AE74FF008 +:1013D000000807F11403A7F8148010220093414677 +:1013E0000123204601F0EEFFA68A023EB6B2F31CAE +:1013F0009B109B000733DB08A9EBC3039D460DF14F +:10140000180A1FFA88F34FEAC801B34201F110012C +:101410000AD20AEB0803009308220023204601F0B9 +:10142000D1FF08F10108ECE795F8D70000F000FBC8 +:10143000D5F8D83004461BB995F8D70000F008FB62 +:10144000D5F8D83033449C4204D295F8D700013007 +:1014500000F0FEFA4FEA960B4FF000081FFA88F1F1 +:101460008B45D5E9003209D90AEB880103EB8800E6 +:10147000012200F0C1FB08F10108EFE7F31842F187 +:101480000002C5E90032D5F8D83095F8D70006EB50 +:101490000308C5F8D88000F0CBFA804509D395F849 +:1014A000D730D5F8D8000133001B85F8D730C5F800 +:1014B000D800FF2E08D800232B7300F0F3FAFFF7B3 +:1014C00017FE08B1FFF75AF92B68094A9B0A013346 +:1014D00013810023AB6014E726417272DF25D7B772 +:1014E000BD34002000ED00E00400FA059056002015 +:1014F000AC240020C034002030B54FF00054244B01 +:1015000022689A4285B007D003F08CFA0446A8B945 +:101510000024204605B030BD1E4B627D1A701E4867 +:10152000237D03731D49C9220E3000F04BFB20467A +:10153000E022002100F058FB0124EAE7184A194D87 +:10154000136C43F000731364AA6D174B9A42DFD1FA +:101550002B6E013B7E2BDBD8144A07CA01AB83E814 +:1015600007001846032101F075FB6B6D83424FF0B5 +:101570000003CDD12A6D8A4201BFAB65054B2A6EAF +:101580001A7003BF0A4BEA6D1A601C46C1E700BF20 +:101590009AAD44C5B82400209056002016000020C3 +:1015A00000380240006600405041A0B0586600403C +:1015B0001023002037B51C4C1C4D21681C48022309 +:1015C00001226B7100F0DAFF1A48216850F8D03F11 +:1015D00001225B68984700230193174B174900933A +:1015E0001748184B4FF4805201F0A8FD164B19789C +:1015F00011B1134801F0C8FD01F010FB0446FFF7DC +:1016000095FB4FF4C873B0FBF3F202FB130304F530 +:10161000167010FA83F00D4B186003F0F9F908B159 +:101620000F232B8103B030BD10230020AC240020F9 +:10163000F0340020F0440020190E0008BC240020E3 +:10164000C4340020F1110008B8240020C034002068 +:101650002DE9F04F2DED028BDFF8A4B293B0DFF847 +:101660008092DFF8A0A2484601F064FE03460028FD +:101670003ED00024CDE90F440E94ADF84440027BE7 +:101680008DF8442099684068934D0FAA03C21B68E7 +:1016900043F000430E932746A0462B681B691E4665 +:1016A00001F0BEFA10EB0A0241F100032846CDF822 +:1016B00000800EA9B04704F2344440F668030028C5 +:1016C000C8BF47F0010705F586559C4205F1100596 +:1016D000E3D137B1484601F031FE804B83F80080FA +:1016E000C1E77E4A1378072B00F2E58001331370BF +:1016F0000BAF9FED738B00230A93ADF834300B933F +:101700007B600025744CDFF8D8912E4601238DF8BC +:101710001C3023688DED008B4FF0000AD3F8088051 +:101720008DF81DA053460DF11D0207A92046C047A4 +:101730009DF81C80B8F1000F24D0DBF8143083F43E +:101740000043CBF81430102251460EA800F04CFA9A +:10175000236808AA5E690AA90DF11E032046B04756 +:1017600097E803000FAB83E803009DF834308DF851 +:1017700044300A9B0E930EA9DDE90823484601F088 +:10178000A5FF464605F2344540F6680304F5865445 +:101790009D4204F11004B9D1002EB2D1504801F09D +:1017A000FBFC002840D14F4D01F038FA2B689842DD +:1017B0003AD301F033FA0446FFF7B8FA4FF4C8738E +:1017C00004F51674B0FBF3F202FB130314FA83F36F +:1017D0002B60454D8DF828602E7816B901238DF8C1 +:1017E0002830C6F11004E4B20EA8FFF7B7FA062CB1 +:1017F00028BF06240EAB224699190DF1290000F0EE +:10180000E1F90AAB0393182302930134374B019398 +:10181000E4B201230093324804942BA3D3E90023BC +:1018200001F0BCFC00232B7001F0F8F9304A314C78 +:101830001368C31AB3F57A7F30D3106001F0F0F962 +:1018400002460B46264801F083FD254801F0A4FC22 +:1018500020B3237B284D002B14BF032302236B717D +:1018600001F0DCF90EAE4FF47A733146B0FBF3F0C1 +:1018700028602846FFF714FB1823073002931F4BFC +:101880000193C0F3CF0040F25513CDE903600093FC +:1018900013480FA3D3E9002301F080FC237B2BB175 +:1018A000FFF76CFA237B002B7FF4D9AE13B0BDECAD +:1018B000028BBDE8F08F0A4801F040FD18E700BF39 +:1018C0000000000000000000401DA12026812A0B1E +:1018D000F1C6A7C1D068080FF0340020755700206A +:1018E000C4340020C0340020BD340020BC340020AB +:1018F0007057002090560020AC2400207457002020 +:101900000004024040420F0008B5064800F0ACFB5E +:10191000054800F0A9FBBDE80840044A044900203E +:1019200003F05ABBF0340020C0450020C857002007 +:10193000A110000870B50F4B1B780133DBB2012BEF +:101940000C4611D80C4D29684FF47A730E6AA2FB2D +:101950000332014622462846B047844204D1074B51 +:1019600000221A70012070BD4FF4FA7002F03EFDA3 +:101970000020F8E71C230020CC570020B857002097 +:1019800007B50023024601210DF107008DF807304D +:10199000FFF7D0FF20B19DF8070003B05DF804FB0E +:1019A0004FF0FF30F9E700000A4608B50421FFF7C1 +:1019B000C1FF80F00100C0B2404208BD30B4054C08 +:1019C0002368DD69044B0A46AC460146204630BC1C +:1019D000604700BFCC570020A086010070B502F020 +:1019E0005FFE094E094D3080002428683388834209 +:1019F00008D902F04FFE2B6804440133B4F5803F50 +:101A00002B60F2D370BD00BFBA570020785700207A +:101A100002F00ABF00F1006000F5803000687047F6 +:101A200000F10060920000F5803002F087BE0000F7 +:101A3000054B1A68054B1B889B1A834202D9104438 +:101A400002F028BE0020704778570020BA570020C7 +:101A500038B5074D04462868204402F023FE28B913 +:101A600028682044BDE8384002F034BE38BD00BFCD +:101A70007857002010F003030AD1B0F5047F05D297 +:101A800000F10050A0F51040D0F80038184670471B +:101A90000023FBE700F10050A0F51040D0F8100A39 +:101AA00070470000064991F8243033B10023086ADA +:101AB00081F824300822FFF7B3BF0120704700BF30 +:101AC0007C570020014B1868704700BF002004E0DD +:101AD00070B52A4B1B68C3F30B0204461B0C62B1A2 +:101AE00040F21340824230D040F2194082422ED060 +:101AF00040F2214082422CD10322214D0C2000FBD8 +:101B00000252556842F20102934224D0B3F5805F3D +:101B100023D041F20102934221D041F203029342C9 +:101B20001FD041F20702934214BF3F233123013CEF +:101B30000C44013D0A46A24215D215F9016F501C12 +:101B40009EB100F8016C0246F5E70122D5E70222BA +:101B5000D3E70C4DD6E73323E9E74123E7E75A23E0 +:101B6000E5E75923E3E7104605E02C25844215708C +:101B700001D9901C5370401A70BD00BF002004E0D2 +:101B8000D4530008A8530008022802BF024B4FF0AC +:101B900000429A61704700BF00040240022802BF61 +:101BA000024B4FF400429A61704700BF00040240AC +:101BB000022801BF024A536983F40043536170470E +:101BC0000004024010B50023934203D0CC5CC454FF +:101BD0000133F9E710BD000003460246D01A12F99E +:101BE000011B0029FAD1704702440346934202D0F8 +:101BF00003F8011BFAE770472DE9F8431F4D14461F +:101C000095F824200746884652BBDFF870909CB3B5 +:101C100095F824302BB92022FF2148462F62FFF788 +:101C2000E3FF95F82400C0F10802A24228BF224633 +:101C3000D6B24146920005EB8000FFF7C3FF95F84E +:101C40002430A41B1E44F6B2082E17449044E4B27C +:101C500085F82460DBD1FFF725FF0028D7D108E005 +:101C60002B6A03EB82038342CFD0FFF71BFF0028D0 +:101C7000CBD10020BDE8F8830120FBE77C57002092 +:101C8000024B1A78024B1A70704700BFB8570020F9 +:101C90001C230020034904484FF461430B6002F009 +:101CA0003FBA00BFA4570020CC570020074B10B507 +:101CB0000021044614221846FFF796FF04600146EF +:101CC000BDE81040024802F02BBA00BFA457002024 +:101CD000CC570020202383F3118862B670470000A0 +:101CE000002383F3118862B67047000010B40268C5 +:101CF00054681A4623465DF8044B18470120704784 +:101D000000207047002070477047000070470000B7 +:101D1000002070470E20704700F5805090F8C800F2 +:101D2000C0F340007047000000F5805090F9C900F2 +:101D3000704700002DE9F0410C68BDF8187014F0F0 +:101D400000541E466FD10B7B082B6CD8FFF7C2FFE7 +:101D50004569AB685B010CD4AB681B0108D4AC6867 +:101D600014F080545DD1FFF7BBFF2046BDE8F08141 +:101D700001240B6804F1180C002BB8BFDB004FEAFC +:101D80000C1CB4BF43F004035B0545F80C300B6832 +:101D90000FFA84FC13F0804F18BF05EB0C1E05EB07 +:101DA0000C1C1EBFDEF8803143F00203CEF88031F8 +:101DB0000B7BCCF8843105EB04158B68C5F88C31AE +:101DC0004B68C5F88831DCF8803143F00103CCF86A +:101DD000803100EB441541F268031D4403EB4413CA +:101DE0000344C5E9002608330D4601F10C0C55F8F3 +:101DF00004EB43F804EB6545F9D184342D881D804C +:101E000000EB441407F00303257925F00B052B4361 +:101E10002371FFF765FF06973346BDE8F04100F0F8 +:101E20001BBD0224A5E74FF0FF309FE713B500F577 +:101E300080540191E06D00F0A5FD1F280AD9019999 +:101E4000E06D202200F014FEA0F12003584258411A +:101E500002B010BD0020FBE708B500F58050FFF789 +:101E600039FFC06D00F062FDBDE80840FFF738BFE4 +:101E700000220260828142608260704710B50022B9 +:101E80000023C0E900230023044603810C30FFF740 +:101E9000EFFF204610BD0000F0B5054600F580506C +:101EA0000C4690F8C83013F0040FC3F3800108BF4C +:101EB000114661F3820304F1840680F8C83005EB13 +:101EC000461389B01B79D8072ED57AB319072DD4BC +:101ED0006846FFF7D3FF05EB441303F5835303F183 +:101EE000180703AA103318685968144603C4083346 +:101EF000BB422246F7D1186820609B88A380DDE9A9 +:101F00000E23CDE900230123ADF808302B68694684 +:101F10001B6C2846984705EB46152B791A075CBFC2 +:101F200043F008032B7101E0002AF4D109B0F0BDA1 +:101F30002DE9F047074688B007F5805468469A4671 +:101F40008846FFF7C7FE9146FFF798FFE06D00F067 +:101F5000FFFC1F2829D9E06D2022694600F00AFE07 +:101F6000202822D103AD444605AB2E4603CE9E4227 +:101F700020606160354604F10804F6D130682060C5 +:101F8000B388A380DDE90023C9E90023BDF8083048 +:101F9000AAF80030FFF7A4FE4A46534641463846A9 +:101FA00008B0BDE8F04700F045BCFFF799FE0020FF +:101FB00008B0BDE8F08700002DE9F84F0023C0E924 +:101FC0000133264B044640F8183B0F46FFF750FFFD +:101FD00004F12800FFF752FF04F1480804F5825588 +:101FE0004646083530462036FFF748FFAE42F9D165 +:101FF00004F580554FF480534FF00009C5E91339BB +:10200000C5F848800123EE6504F5875804F5845629 +:10201000C5F8549085F8583085F86030083608F1D6 +:1020200008084FF0000A4FF0000B46E908ABA6F194 +:102030001800FFF71DFF203646F8289C4645F4D1CE +:10204000012F85F8C97002D9054800F0E1FD054B64 +:1020500053F8273063612046BDE8F88F3C540008F0 +:10206000045400082054000810B5044B19780446A5 +:102070004A1C1A70FFF7A0FF204610BDC45700206D +:102080002DE9F047002950D0294B2A4FB7FBF1F535 +:1020900099428CBF0A231123581EB5FBF3FC03FBA6 +:1020A0001C53C4B22BB102280346F5D80020BDE86A +:1020B000F0870CF1FF36B6F5806FF7D2C4EBC40E93 +:1020C0000EF103034FEAE309C3F3C703A4EB0308CC +:1020D00009F1010A4FF47A755FFA88F009FB05559A +:1020E0005AFA88F8B5FBF8F5B5F5617FC1BF0EF176 +:1020F000FF33C3F3C703E01AC0B25C1C50FA84F488 +:102100000CFB04F4B7FBF4F4A142CFD1013BDBB2EA +:102110000F2BCBD80138C0B20728C7D800211071C7 +:1021200016809170D3700120C1E70846BFE700BF59 +:102130003F420F0040787D0170B505460E464FF4D2 +:102140007A746B695B6803F00103B34207D04FF404 +:102150007A7002F04BF9013CF3D1204670BD0120AA +:10216000FCE7000030B54269936913F0700F16D098 +:1021700000230B4C936103F1840200EB42121179AE +:102180004D0709D5890707D5416954F823508D605B +:10219000117941F0040111710133032BEBD130BDF2 +:1021A0002854000873B51D46436916469A68D2073D +:1021B000044609D59A6801219960C2F34002CDE92D +:1021C00000650021FFF768FE63699A68D1050BD5A9 +:1021D0009A684FF480719960C2F34022CDE900659E +:1021E00001212046FFF758FE63699A68D2030BD598 +:1021F0009A684FF480319960C2F34042CDE900659E +:1022000002212046FFF748FE204602B0BDE870409C +:10221000FFF7A8BF0C4B10B51C561B5C012B11D847 +:1022200000F0FEFC50EA0103024602D0421E61F1BA +:102230000001064B53F8240020B1BDE810400B46C6 +:10224000FFF7B0BF10BD00BF1C540008BC570020F2 +:10225000F8B50446466900296CD106F10C073868C8 +:1022600080076AD006EB01153868D5F8B00110F088 +:10227000040FD5F8B0011ABFC00840F00040400D6F +:10228000A061D5F8B0C11CF0020F1CBF40F0804027 +:10229000A061D5F8B40106EB011100F00F0084F83D +:1022A0002400D1F8B8012077D1F8B801000A60778E +:1022B000D1F8B801000CA077D1F8B801000EE07792 +:1022C000D1F8BC0184F82000D1F8BC01000A84F8E0 +:1022D0002100D1F8BC01000C84F82200D1F8BC1117 +:1022E000090E84F823103821396004F1340004F118 +:1022F000180104F1240551F8046B40F8046BA9425D +:10230000F9D109880180C4E90A23214600232386E4 +:1023100051F8283B20461B6C984704F58052204614 +:1023200092F8C83043F0040382F8C830BDE8F840A2 +:10233000FFF718BF06F1100791E7F8BD0D4B70B518 +:102340001D561B5C012B0C4612D800F069FC02469E +:102350000B4652EA030102D0013A63F10003064939 +:1023600051F8250020B12146BDE87040FFF770BF4D +:1023700070BD00BF1C540008BC570020F8B500F524 +:1023800083511E46FFF7A6FCDFF844C00831002445 +:1023900004F1840500EB45152B795F070ED4DB06AD +:1023A0000CD5D1E900739742B34107D243695CF879 +:1023B00024709F602B7943F004032B710134032CAC +:1023C00001F12001E4D1BDE8F840FFF789BC00BF6E +:1023D0002854000808B5FFF77DFCFFF7C3FEBDE8F1 +:1023E0000840FFF77DBC0000F8B5436905469868D2 +:1023F00000F0E050B0F1E05F0F461FD0E8B1FFF70A +:1024000069FC05F583541034002606F1840305EBBE +:1024100043131B791A0706D50136032E04F1200455 +:10242000F3D1012007E05B07F6D42146384600F0DF +:102430004DFA0028F0D1FFF753FCF8BD0120FCE76E +:1024400000F5805008B5FFF745FCC06D00F080FA3C +:10245000FFF746FC43090CBF0120002008BD000027 +:10246000F8B51D46002313700F4606461446FFF7C5 +:10247000E7FF80F00100387025B129463046FFF7AC +:10248000B3FF2070F8BD00002DE9B8410C46154699 +:102490001F46804600F0C4FB0B462178024609B96E +:1024A000287850B14046FFF769FFFFF793FF3B469E +:1024B0002A462146FFF7D4FF0120BDE8B88100007D +:1024C00038B500F58054FFF705FC2A4D94F8C93063 +:1024D000EB5CDBB1012B27D0FFF702FC94F8C8308E +:1024E000DB0746D4002944D0FFF7F4FB94F8C93049 +:1024F000EB5C33B3012B31D094F8C83043F00103C7 +:1025000084F8C830BDE83840FFF7EABB1A4B1A6CB4 +:1025100042F000721A641A6A42F000721A621A6A71 +:1025200022F000721A62D7E7134B1A6C42F08062F5 +:102530001A641A6A42F080621A621A6A22F0806291 +:10254000F0E70221132001F023FC0221142001F006 +:102550001FFC0221152001F01BFCCDE702213F20CA +:1025600001F016FC0221402001F012FC0221412062 +:10257000F1E738BD18540008003802402DE9F04753 +:1025800000F5805588B095F8C930022B044688467E +:10259000164600F20381824F57F823200AB947F804 +:1025A0002300D7F800A0C4F80C802674BAF1000FFD +:1025B00009D141F2D00002F017FD51468146FFF7E4 +:1025C000FBFCC7F8009095F8C930012B5DD00121C4 +:1025D0002046FFF775FFFFF77DFB6269136823F064 +:1025E000020313606269136843F0010313606369B7 +:1025F00000275F6101212046FFF772FBFFF79CFD7A +:10260000002800F08480E86D00F090F904F583590B +:10261000BA4609F10809202200216846FFF7E4FACA +:1026200002A8FFF725FCCDF818A06A4609EB0703BE +:102630000DF1180E9446BCE80300F445186059608B +:10264000624603F10803F5D1DCF80000186020377A +:102650009CF804201A71602FDDD195F8C8306FF313 +:102660008203002785F8C8306A4641462046ADF807 +:102670000070ADF802708DF80470FFF701FD63691A +:10268000C0B94FF400421A6011E0386803685B6B10 +:102690009847014600289AD13868FFF711FF38683B +:1026A000036832465B684146984700288FD108B0DE +:1026B000BDE8F08761221A609DF802309DF8032082 +:1026C0001B06120402F4702203F040731343BDF89A +:1026D0000020C2F3090213439DF804201205022EC4 +:1026E00002F4E0020CBF4FF0004100211343626985 +:1026F0000B43D361636913225A616269136823F043 +:102700000103136039462046FFF716FD08B96369D7 +:10271000B7E795F8C930002B39D16169D1F80022AB +:1027200042F00102C1F800226169D1F8002222F4CE +:102730007C5222F00E02C1F800226169D1F8002219 +:1027400042F46062C1F800226269C2F81432626920 +:10275000C2F8043262696FF07841C2F80C12626903 +:10276000C2F840326269C2F844326269C2F8B032DB +:102770006269C2F8B432636944F20102C3F81C22F0 +:102780006269D2F8003223F00103C2F8003295F8F2 +:10279000C83043F0020385F8C83088E7002086E798 +:1027A000BC57002008B50020FFF734FDBDE8084005 +:1027B00001F0BCB908B500210846FFF7BFFDBDE830 +:1027C000084001F0B3B9000008B501210020FFF76F +:1027D000B5FDBDE8084001F0A9B9000008B5012029 +:1027E000FFF718FDBDE8084001F0A0B908B50021C9 +:1027F0000120FFF7A3FDBDE8084001F097B90000F4 +:1028000008B501210846FFF799FDBDE8084001F031 +:102810008DB900000FB4002004B0704713B56C46AA +:1028200084E80600031D94E8030083E80500012006 +:1028300002B010BD73B58568019155B11B885B0767 +:1028400007D4D0E90036DB6B9847019AC1B2304615 +:10285000A847012002B070BDF0B5866889B0054672 +:102860000C465EB1BDF838305B070AD4D0E90037BA +:10287000DB6B98472246C1B23846B047012009B009 +:10288000F0BD00220023CDE900230023ADF808307D +:102890000A4603AB01F10806106851681C4603C4E0 +:1028A0000832B2422346F7D1106820609288A28095 +:1028B00000F0B8F90423ADF808302B68CDE9000129 +:1028C0001B6C694628469847D8E7000030B5036876 +:1028D0000968DD0FB5EBD17F23F0604421F0604241 +:1028E0004FEAD1700BD0002BB8BFA40C0029B8BFA1 +:1028F000920C944202D034BF0120002030BD94429B +:1029000005D1C1F38070C3F380738342F6D1944242 +:102910002CBF00200120F1E710B5037C044613B959 +:10292000006802F099FB204610BD00000023BFF3B1 +:102930005B8FC360BFF35B8FBFF35B8F8360BFF3BD +:102940005B8F7047BFF35B8F0068BFF35B8F70478F +:1029500070B505460C30FFF7F5FF05F10806044693 +:102960003046FFF7EFFFA04206D930466D68FFF70B +:10297000E9FF2544281A70BD3046FFF7E3FF201A0F +:10298000F9E7000070B50546406898B105F1080008 +:10299000FFF7D8FF05F10C0604463046FFF7D2FFDB +:1029A0008442304694BF6D680025FFF7CBFF013CA1 +:1029B0002C44201A70BD000038B50C460546FFF7C0 +:1029C000C7FFA04210D305F10800FFF7BBFF044486 +:1029D0006868B4FBF0F100FB1144BFF35B8F01208A +:1029E000AC60BFF35B8F38BD0020FCE72DE9F04100 +:1029F000144607460D46FFF7C5FF844228BF04462C +:102A0000D4B1B84658F80C6B4046FFF79BFF3044F2 +:102A1000286040467E68FFF795FF331A9C4203D832 +:102A20006C600120BDE8F0816B60A41B3B68AB606B +:102A30002044E8600220F5E72046F3E738B50C466D +:102A40000546FFF79FFFA04210D305F10C00FFF7EA +:102A500079FF04446868B4FBF0F100FB1144BFF354 +:102A60005B8F0120EC60BFF35B8F38BD0020FCE77B +:102A70002DE9FF41884669460746FFF7B7FF6C46D8 +:102A800006B204EBC6060025B44209D0626820688D +:102A900008EB0501FFF796F8636808341D44F3E777 +:102AA00029463846FFF7CAFF284604B0BDE8F08142 +:102AB000F8B505460C300F46FFF744FF05F1080650 +:102AC00004463046FFF73EFFA042304688BF6C68A0 +:102AD000FFF738FF201A386020B130462C68FFF726 +:102AE00031FF2044F8BD000073B5144606460D467C +:102AF000FFF72EFF844228BF04460190DCB101A9F4 +:102B00003046FFF7D5FF019B33B93268C5E9023380 +:102B1000C5E9002401200CE09C4238BF01942860E4 +:102B2000019868608442F5D93368AB60241AEC6080 +:102B3000022002B070BD2046FBE700002DE9FF41F6 +:102B40000F466946FFF7D0FF6C4600B204EBC005A4 +:102B50000026AC4209D0D4F8048054F8081BB819F8 +:102B60004246FFF72FF84644F3E7304604B0BDE88D +:102B7000F081000038B50546FFF7E0FF0446014646 +:102B80002846FFF719FF204638BD000000B59BB06E +:102B9000EFF3098168226846FFF714F8EFF3058325 +:102BA000044B9A6BDA6A9A6A9A6A9A6A9A6A9A6A79 +:102BB0009B6AFEE700ED00E000B59BB0EFF30981F2 +:102BC00068226846FEF7FEFFEFF30583044B9A6B1D +:102BD0009A6A9A6A9A6A9A6A9A6A9B6AFEE700BF38 +:102BE00000ED00E000B59BB0EFF309816822684674 +:102BF000FEF7E8FFEFF30583034B5A6B9A6A9A6A74 +:102C00009A6A9A6A9B6AFEE700ED00E0FEE7000020 +:102C10000FB408B5029801F083FBFEE701F044BE53 +:102C200001F01CBE01F01ABE30B5094D0A449142B4 +:102C30000DD011F8013B5840082340F30004013B3C +:102C40002C4013F0FF0384EA5000F6D1EFE730BDCB +:102C50002083B8EDF7B54FF0FF33DFF854C0DFF84D +:102C600054E000EB81011A4688421CD050F8044B16 +:102C7000019401AF042417F8015B82EA056208257C +:102C8000DB18164605F1FF355241002EBCBF83EA22 +:102C90000C0382EA0E0215F0FF05F1D1013C14F09D +:102CA000FF04E8D1E0E7D843D14303B0F0BD00BF53 +:102CB0009336EAA9EBE1F0422DE9F041C56915B977 +:102CC000C161BDE8F0814B6823F06047C3F38A46D9 +:102CD0004FEAD37EC3F3807816EA230638BF3E4618 +:102CE000AC462B465A68BEEBD27F22F060440AD035 +:102CF000002A18DAA40CB44217D19D420FD10D60FE +:102D0000DEE71346EEE7A74207D102F08044C2F3A4 +:102D1000807242450BD054B1EFE708D2EDE7CCF812 +:102D200000100B60CDE7B44201D0B442E5D81A6878 +:102D30009C46002AE5D11960C3E700002DE9F04761 +:102D4000089D01F007044FEAD508224405F0070565 +:102D500000EBD1004FF47F49944201D1BDE8F087E8 +:102D600004F0070705F0070A57453E4638BF5646A8 +:102D7000C6F10806111B8E4228BF0E46E10808EB7B +:102D8000D50E415C13F80EC0B94029FA06F721FAB6 +:102D90000AF1FFB28CEA010147FA0AF739408CEADE +:102DA000010C03F80EC034443544D5E780EA012015 +:102DB000082341F2210201B24000002980B203F150 +:102DC000FF33B8BF504013F0FF03F4D17047000049 +:102DD00038B50C468D18A54200D138BD14F8011B3A +:102DE000FFF7E4FFF7E7000002684AB113680360E9 +:102DF000C388018901339BB29942C38038BF0381E4 +:102E00001046704770B588B0202204460D466846CB +:102E10000021FEF7E9FE20460495FFF7E5FF024694 +:102E200058B16B46054608AE1C4603CCB442286038 +:102E30006960234605F10805F6D1104608B070BD5B +:102E4000082817D909280CD00A280CD00B280CD038 +:102E50000C280CD00D280CD00E2814BF4020302098 +:102E600070470C20704710207047142070471820BE +:102E70007047202070470000082817D90C280CD96B +:102E800010280CD914280CD918280CD920280CD9B2 +:102E900030288CBF0F200E207047092070470A2071 +:102EA00070470B2070470C2070470D2070470000C2 +:102EB00010B54B6823B9CA8A63F30902CA8210BDF0 +:102EC000C4681A681C60C360438A013B43824A603D +:102ED000EFE700002DE9F84F1D46CB8A0F46C3F3FC +:102EE00009010629814692460B4630D00020AAB23D +:102EF00007F119049EB2052E1FFA80F80FD89045ED +:102F000003F1010306D3FB8A0A4462F30903FB823F +:102F100001201AE01AF80060E6540130EAE7904513 +:102F2000F1D2A1F1060B1C237C68BBFBF3F203FB7F +:102F300012BB1FFA8BF6002C45D14846FFF754FF11 +:102F4000044638B978606FF00200BDE8F88F4FF0A2 +:102F50000008E6E7002606607860ADB24FF0000B8F +:102F6000454510D90AEB0803221D13F8011B9155A2 +:102F7000B1B208F101081B291FFA88F82BD045458A +:102F800006F10106F1D8FB8AC3F30902154465F383 +:102F90000903BCE7013292B21C462368002BF9D129 +:102FA000AB1F0B441C21B3FBF1F301339BB29A42DC +:102FB000D3D2BBF1000FD0D14846FFF715FF20B99F +:102FC000C4F800B0BFE70122E7E7C0F800B05E46F2 +:102FD00020600446C1E74545D5D94846FFF704FFC0 +:102FE00008B92060AFE7C0F800B0002620600446B2 +:102FF000B6E700002DE9F04F2DED028B83B0CDE94F +:103000000013BDF83C5007469146002A00F092801C +:103010002DB10E9B002B00F08D80072D32D807F1CB +:103020000C00FFF7E1FE044638B96FF002042046B9 +:1030300003B0BDEC028BBDE8F08F14220021FEF737 +:10304000D3FD0E992A4604F10800FEF7BBFD681C6B +:10305000C0B2FFF711FFFFF7F3FE207499F80030BC +:10306000013814FA80F003F01F0363F03F0303728A +:10307000009B43F00041616038462146FFF71CFE8B +:103080000124D4E700F10C034FF0000808EE103AD9 +:103090004FF0800A4646444618EE100AFFF7A4FE99 +:1030A00083460028C1D014220021FEF79DFDC6BB37 +:1030B000019BABF8083002200E9B00F10802991921 +:1030C0005BFA82F20130C0B2082801D0AE422AD3A6 +:1030D000FFF7D2FEFFF7B4FE99F80020009B411ED7 +:1030E00002F01F0242EA4812AE4208BF4FF0400A07 +:1030F0005BFA81F14AEA020A43F0004281F808A033 +:103100008BF81000CBF8042059463846FFF7D4FD61 +:103110000134AE4224B288F001084FF0000ABBD15E +:1031200085E70020C8E711F801CB02F801CB013692 +:10313000B6B2C7E76FF0010479E70000F8B51546AD +:103140000E462822002104461F46FEF74DFD069B31 +:103150006360B5F5001F079BA76034BF6A094FF68F +:10316000FF72236204F10C0097B200239A4205D843 +:103170000023036027826382A382F8BD06600133C7 +:1031800030462036F2E7000003781BB94BB2002B23 +:10319000C8BF017070470000007870472DE9F74FF5 +:1031A000DDF83C90BDF830500D9E9DF83840BDF8DC +:1031B0004070804692469B46B9F1000F01D1002F26 +:1031C00051D11F2C4FD898F80000B0B9072F47D81D +:1031D00035F0030347D13A4649464FF6FF70FFF7F3 +:1031E000F7FD20F001002D02400445EA0464400C84 +:1031F00044EA40244FF6FF7321E040EA0520072F00 +:1032000040EA0464F6D900254FF6FF73C5F12000AB +:10321000A5F120022AFA05F10BFA00F001432BFA7E +:1032200002F211431846C9B2FFF7C0FD0835402D20 +:103230000346EBD13A464946FFF7CAFD0346CDE9BE +:103240000097324621464046FFF7D4FE33780133DB +:10325000DBB21F2B88BF0023337003B0BDE8F08FB3 +:103260006FF00300F9E76FF00100F6E72DE9F04F8A +:1032700085B09246DDF848800F9D9DF840209DF86E +:103280004490BDF84C7006469B46B8F1000F01D142 +:10329000002F48D11F2A46D83378002B46D00C0285 +:1032A00044EA02649DF8381044EAC93444EA01440F +:1032B0001C43072F44F0800432D900234FF6FF72DD +:1032C000C3F1200CA3F120002AFA03F10BFA0CFC45 +:1032D00041EA0C012BFA00F00143C9B210460393F6 +:1032E000FFF764FD039B0833402B0246E8D13A46C2 +:1032F0004146FFF76DFD0346CDE900872A4621468A +:103300003046FFF777FEB9F1010F06D12B78013374 +:10331000DBB21F2B88BF00232B7005B0BDE8F08FF8 +:103320004FF6FF73E8E76FF00100F6E76FF0030078 +:10333000F3E70000C06900B104307047C3691A6840 +:10334000C261C2681A60C360438A013B438270470E +:103350002DE9F041D0F81880194E14461D4641461B +:10336000002709B9BDE8F081D1E90223A21A65EB73 +:103370000303964277EB03031ED283698B420DD180 +:10338000FFF796FD83691B688361C3680B60438AFE +:10339000C1608169013B43828846E2E7FFF788FD0F +:1033A0000B68C8F80030C3680B60438AC160013BFA +:1033B0004382D8F80010D4E788460968D1E700BFF7 +:1033C00080841E002DE9F04F8BB00D46DDF8509043 +:1033D00014469B468046002800F01981B9F1000F81 +:1033E00000F01581531E3F2B00F21181012A03D1F9 +:1033F000BBF1000F40F00B810023CDE90833B8F892 +:103400001430B5EBC30F4FEAC30703D300200BB052 +:10341000BDE8F08F2B199F42D8F80C303ABF7F1BC4 +:10342000FFB227461BB9D8F81030002B7AD02F2DC9 +:103430004ED8C5F13006B7424FF000032CBFF6B2AC +:103440003E4600932946D8F8080008AB3246FFF7FD +:1034500075FCA7EB060A35445FFA8AFAB8F814300F +:1034600003F10053063BDB000493D8F80C300393C0 +:103470003021039B13B1BAF1000F2CD1D8F8100002 +:1034800040B1BAF1000F05D0009608AB5246691A58 +:10349000FFF754FC38B2002FB8D066070AD00AAB49 +:1034A00003EBD401624211F8083C02F00702134119 +:1034B00001F8083C082C3CD9102C40F2B580202C97 +:1034C00040F2B780BBF1000F00F09C80082334E08D +:1034D000BA460026C2E7049BE02B28BFE0230693F0 +:1034E0000B44AB42059314D95A1B0398009692459E +:1034F00034BF5246D2B2691A08AB04300792FFF7C4 +:103500001DFC079A1644AAEB020A1544F6B25FFAAC +:103510008AFA049B069A05999B1A0493039B1B68DD +:103520000393A6E70093D8F8080008AB3A4629466B +:10353000AEE7BBF1000F13D00123B4EBC30F6CD087 +:10354000082C12D89DF82030621E23FA02F2D5070B +:1035500006D54FF0FF3202FA04F423438DF82030F1 +:103560009DF8203089F8003051E7102C12D8BDF8B2 +:103570002030621E23FA02F2D10706D54FF0FF3247 +:1035800002FA04F42343ADF82030BDF82030A9F846 +:1035900000303CE7202C0FD80899631E21FA03F372 +:1035A000DA0705D54FF0FF3202FA04F40C43089411 +:1035B000089BC9F800302AE7402C2BD0DDE90865CC +:1035C000611EC4F12102A4F1210326FA01F105FADA +:1035D00002F225FA03F311431943CB0712D5012256 +:1035E000A4F12003C4F1200102FA03F322FA01F14D +:1035F000A240524243EA010363EB430332432B43AD +:10360000CDE90823DDE90823C9E90023FFE66FF0CF +:103610000100FCE66FF00800F9E6082CA0D9102C98 +:10362000B3D9202CEED8C3E7BBF1000FADD00223F5 +:1036300083E7BBF1000FBBD004237EE730B5012A3E +:10364000144638BF0124402C85B028BF40240025F3 +:10365000012ACDE9025518D81B788DF80830630788 +:103660000AD004AB03EBD405624215F8083C02F023 +:103670000702934005F8083C0091034622460021CA +:1036800002A8FFF75BFB05B030BD082AE4D9102A79 +:1036900003D81B88ADF80830E1E7202A8DBFD3E9B5 +:1036A00000231B680293CDE90223D8E710B5CB684D +:1036B0001BB98B600B618B8210BDC4681A681C60DB +:1036C000C360438A013B4382CA60F0E72DE9F04FB3 +:1036D000D1F8008093B018F0800FCDE90323C8F330 +:1036E000C01219BFC8F3C03BC8F306264FF0020B47 +:1036F0001646B8F1000F04460D4680F2D18118F04D +:10370000C043059340F0CC810B7B002B00F0C881B7 +:10371000BBF1020F03D00178B14240F0C48108F040 +:103720007F0106916AB3C8F3074A2B44069A93F8BF +:103730000390760646EA0B4646EA82465FEAD913CC +:1037400046EA0A06079300F0908000220023CDE9A4 +:103750000A23069B009367685B4652460AA92046E7 +:10376000B84700287ED0A7699FB9314604F10C0004 +:10377000FFF748FB0746E0B96FF0020013B0BDE861 +:10378000F08FC8F30F2A18F07F0F08BF0AF0030A62 +:10379000CBE73B699E420DD03F68002FF9D13146FF +:1037A00004F10C00FFF72EFB07460028E4D0A369C4 +:1037B0003B60A761DDE90A2300264FF6FF70C6F1E2 +:1037C000200E22FA06F103FA0EFEA6F1200C23FACF +:1037D0000CFC41EA0E0141EA0C01C9B2083609921B +:1037E0000893FFF7E3FA402EDDE90832E7D1B8820B +:1037F000FB7D09F01F06C3F384039B1BD7E902215D +:1038000098B2002BBCBF00F120031BB252EA0100AA +:10381000C8F304680FD00398821A049860EB010182 +:10382000A74890424FF000028A4104D3079A002A29 +:103830005BD0012B23DDFA7D4FEA890302F00302FE +:1038400003F07C031343FB7539462046FFF730FB3A +:10385000079BA3B9FB7DC3F38402013262F38603A5 +:10386000FB7504E06FF00B0088E7A76917B96FF0EC +:103870000C0083E73B699E42BAD03F68F6E719F037 +:10388000400F32D0039BBB60049BFB6014220021DD +:103890000DA8FEF7A9F9039B0A93049B0B932B1D1C +:1038A0000C932B7BADF83EA0013BDBB2ADF83C3076 +:1038B000069B8DF8433094F824308DF840B083F0A7 +:1038C00001038DF844308DF84160A3688DF8428083 +:1038D0000AA920469847FB7DC3F38403013303F014 +:1038E0001F039B02FB82002048E7FB7DC9F34012C7 +:1038F000B2EBD31F40F0DA80C3F38403B34240F04D +:10390000D88007992B7B4FEA9912002934D0D2072F +:1039100041D4032B40F2D080039BBB60049BFB602F +:103920002B7BAE1D033BDBB23246394604F10C0063 +:10393000FFF7D0FA00280DDA20463946FFF7B8FA2B +:10394000FB7DC3F38403013303F01F039B02FB825F +:10395000032013E7AB883B832A7B033AB88AD2B2B1 +:103960003146FFF735FAFB7DB882DA43C2F3C01265 +:1039700062F3C713FB75B6E76AB92E1D013BDBB2D4 +:103980003246394604F10C00FFF7A4FA0028D3DBD5 +:103990002A7B013AE2E7F98AC1F30901013B0529D3 +:1039A000DAB259D8281D002307F11A0C9A4208D917 +:1039B00010F801EB0CF801E0013101330629DBB20C +:1039C000F4D103990A9104990B91934207F11A01DA +:1039D0000C9138BF043379680D9134BF55FA83F3E5 +:1039E00000230E93FB8AADF83EA0C3F309031A44EB +:1039F000069B8DF8433094F82430ADF83C2083F0DA +:103A000001038DF8443000238DF840B08DF84160FB +:103A10008DF842807B602A7BB88A013A291DFFF726 +:103A2000D7F93B8BB882834203D1A3680AA9204609 +:103A3000984720460AA9FFF739FEFB7DB88AC3F3F1 +:103A40008403013303F01F039B02FB823B8B9842EC +:103A500014BF1120002091E67B68002BB1D0062016 +:103A600001E01C306346D3F800C0BCF1000FF8D170 +:103A7000091A081D05F1040C00EB030905989DF8CF +:103A8000143001EB000EBEF11B0F9AD89A4298D960 +:103A90001CF8013B09F8013B059B01330593EDE759 +:103AA0006FF009006AE66FF00A0067E66FF00D003C +:103AB00064E66FF00E0061E66FF00F005EE600BF97 +:103AC00080841E00EFF3098305494A6B22F001024E +:103AD0004A63683383F30988002383F311887047AE +:103AE00000EF00E0202080F3118862B60C4B0D4AF5 +:103AF000D96821F4E0610904090C0A43DA60D3F8BB +:103B0000FC20094942F08072C3F8FC200A6842F0A8 +:103B100001020A601022DA7783F82200704700BFA2 +:103B200000ED00E00003FA05001000E010B52023CE +:103B300083F311880E4B5B6813F4006314D0F1EE2D +:103B4000103AEFF30984683C4FF08073E361094B4E +:103B5000DB6B236684F3098800F094FB10B1064BFD +:103B6000A36110BD054BFBE783F31188F9E700BFA4 +:103B700000ED00E000EF00E04B0600084E060008F4 +:103B8000024AD36843F0C003D3607047004400404A +:103B9000044B5A6810439A6858600AB1181D1047C0 +:103BA000704700BFCC5700202DE9F0413C4ED6F8BD +:103BB0005C52EF682B68DA059CB20CD5202383F3A6 +:103BC00011884FF40070FFF7E3FF6FF480732B60F0 +:103BD000002383F31188202383F31188DFF8C0804A +:103BE00014F02F0339D183F31188380613D5210639 +:103BF00011D5202383F311882A4800F0EFF900281B +:103C00004CDA0820FFF7C4FF4FF67F733B40EB60B0 +:103C1000002383F311887A0615D5630613D5202374 +:103C200083F31188D6E913239A4209D1336C3BB14F +:103C300027F040073F0410203F0CFFF7A9FFEF607B +:103C4000002383F31188D6F86422D3680BB110697E +:103C50009847BDE8F041FFF769BF230712D014F081 +:103C6000080F0CBF00208020E10748BF40F0200073 +:103C7000A20748BF40F04000630748BF40F480708F +:103C8000FFF786FFA4066B6805D596F860124046DC +:103C9000194000F053FA2C68A4B2A1E76860B7E7B6 +:103CA000CC5700200458002010B5054C054A0021CF +:103CB000204600F013FA044BC4F85C3210BD00BF7C +:103CC000CC570020813B00080044004038B52A4C06 +:103CD000037C002918BF0C46012B0546C0F864423E +:103CE00010D1264B98420DD1254B1A6C42F400326C +:103CF0001A641A6E42F400321A660B2126201B6EDB +:103D000000F046F8D5F85C221E4923688A424FEA43 +:103D1000530003D001F580618A422AD11A49014437 +:103D2000B4F90400B1FBF3F30028BEBF23F0070091 +:103D300003F0070343EA4003A1889360E38843F05C +:103D400040031361238943F00103536141F4045399 +:103D500043F02C03D36001F4A05100231360B1F5AC +:103D6000806F136853680CBF7F23FF2385F8603290 +:103D700038BD0649D3E700BF80540008CC57002067 +:103D8000003802400010014080F0FA0240787D01C6 +:103D900000F1604303F561430901C9B283F80013E0 +:103DA000012200F01F039A4043099B0003F1604386 +:103DB00003F56143C3F880211A607047F8B51546D2 +:103DC00082680669AA420B46816938BF8568761AFF +:103DD000B54204460BD218462A46FDF7F3FEA36906 +:103DE0002B44A361A3685B1BA3602846F8BD0CD9D4 +:103DF00018463246FDF7E6FEAF1BE1683A4630440E +:103E0000FDF7E0FEE3683B44EBE718462A46FDF782 +:103E1000D9FEE368E5E7000083689342F7B51546ED +:103E2000044638BF8568D0E90460361AB5420BD223 +:103E30002A46FDF7C7FE63692B446361A3682846E1 +:103E40005B1BA36003B0F0BD0DD932460191FDF7B5 +:103E5000B9FE0199E068AF1B3A463144FDF7B2FE66 +:103E6000E3683B44E9E72A46FDF7ACFEE368E4E794 +:103E700010B50A440024C361029B8460C0E90000BD +:103E8000C0E90511C1600261036210BD08B5D0E947 +:103E90000532934201D1826882B982680132826020 +:103EA0005A1C42611970D0E904329A4224BFC36897 +:103EB0004361002100F0B6FA002008BD4FF0FF304A +:103EC000FBE7000070B5202304460E4683F31188FB +:103ED000A568A5B1A368A269013BA360531CA361B7 +:103EE00015782269934224BFE368A361E3690BB1AB +:103EF00020469847002383F31188284607E031467F +:103F0000204600F07FFA0028E2DA85F3118870BDC0 +:103F10002DE9F74F04460E4617469846D0F81C90F8 +:103F20004FF0200A8AF311884FF0000B154665B157 +:103F30002A4631462046FFF741FF034660B9414615 +:103F4000204600F05FFA0028F1D0002383F31188A7 +:103F5000781B03B0BDE8F08FB9F1000F03D00190DA +:103F60002046C847019B8BF31188ED1A1E448AF343 +:103F70001188DCE7C0E90511C160C3611144009BF1 +:103F80008260C0E90000016103627047F8B5044631 +:103F90000D461646202383F31188A768A7B1A368AE +:103FA000013BA36063695A1C62611D70D4E904324D +:103FB0009A4224BFE3686361E3690BB120469847E6 +:103FC000002080F3118807E03146204600F01AFAFD +:103FD0000028E2DA87F31188F8BD0000D0E9052354 +:103FE0009A4210B501D182687AB982680132826042 +:103FF0005A1C82611C7803699A4224BFC36883619A +:10400000002100F00FFA204610BD4FF0FF30FBE713 +:104010002DE9F74F04460E4617469846D0F81C90F7 +:104020004FF0200A8AF311884FF0000B154665B156 +:104030002A4631462046FFF7EFFE034660B9414667 +:10404000204600F0DFF90028F1D0002383F3118827 +:10405000781B03B0BDE8F08FB9F1000F03D00190D9 +:104060002046C847019B8BF31188ED1A1E448AF342 +:104070001188DCE7026843681143016003B1184707 +:10408000704700001430FFF743BF00004FF0FF33CC +:104090001430FFF73DBF00003830FFF7B9BF000014 +:1040A0004FF0FF333830FFF7B3BF00001430FFF795 +:1040B00009BF00004FF0FF311430FFF703BF0000CD +:1040C0003830FFF763BF00004FF0FF323830FFF7A2 +:1040D0005DBF000000207047FFF7E6BD37B515460D +:1040E0000E4A026000224260C0E902220122044618 +:1040F00002740B46009000F15C014FF480721430A2 +:10410000FFF7B6FE00942B464FF4807204F5AE71B3 +:1041100004F13800FFF72EFF03B030BD94540008BF +:1041200010B52023044683F31188FFF7CFFD022347 +:104130002374002383F3118810BD000038B5C369D0 +:1041400004460D461BB904210844FFF793FF294696 +:1041500004F11400FFF79AFE002806DA201D4FF440 +:104160008061BDE83840FFF785BF38BD024B0022B3 +:10417000C3E900339A607047345A00200023037467 +:104180008268054B1B6899689142FBD25A680360AC +:104190004260106058607047345A002008B52023F0 +:1041A00083F31188037C032B05D0042B0DD02BB98E +:1041B00083F3118808BD436900221A604FF0FF3372 +:1041C0004361FFF7DBFF0023F2E7D0E90032136021 +:1041D0005A60F3E7002303748268054B1B689968F3 +:1041E0009142FBD85A680360426010605860704783 +:1041F000345A0020054B19690874186802681A605F +:104200005360186101230374FCF70ABA345A002082 +:1042100030B54B1C0B4D87B0044610D02B690A4AB1 +:1042200001A800F019F92046FFF7E4FF049B13B141 +:1042300001A800F04DF92B69586907B030BDFFF7B0 +:10424000D9FFF8E7345A00209D41000838B50C4DDD +:1042500041612B6981689A689142044603D8BDE8A0 +:104260003840FFF78BBF1846FFF7B4FF01232C61DE +:10427000014623742046BDE83840FCF7D1B900BFA1 +:10428000345A0020044B1A681B6990689B68984256 +:1042900094BF002001207047345A002010B5084C0C +:1042A000236820691A6822605460012223611A740D +:1042B000FFF790FF01462069BDE81040FCF7B0B958 +:1042C000345A002008B5FFF7DDFF18B1BDE80840FB +:1042D000FFF7E4BF08BD0000FFF7E0BFFEE7000006 +:1042E00010B50C4CFFF742FF00F0A8F80A498022F5 +:1042F000204600F03DF8012344F8180C0374FFF742 +:10430000F1FB002383F3118862B60448BDE8104036 +:1043100000F04EB85C5A0020BC540008CC54000891 +:1043200008B572B6034B586200F092FA00F03AFBFF +:10433000FEE700BF345A002000F004B9EFF311800B +:1043400020B9EFF30583202282F311887047000023 +:1043500010B530B9EFF30584C4F3080414B180F349 +:10436000118810BDFFF7AEFF84F31188F9E7000054 +:1043700082600222028270478368A3F17C0243F8C4 +:104380000C2C026943F83C2C426943F8382C074A4C +:1043900043F81C2CC26843F8102C022203F8082CA6 +:1043A000002203F8072CA3F1180070473906000813 +:1043B00010B5202383F31188FFF7DEFF00210446A8 +:1043C000FFF744FF002383F31188204610BD00004F +:1043D000024B1B6958610F20FFF70CBF345A0020B5 +:1043E000202383F31188FFF7F3BF000008B50146CF +:1043F000202383F311880820FFF70AFF002383F3AB +:10440000118808BD49B1064B42681B6918605A60A3 +:10441000136043600420FFF7FBBE4FF0FF3070478E +:10442000345A00200368984206D01A68026050602F +:1044300059611846FFF7A2BE70470000054B03F113 +:104440001402C3E905224FF0FF310022C3E907122D +:10445000704700BF345A002070B51C4EC0E90323DA +:1044600005460C4600F020FB334653F8142F9A42C1 +:104470000DD13062C5E901242A600A2C2CBF001935 +:104480000A30C6E90555BDE8704000F0FBBA316A54 +:10449000431AE31838BF1C469368A34202D908198F +:1044A00000F0FEFA73699A6894420CD85A68AC60BE +:1044B0002B606A6015609A685D60121B9A604FF00D +:1044C000FF33F36170BD1B68A41AECE7345A002077 +:1044D00038B51B4C636998420DD0D0E900321360A7 +:1044E0005A6000228168C2609A680A449A604FF05C +:1044F000FF33E36138BD2246036842F8143F0021D0 +:1045000093425A60C16003D1BDE8384000F0C2BA9E +:104510009A688168256A0A449A6000F0C5FA63695E +:104520009A68411B8A42E5D9AB181D1A092D206AE9 +:1045300098BF01F10A02BDE83840104400F0B0BA5B +:10454000345A00202DE9F041184C002704F11406DC +:10455000656900F0A9FA236AAA68C11A8A4215D8C7 +:1045600013442362D5E9003213605A606369D5F8B9 +:104570000C80EF60B34201D100F08CFA87F3118810 +:104580002869C047202383F31188E1E76169B142BC +:1045900009D013441B1ABDE8F0410A2B2CBFC018E8 +:1045A0000A3000F07DBABDE8F08100BF345A002027 +:1045B0000C2303604FF0FF3070470000002070476D +:1045C000FEE70000704700004FF0FF30704700002A +:1045D000BFF34F8F024AD368DB03FCD4704700BFA0 +:1045E000003C024008B5094B1B7873B9FFF7F0FF98 +:1045F000074B1A69002ABFBF064A5A6002F1883287 +:104600005A601A6822F480621A6008BDF05B0020CC +:10461000003C02402301674508B50B4B1B7893B95A +:10462000FFF7D6FF094B1A6942F000421A611A6877 +:1046300042F480521A601A6822F480521A601A6892 +:1046400042F480621A6008BDF05B0020003C02402A +:104650000728F0B516D80C4C0C4923787BB90C4DC3 +:104660000E4608234FF0006255F8047B46F8042BF1 +:10467000013B13F0FF033A44F6D10123237051F8B4 +:104680002000F0BD0020FCE7145C0020F45B00205B +:10469000E4540008014B53F820007047E45400082C +:1046A00008207047072810B5044601D9002010BD26 +:1046B000FFF7CEFF064B53F824301844C21A0BB94B +:1046C0000120F4E712680132F0D1043BF6E700BFA5 +:1046D000E4540008072838B5044628D8FFF72EFE12 +:1046E000FFF776FFFFF77EFF124AF323D360E30064 +:1046F000DBB243F4007343F002031361136943F424 +:104700008033136105462046FFF762FFFFF7A0FFE5 +:10471000094B53F8241000F041F92846FFF77CFFBD +:10472000FFF716FE2046BDE83840FFF7BBBF00206C +:1047300038BD00BF003C0240E454000812F0010301 +:104740002DE9F04105460E4614464BD18118334AF7 +:10475000914261D8324B1B6813F001035CD0314F9A +:10476000FFF7ECFDFFF73EFFF323FB60FFF730FFA1 +:10477000314640F20128032C18D824F00104294EB8 +:104780000C446D1A40F20118A142336905EB010790 +:104790002AD123F001033361FFF73EFFFFF7D8FD75 +:1047A0000120BDE8F081043C0435E4E7AB07E4D127 +:1047B0003B6923F440733B613B6943EA08033B6177 +:1047C00051F8046B2E60BFF34F8FFFF701FF2B688A +:1047D0009E42E8D03B6923F001033B61FFF71CFFD9 +:1047E000FFF7B6FD0020DCE723F440733361336943 +:1047F00043EA080333610B883B80BFF34F8FFFF719 +:10480000E7FE3F8831F8023BBFB2BB42BCD0336900 +:1048100023F001033361E1E71846C2E7000008080E +:1048200000380240003C0240084908B50B7828B126 +:104830001BB9FFF7D7FE01230B7008BD002BFCD07E +:10484000BDE808400870FFF7E7BE00BFF05B00203E +:104850004FF480214FF0005000F0A2B870B582B044 +:10486000FFF76CFD0E4E054600F01EF932689042CF +:1048700037BF0C4A0B49516814682EBFD1E900417B +:10488000013151600419034641F1000128460191AC +:104890003360FFF75DFD0199204602B070BD00BF97 +:1048A000185C0020205C002070B582B0FFF746FD48 +:1048B000104E054600F0F8F83268904237BF0E4AB5 +:1048C0000D49516814682EBFD1E900410131516092 +:1048D000041941F100010346284601913360FFF7B6 +:1048E00037FD01994FF47A7200232046FBF780FCD4 +:1048F00002B070BD185C0020205C002010B502449E +:10490000064BD2B2904200D110BD441C00B253F805 +:10491000200041F8040BE0B2F4E700BF502800404B +:104920000F4B30B51C6F240407D41C6F44F4007483 +:104930001C671C6F44F400441C670A4C236843F452 +:10494000807323600244084BD2B2904200D130BD44 +:10495000441C00B251F8045B43F82050E0B2F4E785 +:1049600000380240007000405028004007B5012286 +:1049700001A90020FFF7C2FF019803B05DF804FB16 +:1049800013B50446FFF7F2FFA04205D0012201A9AA +:1049900000200194FFF7C4FF02B010BD7047000073 +:1049A0007047000070470000074B45F255521A60EF +:1049B00002225A6040F6FF729A604CF6CC421A60AE +:1049C000024B01221A707047003000402C5C00201E +:1049D000034B1B781BB1034B4AF6AA221A6070479F +:1049E0002C5C002000300040034B1A681AB9034ABF +:1049F000D2F874281A607047285C0020003002400A +:104A0000024B4FF08072C3F87428704700300240A8 +:104A100008B5FFF7E9FF024B1868C0F3407008BD06 +:104A2000285C002008B5FFF7DFFF024B1868C0F3D1 +:104A3000007008BD285C002070470000FEE7000001 +:104A40000A4B0B480B4A90420BD30B4BDA1C121A41 +:104A5000C11E22F003028B4238BF00220021FDF765 +:104A6000C3B853F8041B40F8041BECE77456000865 +:104A7000C45C0020C45C0020C45C002070470000BF +:104A800000F080B84FF08043002258631A61022280 +:104A9000DA6070474FF080430022DA607047000010 +:104AA0004FF08043586370474FF08043586A704717 +:104AB0004B6843608B688360CB68C3600B6943615C +:104AC0004B6903628B6943620B68036070470000A7 +:104AD00008B5234B23481A6942F0FF021A611A698C +:104AE00022F0FF021A611A691A6B42F0FF021A6380 +:104AF0001A6D42F0FF021A651B4A1B6D1146FFF743 +:104B0000D7FF02F11C0100F58060FFF7D1FF02F131 +:104B1000380100F58060FFF7CBFF02F1540100F58A +:104B20008060FFF7C5FF02F1700100F58060FFF7BC +:104B3000BFFF02F18C0100F58060FFF7B9FF02F1C1 +:104B4000A80100F58060FFF7B3FF02F1C40100F592 +:104B50008060FFF7ADFFBDE8084000F097B800BFE8 +:104B600000380240000002400455000808B500F07B +:104B700017FAFFF7B5FBBDE80840FFF735BF0000A7 +:104B800070470000104B1A6C42F001021A641A6E52 +:104B900042F001021A660D4A1B6E936843F001034E +:104BA00093604FF0804331229A624FF0FF32DA6215 +:104BB00000229A615A63DA605A6001225A61082120 +:104BC0001A601C20FFF7E4B800380240002004E01F +:104BD0004FF0804208B51169D3680B40D9B2C94380 +:104BE0009B07116107D5202383F31188FFF7A4FBEE +:104BF000002383F3118808BD08B5FFF7E9FFBDE87E +:104C00000840FEF793BF00001E4B1A6962F0FF02D6 +:104C10001A611A69D2B21A614FF0FF301A695A69E3 +:104C2000586100215A6959615A691A6A62F08052C2 +:104C30001A621A6A02F080521A621A6A5A6A586232 +:104C40005A6A59625A6A1A6C42F080521A641A6E91 +:104C500042F080521A661A6E0B4A106840F4807057 +:104C60001060186F00F44070B0F5007F1EBF4FF465 +:104C7000803018671967536823F40073536000F09D +:104C80006FB900BF00380240007000403B4B3C4A07 +:104C90001A643C4A4FF4404111601A6842F0010224 +:104CA0001A601A689007FCD59A6822F003029A608D +:104CB000324B9A6812F00C02FBD1196801F0F9012D +:104CC00019609A601A6842F480321A601A68910377 +:104CD000FCD55A6F42F001025A67284B5A6F92076F +:104CE000FCD5294A5A601A6842F080721A60254A37 +:104CF00053685804FCD5214B1A689101FCD5234A0E +:104D0000C3F884201A6842F080621A601A6812019F +:104D1000FCD51F4A9A600322C3F88C204FF0006232 +:104D2000C3F894201B4B1A681B4B9A421B4B21D192 +:104D30001B4A11681B4A91421CD140F203121A60AF +:104D4000164A136803F00F03032BFAD10B4B9A6832 +:104D500042F002029A609A6802F00C02082AFAD124 +:104D60005A6C42F480425A645A6E42F480425A6647 +:104D70005B6E704740F20372E1E700BF003802400B +:104D80000004001000700040081940021030002498 +:104D900000948838002004E011640020003C0240A8 +:104DA00000ED00E041C20F41084A08B5516913689F +:104DB0000B4003F00103536123B1054A13680BB1A3 +:104DC00050689847BDE80840FEF7B0BE003C01407F +:104DD000305C0020084A08B5516913680B4003F0A5 +:104DE0000203536123B1054A93680BB1D068984719 +:104DF000BDE80840FEF79ABE003C0140305C002050 +:104E0000084A08B5516913680B4003F00403536165 +:104E100023B1054A13690BB150699847BDE80840B2 +:104E2000FEF784BE003C0140305C0020084A08B513 +:104E3000516913680B4003F00803536123B1054A1D +:104E400093690BB1D0699847BDE80840FEF76EBE84 +:104E5000003C0140305C0020084A08B551691368E5 +:104E60000B4003F01003536123B1054A136A0BB1E1 +:104E7000506A9847BDE80840FEF758BE003C014024 +:104E8000305C0020174B10B55A691C68144004F4BC +:104E900078725A61A30604D5134A936A0BB1D06A9B +:104EA0009847600604D5104A136B0BB1506B9847B6 +:104EB000210604D50C4A936B0BB1D06B9847E205E1 +:104EC00004D5094A136C0BB1506C9847A30504D55F +:104ED000054A936C0BB1D06C9847BDE81040FEF7C3 +:104EE00025BE00BF003C0140305C00201A4B10B5CD +:104EF0005A691C68144004F47C425A61620504D566 +:104F0000164A136D0BB1506D9847230504D5134A0B +:104F1000936D0BB1D06D9847E00404D50F4A136E22 +:104F20000BB1506E9847A10404D50C4A936E0BB197 +:104F3000D06E9847620404D5084A136F0BB1506FC6 +:104F40009847230404D5054A936F0BB1D06F984757 +:104F5000BDE81040FEF7EABD003C0140305C002097 +:104F6000062108B50846FEF713FF06210720FEF7C5 +:104F70000FFF06210820FEF70BFF06210920FEF790 +:104F800007FF06210A20FEF703FF06211720FEF780 +:104F9000FFFEBDE8084006212820FEF7F9BE00000C +:104FA00008B5FFF731FE00F009F8FFF795F8FFF7B5 +:104FB000E7FDBDE80840FFF763BD00000023054A98 +:104FC00019460133102BC2E9001102F10802F8D191 +:104FD000704700BF305C00200B460146184600F0C9 +:104FE00025B8000000F038B8012838BF012010B5FE +:104FF0000446204600F028F830B900F007F808B958 +:1050000000F00CF88047F4E710BD0000024B186870 +:10501000BFF35B8F704700BFB05C002008B506206F +:1050200000F032F90120FFF7CBFA000010B5054C73 +:1050300013462CB10A4601460220AFF3008010BD92 +:105040002046FCE700000000024B0146186800F013 +:1050500089B800BF20230020024B0146186800F0E9 +:1050600035B800BF2023002010B50139024490421A +:1050700001D1002005E0037811F8014FA34201D0CF +:10508000181B10BD0130F2E72DE9F041A3B1C91A98 +:1050900017780144044603F1FF3C8C42204601D9B5 +:1050A000002009E00578BD4204F10104F5D10CEBC4 +:1050B0000405D618A54201D1BDE8F08115F8018D8F +:1050C00016F801EDF045F5D0E7E7000037B5002907 +:1050D00044D051F8043C0190002BA1F10404B8BF66 +:1050E000E41800F0F5F81E4A0198136833B96360BC +:1050F000146003B0BDE8304000F0F0B8A34208D916 +:10510000256861198B4201BF19685B6849192160E4 +:10511000EDE71A465B680BB1A342FAD9116855183E +:10512000A5420BD1246821445418A3421160E0D158 +:105130001C685B68536021441160DAE702D90C23D4 +:105140000360D6E7256861198B4204BF19685B6864 +:10515000636004BF491921605460CAE703B030BDE1 +:10516000B45C0020F8B5CD1C25F0030508350C2DE6 +:1051700038BF0C25002D064601DBA94203D90C23BC +:1051800033600020F8BD00F0A3F821490A681446F6 +:105190009CB9204F3B6823B92146304600F03CF8CB +:1051A00038602946304600F037F8431C23D10C23E1 +:1051B0003360304600F092F8E3E723685B1B17D4B6 +:1051C0000B2B03D923601C44256004E06368A242D2 +:1051D0000CBF0B605360304600F080F804F10B0008 +:1051E000231D20F00700C21ACCD01B1AA350C9E718 +:1051F00022466468CCE7C41C24F00304A042E3D038 +:10520000211A304600F008F80130DDD1CFE700BFA9 +:10521000B45C0020B85C002038B5064D002304467D +:1052200008462B60FFF7C4F9431C02D12B6803B179 +:10523000236038BDBC5C00201F2938B504460D46EC +:1052400004D9162303604FF0FF3038BD426C12B111 +:1052500052F821304BB9204600F030F82A4601467A +:105260002046BDE8384000F017B8012B0AD0591C81 +:1052700003D1162303600120E7E7002442F825400C +:10528000284698470020E0E7024B01461868FFF7E0 +:10529000D3BF00BF2023002038B5074D00230446AC +:1052A000084611462B60FFF78FF9431C02D12B688B +:1052B00003B1236038BD00BFBC5C0020FFF77EB99E +:1052C000034611F8012B03F8012B002AF9D170478E +:1052D000014800F009B800BFC05C0020014800F0A0 +:1052E00005B800BFC05C0020704700007047000098 +:1052F0006F72672E6172647570696C6F742E486F7F +:105300006C7962726F475053000000004E6F20614D +:105310007070207369670A00426164206677206CB0 +:10532000656E6774682025750A0042616420626FAB +:105330006172645F69642025752073686F756C64A1 +:105340002062652025750A0042616420667720642A +:10535000657363726970746F72206C656E677468D0 +:105360002025750A00426164206170702043524319 +:10537000203078253038783A307825303878203029 +:1053800078253038783A3078253038780A00476FF9 +:105390006F64206669726D776172650A0040A2E4ED +:1053A000F16468910600000053544D3332463F3F8C +:1053B0003F00000053544D3332463430780053548C +:1053C0004D3332463432780053544D333246343400 +:1053D0003658580000000000A85300083F000000A5 +:1053E00013040000B45300083F000000190400003B +:1053F000BE5300083F00000021040000C85300080D +:105400003F0000004261642043414E49666163658C +:1054100020696E6465782E00000100000001FF0025 +:105420000064004000680040800000000080000030 +:10543000000080000000000000000000ED1C0008DB +:105440007D25000889240008FD1C0008351D000882 +:10545000311F0008011D0008151D0008051D00086A +:10546000091D0008111D00080D1D0008591E000827 +:10547000191D00081D280008291D00082D1E000800 +:105480000096000000000000000000000000000086 +:105490000000000000000000A14000088D4000084E +:1054A000C9400008B5400008C1400008AD400008F0 +:1054B0009940000885400008D54000086D61696E7C +:1054C0000000000069646C6500000000C45400081E +:1054D000785A0020F05B002001000000DD42000847 +:1054E00000000000004000000040000000400000FC +:1054F0000040000000000100000002000000020067 +:1055000000000200A001812A00000000AAA9AAAAA6 +:1055100050000124EFFF0000007700000090090018 +:105520001000004A000000009AAAAAAA0000000089 +:10553000FBFF0000000000000000990000000000D8 +:1055400000000000AAAAAAAA00000000FFFF0000B5 +:10555000000000000000000000000000000000004B +:10556000AAAAAAAA00000000FFFF00000000000095 +:10557000000000000000000000000000AAAAAAAA83 +:1055800000000000FFFF000000000000000000001D +:105590000000000000000000AAAAAAAA0000000063 +:1055A000FFFF0000000000000000000000000000FD +:1055B00000000000AAAAAAAA00000000FFFF000045 +:1055C00000000000000000000000000000000000DB +:1055D0000A000000000000000300000000000000BE +:1055E000000000003CACFF7F010000000000000054 +:1055F0000B04000000000000000007000000000095 +:1056000040420F00FE2A0100D2040000FF0000000B +:105610002423002000000000000000000000000023 +:10562000000000000000000000000000000000007A +:10563000000000000000000000000000000000006A +:10564000000000000000000000000000000000005A +:10565000000000000000000000000000000000004A +:10566000000000000000000000000000000000003A +:045670000000000036 :00000001FF diff --git a/Tools/bootloaders/KakuteF4Mini_bl.bin b/Tools/bootloaders/KakuteF4Mini_bl.bin old mode 100644 new mode 100755 index c65036a4119..a5bbb965f8c Binary files a/Tools/bootloaders/KakuteF4Mini_bl.bin and b/Tools/bootloaders/KakuteF4Mini_bl.bin differ diff --git a/Tools/bootloaders/KakuteF4Mini_bl.hex b/Tools/bootloaders/KakuteF4Mini_bl.hex index f6357f7aeef..d4021e09b01 100644 --- a/Tools/bootloaders/KakuteF4Mini_bl.hex +++ b/Tools/bootloaders/KakuteF4Mini_bl.hex @@ -1,25 +1,25 @@ :020000040800F2 -:1000000000060020E1010008190E00081D0E00087E -:10001000750E00081D0E0008490E0008E3010008D7 -:10002000E3010008E3010008E3010008492100089A +:1000000000060020E1010008790E0008F90D000843 +:10001000510E0008F90D0008250E0008E301000844 +:10002000E3010008E3010008E30100084D21000896 :10003000E3010008E3010008E3010008E301000810 :10004000E3010008E3010008E3010008E301000800 -:10005000E3010008E30100082932000855320008D6 -:1000600081320008AD320008D9320008E3010008EF +:10005000E3010008E30100081532000841320008FE +:100060006D32000899320008C5320008E30100082B :10007000E3010008E3010008E3010008E3010008D0 :10008000E3010008E3010008E3010008E3010008C0 -:10009000E3010008E3010008E3010008053300085C +:10009000E3010008E3010008E3010008F132000871 :1000A000E3010008E3010008E3010008E3010008A0 -:1000B0009D300008E3010008E3010008E3010008A7 +:1000B00089300008E3010008E3010008E3010008BB :1000C000E3010008E3010008E3010008E301000880 :1000D000E3010008E3010008E3010008E301000870 -:1000E0006D330008E3010008E3010008E3010008A4 +:1000E00059330008E3010008E3010008E3010008B8 :1000F000E3010008E3010008E3010008E301000850 :10010000E3010008E3010008E3010008E30100083F :10011000E3010008E3010008E3010008E30100082F :10012000E3010008E3010008E3010008E30100081F :10013000E3010008E3010008E3010008E30100080F -:10014000E3010008E3010008E30100088D2800082E +:10014000E3010008E3010008E30100088528000836 :10015000E3010008E3010008E3010008E3010008EF :10016000E3010008E3010008E3010008E3010008DF :10017000E3010008E3010008E3010008E3010008CF @@ -29,681 +29,681 @@ :1001B000E3010008E3010008E3010008E30100088F :1001C000E3010008E3010008E3010008E30100087F :1001D000E3010008E3010008E3010008E30100086F -:1001E00002E000F000F8FEE772B6394880F30888B4 -:1001F000384880F3098838484EF60851CEF200019D +:1001E00002E000F000F8FEE772B63A4880F30888B3 +:1001F000394880F3098839484EF60851CEF200019B :10020000086040F20000CCF200004EF63471CEF2ED :1002100000010860BFF34F8FBFF36F8F40F2000003 :10022000C0F2F0004EF68851CEF200010860BFF334 :100230004F8FBFF36F8F4FF00000E1EE100A4EF6C4 :100240003C71CEF200010860062080F31488BFF3F1 -:100250006F8F01F0D7FF02F07DFE4FF055301F4940 -:100260001B4A91423CBF41F8040BFAE71C49194A6A -:1002700091423CBF41F8040BFAE71A491A4A1B4B5A -:100280009A423EBF51F8040B42F8040BF8E70020F5 -:100290001749184A91423CBF41F8040BFAE701F0B4 -:1002A000B5FF02F0B3FE144C144DAC4203DA54F81F -:1002B000041B8847F9E700F041F8114C114DAC429E -:1002C00003DA54F8041B8847F9E701F09DBF0000EA -:1002D000000600200022002000000008000000208E -:1002E000000600208037000800220020282200207D -:1002F00028220020942D0020E0010008E0010008E1 -:10030000E0010008E00100082DE9F04F2DED108A12 -:10031000C1F80CD0C3689D46BDEC108ABDE8F08FD3 -:10032000002383F311882846A047002001F036FB04 -:10033000FEE701F0B7FA00DFFEE700001A4B0622E5 -:1003400070B51A70042200245A700F229C70DC7061 -:100350001C715C719C71DC711C725C729A72DC7233 -:1003600001F0C4FE064601F0E9FE054650B90F4B08 -:100370009E4217D001339E4241F2883412BF054697 -:1003800000240125002001F0BBFE0DB100F058F85B -:1003900000F016FD00F09EFB204600F0AFF800F0E4 -:1003A0004FF8F9E70446EDE728220020010007B0E6 -:1003B00008B500F061FBA0F120035842584108BD88 -:1003C00007B5054B02211B88ADF8043001A800F0E9 -:1003D00071FB03B05DF804FB5034000810B5202316 -:1003E00083F311881248C3680BB101F073FB00233B -:1003F000104A0F484FF47A7101F01AFB002383F37F -:1004000011880D4C236813B12368013B2360636896 -:1004100013B16368013B6360084B1B7833B96368B1 -:1004200023B9022000F03AFC3223636010BD00BF04 -:1004300034220020DD030008502300204822002041 -:1004400010B5254B254953F8042F013200D110BDBA -:100450008B42F8D1224C234B22689A423AD9224B44 -:100460009B6803F1006303F580339A4232D2002087 -:1004700000F04AFB1D4B0220187000F007FC1C4BDB -:100480001A6C00221A64196E1A66196E596C5A6435 -:10049000596E5A665A6E5A6942F080025A615A6918 -:1004A00022F080025A615A691A6942F000521A61B8 -:1004B0001A6922F000521A611B6972B60D4A0E4B7E -:1004C00013601B682268202181F311889D4683F305 -:1004D0000888104710BD00BFFCFF00081C00010881 -:1004E00004000108FFFF0008282200204822002005 -:1004F0000038024008ED00E0000001082DE9F04F4F -:1005000099B0B94D00902022FF2110A8AC6800F0EE -:10051000F9FBB64A01951378A3B9B5480121C36028 -:100520001170202383F31188C3680BB101F0D2FA54 -:100530000023B04AAE484FF47A7101F079FA0023F3 -:1005400083F31188009BAC4A03B11360AB4B009D51 -:10055000029300261E705660B2463746B14601200F -:1005600000F094FB002D00F02582A34B1B68002BAC -:1005700040F0208219B0BDE8F08F0220FFF718FF8D -:10058000002840F01082009B002E08BF1D469C4BA7 -:1005900002211B88ADF82C300BA800F08BFADEE7A7 -:1005A0004FF47A7000F068FAB0F10008EBDB02203B -:1005B000FFF7FEFE0028E6D008F1FF38B8F1040F7F -:1005C00000F2F381DFE808F0031E2124270018A8B9 -:1005D000052340F8343D042100F06CFA012303FAAE -:1005E00008F848EA0A0A5FFA8AFA4FF0000900F0B0 -:1005F000DDFB27B10AF00B030B2B08BF0025FFF72B -:10060000DFFEACE704217848E6E704217D48E3E714 -:1006100004217D48E0E74FF01C09484600F076FAD7 -:1006200009F104090B9004210BA800F043FAB9F179 -:100630002C0FF2D1D2E7002FA5D00AF00B030B2B21 -:10064000A1D10220FFF7B4FE804600289BD00120F4 -:100650006A4E00F059FA0220307000F017FB0027B4 -:100660005FFA87FB584600F05FFA054688B15846A6 -:1006700000F06AFA01370028F2D146460025634BA4 -:1006800002211B88ADF82C300BA800F013FA474666 -:1006900065E701230220337000F0EEFA2C46019B3F -:1006A0009B689C4206D2204600F030FA0130E4D12B -:1006B0000434F4E7029B00241C704F4B46465C60F8 -:1006C0004746254693E7002F3FF45DAF0AF00B0342 -:1006D0000B2B7FF458AF029B0220187000F0D6FA63 -:1006E000322000F0C9F9B0F1000BFFF64CAF1BF05F -:1006F00003087FF448AF019B996804EB0B028A4220 -:100700003FF641AFBBF5807F3FF63DAF404A0392D5 -:10071000D8450FDA4FF47A7000F0AEF904900499DE -:100720000029FFF630AF039A049908F8021008F187 -:100730000108ECE7C820FFF73BFE804600283FF4A5 -:1007400022AF1F2C11D8C4F120075F4528BF5F4698 -:1007500010AB24F003003A462D49184400F0A8FAE3 -:100760003A46FF212A4800F0CDFA4FEAAB03DAB24D -:1007700027490393204600F0CDFA074600283FF4AE -:100780007EAF039B04EB830431E70220FFF710FEEA -:1007900000283FF4F8AE00F0FDF900283FF4F3AE76 -:1007A0004FF000084346019A9268904532D2B8F162 -:1007B0001F0F12D8109A01320FD028F0030218A987 -:1007C0000A4452F8202C0B92184604220BA900F080 -:1007D00065FB08F104080346E5E74046039300F093 -:1007E00095F9039B0B90EFE7282200204C23002073 -:1007F00034220020DD03000850230020482200207E -:10080000523400082C2200203022002054340008EA -:100810004C22002018A8042140F84C3D00F04AF971 -:10082000E5E618A8002340F8343D642100F038F9CB -:1008300000287FF4A8AE0220FFF7BAFD00283FF49D -:10084000A2AE0B9800F092F918AB43F8480D0421C2 -:100850001846E3E718A8002340F8343D642100F06F -:100860001FF900287FF48FAE0220FFF7A1FD0028BA -:100870003FF489AE0B9800F087F918AB43F8440DAC -:10088000E5E70220FFF794FD00283FF47CAE00F07E -:1008900091F918AB43F8400DD9E70220FFF788FD26 -:1008A00000283FF470AE0BA9142000F089F98046AF -:1008B00018A8042140F83C8D00F0FCF841460BA834 -:1008C000ACE7322000F0D8F8B0F10008FFF65BAEDC -:1008D00018F0030F7FF457AE019A926808EB0903F2 -:1008E00093423FF650AE0220FFF762FD00283FF42E -:1008F0004AAE28F00308C844C1453FF478AE4846E4 -:1009000000F004F904210A900AA800F0D3F809F1D4 -:100910000409F1E74FF47A70FFF74AFD00283FF42D -:1009200032AE00F037F9002842D0109B01330BD0D3 -:10093000082210A9002000F0EDF9002838D020226C -:10094000FF2110A800F0DEF9FFF73AFD364801F06C -:100950002BF80FE6002F3FF416AE0AF00B030B2B1B -:100960007FF411AE18A8002340F8343D642100F054 -:1009700097F8804600287FF406AE0220FFF718FDA6 -:1009800000283FF400AE0390FFF71AFD41F28830D3 -:1009900001F00AF80B9800F03DFA00F007FA039B0B -:1009A00045461F46DBE5074621E64FF00009EAE52C -:1009B000B84664E6002000F05FF80490049B002B2A -:1009C000FFF6D0AD012000F057F9049B213B122B1C -:1009D0003FF6C5AD01A252F823F000BF7B05000829 -:1009E000A1050008370600085F0500085F0500083C -:1009F0005F050008C7060008C30800088B07000849 -:100A00002308000855080008830800085F0500084F -:100A10009B0800085F05000815090008EF0500089D -:100A20005F05000855090008A086010070B50F4B4E -:100A30000C4619780131C9B2012906460FD80C4875 -:100A400003681D6A4FF47A73534331462246A84720 -:100A5000844204D1074B00221A70012070BD4FF46C -:100A6000FA7000F0A1FF002070BD00BF002200203E -:100A7000C02500208423002007B502AB002203F824 -:100A8000012D012102461846FFF7D0FF20B19DF845 -:100A9000070003B05DF804FB4FF0FF30F9E70000FA -:100AA0000A4608B50421FFF7C1FF80F00100C0B27B -:100AB000404208BD30B4054C2368DD69044B0A464A -:100AC000AC460146204630BC604700BFC025002030 -:100AD000A086010070B501F00DFA094C094E208086 -:100AE000002530682388834208D901F0FDF9336876 -:100AF00005440133B5F5803F3360F2D370BD00BFCC -:100B0000862300205823002001F0A2BA00F10060E3 -:100B100000F580300068704700F10060920000F539 -:100B2000803001F02DBA0000054B1A68054B1B8878 -:100B30009B1A834202D9104401F0D6B900207047B5 -:100B4000582300208623002038B5074D0446286826 -:100B5000204401F0D1F928B928682044BDE8384084 -:100B600001F0E2B938BD00BF5823002010F00303A4 -:100B700008D1B0F5047F05D200F10050A0F508407F -:100B80000068704700207047014BC058704700BF95 -:100B9000107AFF1F064991F8243033B10023082250 -:100BA000086A81F82430FFF7B7BF0120704700BF03 -:100BB0005C230020014B1868704700BF002004E050 -:100BC00070B52A4B1C68C4F30B03240C63B140F2CC -:100BD0001342934231D040F2194293422FD040F257 -:100BE000214293422DD10323214A0C2505FB0323E7 -:100BF0005D6893F9082042F201039C4224D0B4F5C9 -:100C0000805F23D041F201039C4221D041F20303D3 -:100C10009C421FD041F207039C4208BF3122441E70 -:100C20000C44013D0B46A3421ED215F9016F581C1E -:100C300096B1034600F8016CF5E70123D4E70223DF -:100C4000D2E73F220B4DD6E73322E3E74122E1E72B -:100C50005A22E4E75922E2E72C2584421D7001D98B -:100C6000981C5A70401A70BD1846FBE7002004E03B -:100C70006434000858340008022802BF024B4FF4C5 -:100C800000129A61704700BF00040240022802BFB0 -:100C9000014B20229A61704700040240022801BFE4 -:100CA000024A536983F020035361704700040240F5 -:100CB00010B50023934203D0CC5CC4540133F9E750 -:100CC00010BD000030B5441E14F9010F0B4660B191 -:100CD00093F90050854201F1010106D11AB993F947 -:100CE0000020801A30BD013AEEE7002AF7D1104605 -:100CF00030BD000002460346981A13F9011B002973 -:100D0000FAD1704702440346934202D003F8011B14 -:100D1000FAE770472DE9F047234C94F82430054654 -:100D20008846174683BB2E46DFF87C90C7B394F8FD -:100D300024302BB92022FF2148462662FFF7E2FF2C -:100D400094F82400C0F10805BD4228BF3D465FFA73 -:100D500085FAAD0041462A4604EB8000FFF7A8FF64 -:100D600094F82430A7EB0A079A445FFA8AFABAF19A -:100D7000080F2E44A844FFB284F824A0D6D1FFF770 -:100D800009FF0028D2D108E0266A06EB8306B042AC -:100D9000CAD0FFF7FFFE0028C5D10020BDE8F087CC -:100DA0000120BDE8F08700BF5C230020024B1A78C9 -:100DB000024B1A70704700BF8423002000220020DD -:100DC00038B5104D104C284600F004F9214628464D -:100DD00000F02CF924680D48626DD2F8043843F015 -:100DE0000203C2F8043800F0DFFD0949204600F094 -:100DF00029FA626DD2F8043823F00203C2F80438ED -:100E000038BD00BFC02500205835000840420F0003 -:100E10008035000870470000FEE7000000B59BB079 -:100E2000EFF3098168226846FFF742FFEFF305837D -:100E3000044B9A6BDA6A9A6A9A6A9A6A9A6A9A6A06 -:100E40009B6AFEE700ED00E000B59BB0EFF309817F -:100E500068226846FFF72CFFEFF30583044B9A6B7B -:100E60009A6A9A6A9A6A9A6A9A6A9B6AFEE700BFC5 -:100E700000ED00E000B59BB0EFF309816822684601 -:100E8000FFF716FFEFF30583034B5A6B9A6A9A6AD2 -:100E90009A6A9A6A9B6AFEE700ED00E030B5084D59 -:100EA0000A4491420BD011F8013B09245840013CFF -:100EB000F7D040F300032B4083EA5000F7E730BD42 -:100EC0002083B8ED002304491A465A50C818083345 -:100ED000802B4260F9D17047882300200268436864 -:100EE0001143016003B118477047000013B5446B0C -:100EF000D4F894341A681178042915D1217C022978 -:100F000012D11979128901238B4013420CD101A906 -:100F100004F14C0001F022FFD4F89444019B2179A4 -:100F20000246206800F0DAF902B010BD143001F07A -:100F3000A5BE00004FF0FF33143001F09FBE00004B -:100F40004C3001F077BF00004FF0FF334C3001F020 -:100F500071BF0000143001F073BE00004FF0FF318C -:100F6000143001F06DBE00004C3001F043BF0000B2 -:100F70004FF0FF324C3001F03DBF0000D0F8942418 -:100F800038B5136819780429054601D0012038BD09 -:100F9000017C0229FAD112795C8901209040044039 -:100FA000F4D105F1140001F005FE02460028EDD051 -:100FB000D5F894544FF480732868697900F07CF96F -:100FC000204638BD406BFFF7D9BF000000207047B6 -:100FD000704700007FB5124B0360002343608360BD -:100FE000C360012502260F4B05740446029001934D -:100FF00000F18402294600964FF48073143001F00A -:10100000B5FD094B0193029400964FF4807304F5EB -:101010002372294604F14C0001F07CFE04B070BD3F -:10102000B4340008C50F0008ED0E00080B6820223C -:1010300082F311880A7903EB820290614A790932BE -:1010400043F822008A7912B103EB820398610223EC -:101050000374C0F89414002383F3118870470000D0 -:1010600038B5037F044613B190F85430ABB9201D56 -:1010700001250221FFF732FF04F1140025776FF0FC -:10108000010100F0B9FC84F8545004F14C006FF0F9 -:101090000101BDE8384000F0AFBC38BD10B50121FA -:1010A00004460430FFF71AFF0023237784F85430F6 -:1010B00010BD000038B504460025143001F06EFD67 -:1010C00004F14C00257701F03DFE201D84F85450BA -:1010D0000121FFF703FF2046BDE83840FFF74EBF70 -:1010E00090F8443003F06003202B19D190F845208C -:1010F000212A0AD0222A4FF000030ED0202A0FD135 -:10110000084A82630722C26304E0064B8363072315 -:10111000C36300230364012070478363C363F9E75B -:101120000020704701220020D0F8943437B51A68A7 -:101130001178042904461AD1017C022917D11979A2 -:10114000128901238B40134211D100F14C0528462E -:1011500001F0B8FE58B101A9284601F0FFFDD4F80E -:101160009444019B21790246206800F0B7F803B04F -:1011700030BD000000EB8103F7B59C6905460E46C3 -:10118000F4B1202383F3118805EB8607201D082185 -:10119000FFF7A4FEFB685B691B684C3413B1204663 -:1011A00001F0EAFD01A9204601F0D8FD024648B150 -:1011B000019B3146284600F091F8002383F3118803 -:1011C00003B0F0BDFB685A691268002AF5D01B8A8B -:1011D000013B1340F1D105F14402EAE7093138B58A -:1011E00050F82140DCB1202383F31188D4F89424F3 -:1011F0001368527903EB8203DB689B695D6845B134 -:1012000004216018FFF76AFE294604F1140001F07A -:10121000DBFC2046FFF7B2FE002383F3118838BDC4 -:101220007047000001F084B801230370002343607D -:10123000C36183620362C3624362036303814381C8 -:101240007047000038B50446202383F31188002539 -:101250004160C56005614561856101F079F802234F -:10126000237085F3118838BD70B500EB8103054606 -:101270005069DA600E46144618B110220021FFF7BB -:1012800041FDA06918B110220021FFF73BFD314656 -:101290002846BDE8704001F025B90000028902F03F -:1012A00001020281428902F00102428100220261B0 -:1012B0004261826101F0AAB9F0B400EB8104478970 -:1012C000E4680125A4698D403D43458123600023E6 -:1012D000A2606360F0BC01F0C5B90000F0B400EB9F -:1012E00081040789E468012564698D403D430581D7 -:1012F00023600023A2606360F0BC01F03FBA0000ED -:1013000070B50223002504460370A0F84C5080F805 -:101310004E5080F84F5005814581C560056145619B -:10132000856180F8345001F079F863681B6823B157 -:1013300029462046BDE87040184770BD037880F804 -:1013400050300523037043681B6810B504460BB189 -:101350000421984700232381638110BD436890F8DE -:1013600050201B6802700BB1052118477047000020 -:1013700090F8343070B5044613B1002380F834304F -:1013800004F14402204601F063F963689B6863BB83 -:1013900094F8445015F0600615D194F8453005F0E6 -:1013A0007F0545EA032540F202339D4200F00E819D -:1013B0005BD8022D00F0DC803FD8002D00F0878044 -:1013C000012D00F0CF800021204601F09BFB002181 -:1013D000204601F08DFB63681B6813B1062120468F -:1013E0009847062384F8343070BD2046984700287B -:1013F000CED094F84B2094F84A3043EA0223E26BB3 -:10140000934238BFE36394F94430E56B002B4FF00F -:10141000200380F2FD80002D00F0EC80092284F88A -:10142000342083F311880021E36BA26B2046FFF781 -:1014300055FF002383F3118870BDB5F5817F00F05F -:10144000B180B5F5407F49D0B5F5807FBBD194F828 -:101450004630012BB7D1B4F84C3023F00203A4F886 -:101460004C30A663E6632664C3E740F201639D4205 -:101470001ED8B5F5C06F3BD2B5F5A06FA3D1B4F8B7 -:101480004430B3F5A06F0ED194F8463084F84E3056 -:10149000204601F01BF863681B6813B10121204648 -:1014A0009847032323700023A363E3632364A0E727 -:1014B000B5F5106F32D040F602439D4252D0B5F5DB -:1014C000006F80D104F14F03A363012324E004F1F2 -:1014D0004C03A3630223E36325648AE794F8463050 -:1014E000012B7FF470AFB4F84C3043F00203B6E741 -:1014F00094F84920616894F848304D6894F8471092 -:1015000043EA0223204694F84620A84700283FF4E7 -:101510005AAF4368A3630368E363A4E72378042B0B -:1015200010D1202383F311882046FFF7B7FE86F3FE -:101530001188636884F84F601B68032121700BB128 -:101540002046984794F84630002BACD084F84F30B2 -:101550000423237063681B68002BA4D0022120465B -:101560009847A0E7374BA3630223E36300239DE77B -:1015700094F8481011F0800F204601F00F010ED0B2 -:1015800001F058F8012806D002287FF41CAF2E4B3A -:10159000A363E06367E72D4BA363E56363E701F0B3 -:1015A0003BF8EFE794F84630002B7FF40CAF94F84B -:1015B000483013F00F013FF476AF1A06204602D5EB -:1015C00001F0B4FA6FE701F0A7FA6CE794F846303F -:1015D000002B7FF4F8AE94F8483013F00F013FF47D -:1015E00062AF1B06204602D501F08CFA5BE701F0E2 -:1015F0007FFA58E7142284F8342083F311882B46AD -:101600002A4629462046FFF757FE85F3118870BD0C -:101610005DB1152284F8342083F311880021E36B37 -:10162000A26B2046FFF748FE03E70B2284F8342024 -:1016300083F311882B462A4629462046FFF74EFEA3 -:10164000E3E700BFE4340008DC340008E0340008BD -:1016500038B590F834300446152B29D8DFE803F06C -:101660003E28282828283E28280B293928282828D9 -:10167000282828283E3E90F84B1090F84A20C36B4B -:1016800042EA01229A4214D9C268128AB3FBF2F5E7 -:1016900002FB15356DB9202383F311882B462A46AA -:1016A0002946FFF71BFE85F311880A2384F834309E -:1016B00038BD142384F83430202383F311880023A9 -:1016C0001A4619462046FFF7F7FD002383F31188D9 -:1016D00038BD036C03B198470023E7E7002101F010 -:1016E00011FA0021204601F003FA63681B6813B168 -:1016F0000621204698470623D8E7000090F83420BA -:10170000152A38B5044622D80123934040F6416299 -:1017100013421DD113F480150FD19B0217D50B2353 -:1017200080F83430202383F311882B462A4629463B -:10173000FFF7D4FD85F3118838BDC3689B695B68EA -:101740002BB9036C03B19847002384F8343038BDBB -:10175000002101F0D7F90021204601F0C9F96368A2 -:101760001B6813B10621204698470623EDE70000C9 -:10177000024B00221B605B609A60704708240020C7 -:10178000002303748268054B1B6899689142FBD261 -:101790005A68036042601060586070470824002057 -:1017A00008B5202383F31188037C032B05D0042B79 -:1017B0000DD02BB983F3118808BD436900221A604C -:1017C0004FF0FF334361FFF7DBFF0023F2E790E8C0 -:1017D0000C001A6002685360F2E7000000230374F3 -:1017E0008268054B1B6899689142FBD85A68036070 -:1017F000426010605860704708240020054B19694A -:101800000874186802681A60536018610123037431 -:10181000FEF77ABD0824002030B54B1C87B0054682 -:101820000A4C10D023690A4A01A800F001F92846A1 -:10183000FFF7E4FF049B13B101A800F04BF9236903 -:10184000586907B030BDFFF7D9FFF8E7082400203A -:10185000A117000838B50C4D41612B6981689A6861 -:101860009142044603D8BDE83840FFF789BF1846C7 -:10187000FFF7B4FF01232C61014623742046BDE825 -:101880003840FEF741BD00BF08240020044B1A6811 -:101890001B6990689B68984294BF002001207047A4 -:1018A0000824002010B5084C236820691A682260BB -:1018B0005460012223611A74FFF790FF01462069EA -:1018C000BDE81040FEF720BD08240020FEE7000020 -:1018D00010B50C4CFFF74CFF00F09CF880220A4931 -:1018E000204600F021F8012344F8180C037400F09E -:1018F0003BFC002383F3118862B60448BDE8104026 -:1019000000F034B830240020E8340008F034000837 -:1019100000F01AB9034B59685A68521A9042FBD822 -:10192000704700BF001000E08260022202740022B3 -:10193000427470478368A3F17C0243F80C2C02695F -:1019400043F83C2C426943F8382C074A43F81C2CD6 -:10195000C26843F8102C022203F8082C002203F876 -:10196000072CA3F1180070472103000810B52023AD -:1019700083F31188FFF7DEFF00210446FFF76AFFBB -:10198000002383F31188204610BD0000024B1B6921 -:1019900058610F20FFF732BF08240020202383F373 -:1019A0001188FFF7F3BF000008B50146202383F339 -:1019B00011880820FFF730FF002383F3118808BD4A -:1019C00049B1064B42681B6918605A601360436056 -:1019D0000420FFF721BF4FF0FF307047082400209C -:1019E0000368984206D01A68026050605961184630 -:1019F000FFF7C6BE7047000038B504460D462068A4 -:101A0000844200D138BD036823605C604561FFF704 -:101A1000B7FEF4E7054B03F114025A619A614FF0E7 -:101A2000FF32DA6100221A62704700BF08240020EA -:101A3000F8B5274F0361C2600D46044601F076FAFF -:101A40003B46022D53F8142F294638BF02219A42F3 -:101A50003E461D460AD138627C61BC610844226062 -:101A60006260A160BDE8F84001F04EBAD7F820E00E -:101A7000A0EB0E035F181FD300279068834217D88E -:101A8000376AAA421F44376201D0C01A9060736956 -:101A90009A68914219D85A682360626014605C6049 -:101AA000A1609868411A99604FF0FF33F361F8BD67 -:101AB00097601B1A1268E0E793689F4203D20EEB0F -:101AC000070001F02FFA3946E1E7891A1B68DFE7C2 -:101AD0000824002038B51B4B01685A6990421D4606 -:101AE00003F114020CD04468216003680021934282 -:101AF0005C60C16025D09A6881680A449A6038BDEC -:101B000059614A605B6900219342C16003D1BDE81D -:101B1000384001F001BA9A6881680A449A602C6AD8 -:101B200001F004FA6A699268001B824209D9111A0D -:101B3000012998BF821C286ABDE83840104401F092 -:101B4000F1B938BD082400202DE9F84F204C0027BA -:101B5000656904F11406B84601F0E8F9236AA0EBC0 -:101B6000030AAB6853451DD84FF02009236AAA68C1 -:101B7000D5F80CB013442362AB68AAEB030A2B68B8 -:101B8000B3425E606361EF6001D101F0C5F988F393 -:101B900011882869D84789F311886569AB689A4527 -:101BA000E4D2D9E76369B34210D020629A68A2EB0D -:101BB0000A029A60226AAB68821A9B1A022B2CBF17 -:101BC000C0180230BDE8F84F01F0ACB9BDE8F88F9D -:101BD0000824002000207047FEE700007047000046 -:101BE0004FF0FF3070470000022906D0032906D0CD -:101BF0000129064818BF0020704705487047032A8E -:101C00009ABF044800EBC20000207047DC35000892 -:101C1000903500080822002070B59AB001AD064644 -:101C200008462946144600F095F82846FFF762F862 -:101C3000C0B2431C5B0086E8180023700323637066 -:101C4000002302341946DAB2904204F1020401D8AA -:101C50001AB070BDEA5C04F8022C04F8011C0133D0 -:101C6000F1E7000008B5202383F311880348FFF74C -:101C70005BFA002383F3118808BD00BFC025002054 -:101C800010B50446052916D8DFE801F0161503162D -:101C9000161D202383F311880E4A0121FFF7E4FA71 -:101CA00020460D4A0221FFF7DFFA0C48FFF702FA3F -:101CB000002383F3118810BD202383F31188074884 -:101CC000FFF7CEF9F4E7202383F311880348FFF7E9 -:101CD000E5F9EDE71035000834350008C02500208F -:101CE00038B50C4D0C4C0D492A4604F10800FFF79D -:101CF00093FF05F1CA0204F110000949FFF78CFFB8 -:101D000005F5CA7204F118000649BDE83840FFF72E -:101D100083BF00BF882A0020082200206035000809 -:101D20006A3500087535000870B5044608460D464A -:101D3000FEF7E0FFC6B22046013403780BB918461F -:101D400070BD32462946FEF7BDFF0028F3D10120C1 -:101D500070BD00002DE9F84F05460C46FEF7CAFF9E -:101D60002B49C6B22846FFF7DFFF08B10536F6B2A9 -:101D700028492846FFF7D8FF08B11036F6B2632E7F -:101D80000DD8DFF88C80DFF88C90234FDFF890A01F -:101D9000DFF890B02E7846B92670BDE8F88F294656 -:101DA0002046BDE8F84F01F04BBB252E2CD1072271 -:101DB00041462846FEF786FF58B9DBF8003023601D -:101DC000DBF804306360DBF80830A36007350C34BF -:101DD000E0E7082249462846FEF774FFA0B90F4BFA -:101DE000A21C13F8011F09095345C95D02F8021C22 -:101DF000197801F00F0102F10202C95D02F8031C1B -:101E0000EFD118340835C5E7267001350134C1E734 -:101E1000FC35000875350008113600080F7AFF1FE1 -:101E20001B7AFF1F04360008BFF34F8F024AD368A6 -:101E3000DB03FCD4704700BF003C024008B5094BEF -:101E40001B7873B9FFF7F0FF074B1A69002ABFBF71 -:101E5000064A5A6002F188325A601A6822F4806297 -:101E60001A6008BDE62C0020003C024023016745B3 -:101E700008B50B4B1B7893B9FFF7D6FF094B1A69CE -:101E800042F000421A611A6842F480521A601A68DD -:101E900022F480521A601A6842F480621A6008BD07 -:101EA000E62C0020003C02400B2870B513D80B4AEA -:101EB0000B4C137863B90B4E4FF0006144F82310BC -:101EC00056F8235001330C2B2944F7D1012313700A -:101ED00054F8200070BD002070BD00BF182D0020F8 -:101EE000E82C002024360008014B53F820007047EE -:101EF000243600080C2070470B2810B5044601D981 -:101F0000002010BDFFF7D0FF064B53F824301844D3 -:101F1000C21A0BB9012010BD12680132F0D1043B86 -:101F2000F6E700BF243600080B2810B5044621D878 -:101F3000FFF77AFFFFF782FF0F4AF323D360C30056 -:101F4000DBB243F4007343F002031361136943F4FB -:101F500080331361FFF768FFFFF7A6FF074B53F8C5 -:101F6000241000F0DDF8FFF783FF2046BDE81040A5 -:101F7000FFF7C2BF002010BD003C0240243600081D -:101F80002DE9F84312F00103154640D18218B2F151 -:101F9000016F3CD22C4B1B6813F0010337D02B4C44 -:101FA000FFF74CFFF323E360FFF73EFF40F201270A -:101FB000032D01D9830713D0244C0F46401A40F259 -:101FC0000118EB1B0B44012B00EB0706236924D8F7 -:101FD00023F001032361FFF74BFF0120BDE8F883E5 -:101FE000236923F44073236123693B43236151F840 -:101FF000046B0660BFF34F8FFFF716FF03689E4226 -:1020000008D0236923F001032361FFF731FF00208B -:10201000BDE8F883043D0430CAE723F4407323612C -:10202000236943EA08032361B94637F8023B33804A -:10203000BFF34F8FFFF7F8FE3688B9F80030B6B21D -:10204000B342BED0DDE700BF00380240003C024092 -:10205000084908B50B7828B153B9FFF7EFFE012303 -:102060000B7008BD23B1BDE808400870FFF700BF42 -:1020700008BD00BFE62C002010B50244064B043911 -:10208000D2B2904200D110BD441C00B253F82000DF -:1020900041F8040FE0B2F4E750280040104B30B58F -:1020A0001C6F240407D41C6F44F400741C671C6F5D -:1020B00044F400441C670B4C236843F48073236092 -:1020C0000244094B0439D2B2904200D130BD441CC5 -:1020D00000B251F8045F43F82050E0B2F4E700BFCB +:100250006F8F01F0FBFF01F0D7FF02F079FE4FF046 +:1002600055301F491B4A91423CBF41F8040BFAE745 +:100270001C49194A91423CBF41F8040BFAE71A495C +:100280001A4A1B4B9A423EBF51F8040B42F8040B2A +:10029000F8E700201749184A91423CBF41F8040B87 +:1002A000FAE701F0B5FF02F0A7FE144C144DAC4282 +:1002B00003DA54F8041B8847F9E700F041F8114CC1 +:1002C000114DAC4203DA54F8041B8847F9E701F0FA +:1002D0009DBF000000060020002200200000000852 +:1002E00000000020000600208037000800220020C7 +:1002F0004022002040220020A82D0020E00100081C +:10030000E0010008E0010008E00100082DE9F04FDD +:100310002DED108AC1F80CD0C3689D46BDEC108A43 +:10032000BDE8F08F002383F311882846A047002002 +:1003300001F018FBFEE701F093FA00DFFEE7000092 +:1003400038B501F0D3FE054601F0F6FE0446D8B9F3 +:100350000F4B9D421AD001339D4218BF044641F213 +:10036000883504BF01240025002001F0C9FE0CB12E +:1003700000F076F800F016FD00F0A4FB284600F02F +:10038000C3F800F06DF8F9E70025EDE70546EBE767 +:10039000010007B008B500F067FBA0F12003584248 +:1003A000584108BD07B541F21203022101A8ADF87A +:1003B000043000F077FB03B05DF804FB38B5202370 +:1003C00083F311881748C3680BB101F051FB164A3B +:1003D000144800234FF47A7101F00EFB002383F3DD +:1003E0001188124C236813B12368013B23606368B2 +:1003F00013B16368013B63600D4D2B7833B96368BB +:100400007BB9022000F048FC322363602B78032B79 +:1004100007D163682BB9022000F03EFC4FF47A73D9 +:10042000636038BD40220020BD0300085C2300202B +:1004300054220020084B187003280CD8DFE800F085 +:1004400008050208022000F01FBC022000F012BCC8 +:10045000024B00225A607047542200205C23002087 +:10046000244B254A10B51C461968013140D004338D +:100470009342F9D16268214B9A4239D9204B9B684B +:1004800003F1006303F580339A4231D2002000F07B +:1004900033FB0220FFF7CEFF1A4B1A6C00221A64BE +:1004A000196E1A66196E596C5A64596E5A665A6EEC +:1004B0005A6942F080025A615A6922F080025A61F8 +:1004C0005A691A6942F000521A611A6922F0005200 +:1004D0001A611B6972B64FF0E0232021C3F8084D62 +:1004E000D4E9003281F311889D4683F308881047D0 +:1004F00010BD00BF0000010820000108FFFF000838 +:1005000000220020003802402DE9F04F93B0AA4BA2 +:1005100000902022FF210AA89D6800F0EDFBA74A69 +:100520001378A3B9A6480121C3601170202383F377 +:100530001188C3680BB101F09BFAA24AA0480023BE +:100540004FF47A7101F058FA002383F31188009B6D +:1005500013B19D4B009A1A609C4A009C1378032BA0 +:100560001EBF00231370984A4FF0000A18BF536053 +:10057000D3465646D146012000F086FB24B1924B6B +:100580001B68002B00F01182002000F06DFA039030 +:10059000039B002BF2DB012000F06CFB039B213B53 +:1005A000162BE8D801A252F823F000BF0906000874 +:1005B00031060008C5060008770500087705000821 +:1005C000770500084F0700081F09000839080008D0 +:1005D0009B080008C3080008E90800087705000820 +:1005E000FB080008770500086D090008A906000847 +:1005F00077050008B109000815060008A9060008DB +:10060000770500089B0800080220FFF7C3FE0028BA +:1006100040F0F581009B0221BAF1000F08BF1C4693 +:1006200005A841F21233ADF8143000F03BFAA2E70E +:100630004FF47A7000F018FA071EEBDB0220FFF788 +:10064000A9FE0028E6D0013F052F00F2DA81DFE89D +:1006500007F0030A0D10133605230593042105A89E +:1006600000F020FA17E054480421F9E75848042123 +:10067000F6E758480421F3E74FF01C08404600F025 +:100680003DFA08F104080590042105A800F00AFAD3 +:10069000B8F12C0FF2D1012000FA07F747EA0B0B53 +:1006A0005FFA8BFB4FF0000900F072FB26B10BF0F4 +:1006B0000B030B2B08BF0024FFF774FE5BE74648D3 +:1006C0000421CDE7002EA5D00BF00B030B2BA1D1FD +:1006D0000220FFF75FFE074600289BD0012000F0B4 +:1006E0000BFA0220FFF7A6FE00265FFA86F84046C6 +:1006F00000F012FA044690B10021404600F01CFAC6 +:1007000001360028F1D1BA46044641F21213022103 +:1007100005A8ADF814303E4600F0C4F92BE70120DF +:10072000FFF788FE2546244B9B68AB4207D9284635 +:1007300000F0E4F9013040F067810435F3E7234B22 +:1007400000251D70204BBA465D603E46ACE7002E8A +:100750003FF460AF0BF00B030B2B7FF45BAF022079 +:10076000FFF768FE322000F07FF9B0F10008FFF6D5 +:1007700051AF18F003077FF44DAF0F4A926808EBB2 +:10078000050393423FF646AFB8F5807F3FF742AF8F +:10079000124B0193B84523DD4FF47A7000F064F9F1 +:1007A0000390039A002AFFF635AF019B039A03F8E2 +:1007B000012B0137EDE700BF002200205823002065 +:1007C00040220020BD0300085C23002054220020AA +:1007D00004220020082200200C22002058220020A1 +:1007E000C820FFF7D7FD074600283FF413AF1F2DA1 +:1007F00011D8C5F1200242450AAB25F0030028BFFD +:10080000424683490192184400F050FA019A804808 +:10081000FF2100F071FA4FEAA8037D490193C8F364 +:100820008702284600F070FA064600283FF46DAFB4 +:10083000019B05EB830537E70220FFF7ABFD00289E +:100840003FF4E8AE00F0A4F900283FF4E3AE00273F +:10085000B846704B9B68BB4218D91F2F11D80A9B12 +:1008600001330ED027F0030312AA134453F8203C9F +:1008700005934046042205A900F000FB043780469A +:10088000E7E7384600F03AF90590F2E7CDF8148032 +:10089000042105A800F006F906E70023642104A856 +:1008A000049300F0F5F800287FF4B4AE0220FFF7BF +:1008B00071FD00283FF4AEAE049800F051F90590A8 +:1008C000E6E70023642104A8049300F0E1F800287F +:1008D0007FF4A0AE0220FFF75DFD00283FF49AAE42 +:1008E000049800F04DF9EAE70220FFF753FD0028D5 +:1008F0003FF490AE00F05CF9E1E70220FFF74AFD1B +:1009000000283FF487AE05A9142000F057F9042110 +:100910000746049004A800F0C5F83946B9E732202C +:1009200000F0A2F8071EFFF675AEBB077FF472AEAB +:10093000384A926807EB090393423FF66BAE0220F8 +:10094000FFF728FD00283FF465AE27F003074F446A +:10095000B9453FF4A9AE484600F0D0F8042105900F +:1009600005A800F09FF809F10409F1E74FF47A7047 +:10097000FFF710FD00283FF44DAE00F009F9002804 +:1009800044D00A9B01330BD008220AA9002000F0B2 +:10099000BBF900283AD02022FF210AA800F0ACF9C8 +:1009A000FFF700FD1C4800F0E3FF13B0BDE8F08F37 +:1009B000002E3FF42FAE0BF00B030B2B7FF42AAE6F +:1009C0000023642105A8059300F062F8074600287B +:1009D0007FF420AE0220FFF7DDFC804600283FF4C4 +:1009E00019AEFFF7DFFC41F2883000F0C1FF059837 +:1009F00000F000FA464600F0CBF93C46BBE506465F +:100A000052E64FF0000905E6BA467EE637467CE638 +:100A10005822002000220020A086010070B50F4B54 +:100A20001B780133DBB2012B0C4611D80C4D296821 +:100A30004FF47A730E6AA2FB03320146224628461F +:100A4000B047844204D1074B00221A70012070BDC8 +:100A50004FF4FA7000F08CFF0020F8E7102200201D +:100A6000502500209023002007B5002302460121D5 +:100A70000DF107008DF80730FFF7D0FF20B19DF88A +:100A8000070003B05DF804FB4FF0FF30F9E700000A +:100A90000A4608B50421FFF7C1FF80F00100C0B28B +:100AA000404208BD30B4054C2368DD69044B0A465A +:100AB000AC460146204630BC604700BF50250020B0 +:100AC000A086010070B501F003FA094E094D30808F +:100AD000002428683388834208D901F0F3F92B6891 +:100AE00004440133B4F5803F2B60F2D370BD00BFE6 +:100AF000922300206423002001F0ACBA00F10060D2 +:100B000000F580300068704700F10060920000F549 +:100B1000803001F02BBA0000054B1A68054B1B888A +:100B20009B1A834202D9104401F0CCB900207047CF +:100B3000642300209223002038B5084D044629B1D3 +:100B400028682044BDE8384001F0DCB9286820441A +:100B500001F0C0F90028F3D038BD00BF64230020A5 +:100B600010F003030AD1B0F5047F05D200F1005064 +:100B7000A0F51040D0F80038184670470023FBE776 +:100B800000F10050A0F51040D0F8100A70470000A6 +:100B9000064991F8243033B10023086A81F82430E3 +:100BA0000822FFF7B1BF0120704700BF6823002073 +:100BB000014B1868704700BF002004E070B52A4B55 +:100BC0001B68C3F30B0204461B0C62B140F21340D6 +:100BD000824230D040F2194082422ED040F2214071 +:100BE00082422CD10322214D0C2000FB0252556879 +:100BF00042F20102934224D0B3F5805F23D041F248 +:100C00000102934221D041F2030293421FD041F2EC +:100C10000702934214BF3F233123013C0C44013DA2 +:100C20000A46A24215D215F9016F501C9EB100F878 +:100C3000016C0246F5E70122D5E70222D3E70C4D0D +:100C4000D6E73323E9E74123E7E75A23E5E75923CA +:100C5000E3E7104605E02C258442157001D9901C6D +:100C60005370401A70BD00BF002004E084340008B7 +:100C700058340008022802BF024B4FF400129A6158 +:100C8000704700BF00040240022802BF014B20222F +:100C90009A61704700040240022801BF024A53696A +:100CA00083F02003536170470004024010B5002315 +:100CB000934203D0CC5CC4540133F9E710BD00006B +:100CC00010B5013810F9013F3BB191F900409C4249 +:100CD00003D11AB10131013AF4E71AB191F90020B8 +:100CE000981A10BD1046FCE703460246D01A12F9C6 +:100CF000011B0029FAD1704702440346934202D0F7 +:100D000003F8011BFAE770472DE9F8431F4D14461D +:100D100095F824200746884652BBDFF870909CB3B4 +:100D200095F824302BB92022FF2148462F62FFF787 +:100D3000E3FF95F82400C0F10802A24228BF224632 +:100D4000D6B24146920005EB8000FFF7AFFF95F861 +:100D50002430A41B1E44F6B2082E17449044E4B27B +:100D600085F82460DBD1FFF713FF0028D7D108E016 +:100D70002B6A03EB82038342CFD0FFF709FF0028E1 +:100D8000CBD10020BDE8F8830120FBE768230020D9 +:100D9000024B1A78024B1A70704700BF9023002054 +:100DA0001022002010B50F4C0F4800F0F7F8214634 +:100DB0000D4800F01FF924680C48626DD2F8043821 +:100DC00043F00203C2F8043800F0D2FD084920467F +:100DD00000F016FA626DD2F8043823F00203C2F86C +:100DE000043810BD783500085025002040420F001F +:100DF000803500087047000000B59BB0EFF3098113 +:100E000068226846FFF752FFEFF30583044B9A6BA5 +:100E1000DA6A9A6A9A6A9A6A9A6A9A6A9B6AFEE790 +:100E200000ED00E000B59BB0EFF309816822684651 +:100E3000FFF73CFFEFF30583044B9A6B9A6A9A6ABB +:100E40009A6A9A6A9A6A9B6AFEE700BF00ED00E020 +:100E500000B59BB0EFF3098168226846FFF726FFD3 +:100E6000EFF30583034B5A6B9A6A9A6A9A6A9A6AF5 +:100E70009B6AFEE700ED00E0FEE7000030B5094D9B +:100E80000A4491420DD011F8013B5840082340F329 +:100E90000004013B2C4013F0FF0384EA5000F6D11C +:100EA000EFE730BD2083B8ED02684368114301606D +:100EB00003B118477047000013B5446BD4F894345D +:100EC0001A681178042915D1217C022912D11979C7 +:100ED000128901238B4013420CD101A904F14C006B +:100EE00001F03CFFD4F89444019B2179024620682C +:100EF00000F0CEF902B010BD143001F0BFBE00000A +:100F00004FF0FF33143001F0B9BE00004C3001F057 +:100F100091BF00004FF0FF334C3001F08BBF000059 +:100F2000143001F08DBE00004FF0FF31143001F09D +:100F300087BE00004C3001F05DBF00004FF0FF3273 +:100F40004C3001F057BF00000020704710B5D0F8BA +:100F500094341A6811780429044617D1017C0229B7 +:100F600014D15979528901238B4013420ED1143088 +:100F700001F020FE024648B1D4F894444FF4807347 +:100F800061792068BDE8104000F070B910BD000024 +:100F9000406BFFF7DBBF0000704700007FB5124BCE +:100FA000036000234360C0E90233012502260F4B92 +:100FB000057404460290019300F1840229460096CC +:100FC0004FF48073143001F0D1FD094B0294CDE948 +:100FD000006304F523724FF48073294604F14C003A +:100FE00001F098FE04B070BDB4340008910F000801 +:100FF000B90E00080B68202282F311880A7903EBEE +:10100000820290614A79093243F822008A7912B14A +:1010100003EB8203986102230374C0F89414002345 +:1010200083F311887047000038B5037F044613B17D +:1010300090F85430ABB9201D01250221FFF734FF91 +:1010400004F1140025776FF0010100F0B9FC84F879 +:10105000545004F14C006FF00101BDE8384000F03D +:10106000AFBC38BD10B5012104460430FFF71CFFAA +:101070000023237784F8543010BD000038B50446AF +:101080000025143001F08AFD04F14C00257701F0B1 +:1010900059FE201D84F854500121FFF705FF20461A +:1010A000BDE83840FFF752BF90F8443003F06003CA +:1010B000202B07D190F84520212A4FF0000303D8B8 +:1010C0001F2A06D800207047222AFBD1C0E90E3320 +:1010D00003E0034A82630722C2630364012070476E +:1010E0001122002037B5D0F894341A6811780429F9 +:1010F00004461AD1017C022917D1197912890123DA +:101100008B40134211D100F14C05284601F0DAFE64 +:1011100058B101A9284601F021FED4F89444019B5E +:1011200021790246206800F0B3F803B030BD00001A +:10113000F0B500EB810385B09E6904460D46FEB113 +:10114000202383F3118804EB8507301D0821FFF766 +:10115000ABFEFB685B691B6806F14C001BB101909C +:1011600001F00AFE019803A901F0F8FD024648B11A +:10117000039B2946204600F08BF8002383F3118857 +:1011800005B0F0BDFB685A691268002AF5D01B8AC9 +:10119000013B1340F1D104F14402EAE7093138B5CB +:1011A00050F82140DCB1202383F31188D4F8942433 +:1011B0001368527903EB8203DB689B695D6845B174 +:1011C00004216018FFF770FE294604F1140001F0B5 +:1011D000FBFC2046FFF7BAFE002383F3118838BDDD +:1011E0007047000001F0A8B8012303700023C0E994 +:1011F0000133C36183620362C36243620363704766 +:1012000038B50446202383F311880025C0E903552F +:10121000C0E90555416001F09FF80223237085F372 +:10122000118838BD70B500EB810305465069DA605E +:101230000E46144618B110220021FFF75DFDA0698B +:1012400018B110220021FFF757FD31462846BDE8AE +:10125000704001F04BB90000826802F00112826018 +:101260000022C0E90422826101F0CCB9F0B400EBA5 +:1012700081044789E4680125A4698D403D43458187 +:1012800023600023A2606360F0BC01F0E7B90000B6 +:10129000F0B400EB81040789E468012564698D409E +:1012A0003D43058123600023A2606360F0BC01F030 +:1012B00061BA000070B50223002504460370C0E93E +:1012C0000255C0E90455C564856180F8345001F0C9 +:1012D000A9F863681B6823B129462046BDE8704021 +:1012E000184770BD037880F85030052303704368B9 +:1012F0001B6810B504460BB1042198470023A36076 +:1013000010BD000090F85020436802701B680BB1BC +:10131000052118477047000070B590F83430044636 +:1013200013B1002380F8343004F14402204601F068 +:101330008BF963689B68B3B994F8443013F0600587 +:1013400035D00021204601F0DDFB0021204601F0D0 +:10135000CFFB63681B6813B106212046984706231C +:1013600084F8343070BD204698470028E4D0B4F8A3 +:101370004A30E26B9A4288BFE36394F94430E56BEC +:10138000002B4FF0200380F20381002D00F0F2804B +:10139000092284F8342083F311880021D4E90E2334 +:1013A0002046FFF775FF002383F31188DAE794F8EE +:1013B000452003F07F0343EA022340F202329342C6 +:1013C00000F0C58021D8B3F5807F48D00DD8012B1F +:1013D0003FD0022B00F09380002BB2D104F14C02DD +:1013E000A2630222E2632364C1E7B3F5817F00F0C8 +:1013F0009B80B3F5407FA4D194F84630012BA0D157 +:10140000B4F84C3043F0020332E0B3F5006F4DD036 +:1014100017D8B3F5A06F31D0A3F5C063012B90D8D6 +:10142000636894F846205E6894F84710B4F8483032 +:101430002046B047002884D04368A3630368E36371 +:101440001AE0B3F5106F36D040F6024293427FF4B3 +:1014500078AF5C4BA3630223E3630023C3E794F8F4 +:101460004630012B7FF46DAFB4F84C3023F002030B +:10147000C4E90E55A4F84C30256478E7B4F844303C +:10148000B3F5A06F0ED194F8463084F84E30204664 +:1014900001F020F863681B6813B1012120469847CA +:1014A000032323700023C4E90E339CE704F14F03A8 +:1014B000A3630123C3E72378042B10D1202383F3F4 +:1014C00011882046FFF7C8FE85F311880321636861 +:1014D00084F84F5021701B680BB12046984794F850 +:1014E0004630002BDED084F84F300423237063682D +:1014F0001B68002BD6D0022120469847D2E794F8EB +:1015000048301D0603F00F0120460AD501F08EF881 +:10151000012804D002287FF414AF2B4B9AE72B4B01 +:1015200098E701F075F8F3E794F84630002B7FF464 +:1015300008AF94F8483013F00F01B3D01A062046D4 +:1015400002D501F0F3FAADE701F0E6FAAAE794F864 +:101550004630002B7FF4F5AE94F8483013F00F01BD +:10156000A0D01B06204602D501F0CCFA9AE701F084 +:10157000BFFA97E7142284F8342083F311882B46AE +:101580002A4629462046FFF771FE85F31188E9E6D1 +:101590005DB1152284F8342083F311880021D4E949 +:1015A0000E232046FFF762FEFDE60B2284F834206E +:1015B00083F311882B462A4629462046FFF768FE0A +:1015C000E3E700BFE4340008DC340008E03400083E +:1015D00038B590F834300446002B3ED0063BDAB2E2 +:1015E0000F2A34D80F2B32D8DFE803F03731310817 +:1015F000223231313131313131313737C56BB0F8C9 +:101600004A309D4214D2C3681B8AB5FBF3F203FB38 +:1016100012556DB9202383F311882B462A4629469B +:10162000FFF736FE85F311880A2384F834300EE084 +:10163000142384F83430202383F3118800231A46BE +:1016400019462046FFF712FE002383F3118838BDA8 +:10165000036C03B198470023E7E70021204601F01F +:1016600051FA0021204601F043FA63681B6813B168 +:101670000621204698470623D7E7000010B590F8CA +:101680003430142B044629D017D8062B05D001D8A6 +:101690001BB110BD093B022BFBD80021204601F0F5 +:1016A00031FA0021204601F023FA63681B6813B168 +:1016B000062120469847062319E0152BE9D10B2374 +:1016C00080F83430202383F3118800231A4619460A +:1016D000FFF7DEFD002383F31188DAE7C3689B6917 +:1016E0005B68002BD5D1036C03B19847002384F8C5 +:1016F0003430CEE7024B0022C3E900339A607047D2 +:1017000094230020002303748268054B1B689968AA +:101710009142FBD25A680360426010605860704783 +:101720009423002008B5202383F31188037C032B26 +:1017300005D0042B0DD02BB983F3118808BD436964 +:1017400000221A604FF0FF334361FFF7DBFF0023F5 +:10175000F2E7D0E9003213605A60F3E70023037424 +:101760008268054B1B6899689142FBD85A680360F0 +:10177000426010605860704794230020054B19693F +:101780000874186802681A605360186101230374B2 +:10179000FEF7BCBD9423002030B54B1C0B4D87B029 +:1017A000044610D02B690A4A01A800F025F920460A +:1017B000FFF7E4FF049B13B101A800F059F92B696E +:1017C000586907B030BDFFF7D9FFF8E79423002030 +:1017D0002517000838B50C4D41612B6981689A685E +:1017E0009142044603D8BDE83840FFF78BBF184646 +:1017F000FFF7B4FF01232C61014623742046BDE8A6 +:101800003840FEF783BD00BF94230020044B1A68C4 +:101810001B6990689B68984294BF00200120704724 +:101820009423002010B5084C236820691A682260B0 +:101830005460012223611A74FFF790FF014620696A +:10184000BDE81040FEF762BD9423002008B5FFF705 +:10185000DDFF18B1BDE80840FFF7E4BF08BD000098 +:10186000FFF7E0BFFEE7000010B50C4CFFF742FFAA +:1018700000F0B4F80A498022204600F03BF801232A +:1018800044F8180C037400F071FC002383F31188F2 +:1018900062B60448BDE8104000F04CB8BC230020FC +:1018A000E8340008F834000800F01CB9EFF31180A8 +:1018B00020B9EFF30583202282F3118870470000DE +:1018C00010B530B9EFF30584C4F3080414B180F304 +:1018D000118810BDFFF7BAFF84F31188F9E7000003 +:1018E000034A516853685B1A9842FBD8704700BF9F +:1018F000001000E082600222028270478368A3F138 +:101900007C0243F80C2C026943F83C2C426943F8F2 +:10191000382C074A43F81C2CC26843F8102C0222CA +:1019200003F8082C002203F8072CA3F118007047D5 +:101930002503000810B5202383F31188FFF7DEFF8D +:1019400000210446FFF746FF002383F31188204659 +:1019500010BD0000024B1B6958610F20FFF70EBF3E +:1019600094230020202383F31188FFF7F3BF0000A6 +:1019700008B50146202383F311880820FFF70CFFE8 +:10198000002383F3118808BD49B1064B42681B69E7 +:1019900018605A60136043600420FFF7FDBE4FF0EB +:1019A000FF307047942300200368984206D01A68DD +:1019B0000260506059611846FFF7A4BE70470000EE +:1019C00038B504460D462068844200D138BD03680E +:1019D00023605C604561FFF795FEF4E7054B03F17A +:1019E0001402C3E905224FF0FF310022C3E90712B8 +:1019F000704700BF9423002070B51C4EC0E903233C +:101A000005460C4601F090FA334653F8142F9A42DB +:101A10000DD13062C5E901242A600A2C2CBF0019BF +:101A20000A30C6E90555BDE8704001F06BBA316A6D +:101A3000431AE31838BF1C469368A34202D9081919 +:101A400001F06EFA73699A6894420CD85A68AC60D7 +:101A50002B606A6015609A685D60121B9A604FF097 +:101A6000FF33F36170BD1B68A41AECE794230020D8 +:101A700038B51B4C636998420DD0D0E90032136031 +:101A80005A6000228168C2609A680A449A604FF0E6 +:101A9000FF33E36138BD2246036842F8143F00215A +:101AA00093425A60C16003D1BDE8384001F032BAB8 +:101AB0009A688168256A0A449A6001F035FA636978 +:101AC0009A68411B8A42E5D9AB181D1A092D206A74 +:101AD00098BF01F10A02BDE83840104401F020BA75 +:101AE000942300202DE9F041184C002704F114063E +:101AF000656901F019FA236AAA68C11A8A4215D8E1 +:101B000013442362D5E9003213605A606369D5F843 +:101B10000C80EF60B34201D101F0FCF987F311882A +:101B20002869C047202383F31188E1E76169B14246 +:101B300009D013441B1ABDE8F0410A2B2CBFC01872 +:101B40000A3001F0EDB9BDE8F08100BF9423002018 +:101B500000207047FEE70000704700004FF0FF30A4 +:101B60007047000002290CD0032904D0012907483E +:101B700018BF00207047032A05D8054800EBC200B3 +:101B80007047044870470020704700BFDC350008EC +:101B9000202200209035000870B59AB0054608460E +:101BA00001A9144600F0C2F801A8FFF79DF8431CF4 +:101BB0005B00C5E900340022237003236370C6B2C2 +:101BC00001AB02341046D1B28E4204F1020401D8B6 +:101BD0001AB070BD13F8011B04F8021C04F8010CC4 +:101BE0000132F0E708B5202383F311880348FFF79B +:101BF00079FA002383F3118808BD00BF5025002027 +:101C000090F8443003F01F02012A07D190F84520D4 +:101C10000B2A03D10023C0E90E3315E003F0600363 +:101C2000202B08D1B0F848302BB990F84520212A54 +:101C300003D81F2A04D8FFF737BA222AEBD0FAE7D5 +:101C4000034A82630722C26303640120704700BF16 +:101C50001822002007B5052917D8DFE801F019166A +:101C600003191920202383F31188104A01900121C0 +:101C7000FFF7D8FA01980E4A0221FFF7D3FA0D4870 +:101C8000FFF7FCF9002383F3118803B05DF804FB30 +:101C9000202383F311880748FFF7C6F9F2E72023D2 +:101CA00083F311880348FFF7DDF9EBE730350008CF +:101CB000543500085025002038B50C4D0C4C0D490A +:101CC0002A4604F10800FFF767FF05F1CA0204F194 +:101CD00010000949FFF760FF05F5CA7204F118000A +:101CE0000649BDE83840FFF757BF00BF182A00205B +:101CF00020220020103500081A350008253500087C +:101D000070B5044608460D46FEF7EEFFC6B2204603 +:101D1000013403780BB9184670BD32462946FEF7E8 +:101D2000CFFF0028F3D10120F6E700002DE9F84F9E +:101D300005460C46FEF7D8FF2B49C6B22846FFF7EA +:101D4000DFFF08B10536F6B228492846FFF7D8FF6D +:101D500008B11036F6B2632E0DD8DFF88C80DFF8AC +:101D60008C90234FDFF890A0DFF890B02E7846B922 +:101D70002670BDE8F88F29462046BDE8F84F01F0EF +:101D800063BB252E2BD1072241462846FEF798FF3C +:101D900058B9DBF800302360DBF804306360DBF80F +:101DA0000830A36007350C34E0E70822494628468E +:101DB000FEF786FF98B90F4BA21C19780909023269 +:101DC000C95D02F8041C13F8011B01F00F01534513 +:101DD000C95D02F8031CF0D118340835C6E704F8D1 +:101DE000016B0135C2E700BFFC350008253500084E +:101DF00011360008107AFF1F1C7AFF1F04360008F6 +:101E0000BFF34F8F024AD368DB03FCD4704700BF97 +:101E1000003C024008B5094B1B7873B9FFF7F0FF8F +:101E2000074B1A69002ABFBF064A5A6002F188327E +:101E30005A601A6822F480621A6008BD762C00206D +:101E4000003C02402301674508B50B4B1B7893B952 +:101E5000FFF7D6FF094B1A6942F000421A611A686F +:101E600042F480521A601A6822F480521A601A688A +:101E700042F480621A6008BD762C0020003C0240CB +:101E80000B28F0B516D80C4C0C4923787BB90C4DB7 +:101E90000E460C234FF0006255F8047B46F8042BE5 +:101EA000013B13F0FF033A44F6D10123237051F8AC +:101EB0002000F0BD0020FCE7A82C0020782C00209A +:101EC00024360008014B53F82000704724360008E0 +:101ED0000C2070470B2810B5044601D9002010BD16 +:101EE000FFF7CEFF064B53F824301844C21A0BB943 +:101EF0000120F4E712680132F0D1043BF6E700BF9D +:101F0000243600080B2838B5044628D8FFF7CEFC45 +:101F1000FFF776FFFFF77EFF124AF323D360E3005B +:101F2000DBB243F4007343F002031361136943F41B +:101F30008033136105462046FFF762FFFFF7A0FFDD +:101F4000094B53F8241000F0E9F82846FFF77CFF0E +:101F5000FFF7B6FC2046BDE83840FFF7BBBF0020C6 +:101F600038BD00BF003C02402436000812F00103D7 +:101F70002DE9F04105460E4614464BD18218B2F1C8 +:101F8000016F61D8314B1B6813F001035CD0304FF7 +:101F9000FFF78CFCFFF73EFFF323FB60FFF730FFFA +:101FA000314640F20128032C18D824F00104284EB1 +:101FB0000C446D1A40F20118A142336905EB010788 +:101FC0002AD123F001033361FFF73EFFFFF778FCCE +:101FD0000120BDE8F081043C0435E4E7AB07E4D11F +:101FE0003B6923F440733B613B6943EA08033B616F +:101FF00051F8046B2E60BFF34F8FFFF701FF2B6882 +:102000009E42E8D03B6923F001033B61FFF71CFFD0 +:10201000FFF756FC0020DCE723F44073336133699B +:1020200043EA080333610B883B80BFF34F8FFFF710 +:10203000E7FE3F8831F8023BBFB2BB42BCD03369F8 +:1020400023F001033361E1E71846C2E7003802409C +:10205000003C0240084908B50B7828B11BB9FFF7CE +:10206000D9FE01230B7008BD002BFCD0BDE8084051 +:102070000870FFF7E9BE00BF762C002010B50244BF +:10208000064BD2B2904200D110BD441C00B253F8AE +:10209000200041F8040BE0B2F4E700BF50280040F4 +:1020A0000F4B30B51C6F240407D41C6F44F400742C +:1020B0001C671C6F44F400441C670A4C236843F4FB +:1020C000807323600244084BD2B2904200D130BDED +:1020D000441C00B251F8045B43F82050E0B2F4E72E :1020E00000380240007000405028004007B501222F -:1020F00001A90020FFF7C0FF019803B05DF804FBC1 -:1021000013B50446FFF7F2FFA04206D002A9012250 -:1021100041F8044D0020FFF7C1FF02B010BD0000E0 -:1021200070470000034B1B689B0042BF024B01221B -:102130001A70704774380240192D0020014B18782E -:10214000704700BF192D0020EFF3098305494A6845 -:1021500022F001024A60683383F30988002383F385 -:102160001188704730EF00E0202080F3118862B6BC -:102170000B4B0C4AD96821F4E0610904090C0A43AD -:102180000949DA60CA6842F08072CA6007490A6881 -:1021900042F001020A601022DA7783F822007047C9 -:1021A00000ED00E00003FA05F0ED00E0001000E0B3 -:1021B00010B5202383F311880E4B5B6813F4006382 -:1021C00014D0F1EE103AEFF30984683C4FF08073BD -:1021D000E361094BDB68236684F30988FFF756FB4C -:1021E00010B1064BA36110BD054BFBE783F31188CB -:1021F00010BD00BF00ED00E030EF00E03303000849 -:102200003603000870470000FEE70000084A094B4B -:1022100009498B4204D3094A0021934205D37047F0 -:1022200052F8040F43F8040BF3E743F8041BF4E7F8 -:10223000A4370008942D0020942D0020942D002018 -:10224000836D70B5446D9E6800214FF0FF354A01E3 -:10225000A3180131D3F800090028BEBFD3F8000944 -:1022600040F08040C3F80009D3F8000B0028BEBF3F -:10227000D3F8000B40F08040C3F8000BA3188E4247 -:10228000C3F80859C3F8085BE1D24FF00113C4F852 -:102290001C3870BD890141F02001016103699B0672 -:1022A000FCD41220FFF736BB204B03EB80022DE954 -:1022B000F047D2F80CE05D6DDEF81420461CD2F831 -:1022C00000C005EB063605EB4018516861450BD39D -:1022D000D5F83428012303FA00F022EA0000C5F8FB -:1022E00034081846BDE8F087BEF81040ACEB010397 -:1022F000A34228BF2346D8F81849A4B2B3EB840FF1 -:1023000010D894681F46A4F1040959F804AFC6F820 -:1023100000A0042F01D9043FF7E71C440B4494604C -:102320005360D2E70020BDE8F08700BF1C2D0020DD -:1023300010B5054C2046FEF777FF4FF0A0436365CC -:10234000024BA36510BD00BF1C2D0020783600088D -:102350000378012B70B5054650D12A4B446D984245 -:102360001BD1294B5A6B42F080025A635A6D42F0DE -:1023700080025A655A6D5A6942F080025A615A6960 -:1023800022F080025A610E2143205B6900F0D8FBE5 -:102390001E4BE3601E4BC4F800380023C4F8003E17 -:1023A000C02323606E6D4FF40413A3633369002BC5 -:1023B000FCDA012333610C20FFF7ACFA3369DB0749 -:1023C000FCD41220FFF7A6FA3369002BFCDA0026B2 -:1023D000A6602846FFF734FF6B68C4F81068DB6816 -:1023E000C4F81468C4F81C684BB90A4BA3614FF0D9 -:1023F000FF336361A36843F00103A36070BD064B24 -:10240000F4E700BF1C2D00200038024040140040BB -:1024100003002002003C30C0083C30C0F8B5446DD9 -:10242000054600212046FFF735FFA96D00234FF038 -:1024300001128F68C4F834384FF00066C4F81C28C5 -:102440004FF0FF3004EB431201339F42C2F80069A2 -:10245000C2F8006BC2F80809C2F8080BF2D20B6888 -:102460006A6DEB65636210231361166916F010063E -:10247000FBD11220FFF74EFAD4F8003823F4FE63A4 -:10248000C4F80038A36943F4402343F01003A36168 -:102490000923C4F81038C4F814380A4BEB604FF025 -:1024A000C043C4F8103B084BC4F8003BC4F81069A3 -:1024B000C4F80039EB6D03F1100243F48013EA65B0 -:1024C000A362F8BD5436000840800010426D90F8B9 -:1024D0004E10D2F8003823F4FE6343EA0113C2F829 -:1024E000003870472DE9F0410EB200EB86080D462A -:1024F000D8F80C100F6807F00303022B50D0032B01 -:1025000050D03D4A3D4F012B18BF1746446D4FEA4E -:10251000451E04EB0E030022C3F8102B8A6905F157 -:10252000100C002A40D04A8A05F158035B013A4357 -:10253000E2500123D4F81C2803FA0CF31343A644F9 -:102540004A69C4F81C380023CEF8103905F13F035E -:10255000002A39D00A8A898B9208012988BF4A4308 -:10256000C16D04EB8303561841EA0242C665294651 -:102570005A602046FFF78EFED8F80C301B8A43EADB -:1025800085531F4305F148035B01E7500123D4F84D -:102590001C2803FA05F51543C4F81C58BDE8F08162 -:1025A000174FB3E7174FB1E704EB4613D3F8002BEF -:1025B00022F40042C3F8002BD4F81C28012303FAAC -:1025C0000CF322EA0303BAE704EB83030E4A5A60D2 -:1025D00004EB461629462046FFF75CFED6F8003984 -:1025E00023F40043C6F80039D4F81C38012202FA5B -:1025F00005F523EA0505CFE70080001000800410F0 -:102600000080081000800C1000040002826D126827 -:10261000C265FFF715BE00005831436D49015B5894 -:1026200013F4004004D013F4001F14BF0120022053 -:10263000704700004831436D49015B5813F4004076 -:1026400004D013F4001F14BF0120022070470000C3 -:1026500000EB8101CB68196A0B6813604B6853600B -:102660007047000000EB810330B5DD68AA6913688C -:10267000D36019B9402B84BF402313606B8A146860 -:10268000426D1C44013CB4FBF3F46343033323F079 -:10269000030302EB411043EAC44343F0C043C0F8D4 -:1026A000103B2B6803F00303012B09B20ED1D2F8C3 -:1026B000083802EB411013F4807FD0F8003B14BFC0 -:1026C00043F0805343F00053C0F8003B02EB41124B -:1026D000D2F8003B43F00443C2F8003B30BD000099 -:1026E0002DE9F041244D6E6D06EB40130446D3F8FE -:1026F000087BC3F8087B38070AD5D6F814381907C1 -:1027000006D505EB84032146DB6828465B689847BD -:10271000FA072FD5D6F81438DB072BD505EB840341 -:10272000D968CCB98B69488A5E68B6FBF0F200FBC9 -:1027300012628AB91868DA6890420DD2121A83E8D8 -:102740001400202383F311880B482146FFF78AFFEA -:1027500084F31188BDE8F081012303FA04F26B8948 -:1027600023EA02036B81CB6823B121460248BDE80E -:10277000F0411847BDE8F0811C2D002000EB8103DB -:1027800070B5DD68436D6C692668E6604A0156BB2A -:102790001A444FF40020C2F810092A6802F003021C -:1027A000012A0AB20ED1D3F8080803EB421410F440 -:1027B000807FD4F8000914BF40F0805040F00050F2 -:1027C000C4F8000903EB4212D2F8000940F00440BB -:1027D000C2F80009D3F83408012202FA01F10143DA -:1027E000C3F8341870BD19B9402E84BF4020206052 -:1027F00020682E8A841940F00050013C1A44B4FB32 -:10280000F6F440EAC440C6E7F8B504461E48456DF4 -:1028100005EB4413D3F80869C3F80869F10717D525 -:10282000D5F81038DA0713D500EB8403D9684B6963 -:102830001F68DA68974218D2D21B00271A605F60BF -:10284000202383F311882146FFF798FF87F311882F -:10285000330617D5D5F834280123A340134211D0ED -:102860002046BDE8F840FFF71FBD012303FA04F23C -:10287000038923EA020303818B68002BE8D02146F9 -:102880009847E5E7F8BD00BF1C2D002097482DE9CB -:10289000F84F456D6E69AB691E4016F4805F6E613E -:1028A000044605D0FEF72CFDBDE8F84FFFF780BCCD -:1028B000002E12DAD5F8003E8C489B071EBFD5F8D3 -:1028C000003E23F00303C5F8003ED5F8043823F09A -:1028D0000103C5F80438FEF741FD370505D58348E7 -:1028E000FFF7AEFC8148FEF729FDB0040CD5D5F802 -:1028F000083813F0060FEB6823F470530CBF43F451 -:10290000105343F4A053EB60310704D56368DB68D0 -:102910000BB176489847F2025AD4B3020CD5D4F8DA -:102920005480DFF8C8A100274FF00109A36D9B6810 -:10293000F9B28B4280F08780F70619D5616D0A6A7B -:10294000C2F30A1702F00F0302F4F012B2F5802F5F -:1029500000F0A180B2F5402F0AD104EB830301F50A -:102960008051DB68186A00231A469F4240F0878036 -:102970003003D5F8184813D5E10302D50020FFF73E -:10298000AFFEA20302D50120FFF7AAFE630302D522 -:102990000220FFF7A5FE270302D50320FFF7A0FEC4 -:1029A000750381D5E00702D50020FFF72DFFA107B1 -:1029B00002D50120FFF728FF620702D50220FFF7AA -:1029C00023FF23077FF570AF0320FFF71DFF6BE7A1 -:1029D000D4F85480DFF814A100274FF00109A36D4B -:1029E0009B685FFA87FB5B4597D308EB4B13D3F8E3 -:1029F000002902F44022B2F5802F22D1D3F8002919 -:102A0000002A1EDAD3F8002942F09042C3F80029C8 -:102A1000D3F80029002AFBDB5946606DFFF73AFC2A -:102A2000228909FA0BF322EA0303238104EB8B03C7 -:102A3000DB689B6813B15946504698475846FFF7E4 -:102A400033FC0137CBE708EB4112D2F8003B03F42B -:102A50004023B3F5802F10D1D2F8003B002B0CDAC5 -:102A6000628909FA01F322EA0303638104EB81031B -:102A7000DB68DB680BB150469847013756E79C0787 -:102A800008BF0A68072B98BF027003F101039CBFBF -:102A9000120A013069E7023304EB830201F5805129 -:102AA000526890690268D0F808C04068A2EB000E36 -:102AB0000022104697420AD104EB830463689B69A5 -:102AC0009A683A449A605A6817445F6050E712F077 -:102AD000030F08BF0868964588BF8CF8000002F114 -:102AE000010284BF000A0CF1010CE3E71C2D002059 +:1020F00001A90020FFF7C2FF019803B05DF804FBBF +:1021000013B50446FFF7F2FFA04205D0012201A952 +:1021100000200194FFF7C4FF02B010BD704700001B +:10212000034B1A681AB9034AD2F874281A60704728 +:10213000AC2C00200030024008B5FFF7F1FF024B45 +:102140001868C0F3407008BDAC2C0020EFF3098381 +:1021500005494A6B22F001024A63683383F3098818 +:10216000002383F31188704700EF00E0202080F304 +:10217000118862B60C4B0D4AD96821F4E06109045C +:10218000090C0A43DA60D3F8FC20094942F0807256 +:10219000C3F8FC200A6842F001020A601022DA77D4 +:1021A00083F82200704700BF00ED00E00003FA054D +:1021B000001000E010B5202383F311880E4B5B68FC +:1021C00013F4006314D0F1EE103AEFF30984683C85 +:1021D0004FF08073E361094BDB6B236684F309885E +:1021E000FFF714FB10B1064BA36110BD054BFBE7D5 +:1021F00083F31188F9E700BF00ED00E000EF00E095 +:10220000370300083A03000870470000FEE70000AB +:102210000A4B0B480B4A90420BD30B4BDA1C121A99 +:10222000C11E22F003028B4238BF00220021FEF7BC +:1022300063BD53F8041B40F8041BECE7C0370008EB +:10224000A82D0020A82D0020A82D002070470000F8 +:1022500070B5D0E915439E6800224FF0FF3504EBBE +:1022600042135101D3F800090028BEBFD3F800097A +:1022700040F08040C3F80009D3F8000B0028BEBF2F +:10228000D3F8000B40F08040C3F8000B0132631814 +:102290009642C3F80859C3F8085BE0D24FF0011327 +:1022A000C4F81C3870BD00001D4B03EB80022DE903 +:1022B000F043D2F80CC05D6DDCF81420461CD2F857 +:1022C00000E005EB063605EB4018516871450AD36E +:1022D000D5F83438012202FA00F023EA0000C5F8EC +:1022E0003408BDE8F083BCF81040AEEB0103A34214 +:1022F00028BF2346D8F81849A4B2B3EB840FF0D80E +:102300009468A4F1040959F8047F3760A4EB090725 +:102310001F44042FF7D81C440B4494605360D4E747 +:10232000B02C0020890141F02001016103699B0666 +:10233000FCD41220FFF7D4BA10B5054C2046FEF7A6 +:1023400053FF4FF0A0436365024BA36510BD00BF70 +:10235000B02C00207836000870B50378012B0546B4 +:1023600050D12A4B446D98421BD1294B5A6B42F0F5 +:1023700080025A635A6D42F080025A655A6D5A695A +:1023800042F080025A615A6922F080025A610E219D +:1023900043205B6900F0D4FB1E4BE3601E4BC4F886 +:1023A00000380023C4F8003EC02323606E6D4FF454 +:1023B0000413A3633369002BFCDA012333610C207F +:1023C000FFF78EFA3369DB07FCD41220FFF788FA97 +:1023D0003369002BFCDA0026A6602846FFF738FF99 +:1023E0006B68C4F81068DB68C4F81468C4F81C682B +:1023F0004BB90A4BA3614FF0FF336361A36843F00D +:102400000103A36070BD064BF4E700BFB02C0020B1 +:10241000003802404014004003002002003C30C05D +:10242000083C30C0F8B5446D054600212046FFF752 +:1024300079FFA96D00234FF001128F68C4F834387A +:102440004FF00066C4F81C284FF0FF3004EB431235 +:1024500001339F42C2F80069C2F8006BC2F8080954 +:10246000C2F8080BF2D20B686A6DEB656362102349 +:102470001361166916F01006FBD11220FFF730FA2F +:10248000D4F8003823F4FE63C4F80038A36943F499 +:10249000402343F01003A3610923C4F81038C4F8A3 +:1024A00014380A4BEB604FF0C043C4F8103B084BA4 +:1024B000C4F8003BC4F81069C4F80039EB6D03F1AF +:1024C000100243F48013EA65A362F8BD5436000895 +:1024D00040800010426D90F84E10D2F8003823F47E +:1024E000FE6343EA0113C2F8003870472DE9F84350 +:1024F00000EB8103456DDA68166806F00306731E6B +:10250000022B05EB41130C4680460FFA81F94FEA86 +:1025100041104FF00001C3F8101B4FF0010104F10E +:10252000100398BFB60401FA03F391698EBF334ECE +:1025300006F1805606F5004600293AD0578A04F184 +:102540005801490137436F50D5F81C180B43C5F8A3 +:102550001C382B180021C3F8101953690127611E7C +:10256000A7409BB3138A928B9B08012A88BF5343D1 +:10257000D8F85C20981842EA034301F1400205EBC9 +:102580008202C8F85C00214653602846FFF7CAFE65 +:1025900008EB8900C3681B8A43EA8453483464010A +:1025A0001E432E51D5F81C381F43C5F81C78BDE8D2 +:1025B000F88305EB4917D7F8001B21F40041C7F851 +:1025C000001BD5F81C1821EA0303C0E704F13F0300 +:1025D00005EB83030A4A5A6028462146FFF7A2FE0C +:1025E00005EB4910D0F8003923F40043C0F8003956 +:1025F000D5F81C3823EA0707D7E700BF0080001092 +:1026000000040002826D1268C265FFF721BE00005F +:102610005831436D49015B5813F4004004D013F462 +:10262000001F0CBF02200120704700004831436D9D +:1026300049015B5813F4004004D013F4001F0CBF91 +:10264000022001207047000000EB8101CB68196A6D +:102650000B6813604B6853607047000000EB810308 +:1026600030B5DD68AA691368D36019B9402B84BFFF +:10267000402313606B8A1468426D1C44013CB4FB18 +:10268000F3F46343033323F0030302EB411043EA03 +:10269000C44343F0C043C0F8103B2B6803F003036E +:1026A000012B09B20ED1D2F8083802EB411013F415 +:1026B000807FD0F8003B14BF43F0805343F00053B9 +:1026C000C0F8003B02EB4112D2F8003B43F0044358 +:1026D000C2F8003B30BD00002DE9F041244D6E6D85 +:1026E00006EB40130446D3F8087BC3F8087B380791 +:1026F0000AD5D6F81438190706D505EB8403214608 +:10270000DB6828465B689847FA071FD5D6F8143867 +:10271000DB071BD505EB8403D968CCB98B69488AE4 +:102720005A68B2FBF0F600FB16228AB91868DA681C +:1027300090420DD2121AC3E90024202383F311889A +:102740000B482146FFF78AFF84F31188BDE8F0812A +:10275000012303FA04F26B8923EA02036B81CB683D +:10276000002BF3D021460248BDE8F041184700BFD6 +:10277000B02C002000EB810370B5DD68436D6C69FF +:102780002668E6604A0156BB1A444FF40020C2F89E +:1027900010092A6802F00302012A0AB20ED1D3F806 +:1027A000080803EB421410F4807FD4F8000914BF2A +:1027B00040F0805040F00050C4F8000903EB421292 +:1027C000D2F8000940F00440C2F80009D3F83408F8 +:1027D000012202FA01F10143C3F8341870BD19B99E +:1027E000402E84BF4020206020682E8A8419013C3E +:1027F000B4FBF6F440EAC44040F000501A44C6E787 +:10280000F8B504461E48456D05EB4413D3F8086936 +:10281000C3F80869F10717D5D5F81038DA0713D5CA +:1028200000EB8403D9684B691F68DA68974218D2B5 +:10283000D21B00271A605F60202383F31188214692 +:10284000FFF798FF87F31188330617D5D5F834289A +:102850000123A340134211D02046BDE8F840FFF702 +:1028600023BD012303FA04F2038923EA020303814F +:102870008B68002BE8D021469847E5E7F8BD00BFFC +:10288000B02C00202DE9F74F984C666D7569B3693F +:102890001D4015F48058756107D02046FEF70AFDEB +:1028A00003B0BDE8F04FFFF785BC002D12DAD6F873 +:1028B000003E8E489F071EBFD6F8003E23F003035C +:1028C000C6F8003ED6F8043823F00103C6F80438F1 +:1028D000FEF718FD280505D58448FFF7B9FC8348A5 +:1028E000FEF700FDA9040CD5D6F8083813F0060F42 +:1028F000F36823F470530CBF43F4105343F4A05314 +:10290000F3602A0704D56368DB680BB17748984702 +:10291000EB0274D4AF0227D5D4F85490DFF8CCB1D1 +:1029200000274FF0010A09EB4712D2F8003B03F4ED +:102930004023B3F5802F11D1D2F8003B002B0DDAE4 +:1029400062890AFA07F322EA0303638104EB87032F +:10295000DB68DB6813B1394658469847A36D0137E9 +:102960009B68FFB29F42DED9E80617D5676D3A6AC9 +:10297000C2F30A1002F00F0302F4F012B2F5802F36 +:1029800000F08880B2F5402F08D104EB83030022C9 +:10299000DB681B6A07F5805790426DD12903D6F892 +:1029A000184813D5E20302D50020FFF795FEA303D4 +:1029B00002D50120FFF790FE670302D50220FFF742 +:1029C0008BFE260302D50320FFF786FE6D037FF5FD +:1029D00067AFE00702D50020FFF712FFA10702D57D +:1029E0000120FFF70DFF620702D50220FFF708FF65 +:1029F00023077FF555AF0320FFF702FF50E7636D14 +:102A0000DFF8E8B0019300274FF0010AA36D9B683F +:102A10005FFA87F999453FF67DAF019B03EB4913B8 +:102A2000D3F8002902F44022B2F5802F22D1D3F846 +:102A30000029002A1EDAD3F8002942F09042C3F898 +:102A40000029D3F80029002AFBDB606D4946FFF717 +:102A500069FC22890AFA09F322EA0303238104EBC1 +:102A60008903DB689B6813B1494658469847484636 +:102A7000FFF71AFC0137C9E7910708BFD7F80080B4 +:102A8000072A98BF03F8018B02F1010298BF4FEAB1 +:102A9000182881E7023304EB830207F58057526858 +:102AA000D2F818C0DCF80820DCE9001CA1EB0C0C03 +:102AB000002188420AD104EB830463689B699A6809 +:102AC00002449A605A6802445A6067E711F0030FA3 +:102AD00008BFD7F800808C4588BF02F8018B01F150 +:102AE000010188BF4FEA1828E3E700BFB02C00209F :102AF000436D03EB4111D1F8003B43F40013C1F8DF :102B0000003B7047436D03EB4111D1F8003943F4AA :102B10000013C1F800397047436D03EB4111D1F840 :102B2000003B23F40013C1F8003B7047436D03EBF7 :102B30004111D1F8003923F40013C1F8003970476E -:102B400000F1604300F01F02400903F561430901F1 -:102B50008000C9B200F1604083F8001300F56140C5 -:102B600001239340C0F880310360704730B5039C67 -:102B70000172043304FB0325C361049B036300213A -:102B8000059B00604060C160426102618561046232 -:102B900042628162C162436330BD00000022416A2B -:102BA00041610161C2608262C2626FF00101FEF7A1 -:102BB00023BF000003694269934203D1C2680AB18E -:102BC00000207047181D704703691960C268013200 +:102B400000F1604303F561430901C9B283F8001342 +:102B5000012200F01F039A4043099B0003F16043E8 +:102B600003F56143C3F880211A60704730B5039CB8 +:102B70000172043304FB0325C0E90653049B03637D +:102B80000021059BC160C0E90000C0E90422C0E942 +:102B90000842C0E90A11436330BD0000416A0022C7 +:102BA000C0E90411C0E90A22C2606FF00101FEF71A +:102BB00007BF0000D0E90432934201D1C2680AB9CC +:102BC000181D70470020704703691960C268013200 :102BD000C260C269134482690361934224BF436A9D -:102BE00003610021FEF7FCBE38B504460D46E368DC +:102BE00003610021FEF7E0BE38B504460D46E368F8 :102BF0003BB16269131D1268A3621344E3620020B3 -:102C000038BD237A33B929462046FEF7D9FE00287D +:102C000007E0237A33B929462046FEF7BDFE0028A7 :102C1000EDDA38BD6FF00100FBE70000C368C26960 :102C2000013BC3604369134482694361934224BFFB :102C3000436A436100238362036B03B11847704703 @@ -711,151 +711,151 @@ :102C5000CBFF054618B186F31188284670BDA36ADC :102C6000E26A13F8015BA362934202D32046FFF7A6 :102C7000D5FF002383F31188EFE700002DE9F84F1B -:102C800004460E4690469946202787F31188002572 -:102C9000AA46D4F828B0BBF1000F09D14946204616 -:102CA000FFF7A2FF20B18BF311882846BDE8F88F0B -:102CB000A16AE36AA8EB050B5B1A9B4528BF9B46FC -:102CC000BBF1400F1BD9334601F1400251F8040B10 -:102CD00043F8040B9142F9D1A36A40334036A36212 -:102CE0004035A26AE36A9A4202D32046FFF796FF74 -:102CF0008AF311884545D8D287F31188C9E7304651 -:102D00005A46FDF7D5FFA36A5B445E44A3625D4467 -:102D1000E7E7000010B5029C0172043303FB0421B5 -:102D2000C36100238362C362039B0363049B00604F -:102D30004060C46042610261816104624262436337 -:102D400010BD0000026AC260426A42610261002254 -:102D50008262C2626FF00101FEF74EBE43690269F2 -:102D60009A4203D1C2680AB100207047184650F851 -:102D7000043B0B6070470000C368C2690133C36045 +:102C800004460E46174698464FF0200989F31188EE +:102C90000025AA46D4F828B0BBF1000F09D141465F +:102CA0002046FFF7A1FF20B18BF311882846BDE82D +:102CB000F88FD4E90A12A7EB050B521A934528BFE7 +:102CC0009346BBF1400F1BD9334601F1400251F846 +:102CD000040B43F8040B9142F9D1A36A4033403608 +:102CE000A3624035D4E90A239A4202D32046FFF773 +:102CF00095FF8AF31188BD42D8D289F31188C9E7BC +:102D000030465A46FDF7D2FFA36A5B445E44A36295 +:102D10005D44E7E710B5029C0172043304FB032114 +:102D2000C0E906130023C0E90A33039B0363049B35 +:102D3000C460C0E90000C0E90422C0E9084243635E +:102D400010BD0000026AC260426AC0E9042200228B +:102D5000C0E90A226FF00101FEF732BED0E9042378 +:102D60009A4201D1C26822B9184650F8043B0B6060 +:102D70007047002070470000C368C2690133C36018 :102D80004369134482694361934224BF436A4361A8 -:102D90000021FEF725BE000038B504460D46E36865 +:102D90000021FEF709BE000038B504460D46E36881 :102DA0003BB123691A1DA262E2691344E362002069 -:102DB00038BD237A33B929462046FEF701FE0028A4 +:102DB00007E0237A33B929462046FEF7E5FD0028CF :102DC000EDDA38BD6FF00100FBE700000369196020 :102DD000C268013AC260C2691344826903619342C6 :102DE00024BF436A036100238362036B03B1184766 -:102DF0007047000070B5202304460E4683F3118807 -:102E0000856A35B91146FFF7C7FF10B185F3118800 -:102E100070BDA36A1E70A36AE26A01339342A36283 +:102DF0007047000070B520230D460446114683F34A +:102E00001188866A2EB9FFF7C7FF10B186F31188C3 +:102E100070BDA36A1D70A36AE26A01339342A36284 :102E200004D3E16920460439FFF7D0FF002080F386 -:102E3000118870BD2DE9F84F04460D4691469A461B -:102E40004FF0200888F311880026B346A76A4FB9CF -:102E500051462046FFF7A0FF20B187F31188304686 -:102E6000BDE8F88FA06AE76AA9EB06033F1A9F4204 -:102E700028BF1F46402F1BD905F1400355F8042BEE +:102E30001188EDE72DE9F84F04460D469046994676 +:102E40004FF0200A8AF311880026B346A76A4FB9CB +:102E500049462046FFF7A0FF20B187F3118830468E +:102E6000BDE8F88FD4E90A073A1AA8EB060797429B +:102E700028BF1746402F1BD905F1400355F8042BF6 :102E800040F8042B9D42F9D1A36A4033A362403637 -:102E9000A26AE36A9A4204D3E16920460439FFF743 -:102EA00095FF8BF311884E45D9D288F31188CDE771 -:102EB00029463A46FDF7FCFEA36A3B443D44A36223 -:102EC0003E44E5E7026943699A4203D1C3681BB9EE -:102ED000184670470023FBE7836A002BF8D0043BB9 -:102EE0009B1AF5D01360C368013BC360C3691A44E1 -:102EF000836902619A4224BF436A036100238362AB -:102F00000123E5E700F090B84FF0804300225863BA -:102F10001A610222DA6070474FF080430022DA60C3 -:102F2000704700004FF08043586370474FF0804374 -:102F3000586A70474B6843608B688360CB68C36096 -:102F40000B6943614B6903628B6943620B680360E1 -:102F50007047000008B5224B22481A6940F2FF1161 -:102F60000A431A611A6922F4FF7222F001021A61FF -:102F70001A691A6B0A431A631A6D0A431A651A4AC8 -:102F80001B6D1146FFF7D6FF184802F11C01FFF731 -:102F9000D1FF174802F13801FFF7CCFF154802F1C5 -:102FA0005401FFF7C7FF144802F17001FFF7C2FF99 -:102FB000124802F18C01FFF7BDFF114802F1A80190 -:102FC000FFF7B8FF0F4802F1C401FFF7B3FF0E4847 -:102FD00002F1E001FFF7AEFFBDE8084000F0AAB83B -:102FE000003802400000024084360008000402401D -:102FF00000080240000C0240001002400014024091 -:1030000000180240001C02400020024008B500F0F9 -:1030100007FAFEF75DFCFFF785F8BDE80840FEF70C -:103020005FBE000070470000104B1A6C42F00102B6 -:103030001A641A6E42F001021A660D4A1B6E9368FA -:1030400043F0010393604FF0804353229A624FF0A4 -:10305000FF32DA6200229A615A63DA605A60012212 -:103060005A6108211A601C20FFF76ABD003802402F -:10307000002004E04FF0804208B51369D1680B408E -:10308000D9B2C9439B07116107D5202383F3118867 -:10309000FEF73EFC002383F3118808BD08B5FFF757 -:1030A000E9FFBDE80840FFF783B800001F4B1A692D -:1030B0006FEAC2526FEAD2521A611A69C2F3080269 -:1030C0001A614FF0FF301A695A69586100215A6934 -:1030D00059615A691A6A62F080521A621A6A02F0D9 -:1030E00080521A621A6A5A6A58625A6A59625A6A4D -:1030F0001A6C42F080521A641A6E42F080521A66BC -:103100001A6E0B4A106840F480701060186F00F45B -:103110004070B0F5007F1EBF4FF48030186719670C -:10312000536823F40073536000F05AB9003802402A -:1031300000700040334B4FF080521A64324A4FF413 -:10314000404111601A6842F001021A601A68920741 -:10315000FCD59A6822F003029A602A4B19469A68B5 -:1031600012F00C02FBD1186800F0F90018609A60A8 -:103170001A6842F480321A600B689B03FCD54B6FCF -:1031800043F001034B671F4B5A6F9007FCD51F4A52 -:103190005A601A6842F080721A601B4A53685904D8 -:1031A000FCD5184B1A689201FCD5194A9A60194B44 -:1031B0001A68194B9A42194B21D1194A1168194AB8 -:1031C00091421CD140F205121A60144A136803F0B0 -:1031D0000F03052BFAD10B4B9A6842F002029A605A -:1031E0009A6802F00C02082AFAD15A6C42F4804222 -:1031F0005A645A6E42F480425A665B6E704740F2DF -:103200000572E1E7003802400070004008544007B2 -:1032100000948838002004E011640020003C024043 -:1032200000ED00E041C20F41084A08B5536911683A -:103230000B4003F00103536123B1054A13680BB13E -:1032400050689847BDE80840FEF7B2BF003C014017 -:1032500088230020084A08B5536911680B4003F021 -:103260000203536123B1054A93680BB1D0689847B4 -:10327000BDE80840FEF79CBF003C014088230020C9 -:10328000084A08B5536911680B4003F00403536101 -:1032900023B1054A13690BB150699847BDE808404E -:1032A000FEF786BF003C014088230020084A08B58D -:1032B000536911680B4003F00803536123B1054AB9 -:1032C00093690BB1D0699847BDE80840FEF770BF1D -:1032D000003C014088230020084A08B55369116862 -:1032E0000B4003F01003536123B1054A136A0BB17D -:1032F000506A9847BDE80840FEF75ABF003C0140BD -:1033000088230020174B10B55C691A68144004F438 -:1033100078725A61A30604D5134A936A0BB1D06A36 -:103320009847600604D5104A136B0BB1506B984751 -:10333000210604D50C4A936B0BB1D06B9847E2057C -:1033400004D5094A136C0BB1506C9847A30504D5FA -:10335000054A936C0BB1D06C9847BDE81040FEF75E -:1033600027BF00BF003C0140882300201A4B10B546 -:103370005C691A68144004F47C425A61620504D501 -:10338000164A136D0BB1506D9847230504D5134AA7 -:10339000936D0BB1D06D9847E00404D50F4A136EBE -:1033A0000BB1506E9847A10404D50C4A936E0BB133 -:1033B000D06E9847620404D5084A136F0BB1506F62 -:1033C0009847230404D5054A936F0BB1D06F9847F3 -:1033D000BDE81040FEF7ECBE003C01408823002011 -:1033E000062108B50846FFF7ABFB06210720FFF7CB -:1033F000A7FB06210820FFF7A3FB06210920FFF702 -:103400009FFB06210A20FFF79BFB06211720FFF7F1 -:1034100097FB06212820BDE80840FFF791BB00007C -:1034200008B5FFF743FEFDF74DFDFDF7FBFEFDF789 -:10343000CFFDFFF7F7FDBDE80840FFF763BD0000D3 -:10344000034611F8012B03F8012B002AF9D170472C -:10345000121012131211000053544D3332463F3FE5 -:103460003F00000000000000583400083F0000004A -:1034700013040000943400083F0000001904000009 -:103480009E3400083F00000021040000A83400081A -:103490003F00000053544D333246343078005354CB -:1034A0004D3332463432780053544D33324634343F -:1034B0003658580000000000490F0008350F00087A -:1034C000710F00085D0F0008690F0008550F000814 -:1034D000410F00082D0F0008CD0F0008000000006C +:102E9000D4E90A239A4204D3E16920460439FFF7B2 +:102EA00095FF8BF311884645D9D28AF31188CDE777 +:102EB00029463A46FDF7FAFEA36A3B443D44A36225 +:102EC0003E44E5E7D0E904239A4217D1C3689BB199 +:102ED000836A8BB1043B9B1A0ED01360C368013B1D +:102EE000C360C3691A44836902619A4224BF436A7A +:102EF0000361002383620123184670470023FBE728 +:102F000000F088B84FF08043002258631A61022213 +:102F1000DA6070474FF080430022DA6070470000AB +:102F20004FF08043586370474FF08043586A7047B2 +:102F30004B6843608B688360CB68C3600B694361F7 +:102F40004B6903628B6943620B6803607047000042 +:102F500008B5264B26481A6940F2FF110A431A6148 +:102F60001A6922F4FF7222F001021A611A691A6BBF +:102F70000A431A631A6D0A431A651E4A1B6D1146ED +:102F8000FFF7D6FF02F11C0100F58060FFF7D0FFCC +:102F900002F1380100F58060FFF7CAFF02F1540129 +:102FA00000F58060FFF7C4FF02F1700100F580605A +:102FB000FFF7BEFF02F18C0100F58060FFF7B8FF5C +:102FC00002F1A80100F58060FFF7B2FF02F1C40131 +:102FD00000F58060FFF7ACFF02F1E00100F58060D2 +:102FE000FFF7A6FFBDE8084000F09AB8003802409D +:102FF000000002408436000808B500F007FAFEF72A +:1030000033FCFFF78DF8BDE80840FEF755BE000021 +:1030100070470000104B1A6C42F001021A641A6EDD +:1030200042F001021A660D4A1B6E936843F00103D9 +:1030300093604FF0804353229A624FF0FF32DA627E +:1030400000229A615A63DA605A6001225A610821AB +:103050001A601C20FFF774BD00380240002004E015 +:103060004FF0804208B51169D3680B40D9B2C9430B +:103070009B07116107D5202383F31188FEF714FC09 +:10308000002383F3118808BD08B5FFF7E9FFBDE809 +:103090000840FFF78FB800001F4B1A696FEAC25251 +:1030A0006FEAD2521A611A69C2F308021A614FF02C +:1030B000FF301A695A69586100215A6959615A6981 +:1030C0001A6A62F080521A621A6A02F080521A6218 +:1030D0001A6A5A6A58625A6A59625A6A1A6C42F0F3 +:1030E00080521A641A6E42F080521A661A6E0B4AA7 +:1030F000106840F480701060186F00F44070B0F5F4 +:10310000007F1EBF4FF4803018671967536823F49F +:103110000073536000F05AB900380240007000405C +:10312000334B4FF080521A64324A4FF440411160E1 +:103130001A6842F001021A601A689107FCD59A6871 +:1031400022F003029A602A4B9A6812F00C02FBD11B +:10315000196801F0F90119609A601A6842F4803226 +:103160001A601A689203FCD55A6F42F001025A673E +:103170001F4B5A6F9007FCD51F4A5A601A6842F0DD +:1031800080721A601B4A53685904FCD5184B1A68A0 +:103190009201FCD5194A9A60194B1A68194B9A4248 +:1031A000194B21D1194A1168194A91421CD140F298 +:1031B00005121A60144A136803F00F03052BFAD1A5 +:1031C0000B4B9A6842F002029A609A6802F00C0275 +:1031D000082AFAD15A6C42F480425A645A6E42F478 +:1031E00080425A665B6E704740F20572E1E700BFAD +:1031F00000380240007000400854400700948838AE +:10320000002004E011640020003C024000ED00E0DA +:1032100041C20F41084A08B5516913680B4003F0D9 +:103220000103536123B1054A13680BB150689847F5 +:10323000BDE80840FEF7BEBF003C0140282D00203D +:10324000084A08B5516913680B4003F00203536143 +:1032500023B1054A93680BB1D0689847BDE8084090 +:10326000FEF7A8BF003C0140282D0020084A08B501 +:10327000516913680B4003F00403536123B1054AFD +:1032800013690BB150699847BDE80840FEF792BF3B +:10329000003C0140282D0020084A08B551691368F8 +:1032A0000B4003F00803536123B1054A93690BB146 +:1032B000D0699847BDE80840FEF77CBF003C01405C +:1032C000282D0020084A08B5516913680B4003F007 +:1032D0001003536123B1054A136A0BB1506A984732 +:1032E000BDE80840FEF766BF003C0140282D0020E5 +:1032F000174B10B55A691C68144004F478725A616F +:10330000A30604D5134A936A0BB1D06A98476006A6 +:1033100004D5104A136B0BB1506B9847210604D5A6 +:103320000C4A936B0BB1D06B9847E20504D5094A60 +:10333000136C0BB1506C9847A30504D5054A936CE8 +:103340000BB1D06C9847BDE81040FEF733BF00BF0B +:10335000003C0140282D00201A4B10B55A691C680A +:10336000144004F47C425A61620504D5164A136D78 +:103370000BB1506D9847230504D5134A936D0BB1DB +:10338000D06D9847E00404D50F4A136E0BB1506E10 +:103390009847A10404D50C4A936E0BB1D06E9847A0 +:1033A000620404D5084A136F0BB1506F9847230489 +:1033B00004D5054A936F0BB1D06F9847BDE8104014 +:1033C000FEF7F8BE003C0140282D0020062108B57C +:1033D0000846FFF7B5FB06210720FFF7B1FB0621E2 +:1033E0000820FFF7ADFB06210920FFF7A9FB062106 +:1033F0000A20FFF7A5FB06211720FFF7A1FBBDE878 +:10340000084006212820FFF79BBB000008B5FFF706 +:1034100043FE00F00BF8FDF7E5FEFDF7BDFDFFF7FD +:10342000F7FDBDE80840FFF76BBD00000023054A2B +:1034300019460133102BC2E9001102F10802F8D13C +:10344000704700BF282D0020034611F8012B03F818 +:10345000012B002AF9D1704753544D3332463F3F78 +:103460003F00000053544D333246343078005354FB +:103470004D3332463432780053544D33324634346F +:103480003658580000000000583400083F00000083 +:1034900013040000643400083F0000001904000019 +:1034A0006E3400083F00000021040000783400085A +:1034B0003F00000000000000150F0008010F000889 +:1034C0003D0F0008290F0008350F0008210F0008E4 +:1034D0000D0F0008F90E0008490F00080000000059 :1034E00001000000000000006D61696E0000000036 -:1034F0000835000848240020C025002001000000F5 -:10350000CD1800080000000069646C650000000030 -:10351000020000000000000075110008DD11000825 -:1035200040004000582A0020682A002002000000C5 -:10353000000000000300000000000000211200084D -:103540000000000010000000782A002000000000A9 -:1035500001000000000000001C2D002001010200FD -:103560004172647550696C6F740025424F4152443A -:10357000252D424C002553455249414C2500000061 -:10358000811C0008E91B0008E1100008651C000808 +:1034F00069646C6500000000F0340008D8230020E7 +:1035000050250020010000006518000800000000A0 +:103510004172647550696C6F740025424F4152448A +:10352000252D424C002553455249414C25000000B1 +:103530000200000000000000311100089D11000889 +:1035400040004000E8290020F82900200200000087 +:10355000000000000300000000000000E11100086E +:103560000000000010000000082A002000000000F9 +:103570000100000000000000B02C0020010102004A +:10358000551C0008651B0008011C0008E51B00080D :10359000430000009835000809024300020100C002 :1035A0003209040000010202010005240010010597 :1035B00024010001042402020524060001070582FB @@ -868,9 +868,9 @@ :103620004600000000400000004000000040000094 :103630000040000000000100000002000000020045 :103640000000020000000200000002000000020072 -:10365000000002000000000071130008511600086D -:10366000FD160008400040007C2D00207C2D00202D -:10367000010000008C2D00208000000040010000AF +:10365000000002000000000019130008D115000846 +:103660007D16000840004000102D0020102D002085 +:1036700001000000202D002080000000400100001B :10368000030000000000800200000000AAAAAAAA0D :1036900000000000FFFF00000000000000A00A0082 :1036A0004004001000000000AAAAAAAA40000010CE @@ -887,7 +887,8 @@ :103750000A0000000000000003000000000000005C :103760000000000000000000000000000000000059 :103770000000000000000000000000000000000049 -:10378000FF0096000000000804000000F835000863 -:103790000000000000000000000000000000000029 -:0837A000000000000000000021 +:10378000060400000000000000000F000000000020 +:10379000FF009600000000080096000000000800EE +:1037A00004000000F83500080000000000000000E0 +:1037B0000000000000000000000000000000000009 :00000001FF diff --git a/Tools/bootloaders/KakuteF7-bdshot_bl.bin b/Tools/bootloaders/KakuteF7-bdshot_bl.bin new file mode 100755 index 00000000000..1716d1006df Binary files /dev/null and b/Tools/bootloaders/KakuteF7-bdshot_bl.bin differ diff --git a/Tools/bootloaders/KakuteH7-bdshot_bl.bin b/Tools/bootloaders/KakuteH7-bdshot_bl.bin new file mode 100644 index 00000000000..b96f9df2620 Binary files /dev/null and b/Tools/bootloaders/KakuteH7-bdshot_bl.bin differ diff --git a/Tools/bootloaders/KakuteH7-bdshot_bl.hex b/Tools/bootloaders/KakuteH7-bdshot_bl.hex new file mode 100644 index 00000000000..62e1f9bf182 --- /dev/null +++ b/Tools/bootloaders/KakuteH7-bdshot_bl.hex @@ -0,0 +1,975 @@ +:020000040800F2 +:1000000000060020A1020008950F0008150F000847 +:100010006D0F0008150F0008410F0008A30200082B +:10002000A3020008A3020008A3020008812200081E +:10003000A3020008A3020008A3020008A30200080C +:10004000A3020008A3020008A3020008A3020008FC +:10005000A3020008A3020008F13600081D370008BB +:100060004937000875370008A1370008A3020008C7 +:10007000A3020008A3020008A3020008A3020008CC +:10008000A3020008A3020008A3020008A3020008BC +:10009000A3020008A3020008A3020008CD3700084D +:1000A000A3020008A3020008A3020008A30200089C +:1000B000A3020008A3020008A3020008A30200088C +:1000C000A3020008A3020008A3020008A30200087C +:1000D000A3020008A3020008A3020008A30200086C +:1000E00031380008A3020008A3020008A302000898 +:1000F000A3020008A3020008A3020008A30200084C +:10010000A3020008A3020008A5380008A302000803 +:10011000A3020008A3020008A3020008A30200082B +:10012000A3020008A3020008A3020008A30200081B +:10013000A3020008A3020008A3020008A30200080B +:10014000A3020008A3020008A3020008A3020008FB +:10015000A3020008A3020008A3020008A3020008EB +:10016000A3020008A3020008A3020008A3020008DB +:10017000A3020008ED2D0008A3020008A302000856 +:10018000A3020008A3020008A3020008A3020008BB +:10019000A3020008A3020008A3020008A3020008AB +:1001A000A3020008A3020008A3020008A30200089B +:1001B000A3020008A3020008A3020008A30200088B +:1001C000A3020008A3020008A3020008A30200087B +:1001D000A3020008D92D0008A3020008A30200080A +:1001E000A3020008A3020008A3020008A30200085B +:1001F000A3020008A3020008A3020008A30200084B +:10020000A3020008A3020008A3020008A30200083A +:10021000A3020008A3020008A3020008A30200082A +:10022000A3020008A3020008A3020008A30200081A +:10023000A3020008A3020008A3020008A30200080A +:10024000A3020008A3020008A3020008A3020008FA +:10025000A3020008A3020008A3020008A3020008EA +:10026000A3020008A3020008A3020008A3020008DA +:10027000A3020008A3020008A3020008A3020008CA +:10028000A3020008A3020008A3020008A3020008BA +:10029000A3020008A3020008A3020008A3020008AA +:1002A00002E000F000F8FEE772B63A4880F30888F2 +:1002B000394880F3098839484EF60851CEF20001DA +:1002C000086040F20000CCF200004EF63471CEF22D +:1002D00000010860BFF34F8FBFF36F8F40F2000043 +:1002E000C0F2F0004EF68851CEF200010860BFF374 +:1002F0004F8FBFF36F8F4FF00000E1EE100A4EF604 +:100300003C71CEF200010860062080F31488BFF330 +:100310006F8F02F073F802F015F802F0AFFF4FF0A4 +:1003200055301F491B4A91423CBF41F8040BFAE784 +:100330001C49194A91423CBF41F8040BFAE71A499B +:100340001A4A1B4B9A423EBF51F8040B42F8040B69 +:10035000F8E700201749184A91423CBF41F8040BC6 +:10036000FAE702F02DF803F001F8144C144DAC42FA +:1003700003DA54F8041B8847F9E700F041F8114C00 +:10038000114DAC4203DA54F8041B8847F9E702F038 +:1003900015B8000000060020002200200000000820 +:1003A0000000002000060020703C00080022002011 +:1003B0005C220020602200207C420020A002000875 +:1003C000A0020008A0020008A00200082DE9F04FDA +:1003D0002DED108AC1F80CD0D0F80CD0BDEC108AED +:1003E000BDE8F08F002383F311882846A047002042 +:1003F00001F038FBFEE701F0CDFA00DFFEE7000078 +:1004000038B500F0C1FC30B1164B00220E211A7233 +:100410005A729972DA7201F0F3FE054601F026FF76 +:100420000446D0B9104B9D4219D001339D4241F290 +:10043000883512BF044600250124002001F0EAFEA1 +:100440000CB100F059F800F039FD00F0E3FB28464C +:1004500000F004F900F050F8F9E70025EDE7054653 +:10046000EBE700BF00220020010007B008B500F054 +:10047000A3FBA0F120035842584108BD07B541F243 +:100480001203022101A8ADF8043000F0B3FB03B061 +:100490005DF804FB202310B583F311881248C3686C +:1004A0000BB101F065FB0023104A4FF47A710E483E +:1004B00001F022FB002383F311880D4C236813B154 +:1004C0002368013B2360636813B16368013B636089 +:1004D000084B1B7833B9636823B9022000F068FC2D +:1004E0003223636010BD00BF602200209504000825 +:1004F0007C23002074220020F8B5514B514A1C4641 +:100500001968013100F09B8004339342F8D162688E +:100510004D4B9A4240F293804C4B9B6803F1006331 +:1005200003F500339A4280F08A80002000F08CFBB3 +:100530000220474B187000F031FC464B0021D3F8E5 +:10054000E820C3F8E810D3F81021C3F81011D3F84D +:100550001021D3F8EC20C3F8EC10D3F81421C3F821 +:100560001411D3F81421D3F8F020C3F8F010D3F805 +:100570001821C3F81811D3F81821D3F8802042F0BD +:100580000062C3F88020D3F8802022F00062C3F814 +:100590008020D3F88020D3F8802042F00072C3F886 +:1005A0008020D3F8802022F00072C3F88020D3F896 +:1005B000803072B64FF0E023C3F8084DD4E9000450 +:1005C000BFF34F8FBFF36F8F234AC2F88410BFF37E +:1005D0004F8F536923F480335361BFF34F8FD2F8A9 +:1005E000803043F6E076C3F3C905C3F34E335B01B5 +:1005F00003EA060C29464CEA81770139C2F8747285 +:10060000F9D2203B13F1200FF2D1BFF34F8FBFF38C +:100610006F8FBFF34F8FBFF36F8F536923F4003396 +:1006200053610023C2F85032BFF34F8FBFF36F8F77 +:10063000202383F31188854680F308882047F8BD7E +:100640000000020820000208FFFF0108002200202D +:10065000742200200044025800ED00E02DE9F04F24 +:1006600093B0A94B2022FF2100900AA89D6800F0BA +:10067000CFFBA64A1378A3B90121A5481170C36026 +:10068000202383F31188C3680BB101F071FA0023B2 +:10069000A04A4FF47A719E4801F02EFA002383F3AA +:1006A0001188009B9C4A03B1136000239B49009C66 +:1006B00098469B461E469A460B705360012000F0F8 +:1006C0006DFB24B1944B1B68002B00F016820020B8 +:1006D00000F072FA0390039B002BF2DB012000F084 +:1006E00055FB039B213B162BE8D801A252F823F0BF +:1006F0004D0700087507000809080008BD06000836 +:10070000BD060008BD0600089D0800086F0A000825 +:1007100089090008EB090008130A0008390A0008D3 +:10072000BD0600084B0A0008BD060008BD0A000807 +:10073000ED070008BD060008010B00085907000876 +:10074000ED070008BD060008EB0900080220FFF7CE +:100750008DFE002840F0FB81009B022105A8B8F126 +:10076000000F08BF1C4641F21233ADF8143000F000 +:1007700041FAA3E74FF47A7000F01EFA071EEBDB94 +:100780000220FFF773FE0028E6D0013F052F00F29C +:10079000E081DFE807F0030A0D101336052304217A +:1007A00005A8059300F026FA17E004215648F9E75A +:1007B00004215B48F6E704215A48F3E74FF01C098F +:1007C000484609F1040900F041FA0421059005A802 +:1007D00000F010FAB9F12C0FF2D101204FF0000A0D +:1007E00000FA07F747EA0B0B5FFA8BFB00F05CFBA4 +:1007F00026B10BF00B030B2B08BF0024FFF73EFEC6 +:100800005CE704214848CDE7002EA5D00BF00B0390 +:100810000B2BA1D10220FFF729FE074600289BD011 +:1008200001203E4E00F010FA4FF000080220307018 +:1008300000F0B4FA5FFA88F9484600F015FA044669 +:1008400090B1484608F1010800F01EFA0028F1D1E5 +:10085000B846044641F21213022105A83E46ADF8FF +:10086000143000F0C7F929E7012325460220337030 +:1008700000F08CFA244B9B68AB4207D9284600F065 +:10088000E5F9013040F068810435F3E70025234B9A +:10089000B8463E461D70204B5D60A7E7002E3FF432 +:1008A0005BAF0BF00B030B2B7FF456AF02201B4BFF +:1008B000187000F073FA322000F07EF9B0F10009F0 +:1008C000FFF64AAF19F003077FF446AF0E4A09EB73 +:1008D0000503926893423FF63FAFB9F5807F3FF73B +:1008E0003BAF124BB945019322DD4FF47A7000F013 +:1008F00063F90390039A002AFFF62EAF039A01379B +:10090000019B03F8012BEDE7002200207823002053 +:1009100060220020950400087C230020742200201F +:1009200004220020082200200C220020782200202F +:10093000C820FFF79BFD074600283FF40DAF1F2D91 +:1009400011D8C5F120020AAB25F0030084494A45BD +:10095000184428BF4A46019200F034FA019AFF2158 +:100960007F4800F055FA4FEAA903C9F387027C4992 +:100970002846019300F054FA064600283FF46AAF77 +:10098000019B05EB830531E70220FFF76FFD00288F +:100990003FF4E2AE00F094F900283FF4DDAE00270A +:1009A000B946704B9B68BB4218D91F2F11D80A9BC0 +:1009B00001330ED027F0030312AA134453F8203C4E +:1009C00005934846042205A9043700F0E5FA81465C +:1009D000E7E7384600F03AF90590F2E7CDF81490D1 +:1009E000042105A800F006F900E70023642104A80B +:1009F000049300F0F5F800287FF4AEAE0220FFF774 +:100A000035FD00283FF4A8AE049800F04FF905909A +:100A1000E6E70023642104A8049300F0E1F800282D +:100A20007FF49AAE0220FFF721FD00283FF494AE38 +:100A3000049800F03DF9EAE70220FFF717FD0028CF +:100A40003FF48AAE00F04CF9E1E70220FFF70EFD1B +:100A500000283FF481AE05A9142000F047F90746AD +:100A60000421049004A800F0C5F83946B9E7322003 +:100A700000F0A2F8071EFFF66FAEBB077FF46CAE66 +:100A8000384A07EB0A03926893423FF665AE0220AC +:100A9000FFF7ECFC00283FF45FAE27F00307574454 +:100AA000BA453FF4A3AE50460AF1040A00F0CEF86E +:100AB0000421059005A800F09DF8F1E74FF47A7045 +:100AC000FFF7D4FC00283FF447AE00F0F9F8002807 +:100AD00044D00A9B01330BD008220AA9002000F061 +:100AE0009FF900283AD02022FF210AA800F090F9AF +:100AF000FFF7C4FC1C4800F0BBFF13B0BDE8F08F4B +:100B0000002E3FF429AE0BF00B030B2B7FF424AE29 +:100B10000023642105A8059300F062F80746002829 +:100B20007FF41AAE0220FFF7A1FC814600283FF4B3 +:100B300013AEFFF7A3FC41F2883000F099FF05984F +:100B400000F0E6F94E463C4600F0AEF9B6E5064642 +:100B50004CE64FF0000AFFE5B8467BE6374679E6FB +:100B60007822002000220020A08601000F4B70B5E3 +:100B70001B780C460133DBB2012B11D80C4D4FF41E +:100B80007A732968A2FB033222460E6A0146284680 +:100B9000B047844204D1074B002201201A7070BD77 +:100BA0004FF4FA7000F064FF0020F8E710220020F4 +:100BB00070250020B0230020002307B50246012144 +:100BC0000DF107008DF80730FFF7D0FF20B19DF839 +:100BD000070003B05DF804FB4FF0FF30F9E70000B9 +:100BE0000A46042108B5FFF7C1FF80F00100C0B23A +:100BF000404208BD30B4054C0A46014623682046F1 +:100C0000DD69034BAC4630BC604700BF7025002057 +:100C1000A086010070B50A4E00240A4D01F0D6F9F5 +:100C2000308028683388834208D901F0CBF92B68DB +:100C300004440133B4F5003F2B60F2D370BD00BF14 +:100C4000B22300208423002001F090BA00F100605C +:100C500000F500300068704700F10060920000F578 +:100C6000003001F00FBA0000054B1A68054B1B88D5 +:100C70009B1A834202D9104401F0A4B900207047A6 +:100C800084230020B223002038B5074D044628688D +:100C9000204401F09DF928B928682044BDE8384077 +:100CA00001F0A8B938BD00BF8423002000207047A0 +:100CB00000F1FF5000F58F10D0F8000870470000D9 +:100CC000064991F8243033B100230822086A81F8DC +:100CD0002430FFF7C1BF0120704700BF88230020E8 +:100CE000014B1868704700BF0010005C244BF0B542 +:100CF0001A680446234BC2F30B06120C1F8858686F +:100D0000BE4293F9085028D09F89BE4206D10120E7 +:100D10000C2505FB0033586893F9085041F2010394 +:100D20009A421CD041F203039A421AD042F20103C4 +:100D30009A4218D042F203039A4208BF5625621E17 +:100D40000B46441E0A4493420FD214F9016F581CFB +:100D50006EB1034600F8016CF5E70020D8E75A258C +:100D6000EDE75925EBE75825E9E7184605E02C247F +:100D700082421C7001D9981C5D70401AF0BD00BF02 +:100D80000010005C1422002000207047022802D1CD +:100D9000014B04229A61704700080258022803D1CF +:100DA000024B4FF480229A61704700BF000802583E +:100DB000022804D1024A536983F004035361704747 +:100DC00000080258002310B5934203D0CC5CC454F1 +:100DD0000133F9E710BD0000013810B510F9013FEB +:100DE0003BB191F900409C4203D11AB10131013A63 +:100DF000F4E71AB191F90020981A10BD1046FCE7EB +:100E000003460246D01A12F9011B0029FAD1704795 +:100E100002440346934202D003F8011BFAE77047ED +:100E20002DE9F8431F4D14460746884695F82420BF +:100E300052BBDFF870909CB395F824302BB9202278 +:100E4000FF2148462F62FFF7E3FF95F82400414653 +:100E5000C0F1080205EB8000A24228BF2246D6B2AC +:100E60009200FFF7AFFF95F82430A41B17441E44EF +:100E70009044E4B2F6B2082E85F82460DBD1FFF787 +:100E80001FFF0028D7D108E02B6A03EB82038342BF +:100E9000CFD0FFF715FF0028CBD10020BDE8F883A5 +:100EA0000120FBE788230020024B1A78024B1A70BE +:100EB000704700BFB02300201022002010B5104C56 +:100EC000104800F0FBF821460E4800F023F9246892 +:100ED0000D48D4F89020D2F8043843F00203C2F849 +:100EE000043800F0C5FD0949204600F021FAD4F885 +:100EF0009020D2F8043823F00203C2F8043810BD61 +:100F0000503A00087025002040420F00583A00086F +:100F10007047000000B59BB0EFF309816822684676 +:100F2000FFF750FFEFF30583044B9A6BDA6A9A6A76 +:100F30009A6A9A6A9A6A9A6A9B6AFEE700ED00E0EA +:100F400000B59BB0EFF3098168226846FFF73AFFCE +:100F5000EFF30583044B9A6B9A6A9A6A9A6A9A6AC3 +:100F60009A6A9B6AFEE700BF00ED00E000B59BB007 +:100F7000EFF3098168226846FFF724FFEFF305834A +:100F8000034B5A6B9A6A9A6A9A6A9A6A9B6AFEE754 +:100F900000ED00E0FEE7000030B50A44084D914244 +:100FA0000DD011F8013B5840082340F30004013BE9 +:100FB0002C4013F0FF0384EA5000F6D1EFE730BD78 +:100FC0002083B8ED026843681143016003B11847FC +:100FD0007047000013B5406B00F58054D4F8A43876 +:100FE0001A681178042914D1017C022911D11979C8 +:100FF000012312898B4013420BD101A94C3002F01E +:101000003DF8D4F8A4480246019B2179206800F0FD +:10101000DFF902B010BD0000143001F0BFBF0000C6 +:101020004FF0FF33143001F0B9BF00004C3002F034 +:1010300091B800004FF0FF334C3002F08BB8000045 +:10104000143001F08DBF00004FF0FF31143001F07B +:1010500087BF00004C3002F05DB800004FF0FF3257 +:101060004C3002F057B800000020704710B500F572 +:101070008054D4F8A4381A681178042917D1017C57 +:10108000022914D15979012352898B4013420ED180 +:10109000143001F01FFF024648B1D4F8A4484FF4C1 +:1010A000407361792068BDE8104000F07FB910BD41 +:1010B000406BFFF7DBBF0000704700007FB5124BAD +:1010C00001250426044603600023057400F1840210 +:1010D00043602946C0E902330C4B0290143001935F +:1010E0004FF44073009601F0D1FE094B04F6944290 +:1010F000294604F14C000294CDE900634FF440739B +:1011000001F098FF04B070BD8C390008B1100008E0 +:10111000D50F00080A68202383F311880B790B335D +:1011200042F823004B79133342F823008B7913B133 +:101130000B3342F8230000F58053C3F8A4180223B0 +:101140000374002383F311887047000038B5037FD0 +:10115000044613B190F85430ABB90125201D02218B +:10116000FFF730FF04F114006FF00101257700F064 +:10117000A7FC04F14C0084F854506FF00101BDE865 +:10118000384000F09DBC38BD10B501210446043044 +:10119000FFF718FF0023237784F8543010BD0000B8 +:1011A00038B504460025143001F088FE04F14C00E7 +:1011B000257701F057FF201D84F854500121FFF7D7 +:1011C00001FF2046BDE83840FFF750BF90F880305F +:1011D00003F06003202B06D190F881200023212A00 +:1011E00003D81F2A06D800207047222AFBD1C0E965 +:1011F0001D3303E0034A426707228267C367012069 +:10120000704700BF2C22002037B500F58055D5F877 +:10121000A4381A68117804291AD1017C022917D13F +:101220001979012312898B40134211D100F14C042A +:10123000204601F0D7FF58B101A9204601F01EFF5A +:10124000D5F8A4480246019B2179206800F0C0F837 +:1012500003B030BD01F10B03F0B550F8236085B049 +:1012600004460D46FEB1202383F3118804EB850765 +:10127000301D0821FFF7A6FEFB6806F14C005B69F4 +:101280001B681BB1019001F007FF019803A901F051 +:10129000F5FE024648B1039B2946204600F098F827 +:1012A000002383F3118805B0F0BDFB685A6912680A +:1012B000002AF5D01B8A013B1340F1D104F18002D2 +:1012C000EAE70000133138B550F82140ECB1202393 +:1012D00083F3118804F58053D3F8A4281368527956 +:1012E00003EB8203DB689B695D6845B104216018EC +:1012F000FFF768FE294604F1140001F0F5FD2046D1 +:10130000FFF7B4FE002383F3118838BD7047000057 +:1013100001F0E8B801234022002110B5044600F88E +:10132000303BFFF775FD0023C4E9013310BD000019 +:1013300010B52023044683F3118824224160002144 +:101340000C30FFF765FD204601F0EEF80223237014 +:10135000002383F3118810BD70B500EB81030546AF +:1013600050690E461446DA6018B110220021FFF7CA +:101370004FFDA06918B110220021FFF749FD314649 +:101380002846BDE8704001F0E1B9000083682022E2 +:10139000002103F0011310B5044683601030FFF7FD +:1013A00037FD2046BDE8104001F05CBAF0B40125DD +:1013B00000EB810447898D40E4683D43A469458181 +:1013C00023600023A2606360F0BC01F079BA0000E2 +:1013D000F0B4012500EB810407898D40E4683D43AA +:1013E0006469058123600023A2606360F0BC01F0A2 +:1013F000EFBA000070B502230025044624220370D2 +:101400002946C0F888500C3040F8045CFFF700FD16 +:10141000204684F8705001F02DF963681B6823B1F1 +:1014200029462046BDE87040184770BD037880F813 +:101430008C300523037043681B6810B504460BB15C +:10144000042198470023A36010BD000090F88C2071 +:10145000436802701B680BB10521184770470000F4 +:1014600070B590F87030044613B1002380F87030E6 +:1014700004F18002204601F019FA63689B68B3B951 +:1014800094F8803013F0600535D00021204601F03B +:10149000C3FC0021204601F0B3FC63681B6813B154 +:1014A000062120469847062384F8703070BD2046F8 +:1014B00098470028E4D0B4F88630A26F9A4288BFDB +:1014C000A36794F98030A56F002B4FF0200380F2C2 +:1014D0000381002D00F0F280092284F8702083F34C +:1014E000118800212046D4E91D23FFF771FF002356 +:1014F00083F31188DAE794F8812003F07F0343EA4D +:10150000022340F20232934200F0C58021D8B3F5A5 +:10151000807F48D00DD8012B3FD0022B00F0938064 +:10152000002BB2D104F1880262670222A267E3674E +:10153000C1E7B3F5817F00F09B80B3F5407FA4D174 +:1015400094F88230012BA0D1B4F8883043F0020324 +:1015500032E0B3F5006F4DD017D8B3F5A06F31D09E +:10156000A3F5C063012B90D86368204694F88220CD +:101570005E6894F88310B4F88430B047002884D0B3 +:10158000436863670368A3671AE0B3F5106F36D04A +:1015900040F6024293427FF478AF5C4B63670223CC +:1015A000A3670023C3E794F88230012B7FF46DAF6B +:1015B000B4F8883023F00203A4F88830C4E91D553C +:1015C000E56778E7B4F88030B3F5A06F0ED194F8F2 +:1015D0008230204684F88A3001F0AAF863681B68DC +:1015E00013B1012120469847032323700023C4E947 +:1015F0001D339CE704F18B0363670123C3E7237862 +:10160000042B10D1202383F311882046FFF7BEFE60 +:1016100085F311880321636884F88B5021701B685F +:101620000BB12046984794F88230002BDED084F826 +:101630008B300423237063681B68002BD6D00221F3 +:1016400020469847D2E794F8843020461D0603F0E0 +:101650000F010AD501F01CF9012804D002287FF4FB +:1016600014AF2B4B9AE72B4B98E701F003F9F3E704 +:1016700094F88230002B7FF408AF94F8843013F094 +:101680000F01B3D01A06204602D501F0DDFBADE70D +:1016900001F0CEFBAAE794F88230002B7FF4F5AE80 +:1016A00094F8843013F00F01A0D01B06204602D519 +:1016B00001F0B2FB9AE701F0A3FB97E7142284F84C +:1016C000702083F311882B462A4629462046FFF7CF +:1016D0006DFE85F31188E9E65DB1152284F870206E +:1016E00083F3118800212046D4E91D23FFF75EFE15 +:1016F000FDE60B2284F8702083F311882B462A46DE +:1017000029462046FFF764FEE3E700BFBC39000826 +:10171000B4390008B839000838B590F8703004467C +:10172000002B3ED0063BDAB20F2A34D80F2B32D82A +:10173000DFE803F0373131082232313131313131D4 +:1017400031313737856FB0F886309D4214D2C36887 +:101750001B8AB5FBF3F203FB12556DB9202383F30B +:1017600011882B462A462946FFF732FE85F3118859 +:101770000A2384F870300EE0142384F8703020239C +:1017800083F31188002320461A461946FFF70EFE00 +:10179000002383F3118838BDC36F03B1984700233A +:1017A000E7E70021204601F037FB0021204601F049 +:1017B00027FB63681B6813B1062120469847062360 +:1017C000D7E7000010B590F870300446142B29D0EC +:1017D00017D8062B05D001D81BB110BD093B022B31 +:1017E000FBD80021204601F017FB0021204601F024 +:1017F00007FB63681B6813B1062120469847062340 +:1018000019E0152BE9D10B2380F87030202383F3E6 +:10181000118800231A461946FFF7DAFD002383F3E7 +:101820001188DAE7C3689B695B68002BD5D1C36F69 +:1018300003B19847002384F87030CEE7024B0022B2 +:10184000C3E900339A607047B42300200023826804 +:101850000374054B1B6899689142FBD25A68036078 +:101860004260106058607047B423002008B5202300 +:1018700083F31188037C032B05D0042B0DD02BB9E7 +:1018800083F3118808BD436900221A604FF0FF33CB +:101890004361FFF7DBFF0023F2E7D0E9003213607A +:1018A0005A60F3E7002382680374054B1B6899684C +:1018B0009142FBD85A6803604260106058607047DC +:1018C000B4230020054B1969087418680268536036 +:1018D0001A60186101230374FEF778BDB423002059 +:1018E0004B1C30B5044687B00A4D10D02B6901A8B7 +:1018F000094A00F001F92046FFF7E4FF049B13B109 +:1019000001A800F035F92B69586907B030BDFFF721 +:10191000D9FFF8E7B42300206D18000838B50C4D46 +:10192000044641612B6981689A68914203D8BDE8F9 +:101930003840FFF78BBF1846FFF7B4FF01232C6137 +:10194000014623742046BDE83840FEF73FBD00BF86 +:10195000B4230020044B1A681B6990689B68984266 +:1019600094BF002001207047B423002010B5084C1C +:10197000236820691A6854602260012223611A7466 +:10198000FFF790FF01462069BDE81040FEF71EBD3D +:10199000B4230020FFF7EABFFEE7000010B50C4CAF +:1019A000FFF74CFF00F09AF880220A49204600F029 +:1019B00021F8012344F8180C037400F071FC002393 +:1019C00083F3118862B60448BDE8104000F032B8D5 +:1019D000DC230020C0390008D039000800F002B92B +:1019E000034A516853685B1A9842FBD8704700BF9E +:1019F000001000E082600222028270478368A3F137 +:101A00007C0243F80C2C026943F83C2C426943F8F1 +:101A1000382C074A43F81C2CC268A3F1180043F87D +:101A2000102C022203F8082C002203F8072C704720 +:101A3000E503000810B5202383F31188FFF7DEFFCC +:101A400000210446FFF76AFF002383F31188204634 +:101A500010BD0000024B1B6958610F20FFF732BF19 +:101A6000B4230020202383F31188FFF7F3BF000085 +:101A700008B50146202383F311880820FFF730FFC3 +:101A8000002383F3118808BD49B1064B42681B69E6 +:101A900018605A60136043600420FFF721BF4FF0C5 +:101AA000FF307047B42300200368984206D01A68BC +:101AB0000260506018465961FFF7C8BE70470000C9 +:101AC00038B504460D462068844200D138BD03680D +:101AD00023605C604561FFF7B9FEF4E7054B4FF00A +:101AE000FF3103F11402C3E905220022C3E9071202 +:101AF000704700BFB423002070B51C4E05460C464D +:101B0000C0E9032301F0A4FB334653F8142F9A4293 +:101B10000DD130620A2C2CBF00190A302A60C5E9A9 +:101B20000124C6E90555BDE8704001F07BBB316A70 +:101B3000431AE31838BF1C469368A34202D9081918 +:101B400001F080FB73699A6894420CD85A68AC60C3 +:101B50002B606A6015609A685D60121B9A604FF096 +:101B6000FF33F36170BDA41A1B68ECE7B4230020B7 +:101B700038B51B4C636998420DD08168D0E90032BA +:101B800013605A600022C2609A680A449A604FF05B +:101B9000FF33E36138BD03682246002142F8143F59 +:101BA00093425A60C16003D1BDE8384001F044BBA4 +:101BB0009A688168256A0A449A6001F049FB636962 +:101BC000411B9A688A42E5D9AB181D1A206A092D73 +:101BD00098BF01F10A02BDE83840104401F032BB61 +:101BE000B42300202DE9F041184C002704F114061D +:101BF000656901F02DFB236AAA68C11A8A4215D8CB +:101C00001344D5F80C802362D5E9003213605A6082 +:101C10006369EF60B34201D101F00EFB87F31188D5 +:101C20002869C047202383F31188E1E76169B14245 +:101C300009D013441B1ABDE8F0410A2B2CBFC01871 +:101C40000A3001F0FFBABDE8F08100BFB4230020E4 +:101C500000207047FEE70000704700004FF0FF30A3 +:101C60007047000002290CD0032904D0012907483D +:101C700018BF00207047032A05D8054800EBC200B2 +:101C80007047044870470020704700BFB43A00080E +:101C90003C220020683A000870B59AB00546084614 +:101CA000144601A900F0C2F801A8FFF7A9F8431CE7 +:101CB0000022C6B25B001046C5E90034237003233E +:101CC000023404F8013C01ABD1B202348E4201D897 +:101CD0001AB070BD13F8011B013204F8010C04F8AE +:101CE000021CF1E708B5202383F311880348FFF7AE +:101CF0008BFA002383F3118808BD00BF70250020F4 +:101D000090F8803003F01F02012A07D190F881205B +:101D10000B2A03D10023C0E91D3315E003F0600353 +:101D2000202B08D1B0F884302BB990F88120212ADB +:101D300003D81F2A04D8FFF749BA222AEBD0FAE7C2 +:101D4000034A426707228267C3670120704700BFCA +:101D50003322002007B5052917D8DFE801F019164E +:101D600003191920202383F31188104A01210190BF +:101D7000FFF7F2FA019802210D4AFFF7EDFA0D483C +:101D8000FFF70EFA002383F3118803B05DF804FB1C +:101D9000202383F311880748FFF7D8F9F2E72023BF +:101DA00083F311880348FFF7EFF9EBE7083A0008DF +:101DB0002C3A00087025002038B50C4D0C4C2A46F2 +:101DC0000C4904F10800FFF767FF05F1CA0204F1AE +:101DD00010000949FFF760FF05F5CA7204F1180009 +:101DE0000649BDE83840FFF757BF00BF483E002016 +:101DF0003C220020E8390008F2390008FD390008CB +:101E000070B5044608460D46FEF7FAFFC6B22046F6 +:101E1000013403780BB9184670BD32462946FEF7E7 +:101E2000DBFF0028F3D10120F6E700002DE9F047A1 +:101E300005460C46FEF7E4FF2C49C6B22846FFF7DC +:101E4000DFFF08B10836F6B229492846FFF7D8FF68 +:101E500008B11036F6B2632E0BD8DFF89080DFF8A9 +:101E60009090244FDFF898A02E7846B92670BDE8F0 +:101E7000F08729462046BDE8F04701F071BD252EC8 +:101E800030D1072241462846FEF7A6FF80B91A4BFB +:101E9000224603F10C0153F8040B8B4242F8040B69 +:101EA000F9D1198807359B780F3411809370DBE7DF +:101EB000082249462846FEF78FFF98B9A21C0F4B0F +:101EC000197802320909C95D02F8041C13F8011BD4 +:101ED00001F00F015345C95D02F8031CF0D118341D +:101EE0000835C1E7013504F8016BBDE7D43A0008B5 +:101EF000FD390008EC3A0008DC3A000800E8F11F60 +:101F00000CE8F11FBFF34F8F044B1A695107FCD146 +:101F1000D3F810215207F8D1704700BF00200052BB +:101F200008B50D4B1B78ABB9FFF7ECFF0B4BDA682C +:101F3000D10704D50A4A5A6002F188325A60D3F8B0 +:101F40000C21D20706D5064AC3F8042102F18832D3 +:101F5000C3F8042108BD00BFA640002000200052A5 +:101F60002301674508B5114B1B78F3B9104B1A696B +:101F7000510703D5DA6842F04002DA60D3F8102145 +:101F8000520705D5D3F80C2142F04002C3F80C21CA +:101F9000FFF7B8FF064BDA6842F00102DA60D3F8C7 +:101FA0000C2142F00102C3F80C2108BDA64000201C +:101FB000002000520F289ABF00F5806040040020E6 +:101FC000704700004FF40030704700001020704749 +:101FD0000F2808B50BD8FFF7EDFF00F500330268B6 +:101FE000013204D104308342F9D1012008BD002020 +:101FF000FCE700000F2838B505463FD8FFF782FF01 +:102000001F4CFFF78DFF4FF0FF3307286361C4F8C3 +:1020100014311DD82361FFF775FF030243F0240339 +:10202000E360E36843F08003E36023695A07FCD46C +:102030002846FFF767FFFFF7BDFF4FF4003100F0C0 +:10204000F7F82846FFF78EFFBDE83840FFF7C0BF1E +:10205000C4F81031FFF756FFA0F108031B0243F04C +:102060002403C4F80C31D4F80C3143F08003C4F8D5 +:102070000C31D4F810315B07FBD4D9E7002038BD10 +:10208000002000522DE9F84F05460C46104645EA5F +:102090000203DB065DD122F003022B462A44934261 +:1020A00009D120F01F00DFF8BCB0DFF8BCA0FFF7BB +:1020B00037FF271844E0196801314AD10433EEE7AD +:1020C00005F1784324492548B3F5801F244B38BFD8 +:1020D000184603F1F80339BF8846D9469846D146D9 +:1020E000FFF710FF4FF0FF33A5EB040C04F11C01C8 +:1020F0000360D8F8003043F00203C8F80030231F13 +:10210000D9F8006016F00506FAD153F8042F994269 +:102110004CF80320F4D1BFF34F8FFFF7F3FE4FF0DD +:10212000FF332022214603602846D8F8003023F0F0 +:102130000203C8F8003001F003FC40B92035203418 +:10214000BC42BDD10120FFF70DFFBDE8F88F30463E +:10215000F9E70020F9E700BF0C20005214210052DB +:1021600014200052102000521021005210B5084CCB +:10217000237828B11BB9FFF7D3FE0123237010BDCC +:10218000002BFCD02070BDE81040FFF7EBBE00BF75 +:10219000A64000200244074BD2B210B5904200D1B5 +:1021A00010BD441C00B253F8200041F8040BE0B20B +:1021B000F4E700BF504000580E4B30B51C6F2404AC +:1021C00005D41C6F1C671C6F44F400441C670A4C48 +:1021D00002442368D2B243F480732360074B9042D9 +:1021E00000D130BD441C51F8045B00B243F82050CC +:1021F000E0B2F4E70044025800480258504000584A +:1022000007B5012201A90020FFF7C4FF019803B020 +:102210005DF804FB13B50446FFF7F2FFA04205D0BA +:10222000012201A900200194FFF7C6FF02B010BDF2 +:102230000144BFF34F8F064B884204D3BFF34F8F47 +:10224000BFF36F8F7047C3F85C022030F4E700BF24 +:1022500000ED00E0034B1A681AB9034AD2F8D02403 +:102260001A607047A84000200040025808B5FFF7E8 +:10227000F1FF024B1868C0F3806008BDA840002041 +:10228000EFF30983054968334A6B22F001024A6380 +:1022900083F30988002383F31188704700EF00E07F +:1022A000202080F3118862B60D4B0E4AD96821F4C4 +:1022B000E0610904090C0A430B49DA60D3F8FC20F9 +:1022C00042F08072C3F8FC20084AC2F8B01F1168BF +:1022D00041F0010111601022DA7783F82200704783 +:1022E00000ED00E00003FA0555CEACC5001000E09B +:1022F000202310B583F311880E4B5B6813F4006341 +:1023000014D0F1EE103AEFF309844FF08073683C7B +:10231000E361094BDB6B236684F30988FFF71AFB43 +:1023200010B1064BA36110BD054BFBE783F3118889 +:10233000F9E700BF00ED00E000EF00E0F703000860 +:10234000FA03000870B5BFF34F8FBFF36F8F1A4ABF +:102350000021C2F85012BFF34F8FBFF36F8F536944 +:1023600043F400335361BFF34F8FBFF36F8FC2F855 +:102370008410BFF34F8FD2F8803043F6E074C3F37C +:10238000C900C3F34E335B0103EA0406014646EA83 +:1023900081750139C2F86052F9D2203B13F1200F48 +:1023A000F2D1BFF34F8F536943F480335361BFF3CE +:1023B0004F8FBFF36F8F70BD00ED00E0FEE70000B0 +:1023C0000A4B0B480B4A90420BD30B4BC11EDA1C35 +:1023D000121A22F003028B4238BF00220021FEF7BE +:1023E00017BD53F8041B40F8041BECE7CC3C000875 +:1023F0007C4200207C4200207C420020704700008C +:1024000070B5D0E9244300224FF0FF359E6804EBFD +:1024100042135101D3F80009002805DAD3F8000966 +:1024200040F08040C3F80009D3F8000B002805DA1B +:10243000D3F8000B40F08040C3F8000B0132631862 +:102440009642C3F80859C3F8085BE0D24FF0011375 +:10245000C4F81C3870BD000000EB8103D3F80CC039 +:102460002DE9F043DCF814204E1CD0F89050D2F83F +:1024700000E005EB063605EB4118506870450AD3BD +:102480000122D5F8343802FA01F123EA0101C5F836 +:102490003418BDE8F083AEEB0003BCF81040A34253 +:1024A00028BF2346D8F81849A4B2B3EB840FF0D85C +:1024B0009468A4F1040959F8047F3760A4EB090774 +:1024C0001F44042FF7D81C44034494605360D4E79E +:1024D000890141F02001016103699B06FCD41220AF +:1024E000FFF77EBA10B50A4C2046FEF713FF094BE2 +:1024F000C4F89030084BC4F89430084C2046FEF7DE +:1025000009FF074BC4F89030064BC4F8943010BD57 +:10251000AC40002000000840243B00084841002057 +:1025200000000440303B000870B503780546012BDD +:102530005DD1494BD0F89040984259D1474B0E217C +:102540006520D3F8D82042F00062C3F8D820D3F831 +:10255000002142F00062C3F80021D3F80021D3F833 +:10256000802042F00062C3F88020D3F8802022F05F +:102570000062C3F88020D3F8803000F071FC384B43 +:10258000E360384BC4F800380023D5F89060C4F8F5 +:10259000003EC02323604FF40413A3633369002B70 +:1025A000FCDA01230C203361FFF71AFA3369DB07E9 +:1025B000FCD41220FFF714FA3369002BFCDA002652 +:1025C0002846A660FFF71CFF6B68C4F81068DB683C +:1025D000C4F81468C4F81C68002B3AD1224BA361DC +:1025E0004FF0FF336361A36843F00103A36070BD44 +:1025F0001E4B9842C8D1194B0E214D20D3F8D8203C +:1026000042F00072C3F8D820D3F8002142F00072E3 +:10261000C3F80021D3F80021D3F8802042F00072E3 +:10262000C3F88020D3F8802022F00072C3F8802005 +:10263000D3F88020D3F8D82022F08062C3F8D820C5 +:10264000D3F8002122F08062C3F80021D3F80031D2 +:1026500093E7074BC3E700BFAC400020004402589B +:102660004014004003002002003C30C048410020DC +:10267000083C30C0F8B5D0F89040054600214FF036 +:1026800000662046FFF724FFD5F8941000234FF092 +:1026900001128F684FF0FF30C4F83438C4F81C289A +:1026A00004EB431201339F42C2F80069C2F8006B89 +:1026B000C2F80809C2F8080BF2D20B68D5F89020CE +:1026C000C5F89830636210231361166916F010067E +:1026D000FBD11220FFF784F9D4F8003823F4FE630D +:1026E000C4F80038A36943F4402343F01003A36106 +:1026F0000923C4F81038C4F814380B4BEB604FF0C2 +:10270000C043C4F8103B094BC4F8003BC4F810693F +:10271000C4F80039D5F8983003F1100243F480135F +:10272000C5F89820A362F8BD003B00084080001067 +:10273000D0F8902090F88A10D2F8003823F4FE6385 +:1027400043EA0113C2F80038704700002DE9F8434E +:1027500000EB8103D0F890500C468046DA680FFAFF +:1027600081F94801166806F00306731E022B05EB7B +:1027700041134FF0000194BFB604384EC3F8101B4C +:102780004FF0010104F1100398BF06F1805601FAE1 +:1027900003F3916998BF06F5004600293AD0578A9D +:1027A00004F15801374349016F50D5F81C180B4309 +:1027B0000021C5F81C382B180127C3F81019A740B1 +:1027C0005369611E9BB3138A928B9B08012A88BFB1 +:1027D0005343D8F89820981842EA034301F1400285 +:1027E0002146C8F89800284605EB82025360FFF79F +:1027F0006FFE08EB8900C3681B8A43EA84534834A0 +:102800001E4364012E51D5F81C381F43C5F81C78AF +:10281000BDE8F88305EB4917D7F8001B21F4004108 +:10282000C7F8001BD5F81C1821EA0303C0E704F120 +:102830003F030B4A2846214605EB83035A60FFF706 +:1028400047FE05EB4910D0F8003923F40043C0F8E7 +:102850000039D5F81C3823EA0707D7E700800010B5 +:1028600000040002D0F894201268C0F89820FFF706 +:10287000C7BD00005831D0F8903049015B5813F4BF +:10288000004004D013F4001F0CBF02200120704749 +:102890004831D0F8903049015B5813F4004004D01F +:1028A00013F4001F0CBF02200120704700EB8101D0 +:1028B000CB68196A0B6813604B685360704700005F +:1028C00000EB810330B5DD68AA691368D36019B9DC +:1028D000402B84BF402313606B8A1468D0F890208B +:1028E0001C4402EB4110013C09B2B4FBF3F4634316 +:1028F000033323F0030343EAC44343F0C043C0F867 +:10290000103B2B6803F00303012B0ED1D2F80838DB +:1029100002EB411013F4807FD0F8003B14BF43F06A +:10292000805343F00053C0F8003B02EB4112D2F851 +:10293000003B43F00443C2F8003B30BD2DE9F041B9 +:10294000D0F8906005460C4606EB4113D3F8087B9F +:102950003A07C3F8087B08D5D6F814381B0704D506 +:1029600000EB8103DB685B689847FA071FD5D6F850 +:102970001438DB071BD505EB8403D968CCB98B6908 +:10298000488A5A68B2FBF0F600FB16228AB918682A +:10299000DA6890420DD2121AC3E90024202383F38F +:1029A000118821462846FFF78BFF84F31188BDE884 +:1029B000F081012303FA04F26B8923EA02036B819D +:1029C000CB68002BF3D021462846BDE8F0411847DC +:1029D00000EB81034A0170B5DD68D0F890306C6976 +:1029E0002668E66056BB1A444FF40020C2F810096E +:1029F0002A6802F00302012A0AB20ED1D3F80808AD +:102A000003EB421410F4807FD4F8000914BF40F0A7 +:102A1000805040F00050C4F8000903EB4212D2F895 +:102A2000000940F00440C2F800090122D3F834083C +:102A300002FA01F10143C3F8341870BD19B9402EF0 +:102A400084BF4020206020681A442E8A8419013CEB +:102A5000B4FBF6F440EAC44040F00050C6E7000082 +:102A60002DE9F041D0F8906004460D4606EB411385 +:102A7000D3F80879C3F80879FB071CD5D6F81038C5 +:102A8000DA0718D500EB8103D3F80CC0DCF814305A +:102A9000D3F800E0DA6896451BD2A2EB0E024FF0A5 +:102AA00000081A60C3F80480202383F31188FFF71D +:102AB0008FFF88F311883B0618D50123D6F83428F8 +:102AC000AB40134212D029462046BDE8F041FFF743 +:102AD000C3BC012303FA01F2038923EA0203038141 +:102AE000DCF80830002BE6D09847E4E7BDE8F08139 +:102AF0002DE9F84FD0F8905004466E69AB691E403E +:102B000016F480586E6103D0BDE8F84FFEF772BC32 +:102B1000002E12DAD5F8003E9F0705D0D5F8003E0A +:102B200023F00303C5F8003ED5F80438204623F00F +:102B30000103C5F80438FEF789FC300505D52046A9 +:102B4000FFF75EFC2046FEF771FCB1040CD5D5F80A +:102B5000083813F0060FEB6823F470530CBF43F4EE +:102B6000105343F4A053EB60320704D56368DB686D +:102B70000BB120469847F30200F1BA80B70226D580 +:102B8000D4F8909000274FF0010A09EB4712D2F8D1 +:102B9000003B03F44023B3F5802F11D1D2F8003B62 +:102BA000002B0DDA62890AFA07F322EA0303638134 +:102BB00004EB8703DB68DB6813B13946204698478E +:102BC0000137D4F89430FFB29B689F42DDD9F006FC +:102BD00019D5D4F89000026AC2F30A1702F00F0365 +:102BE00002F4F012B2F5802F00F0CC80B2F5402F45 +:102BF00009D104EB8303002200F58050DB681B6AD7 +:102C0000974240F0B2803003D5F8185835D5E90323 +:102C100003D500212046FFF791FEAA0303D5012129 +:102C20002046FFF78BFE6B0303D502212046FFF7FA +:102C300085FE2F0303D503212046FFF77FFEE80220 +:102C400003D504212046FFF779FEA90203D505210B +:102C50002046FFF773FE6A0203D506212046FFF7E0 +:102C60006DFE2B0203D507212046FFF767FEEF011B +:102C700003D508212046FFF761FE700340F1A980CB +:102C8000E90703D500212046FFF7EAFEAA0703D58E +:102C900001212046FFF7E4FE6B0703D50221204601 +:102CA000FFF7DEFE2F0703D503212046FFF7D8FEEE +:102CB000EE0603D504212046FFF7D2FEA80603D571 +:102CC00005212046FFF7CCFE690603D506212046E4 +:102CD000FFF7C6FE2A0603D507212046FFF7C0FEF0 +:102CE000EB0576D520460821BDE8F84FFFF7B8BEC2 +:102CF000D4F8909000274FF0010AD4F894305FFA8E +:102D000087FB9B689B453FF639AF09EB4B13D3F824 +:102D1000002902F44022B2F5802F24D1D3F80029F3 +:102D2000002A20DAD3F8002942F09042C3F80029A3 +:102D3000D3F80029002AFBDB5946D4F89000FFF7AE +:102D4000C7FB22890AFA0BF322EA0303238104EB6F +:102D50008B03DB689B6813B1594620469847594658 +:102D60002046FFF779FB0137C7E7910701D1D0F87B +:102D70000080072A02F101029CBF03F8018B4FEA91 +:102D800018283DE704EB830300F58050DA68D2F899 +:102D900018C0DCF80820DCE9001CA1EB0C0C0021B9 +:102DA0008F4208D1DB689B699A683A449A605A68F6 +:102DB0003A445A6027E711F0030F01D1D0F80080A0 +:102DC0008C4501F1010184BF02F8018B4FEA1828FC +:102DD000E6E7BDE8F88F000008B50348FFF788FE76 +:102DE000BDE80840FFF784BAAC40002008B50348AE +:102DF000FFF77EFEBDE80840FFF77ABA48410020A1 +:102E0000D0F8903003EB4111D1F8003B43F40013AC +:102E1000C1F8003B70470000D0F8903003EB41113F +:102E2000D1F8003943F40013C1F8003970470000AD +:102E3000D0F8903003EB4111D1F8003B23F400139C +:102E4000C1F8003B70470000D0F8903003EB41110F +:102E5000D1F8003923F40013C1F80039704700009D +:102E6000090100F16043012203F56143C9B283F80F +:102E7000001300F01F039A4043099B0003F16043D5 +:102E800003F56143C3F880211A60704730B50433FD +:102E9000039C0172002104FB0325C160C0E90653B5 +:102EA000049B0363059BC0E90000C0E90422C0E95C +:102EB0000842C0E90A11436330BD00000022416AA4 +:102EC000C260C0E90411C0E90A226FF00101FEF7F7 +:102ED000F7BD0000D0E90432934201D1C2680AB9BB +:102EE000181D704700207047036919600021C268EF +:102EF0000132C260C269134482699342036124BFF4 +:102F0000436A0361FEF7D0BD38B504460D46E36859 +:102F10003BB162690020131D1268A3621344E3628F +:102F200007E0237A33B929462046FEF7ADFD002895 +:102F3000EDDA38BD6FF00100FBE70000C368C2693D +:102F4000013BC3604369134482699342436124BFD8 +:102F5000436A436100238362036B03B118477047E0 +:102F600070B52023044683F31188866A3EB9FFF7C3 +:102F7000CBFF054618B186F31188284670BDA36AB9 +:102F8000E26A13F8015B9342A36202D32046FFF783 +:102F9000D5FF002383F31188EFE700002DE9F84FF8 +:102FA00004460E46174698464FF0200989F31188CB +:102FB0000025AA46D4F828B0BBF1000F09D141463C +:102FC0002046FFF7A1FF20B18BF311882846BDE80A +:102FD000F88FD4E90A12A7EB050B521A934528BFC4 +:102FE0009346BBF1400F1BD9334601F1400251F823 +:102FF000040B914243F8040BF9D1A36A40364035E3 +:103000004033A362D4E90A239A4202D32046FFF751 +:1030100095FF8AF31188BD42D8D289F31188C9E798 +:1030200030465A46FDF7CEFEA36A5E445D445B44DB +:10303000A362E7E710B5029C0433017204FB03218D +:10304000C460C0E906130023C0E90A33039B03638D +:10305000049BC0E90000C0E90422C0E908424363C0 +:1030600010BD0000026A6FF00101C260426AC0E94F +:1030700004220022C0E90A22FEF722BDD0E904237F +:103080009A4201D1C26822B9184650F8043B0B603D +:103090007047002070470000C3680021C2690133F7 +:1030A000C3604369134482699342436124BF436A06 +:1030B0004361FEF7F9BC000038B504460D46E368ED +:1030C0003BB1236900201A1DA262E2691344E36246 +:1030D00007E0237A33B929462046FEF7D5FC0028BD +:1030E000EDDA38BD6FF00100FBE7000003691960FD +:1030F000C268013AC260C2691344826993420361A3 +:1031000024BF436A036100238362036B03B1184742 +:103110007047000070B520230D460446114683F326 +:103120001188866A2EB9FFF7C7FF10B186F31188A0 +:1031300070BDA36A1D70A36AE26A01339342A36261 +:1031400004D3E16920460439FFF7D0FF002080F363 +:103150001188EDE72DE9F84F04460D469046994653 +:103160004FF0200A8AF311880026B346A76A4FB9A8 +:1031700049462046FFF7A0FF20B187F3118830466B +:10318000BDE8F88FD4E90A073A1AA8EB0607974278 +:1031900028BF1746402F1BD905F1400355F8042BD3 +:1031A0009D4240F8042BF9D1A36A40364033A36214 +:1031B000D4E90A239A4204D3E16920460439FFF78F +:1031C00095FF8BF311884645D9D28AF31188CDE754 +:1031D00029463A46FDF7F6FDA36A3D443E443B448A +:1031E000A362E5E7D0E904239A4217D1C3689BB1F3 +:1031F000836A8BB1043B9B1A0ED01360C368013BFA +:10320000C360C3691A4483699A42026124BF436A56 +:103210000361002383620123184670470023FBE704 +:1032200000F0CEB8034B002258631A610222DA6024 +:10323000704700BF000C0040014B0022DA6070476D +:10324000000C0040014B5863704700BF000C004069 +:10325000014B586A704700BF000C00404B68436048 +:103260008B688360CB68C3600B6943614B69036201 +:103270008B6943620B6803607047000008B5364BEA +:1032800040F2FF713548D3F888200A43C3F88820FC +:10329000D3F8882022F4FF6222F00702C3F88820C6 +:1032A000D3F88820D3F8E0200A43C3F8E020D3F80D +:1032B00008210A43C3F80821294AD3F808311146E6 +:1032C000FFF7CCFF00F5806002F11C01FFF7C6FF9D +:1032D00000F5806002F13801FFF7C0FF00F5806063 +:1032E00002F15401FFF7BAFF00F5806002F17001AE +:1032F000FFF7B4FF00F5806002F18C01FFF7AEFF2D +:1033000000F5806002F1A801FFF7A8FF00F58060DA +:1033100002F1C401FFF7A2FF00F5806002F1E001B5 +:10332000FFF79CFF00F5806002F1FC01FFF796FFBC +:1033300002F58C7100F58060FFF790FF00F0F4F863 +:10334000084B0522C3F898204FF06052C3F89C2028 +:10335000054AC3F8A02008BD0044025800000258E6 +:103360003C3B000800ED00E01F00080308B500F03A +:10337000C9FAFEF713FB0F4BD3F8DC2042F04002F2 +:10338000C3F8DC20D3F8042122F04002C3F8042162 +:10339000D3F80431084B1A6842F008021A601A6820 +:1033A00042F004021A60FEF755FFBDE80840FEF740 +:1033B00003BD00BF004402580018024870470000D7 +:1033C000114BD3F8E82042F00802C3F8E820D3F804 +:1033D000102142F00802C3F810210C4AD3F8103132 +:1033E000D36B43F00803D363C722094B9A624FF0B3 +:1033F000FF32DA6200229A615A63DA605A6001226F +:103400005A611A60704700BF004402580010005C07 +:10341000000C0040094A08B51169D3680B40D9B2C5 +:103420009B076FEA0101116107D5202383F31188FF +:10343000FEF7D4FA002383F3118808BD000C004086 +:10344000384B4FF0FF31D3F88020C3F88010D3F809 +:1034500080200022C3F88020D3F88000D3F88400B5 +:10346000C3F88410D3F88400C3F88420D3F8840010 +:10347000D86F40F0FF4040F4FF0040F43F5040F070 +:103480003F00D867D86F20F0FF4020F4FF0020F401 +:103490003F5020F03F00D867D86FD3F888006FEA1C +:1034A00040506FEA5050C3F88800D3F88800C0F34A +:1034B0000A00C3F88800D3F88800D3F89000C3F856 +:1034C0009010D3F89000C3F89020D3F89000D3F870 +:1034D0009400C3F89410D3F89400C3F89420D3F860 +:1034E0009400D3F89800C3F89810D3F89800C3F864 +:1034F0009820D3F89800D3F88C00C3F88C10D3F838 +:103500008C00C3F88C20D3F88C00D3F89C00C3F84F +:103510009C10D3F89C10C3F89C20D3F89C3000F08A +:10352000C9B900BF00440258614B0122C3F8082109 +:10353000604BD3F8F42042F00202C3F8F420D3F831 +:103540001C2142F00202C3F81C210222D3F81C31D4 +:10355000594BDA605A689104FCD5584A1A60012226 +:103560009A60574ADA6000221A614FF440429A6129 +:10357000514B9A699204FCD51A6842F480721A6021 +:103580004C4B1A6F12F4407F04D04FF480321A670C +:1035900000221A671A6842F001021A60454B1A6845 +:1035A0005007FCD500221A611A6912F03802FBD1CB +:1035B000012119604FF0804159605A67414ADA622F +:1035C000414A1A611A6842F480321A60394B1A680B +:1035D0009103FCD51A6842F480521A601A6892046A +:1035E000FCD53A4A3A499A6200225A63196339492A +:1035F000DA6399635A64384A1A64384ADA621A6894 +:1036000042F0A8521A602B4B1A6802F02852B2F10D +:10361000285FF9D148229A614FF48862DA6140222A +:103620001A622F4ADA644FF080521A652D4A5A65A1 +:103630002D4A9A6532232D4A1360136803F00F0355 +:10364000022BFAD11B4B1A6942F003021A611A6964 +:1036500002F03802182AFAD1D3F8DC2042F00052E6 +:10366000C3F8DC20D3F8042142F00052C3F804214F +:10367000D3F80421D3F8DC2042F08042C3F8DC20E8 +:10368000D3F8042142F08042C3F80421D3F8042186 +:10369000D3F8DC2042F00042C3F8DC20D3F8042148 +:1036A00042F00042C3F80421D3F80431704700BF50 +:1036B00000800051004402580048025800C000F049 +:1036C000020000010000FF01008890081210200095 +:1036D000630209012C02040047040508FD0BFF01E9 +:1036E000200000200010E000000101000020005236 +:1036F0004FF0B04208B5D2F8883003F00103C2F8A9 +:10370000883023B1044A13680BB150689847BDE86C +:103710000840FEF7EDBD00BFFC4100204FF0B04275 +:1037200008B5D2F8883003F00203C2F8883023B11C +:10373000044A93680BB1D0689847BDE80840FEF78B +:10374000D7BD00BFFC4100204FF0B04208B5D2F811 +:10375000883003F00403C2F8883023B1044A1369A7 +:103760000BB150699847BDE80840FEF7C1BD00BFE6 +:10377000FC4100204FF0B04208B5D2F8883003F089 +:103780000803C2F8883023B1044A93690BB1D069A9 +:103790009847BDE80840FEF7ABBD00BFFC410020E4 +:1037A0004FF0B04208B5D2F8883003F01003C2F8E9 +:1037B000883023B1044A136A0BB1506A9847BDE8B8 +:1037C0000840FEF795BD00BFFC4100204FF0B0431C +:1037D00010B5D3F8884004F47872C3F88820A306A3 +:1037E00004D5124A936A0BB1D06A9847600604D593 +:1037F0000E4A136B0BB1506B9847210604D50B4A48 +:10380000936B0BB1D06B9847E20504D5074A136C54 +:103810000BB1506C9847A30504D5044A936C0BB1C7 +:10382000D06C9847BDE81040FEF762BDFC41002017 +:103830004FF0B04310B5D3F8884004F47C42C3F88D +:103840008820620504D5164A136D0BB1506D984758 +:10385000230504D5124A936D0BB1D06D9847E0044F +:1038600004D50F4A136E0BB1506E9847A10404D5CE +:103870000B4A936E0BB1D06E9847620404D5084A88 +:10388000136F0BB1506F9847230404D5044A936F0C +:103890000BB1D06F9847BDE81040FEF729BD00BFBF +:1038A000FC41002008B5FFF7B5FDBDE80840FEF774 +:1038B0001FBD0000062108B50846FFF7D1FA062112 +:1038C0000720FFF7CDFA06210820FFF7C9FA0621E5 +:1038D0000920FFF7C5FA06210A20FFF7C1FA0621E1 +:1038E0001720FFF7BDFA06212820FFF7B9FA0921B2 +:1038F0007A20FFF7B5FA07213220BDE80840FFF72C +:10390000AFBA000008B5FFF79BFD00F00BF8FDF71C +:10391000FFFCFDF7D1FBFFF751FDBDE80840FFF7C5 +:103920007FBC00000023054A19460133102BC2E971 +:10393000001102F10802F8D1704700BFFC410020DD +:1039400010B501390244904201D1002005E003780E +:1039500011F8014FA34201D0181B10BD0130F2E74E +:10396000034611F8012B03F8012B002AF9D1704707 +:1039700053544D333248373F3F3F0053544D333259 +:10398000483734332F373533000000000000000083 +:1039900035100008211000085D10000849100008CB +:1039A00055100008411000082D10000819100008DB +:1039B0006910000800000000010000000000000085 +:1039C0006D61696E0000000069646C6500000000B4 +:1039D000C8390008F82300207025002001000000ED +:1039E00099190008000000004172647550696C6FFD +:1039F000740025424F415244252D424C0025534529 +:103A00005249414C25000000020000000000000067 +:103A100055120008C512000840004000183E002062 +:103A2000283E00200200000000000000030000000B +:103A3000000000000D13000800000000100000004E +:103A4000383E0020000000000100000000000000DF +:103A5000AC40002001010200551D0008651C000853 +:103A6000011D0008E51C000843000000703A000832 +:103A700009024300020100C03209040000010202F1 +:103A800001000524001001052401000104240202A4 +:103A90000524060001070582030800FF0904010050 +:103AA000020A00000007050102400000070581022C +:103AB0004000000012000000BC3A00081201100192 +:103AC00002000040091241570002010203010000F8 +:103AD0000403090425424F41524425004B616B7594 +:103AE000746548372D626473686F74003031323307 +:103AF00034353637383941424344454600000000EA +:103B0000000000006114000819170008C51700081C +:103B100040004000E4410020E4410020010000009A +:103B2000F441002080000000400100000800000077 +:103B30000001000000040000080000000001802ACD +:103B400000000000AAAAAAAA00010024FFFF0000AA +:103B50000000000000A00A000000000100000000BA +:103B6000AAAAAAAA00000001FFFF000000000000AE +:103B7000000000001000000400000000AAAAAAAA89 +:103B800000000008FBDF0000000000000000000053 +:103B90000000000000000000AAAAAAAA000000007D +:103BA000FFFF000000000000000000000001000016 +:103BB00000000000AAAAAAAA00010000FFFF00005E +:103BC00000000000000000000000000000000000F5 +:103BD000AAAAAAAA00000000FFFF0000000000003F +:103BE000000000000000000000000000AAAAAAAA2D +:103BF00000000000FFFF00000000000000000000C7 +:103C00000000000000000000AAAAAAAA000000000C +:103C1000FFFF0000000000000000000000000000A6 +:103C200000000000AAAAAAAA00000000FFFF0000EE +:103C30000000000000000000000000000000000084 +:103C4000AAAAAAAA00000000FFFF000000000000CE +:103C5000000000000000000000000000AAAAAAAABC +:103C600000000000FFFF0000000000000000000056 +:103C7000180400000000000000001E00000000000A +:103C8000FF00000000000000703900083F00000045 +:103C9000500400007B3900083F000000009600003F +:103CA000000008009600000000080000040000006A +:103CB000D03A0008000000000000000000000000F2 +:0C3CC000000000000000000000000000F8 +:00000001FF diff --git a/Tools/bootloaders/KakuteH7Mini-Nand_bl.bin b/Tools/bootloaders/KakuteH7Mini-Nand_bl.bin new file mode 100644 index 00000000000..94dc4e96e40 Binary files /dev/null and b/Tools/bootloaders/KakuteH7Mini-Nand_bl.bin differ diff --git a/Tools/bootloaders/KakuteH7Mini-Nand_bl.hex b/Tools/bootloaders/KakuteH7Mini-Nand_bl.hex new file mode 100644 index 00000000000..0d5f78494c2 --- /dev/null +++ b/Tools/bootloaders/KakuteH7Mini-Nand_bl.hex @@ -0,0 +1,984 @@ +:020000040800F2 +:1000000000060020A1020008AD0F00082D0F000817 +:10001000850F00082D0F0008590F0008A3020008E3 +:10002000A3020008A3020008A3020008F9220008A6 +:10003000A3020008A3020008A3020008A30200080C +:10004000A3020008A3020008A3020008A3020008FC +:10005000A3020008A302000881370008AD3700089A +:10006000D93700080538000831380008A302000815 +:10007000A3020008A3020008A3020008A3020008CC +:10008000A3020008A3020008A3020008A3020008BC +:10009000A3020008A3020008A30200085D380008BC +:1000A000A3020008A3020008A3020008A30200089C +:1000B000A3020008A3020008A3020008A30200088C +:1000C000A3020008A3020008A3020008A30200087C +:1000D000A3020008A3020008A3020008A30200086C +:1000E000C1380008A3020008A3020008A302000808 +:1000F000A3020008A3020008A3020008A30200084C +:10010000A3020008A302000835390008A302000872 +:10011000A3020008A3020008A3020008A30200082B +:10012000A3020008A3020008A3020008A30200081B +:10013000A3020008A3020008A3020008A30200080B +:10014000A3020008A3020008A3020008A3020008FB +:10015000A3020008A3020008A3020008A3020008EB +:10016000A3020008A3020008A3020008A3020008DB +:10017000A3020008652E0008A3020008A3020008DD +:10018000A3020008A3020008A3020008A3020008BB +:10019000A3020008A3020008A3020008A3020008AB +:1001A000A3020008A3020008A3020008A30200089B +:1001B000A3020008A3020008A3020008A30200088B +:1001C000A3020008A3020008A3020008A30200087B +:1001D000A3020008512E0008A3020008A302000891 +:1001E000A3020008A3020008A3020008A30200085B +:1001F000A3020008A3020008A3020008A30200084B +:10020000A3020008A3020008A3020008A30200083A +:10021000A3020008A3020008A3020008A30200082A +:10022000A3020008A3020008A3020008A30200081A +:10023000A3020008A3020008A3020008A30200080A +:10024000A3020008A3020008A3020008A3020008FA +:10025000A3020008A3020008A3020008A3020008EA +:10026000A3020008A3020008A3020008A3020008DA +:10027000A3020008A3020008A3020008A3020008CA +:10028000A3020008A3020008A3020008A3020008BA +:10029000A3020008A3020008A3020008A3020008AA +:1002A00002E000F000F8FEE772B63A4880F30888F2 +:1002B000394880F3098839484EF60851CEF20001DA +:1002C000086040F20000CCF200004EF63471CEF22D +:1002D00000010860BFF34F8FBFF36F8F40F2000043 +:1002E000C0F2F0004EF68851CEF200010860BFF374 +:1002F0004F8FBFF36F8F4FF00000E1EE100A4EF604 +:100300003C71CEF200010860062080F31488BFF330 +:100310006F8F02F0AFF802F051F802F0EBFF4FF0F0 +:1003200055301F491B4A91423CBF41F8040BFAE784 +:100330001C49194A91423CBF41F8040BFAE71A499B +:100340001A4A1B4B9A423EBF51F8040B42F8040B69 +:10035000F8E700201749184A91423CBF41F8040BC6 +:10036000FAE702F069F803F049F8144C144DAC4276 +:1003700003DA54F8041B8847F9E700F041F8114C00 +:10038000114DAC4203DA54F8041B8847F9E702F038 +:1003900051B80000000600200022002000000008E4 +:1003A0000000002000060020003D00080022002080 +:1003B0005C220020602200207C420020A002000875 +:1003C000A0020008A0020008A00200082DE9F04FDA +:1003D0002DED108AC1F80CD0D0F80CD0BDEC108AED +:1003E000BDE8F08F002383F311882846A047002042 +:1003F00001F068FBFEE701F0E3FA00DFFEE7000032 +:1004000038B500F0CDFC30B1164B00220E211A7227 +:100410005A729972DA7201F02FFF054601F062FFFD +:100420000446D0B9104B9D4219D001339D4241F290 +:10043000883512BF044600250124002001F026FF64 +:100440000CB100F059F800F045FD00F0E3FB284640 +:1004500000F004F900F050F8F9E70025EDE7054653 +:10046000EBE700BF00220020010007B008B500F054 +:10047000A3FBA0F120035842584108BD07B541F243 +:100480001203022101A8ADF8043000F0B3FB03B061 +:100490005DF804FB202310B583F311881248C3686C +:1004A0000BB101F095FB0023104A4FF47A710E480E +:1004B00001F052FB002383F311880D4C236813B124 +:1004C0002368013B2360636813B16368013B636089 +:1004D000084B1B7833B9636823B9022000F074FC21 +:1004E0003223636010BD00BF602200209504000825 +:1004F0007C23002074220020F8B5514B514A1C4641 +:100500001968013100F09B8004339342F8D162688E +:100510004D4B9A4240F293804C4B9B6803F1006331 +:1005200003F500339A4280F08A80002000F098FBA7 +:100530000220474B187000F03DFC464B0021D3F8D9 +:10054000E820C3F8E810D3F81021C3F81011D3F84D +:100550001021D3F8EC20C3F8EC10D3F81421C3F821 +:100560001411D3F81421D3F8F020C3F8F010D3F805 +:100570001821C3F81811D3F81821D3F8802042F0BD +:100580000062C3F88020D3F8802022F00062C3F814 +:100590008020D3F88020D3F8802042F00072C3F886 +:1005A0008020D3F8802022F00072C3F88020D3F896 +:1005B000803072B64FF0E023C3F8084DD4E9000450 +:1005C000BFF34F8FBFF36F8F234AC2F88410BFF37E +:1005D0004F8F536923F480335361BFF34F8FD2F8A9 +:1005E000803043F6E076C3F3C905C3F34E335B01B5 +:1005F00003EA060C29464CEA81770139C2F8747285 +:10060000F9D2203B13F1200FF2D1BFF34F8FBFF38C +:100610006F8FBFF34F8FBFF36F8F536923F4003396 +:1006200053610023C2F85032BFF34F8FBFF36F8F77 +:10063000202383F31188854680F308882047F8BD7E +:100640000000020820000208FFFF0108002200202D +:10065000742200200044025800ED00E02DE9F04F24 +:1006600093B0A94B2022FF2100900AA89D6800F0BA +:10067000DBFBA64A1378A3B90121A5481170C3601A +:10068000202383F31188C3680BB101F0A1FA002382 +:10069000A04A4FF47A719E4801F05EFA002383F37A +:1006A0001188009B9C4A03B1136000239B49009C66 +:1006B00098469B461E469A460B705360012000F0F8 +:1006C00079FB24B1944B1B68002B00F016820020AC +:1006D00000F072FA0390039B002BF2DB012000F084 +:1006E00061FB039B213B162BE8D801A252F823F0B3 +:1006F0004D0700087507000809080008BD06000836 +:10070000BD060008BD0600089D0800086F0A000825 +:1007100089090008EB090008130A0008390A0008D3 +:10072000BD0600084B0A0008BD060008BD0A000807 +:10073000ED070008BD060008010B00085907000876 +:10074000ED070008BD060008EB0900080220FFF7CE +:100750008DFE002840F0FB81009B022105A8B8F126 +:10076000000F08BF1C4641F21233ADF8143000F000 +:1007700041FAA3E74FF47A7000F01EFA071EEBDB94 +:100780000220FFF773FE0028E6D0013F052F00F29C +:10079000E081DFE807F0030A0D101336052304217A +:1007A00005A8059300F026FA17E004215648F9E75A +:1007B00004215B48F6E704215A48F3E74FF01C098F +:1007C000484609F1040900F04DFA0421059005A8F6 +:1007D00000F010FAB9F12C0FF2D101204FF0000A0D +:1007E00000FA07F747EA0B0B5FFA8BFB00F068FB98 +:1007F00026B10BF00B030B2B08BF0024FFF73EFEC6 +:100800005CE704214848CDE7002EA5D00BF00B0390 +:100810000B2BA1D10220FFF729FE074600289BD011 +:1008200001203E4E00F01CFA4FF00008022030700C +:1008300000F0C0FA5FFA88F9484600F021FA044651 +:1008400090B1484608F1010800F02AFA0028F1D1D9 +:10085000B846044641F21213022105A83E46ADF8FF +:10086000143000F0C7F929E7012325460220337030 +:1008700000F098FA244B9B68AB4207D9284600F059 +:10088000F1F9013040F068810435F3E70025234B8E +:10089000B8463E461D70204B5D60A7E7002E3FF432 +:1008A0005BAF0BF00B030B2B7FF456AF02201B4BFF +:1008B000187000F07FFA322000F07EF9B0F10009E4 +:1008C000FFF64AAF19F003077FF446AF0E4A09EB73 +:1008D0000503926893423FF63FAFB9F5807F3FF73B +:1008E0003BAF124BB945019322DD4FF47A7000F013 +:1008F00063F90390039A002AFFF62EAF039A01379B +:10090000019B03F8012BEDE7002200207823002053 +:1009100060220020950400087C230020742200201F +:1009200004220020082200200C220020782200202F +:10093000C820FFF79BFD074600283FF40DAF1F2D91 +:1009400011D8C5F120020AAB25F0030084494A45BD +:10095000184428BF4A46019200F040FA019AFF214C +:100960007F4800F061FA4FEAA903C9F387027C4986 +:100970002846019300F060FA064600283FF46AAF6B +:10098000019B05EB830531E70220FFF76FFD00288F +:100990003FF4E2AE00F0A0F900283FF4DDAE0027FE +:1009A000B946704B9B68BB4218D91F2F11D80A9BC0 +:1009B00001330ED027F0030312AA134453F8203C4E +:1009C00005934846042205A9043700F0F1FA814650 +:1009D000E7E7384600F046F90590F2E7CDF81490C5 +:1009E000042105A800F006F900E70023642104A80B +:1009F000049300F0F5F800287FF4AEAE0220FFF774 +:100A000035FD00283FF4A8AE049800F05BF905908E +:100A1000E6E70023642104A8049300F0E1F800282D +:100A20007FF49AAE0220FFF721FD00283FF494AE38 +:100A3000049800F049F9EAE70220FFF717FD0028C3 +:100A40003FF48AAE00F058F9E1E70220FFF70EFD0F +:100A500000283FF481AE05A9142000F053F90746A1 +:100A60000421049004A800F0C5F83946B9E7322003 +:100A700000F0A2F8071EFFF66FAEBB077FF46CAE66 +:100A8000384A07EB0A03926893423FF665AE0220AC +:100A9000FFF7ECFC00283FF45FAE27F00307574454 +:100AA000BA453FF4A3AE50460AF1040A00F0DAF862 +:100AB0000421059005A800F09DF8F1E74FF47A7045 +:100AC000FFF7D4FC00283FF447AE00F005F90028FA +:100AD00044D00A9B01330BD008220AA9002000F061 +:100AE000ABF900283AD02022FF210AA800F09CF997 +:100AF000FFF7C4FC1C4800F0EBFF13B0BDE8F08F1B +:100B0000002E3FF429AE0BF00B030B2B7FF424AE29 +:100B10000023642105A8059300F062F80746002829 +:100B20007FF41AAE0220FFF7A1FC814600283FF4B3 +:100B300013AEFFF7A3FC41F2883000F0C9FF05981F +:100B400000F0F2F94E463C4600F0BAF9B6E506462A +:100B50004CE64FF0000AFFE5B8467BE6374679E6FB +:100B60007822002000220020A08601000F4B70B5E3 +:100B70001B780C460133DBB2012B11D80C4D4FF41E +:100B80007A732968A2FB033222460E6A0146284680 +:100B9000B047844204D1074B002201201A7070BD77 +:100BA0004FF4FA7000F094FF0020F8E710220020C4 +:100BB00070250020B0230020002307B50246012144 +:100BC0000DF107008DF80730FFF7D0FF20B19DF839 +:100BD000070003B05DF804FB4FF0FF30F9E70000B9 +:100BE0000A46042108B5FFF7C1FF80F00100C0B23A +:100BF000404208BD30B4054C0A46014623682046F1 +:100C0000DD69034BAC4630BC604700BF7025002057 +:100C1000A086010070B5104C0025104E01F004FABA +:100C200020803068238883420CD800252088013832 +:100C300001F0F6F923880544013BB5F5802F2380A8 +:100C4000F4D370BD01F0ECF9336805440133B5F518 +:100C5000003F3360E5D3E8E7B2230020842300207F +:100C600001F0C0BA00F1006000F500300068704784 +:100C700000F10060920000F5003001F037BA00008A +:100C8000054B1A68054B1B889B1A834202D91044F6 +:100C900001F0C6B90020704784230020B223002051 +:100CA00038B5074D04462868204401F0BFF928B93B +:100CB00028682044BDE8384001F0CAB938BD00BFFB +:100CC000842300200020704700F1FF5000F58F10B2 +:100CD000D0F8000870470000064991F8243033B17D +:100CE00000230822086A81F82430FFF7C1BF0120E1 +:100CF000704700BF88230020014B1868704700BF71 +:100D00000010005C244BF0B51A680446234BC2F374 +:100D10000B06120C1F885868BE4293F9085028D061 +:100D20009F89BE4206D101200C2505FB003358687F +:100D300093F9085041F201039A421CD041F2030397 +:100D40009A421AD042F201039A4218D042F20303A7 +:100D50009A4208BF5625621E0B46441E0A4493421F +:100D60000FD214F9016F581C6EB1034600F8016CE4 +:100D7000F5E70020D8E75A25EDE75925EBE7582598 +:100D8000E9E7184605E02C2482421C7001D9981C22 +:100D90005D70401AF0BD00BF0010005C14220020FE +:100DA00000207047022802D1014B04229A6170474B +:100DB00000080258022803D1024B4FF480229A61A6 +:100DC000704700BF00080258022804D1024A536944 +:100DD00083F004035361704700080258002310B5E4 +:100DE000934203D0CC5CC4540133F9E710BD00003A +:100DF000013810B510F9013F3BB191F900409C4218 +:100E000003D11AB10131013AF4E71AB191F9002086 +:100E1000981A10BD1046FCE703460246D01A12F994 +:100E2000011B0029FAD1704702440346934202D0C5 +:100E300003F8011BFAE770472DE9F8431F4D1446EC +:100E40000746884695F8242052BBDFF870909CB383 +:100E500095F824302BB92022FF2148462F62FFF756 +:100E6000E3FF95F824004146C0F1080205EB80003D +:100E7000A24228BF2246D6B29200FFF7AFFF95F8F4 +:100E80002430A41B17441E449044E4B2F6B2082E4A +:100E900085F82460DBD1FFF71FFF0028D7D108E0D9 +:100EA0002B6A03EB82038342CFD0FFF715FF0028A4 +:100EB000CBD10020BDE8F8830120FBE78823002088 +:100EC000024B1A78024B1A70704700BFB023002003 +:100ED0001022002010B5104C104800F0FBF82146FD +:100EE0000E4800F023F924680D48D4F89020D2F879 +:100EF000043843F00203C2F8043800F0E9FD094960 +:100F0000204600F021FAD4F89020D2F8043823F0DB +:100F10000203C2F8043810BDE03A00087025002032 +:100F200040420F00E83A00087047000000B59BB04F +:100F3000EFF3098168226846FFF750FFEFF305835E +:100F4000044B9A6BDA6A9A6A9A6A9A6A9A6A9A6AF5 +:100F50009B6AFEE700ED00E000B59BB0EFF309816E +:100F600068226846FFF73AFFEFF30583044B9A6B5C +:100F70009A6A9A6A9A6A9A6A9A6A9B6AFEE700BFB4 +:100F800000ED00E000B59BB0EFF3098168226846F0 +:100F9000FFF724FFEFF30583034B5A6B9A6A9A6AB3 +:100FA0009A6A9A6A9B6AFEE700ED00E0FEE700009D +:100FB00030B50A44084D91420DD011F8013B58401C +:100FC000082340F30004013B2C4013F0FF0384EAA4 +:100FD0005000F6D1EFE730BD2083B8ED02684368DA +:100FE0001143016003B118477047000013B5406B0F +:100FF00000F58054D4F8A4381A681178042914D163 +:10100000017C022911D11979012312898B401342E5 +:101010000BD101A94C3002F06DF8D4F8A448024677 +:10102000019B2179206800F0DFF902B010BD0000BB +:10103000143001F0EFBF00004FF0FF33143001F027 +:10104000E9BF00004C3002F0C1B800004FF0FF33A0 +:101050004C3002F0BBB80000143001F0BDBF0000FE +:101060004FF0FF31143001F0B7BF00004C3002F0F8 +:101070008DB800004FF0FF324C3002F087B800000E +:101080000020704710B500F58054D4F8A4381A68D1 +:101090001178042917D1017C022914D1597901232F +:1010A00052898B4013420ED1143001F04FFF02469B +:1010B00048B1D4F8A4484FF4407361792068BDE882 +:1010C000104000F07FB910BD406BFFF7DBBF0000A0 +:1010D000704700007FB5124B0125042604460360CB +:1010E0000023057400F1840243602946C0E90233FD +:1010F0000C4B0290143001934FF44073009601F0B2 +:1011000001FF094B04F69442294604F14C00029475 +:10111000CDE900634FF4407301F0C8FF04B070BD27 +:101120001C3A0008C9100008ED0F00080A682023C7 +:1011300083F311880B790B3342F823004B79133377 +:1011400042F823008B7913B10B3342F8230000F5EA +:101150008053C3F8A41802230374002383F3118877 +:101160007047000038B5037F044613B190F854303F +:10117000ABB90125201D0221FFF730FF04F1140057 +:101180006FF00101257700F0CBFC04F14C0084F8EE +:1011900054506FF00101BDE8384000F0C1BC38BDCB +:1011A00010B5012104460430FFF718FF0023237710 +:1011B00084F8543010BD000038B5044600251430C2 +:1011C00001F0B8FE04F14C00257701F087FF201DE7 +:1011D00084F854500121FFF701FF2046BDE8384054 +:1011E000FFF750BF90F8803003F06003202B06D14A +:1011F00090F881200023212A03D81F2A06D8002036 +:101200007047222AFBD1C0E91D3303E0034A42673D +:1012100007228267C3670120704700BF2C2200208D +:1012200037B500F58055D5F8A4381A681178042927 +:101230001AD1017C022917D11979012312898B4017 +:10124000134211D100F14C04204602F007F858B1C6 +:1012500001A9204601F04EFFD5F8A4480246019BA3 +:101260002179206800F0C0F803B030BD01F10B0314 +:10127000F0B550F8236085B004460D46FEB120233A +:1012800083F3118804EB8507301D0821FFF7A6FEC4 +:10129000FB6806F14C005B691B681BB1019001F013 +:1012A00037FF019803A901F025FF024648B1039BCF +:1012B0002946204600F098F8002383F3118805B0F2 +:1012C000F0BDFB685A691268002AF5D01B8A013B01 +:1012D0001340F1D104F18002EAE70000133138B580 +:1012E00050F82140ECB1202383F3118804F580539A +:1012F000D3F8A4281368527903EB8203DB689B6957 +:101300005D6845B104216018FFF768FE294604F1C5 +:10131000140001F025FE2046FFF7B4FE002383F3FE +:10132000118838BD7047000001F018B90123402230 +:10133000002110B5044600F8303BFFF775FD00238F +:10134000C4E9013310BD000010B52023044683F327 +:1013500011882422416000210C30FFF765FD2046F2 +:1013600001F01EF902232370002383F3118810BDBE +:1013700070B500EB8103054650690E461446DA60ED +:1013800018B110220021FFF74FFDA06918B11022FB +:101390000021FFF749FD31462846BDE8704001F0C5 +:1013A00011BA000083682022002103F0011310B558 +:1013B000044683601030FFF737FD2046BDE810403B +:1013C00001F08CBAF0B4012500EB810447898D400F +:1013D000E4683D43A469458123600023A260636003 +:1013E000F0BC01F0A9BA0000F0B4012500EB8104C3 +:1013F00007898D40E4683D436469058123600023CB +:10140000A2606360F0BC01F01FBB000070B5022356 +:1014100000250446242203702946C0F888500C3069 +:1014200040F8045CFFF700FD204684F8705001F09E +:101430005DF963681B6823B129462046BDE870400A +:10144000184770BD037880F88C300523037043681B +:101450001B6810B504460BB1042198470023A36014 +:1014600010BD000090F88C20436802701B680BB11F +:10147000052118477047000070B590F87030044699 +:1014800013B1002380F8703004F18002204601F08F +:1014900049FA63689B68B3B994F8803013F060052B +:1014A00035D00021204601F0F3FC0021204601F058 +:1014B000E3FC63681B6813B10621204698470623A6 +:1014C00084F8703070BD204698470028E4D0B4F806 +:1014D0008630A26F9A4288BFA36794F98030A56FC7 +:1014E000002B4FF0200380F20381002D00F0F280EA +:1014F000092284F8702083F3118800212046D4E962 +:101500001D23FFF771FF002383F31188DAE794F8B6 +:10151000812003F07F0343EA022340F20232934228 +:1015200000F0C58021D8B3F5807F48D00DD8012BBD +:101530003FD0022B00F09380002BB2D104F188023F +:1015400062670222A267E367C1E7B3F5817F00F01B +:101550009B80B3F5407FA4D194F88230012BA0D1B9 +:10156000B4F8883043F0020332E0B3F5006F4DD099 +:1015700017D8B3F5A06F31D0A3F5C063012B90D875 +:101580006368204694F882205E6894F88310B4F86B +:101590008430B047002884D0436863670368A3673A +:1015A0001AE0B3F5106F36D040F6024293427FF452 +:1015B00078AF5C4B63670223A3670023C3E794F80B +:1015C0008230012B7FF46DAFB4F8883023F0020332 +:1015D000A4F88830C4E91D55E56778E7B4F8803091 +:1015E000B3F5A06F0ED194F88230204684F88A308B +:1015F00001F0DAF863681B6813B1012120469847AF +:10160000032323700023C4E91D339CE704F18B03FB +:1016100063670123C3E72378042B10D1202383F3CE +:1016200011882046FFF7BEFE85F311880321636809 +:1016300084F88B5021701B680BB12046984794F8B2 +:101640008230002BDED084F88B3004232370636853 +:101650001B68002BD6D0022120469847D2E794F889 +:10166000843020461D0603F00F010AD501F04CF925 +:10167000012804D002287FF414AF2B4B9AE72B4BA0 +:1016800098E701F033F9F3E794F88230002B7FF408 +:1016900008AF94F8843013F00F01B3D01A06204637 +:1016A00002D501F00DFCADE701F0FEFBAAE794F8CE +:1016B0008230002B7FF4F5AE94F8843013F00F01E4 +:1016C000A0D01B06204602D501F0E2FB9AE701F00C +:1016D000D3FB97E7142284F8702083F311882B46FC +:1016E0002A4629462046FFF76DFE85F31188E9E674 +:1016F0005DB1152284F8702083F311880021204603 +:10170000D4E91D23FFF75EFEFDE60B2284F870206E +:1017100083F311882B462A4629462046FFF764FEAC +:10172000E3E700BF4C3A0008443A0008483A000892 +:1017300038B590F870300446002B3ED0063BDAB244 +:101740000F2A34D80F2B32D8DFE803F037313108B5 +:10175000223231313131313131313737856FB0F8A3 +:1017600086309D4214D2C3681B8AB5FBF3F203FB9B +:1017700012556DB9202383F311882B462A4629463A +:10178000FFF732FE85F311880A2384F870300EE0EB +:10179000142384F87030202383F31188002320461B +:1017A0001A461946FFF70EFE002383F3118838BD51 +:1017B000C36F03B198470023E7E70021204601F0FB +:1017C00067FB0021204601F057FB63681B6813B1DB +:1017D0000621204698470623D7E7000010B590F869 +:1017E00070300446142B29D017D8062B05D001D809 +:1017F0001BB110BD093B022BFBD80021204601F094 +:1018000047FB0021204601F037FB63681B6813B1DA +:10181000062120469847062319E0152BE9D10B2312 +:1018200080F87030202383F3118800231A4619466C +:10183000FFF7DAFD002383F31188DAE7C3689B69B9 +:101840005B68002BD5D1C36F03B19847002384F8A0 +:101850007030CEE7024B0022C3E900339A60704734 +:10186000B4230020002382680374054B1B68996829 +:101870009142FBD25A680360426010605860704722 +:10188000B423002008B5202383F31188037C032BA5 +:1018900005D0042B0DD02BB983F3118808BD436903 +:1018A00000221A604FF0FF334361FFF7DBFF002394 +:1018B000F2E7D0E9003213605A60F3E70023826850 +:1018C0000374054B1B6899689142FBD85A68036002 +:1018D0004260106058607047B4230020054B1969BE +:1018E00008741868026853601A6018610123037451 +:1018F000FEF76CBDB42300204B1C30B5044687B006 +:101900000A4D10D02B6901A8094A00F025F920469C +:10191000FFF7E4FF049B13B101A800F059F92B690C +:10192000586907B030BDFFF7D9FFF8E7B4230020AE +:101930008518000838B50C4D044641612B69816853 +:101940009A68914203D8BDE83840FFF78BBF18462C +:10195000FFF7B4FF01232C61014623742046BDE844 +:101960003840FEF733BD00BFB4230020044B1A6893 +:101970001B6990689B68984294BF002001207047C3 +:10198000B423002010B5084C236820691A685460FD +:101990002260012223611A74FFF790FF014620693B +:1019A000BDE81040FEF712BDB423002008B5FFF7D4 +:1019B000DDFF18B1BDE80840FFF7E4BF08BD000037 +:1019C000FFF7E0BFFEE7000010B50C4CFFF742FF49 +:1019D00000F0B4F880220A49204600F03BF80123C9 +:1019E00044F8180C037400F097FC002383F311886B +:1019F00062B60448BDE8104000F04CB8DC2300207B +:101A0000503A0008603A000800F01CB9EFF311806A +:101A100020B9EFF30583202282F31188704700007C +:101A200010B530B9EFF30584C4F3080414B180F3A2 +:101A3000118810BDFFF7BAFF84F31188F9E70000A1 +:101A4000034A516853685B1A9842FBD8704700BF3D +:101A5000001000E082600222028270478368A3F1D6 +:101A60007C0243F80C2C026943F83C2C426943F891 +:101A7000382C074A43F81C2CC268A3F1180043F81D +:101A8000102C022203F8082C002203F8072C7047C0 +:101A9000E503000810B5202383F31188FFF7DEFF6C +:101AA00000210446FFF746FF002383F311882046F8 +:101AB00010BD0000024B1B6958610F20FFF70EBFDD +:101AC000B4230020202383F31188FFF7F3BF000025 +:101AD00008B50146202383F311880820FFF70CFF87 +:101AE000002383F3118808BD49B1064B42681B6986 +:101AF00018605A60136043600420FFF7FDBE4FF08A +:101B0000FF307047B42300200368984206D01A685B +:101B10000260506018465961FFF7A4BE704700008C +:101B200038B504460D462068844200D138BD0368AC +:101B300023605C604561FFF795FEF4E7054B4FF0CD +:101B4000FF3103F11402C3E905220022C3E90712A1 +:101B5000704700BFB423002070B51C4E05460C46EC +:101B6000C0E9032301F0B0FB334653F8142F9A4227 +:101B70000DD130620A2C2CBF00190A302A60C5E949 +:101B80000124C6E90555BDE8704001F087BB316A04 +:101B9000431AE31838BF1C469368A34202D90819B8 +:101BA00001F08CFB73699A6894420CD85A68AC6057 +:101BB0002B606A6015609A685D60121B9A604FF036 +:101BC000FF33F36170BDA41A1B68ECE7B423002057 +:101BD00038B51B4C636998420DD08168D0E900325A +:101BE00013605A600022C2609A680A449A604FF0FB +:101BF000FF33E36138BD03682246002142F8143FF9 +:101C000093425A60C16003D1BDE8384001F050BB37 +:101C10009A688168256A0A449A6001F055FB6369F5 +:101C2000411B9A688A42E5D9AB181D1A206A092D12 +:101C300098BF01F10A02BDE83840104401F03EBBF4 +:101C4000B42300202DE9F041184C002704F11406BC +:101C5000656901F039FB236AAA68C11A8A4215D85E +:101C60001344D5F80C802362D5E9003213605A6022 +:101C70006369EF60B34201D101F01AFB87F3118869 +:101C80002869C047202383F31188E1E76169B142E5 +:101C900009D013441B1ABDE8F0410A2B2CBFC01811 +:101CA0000A3001F00BBBBDE8F08100BFB423002077 +:101CB00000207047FEE70000704700004FF0FF3043 +:101CC0007047000002290CD0032904D001290748DD +:101CD00018BF00207047032A05D8054800EBC20052 +:101CE0007047044870470020704700BF443B00081D +:101CF0003C220020F83A000870B59AB00546084624 +:101D0000144601A900F0C2F801A8FFF785F8431CAA +:101D10000022C6B25B001046C5E9003423700323DD +:101D2000023404F8013C01ABD1B202348E4201D836 +:101D30001AB070BD13F8011B013204F8010C04F84D +:101D4000021CF1E708B5202383F311880348FFF74D +:101D500067FA002383F3118808BD00BF70250020B7 +:101D600090F8803003F01F02012A07D190F88120FB +:101D70000B2A03D10023C0E91D3315E003F06003F3 +:101D8000202B08D1B0F884302BB990F88120212A7B +:101D900003D81F2A04D8FFF725BA222AEBD0FAE786 +:101DA000034A426707228267C3670120704700BF6A +:101DB0003322002007B5052917D8DFE801F01916EE +:101DC00003191920202383F31188104A012101905F +:101DD000FFF7CEFA019802210D4AFFF7C9FA0D4824 +:101DE000FFF7EAF9002383F3118803B05DF804FBE1 +:101DF000202383F311880748FFF7B4F9F2E7202383 +:101E000083F311880348FFF7CBF9EBE7983A000812 +:101E1000BC3A00087025002038B50C4D0C4C2A4601 +:101E20000C4904F10800FFF767FF05F1CA0204F14D +:101E300010000949FFF760FF05F5CA7204F11800A8 +:101E40000649BDE83840FFF757BF00BF483E0020B5 +:101E50003C220020783A0008823A00088D3A0008B7 +:101E600070B5044608460D46FEF7D6FFC6B22046BA +:101E7000013403780BB9184670BD32462946FEF787 +:101E8000B7FF0028F3D10120F6E700002DE9F04765 +:101E900005460C46FEF7C0FF2B49C6B22846FFF7A1 +:101EA000DFFF08B10736F6B228492846FFF7D8FF0A +:101EB00008B11036F6B2632E0BD8DFF88C80DFF84D +:101EC0008C90234FDFF894A02E7846B92670BDE899 +:101ED000F08729462046BDE8F04701F089BD252E50 +:101EE0002ED1072241462846FEF782FF70B9194BD2 +:101EF000224603F10C0153F8040B8B4242F8040B09 +:101F0000F9D11B8807350E341380DDE708224946D6 +:101F10002846FEF76DFF98B9A21C0F4B19780232C4 +:101F20000909C95D02F8041C13F8011B01F00F0137 +:101F30005345C95D02F8031CF0D118340835C3E7D6 +:101F4000013504F8016BBFE7643B00088D3A0008D7 +:101F50007B3B00086C3B000800E8F11F0CE8F11F18 +:101F6000BFF34F8F044B1A695107FCD1D3F81021EE +:101F70005207F8D1704700BF0020005208B50D4B42 +:101F80001B78ABB9FFF7ECFF0B4BDA68D10704D530 +:101F90000A4A5A6002F188325A60D3F80C21D207FB +:101FA00006D5064AC3F8042102F18832C3F8042199 +:101FB00008BD00BFA6400020002000522301674555 +:101FC00008B5114B1B78F3B9104B1A69510703D5AB +:101FD000DA6842F04002DA60D3F81021520705D5E2 +:101FE000D3F80C2142F04002C3F80C21FFF7B8FFF0 +:101FF000064BDA6842F00102DA60D3F80C2142F0B5 +:102000000102C3F80C2108BDA640002000200052A8 +:102010000F289ABF00F58060400400207047000040 +:102020004FF4003070470000102070470F2808B5AB +:102030000BD8FFF7EDFF00F500330268013204D141 +:1020400004308342F9D1012008BD0020FCE70000E4 +:102050000F2870B5054645D8FFF7D8FC224CFFF78E +:102060007FFF0646FFF78AFF4FF0FF33072D6361BE +:10207000C4F8143120D82361FFF772FF2B0243F01C +:102080002403E360E36843F08003E36023695A07B5 +:10209000FCD42846FFF764FF4FF40031FFF7B8FF88 +:1020A00000F002F93046FFF78BFFFFF7B9FC284636 +:1020B000BDE87040FFF7BABFC4F81031FFF750FF1A +:1020C000A5F108031B0243F02403C4F80C31D4F833 +:1020D0000C3143F08003C4F80C31D4F810315B07A5 +:1020E000FBD4D6E7002070BD002000522DE9F84F48 +:1020F00040EA020305460C461746D80602D00020E7 +:10210000BDE8F88F27F01F07DFF8D4B0FFF736FFE0 +:102110002744BC4203D10120FFF752FFF0E7202201 +:102120002946204601F054FC10B920352034F0E750 +:102130002B4605F120021E68711CE0D104339A423F +:10214000F9D1FFF763FC05F17843234AB3F5801F0B +:10215000224B28BF9A4603F1040338BF9046A2F1F0 +:10216000080228BF9846A3F108033ABF9146DA4611 +:102170009946FFF7F5FEC8F80060A5EB040CD9F806 +:10218000002004F11C0142F00202C9F80020221FC5 +:10219000DAF8006016F00506FAD152F8043F8A42D8 +:1021A0004CF80230F4D1BFF34F8FFFF7D9FE4FF058 +:1021B000FF32C8F80020D9F8002022F00202C9F846 +:1021C0000020FFF72DFC20222146284601F000FCCC +:1021D0000028AAD030469FE7142000521021005258 +:1021E0001020005210B5084C237828B11BB9FFF716 +:1021F000C5FE0123237010BD002BFCD02070BDE86C +:102200001040FFF7DDBE00BFA64000200244074B90 +:10221000D2B210B5904200D110BD441C00B253F8A8 +:10222000200041F8040BE0B2F4E700BF5040005832 +:102230000E4B30B51C6F240405D41C6F1C671C6F3B +:1022400044F400441C670A4C02442368D2B243F4AD +:1022500080732360074B904200D130BD441C51F87D +:10226000045B00B243F82050E0B2F4E700440258A7 +:10227000004802585040005807B5012201A900202B +:10228000FFF7C4FF019803B05DF804FB13B50446E3 +:10229000FFF7F2FFA04205D0012201A9002001941E +:1022A000FFF7C6FF02B010BD0144BFF34F8F064BCE +:1022B000884204D3BFF34F8FBFF36F8F7047C3F8CB +:1022C0005C022030F4E700BF00ED00E0034B1A6829 +:1022D0001AB9034AD2F8D0241A607047A8400020E7 +:1022E0000040025808B5FFF7F1FF024B1868C0F331 +:1022F000806008BDA8400020EFF3098305496833DA +:102300004A6B22F001024A6383F30988002383F3B6 +:102310001188704700EF00E0202080F3118862B63A +:102320000D4B0E4AD96821F4E0610904090C0A43F7 +:102330000B49DA60D3F8FC2042F08072C3F8FC202D +:10234000084AC2F8B01F116841F001011160102263 +:10235000DA7783F82200704700ED00E00003FA0509 +:1023600055CEACC5001000E0202310B583F31188D2 +:102370000E4B5B6813F4006314D0F1EE103AEFF3E8 +:1023800009844FF08073683CE361094BDB6B236683 +:1023900084F30988FFF7EAFA10B1064BA36110BD78 +:1023A000054BFBE783F31188F9E700BF00ED00E080 +:1023B00000EF00E0F7030008FA03000870B5BFF370 +:1023C0004F8FBFF36F8F1A4A0021C2F85012BFF32C +:1023D0004F8FBFF36F8F536943F400335361BFF3E3 +:1023E0004F8FBFF36F8FC2F88410BFF34F8FD2F8B7 +:1023F000803043F6E074C3F3C900C3F34E335B018E +:1024000003EA0406014646EA81750139C2F86052C2 +:10241000F9D2203B13F1200FF2D1BFF34F8F536954 +:1024200043F480335361BFF34F8FBFF36F8F70BDA1 +:1024300000ED00E0FEE700000A4B0B480B4A90421B +:102440000BD30B4BC11EDA1C121A22F003028B4273 +:1024500038BF00220021FEF7E7BC53F8041B40F808 +:10246000041BECE75C3D00087C4200207C4200201D +:102470007C4200207047000070B5D0E92443002260 +:102480004FF0FF359E6804EB42135101D3F8000969 +:10249000002805DAD3F8000940F08040C3F80009AD +:1024A000D3F8000B002805DAD3F8000B40F0804089 +:1024B000C3F8000B013263189642C3F80859C3F8F9 +:1024C000085BE0D24FF00113C4F81C3870BD000067 +:1024D00000EB8103D3F80CC02DE9F043DCF81420A5 +:1024E0004E1CD0F89050D2F800E005EB063605EB14 +:1024F0004118506870450AD30122D5F8343802FAE1 +:1025000001F123EA0101C5F83418BDE8F083AEEB10 +:102510000003BCF81040A34228BF2346D8F818494E +:10252000A4B2B3EB840FF0D89468A4F1040959F86D +:10253000047F3760A4EB09071F44042FF7D81C441D +:10254000034494605360D4E7890141F020010161A4 +:1025500003699B06FCD41220FFF772BA10B50A4C2F +:102560002046FEF7E3FE094BC4F89030084BC4F850 +:102570009430084C2046FEF7D9FE074BC4F8903043 +:10258000064BC4F8943010BDAC4000200000084059 +:10259000B03B00084841002000000440BC3B00085C +:1025A00070B503780546012B5DD1494BD0F89040BA +:1025B000984259D1474B0E216520D3F8D82042F0DC +:1025C0000062C3F8D820D3F8002142F00062C3F8BB +:1025D0000021D3F80021D3F8802042F00062C3F834 +:1025E0008020D3F8802022F00062C3F88020D3F846 +:1025F000803000F071FC384BE360384BC4F8003891 +:102600000023D5F89060C4F8003EC02323604FF447 +:102610000413A3633369002BFCDA01230C2033611C +:10262000FFF70EFA3369DB07FCD41220FFF708FA34 +:102630003369002BFCDA00262846A660FFF71CFF52 +:102640006B68C4F81068DB68C4F81468C4F81C68C8 +:10265000002B3AD1224BA3614FF0FF336361A36893 +:1026600043F00103A36070BD1E4B9842C8D1194BC3 +:102670000E214D20D3F8D82042F00072C3F8D820A4 +:10268000D3F8002142F00072C3F80021D3F80021F2 +:10269000D3F8802042F00072C3F88020D3F8802065 +:1026A00022F00072C3F88020D3F88020D3F8D8201D +:1026B00022F08062C3F8D820D3F8002122F0806293 +:1026C000C3F80021D3F8003193E7074BC3E700BFFD +:1026D000AC40002000440258401400400300200297 +:1026E000003C30C048410020083C30C0F8B5D0F86C +:1026F0009040054600214FF000662046FFF724FF7A +:10270000D5F8941000234FF001128F684FF0FF307E +:10271000C4F83438C4F81C2804EB431201339F4238 +:10272000C2F80069C2F8006BC2F80809C2F8080BC9 +:10273000F2D20B68D5F89020C5F898306362102368 +:102740001361166916F01006FBD11220FFF778F915 +:10275000D4F8003823F4FE63C4F80038A36943F4C6 +:10276000402343F01003A3610923C4F81038C4F8D0 +:1027700014380B4BEB604FF0C043C4F8103B094BCF +:10278000C4F8003BC4F81069C4F80039D5F8983093 +:1027900003F1100243F48013C5F89820A362F8BD3A +:1027A0008C3B000840800010D0F8902090F88A10F0 +:1027B000D2F8003823F4FE6343EA0113C2F800386C +:1027C000704700002DE9F84300EB8103D0F89050EA +:1027D0000C468046DA680FFA81F94801166806F05F +:1027E0000306731E022B05EB41134FF0000194BF4B +:1027F000B604384EC3F8101B4FF0010104F110036A +:1028000098BF06F1805601FA03F3916998BF06F567 +:10281000004600293AD0578A04F15801374349014C +:102820006F50D5F81C180B430021C5F81C382B1825 +:102830000127C3F81019A7405369611E9BB3138A7F +:10284000928B9B08012A88BF5343D8F89820981888 +:1028500042EA034301F140022146C8F898002846A5 +:1028600005EB82025360FFF76FFE08EB8900C36837 +:102870001B8A43EA845348341E4364012E51D5F821 +:102880001C381F43C5F81C78BDE8F88305EB4917D1 +:10289000D7F8001B21F40041C7F8001BD5F81C181D +:1028A00021EA0303C0E704F13F030B4A284621460F +:1028B00005EB83035A60FFF747FE05EB4910D0F89C +:1028C000003923F40043C0F80039D5F81C3823EA56 +:1028D0000707D7E70080001000040002D0F894201A +:1028E0001268C0F89820FFF7C7BD00005831D0F833 +:1028F000903049015B5813F4004004D013F4001FDA +:102900000CBF0220012070474831D0F890304901B7 +:102910005B5813F4004004D013F4001F0CBF0220D6 +:102920000120704700EB8101CB68196A0B681360C6 +:102930004B6853607047000000EB810330B5DD68E1 +:10294000AA691368D36019B9402B84BF4023136070 +:102950006B8A1468D0F890201C4402EB4110013CB3 +:1029600009B2B4FBF3F46343033323F0030343EAF4 +:10297000C44343F0C043C0F8103B2B6803F003038B +:10298000012B0ED1D2F8083802EB411013F4807FEE +:10299000D0F8003B14BF43F0805343F00053C0F81D +:1029A000003B02EB4112D2F8003B43F00443C2F873 +:1029B000003B30BD2DE9F041D0F8906005460C4653 +:1029C00006EB4113D3F8087B3A07C3F8087B08D518 +:1029D000D6F814381B0704D500EB8103DB685B686D +:1029E0009847FA071FD5D6F81438DB071BD505EB37 +:1029F0008403D968CCB98B69488A5A68B2FBF0F66F +:102A000000FB16228AB91868DA6890420DD2121AB1 +:102A1000C3E90024202383F3118821462846FFF7C9 +:102A20008BFF84F31188BDE8F081012303FA04F2DF +:102A30006B8923EA02036B81CB68002BF3D021461C +:102A40002846BDE8F041184700EB81034A0170B504 +:102A5000DD68D0F890306C692668E66056BB1A4491 +:102A60004FF40020C2F810092A6802F00302012A7C +:102A70000AB20ED1D3F8080803EB421410F4807F99 +:102A8000D4F8000914BF40F0805040F00050C4F862 +:102A9000000903EB4212D2F8000940F00440C2F8EA +:102AA00000090122D3F8340802FA01F10143C3F806 +:102AB000341870BD19B9402E84BF402020602068B2 +:102AC0001A442E8A8419013CB4FBF6F440EAC4404F +:102AD00040F00050C6E700002DE9F041D0F89060CA +:102AE00004460D4606EB4113D3F80879C3F808797C +:102AF000FB071CD5D6F81038DA0718D500EB810390 +:102B0000D3F80CC0DCF81430D3F800E0DA6896454E +:102B10001BD2A2EB0E024FF000081A60C3F804802B +:102B2000202383F31188FFF78FFF88F311883B067A +:102B300018D50123D6F83428AB40134212D02946C9 +:102B40002046BDE8F041FFF7C3BC012303FA01F2C0 +:102B5000038923EA02030381DCF80830002BE6D066 +:102B60009847E4E7BDE8F0812DE9F84FD0F89050A0 +:102B700004466E69AB691E4016F480586E6103D03E +:102B8000BDE8F84FFEF742BC002E12DAD5F8003E41 +:102B90009F0705D0D5F8003E23F00303C5F8003E9B +:102BA000D5F80438204623F00103C5F80438FEF7B1 +:102BB00059FC300505D52046FFF75EFC2046FEF7A0 +:102BC00041FCB1040CD5D5F8083813F0060FEB68BA +:102BD00023F470530CBF43F4105343F4A053EB6041 +:102BE000320704D56368DB680BB120469847F302CF +:102BF00000F1BA80B70226D5D4F8909000274FF0A4 +:102C0000010A09EB4712D2F8003B03F44023B3F565 +:102C1000802F11D1D2F8003B002B0DDA62890AFA1D +:102C200007F322EA0303638104EB8703DB68DB68B5 +:102C300013B13946204698470137D4F89430FFB293 +:102C40009B689F42DDD9F00619D5D4F89000026A3E +:102C5000C2F30A1702F00F0302F4F012B2F5802F4C +:102C600000F0CC80B2F5402F09D104EB83030022A1 +:102C700000F58050DB681B6A974240F0B280300359 +:102C8000D5F8185835D5E90303D500212046FFF7BC +:102C900091FEAA0303D501212046FFF78BFE6B03AB +:102CA00003D502212046FFF785FE2F0303D503211C +:102CB0002046FFF77FFEE80203D504212046FFF7F8 +:102CC00079FEA90203D505212046FFF773FE6A02AB +:102CD00003D506212046FFF76DFE2B0203D5072101 +:102CE0002046FFF767FEEF0103D508212046FFF7D6 +:102CF00061FE700340F1A980E90703D50021204659 +:102D0000FFF7EAFEAA0703D501212046FFF7E4FEFC +:102D10006B0703D502212046FFF7DEFE2F0703D500 +:102D200003212046FFF7D8FEEE0603D504212046F6 +:102D3000FFF7D2FEA80603D505212046FFF7CCFEFB +:102D4000690603D506212046FFF7C6FE2A0603D5ED +:102D500007212046FFF7C0FEEB0576D52046082167 +:102D6000BDE8F84FFFF7B8BED4F8909000274FF0B9 +:102D7000010AD4F894305FFA87FB9B689B453FF6C5 +:102D800039AF09EB4B13D3F8002902F44022B2F516 +:102D9000802F24D1D3F80029002A20DAD3F8002983 +:102DA00042F09042C3F80029D3F80029002AFBDB47 +:102DB0005946D4F89000FFF7C7FB22890AFA0BF3B3 +:102DC00022EA0303238104EB8B03DB689B6813B1C6 +:102DD00059462046984759462046FFF779FB013768 +:102DE000C7E7910701D1D0F80080072A02F101025C +:102DF0009CBF03F8018B4FEA18283DE704EB8303DF +:102E000000F58050DA68D2F818C0DCF80820DCE958 +:102E1000001CA1EB0C0C00218F4208D1DB689B69E0 +:102E20009A683A449A605A683A445A6027E711F01F +:102E3000030F01D1D0F800808C4501F1010184BF5E +:102E400002F8018B4FEA1828E6E7BDE8F88F00008A +:102E500008B50348FFF788FEBDE80840FFF784BACD +:102E6000AC40002008B50348FFF77EFEBDE80840EF +:102E7000FFF77ABA48410020D0F8903003EB4111B7 +:102E8000D1F8003B43F40013C1F8003B7047000049 +:102E9000D0F8903003EB4111D1F8003943F400131E +:102EA000C1F8003970470000D0F8903003EB4111B1 +:102EB000D1F8003B23F40013C1F8003B7047000039 +:102EC000D0F8903003EB4111D1F8003923F400130E +:102ED000C1F8003970470000090100F16043012288 +:102EE00003F56143C9B283F8001300F01F039A4051 +:102EF00043099B0003F1604303F56143C3F880215C +:102F00001A60704730B50433039C0172002104FB42 +:102F10000325C160C0E90653049B0363059BC0E918 +:102F20000000C0E90422C0E90842C0E90A11436375 +:102F300030BD00000022416AC260C0E90411C0E94E +:102F40000A226FF00101FEF7EBBD0000D0E9043268 +:102F5000934201D1C2680AB9181D7047002070471A +:102F6000036919600021C2680132C260C26913445A +:102F700082699342036124BF436A0361FEF7C4BDC3 +:102F800038B504460D46E3683BB162690020131D65 +:102F90001268A3621344E36207E0237A33B9294637 +:102FA0002046FEF7A1FD0028EDDA38BD6FF00100E4 +:102FB000FBE70000C368C269013BC3604369134477 +:102FC00082699342436124BF436A43610023836261 +:102FD000036B03B11847704770B52023044683F391 +:102FE0001188866A3EB9FFF7CBFF054618B186F314 +:102FF0001188284670BDA36AE26A13F8015B934208 +:10300000A36202D32046FFF7D5FF002383F3118884 +:10301000EFE700002DE9F84F04460E4617469846A4 +:103020004FF0200989F311880025AA46D4F828B06A +:10303000BBF1000F09D141462046FFF7A1FF20B1A7 +:103040008BF311882846BDE8F88FD4E90A12A7EB64 +:10305000050B521A934528BF9346BBF1400F1BD96D +:10306000334601F1400251F8040B914243F8040B3E +:10307000F9D1A36A403640354033A362D4E90A232C +:103080009A4202D32046FFF795FF8AF31188BD428A +:10309000D8D289F31188C9E730465A46FDF79EFE1B +:1030A000A36A5E445D445B44A362E7E710B5029CFB +:1030B0000433017204FB0321C460C0E9061300233A +:1030C000C0E90A33039B0363049BC0E90000C0E925 +:1030D0000422C0E90842436310BD0000026A6FF099 +:1030E0000101C260426AC0E904220022C0E90A224A +:1030F000FEF716BDD0E904239A4201D1C26822B975 +:10310000184650F8043B0B607047002070470000E1 +:10311000C3680021C2690133C360436913448269F3 +:103120009342436124BF436A4361FEF7EDBC000054 +:1031300038B504460D46E3683BB1236900201A1DEB +:10314000A262E2691344E36207E0237A33B92946B5 +:103150002046FEF7C9FC0028EDDA38BD6FF001000B +:10316000FBE7000003691960C268013AC260C269E6 +:10317000134482699342036124BF436A03610023BD +:103180008362036B03B118477047000070B52023BA +:103190000D460446114683F31188866A2EB9FFF75F +:1031A000C7FF10B186F3118870BDA36A1D70A36AB2 +:1031B000E26A01339342A36204D3E16920460439F1 +:1031C000FFF7D0FF002080F31188EDE72DE9F84FDD +:1031D00004460D46904699464FF0200A8AF311881E +:1031E0000026B346A76A4FB949462046FFF7A0FF1D +:1031F00020B187F311883046BDE8F88FD4E90A077B +:103200003A1AA8EB0607974228BF1746402F1BD94A +:1032100005F1400355F8042B9D4240F8042BF9D1E9 +:10322000A36A40364033A362D4E90A239A4204D306 +:10323000E16920460439FFF795FF8BF31188464575 +:10324000D9D28AF31188CDE729463A46FDF7C6FD63 +:10325000A36A3D443E443B44A362E5E7D0E904232E +:103260009A4217D1C3689BB1836A8BB1043B9B1A06 +:103270000ED01360C368013BC360C3691A448369FD +:103280009A42026124BF436A0361002383620123DF +:10329000184670470023FBE700F0DAB8034B002222 +:1032A00058631A610222DA60704700BF000C0040C8 +:1032B000014B0022DA607047000C0040014B58635C +:1032C000704700BF000C0040014B586A704700BFB8 +:1032D000000C00404B6843608B688360CB68C36020 +:1032E0000B6943614B6903628B6943620B6803603E +:1032F0007047000008B53C4B40F2FF713B48D3F8E3 +:1033000088200A43C3F88820D3F8882022F4FF627B +:1033100022F00702C3F88820D3F88820D3F8E020F1 +:103320000A43C3F8E020D3F808210A43C3F8082170 +:103330002F4AD3F808311146FFF7CCFF00F5806023 +:1033400002F11C01FFF7C6FF00F5806002F13801B1 +:10335000FFF7C0FF00F5806002F15401FFF7BAFFEC +:1033600000F5806002F17001FFF7B4FF00F58060A6 +:1033700002F18C01FFF7AEFF00F5806002F1A801B9 +:10338000FFF7A8FF00F5806002F1C401FFF7A2FF7C +:1033900000F5806002F1E001FFF79CFF00F580601E +:1033A00002F1FC01FFF796FF02F58C7100F58060D9 +:1033B000FFF790FF00F000F90E4BD3F8902242F097 +:1033C0000102C3F89022D3F8942242F00102C3F81C +:1033D00094220522C3F898204FF06052C3F89C2035 +:1033E000054AC3F8A02008BD004402580000025856 +:1033F000C83B000800ED00E01F00080308B500F01E +:10340000C9FAFEF7E1FA0F4BD3F8DC2042F0400294 +:10341000C3F8DC20D3F8042122F04002C3F80421D1 +:10342000D3F80431084B1A6842F008021A601A688F +:1034300042F004021A60FEF749FFBDE80840FEF7BB +:10344000EBBC00BF0044025800180248704700005F +:10345000114BD3F8E82042F00802C3F8E820D3F873 +:10346000102142F00802C3F810210C4AD3F81031A1 +:10347000D36B43F00803D363C722094B9A624FF022 +:10348000FF32DA6200229A615A63DA605A600122DE +:103490005A611A60704700BF004402580010005C77 +:1034A000000C0040094A08B51169D3680B40D9B235 +:1034B0009B076FEA0101116107D5202383F311886F +:1034C000FEF7A2FA002383F3118808BD000C004028 +:1034D000384B4FF0FF31D3F88020C3F88010D3F879 +:1034E00080200022C3F88020D3F88000D3F8840025 +:1034F000C3F88410D3F88400C3F88420D3F8840080 +:10350000D86F40F0FF4040F4FF0040F43F5040F0DF +:103510003F00D867D86F20F0FF4020F4FF0020F470 +:103520003F5020F03F00D867D86FD3F888006FEA8B +:1035300040506FEA5050C3F88800D3F88800C0F3B9 +:103540000A00C3F88800D3F88800D3F89000C3F8C5 +:103550009010D3F89000C3F89020D3F89000D3F8DF +:103560009400C3F89410D3F89400C3F89420D3F8CF +:103570009400D3F89800C3F89810D3F89800C3F8D3 +:103580009820D3F89800D3F88C00C3F88C10D3F8A7 +:103590008C00C3F88C20D3F88C00D3F89C00C3F8BF +:1035A0009C10D3F89C10C3F89C20D3F89C3000F0FA +:1035B000C9B900BF00440258614B0122C3F8082179 +:1035C000604BD3F8F42042F00202C3F8F420D3F8A1 +:1035D0001C2142F00202C3F81C210222D3F81C3144 +:1035E000594BDA605A689104FCD5584A1A60012296 +:1035F0009A60574ADA6000221A614FF440429A6199 +:10360000514B9A699204FCD51A6842F480721A6090 +:103610004C4B1A6F12F4407F04D04FF480321A677B +:1036200000221A671A6842F001021A60454B1A68B4 +:103630005007FCD500221A611A6912F03802FBD13A +:10364000012119604FF0804159605A67414ADA629E +:10365000414A1A611A6842F480321A60394B1A687A +:103660009103FCD51A6842F480521A601A689204D9 +:10367000FCD53A4A3A499A6200225A631963394999 +:10368000DA6399635A64384A1A64384ADA621A6803 +:1036900042F0A8521A602B4B1A6802F02852B2F17D +:1036A000285FF9D148229A614FF48862DA6140229A +:1036B0001A622F4ADA644FF080521A652D4A5A6511 +:1036C0002D4A9A6532232D4A1360136803F00F03C5 +:1036D000022BFAD11B4B1A6942F003021A611A69D4 +:1036E00002F03802182AFAD1D3F8DC2042F0005256 +:1036F000C3F8DC20D3F8042142F00052C3F80421BF +:10370000D3F80421D3F8DC2042F08042C3F8DC2057 +:10371000D3F8042142F08042C3F80421D3F80421F5 +:10372000D3F8DC2042F00042C3F8DC20D3F80421B7 +:1037300042F00042C3F80421D3F80431704700BFBF +:1037400000800051004402580048025800C000F0B8 +:10375000020000010000FF01008890081210200004 +:10376000630209012C02040047040508FD0BFF0158 +:10377000200000200010E0000001010000200052A5 +:103780004FF0B04208B5D2F8883003F00103C2F818 +:10379000883023B1044A13680BB150689847BDE8DC +:1037A0000840FEF7E1BD00BFFC4100204FF0B042F1 +:1037B00008B5D2F8883003F00203C2F8883023B18C +:1037C000044A93680BB1D0689847BDE80840FEF7FB +:1037D000CBBD00BFFC4100204FF0B04208B5D2F88D +:1037E000883003F00403C2F8883023B1044A136917 +:1037F0000BB150699847BDE80840FEF7B5BD00BF62 +:10380000FC4100204FF0B04208B5D2F8883003F0F8 +:103810000803C2F8883023B1044A93690BB1D06918 +:103820009847BDE80840FEF79FBD00BFFC4100205F +:103830004FF0B04208B5D2F8883003F01003C2F858 +:10384000883023B1044A136A0BB1506A9847BDE827 +:103850000840FEF789BD00BFFC4100204FF0B04397 +:1038600010B5D3F8884004F47872C3F88820A30612 +:1038700004D5124A936A0BB1D06A9847600604D502 +:103880000E4A136B0BB1506B9847210604D50B4AB7 +:10389000936B0BB1D06B9847E20504D5074A136CC4 +:1038A0000BB1506C9847A30504D5044A936C0BB137 +:1038B000D06C9847BDE81040FEF756BDFC41002093 +:1038C0004FF0B04310B5D3F8884004F47C42C3F8FD +:1038D0008820620504D5164A136D0BB1506D9847C8 +:1038E000230504D5124A936D0BB1D06D9847E004BF +:1038F00004D50F4A136E0BB1506E9847A10404D53E +:103900000B4A936E0BB1D06E9847620404D5084AF7 +:10391000136F0BB1506F9847230404D5044A936F7B +:103920000BB1D06F9847BDE81040FEF71DBD00BF3A +:10393000FC41002008B5FFF7B5FDBDE80840FEF7E3 +:1039400013BD0000062108B50846FFF7C5FA062199 +:103950000720FFF7C1FA06210820FFF7BDFA06216C +:103960000920FFF7B9FA06210A20FFF7B5FA062168 +:103970001720FFF7B1FA06212820FFF7ADFA092139 +:103980007A20FFF7A9FA07213220BDE80840FFF7A7 +:10399000A3BA000008B5FFF79BFD00F00BF8FDF798 +:1039A000C3FCFDF795FBFFF751FDBDE80840FFF7AD +:1039B00073BC00000023054A19460133102BC2E9ED +:1039C000001102F10802F8D1704700BFFC4100204D +:1039D00010B501390244904201D1002005E003787E +:1039E00011F8014FA34201D0181B10BD0130F2E7BE +:1039F000034611F8012B03F8012B002AF9D1704777 +:103A000053544D333248373F3F3F0053544D3332C8 +:103A1000483734332F3735330000000000000000F2 +:103A20004D100008391000087510000861100008DA +:103A30006D100008591000084510000831100008EA +:103A400081100008000000000100000000000000DC +:103A50006D61696E0000000069646C650000000023 +:103A6000583A0008F82300207025002001000000CB +:103A7000C5190008000000004172647550696C6F40 +:103A8000740025424F415244252D424C0025534598 +:103A90005249414C250000000200000000000000D7 +:103AA0006D120008DD12000840004000183E0020A2 +:103AB000283E00200200000000000000030000007B +:103AC00000000000251300080000000010000000A6 +:103AD000383E00200000000001000000000000004F +:103AE000AC40002001010200B51D0008C51C000803 +:103AF000611D0008451D000843000000003B000850 +:103B000009024300020100C0320904000001020260 +:103B10000100052400100105240100010424020213 +:103B20000524060001070582030800FF09040100BF +:103B3000020A00000007050102400000070581029B +:103B400040000000120000004C3B00081201100170 +:103B50000200004009124157000201020301000067 +:103B60000403090425424F41524425004B616B7503 +:103B7000746548374D696E697632003031323334BE +:103B8000353637383941424344454600000000008D +:103B90007914000831170008DD17000840004000C4 +:103BA000E4410020E441002001000000F441002035 +:103BB000800000004001000008000000000100003B +:103BC00000040000080000000001802A000000003E +:103BD000AAAAAAAA00010024FFFF0000000000001A +:103BE00000A00A000000400100000000AAAAAAAA42 +:103BF00000000001FFFF00000000000000000000C6 +:103C00001000000400000000AAAAAAAA00000008F0 +:103C1000FBDF0000000000000000000000000000CA +:103C200000000000AAAAAAAA00000000FFFF0000EE +:103C30000000000000000000000100000000000083 +:103C4000AAAAAAAA00010000FFFF000000000000CD +:103C5000000000000000000000000000AAAAAAAABC +:103C600000000000FFFF0000000000000000000056 +:103C70000000000000000000AAAAAAAA000000009C +:103C8000FFFF000000000000000000000000000036 +:103C900000000000AAAAAAAA00000000FFFF00007E +:103CA0000000000000000000000000000000000014 +:103CB000AAAAAAAA00000000FFFF0000000000005E +:103CC000000000000000000000000000AAAAAAAA4C +:103CD00000000000FFFF00000000000000000000E6 +:103CE0000000000000000000AAAAAAAA000000002C +:103CF000FFFF0000000000000000000000000000C6 +:103D0000220400000000000000001A000000000073 +:103D1000FF00000000000000003A00083F00000023 +:103D2000500400000B3A00083F000000009600001D +:103D300000000800960000000008000004000000D9 +:103D4000603B0008000000000000000000000000D0 +:0C3D500000000000000000000000000067 +:00000001FF diff --git a/Tools/bootloaders/KakuteH7Mini_bl.bin b/Tools/bootloaders/KakuteH7Mini_bl.bin old mode 100644 new mode 100755 index cb3f6854fac..cf53242742e Binary files a/Tools/bootloaders/KakuteH7Mini_bl.bin and b/Tools/bootloaders/KakuteH7Mini_bl.bin differ diff --git a/Tools/bootloaders/KakuteH7Mini_bl.hex b/Tools/bootloaders/KakuteH7Mini_bl.hex index 10b28896410..fe0536284c1 100644 --- a/Tools/bootloaders/KakuteH7Mini_bl.hex +++ b/Tools/bootloaders/KakuteH7Mini_bl.hex @@ -1,34 +1,34 @@ :020000040800F2 :1000000000060020A1020008AD0F00082D0F000817 :10001000850F00082D0F0008590F0008A3020008E3 -:10002000A3020008A3020008A3020008952200080A +:10002000A3020008A3020008A3020008FD220008A2 :10003000A3020008A3020008A3020008A30200080C :10004000A3020008A3020008A3020008A3020008FC -:10005000A3020008A3020008053700083137000892 -:100060005D37000889370008B5370008A30200088B +:10005000A3020008A302000885370008B137000892 +:10006000DD3700080938000835380008A302000809 :10007000A3020008A3020008A3020008A3020008CC :10008000A3020008A3020008A3020008A3020008BC -:10009000A3020008A3020008A3020008E137000839 +:10009000A3020008A3020008A302000861380008B8 :1000A000A3020008A3020008A3020008A30200089C :1000B000A3020008A3020008A3020008A30200088C :1000C000A3020008A3020008A3020008A30200087C :1000D000A3020008A3020008A3020008A30200086C -:1000E00045380008A3020008A3020008A302000884 +:1000E000C5380008A3020008A3020008A302000804 :1000F000A3020008A3020008A3020008A30200084C -:10010000A3020008A3020008B9380008A3020008EF +:10010000A3020008A302000839390008A30200086E :10011000A3020008A3020008A3020008A30200082B :10012000A3020008A3020008A3020008A30200081B :10013000A3020008A3020008A3020008A30200080B :10014000A3020008A3020008A3020008A3020008FB :10015000A3020008A3020008A3020008A3020008EB :10016000A3020008A3020008A3020008A3020008DB -:10017000A3020008012E0008A3020008A302000841 +:10017000A3020008692E0008A3020008A3020008D9 :10018000A3020008A3020008A3020008A3020008BB :10019000A3020008A3020008A3020008A3020008AB :1001A000A3020008A3020008A3020008A30200089B :1001B000A3020008A3020008A3020008A30200088B :1001C000A3020008A3020008A3020008A30200087B -:1001D000A3020008ED2D0008A3020008A3020008F6 +:1001D000A3020008552E0008A3020008A30200088D :1001E000A3020008A3020008A3020008A30200085B :1001F000A3020008A3020008A3020008A30200084B :10020000A3020008A3020008A3020008A30200083A @@ -48,33 +48,33 @@ :1002E000C0F2F0004EF68851CEF200010860BFF374 :1002F0004F8FBFF36F8F4FF00000E1EE100A4EF604 :100300003C71CEF200010860062080F31488BFF330 -:100310006F8F02F07DF802F01FF802F0B9FF4FF086 +:100310006F8F02F0B1F802F053F802F0EDFF4FF0EA :1003200055301F491B4A91423CBF41F8040BFAE784 :100330001C49194A91423CBF41F8040BFAE71A499B :100340001A4A1B4B9A423EBF51F8040B42F8040B69 :10035000F8E700201749184A91423CBF41F8040BC6 -:10036000FAE702F037F803F00BF8144C144DAC42E6 +:10036000FAE702F06BF803F04BF8144C144DAC4272 :1003700003DA54F8041B8847F9E700F041F8114C00 :10038000114DAC4203DA54F8041B8847F9E702F038 -:100390001FB8000000060020002200200000000816 -:1003A0000000002000060020803C00080022002001 -:1003B0005C2200206022002078420020A002000879 +:1003900053B80000000600200022002000000008E2 +:1003A0000000002000060020003D00080022002080 +:1003B0005C220020602200207C420020A002000875 :1003C000A0020008A0020008A00200082DE9F04FDA :1003D0002DED108AC1F80CD0D0F80CD0BDEC108AED :1003E000BDE8F08F002383F311882846A047002042 -:1003F00001F044FBFEE701F0D9FA00DFFEE7000060 +:1003F00001F068FBFEE701F0E3FA00DFFEE7000032 :1004000038B500F0CDFC30B1164B00220E211A7227 -:100410005A729972DA7201F0FFFE054601F034FF5C +:100410005A729972DA7201F031FF054601F064FFF9 :100420000446D0B9104B9D4219D001339D4241F290 -:10043000883512BF044600250124002001F0F6FE95 +:10043000883512BF044600250124002001F028FF62 :100440000CB100F059F800F045FD00F0E3FB284640 :1004500000F004F900F050F8F9E70025EDE7054653 :10046000EBE700BF00220020010007B008B500F054 :10047000A3FBA0F120035842584108BD07B541F243 :100480001203022101A8ADF8043000F0B3FB03B061 :100490005DF804FB202310B583F311881248C3686C -:1004A0000BB101F071FB0023104A4FF47A710E4832 -:1004B00001F02EFB002383F311880D4C236813B148 +:1004A0000BB101F095FB0023104A4FF47A710E480E +:1004B00001F052FB002383F311880D4C236813B124 :1004C0002368013B2360636813B16368013B636089 :1004D000084B1B7833B9636823B9022000F074FC21 :1004E0003223636010BD00BF602200209504000825 @@ -103,8 +103,8 @@ :10065000742200200044025800ED00E02DE9F04F24 :1006600093B0A94B2022FF2100900AA89D6800F0BA :10067000DBFBA64A1378A3B90121A5481170C3601A -:10068000202383F31188C3680BB101F07DFA0023A6 -:10069000A04A4FF47A719E4801F03AFA002383F39E +:10068000202383F31188C3680BB101F0A1FA002382 +:10069000A04A4FF47A719E4801F05EFA002383F37A :1006A0001188009B9C4A03B1136000239B49009C66 :1006B00098469B461E469A460B705360012000F0F8 :1006C00079FB24B1944B1B68002B00F016820020AC @@ -174,35 +174,35 @@ :100AC000FFF7D4FC00283FF447AE00F005F90028FA :100AD00044D00A9B01330BD008220AA9002000F061 :100AE000ABF900283AD02022FF210AA800F09CF997 -:100AF000FFF7C4FC1C4800F0C7FF13B0BDE8F08F3F +:100AF000FFF7C4FC1C4800F0EBFF13B0BDE8F08F1B :100B0000002E3FF429AE0BF00B030B2B7FF424AE29 :100B10000023642105A8059300F062F80746002829 :100B20007FF41AAE0220FFF7A1FC814600283FF4B3 -:100B300013AEFFF7A3FC41F2883000F0A5FF059843 +:100B300013AEFFF7A3FC41F2883000F0C9FF05981F :100B400000F0F2F94E463C4600F0BAF9B6E506462A :100B50004CE64FF0000AFFE5B8467BE6374679E6FB :100B60007822002000220020A08601000F4B70B5E3 :100B70001B780C460133DBB2012B11D80C4D4FF41E :100B80007A732968A2FB033222460E6A0146284680 :100B9000B047844204D1074B002201201A7070BD77 -:100BA0004FF4FA7000F070FF0020F8E710220020E8 +:100BA0004FF4FA7000F094FF0020F8E710220020C4 :100BB00070250020B0230020002307B50246012144 :100BC0000DF107008DF80730FFF7D0FF20B19DF839 :100BD000070003B05DF804FB4FF0FF30F9E70000B9 :100BE0000A46042108B5FFF7C1FF80F00100C0B23A :100BF000404208BD30B4054C0A46014623682046F1 :100C0000DD69034BAC4630BC604700BF7025002057 -:100C1000A086010070B5104C0025104E01F0E2F9DD +:100C1000A086010070B5104C0025104E01F006FAB8 :100C200020803068238883420CD800252088013832 -:100C300001F0D4F923880544013BB5F5802F2380CA -:100C4000F4D370BD01F0CAF9336805440133B5F53A +:100C300001F0F8F923880544013BB5F5802F2380A6 +:100C4000F4D370BD01F0EEF9336805440133B5F516 :100C5000003F3360E5D3E8E7B2230020842300207F -:100C600001F090BA00F1006000F5003000687047B4 -:100C700000F10060920000F5003001F00FBA0000B2 +:100C600001F0C2BA00F1006000F500300068704782 +:100C700000F10060920000F5003001F039BA000088 :100C8000054B1A68054B1B889B1A834202D91044F6 -:100C900001F0A4B90020704784230020B223002073 -:100CA00038B5074D04462868204401F09DF928B95D -:100CB00028682044BDE8384001F0A8B938BD00BF1D +:100C900001F0C8B90020704784230020B22300204F +:100CA00038B5074D04462868204401F0C1F928B939 +:100CB00028682044BDE8384001F0CCB938BD00BFF9 :100CC000842300200020704700F1FF5000F58F10B2 :100CD000D0F8000870470000064991F8243033B17D :100CE00000230822086A81F82430FFF7C1BF0120E1 @@ -238,10 +238,10 @@ :100EC000024B1A78024B1A70704700BFB023002003 :100ED0001022002010B5104C104800F0FBF82146FD :100EE0000E4800F023F924680D48D4F89020D2F879 -:100EF000043843F00203C2F8043800F0C5FD094984 +:100EF000043843F00203C2F8043800F0E9FD094960 :100F0000204600F021FAD4F89020D2F8043823F0DB -:100F10000203C2F8043810BD643A000870250020AE -:100F200040420F006C3A00087047000000B59BB0CB +:100F10000203C2F8043810BDE43A0008702500202E +:100F200040420F00EC3A00087047000000B59BB04B :100F3000EFF3098168226846FFF750FFEFF305835E :100F4000044B9A6BDA6A9A6A9A6A9A6A9A6A9A6AF5 :100F50009B6AFEE700ED00E000B59BB0EFF309816E @@ -256,34 +256,34 @@ :100FE0001143016003B118477047000013B5406B0F :100FF00000F58054D4F8A4381A681178042914D163 :10100000017C022911D11979012312898B401342E5 -:101010000BD101A94C3002F03BF8D4F8A4480246A9 +:101010000BD101A94C3002F06FF8D4F8A448024675 :10102000019B2179206800F0DFF902B010BD0000BB -:10103000143001F0BDBF00004FF0FF33143001F059 -:10104000B7BF00004C3002F08FB800004FF0FF3304 -:101050004C3002F089B80000143001F08BBF000062 -:101060004FF0FF31143001F085BF00004C3002F02A -:101070005BB800004FF0FF324C3002F055B8000072 +:10103000143001F0F1BF00004FF0FF33143001F025 +:10104000EBBF00004C3002F0C3B800004FF0FF339C +:101050004C3002F0BDB80000143001F0BFBF0000FA +:101060004FF0FF31143001F0B9BF00004C3002F0F6 +:101070008FB800004FF0FF324C3002F089B800000A :101080000020704710B500F58054D4F8A4381A68D1 :101090001178042917D1017C022914D1597901232F -:1010A00052898B4013420ED1143001F01DFF0246CD +:1010A00052898B4013420ED1143001F051FF024699 :1010B00048B1D4F8A4484FF4407361792068BDE882 :1010C000104000F07FB910BD406BFFF7DBBF0000A0 :1010D000704700007FB5124B0125042604460360CB :1010E0000023057400F1840243602946C0E90233FD :1010F0000C4B0290143001934FF44073009601F0B2 -:10110000CFFE094B04F69442294604F14C000294A8 -:10111000CDE900634FF4407301F096FF04B070BD59 -:10112000A0390008C9100008ED0F00080A68202344 +:1011000003FF094B04F69442294604F14C00029473 +:10111000CDE900634FF4407301F0CAFF04B070BD25 +:10112000203A0008C9100008ED0F00080A682023C3 :1011300083F311880B790B3342F823004B79133377 :1011400042F823008B7913B10B3342F8230000F5EA :101150008053C3F8A41802230374002383F3118877 :101160007047000038B5037F044613B190F854303F :10117000ABB90125201D0221FFF730FF04F1140057 -:101180006FF00101257700F0A7FC04F14C0084F812 -:1011900054506FF00101BDE8384000F09DBC38BDEF +:101180006FF00101257700F0CBFC04F14C0084F8EE +:1011900054506FF00101BDE8384000F0C1BC38BDCB :1011A00010B5012104460430FFF718FF0023237710 :1011B00084F8543010BD000038B5044600251430C2 -:1011C00001F086FE04F14C00257701F055FF201D4B +:1011C00001F0BAFE04F14C00257701F089FF201DE3 :1011D00084F854500121FFF701FF2046BDE8384054 :1011E000FFF750BF90F8803003F06003202B06D14A :1011F00090F881200023212A03D81F2A06D8002036 @@ -291,46 +291,46 @@ :1012100007228267C3670120704700BF2C2200208D :1012200037B500F58055D5F8A4381A681178042927 :101230001AD1017C022917D11979012312898B4017 -:10124000134211D100F14C04204601F0D5FF58B1F2 -:1012500001A9204601F01CFFD5F8A4480246019BD5 +:10124000134211D100F14C04204602F009F858B1C4 +:1012500001A9204601F050FFD5F8A4480246019BA1 :101260002179206800F0C0F803B030BD01F10B0314 :10127000F0B550F8236085B004460D46FEB120233A :1012800083F3118804EB8507301D0821FFF7A6FEC4 :10129000FB6806F14C005B691B681BB1019001F013 -:1012A00005FF019803A901F0F3FE024648B1039B34 +:1012A00039FF019803A901F027FF024648B1039BCB :1012B0002946204600F098F8002383F3118805B0F2 :1012C000F0BDFB685A691268002AF5D01B8A013B01 :1012D0001340F1D104F18002EAE70000133138B580 :1012E00050F82140ECB1202383F3118804F580539A :1012F000D3F8A4281368527903EB8203DB689B6957 :101300005D6845B104216018FFF768FE294604F1C5 -:10131000140001F0F3FD2046FFF7B4FE002383F331 -:10132000118838BD7047000001F0E6B80123402263 +:10131000140001F027FE2046FFF7B4FE002383F3FC +:10132000118838BD7047000001F01AB9012340222E :10133000002110B5044600F8303BFFF775FD00238F :10134000C4E9013310BD000010B52023044683F327 :1013500011882422416000210C30FFF765FD2046F2 -:1013600001F0ECF802232370002383F3118810BDF1 +:1013600001F020F902232370002383F3118810BDBC :1013700070B500EB8103054650690E461446DA60ED :1013800018B110220021FFF74FFDA06918B11022FB :101390000021FFF749FD31462846BDE8704001F0C5 -:1013A000DFB9000083682022002103F0011310B58B +:1013A00013BA000083682022002103F0011310B556 :1013B000044683601030FFF737FD2046BDE810403B -:1013C00001F05ABAF0B4012500EB810447898D4041 +:1013C00001F08EBAF0B4012500EB810447898D400D :1013D000E4683D43A469458123600023A260636003 -:1013E000F0BC01F077BA0000F0B4012500EB8104F5 +:1013E000F0BC01F0ABBA0000F0B4012500EB8104C1 :1013F00007898D40E4683D436469058123600023CB -:10140000A2606360F0BC01F0EDBA000070B5022389 +:10140000A2606360F0BC01F021BB000070B5022354 :1014100000250446242203702946C0F888500C3069 :1014200040F8045CFFF700FD204684F8705001F09E -:101430002BF963681B6823B129462046BDE870403C +:101430005FF963681B6823B129462046BDE8704008 :10144000184770BD037880F88C300523037043681B :101450001B6810B504460BB1042198470023A36014 :1014600010BD000090F88C20436802701B680BB11F :10147000052118477047000070B590F87030044699 :1014800013B1002380F8703004F18002204601F08F -:1014900017FA63689B68B3B994F8803013F060055D -:1014A00035D00021204601F0C1FC0021204601F08A -:1014B000B1FC63681B6813B10621204698470623D8 +:101490004BFA63689B68B3B994F8803013F0600529 +:1014A00035D00021204601F0F5FC0021204601F056 +:1014B000E5FC63681B6813B10621204698470623A4 :1014C00084F8703070BD204698470028E4D0B4F806 :1014D0008630A26F9A4288BFA36794F98030A56FC7 :1014E000002B4FF0200380F20381002D00F0F280EA @@ -350,26 +350,26 @@ :1015C0008230012B7FF46DAFB4F8883023F0020332 :1015D000A4F88830C4E91D55E56778E7B4F8803091 :1015E000B3F5A06F0ED194F88230204684F88A308B -:1015F00001F0A8F863681B6813B1012120469847E1 +:1015F00001F0DCF863681B6813B1012120469847AD :10160000032323700023C4E91D339CE704F18B03FB :1016100063670123C3E72378042B10D1202383F3CE :1016200011882046FFF7BEFE85F311880321636809 :1016300084F88B5021701B680BB12046984794F8B2 :101640008230002BDED084F88B3004232370636853 :101650001B68002BD6D0022120469847D2E794F889 -:10166000843020461D0603F00F010AD501F01AF957 +:10166000843020461D0603F00F010AD501F04EF923 :10167000012804D002287FF414AF2B4B9AE72B4BA0 -:1016800098E701F001F9F3E794F88230002B7FF43A +:1016800098E701F035F9F3E794F88230002B7FF406 :1016900008AF94F8843013F00F01B3D01A06204637 -:1016A00002D501F0DBFBADE701F0CCFBAAE794F833 +:1016A00002D501F00FFCADE701F000FCAAE794F8C9 :1016B0008230002B7FF4F5AE94F8843013F00F01E4 -:1016C000A0D01B06204602D501F0B0FB9AE701F03E -:1016D000A1FB97E7142284F8702083F311882B462E +:1016C000A0D01B06204602D501F0E4FB9AE701F00A +:1016D000D5FB97E7142284F8702083F311882B46FA :1016E0002A4629462046FFF76DFE85F31188E9E674 :1016F0005DB1152284F8702083F311880021204603 :10170000D4E91D23FFF75EFEFDE60B2284F870206E :1017100083F311882B462A4629462046FFF764FEAC -:10172000E3E700BFD0390008C8390008CC39000809 +:10172000E3E700BF503A0008483A00084C3A000886 :1017300038B590F870300446002B3ED0063BDAB244 :101740000F2A34D80F2B32D8DFE803F037313108B5 :10175000223231313131313131313737856FB0F8A3 @@ -379,11 +379,11 @@ :10179000142384F87030202383F31188002320461B :1017A0001A461946FFF70EFE002383F3118838BD51 :1017B000C36F03B198470023E7E70021204601F0FB -:1017C00035FB0021204601F025FB63681B6813B13F +:1017C00069FB0021204601F059FB63681B6813B1D7 :1017D0000621204698470623D7E7000010B590F869 :1017E00070300446142B29D017D8062B05D001D809 :1017F0001BB110BD093B022BFBD80021204601F094 -:1018000015FB0021204601F005FB63681B6813B13E +:1018000049FB0021204601F039FB63681B6813B1D6 :10181000062120469847062319E0152BE9D10B2312 :1018200080F87030202383F3118800231A4619466C :10183000FFF7DAFD002383F31188DAE7C3689B69B9 @@ -399,8 +399,8 @@ :1018D0004260106058607047B4230020054B1969BE :1018E00008741868026853601A6018610123037451 :1018F000FEF76CBDB42300204B1C30B5044687B006 -:101900000A4D10D02B6901A8094A00F001F92046C0 -:10191000FFF7E4FF049B13B101A800F035F92B6930 +:101900000A4D10D02B6901A8094A00F025F920469C +:10191000FFF7E4FF049B13B101A800F059F92B690C :10192000586907B030BDFFF7D9FFF8E7B4230020AE :101930008518000838B50C4D044641612B69816853 :101940009A68914203D8BDE83840FFF78BBF18462C @@ -409,568 +409,576 @@ :101970001B6990689B68984294BF002001207047C3 :10198000B423002010B5084C236820691A685460FD :101990002260012223611A74FFF790FF014620693B -:1019A000BDE81040FEF712BDB4230020FFF7EABFE8 -:1019B000FEE7000010B50C4CFFF74CFF00F09AF862 -:1019C00080220A49204600F021F8012344F8180C2F -:1019D000037400F06FFC002383F3118862B604489F -:1019E000BDE8104000F032B8DC230020D4390008F4 -:1019F000E439000800F002B9034A516853685B1AE1 -:101A00009842FBD8704700BF001000E082600222BD -:101A1000028270478368A3F17C0243F80C2C0269B0 -:101A200043F83C2C426943F8382C074A43F81C2CF5 -:101A3000C268A3F1180043F8102C022203F8082C06 -:101A4000002203F8072C7047E503000810B5202397 -:101A500083F31188FFF7DEFF00210446FFF76AFFDA -:101A6000002383F31188204610BD0000024B1B6940 -:101A700058610F20FFF732BFB4230020202383F3E7 -:101A80001188FFF7F3BF000008B50146202383F358 -:101A900011880820FFF730FF002383F3118808BD69 -:101AA00049B1064B42681B6918605A601360436075 -:101AB0000420FFF721BF4FF0FF307047B423002010 -:101AC0000368984206D01A6802605060184659614F -:101AD000FFF7C8BE7047000038B504460D462068C1 -:101AE000844200D138BD036823605C604561FFF724 -:101AF000B9FEF4E7054B4FF0FF3103F11402C3E9DF -:101B000005220022C3E90712704700BFB42300205A -:101B100070B51C4E05460C46C0E9032301F0A2FB3C -:101B2000334653F8142F9A420DD130620A2C2CBF41 -:101B300000190A302A60C5E90124C6E90555BDE847 -:101B4000704001F079BB316A431AE31838BF1C4674 -:101B50009368A34202D9081901F07EFB73699A6861 -:101B600094420CD85A68AC602B606A6015609A6821 -:101B70005D60121B9A604FF0FF33F36170BDA41AD1 -:101B80001B68ECE7B423002038B51B4C636998420E -:101B90000DD08168D0E9003213605A600022C26023 -:101BA0009A680A449A604FF0FF33E36138BD0368D6 -:101BB0002246002142F8143F93425A60C16003D18B -:101BC000BDE8384001F042BB9A688168256A0A4442 -:101BD0009A6001F047FB6369411B9A688A42E5D924 -:101BE000AB181D1A206A092D98BF01F10A02BDE841 -:101BF0003840104401F030BBB42300202DE9F041FF -:101C0000184C002704F11406656901F02BFB236AC8 -:101C1000AA68C11A8A4215D81344D5F80C802362E9 -:101C2000D5E9003213605A606369EF60B34201D1B5 -:101C300001F00CFB87F311882869C047202383F348 -:101C40001188E1E76169B14209D013441B1ABDE86C -:101C5000F0410A2B2CBFC0180A3001F0FDBABDE8D4 -:101C6000F08100BFB423002000207047FEE7000091 -:101C7000704700004FF0FF307047000002290CD081 -:101C8000032904D00129074818BF00207047032A00 -:101C900005D8054800EBC200704704487047002093 -:101CA000704700BFC83A00083C2200207C3A000878 -:101CB00070B59AB005460846144601A900F0C2F86E -:101CC00001A8FFF7A9F8431C0022C6B25B0010462A -:101CD000C5E9003423700323023404F8013C01AB4E -:101CE000D1B202348E4201D81AB070BD13F8011B74 -:101CF000013204F8010C04F8021CF1E708B52023B6 -:101D000083F311880348FFF78BFA002383F31188CC -:101D100008BD00BF7025002090F8803003F01F023E -:101D2000012A07D190F881200B2A03D10023C0E9B2 -:101D30001D3315E003F06003202B08D1B0F8843088 -:101D40002BB990F88120212A03D81F2A04D8FFF745 -:101D500049BA222AEBD0FAE7034A42670722826790 -:101D6000C3670120704700BF3322002007B5052953 -:101D700017D8DFE801F0191603191920202383F37F -:101D80001188104A01210190FFF7F2FA019802210F -:101D90000D4AFFF7EDFA0D48FFF70EFA002383F323 -:101DA000118803B05DF804FB202383F311880748F2 -:101DB000FFF7D8F9F2E7202383F311880348FFF7F0 -:101DC000EFF9EBE71C3A0008403A000870250020C4 -:101DD00038B50C4D0C4C2A460C4904F10800FFF7AD -:101DE00067FF05F1CA0204F110000949FFF760FF1F -:101DF00005F5CA7204F118000649BDE83840FFF73E -:101E000057BF00BF483E00203C220020FC3900089C -:101E1000063A0008113A000870B5044608460D4617 -:101E2000FEF7FAFFC6B22046013403780BB9184614 -:101E300070BD32462946FEF7DBFF0028F3D10120B2 -:101E4000F6E700002DE9F84F05460C46FEF7E4FFE3 -:101E50002C49C6B22846FFF7DFFF08B10536F6B2B7 -:101E600029492846FFF7D8FF08B11036F6B2632E8D -:101E70000DD8DFF89080DFF89090244FDFF894A021 -:101E8000DFF894B02E7846B92670BDE8F88F294661 -:101E90002046BDE8F84F01F06DBD252E2ED107225A -:101EA00041462846FEF7A4FF70B9DBF8003007353D -:101EB0000C3444F80C3CDBF8043044F8083CDBF804 -:101EC000083044F8043CDDE7082249462846FEF77E -:101ED0008FFF98B9A21C0E4B197802320909C95D0F -:101EE00002F8041C13F8011B01F00F015345C95DF2 -:101EF00002F8031CF0D118340835C3E7013504F8A3 -:101F0000016BBFE7E83A0008113A0008FD3A000803 -:101F100000E8F11F0CE8F11FF03A0008BFF34F8F03 -:101F2000044B1A695107FCD1D3F810215207F8D19C -:101F3000704700BF0020005208B50D4B1B78ABB9AD -:101F4000FFF7ECFF0B4BDA68D10704D50A4A5A6059 -:101F500002F188325A60D3F80C21D20706D5064A1E -:101F6000C3F8042102F18832C3F8042108BD00BF80 -:101F7000A6400020002000522301674508B5114B00 -:101F80001B78F3B9104B1A69510703D5DA6842F090 -:101F90004002DA60D3F81021520705D5D3F80C219E -:101FA00042F04002C3F80C21FFF7B8FF064BDA6895 -:101FB00042F00102DA60D3F80C2142F00102C3F8CA -:101FC0000C2108BDA6400020002000520F289ABF17 -:101FD00000F5806040040020704700004FF400309E -:101FE00070470000102070470F2808B50BD8FFF786 -:101FF000EDFF00F500330268013204D10430834262 -:10200000F9D1012008BD0020FCE700000F2838B5F9 -:1020100005463FD8FFF782FF1F4CFFF78DFF4FF0BB -:10202000FF3307286361C4F814311DD82361FFF71B -:1020300075FF030243F02403E360E36843F0800389 -:10204000E36023695A07FCD42846FFF767FFFFF7D0 -:10205000BDFF4FF4003100F0F7F82846FFF78EFF80 -:10206000BDE83840FFF7C0BFC4F81031FFF756FF96 -:10207000A0F108031B0243F02403C4F80C31D4F888 -:102080000C3143F08003C4F80C31D4F810315B07F5 -:10209000FBD4D9E7002038BD002000522DE9F84FCD -:1020A00005460C46104645EA0203DB065DD122F0E8 -:1020B00003022B462A44934209D120F01F00DFF887 -:1020C000BCB0DFF8BCA0FFF737FF271844E0196861 -:1020D00001314AD10433EEE705F17843244925481C -:1020E000B3F5801F244B38BF184603F1F80339BFFE -:1020F0008846D9469846D146FFF710FF4FF0FF3388 -:10210000A5EB040C04F11C010360D8F8003043F087 -:102110000203C8F80030231FD9F8006016F0050646 -:10212000FAD153F8042F99424CF80320F4D1BFF3AD -:102130004F8FFFF7F3FE4FF0FF332022214603605D -:102140002846D8F8003023F00203C8F8003001F028 -:1021500001FC40B920352034BC42BDD10120FFF73D -:102160000DFFBDE8F88F3046F9E70020F9E700BF22 -:102170000C20005214210052142000521020005252 -:102180001021005210B5084C237828B11BB9FFF775 -:10219000D3FE0123237010BD002BFCD02070BDE8BE -:1021A0001040FFF7EBBE00BFA64000200244074BE3 -:1021B000D2B210B5904200D110BD441C00B253F809 -:1021C000200041F8040BE0B2F4E700BF5040005893 -:1021D0000E4B30B51C6F240405D41C6F1C671C6F9C -:1021E00044F400441C670A4C02442368D2B243F40E -:1021F00080732360074B904200D130BD441C51F8DE -:10220000045B00B243F82050E0B2F4E70044025807 -:10221000004802585040005807B5012201A900208B -:10222000FFF7C4FF019803B05DF804FB13B5044643 -:10223000FFF7F2FFA04205D0012201A9002001947E -:10224000FFF7C6FF02B010BD0144BFF34F8F064B2E -:10225000884204D3BFF34F8FBFF36F8F7047C3F82B -:102260005C022030F4E700BF00ED00E0044BD3F83F -:10227000D0345B0142BF034B01221A70704700BF8C -:1022800000400258A7400020014B1878704700BF5B -:10229000A7400020EFF30983054968334A6B22F019 -:1022A00001024A6383F30988002383F3118870478E -:1022B00000EF00E0202080F3118862B60D4B0E4A3B -:1022C000D96821F4E0610904090C0A430B49DA607A -:1022D000D3F8FC2042F08072C3F8FC20084AC2F810 -:1022E000B01F116841F0010111601022DA7783F804 -:1022F0002200704700ED00E00003FA0555CEACC5A2 -:10230000001000E0202310B583F311880E4B5B68AA -:1023100013F4006314D0F1EE103AEFF309844FF098 -:102320008073683CE361094BDB6B236684F30988A7 -:10233000FFF71CFB10B1064BA36110BD054BFBE77B -:1023400083F31188F9E700BF00ED00E000EF00E043 -:10235000F7030008FA03000870B5BFF34F8FBFF30F -:102360006F8F1A4A0021C2F85012BFF34F8FBFF38C -:102370006F8F536943F400335361BFF34F8FBFF343 -:102380006F8FC2F88410BFF34F8FD2F8803043F6BE -:10239000E074C3F3C900C3F34E335B0103EA0406E0 -:1023A000014646EA81750139C2F86052F9D2203BF4 -:1023B00013F1200FF2D1BFF34F8F536943F48033F1 -:1023C0005361BFF34F8FBFF36F8F70BD00ED00E01F -:1023D000FEE700000A4B0B480B4A90420BD30B4B15 -:1023E000C11EDA1C121A22F003028B4238BF0022EF -:1023F0000021FEF719BD53F8041B40F8041BECE75D -:10240000DC3C00087842002078420020784200201E -:102410007047000070B5D0E9244300224FF0FF352B -:102420009E6804EB42135101D3F80009002805DA35 -:10243000D3F8000940F08040C3F80009D3F8000B3E -:10244000002805DAD3F8000B40F08040C3F8000BF9 -:10245000013263189642C3F80859C3F8085BE0D20A -:102460004FF00113C4F81C3870BD000000EB81036D -:10247000D3F80CC02DE9F043DCF814204E1CD0F842 -:102480009050D2F800E005EB063605EB4118506895 -:1024900070450AD30122D5F8343802FA01F123EA53 -:1024A0000101C5F83418BDE8F083AEEB0003BCF8B9 -:1024B0001040A34228BF2346D8F81849A4B2B3EB72 -:1024C000840FF0D89468A4F1040959F8047F3760A8 -:1024D000A4EB09071F44042FF7D81C44034494605D -:1024E0005360D4E7890141F02001016103699B0633 -:1024F000FCD41220FFF780BA10B50A4C2046FEF734 -:1025000015FF094BC4F89030084BC4F89430084CC0 -:102510002046FEF70BFF074BC4F89030064BC4F87B -:10252000943010BDA840002000000840343B000853 -:102530004441002000000440403B000870B503788F -:102540000546012B5DD1494BD0F89040984259D1B6 -:10255000474B0E216520D3F8D82042F00062C3F823 -:10256000D820D3F8002142F00062C3F80021D3F84C -:102570000021D3F8802042F00062C3F88020D3F815 -:10258000802022F00062C3F88020D3F8803000F071 -:1025900071FC384BE360384BC4F800380023D5F8A1 -:1025A0009060C4F8003EC02323604FF40413A3637B -:1025B0003369002BFCDA01230C203361FFF71CFA8E -:1025C0003369DB07FCD41220FFF716FA3369002BBE -:1025D000FCDA00262846A660FFF71CFF6B68C4F8EB -:1025E0001068DB68C4F81468C4F81C68002B3AD182 -:1025F000224BA3614FF0FF336361A36843F00103F3 -:10260000A36070BD1E4B9842C8D1194B0E214D20BE -:10261000D3F8D82042F00072C3F8D820D3F80021B4 -:1026200042F00072C3F80021D3F80021D3F88020D3 -:1026300042F00072C3F88020D3F8802022F00072AC -:10264000C3F88020D3F88020D3F8D82022F080620D -:10265000C3F8D820D3F8002122F08062C3F800210B -:10266000D3F8003193E7074BC3E700BFA840002031 -:10267000004402584014004003002002003C30C0D7 -:1026800044410020083C30C0F8B5D0F890400546E1 -:1026900000214FF000662046FFF724FFD5F8941084 -:1026A00000234FF001128F684FF0FF30C4F8343828 -:1026B000C4F81C2804EB431201339F42C2F800699E -:1026C000C2F8006BC2F80809C2F8080BF2D20B6816 -:1026D000D5F89020C5F8983063621023136116690D -:1026E00016F01006FBD11220FFF786F9D4F8003857 -:1026F00023F4FE63C4F80038A36943F4402343F095 -:102700001003A3610923C4F81038C4F814380B4B24 -:10271000EB604FF0C043C4F8103B094BC4F8003BDA -:10272000C4F81069C4F80039D5F8983003F11002E4 -:1027300043F48013C5F89820A362F8BD103B00084D -:1027400040800010D0F8902090F88A10D2F800381D -:1027500023F4FE6343EA0113C2F800387047000017 -:102760002DE9F84300EB8103D0F890500C468046E9 -:10277000DA680FFA81F94801166806F00306731E3D -:10278000022B05EB41134FF0000194BFB604384E05 -:10279000C3F8101B4FF0010104F1100398BF06F1BC -:1027A000805601FA03F3916998BF06F500460029A7 -:1027B0003AD0578A04F15801374349016F50D5F890 -:1027C0001C180B430021C5F81C382B180127C3F82F -:1027D0001019A7405369611E9BB3138A928B9B0803 -:1027E000012A88BF5343D8F89820981842EA034337 -:1027F00001F140022146C8F89800284605EB820204 -:102800005360FFF76FFE08EB8900C3681B8A43EA39 -:10281000845348341E4364012E51D5F81C381F439D -:10282000C5F81C78BDE8F88305EB4917D7F8001BFD -:1028300021F40041C7F8001BD5F81C1821EA030356 -:10284000C0E704F13F030B4A2846214605EB83030A -:102850005A60FFF747FE05EB4910D0F8003923F422 -:102860000043C0F80039D5F81C3823EA0707D7E73A -:102870000080001000040002D0F894201268C0F814 -:102880009820FFF7C7BD00005831D0F890304901BB -:102890005B5813F4004004D013F4001F0CBF022057 -:1028A000012070474831D0F8903049015B5813F44B -:1028B000004004D013F4001F0CBF02200120704719 -:1028C00000EB8101CB68196A0B6813604B68536099 -:1028D0007047000000EB810330B5DD68AA6913681A -:1028E000D36019B9402B84BF402313606B8A1468EE -:1028F000D0F890201C4402EB4110013C09B2B4FB1B -:10290000F3F46343033323F0030343EAC44343F084 -:10291000C043C0F8103B2B6803F00303012B0ED11A -:10292000D2F8083802EB411013F4807FD0F8003B56 -:1029300014BF43F0805343F00053C0F8003B02EB58 -:102940004112D2F8003B43F00443C2F8003B30BDD3 -:102950002DE9F041D0F8906005460C4606EB411396 -:10296000D3F8087B3A07C3F8087B08D5D6F81438A3 -:102970001B0704D500EB8103DB685B689847FA0707 -:102980001FD5D6F81438DB071BD505EB8403D968AF -:10299000CCB98B69488A5A68B2FBF0F600FB162264 -:1029A0008AB91868DA6890420DD2121AC3E9002475 -:1029B000202383F3118821462846FFF78BFF84F3F9 -:1029C0001188BDE8F081012303FA04F26B8923EA40 -:1029D00002036B81CB68002BF3D021462846BDE86B -:1029E000F041184700EB81034A0170B5DD68D0F86B -:1029F00090306C692668E66056BB1A444FF400209C -:102A0000C2F810092A6802F00302012A0AB20ED1A4 -:102A1000D3F8080803EB421410F4807FD4F80009BF -:102A200014BF40F0805040F00050C4F8000903EBA0 -:102A30004212D2F8000940F00440C2F80009012215 -:102A4000D3F8340802FA01F10143C3F8341870BD19 -:102A500019B9402E84BF4020206020681A442E8A75 -:102A60008419013CB4FBF6F440EAC44040F0005045 -:102A7000C6E700002DE9F041D0F8906004460D460D -:102A800006EB4113D3F80879C3F80879FB071CD586 -:102A9000D6F81038DA0718D500EB8103D3F80CC04C -:102AA000DCF81430D3F800E0DA6896451BD2A2EBCC -:102AB0000E024FF000081A60C3F80480202383F34D -:102AC0001188FFF78FFF88F311883B0618D5012383 -:102AD000D6F83428AB40134212D029462046BDE830 -:102AE000F041FFF7C3BC012303FA01F2038923EA93 -:102AF00002030381DCF80830002BE6D09847E4E7B6 -:102B0000BDE8F0812DE9F84FD0F8905004466E6989 -:102B1000AB691E4016F480586E6103D0BDE8F84FD3 -:102B2000FEF774BC002E12DAD5F8003E9F0705D0E0 -:102B3000D5F8003E23F00303C5F8003ED5F804386D -:102B4000204623F00103C5F80438FEF78BFC30055E -:102B500005D52046FFF75EFC2046FEF773FCB10466 -:102B60000CD5D5F8083813F0060FEB6823F4705332 -:102B70000CBF43F4105343F4A053EB60320704D569 -:102B80006368DB680BB120469847F30200F1BA8016 -:102B9000B70226D5D4F8909000274FF0010A09EB30 -:102BA0004712D2F8003B03F44023B3F5802F11D134 -:102BB000D2F8003B002B0DDA62890AFA07F322EA09 -:102BC0000303638104EB8703DB68DB6813B13946D9 -:102BD000204698470137D4F89430FFB29B689F4253 -:102BE000DDD9F00619D5D4F89000026AC2F30A17AD -:102BF00002F00F0302F4F012B2F5802F00F0CC8047 -:102C0000B2F5402F09D104EB8303002200F5805078 -:102C1000DB681B6A974240F0B2803003D5F8185841 -:102C200035D5E90303D500212046FFF791FEAA031D -:102C300003D501212046FFF78BFE6B0303D502214C -:102C40002046FFF785FE2F0303D503212046FFF71B -:102C50007FFEE80203D504212046FFF779FEA90292 -:102C600003D505212046FFF773FE6A0203D506212E -:102C70002046FFF76DFE2B0203D507212046FFF704 -:102C800067FEEF0103D508212046FFF761FE7003C0 -:102C900040F1A980E90703D500212046FFF7EAFEAD -:102CA000AA0703D501212046FFF7E4FE6B0703D5F1 -:102CB00002212046FFF7DEFE2F0703D50321204621 -:102CC000FFF7D8FEEE0603D504212046FFF7D2FE1B -:102CD000A80603D505212046FFF7CCFE690603D5DB -:102CE00006212046FFF7C6FE2A0603D50721204607 -:102CF000FFF7C0FEEB0576D520460821BDE8F84F6A -:102D0000FFF7B8BED4F8909000274FF0010AD4F82E -:102D100094305FFA87FB9B689B453FF639AF09EB20 -:102D20004B13D3F8002902F44022B2F5802F24D1AE -:102D3000D3F80029002A20DAD3F8002942F0904283 -:102D4000C3F80029D3F80029002AFBDB5946D4F840 -:102D50009000FFF7C7FB22890AFA0BF322EA03036C -:102D6000238104EB8B03DB689B6813B15946204633 -:102D7000984759462046FFF779FB0137C7E7910787 -:102D800001D1D0F80080072A02F101029CBF03F8AC -:102D9000018B4FEA18283DE704EB830300F58050D0 -:102DA000DA68D2F818C0DCF80820DCE9001CA1EBD6 -:102DB0000C0C00218F4208D1DB689B699A683A4469 -:102DC0009A605A683A445A6027E711F0030F01D11C -:102DD000D0F800808C4501F1010184BF02F8018B1D -:102DE0004FEA1828E6E7BDE8F88F000008B5034869 -:102DF000FFF788FEBDE80840FFF784BAA84000202E -:102E000008B50348FFF77EFEBDE80840FFF77ABA31 -:102E100044410020D0F8903003EB4111D1F8003B41 -:102E200043F40013C1F8003B70470000D0F8903025 -:102E300003EB4111D1F8003943F40013C1F8003914 -:102E400070470000D0F8903003EB4111D1F8003BFF -:102E500023F40013C1F8003B70470000D0F8903015 -:102E600003EB4111D1F8003923F40013C1F8003904 -:102E700070470000090100F16043012203F561433E -:102E8000C9B283F8001300F01F039A4043099B0066 -:102E900003F1604303F56143C3F880211A60704772 -:102EA00030B50433039C0172002104FB0325C1608B -:102EB000C0E90653049B0363059BC0E90000C0E919 -:102EC0000422C0E90842C0E90A11436330BD000092 -:102ED0000022416AC260C0E90411C0E90A226FF011 -:102EE0000101FEF7F9BD0000D0E90432934201D19F -:102EF000C2680AB9181D704700207047036919603D -:102F00000021C2680132C260C269134482699342DF -:102F1000036124BF436A0361FEF7D2BD38B504469E -:102F20000D46E3683BB162690020131D1268A3627D -:102F30001344E36207E0237A33B929462046FEF7BB -:102F4000AFFD0028EDDA38BD6FF00100FBE70000AF -:102F5000C368C269013BC3604369134482699342F9 -:102F6000436124BF436A436100238362036B03B15F -:102F70001847704770B52023044683F31188866A8A -:102F80003EB9FFF7CBFF054618B186F311882846F6 -:102F900070BDA36AE26A13F8015B9342A36202D395 -:102FA0002046FFF7D5FF002383F31188EFE70000E9 -:102FB0002DE9F84F04460E46174698464FF0200973 -:102FC00089F311880025AA46D4F828B0BBF1000F78 -:102FD00009D141462046FFF7A1FF20B18BF31188AC -:102FE0002846BDE8F88FD4E90A12A7EB050B521A60 -:102FF000934528BF9346BBF1400F1BD9334601F1DF -:10300000400251F8040B914243F8040BF9D1A36A32 -:10301000403640354033A362D4E90A239A4202D3B2 -:103020002046FFF795FF8AF31188BD42D8D289F375 -:103030001188C9E730465A46FDF7D0FEA36A5E44C0 -:103040005D445B44A362E7E710B5029C0433017260 -:1030500004FB0321C460C0E906130023C0E90A335E -:10306000039B0363049BC0E90000C0E90422C0E99C -:103070000842436310BD0000026A6FF00101C260A4 -:10308000426AC0E904220022C0E90A22FEF724BDF8 -:10309000D0E904239A4201D1C26822B9184650F8F7 -:1030A000043B0B607047002070470000C36800219C -:1030B000C2690133C3604369134482699342436127 -:1030C00024BF436A4361FEF7FBBC000038B50446E9 -:1030D0000D46E3683BB1236900201A1DA262E26934 -:1030E0001344E36207E0237A33B929462046FEF70A -:1030F000D7FC0028EDDA38BD6FF00100FBE70000D7 -:1031000003691960C268013AC260C26913448269E6 -:103110009342036124BF436A036100238362036B0C -:1031200003B118477047000070B520230D460446D0 -:10313000114683F31188866A2EB9FFF7C7FF10B1D5 -:1031400086F3118870BDA36A1D70A36AE26A013319 -:103150009342A36204D3E16920460439FFF7D0FF0C -:10316000002080F31188EDE72DE9F84F04460D4665 -:10317000904699464FF0200A8AF311880026B346FC -:10318000A76A4FB949462046FFF7A0FF20B187F351 -:1031900011883046BDE8F88FD4E90A073A1AA8EB3F -:1031A0000607974228BF1746402F1BD905F1400359 -:1031B00055F8042B9D4240F8042BF9D1A36A403600 -:1031C0004033A362D4E90A239A4204D3E16920463A -:1031D0000439FFF795FF8BF311884645D9D28AF35E -:1031E0001188CDE729463A46FDF7F8FDA36A3D442C -:1031F0003E443B44A362E5E7D0E904239A4217D159 -:10320000C3689BB1836A8BB1043B9B1A0ED01360D9 -:10321000C368013BC360C3691A4483699A4202616F -:1032200024BF436A03610023836201231846704769 -:103230000023FBE700F0CEB8034B002258631A616D -:103240000222DA60704700BF000C0040014B0022F0 -:10325000DA607047000C0040014B5863704700BFB4 -:10326000000C0040014B586A704700BF000C004042 -:103270004B6843608B688360CB68C3600B694361B4 -:103280004B6903628B6943620B68036070470000FF -:1032900008B5364B40F2FF713548D3F888200A4311 -:1032A000C3F88820D3F8882022F4FF6222F00702B6 -:1032B000C3F88820D3F88820D3F8E0200A43C3F865 -:1032C000E020D3F808210A43C3F80821294AD3F89B -:1032D00008311146FFF7CCFF00F5806002F11C01B8 -:1032E000FFF7C6FF00F5806002F13801FFF7C0FF6D -:1032F00000F5806002F15401FFF7BAFF00F580602D -:1033000002F17001FFF7B4FF00F5806002F18C015B -:10331000FFF7AEFF00F5806002F1A801FFF7A8FFFC -:1033200000F5806002F1C401FFF7A2FF00F58060A4 -:1033300002F1E001FFF79CFF00F5806002F1FC0163 -:10334000FFF796FF02F58C7100F58060FFF790FFA4 -:1033500000F0F4F8084B0522C3F898204FF06052B3 -:10336000C3F89C20054AC3F8A02008BD00440258B9 -:10337000000002584C3B000800ED00E01F0008036D -:1033800008B500F0C9FAFEF715FB0F4BD3F8DC20A7 -:1033900042F04002C3F8DC20D3F8042122F04002BE -:1033A000C3F80421D3F80431084B1A6842F008022C -:1033B0001A601A6842F004021A60FEF757FFBDE86F -:1033C0000840FEF705BD00BF00440258001802483F -:1033D00070470000114BD3F8E82042F00802C3F810 -:1033E000E820D3F8102142F00802C3F810210C4A5B -:1033F000D3F81031D36B43F00803D363C722094BD2 -:103400009A624FF0FF32DA6200229A615A63DA6000 -:103410005A6001225A611A60704700BF0044025886 -:103420000010005C000C0040094A08B51169D3681F -:103430000B40D9B29B076FEA0101116107D5202328 -:1034400083F31188FEF7D6FA002383F3118808BDB1 -:10345000000C0040384B4FF0FF31D3F88020C3F808 -:103460008010D3F880200022C3F88020D3F8800099 -:10347000D3F88400C3F88410D3F88400C3F8842000 -:10348000D3F88400D86F40F0FF4040F4FF0040F4D0 -:103490003F5040F03F00D867D86F20F0FF4020F445 -:1034A000FF0020F43F5020F03F00D867D86FD3F8DA -:1034B00088006FEA40506FEA5050C3F88800D3F894 -:1034C0008800C0F30A00C3F88800D3F88800D3F856 -:1034D0009000C3F89010D3F89000C3F89020D3F870 -:1034E0009000D3F89400C3F89410D3F89400C3F874 -:1034F0009420D3F89400D3F89800C3F89810D3F828 -:103500009800C3F89820D3F89800D3F88C00C3F83B -:103510008C10D3F88C00C3F88C20D3F88C00D3F82F -:103520009C00C3F89C10D3F89C10C3F89C20D3F8DF -:103530009C3000F0C9B900BF00440258614B012221 -:10354000C3F80821604BD3F8F42042F00202C3F81C -:10355000F420D3F81C2142F00202C3F81C210222FD -:10356000D3F81C31594BDA605A689104FCD5584A9B -:103570001A6001229A60574ADA6000221A614FF4F9 -:1035800040429A61514B9A699204FCD51A6842F400 -:1035900080721A604C4B1A6F12F4407F04D04FF4C3 -:1035A00080321A6700221A671A6842F001021A6014 -:1035B000454B1A685007FCD500221A611A6912F0AF -:1035C0003802FBD1012119604FF0804159605A67E0 -:1035D000414ADA62414A1A611A6842F480321A603A -:1035E000394B1A689103FCD51A6842F480521A606C -:1035F0001A689204FCD53A4A3A499A6200225A6300 -:1036000019633949DA6399635A64384A1A64384A43 -:10361000DA621A6842F0A8521A602B4B1A6802F05C -:103620002852B2F1285FF9D148229A614FF488629A -:10363000DA6140221A622F4ADA644FF000521A65AA -:103640002D4A5A652D4A9A6532232D4A1360136814 -:1036500003F00F03022BFAD11B4B1A6942F003024D -:103660001A611A6902F03802182AFAD1D3F8DC205C -:1036700042F00052C3F8DC20D3F8042142F000529B -:10368000C3F80421D3F80421D3F8DC2042F08042AF -:10369000C3F8DC20D3F8042142F08042C3F80421AF -:1036A000D3F80421D3F8DC2042F00042C3F8DC2038 -:1036B000D3F8042142F00042C3F80421D3F80431C6 -:1036C000704700BF00800051004402580048025873 -:1036D00000C000F0020000010000FF010088900817 -:1036E00012102000630207012C02040047040508A1 -:1036F000FD0BFF01200000200010E0000001010090 -:10370000002000524FF0B04208B5D2F8883003F0E4 -:103710000103C2F8883023B1044A13680BB1506822 -:103720009847BDE80840FEF7EDBD00BFF841002016 -:103730004FF0B04208B5D2F8883003F00203C2F867 -:10374000883023B1044A93680BB1D0689847BDE82C -:103750000840FEF7D7BD00BFF84100204FF0B0424F -:1037600008B5D2F8883003F00403C2F8883023B1DA -:10377000044A13690BB150699847BDE80840FEF749 -:10378000C1BD00BFF84100204FF0B04208B5D2F8EB -:10379000883003F00803C2F8883023B1044A9369E3 -:1037A0000BB1D0699847BDE80840FEF7ABBD00BF3C -:1037B000F84100204FF0B04208B5D2F8883003F04D -:1037C0001003C2F8883023B1044A136A0BB1506A5F -:1037D0009847BDE80840FEF795BD00BFF8410020BE -:1037E0004FF0B04310B5D3F8884004F47872C3F8B2 -:1037F0008820A30604D5124A936A0BB1D06A984771 -:10380000600604D50E4A136B0BB1506B9847210626 -:1038100004D50B4A936B0BB1D06B9847E20504D5E6 -:10382000074A136C0BB1506C9847A30504D5044AA2 -:10383000936C0BB1D06C9847BDE81040FEF762BDA9 -:10384000F84100204FF0B04310B5D3F8884004F49D -:103850007C42C3F88820620504D5164A136D0BB16B -:10386000506D9847230504D5124A936D0BB1D06D66 -:103870009847E00404D50F4A136E0BB1506E984779 -:10388000A10404D50B4A936E0BB1D06E9847620425 -:1038900004D5084A136F0BB1506F9847230404D521 -:1038A000044A936F0BB1D06F9847BDE81040FEF704 -:1038B00029BD00BFF841002008B5FFF7B5FDBDE800 -:1038C0000840FEF71FBD0000062108B50846FFF7B7 -:1038D000D1FA06210720FFF7CDFA06210820FFF7CD -:1038E000C9FA06210920FFF7C5FA06210A20FFF7C9 -:1038F000C1FA06211720FFF7BDFA06212820FFF79D -:10390000B9FA09217A20FFF7B5FA07213220BDE87C -:103910000840FFF7AFBA000008B5FFF79BFD00F0C5 -:103920000BF8FDF701FDFDF7D3FBFFF751FDBDE8F7 -:103930000840FFF77FBC00000023054A1946013309 -:10394000102BC2E9001102F10802F8D1704700BF44 -:10395000F841002010B501390244904201D1002005 -:1039600005E0037811F8014FA34201D0181B10BDE8 -:103970000130F2E7034611F8012B03F8012B002A6E -:10398000F9D1704753544D333248373F3F3F0053CE -:10399000544D3332483734332F373533000000006D -:1039A000000000004D1000083910000875100008D4 -:1039B000611000086D10000859100008451000083B -:1039C0003110000881100008000000000100000014 -:1039D000000000006D61696E0000000069646C65A4 -:1039E00000000000DC390008F823002070250020CA -:1039F00001000000B1190008000000004172647568 -:103A000050696C6F740025424F415244252D424C41 -:103A1000002553455249414C25000000020000009A -:103A2000000000006D120008DD1200084000400098 -:103A3000183E0020283E0020020000000000000088 -:103A40000300000000000000251300080000000033 -:103A500010000000383E00200000000001000000BF -:103A600000000000A8400020010102006D1D0008B8 -:103A70007D1C0008191D0008FD1C00084300000003 -:103A8000843A000809024300020100C03209040020 -:103A900000010202010005240010010524010001BB -:103AA000042402020524060001070582030800FF22 -:103AB00009040100020A000000070501024000009D -:103AC000070581024000000012000000D03A000803 -:103AD00012011001020000400912415700020102C8 -:103AE000030100000403090425424F41524425000C -:103AF0004B616B75746548374D696E6900303132C2 -:103B000033343536373839414243444546000000A6 -:103B1000000000007914000831170008DD170008C4 -:103B200040004000E0410020E04100200100000092 -:103B3000F04100208000000040010000080000006B -:103B40000001000000040000080000000001802ABD -:103B500000000000AAAAAAAA00010024FFFF00009A -:103B60000000000000A00A0000004001000000006A -:103B7000AAAAAAAA00000001FFFF0000000000009E -:103B8000000000001000000400000000AAAAAAAA79 -:103B900000000008FBDF0000000000000000000043 -:103BA0000000000000000000AAAAAAAA000000006D -:103BB000FFFF000000000000000000000001000006 -:103BC00000000000AAAAAAAA00010000FFFF00004E -:103BD00000000000000000000000000000000000E5 -:103BE000AAAAAAAA00000000FFFF0000000000002F -:103BF000000000000000000000000000AAAAAAAA1D -:103C000000000000FFFF00000000000000000000B6 -:103C10000000000000000000AAAAAAAA00000000FC -:103C2000FFFF000000000000000000000000000096 -:103C300000000000AAAAAAAA00000000FFFF0000DE -:103C40000000000000000000000000000000000074 -:103C5000AAAAAAAA00000000FFFF000000000000BE -:103C6000000000000000000000000000AAAAAAAAAC -:103C700000000000FFFF0000000000000000000046 -:103C8000220400000000000000001A0000000000F4 -:103C9000FF00000000000000843900083F00000021 -:103CA000500400008F3900083F000000009600001B -:103CB000000008009600000000080000040000005A -:103CC000E43A0008000000000000000000000000CE -:0C3CD000000000000000000000000000E8 +:1019A000BDE81040FEF712BDB423002008B5FFF7D4 +:1019B000DDFF18B1BDE80840FFF7E4BF08BD000037 +:1019C000FFF7E0BFFEE7000010B50C4CFFF742FF49 +:1019D00000F0B4F880220A49204600F03BF80123C9 +:1019E00044F8180C037400F099FC002383F3118869 +:1019F00062B60448BDE8104000F04CB8DC2300207B +:101A0000543A0008643A000800F01CB9EFF3118062 +:101A100020B9EFF30583202282F31188704700007C +:101A200010B530B9EFF30584C4F3080414B180F3A2 +:101A3000118810BDFFF7BAFF84F31188F9E70000A1 +:101A4000034A516853685B1A9842FBD8704700BF3D +:101A5000001000E082600222028270478368A3F1D6 +:101A60007C0243F80C2C026943F83C2C426943F891 +:101A7000382C074A43F81C2CC268A3F1180043F81D +:101A8000102C022203F8082C002203F8072C7047C0 +:101A9000E503000810B5202383F31188FFF7DEFF6C +:101AA00000210446FFF746FF002383F311882046F8 +:101AB00010BD0000024B1B6958610F20FFF70EBFDD +:101AC000B4230020202383F31188FFF7F3BF000025 +:101AD00008B50146202383F311880820FFF70CFF87 +:101AE000002383F3118808BD49B1064B42681B6986 +:101AF00018605A60136043600420FFF7FDBE4FF08A +:101B0000FF307047B42300200368984206D01A685B +:101B10000260506018465961FFF7A4BE704700008C +:101B200038B504460D462068844200D138BD0368AC +:101B300023605C604561FFF795FEF4E7054B4FF0CD +:101B4000FF3103F11402C3E905220022C3E90712A1 +:101B5000704700BFB423002070B51C4E05460C46EC +:101B6000C0E9032301F0B2FB334653F8142F9A4225 +:101B70000DD130620A2C2CBF00190A302A60C5E949 +:101B80000124C6E90555BDE8704001F089BB316A02 +:101B9000431AE31838BF1C469368A34202D90819B8 +:101BA00001F08EFB73699A6894420CD85A68AC6055 +:101BB0002B606A6015609A685D60121B9A604FF036 +:101BC000FF33F36170BDA41A1B68ECE7B423002057 +:101BD00038B51B4C636998420DD08168D0E900325A +:101BE00013605A600022C2609A680A449A604FF0FB +:101BF000FF33E36138BD03682246002142F8143FF9 +:101C000093425A60C16003D1BDE8384001F052BB35 +:101C10009A688168256A0A449A6001F057FB6369F3 +:101C2000411B9A688A42E5D9AB181D1A206A092D12 +:101C300098BF01F10A02BDE83840104401F040BBF2 +:101C4000B42300202DE9F041184C002704F11406BC +:101C5000656901F03BFB236AAA68C11A8A4215D85C +:101C60001344D5F80C802362D5E9003213605A6022 +:101C70006369EF60B34201D101F01CFB87F3118867 +:101C80002869C047202383F31188E1E76169B142E5 +:101C900009D013441B1ABDE8F0410A2B2CBFC01811 +:101CA0000A3001F00DBBBDE8F08100BFB423002075 +:101CB00000207047FEE70000704700004FF0FF3043 +:101CC0007047000002290CD0032904D001290748DD +:101CD00018BF00207047032A05D8054800EBC20052 +:101CE0007047044870470020704700BF483B000819 +:101CF0003C220020FC3A000870B59AB00546084620 +:101D0000144601A900F0C2F801A8FFF785F8431CAA +:101D10000022C6B25B001046C5E9003423700323DD +:101D2000023404F8013C01ABD1B202348E4201D836 +:101D30001AB070BD13F8011B013204F8010C04F84D +:101D4000021CF1E708B5202383F311880348FFF74D +:101D500067FA002383F3118808BD00BF70250020B7 +:101D600090F8803003F01F02012A07D190F88120FB +:101D70000B2A03D10023C0E91D3315E003F06003F3 +:101D8000202B08D1B0F884302BB990F88120212A7B +:101D900003D81F2A04D8FFF725BA222AEBD0FAE786 +:101DA000034A426707228267C3670120704700BF6A +:101DB0003322002007B5052917D8DFE801F01916EE +:101DC00003191920202383F31188104A012101905F +:101DD000FFF7CEFA019802210D4AFFF7C9FA0D4824 +:101DE000FFF7EAF9002383F3118803B05DF804FBE1 +:101DF000202383F311880748FFF7B4F9F2E7202383 +:101E000083F311880348FFF7CBF9EBE79C3A00080E +:101E1000C03A00087025002038B50C4D0C4C2A46FD +:101E20000C4904F10800FFF767FF05F1CA0204F14D +:101E300010000949FFF760FF05F5CA7204F11800A8 +:101E40000649BDE83840FFF757BF00BF483E0020B5 +:101E50003C2200207C3A0008863A0008913A0008AB +:101E600070B5044608460D46FEF7D6FFC6B22046BA +:101E7000013403780BB9184670BD32462946FEF787 +:101E8000B7FF0028F3D10120F6E700002DE9F84F55 +:101E900005460C46FEF7C0FF2C49C6B22846FFF7A0 +:101EA000DFFF08B10536F6B229492846FFF7D8FF0B +:101EB00008B11036F6B2632E0DD8DFF89080DFF847 +:101EC0009090244FDFF894A0DFF894B02E7846B9B4 +:101ED0002670BDE8F88F29462046BDE8F84F01F08E +:101EE00089BD252E2ED1072241462846FEF780FFC8 +:101EF00070B9DBF8003007350C3444F80C3CDBF8E3 +:101F0000043044F8083CDBF8083044F8043CDDE7D2 +:101F1000082249462846FEF76BFF98B9A21C0E4BD3 +:101F2000197802320909C95D02F8041C13F8011B73 +:101F300001F00F015345C95D02F8031CF0D11834BC +:101F40000835C3E7013504F8016BBFE7683B0008BB +:101F5000913A00087D3B000800E8F11F0CE8F11FF2 +:101F6000703B0008BFF34F8F044B1A695107FCD137 +:101F7000D3F810215207F8D1704700BF002000525B +:101F800008B50D4B1B78ABB9FFF7ECFF0B4BDA68CC +:101F9000D10704D50A4A5A6002F188325A60D3F850 +:101FA0000C21D20706D5064AC3F8042102F1883273 +:101FB000C3F8042108BD00BFA64000200020005245 +:101FC0002301674508B5114B1B78F3B9104B1A690B +:101FD000510703D5DA6842F04002DA60D3F81021E5 +:101FE000520705D5D3F80C2142F04002C3F80C216A +:101FF000FFF7B8FF064BDA6842F00102DA60D3F867 +:102000000C2142F00102C3F80C2108BDA6400020BB +:10201000002000520F289ABF00F580604004002085 +:10202000704700004FF400307047000010207047E8 +:102030000F2808B50BD8FFF7EDFF00F50033026855 +:10204000013204D104308342F9D1012008BD0020BF +:10205000FCE700000F2870B5054645D8FFF7D6FC11 +:10206000224CFFF77FFF0646FFF78AFF4FF0FF3352 +:10207000072D6361C4F8143120D82361FFF772FF84 +:102080002B0243F02403E360E36843F08003E36042 +:1020900023695A07FCD42846FFF764FF4FF4003148 +:1020A000FFF7B8FF00F002F93046FFF78BFFFFF7AC +:1020B000B7FC2846BDE87040FFF7BABFC4F810313E +:1020C000FFF750FFA5F108031B0243F02403C4F8F7 +:1020D0000C31D4F80C3143F08003C4F80C31D4F83F +:1020E00010315B07FBD4D6E7002070BD0020005202 +:1020F0002DE9F84F40EA020305460C461746D8067C +:1021000002D00020BDE8F88F27F01F07DFF8D4B019 +:10211000FFF736FF2744BC4203D10120FFF752FFEF +:10212000F0E720222946204601F054FC10B9203562 +:102130002034F0E72B4605F120021E68711CE0D127 +:1021400004339A42F9D1FFF761FC05F17843234A41 +:10215000B3F5801F224B28BF9A4603F1040338BF12 +:102160009046A2F1080228BF9846A3F108033ABF9F +:102170009146DA469946FFF7F5FEC8F80060A5EBF0 +:10218000040CD9F8002004F11C0142F00202C9F845 +:102190000020221FDAF8006016F00506FAD152F886 +:1021A000043F8A424CF80230F4D1BFF34F8FFFF75F +:1021B000D9FE4FF0FF32C8F80020D9F8002022F0F5 +:1021C0000202C9F80020FFF72BFC202221462846F6 +:1021D00001F000FC0028AAD030469FE714200052EE +:1021E000102100521020005210B5084C237828B15D +:1021F0001BB9FFF7C5FE0123237010BD002BFCD0D7 +:102200002070BDE81040FFF7DDBE00BFA6400020F3 +:102210000244074BD2B210B5904200D110BD441C0D +:1022200000B253F8200041F8040BE0B2F4E700BF1D +:10223000504000580E4B30B51C6F240405D41C6F61 +:102240001C671C6F44F400441C670A4C024423685A +:10225000D2B243F480732360074B904200D130BD6B +:10226000441C51F8045B00B243F82050E0B2F4E79C +:1022700000440258004802585040005807B5012257 +:1022800001A90020FFF7C4FF019803B05DF804FB2B +:1022900013B50446FFF7F2FFA04205D0012201A9C1 +:1022A00000200194FFF7C6FF02B010BD0144BFF348 +:1022B0004F8F064B884204D3BFF34F8FBFF36F8F0E +:1022C0007047C3F85C022030F4E700BF00ED00E087 +:1022D000034B1A681AB9034AD2F8D0241A6070471F +:1022E000A84000200040025808B5FFF7F1FF024B5C +:1022F0001868C0F3806008BDA8400020EFF3098390 +:10230000054968334A6B22F001024A6383F3098866 +:10231000002383F31188704700EF00E0202080F352 +:10232000118862B60D4B0E4AD96821F4E0610904A8 +:10233000090C0A430B49DA60D3F8FC2042F08072A2 +:10234000C3F8FC20084AC2F8B01F116841F001012F +:1023500011601022DA7783F82200704700ED00E068 +:102360000003FA0555CEACC5001000E0202310B5DF +:1023700083F311880E4B5B6813F4006314D0F1EE05 +:10238000103AEFF309844FF08073683CE361094B26 +:10239000DB6B236684F30988FFF7E8FA10B1064B7C +:1023A000A36110BD054BFBE783F31188F9E700BF7C +:1023B00000ED00E000EF00E0F7030008FA0300087A +:1023C00070B5BFF34F8FBFF36F8F1A4A0021C2F869 +:1023D0005012BFF34F8FBFF36F8F536943F4003335 +:1023E0005361BFF34F8FBFF36F8FC2F88410BFF3F9 +:1023F0004F8FD2F8803043F6E074C3F3C900C3F3C3 +:102400004E335B0103EA0406014646EA8175013951 +:10241000C2F86052F9D2203B13F1200FF2D1BFF382 +:102420004F8F536943F480335361BFF34F8FBFF332 +:102430006F8F70BD00ED00E0FEE700000A4B0B4817 +:102440000B4A90420BD30B4BC11EDA1C121A22F01E +:1024500003028B4238BF00220021FEF7E5BC53F88F +:10246000041B40F8041BECE75C3D00087C420020A4 +:102470007C4200207C4200207047000070B5D0E90B +:10248000244300224FF0FF359E6804EB42135101B4 +:10249000D3F80009002805DAD3F8000940F080409D +:1024A000C3F80009D3F8000B002805DAD3F8000BB5 +:1024B00040F08040C3F8000B013263189642C3F825 +:1024C0000859C3F8085BE0D24FF00113C4F81C3878 +:1024D00070BD000000EB8103D3F80CC02DE9F04380 +:1024E000DCF814204E1CD0F89050D2F800E005EB38 +:1024F000063605EB4118506870450AD30122D5F81D +:10250000343802FA01F123EA0101C5F83418BDE8B4 +:10251000F083AEEB0003BCF81040A34228BF234673 +:10252000D8F81849A4B2B3EB840FF0D89468A4F19A +:10253000040959F8047F3760A4EB09071F44042FEE +:10254000F7D81C44034494605360D4E7890141F0F8 +:102550002001016103699B06FCD41220FFF770BAC9 +:1025600010B50A4C2046FEF7E1FE094BC4F8903046 +:10257000084BC4F89430084C2046FEF7D7FE074BB2 +:10258000C4F89030064BC4F8943010BDAC40002025 +:1025900000000840B43B000848410020000004400F +:1025A000C03B000870B503780546012B5DD1494B4F +:1025B000D0F89040984259D1474B0E216520D3F86E +:1025C000D82042F00062C3F8D820D3F8002142F0AE +:1025D0000062C3F80021D3F80021D3F8802042F034 +:1025E0000062C3F88020D3F8802022F00062C3F894 +:1025F0008020D3F8803000F071FC384BE360384B1A +:10260000C4F800380023D5F89060C4F8003EC02319 +:1026100023604FF40413A3633369002BFCDA012316 +:102620000C203361FFF70CFA3369DB07FCD412206E +:10263000FFF706FA3369002BFCDA00262846A6606D +:10264000FFF71CFF6B68C4F81068DB68C4F81468F7 +:10265000C4F81C68002B3AD1224BA3614FF0FF3322 +:102660006361A36843F00103A36070BD1E4B9842F1 +:10267000C8D1194B0E214D20D3F8D82042F000725A +:10268000C3F8D820D3F8002142F00072C3F800212B +:10269000D3F80021D3F8802042F00072C3F88020E4 +:1026A000D3F8802022F00072C3F88020D3F8802075 +:1026B000D3F8D82022F08062C3F8D820D3F80021C4 +:1026C00022F08062C3F80021D3F8003193E7074B72 +:1026D000C3E700BFAC400020004402584014004053 +:1026E00003002002003C30C048410020083C30C0BC +:1026F000F8B5D0F89040054600214FF0006620461E +:10270000FFF724FFD5F8941000234FF001128F68D3 +:102710004FF0FF30C4F83438C4F81C2804EB4312DF +:1027200001339F42C2F80069C2F8006BC2F8080981 +:10273000C2F8080BF2D20B68D5F89020C5F8983093 +:10274000636210231361166916F01006FBD1122084 +:10275000FFF776F9D4F8003823F4FE63C4F80038A4 +:10276000A36943F4402343F01003A3610923C4F891 +:102770001038C4F814380B4BEB604FF0C043C4F86A +:10278000103B094BC4F8003BC4F81069C4F8003989 +:10279000D5F8983003F1100243F48013C5F898205F +:1027A000A362F8BD903B000840800010D0F8902054 +:1027B00090F88A10D2F8003823F4FE6343EA01133C +:1027C000C2F80038704700002DE9F84300EB8103A0 +:1027D000D0F890500C468046DA680FFA81F948012B +:1027E000166806F00306731E022B05EB41134FF02B +:1027F000000194BFB604384EC3F8101B4FF001011E +:1028000004F1100398BF06F1805601FA03F39169B1 +:1028100098BF06F5004600293AD0578A04F15801BE +:10282000374349016F50D5F81C180B430021C5F8F8 +:102830001C382B180127C3F81019A7405369611ED3 +:102840009BB3138A928B9B08012A88BF5343D8F805 +:102850009820981842EA034301F140022146C8F843 +:102860009800284605EB82025360FFF76FFE08EBE5 +:102870008900C3681B8A43EA845348341E436401B9 +:102880002E51D5F81C381F43C5F81C78BDE8F883D5 +:1028900005EB4917D7F8001B21F40041C7F8001BCE +:1028A000D5F81C1821EA0303C0E704F13F030B4AE3 +:1028B0002846214605EB83035A60FFF747FE05EBE8 +:1028C0004910D0F8003923F40043C0F80039D5F896 +:1028D0001C3823EA0707D7E7008000100004000235 +:1028E000D0F894201268C0F89820FFF7C7BD000008 +:1028F0005831D0F8903049015B5813F4004004D0AF +:1029000013F4001F0CBF0220012070474831D0F89B +:10291000903049015B5813F4004004D013F4001FB9 +:102920000CBF02200120704700EB8101CB68196ABF +:102930000B6813604B6853607047000000EB810325 +:1029400030B5DD68AA691368D36019B9402B84BF1C +:10295000402313606B8A1468D0F890201C4402EB6B +:102960004110013C09B2B4FBF3F46343033323F099 +:10297000030343EAC44343F0C043C0F8103B2B6851 +:1029800003F00303012B0ED1D2F8083802EB4110FB +:1029900013F4807FD0F8003B14BF43F0805343F022 +:1029A0000053C0F8003B02EB4112D2F8003B43F069 +:1029B0000443C2F8003B30BD2DE9F041D0F89060EF +:1029C00005460C4606EB4113D3F8087B3A07C3F8DB +:1029D000087B08D5D6F814381B0704D500EB810313 +:1029E000DB685B689847FA071FD5D6F81438DB0711 +:1029F0001BD505EB8403D968CCB98B69488A5A6822 +:102A0000B2FBF0F600FB16228AB91868DA68904229 +:102A10000DD2121AC3E90024202383F31188214622 +:102A20002846FFF78BFF84F31188BDE8F08101236E +:102A300003FA04F26B8923EA02036B81CB68002B53 +:102A4000F3D021462846BDE8F041184700EB81034A +:102A50004A0170B5DD68D0F890306C692668E66090 +:102A600056BB1A444FF40020C2F810092A6802F03D +:102A70000302012A0AB20ED1D3F8080803EB42146C +:102A800010F4807FD4F8000914BF40F0805040F06B +:102A90000050C4F8000903EB4212D2F8000940F0DC +:102AA0000440C2F800090122D3F8340802FA01F107 +:102AB0000143C3F8341870BD19B9402E84BF4020BB +:102AC000206020681A442E8A8419013CB4FBF6F475 +:102AD00040EAC44040F00050C6E700002DE9F04154 +:102AE000D0F8906004460D4606EB4113D3F8087900 +:102AF000C3F80879FB071CD5D6F81038DA0718D5C3 +:102B000000EB8103D3F80CC0DCF81430D3F800E0FC +:102B1000DA6896451BD2A2EB0E024FF000081A604D +:102B2000C3F80480202383F31188FFF78FFF88F315 +:102B300011883B0618D50123D6F83428AB40134240 +:102B400012D029462046BDE8F041FFF7C3BC01235F +:102B500003FA01F2038923EA02030381DCF8083057 +:102B6000002BE6D09847E4E7BDE8F0812DE9F84F67 +:102B7000D0F8905004466E69AB691E4016F4805838 +:102B80006E6103D0BDE8F84FFEF740BC002E12DAAC +:102B9000D5F8003E9F0705D0D5F8003E23F003038B +:102BA000C5F8003ED5F80438204623F00103C5F8E7 +:102BB0000438FEF757FC300505D52046FFF75EFCCC +:102BC0002046FEF73FFCB1040CD5D5F8083813F0C9 +:102BD000060FEB6823F470530CBF43F4105343F417 +:102BE000A053EB60320704D56368DB680BB1204665 +:102BF0009847F30200F1BA80B70226D5D4F8909036 +:102C000000274FF0010A09EB4712D2F8003B03F40A +:102C10004023B3F5802F11D1D2F8003B002B0DDA01 +:102C200062890AFA07F322EA0303638104EB87034C +:102C3000DB68DB6813B13946204698470137D4F882 +:102C40009430FFB29B689F42DDD9F00619D5D4F8C5 +:102C50009000026AC2F30A1702F00F0302F4F012A6 +:102C6000B2F5802F00F0CC80B2F5402F09D104EBF3 +:102C70008303002200F58050DB681B6A974240F016 +:102C8000B2803003D5F8185835D5E90303D50021B3 +:102C90002046FFF791FEAA0303D501212046FFF746 +:102CA0008BFE6B0303D502212046FFF785FE2F0321 +:102CB00003D503212046FFF77FFEE80203D5042158 +:102CC0002046FFF779FEA90203D505212046FFF72C +:102CD00073FE6A0203D506212046FFF76DFE2B0224 +:102CE00003D507212046FFF767FEEF0103D5082132 +:102CF0002046FFF761FE700340F1A980E90703D584 +:102D000000212046FFF7EAFEAA0703D5012120464D +:102D1000FFF7E4FE6B0703D502212046FFF7DEFE36 +:102D20002F0703D503212046FFF7D8FEEE0603D573 +:102D300004212046FFF7D2FEA80603D50521204630 +:102D4000FFF7CCFE690603D506212046FFF7C6FE35 +:102D50002A0603D507212046FFF7C0FEEB0576D5EE +:102D600020460821BDE8F84FFFF7B8BED4F8909090 +:102D700000274FF0010AD4F894305FFA87FB9B6874 +:102D80009B453FF639AF09EB4B13D3F8002902F40A +:102D90004022B2F5802F24D1D3F80029002A20DA6E +:102DA000D3F8002942F09042C3F80029D3F8002953 +:102DB000002AFBDB5946D4F89000FFF7C7FB2289B5 +:102DC0000AFA0BF322EA0303238104EB8B03DB688B +:102DD0009B6813B159462046984759462046FFF74D +:102DE00079FB0137C7E7910701D1D0F80080072AA6 +:102DF00002F101029CBF03F8018B4FEA18283DE75E +:102E000004EB830300F58050DA68D2F818C0DCF8D0 +:102E10000820DCE9001CA1EB0C0C00218F4208D13A +:102E2000DB689B699A683A449A605A683A445A60E7 +:102E300027E711F0030F01D1D0F800808C4501F194 +:102E4000010184BF02F8018B4FEA1828E6E7BDE8CC +:102E5000F88F000008B50348FFF788FEBDE808407A +:102E6000FFF784BAAC40002008B50348FFF77EFEA8 +:102E7000BDE80840FFF77ABA48410020D0F890300A +:102E800003EB4111D1F8003B43F40013C1F8003BC0 +:102E900070470000D0F8903003EB4111D1F80039B1 +:102EA00043F40013C1F8003970470000D0F89030A7 +:102EB00003EB4111D1F8003B23F40013C1F8003BB0 +:102EC00070470000D0F8903003EB4111D1F8003981 +:102ED00023F40013C1F8003970470000090100F124 +:102EE0006043012203F56143C9B283F8001300F087 +:102EF0001F039A4043099B0003F1604303F56143BC +:102F0000C3F880211A60704730B50433039C017206 +:102F1000002104FB0325C160C0E90653049B036341 +:102F2000059BC0E90000C0E90422C0E90842C0E9ED +:102F30000A11436330BD00000022416AC260C0E94B +:102F40000411C0E90A226FF00101FEF7E9BD00009B +:102F5000D0E90432934201D1C2680AB9181D704702 +:102F600000207047036919600021C2680132C26005 +:102F7000C269134482699342036124BF436A0361B7 +:102F8000FEF7C2BD38B504460D46E3683BB1626941 +:102F90000020131D1268A3621344E36207E0237A42 +:102FA00033B929462046FEF79FFD0028EDDA38BDEB +:102FB0006FF00100FBE70000C368C269013BC3601A +:102FC0004369134482699342436124BF436A436166 +:102FD00000238362036B03B11847704770B5202349 +:102FE000044683F31188866A3EB9FFF7CBFF054696 +:102FF00018B186F31188284670BDA36AE26A13F8F7 +:10300000015B9342A36202D32046FFF7D5FF002362 +:1030100083F31188EFE700002DE9F84F04460E46D0 +:10302000174698464FF0200989F311880025AA46D3 +:10303000D4F828B0BBF1000F09D141462046FFF774 +:10304000A1FF20B18BF311882846BDE8F88FD4E9A1 +:103050000A12A7EB050B521A934528BF9346BBF102 +:10306000400F1BD9334601F1400251F8040B914245 +:1030700043F8040BF9D1A36A403640354033A362CC +:10308000D4E90A239A4202D32046FFF795FF8AF338 +:103090001188BD42D8D289F31188C9E730465A4613 +:1030A000FDF79CFEA36A5E445D445B44A362E7E7D0 +:1030B00010B5029C0433017204FB0321C460C0E913 +:1030C00006130023C0E90A33039B0363049BC0E992 +:1030D0000000C0E90422C0E90842436310BD0000BB +:1030E000026A6FF00101C260426AC0E90422002254 +:1030F000C0E90A22FEF714BDD0E904239A4201D1A7 +:10310000C26822B9184650F8043B0B607047002093 +:1031100070470000C3680021C2690133C36043697E +:10312000134482699342436124BF436A4361FEF7BB +:10313000EBBC000038B504460D46E3683BB123699B +:1031400000201A1DA262E2691344E36207E0237AB9 +:1031500033B929462046FEF7C7FC0028EDDA38BD12 +:103160006FF00100FBE7000003691960C268013AD3 +:10317000C260C269134482699342036124BF436AF7 +:10318000036100238362036B03B11847704700009B +:1031900070B520230D460446114683F31188866AD4 +:1031A0002EB9FFF7C7FF10B186F3118870BDA36A6F +:1031B0001D70A36AE26A01339342A36204D3E169FA +:1031C00020460439FFF7D0FF002080F31188EDE797 +:1031D0002DE9F84F04460D46904699464FF0200AD7 +:1031E0008AF311880026B346A76A4FB9494620469C +:1031F000FFF7A0FF20B187F311883046BDE8F88FB4 +:10320000D4E90A073A1AA8EB0607974228BF1746DF +:10321000402F1BD905F1400355F8042B9D4240F87F +:10322000042BF9D1A36A40364033A362D4E90A23C0 +:103230009A4204D3E16920460439FFF795FF8BF3E6 +:1032400011884645D9D28AF31188CDE729463A46F6 +:10325000FDF7C4FDA36A3D443E443B44A362E5E759 +:10326000D0E904239A4217D1C3689BB1836A8BB11A +:10327000043B9B1A0ED01360C368013BC360C36953 +:103280001A4483699A42026124BF436A036100239E +:1032900083620123184670470023FBE700F0DAB889 +:1032A000034B002258631A610222DA60704700BFA4 +:1032B000000C0040014B0022DA607047000C004017 +:1032C000014B5863704700BF000C0040014B586A27 +:1032D000704700BF000C00404B6843608B68836000 +:1032E000CB68C3600B6943614B6903628B694362BE +:1032F0000B6803607047000008B53C4B40F2FF715B +:103300003B48D3F888200A43C3F88820D3F88820A4 +:1033100022F4FF6222F00702C3F88820D3F8882045 +:10332000D3F8E0200A43C3F8E020D3F808210A4389 +:10333000C3F808212F4AD3F808311146FFF7CCFF14 +:1033400000F5806002F11C01FFF7C6FF00F5806008 +:1033500002F13801FFF7C0FF00F5806002F154016F +:10336000FFF7BAFF00F5806002F17001FFF7B4FFCC +:1033700000F5806002F18C01FFF7AEFF00F5806080 +:1033800002F1A801FFF7A8FF00F5806002F1C40177 +:10339000FFF7A2FF00F5806002F1E001FFF79CFF5C +:1033A00000F5806002F1FC01FFF796FF02F58C71D9 +:1033B00000F58060FFF790FF00F000F90E4BD3F8A6 +:1033C000902242F00102C3F89022D3F8942242F0F6 +:1033D0000102C3F894220522C3F898204FF06052EE +:1033E000C3F89C20054AC3F8A02008BD0044025839 +:1033F00000000258CC3B000800ED00E01F0008036D +:1034000008B500F0C9FAFEF7DFFA0F4BD3F8DC205D +:1034100042F04002C3F8DC20D3F8042122F040023D +:10342000C3F80421D3F80431084B1A6842F00802AB +:103430001A601A6842F004021A60FEF749FFBDE8FC +:103440000840FEF7E9BC00BF0044025800180248DB +:1034500070470000114BD3F8E82042F00802C3F88F +:10346000E820D3F8102142F00802C3F810210C4ADA +:10347000D3F81031D36B43F00803D363C722094B51 +:103480009A624FF0FF32DA6200229A615A63DA6080 +:103490005A6001225A611A60704700BF0044025806 +:1034A0000010005C000C0040094A08B51169D3689F +:1034B0000B40D9B29B076FEA0101116107D52023A8 +:1034C00083F31188FEF7A0FA002383F3118808BD67 +:1034D000000C0040384B4FF0FF31D3F88020C3F888 +:1034E0008010D3F880200022C3F88020D3F8800019 +:1034F000D3F88400C3F88410D3F88400C3F8842080 +:10350000D3F88400D86F40F0FF4040F4FF0040F44F +:103510003F5040F03F00D867D86F20F0FF4020F4C4 +:10352000FF0020F43F5020F03F00D867D86FD3F859 +:1035300088006FEA40506FEA5050C3F88800D3F813 +:103540008800C0F30A00C3F88800D3F88800D3F8D5 +:103550009000C3F89010D3F89000C3F89020D3F8EF +:103560009000D3F89400C3F89410D3F89400C3F8F3 +:103570009420D3F89400D3F89800C3F89810D3F8A7 +:103580009800C3F89820D3F89800D3F88C00C3F8BB +:103590008C10D3F88C00C3F88C20D3F88C00D3F8AF +:1035A0009C00C3F89C10D3F89C10C3F89C20D3F85F +:1035B0009C3000F0C9B900BF00440258614B0122A1 +:1035C000C3F80821604BD3F8F42042F00202C3F89C +:1035D000F420D3F81C2142F00202C3F81C2102227D +:1035E000D3F81C31594BDA605A689104FCD5584A1B +:1035F0001A6001229A60574ADA6000221A614FF479 +:1036000040429A61514B9A699204FCD51A6842F47F +:1036100080721A604C4B1A6F12F4407F04D04FF442 +:1036200080321A6700221A671A6842F001021A6093 +:10363000454B1A685007FCD500221A611A6912F02E +:103640003802FBD1012119604FF0804159605A675F +:10365000414ADA62414A1A611A6842F480321A60B9 +:10366000394B1A689103FCD51A6842F480521A60EB +:103670001A689204FCD53A4A3A499A6200225A637F +:1036800019633949DA6399635A64384A1A64384AC3 +:10369000DA621A6842F0A8521A602B4B1A6802F0DC +:1036A0002852B2F1285FF9D148229A614FF488621A +:1036B000DA6140221A622F4ADA644FF080521A65AA +:1036C0002D4A5A652D4A9A6532232D4A1360136894 +:1036D00003F00F03022BFAD11B4B1A6942F00302CD +:1036E0001A611A6902F03802182AFAD1D3F8DC20DC +:1036F00042F00052C3F8DC20D3F8042142F000521B +:10370000C3F80421D3F80421D3F8DC2042F080422E +:10371000C3F8DC20D3F8042142F08042C3F804212E +:10372000D3F80421D3F8DC2042F00042C3F8DC20B7 +:10373000D3F8042142F00042C3F80421D3F8043145 +:10374000704700BF008000510044025800480258F2 +:1037500000C000F0020000010000FF010088900896 +:1037600012102000630209012C020400470405081E +:10377000FD0BFF01200000200010E000000101000F +:10378000002000524FF0B04208B5D2F8883003F064 +:103790000103C2F8883023B1044A13680BB15068A2 +:1037A0009847BDE80840FEF7E1BD00BFFC4100209E +:1037B0004FF0B04208B5D2F8883003F00203C2F8E7 +:1037C000883023B1044A93680BB1D0689847BDE8AC +:1037D0000840FEF7CBBD00BFFC4100204FF0B042D7 +:1037E00008B5D2F8883003F00403C2F8883023B15A +:1037F000044A13690BB150699847BDE80840FEF7C9 +:10380000B5BD00BFFC4100204FF0B04208B5D2F872 +:10381000883003F00803C2F8883023B1044A936962 +:103820000BB1D0699847BDE80840FEF79FBD00BFC7 +:10383000FC4100204FF0B04208B5D2F8883003F0C8 +:103840001003C2F8883023B1044A136A0BB1506ADE +:103850009847BDE80840FEF789BD00BFFC41002045 +:103860004FF0B04310B5D3F8884004F47872C3F831 +:103870008820A30604D5124A936A0BB1D06A9847F0 +:10388000600604D50E4A136B0BB1506B98472106A6 +:1038900004D50B4A936B0BB1D06B9847E20504D566 +:1038A000074A136C0BB1506C9847A30504D5044A22 +:1038B000936C0BB1D06C9847BDE81040FEF756BD35 +:1038C000FC4100204FF0B04310B5D3F8884004F419 +:1038D0007C42C3F88820620504D5164A136D0BB1EB +:1038E000506D9847230504D5124A936D0BB1D06DE6 +:1038F0009847E00404D50F4A136E0BB1506E9847F9 +:10390000A10404D50B4A936E0BB1D06E98476204A4 +:1039100004D5084A136F0BB1506F9847230404D5A0 +:10392000044A936F0BB1D06F9847BDE81040FEF783 +:103930001DBD00BFFC41002008B5FFF7B5FDBDE887 +:103940000840FEF713BD0000062108B50846FFF742 +:10395000C5FA06210720FFF7C1FA06210820FFF764 +:10396000BDFA06210920FFF7B9FA06210A20FFF760 +:10397000B5FA06211720FFF7B1FA06212820FFF734 +:10398000ADFA09217A20FFF7A9FA07213220BDE814 +:103990000840FFF7A3BA000008B5FFF79BFD00F051 +:1039A0000BF8FDF7C1FCFDF793FBFFF751FDBDE8F8 +:1039B0000840FFF773BC00000023054A1946013395 +:1039C000102BC2E9001102F10802F8D1704700BFC4 +:1039D000FC41002010B501390244904201D1002081 +:1039E00005E0037811F8014FA34201D0181B10BD68 +:1039F0000130F2E7034611F8012B03F8012B002AEE +:103A0000F9D1704753544D333248373F3F3F00534D +:103A1000544D3332483734332F37353300000000EC +:103A2000000000004D100008391000087510000853 +:103A3000611000086D1000085910000845100008BA +:103A40003110000881100008000000000100000093 +:103A5000000000006D61696E0000000069646C6523 +:103A6000000000005C3A0008F823002070250020C8 +:103A700001000000C51900080000000041726475D3 +:103A800050696C6F740025424F415244252D424CC1 +:103A9000002553455249414C25000000020000001A +:103AA000000000006D120008DD1200084000400018 +:103AB000183E0020283E0020020000000000000008 +:103AC00003000000000000002513000800000000B3 +:103AD00010000000383E002000000000010000003F +:103AE00000000000AC40002001010200B51D0008EC +:103AF000C51C0008611D0008451D000843000000AA +:103B0000043B000809024300020100C0320904001E +:103B1000000102020100052400100105240100013A +:103B2000042402020524060001070582030800FFA1 +:103B300009040100020A000000070501024000001C +:103B4000070581024000000012000000503B000801 +:103B50001201100102000040091241570002010247 +:103B6000030100000403090425424F41524425008B +:103B70004B616B75746548374D696E690030313241 +:103B80003334353637383941424344454600000026 +:103B9000000000007914000831170008DD17000844 +:103BA00040004000E4410020E4410020010000000A +:103BB000F4410020800000004001000008000000E7 +:103BC0000001000000040000080000000001802A3D +:103BD00000000000AAAAAAAA00010024FFFF00001A +:103BE0000000000000A00A000000400100000000EA +:103BF000AAAAAAAA00000001FFFF0000000000001E +:103C0000000000001000000400000000AAAAAAAAF8 +:103C100000000008FBDF00000000000000000000C2 +:103C20000000000000000000AAAAAAAA00000000EC +:103C3000FFFF000000000000000000000001000085 +:103C400000000000AAAAAAAA00010000FFFF0000CD +:103C50000000000000000000000000000000000064 +:103C6000AAAAAAAA00000000FFFF000000000000AE +:103C7000000000000000000000000000AAAAAAAA9C +:103C800000000000FFFF0000000000000000000036 +:103C90000000000000000000AAAAAAAA000000007C +:103CA000FFFF000000000000000000000000000016 +:103CB00000000000AAAAAAAA00000000FFFF00005E +:103CC00000000000000000000000000000000000F4 +:103CD000AAAAAAAA00000000FFFF0000000000003E +:103CE000000000000000000000000000AAAAAAAA2C +:103CF00000000000FFFF00000000000000000000C6 +:103D0000220400000000000000001A000000000073 +:103D1000FF00000000000000043A00083F0000001F +:103D2000500400000F3A00083F0000000096000019 +:103D300000000800960000000008000004000000D9 +:103D4000643B0008000000000000000000000000CC +:0C3D500000000000000000000000000067 :00000001FF diff --git a/Tools/bootloaders/KakuteH7_bl.bin b/Tools/bootloaders/KakuteH7_bl.bin index d8990443aee..76bfbfd5e8b 100755 Binary files a/Tools/bootloaders/KakuteH7_bl.bin and b/Tools/bootloaders/KakuteH7_bl.bin differ diff --git a/Tools/bootloaders/KakuteH7_bl.elf b/Tools/bootloaders/KakuteH7_bl.elf index 4aafa57b3f4..1edde52f158 100755 Binary files a/Tools/bootloaders/KakuteH7_bl.elf and b/Tools/bootloaders/KakuteH7_bl.elf differ diff --git a/Tools/bootloaders/KakuteH7_bl.hex b/Tools/bootloaders/KakuteH7_bl.hex index 86465a9a7a7..b5820559412 100644 --- a/Tools/bootloaders/KakuteH7_bl.hex +++ b/Tools/bootloaders/KakuteH7_bl.hex @@ -1,34 +1,34 @@ :020000040800F2 -:1000000000060020A10200082D0F0008310F000893 -:10001000890F0008310F00085D0F0008A3020008D7 -:10002000A3020008A3020008A30200088D22000812 +:1000000000060020A1020008AD0F00082D0F000817 +:10001000850F00082D0F0008590F0008A3020008E3 +:10002000A3020008A3020008A3020008F5220008AA :10003000A3020008A3020008A3020008A30200080C :10004000A3020008A3020008A3020008A3020008FC -:10005000A3020008A3020008C5360008F136000814 -:100060001D3700084937000875370008A30200084B +:10005000A3020008A30200087D370008A9370008A2 +:10006000D5370008013800082D380008A302000821 :10007000A3020008A3020008A3020008A3020008CC :10008000A3020008A3020008A3020008A3020008BC -:10009000A3020008A3020008A3020008A137000879 +:10009000A3020008A3020008A302000859380008C0 :1000A000A3020008A3020008A3020008A30200089C :1000B000A3020008A3020008A3020008A30200088C :1000C000A3020008A3020008A3020008A30200087C :1000D000A3020008A3020008A3020008A30200086C -:1000E00005380008A3020008A3020008A3020008C4 +:1000E000BD380008A3020008A3020008A30200080C :1000F000A3020008A3020008A3020008A30200084C -:10010000A3020008A302000879380008A30200082F +:10010000A3020008A302000831390008A302000876 :10011000A3020008A3020008A3020008A30200082B :10012000A3020008A3020008A3020008A30200081B :10013000A3020008A3020008A3020008A30200080B :10014000A3020008A3020008A3020008A3020008FB :10015000A3020008A3020008A3020008A3020008EB :10016000A3020008A3020008A3020008A3020008DB -:10017000A3020008F92D0008A3020008A30200084A +:10017000A3020008612E0008A3020008A3020008E1 :10018000A3020008A3020008A3020008A3020008BB :10019000A3020008A3020008A3020008A3020008AB :1001A000A3020008A3020008A3020008A30200089B :1001B000A3020008A3020008A3020008A30200088B :1001C000A3020008A3020008A3020008A30200087B -:1001D000A3020008E52D0008A3020008A3020008FE +:1001D000A30200084D2E0008A3020008A302000895 :1001E000A3020008A3020008A3020008A30200085B :1001F000A3020008A3020008A3020008A30200084B :10020000A3020008A3020008A3020008A30200083A @@ -48,33 +48,33 @@ :1002E000C0F2F0004EF68851CEF200010860BFF374 :1002F0004F8FBFF36F8F4FF00000E1EE100A4EF604 :100300003C71CEF200010860062080F31488BFF330 -:100310006F8F02F079F802F01BF802F0B5FF4FF092 +:100310006F8F02F0ADF802F04FF802F0E9FF4FF0F6 :1003200055301F491B4A91423CBF41F8040BFAE784 :100330001C49194A91423CBF41F8040BFAE71A499B :100340001A4A1B4B9A423EBF51F8040B42F8040B69 :10035000F8E700201749184A91423CBF41F8040BC6 -:10036000FAE702F033F803F007F8144C144DAC42EE +:10036000FAE702F067F803F047F8144C144DAC427A :1003700003DA54F8041B8847F9E700F041F8114C00 :10038000114DAC4203DA54F8041B8847F9E702F038 -:100390001BB800000006002000220020000000081A -:1003A0000000002000060020403C00080022002041 -:1003B0005C2200206022002078420020A002000879 +:100390004FB80000000600200022002000000008E6 +:1003A0000000002000060020F83C00080022002089 +:1003B0005C220020602200207C420020A002000875 :1003C000A0020008A0020008A00200082DE9F04FDA :1003D0002DED108AC1F80CD0D0F80CD0BDEC108AED :1003E000BDE8F08F002383F311882846A047002042 -:1003F00001F044FBFEE701F0D9FA00DFFEE7000060 +:1003F00001F068FBFEE701F0E3FA00DFFEE7000032 :1004000038B500F0CDFC30B1164B00220E211A7227 -:100410005A729972DA7201F0FBFE054601F030FF64 +:100410005A729972DA7201F02DFF054601F060FF01 :100420000446D0B9104B9D4219D001339D4241F290 -:10043000883512BF044600250124002001F0F2FE99 +:10043000883512BF044600250124002001F024FF66 :100440000CB100F059F800F045FD00F0E3FB284640 :1004500000F004F900F050F8F9E70025EDE7054653 :10046000EBE700BF00220020010007B008B500F054 :10047000A3FBA0F120035842584108BD07B541F243 :100480001203022101A8ADF8043000F0B3FB03B061 :100490005DF804FB202310B583F311881248C3686C -:1004A0000BB101F071FB0023104A4FF47A710E4832 -:1004B00001F02EFB002383F311880D4C236813B148 +:1004A0000BB101F095FB0023104A4FF47A710E480E +:1004B00001F052FB002383F311880D4C236813B124 :1004C0002368013B2360636813B16368013B636089 :1004D000084B1B7833B9636823B9022000F074FC21 :1004E0003223636010BD00BF602200209504000825 @@ -103,8 +103,8 @@ :10065000742200200044025800ED00E02DE9F04F24 :1006600093B0A94B2022FF2100900AA89D6800F0BA :10067000DBFBA64A1378A3B90121A5481170C3601A -:10068000202383F31188C3680BB101F07DFA0023A6 -:10069000A04A4FF47A719E4801F03AFA002383F39E +:10068000202383F31188C3680BB101F0A1FA002382 +:10069000A04A4FF47A719E4801F05EFA002383F37A :1006A0001188009B9C4A03B1136000239B49009C66 :1006B00098469B461E469A460B705360012000F0F8 :1006C00079FB24B1944B1B68002B00F016820020AC @@ -174,35 +174,35 @@ :100AC000FFF7D4FC00283FF447AE00F005F90028FA :100AD00044D00A9B01330BD008220AA9002000F061 :100AE000ABF900283AD02022FF210AA800F09CF997 -:100AF000FFF7C4FC1C4800F0C7FF13B0BDE8F08F3F +:100AF000FFF7C4FC1C4800F0EBFF13B0BDE8F08F1B :100B0000002E3FF429AE0BF00B030B2B7FF424AE29 :100B10000023642105A8059300F062F80746002829 :100B20007FF41AAE0220FFF7A1FC814600283FF4B3 -:100B300013AEFFF7A3FC41F2883000F0A5FF059843 +:100B300013AEFFF7A3FC41F2883000F0C9FF05981F :100B400000F0F2F94E463C4600F0BAF9B6E506462A :100B50004CE64FF0000AFFE5B8467BE6374679E6FB :100B60007822002000220020A08601000F4B70B5E3 :100B70001B780C460133DBB2012B11D80C4D4FF41E :100B80007A732968A2FB033222460E6A0146284680 :100B9000B047844204D1074B002201201A7070BD77 -:100BA0004FF4FA7000F070FF0020F8E710220020E8 +:100BA0004FF4FA7000F094FF0020F8E710220020C4 :100BB00070250020B0230020002307B50246012144 :100BC0000DF107008DF80730FFF7D0FF20B19DF839 :100BD000070003B05DF804FB4FF0FF30F9E70000B9 :100BE0000A46042108B5FFF7C1FF80F00100C0B23A :100BF000404208BD30B4054C0A46014623682046F1 :100C0000DD69034BAC4630BC604700BF7025002057 -:100C1000A086010070B5104C0025104E01F0DEF9E1 +:100C1000A086010070B5104C0025104E01F002FABC :100C200020803068238883420CD800252088013832 -:100C300001F0D0F923880544013BB5F5802F2380CE -:100C4000F4D370BD01F0C6F9336805440133B5F53E +:100C300001F0F4F923880544013BB5F5802F2380AA +:100C4000F4D370BD01F0EAF9336805440133B5F51A :100C5000003F3360E5D3E8E7B2230020842300207F -:100C600001F08CBA00F1006000F5003000687047B8 -:100C700000F10060920000F5003001F00BBA0000B6 +:100C600001F0BEBA00F1006000F500300068704786 +:100C700000F10060920000F5003001F035BA00008C :100C8000054B1A68054B1B889B1A834202D91044F6 -:100C900001F0A0B90020704784230020B223002077 -:100CA00038B5074D04462868204401F099F928B961 -:100CB00028682044BDE8384001F0A4B938BD00BF21 +:100C900001F0C4B90020704784230020B223002053 +:100CA00038B5074D04462868204401F0BDF928B93D +:100CB00028682044BDE8384001F0C8B938BD00BFFD :100CC000842300200020704700F1FF5000F58F10B2 :100CD000D0F8000870470000064991F8243033B17D :100CE00000230822086A81F82430FFF7C1BF0120E1 @@ -238,52 +238,52 @@ :100EC000024B1A78024B1A70704700BFB023002003 :100ED0001022002010B5104C104800F0FBF82146FD :100EE0000E4800F023F924680D48D4F89020D2F879 -:100EF000043843F00203C2F8043800F0C5FD094984 +:100EF000043843F00203C2F8043800F0E9FD094960 :100F0000204600F021FAD4F89020D2F8043823F0DB -:100F10000203C2F8043810BD243A000870250020EE -:100F200040420F002C3A000870470000FEE7000026 -:100F300000B59BB0EFF3098168226846FFF74EFFCA -:100F4000EFF30583044B9A6BDA6A9A6A9A6A9A6A93 -:100F50009A6A9A6A9B6AFEE700ED00E000B59BB0D2 -:100F6000EFF3098168226846FFF738FFEFF3058346 -:100F7000044B9A6B9A6A9A6A9A6A9A6A9A6A9B6A04 -:100F8000FEE700BF00ED00E000B59BB0EFF3098184 -:100F900068226846FFF722FFEFF30583034B5A6B85 -:100FA0009A6A9A6A9A6A9A6A9B6AFEE700ED00E07A +:100F10000203C2F8043810BDDC3A00087025002036 +:100F200040420F00E43A00087047000000B59BB053 +:100F3000EFF3098168226846FFF750FFEFF305835E +:100F4000044B9A6BDA6A9A6A9A6A9A6A9A6A9A6AF5 +:100F50009B6AFEE700ED00E000B59BB0EFF309816E +:100F600068226846FFF73AFFEFF30583044B9A6B5C +:100F70009A6A9A6A9A6A9A6A9A6A9B6AFEE700BFB4 +:100F800000ED00E000B59BB0EFF3098168226846F0 +:100F9000FFF724FFEFF30583034B5A6B9A6A9A6AB3 +:100FA0009A6A9A6A9B6AFEE700ED00E0FEE700009D :100FB00030B50A44084D91420DD011F8013B58401C :100FC000082340F30004013B2C4013F0FF0384EAA4 :100FD0005000F6D1EFE730BD2083B8ED02684368DA :100FE0001143016003B118477047000013B5406B0F :100FF00000F58054D4F8A4381A681178042914D163 :10100000017C022911D11979012312898B401342E5 -:101010000BD101A94C3002F037F8D4F8A4480246AD +:101010000BD101A94C3002F06BF8D4F8A448024679 :10102000019B2179206800F0DFF902B010BD0000BB -:10103000143001F0B9BF00004FF0FF33143001F05D -:10104000B3BF00004C3002F08BB800004FF0FF330C -:101050004C3002F085B80000143001F087BF00006A -:101060004FF0FF31143001F081BF00004C3002F02E -:1010700057B800004FF0FF324C3002F051B800007A +:10103000143001F0EDBF00004FF0FF33143001F029 +:10104000E7BF00004C3002F0BFB800004FF0FF33A4 +:101050004C3002F0B9B80000143001F0BBBF000002 +:101060004FF0FF31143001F0B5BF00004C3002F0FA +:101070008BB800004FF0FF324C3002F085B8000012 :101080000020704710B500F58054D4F8A4381A68D1 :101090001178042917D1017C022914D1597901232F -:1010A00052898B4013420ED1143001F019FF0246D1 +:1010A00052898B4013420ED1143001F04DFF02469D :1010B00048B1D4F8A4484FF4407361792068BDE882 :1010C000104000F07FB910BD406BFFF7DBBF0000A0 :1010D000704700007FB5124B0125042604460360CB :1010E0000023057400F1840243602946C0E90233FD :1010F0000C4B0290143001934FF44073009601F0B2 -:10110000CBFE094B04F69442294604F14C000294AC -:10111000CDE900634FF4407301F092FF04B070BD5D -:1011200060390008C9100008ED0F00080A68202384 +:10110000FFFE094B04F69442294604F14C00029478 +:10111000CDE900634FF4407301F0C6FF04B070BD29 +:10112000183A0008C9100008ED0F00080A682023CB :1011300083F311880B790B3342F823004B79133377 :1011400042F823008B7913B10B3342F8230000F5EA :101150008053C3F8A41802230374002383F3118877 :101160007047000038B5037F044613B190F854303F :10117000ABB90125201D0221FFF730FF04F1140057 -:101180006FF00101257700F0A7FC04F14C0084F812 -:1011900054506FF00101BDE8384000F09DBC38BDEF +:101180006FF00101257700F0CBFC04F14C0084F8EE +:1011900054506FF00101BDE8384000F0C1BC38BDCB :1011A00010B5012104460430FFF718FF0023237710 :1011B00084F8543010BD000038B5044600251430C2 -:1011C00001F082FE04F14C00257701F051FF201D53 +:1011C00001F0B6FE04F14C00257701F085FF201DEB :1011D00084F854500121FFF701FF2046BDE8384054 :1011E000FFF750BF90F8803003F06003202B06D14A :1011F00090F881200023212A03D81F2A06D8002036 @@ -291,46 +291,46 @@ :1012100007228267C3670120704700BF2C2200208D :1012200037B500F58055D5F8A4381A681178042927 :101230001AD1017C022917D11979012312898B4017 -:10124000134211D100F14C04204601F0D1FF58B1F6 -:1012500001A9204601F018FFD5F8A4480246019BD9 +:10124000134211D100F14C04204602F005F858B1C8 +:1012500001A9204601F04CFFD5F8A4480246019BA5 :101260002179206800F0C0F803B030BD01F10B0314 :10127000F0B550F8236085B004460D46FEB120233A :1012800083F3118804EB8507301D0821FFF7A6FEC4 :10129000FB6806F14C005B691B681BB1019001F013 -:1012A00001FF019803A901F0EFFE024648B1039B3C +:1012A00035FF019803A901F023FF024648B1039BD3 :1012B0002946204600F098F8002383F3118805B0F2 :1012C000F0BDFB685A691268002AF5D01B8A013B01 :1012D0001340F1D104F18002EAE70000133138B580 :1012E00050F82140ECB1202383F3118804F580539A :1012F000D3F8A4281368527903EB8203DB689B6957 :101300005D6845B104216018FFF768FE294604F1C5 -:10131000140001F0EFFD2046FFF7B4FE002383F335 -:10132000118838BD7047000001F0E2B80123402267 +:10131000140001F023FE2046FFF7B4FE002383F300 +:10132000118838BD7047000001F016B90123402232 :10133000002110B5044600F8303BFFF775FD00238F :10134000C4E9013310BD000010B52023044683F327 :1013500011882422416000210C30FFF765FD2046F2 -:1013600001F0E8F802232370002383F3118810BDF5 +:1013600001F01CF902232370002383F3118810BDC0 :1013700070B500EB8103054650690E461446DA60ED :1013800018B110220021FFF74FFDA06918B11022FB :101390000021FFF749FD31462846BDE8704001F0C5 -:1013A000DBB9000083682022002103F0011310B58F +:1013A0000FBA000083682022002103F0011310B55A :1013B000044683601030FFF737FD2046BDE810403B -:1013C00001F056BAF0B4012500EB810447898D4045 +:1013C00001F08ABAF0B4012500EB810447898D4011 :1013D000E4683D43A469458123600023A260636003 -:1013E000F0BC01F073BA0000F0B4012500EB8104F9 +:1013E000F0BC01F0A7BA0000F0B4012500EB8104C5 :1013F00007898D40E4683D436469058123600023CB -:10140000A2606360F0BC01F0E9BA000070B502238D +:10140000A2606360F0BC01F01DBB000070B5022358 :1014100000250446242203702946C0F888500C3069 :1014200040F8045CFFF700FD204684F8705001F09E -:1014300027F963681B6823B129462046BDE8704040 +:101430005BF963681B6823B129462046BDE870400C :10144000184770BD037880F88C300523037043681B :101450001B6810B504460BB1042198470023A36014 :1014600010BD000090F88C20436802701B680BB11F :10147000052118477047000070B590F87030044699 :1014800013B1002380F8703004F18002204601F08F -:1014900013FA63689B68B3B994F8803013F0600561 -:1014A00035D00021204601F0BDFC0021204601F08E -:1014B000ADFC63681B6813B10621204698470623DC +:1014900047FA63689B68B3B994F8803013F060052D +:1014A00035D00021204601F0F1FC0021204601F05A +:1014B000E1FC63681B6813B10621204698470623A8 :1014C00084F8703070BD204698470028E4D0B4F806 :1014D0008630A26F9A4288BFA36794F98030A56FC7 :1014E000002B4FF0200380F20381002D00F0F280EA @@ -350,26 +350,26 @@ :1015C0008230012B7FF46DAFB4F8883023F0020332 :1015D000A4F88830C4E91D55E56778E7B4F8803091 :1015E000B3F5A06F0ED194F88230204684F88A308B -:1015F00001F0A4F863681B6813B1012120469847E5 +:1015F00001F0D8F863681B6813B1012120469847B1 :10160000032323700023C4E91D339CE704F18B03FB :1016100063670123C3E72378042B10D1202383F3CE :1016200011882046FFF7BEFE85F311880321636809 :1016300084F88B5021701B680BB12046984794F8B2 :101640008230002BDED084F88B3004232370636853 :101650001B68002BD6D0022120469847D2E794F889 -:10166000843020461D0603F00F010AD501F016F95B +:10166000843020461D0603F00F010AD501F04AF927 :10167000012804D002287FF414AF2B4B9AE72B4BA0 -:1016800098E701F0FDF8F3E794F88230002B7FF43F +:1016800098E701F031F9F3E794F88230002B7FF40A :1016900008AF94F8843013F00F01B3D01A06204637 -:1016A00002D501F0D7FBADE701F0C8FBAAE794F83B +:1016A00002D501F00BFCADE701F0FCFBAAE794F8D2 :1016B0008230002B7FF4F5AE94F8843013F00F01E4 -:1016C000A0D01B06204602D501F0ACFB9AE701F042 -:1016D0009DFB97E7142284F8702083F311882B4632 +:1016C000A0D01B06204602D501F0E0FB9AE701F00E +:1016D000D1FB97E7142284F8702083F311882B46FE :1016E0002A4629462046FFF76DFE85F31188E9E674 :1016F0005DB1152284F8702083F311880021204603 :10170000D4E91D23FFF75EFEFDE60B2284F870206E :1017100083F311882B462A4629462046FFF764FEAC -:10172000E3E700BF90390008883900088C390008C9 +:10172000E3E700BF483A0008403A0008443A00089E :1017300038B590F870300446002B3ED0063BDAB244 :101740000F2A34D80F2B32D8DFE803F037313108B5 :10175000223231313131313131313737856FB0F8A3 @@ -379,11 +379,11 @@ :10179000142384F87030202383F31188002320461B :1017A0001A461946FFF70EFE002383F3118838BD51 :1017B000C36F03B198470023E7E70021204601F0FB -:1017C00031FB0021204601F021FB63681B6813B147 +:1017C00065FB0021204601F055FB63681B6813B1DF :1017D0000621204698470623D7E7000010B590F869 :1017E00070300446142B29D017D8062B05D001D809 :1017F0001BB110BD093B022BFBD80021204601F094 -:1018000011FB0021204601F001FB63681B6813B146 +:1018000045FB0021204601F035FB63681B6813B1DE :10181000062120469847062319E0152BE9D10B2312 :1018200080F87030202383F3118800231A4619466C :10183000FFF7DAFD002383F31188DAE7C3689B69B9 @@ -399,8 +399,8 @@ :1018D0004260106058607047B4230020054B1969BE :1018E00008741868026853601A6018610123037451 :1018F000FEF76CBDB42300204B1C30B5044687B006 -:101900000A4D10D02B6901A8094A00F001F92046C0 -:10191000FFF7E4FF049B13B101A800F035F92B6930 +:101900000A4D10D02B6901A8094A00F025F920469C +:10191000FFF7E4FF049B13B101A800F059F92B690C :10192000586907B030BDFFF7D9FFF8E7B4230020AE :101930008518000838B50C4D044641612B69816853 :101940009A68914203D8BDE83840FFF78BBF18462C @@ -409,564 +409,576 @@ :101970001B6990689B68984294BF002001207047C3 :10198000B423002010B5084C236820691A685460FD :101990002260012223611A74FFF790FF014620693B -:1019A000BDE81040FEF712BDB4230020FFF7EABFE8 -:1019B000FEE7000010B50C4CFFF74CFF00F09AF862 -:1019C00080220A49204600F021F8012344F8180C2F -:1019D000037400F06BFC002383F3118862B60448A3 -:1019E000BDE8104000F032B8DC2300209439000834 -:1019F000A439000800F002B9034A516853685B1A21 -:101A00009842FBD8704700BF001000E082600222BD -:101A1000028270478368A3F17C0243F80C2C0269B0 -:101A200043F83C2C426943F8382C074A43F81C2CF5 -:101A3000C268A3F1180043F8102C022203F8082C06 -:101A4000002203F8072C7047E503000810B5202397 -:101A500083F31188FFF7DEFF00210446FFF76AFFDA -:101A6000002383F31188204610BD0000024B1B6940 -:101A700058610F20FFF732BFB4230020202383F3E7 -:101A80001188FFF7F3BF000008B50146202383F358 -:101A900011880820FFF730FF002383F3118808BD69 -:101AA00049B1064B42681B6918605A601360436075 -:101AB0000420FFF721BF4FF0FF307047B423002010 -:101AC0000368984206D01A6802605060184659614F -:101AD000FFF7C8BE7047000038B504460D462068C1 -:101AE000844200D138BD036823605C604561FFF724 -:101AF000B9FEF4E7054B4FF0FF3103F11402C3E9DF -:101B000005220022C3E90712704700BFB42300205A -:101B100070B51C4E05460C46C0E9032301F09EFB40 -:101B2000334653F8142F9A420DD130620A2C2CBF41 -:101B300000190A302A60C5E90124C6E90555BDE847 -:101B4000704001F075BB316A431AE31838BF1C4678 -:101B50009368A34202D9081901F07AFB73699A6865 -:101B600094420CD85A68AC602B606A6015609A6821 -:101B70005D60121B9A604FF0FF33F36170BDA41AD1 -:101B80001B68ECE7B423002038B51B4C636998420E -:101B90000DD08168D0E9003213605A600022C26023 -:101BA0009A680A449A604FF0FF33E36138BD0368D6 -:101BB0002246002142F8143F93425A60C16003D18B -:101BC000BDE8384001F03EBB9A688168256A0A4446 -:101BD0009A6001F043FB6369411B9A688A42E5D928 -:101BE000AB181D1A206A092D98BF01F10A02BDE841 -:101BF0003840104401F02CBBB42300202DE9F04103 -:101C0000184C002704F11406656901F027FB236ACC -:101C1000AA68C11A8A4215D81344D5F80C802362E9 -:101C2000D5E9003213605A606369EF60B34201D1B5 -:101C300001F008FB87F311882869C047202383F34C -:101C40001188E1E76169B14209D013441B1ABDE86C -:101C5000F0410A2B2CBFC0180A3001F0F9BABDE8D8 -:101C6000F08100BFB423002000207047FEE7000091 -:101C7000704700004FF0FF307047000002290CD081 -:101C8000032904D00129074818BF00207047032A00 -:101C900005D8054800EBC200704704487047002093 -:101CA000704700BF883A00083C2200203C3A0008F8 -:101CB00070B59AB005460846144601A900F0C2F86E -:101CC00001A8FFF7A9F8431C0022C6B25B0010462A -:101CD000C5E9003423700323023404F8013C01AB4E -:101CE000D1B202348E4201D81AB070BD13F8011B74 -:101CF000013204F8010C04F8021CF1E708B52023B6 -:101D000083F311880348FFF78BFA002383F31188CC -:101D100008BD00BF7025002090F8803003F01F023E -:101D2000012A07D190F881200B2A03D10023C0E9B2 -:101D30001D3315E003F06003202B08D1B0F8843088 -:101D40002BB990F88120212A03D81F2A04D8FFF745 -:101D500049BA222AEBD0FAE7034A42670722826790 -:101D6000C3670120704700BF3322002007B5052953 -:101D700017D8DFE801F0191603191920202383F37F -:101D80001188104A01210190FFF7F2FA019802210F -:101D90000D4AFFF7EDFA0D48FFF70EFA002383F323 -:101DA000118803B05DF804FB202383F311880748F2 -:101DB000FFF7D8F9F2E7202383F311880348FFF7F0 -:101DC000EFF9EBE7DC390008003A00087025002045 -:101DD00038B50C4D0C4C2A460C4904F10800FFF7AD -:101DE00067FF05F1CA0204F110000949FFF760FF1F -:101DF00005F5CA7204F118000649BDE83840FFF73E -:101E000057BF00BF483E00203C220020BC390008DC -:101E1000C6390008D139000870B5044608460D4699 -:101E2000FEF7FAFFC6B22046013403780BB9184614 -:101E300070BD32462946FEF7DBFF0028F3D10120B2 -:101E4000F6E700002DE9F84F05460C46FEF7E4FFE3 -:101E50002A49C6B22846FFF7DFFF08B10136F6B2BD -:101E600027492846FFF7D8FF08B11036F6B2632E8F -:101E70000DD8DFF88890DFF888A0224FDFF88CB00B -:101E8000DFF88C802E7846B92670BDE8F88F294699 -:101E90002046BDE8F84F01F04DBD252E2AD107227E -:101EA00049462846FEF7A4FF50B9D8F80030073558 -:101EB000083444F8083CD8F8043044F8043CE1E71E -:101EC000082251462846FEF793FF98B9A21C0E4BF4 -:101ED000197802320909C95D02F8041C13F8011BC4 -:101EE00001F00F015B45C95D02F8031CF0D1183405 -:101EF0000835C7E7013504F8016BC3E7A83A0008C5 -:101F0000D1390008B93A000800E8F11F0CE8F11FC8 -:101F1000B03A0008BFF34F8F044B1A695107FCD148 -:101F2000D3F810215207F8D1704700BF00200052AB -:101F300008B50D4B1B78ABB9FFF7ECFF0B4BDA681C -:101F4000D10704D50A4A5A6002F188325A60D3F8A0 -:101F50000C21D20706D5064AC3F8042102F18832C3 -:101F6000C3F8042108BD00BFA64000200020005295 -:101F70002301674508B5114B1B78F3B9104B1A695B -:101F8000510703D5DA6842F04002DA60D3F8102135 -:101F9000520705D5D3F80C2142F04002C3F80C21BA -:101FA000FFF7B8FF064BDA6842F00102DA60D3F8B7 -:101FB0000C2142F00102C3F80C2108BDA64000200C -:101FC000002000520F289ABF00F5806040040020D6 -:101FD000704700004FF40030704700001020704739 -:101FE0000F2808B50BD8FFF7EDFF00F500330268A6 -:101FF000013204D104308342F9D1012008BD002010 -:10200000FCE700000F2838B505463FD8FFF782FFF0 -:102010001F4CFFF78DFF4FF0FF3307286361C4F8B3 -:1020200014311DD82361FFF775FF030243F0240329 -:10203000E360E36843F08003E36023695A07FCD45C -:102040002846FFF767FFFFF7BDFF4FF4003100F0B0 -:10205000F7F82846FFF78EFFBDE83840FFF7C0BF0E -:10206000C4F81031FFF756FFA0F108031B0243F03C -:102070002403C4F80C31D4F80C3143F08003C4F8C5 -:102080000C31D4F810315B07FBD4D9E7002038BD00 -:10209000002000522DE9F84F05460C46104645EA4F -:1020A0000203DB065DD122F003022B462A44934251 -:1020B00009D120F01F00DFF8BCB0DFF8BCA0FFF7AB -:1020C00037FF271844E0196801314AD10433EEE79D -:1020D00005F1784324492548B3F5801F244B38BFC8 -:1020E000184603F1F80339BF8846D9469846D146C9 -:1020F000FFF710FF4FF0FF33A5EB040C04F11C01B8 -:102100000360D8F8003043F00203C8F80030231F02 -:10211000D9F8006016F00506FAD153F8042F994259 -:102120004CF80320F4D1BFF34F8FFFF7F3FE4FF0CD -:10213000FF332022214603602846D8F8003023F0E0 -:102140000203C8F8003001F0E5FB40B92035203427 -:10215000BC42BDD10120FFF70DFFBDE8F88F30462E -:10216000F9E70020F9E700BF0C20005214210052CB -:1021700014200052102000521021005210B5084CBB -:10218000237828B11BB9FFF7D3FE0123237010BDBC -:10219000002BFCD02070BDE81040FFF7EBBE00BF65 -:1021A000A64000200244074BD2B210B5904200D1A5 -:1021B00010BD441C00B253F8200041F8040BE0B2FB -:1021C000F4E700BF504000580E4B30B51C6F24049C -:1021D00005D41C6F1C671C6F44F400441C670A4C38 -:1021E00002442368D2B243F480732360074B9042C9 -:1021F00000D130BD441C51F8045B00B243F82050BC -:10220000E0B2F4E700440258004802585040005839 -:1022100007B5012201A90020FFF7C4FF019803B010 -:102220005DF804FB13B50446FFF7F2FFA04205D0AA -:10223000012201A900200194FFF7C6FF02B010BDE2 -:102240000144BFF34F8F064B884204D3BFF34F8F37 -:10225000BFF36F8F7047C3F85C022030F4E700BF14 -:1022600000ED00E0044BD3F8D0345B0142BF034BD8 -:1022700001221A70704700BF00400258A74000209A -:10228000014B1878704700BFA7400020EFF3098387 -:10229000054968334A6B22F001024A6383F30988D7 -:1022A000002383F31188704700EF00E0202080F3C3 -:1022B000118862B60D4B0E4AD96821F4E061090419 -:1022C000090C0A430B49DA60D3F8FC2042F0807213 -:1022D000C3F8FC20084AC2F8B01F116841F00101A0 -:1022E00011601022DA7783F82200704700ED00E0D9 -:1022F0000003FA0555CEACC5001000E0202310B550 -:1023000083F311880E4B5B6813F4006314D0F1EE75 -:10231000103AEFF309844FF08073683CE361094B96 -:10232000DB6B236684F30988FFF720FB10B1064BB3 -:10233000A36110BD054BFBE783F31188F9E700BFEC -:1023400000ED00E000EF00E0F7030008FA030008EA -:1023500070B5BFF34F8FBFF36F8F1A4A0021C2F8D9 -:102360005012BFF34F8FBFF36F8F536943F40033A5 -:102370005361BFF34F8FBFF36F8FC2F88410BFF369 -:102380004F8FD2F8803043F6E074C3F3C900C3F333 -:102390004E335B0103EA0406014646EA81750139C2 -:1023A000C2F86052F9D2203B13F1200FF2D1BFF3F3 -:1023B0004F8F536943F480335361BFF34F8FBFF3A3 -:1023C0006F8F70BD00ED00E0FEE700000A4B0B4888 -:1023D0000B4A90420BD30B4BC11EDA1C121A22F08F -:1023E00003028B4238BF00220021FEF71DBD53F8C7 -:1023F000041B40F8041BECE79C3C000878420020DA -:1024000078420020784200207047000070B5D0E983 -:10241000244300224FF0FF359E6804EB4213510124 -:10242000D3F80009002805DAD3F8000940F080400D -:10243000C3F80009D3F8000B002805DAD3F8000B25 -:1024400040F08040C3F8000B013263189642C3F895 -:102450000859C3F8085BE0D24FF00113C4F81C38E8 -:1024600070BD000000EB8103D3F80CC02DE9F043F0 -:10247000DCF814204E1CD0F89050D2F800E005EBA8 -:10248000063605EB4118506870450AD30122D5F88D -:10249000343802FA01F123EA0101C5F83418BDE825 -:1024A000F083AEEB0003BCF81040A34228BF2346E4 -:1024B000D8F81849A4B2B3EB840FF0D89468A4F10B -:1024C000040959F8047F3760A4EB09071F44042F5F -:1024D000F7D81C44034494605360D4E7890141F069 -:1024E0002001016103699B06FCD41220FFF784BA26 -:1024F00010B50A4C2046FEF719FF094BC4F890307E -:10250000084BC4F89430084C2046FEF70FFF074BE9 -:10251000C4F89030064BC4F8943010BDA840002099 -:1025200000000840F03A0008444100200000044048 -:10253000FC3A000870B503780546012B5DD1494B84 -:10254000D0F89040984259D1474B0E216520D3F8DE -:10255000D82042F00062C3F8D820D3F8002142F01E -:102560000062C3F80021D3F80021D3F8802042F0A4 -:102570000062C3F88020D3F8802022F00062C3F804 -:102580008020D3F8803000F071FC384BE360384B8A -:10259000C4F800380023D5F89060C4F8003EC0238A -:1025A00023604FF40413A3633369002BFCDA012387 -:1025B0000C203361FFF720FA3369DB07FCD41220CB -:1025C000FFF71AFA3369002BFCDA00262846A660CA -:1025D000FFF71CFF6B68C4F81068DB68C4F8146868 -:1025E000C4F81C68002B3AD1224BA3614FF0FF3393 -:1025F0006361A36843F00103A36070BD1E4B984262 -:10260000C8D1194B0E214D20D3F8D82042F00072CA -:10261000C3F8D820D3F8002142F00072C3F800219B -:10262000D3F80021D3F8802042F00072C3F8802054 -:10263000D3F8802022F00072C3F88020D3F88020E5 -:10264000D3F8D82022F08062C3F8D820D3F8002134 -:1026500022F08062C3F80021D3F8003193E7074BE2 -:10266000C3E700BFA84000200044025840140040C7 -:1026700003002002003C30C044410020083C30C030 -:10268000F8B5D0F89040054600214FF0006620468E -:10269000FFF724FFD5F8941000234FF001128F6844 -:1026A0004FF0FF30C4F83438C4F81C2804EB431250 -:1026B00001339F42C2F80069C2F8006BC2F80809F2 -:1026C000C2F8080BF2D20B68D5F89020C5F8983004 -:1026D000636210231361166916F01006FBD11220F5 -:1026E000FFF78AF9D4F8003823F4FE63C4F8003801 -:1026F000A36943F4402343F01003A3610923C4F802 -:102700001038C4F814380B4BEB604FF0C043C4F8DA -:10271000103B094BC4F8003BC4F81069C4F80039F9 -:10272000D5F8983003F1100243F48013C5F89820CF -:10273000A362F8BDCC3A000840800010D0F8902089 -:1027400090F88A10D2F8003823F4FE6343EA0113AC -:10275000C2F80038704700002DE9F84300EB810310 -:10276000D0F890500C468046DA680FFA81F948019B -:10277000166806F00306731E022B05EB41134FF09B -:10278000000194BFB604384EC3F8101B4FF001018E -:1027900004F1100398BF06F1805601FA03F3916922 -:1027A00098BF06F5004600293AD0578A04F158012F -:1027B000374349016F50D5F81C180B430021C5F869 -:1027C0001C382B180127C3F81019A7405369611E44 -:1027D0009BB3138A928B9B08012A88BF5343D8F876 -:1027E0009820981842EA034301F140022146C8F8B4 -:1027F0009800284605EB82025360FFF76FFE08EB56 -:102800008900C3681B8A43EA845348341E43640129 -:102810002E51D5F81C381F43C5F81C78BDE8F88345 -:1028200005EB4917D7F8001B21F40041C7F8001B3E -:10283000D5F81C1821EA0303C0E704F13F030B4A53 -:102840002846214605EB83035A60FFF747FE05EB58 -:102850004910D0F8003923F40043C0F80039D5F806 -:102860001C3823EA0707D7E70080001000040002A5 -:10287000D0F894201268C0F89820FFF7C7BD000078 -:102880005831D0F8903049015B5813F4004004D01F -:1028900013F4001F0CBF0220012070474831D0F80C -:1028A000903049015B5813F4004004D013F4001F2A -:1028B0000CBF02200120704700EB8101CB68196A30 -:1028C0000B6813604B6853607047000000EB810396 -:1028D00030B5DD68AA691368D36019B9402B84BF8D -:1028E000402313606B8A1468D0F890201C4402EBDC -:1028F0004110013C09B2B4FBF3F46343033323F00A -:10290000030343EAC44343F0C043C0F8103B2B68C1 -:1029100003F00303012B0ED1D2F8083802EB41106B -:1029200013F4807FD0F8003B14BF43F0805343F092 -:102930000053C0F8003B02EB4112D2F8003B43F0D9 -:102940000443C2F8003B30BD2DE9F041D0F890605F -:1029500005460C4606EB4113D3F8087B3A07C3F84B -:10296000087B08D5D6F814381B0704D500EB810383 -:10297000DB685B689847FA071FD5D6F81438DB0781 -:102980001BD505EB8403D968CCB98B69488A5A6892 -:10299000B2FBF0F600FB16228AB91868DA6890429A -:1029A0000DD2121AC3E90024202383F31188214693 -:1029B0002846FFF78BFF84F31188BDE8F0810123DF -:1029C00003FA04F26B8923EA02036B81CB68002BC4 -:1029D000F3D021462846BDE8F041184700EB8103BB -:1029E0004A0170B5DD68D0F890306C692668E66001 -:1029F00056BB1A444FF40020C2F810092A6802F0AE -:102A00000302012A0AB20ED1D3F8080803EB4214DC -:102A100010F4807FD4F8000914BF40F0805040F0DB -:102A20000050C4F8000903EB4212D2F8000940F04C -:102A30000440C2F800090122D3F8340802FA01F177 -:102A40000143C3F8341870BD19B9402E84BF40202B -:102A5000206020681A442E8A8419013CB4FBF6F4E5 -:102A600040EAC44040F00050C6E700002DE9F041C4 -:102A7000D0F8906004460D4606EB4113D3F8087970 -:102A8000C3F80879FB071CD5D6F81038DA0718D533 -:102A900000EB8103D3F80CC0DCF81430D3F800E06D -:102AA000DA6896451BD2A2EB0E024FF000081A60BE -:102AB000C3F80480202383F31188FFF78FFF88F386 -:102AC00011883B0618D50123D6F83428AB401342B1 -:102AD00012D029462046BDE8F041FFF7C3BC0123D0 -:102AE00003FA01F2038923EA02030381DCF80830C8 -:102AF000002BE6D09847E4E7BDE8F0812DE9F84FD8 -:102B0000D0F8905004466E69AB691E4016F48058A8 -:102B10006E6103D0BDE8F84FFEF778BC002E12DAE4 -:102B2000D5F8003E9F0705D0D5F8003E23F00303FB -:102B3000C5F8003ED5F80438204623F00103C5F857 -:102B40000438FEF78FFC300505D52046FFF75EFC04 -:102B50002046FEF777FCB1040CD5D5F8083813F001 -:102B6000060FEB6823F470530CBF43F4105343F487 -:102B7000A053EB60320704D56368DB680BB12046D5 -:102B80009847F30200F1BA80B70226D5D4F89090A6 -:102B900000274FF0010A09EB4712D2F8003B03F47B -:102BA0004023B3F5802F11D1D2F8003B002B0DDA72 -:102BB00062890AFA07F322EA0303638104EB8703BD -:102BC000DB68DB6813B13946204698470137D4F8F3 -:102BD0009430FFB29B689F42DDD9F00619D5D4F836 -:102BE0009000026AC2F30A1702F00F0302F4F01217 -:102BF000B2F5802F00F0CC80B2F5402F09D104EB64 -:102C00008303002200F58050DB681B6A974240F086 -:102C1000B2803003D5F8185835D5E90303D5002123 -:102C20002046FFF791FEAA0303D501212046FFF7B6 -:102C30008BFE6B0303D502212046FFF785FE2F0391 -:102C400003D503212046FFF77FFEE80203D50421C8 -:102C50002046FFF779FEA90203D505212046FFF79C -:102C600073FE6A0203D506212046FFF76DFE2B0294 -:102C700003D507212046FFF767FEEF0103D50821A2 -:102C80002046FFF761FE700340F1A980E90703D5F4 -:102C900000212046FFF7EAFEAA0703D501212046BE -:102CA000FFF7E4FE6B0703D502212046FFF7DEFEA7 -:102CB0002F0703D503212046FFF7D8FEEE0603D5E4 -:102CC00004212046FFF7D2FEA80603D505212046A1 -:102CD000FFF7CCFE690603D506212046FFF7C6FEA6 -:102CE0002A0603D507212046FFF7C0FEEB0576D55F -:102CF00020460821BDE8F84FFFF7B8BED4F8909001 -:102D000000274FF0010AD4F894305FFA87FB9B68E4 -:102D10009B453FF639AF09EB4B13D3F8002902F47A -:102D20004022B2F5802F24D1D3F80029002A20DADE -:102D3000D3F8002942F09042C3F80029D3F80029C3 -:102D4000002AFBDB5946D4F89000FFF7C7FB228925 -:102D50000AFA0BF322EA0303238104EB8B03DB68FB -:102D60009B6813B159462046984759462046FFF7BD -:102D700079FB0137C7E7910701D1D0F80080072A16 -:102D800002F101029CBF03F8018B4FEA18283DE7CE -:102D900004EB830300F58050DA68D2F818C0DCF841 -:102DA0000820DCE9001CA1EB0C0C00218F4208D1AB -:102DB000DB689B699A683A449A605A683A445A6058 -:102DC00027E711F0030F01D1D0F800808C4501F105 -:102DD000010184BF02F8018B4FEA1828E6E7BDE83D -:102DE000F88F000008B50348FFF788FEBDE80840EB -:102DF000FFF784BAA840002008B50348FFF77EFE1D -:102E0000BDE80840FFF77ABA44410020D0F890307E -:102E100003EB4111D1F8003B43F40013C1F8003B30 -:102E200070470000D0F8903003EB4111D1F8003921 -:102E300043F40013C1F8003970470000D0F8903017 -:102E400003EB4111D1F8003B23F40013C1F8003B20 -:102E500070470000D0F8903003EB4111D1F80039F1 -:102E600023F40013C1F8003970470000090100F194 -:102E70006043012203F56143C9B283F8001300F0F7 -:102E80001F039A4043099B0003F1604303F561432C -:102E9000C3F880211A60704730B50433039C017277 -:102EA000002104FB0325C160C0E90653049B0363B2 -:102EB000059BC0E90000C0E90422C0E90842C0E95E -:102EC0000A11436330BD00000022416AC260C0E9BC -:102ED0000411C0E90A226FF00101FEF7FDBD0000F8 -:102EE000D0E90432934201D1C2680AB9181D704773 -:102EF00000207047036919600021C2680132C26076 -:102F0000C269134482699342036124BF436A036127 -:102F1000FEF7D6BD38B504460D46E3683BB162699D -:102F20000020131D1268A3621344E36207E0237AB2 -:102F300033B929462046FEF7B3FD0028EDDA38BD47 -:102F40006FF00100FBE70000C368C269013BC3608A -:102F50004369134482699342436124BF436A4361D6 -:102F600000238362036B03B11847704770B52023B9 -:102F7000044683F31188866A3EB9FFF7CBFF054606 -:102F800018B186F31188284670BDA36AE26A13F867 -:102F9000015B9342A36202D32046FFF7D5FF0023D3 -:102FA00083F31188EFE700002DE9F84F04460E4641 -:102FB000174698464FF0200989F311880025AA4644 -:102FC000D4F828B0BBF1000F09D141462046FFF7E5 -:102FD000A1FF20B18BF311882846BDE8F88FD4E912 -:102FE0000A12A7EB050B521A934528BF9346BBF173 -:102FF000400F1BD9334601F1400251F8040B9142B6 -:1030000043F8040BF9D1A36A403640354033A3623C -:10301000D4E90A239A4202D32046FFF795FF8AF3A8 -:103020001188BD42D8D289F31188C9E730465A4683 -:10303000FDF7D4FEA36A5E445D445B44A362E7E708 -:1030400010B5029C0433017204FB0321C460C0E983 -:1030500006130023C0E90A33039B0363049BC0E902 -:103060000000C0E90422C0E90842436310BD00002B -:10307000026A6FF00101C260426AC0E904220022C4 -:10308000C0E90A22FEF728BDD0E904239A4201D103 -:10309000C26822B9184650F8043B0B607047002004 -:1030A00070470000C3680021C2690133C3604369EF -:1030B000134482699342436124BF436A4361FEF72C -:1030C000FFBC000038B504460D46E3683BB12369F8 -:1030D00000201A1DA262E2691344E36207E0237A2A -:1030E00033B929462046FEF7DBFC0028EDDA38BD6F -:1030F0006FF00100FBE7000003691960C268013A44 -:10310000C260C269134482699342036124BF436A67 -:10311000036100238362036B03B11847704700000B -:1031200070B520230D460446114683F31188866A44 -:103130002EB9FFF7C7FF10B186F3118870BDA36ADF -:103140001D70A36AE26A01339342A36204D3E1696A -:1031500020460439FFF7D0FF002080F31188EDE707 -:103160002DE9F84F04460D46904699464FF0200A47 -:103170008AF311880026B346A76A4FB9494620460C -:10318000FFF7A0FF20B187F311883046BDE8F88F24 -:10319000D4E90A073A1AA8EB0607974228BF174650 -:1031A000402F1BD905F1400355F8042B9D4240F8F0 -:1031B000042BF9D1A36A40364033A362D4E90A2331 -:1031C0009A4204D3E16920460439FFF795FF8BF357 -:1031D00011884645D9D28AF31188CDE729463A4667 -:1031E000FDF7FCFDA36A3D443E443B44A362E5E792 -:1031F000D0E904239A4217D1C3689BB1836A8BB18B -:10320000043B9B1A0ED01360C368013BC360C369C3 -:103210001A4483699A42026124BF436A036100230E -:1032200083620123184670470023FBE700F0B2B821 -:10323000034B002258631A610222DA60704700BF14 -:10324000000C0040014B0022DA607047000C004087 -:10325000014B5863704700BF000C0040014B586A97 -:10326000704700BF000C00404B6843608B68836070 -:10327000CB68C3600B6943614B6903628B6943622E -:103280000B6803607047000008B5364B40F2FF71D1 -:103290003548D3F888200A43C3F88820D3F888201B -:1032A00022F4FF6222F00702C3F88820D3F88820B6 -:1032B000D3F8E0200A43C3F8E020D3F808210A43FA -:1032C000C3F80821294AD3F808311146FFF7CCFF8B -:1032D00000F5806002F11C01FFF7C6FF00F5806079 -:1032E00002F13801FFF7C0FF00F5806002F15401E0 -:1032F000FFF7BAFF00F5806002F17001FFF7B4FF3D -:1033000000F5806002F18C01FFF7AEFF00F58060F0 -:1033100002F1A801FFF7A8FF00F5806002F1C401E7 -:10332000FFF7A2FF00F5806002F1E001FFF79CFFCC -:1033300000F5806002F1FC01FFF796FF02F58C7149 -:1033400000F58060FFF790FF00F0D8F8084B0522E9 -:10335000C3F898204FF06052C3F89C20054AC3F888 -:10336000A02008BD0044025800000258083B000895 -:1033700000ED00E01F00080308B500F0ADFAFEF70D -:1033800019FBFEF76FFFBDE80840FEF721BD000006 -:1033900070470000114BD3F8E82042F00802C3F850 -:1033A000E820D3F8102142F00802C3F810210C4A9B -:1033B000D3F81031D36B43F00803D363C722094B12 -:1033C0009A624FF0FF32DA6200229A615A63DA6041 -:1033D0005A6001225A611A60704700BF00440258C7 -:1033E0000010005C000C0040094A08B51169D36860 -:1033F0000B40D9B29B076FEA0101116107D5202369 -:1034000083F31188FEF7F6FA002383F3118808BDD1 -:10341000000C0040384B4FF0FF31D3F88020C3F848 -:103420008010D3F880200022C3F88020D3F88000D9 -:10343000D3F88400C3F88410D3F88400C3F8842040 -:10344000D3F88400D86F40F0FF4040F4FF0040F410 -:103450003F5040F03F00D867D86F20F0FF4020F485 -:10346000FF0020F43F5020F03F00D867D86FD3F81A -:1034700088006FEA40506FEA5050C3F88800D3F8D4 -:103480008800C0F30A00C3F88800D3F88800D3F896 -:103490009000C3F89010D3F89000C3F89020D3F8B0 -:1034A0009000D3F89400C3F89410D3F89400C3F8B4 -:1034B0009420D3F89400D3F89800C3F89810D3F868 -:1034C0009800C3F89820D3F89800D3F88C00C3F87C -:1034D0008C10D3F88C00C3F88C20D3F88C00D3F870 -:1034E0009C00C3F89C10D3F89C10C3F89C20D3F820 -:1034F0009C3000F0C9B900BF00440258614B012262 -:10350000C3F80821604BD3F8F42042F00202C3F85C -:10351000F420D3F81C2142F00202C3F81C2102223D -:10352000D3F81C31594BDA605A689104FCD5584ADB -:103530001A6001229A60574ADA6000221A614FF439 -:1035400040429A61514B9A699204FCD51A6842F440 -:1035500080721A604C4B1A6F12F4407F04D04FF403 -:1035600080321A6700221A671A6842F001021A6054 -:10357000454B1A685007FCD500221A611A6912F0EF -:103580003802FBD1012119604FF0804159605A6720 -:10359000414ADA62414A1A611A6842F480321A607A -:1035A000394B1A689103FCD51A6842F480521A60AC -:1035B0001A689204FCD53A4A3A499A6200225A6340 -:1035C00019633949DA6399635A64384A1A64384A84 -:1035D000DA621A6842F0A8521A602B4B1A6802F09D -:1035E0002852B2F1285FF9D148229A614FF48862DB -:1035F000DA6140221A622F4ADA644FF000521A65EB -:103600002D4A5A652D4A9A6532232D4A1360136854 -:1036100003F00F03022BFAD11B4B1A6942F003028D -:103620001A611A6902F03802182AFAD1D3F8DC209C -:1036300042F00052C3F8DC20D3F8042142F00052DB -:10364000C3F80421D3F80421D3F8DC2042F08042EF -:10365000C3F8DC20D3F8042142F08042C3F80421EF -:10366000D3F80421D3F8DC2042F00042C3F8DC2078 -:10367000D3F8042142F00042C3F80421D3F8043106 -:10368000704700BF008000510044025800480258B3 -:1036900000C000F0020000010000FF010088900857 -:1036A00012102000630207012C02040047040508E1 -:1036B000FD0BFF01200000200010E00000010100D0 -:1036C000002000524FF0B04208B5D2F8883003F025 -:1036D0000103C2F8883023B1044A13680BB1506863 -:1036E0009847BDE80840FEF709BE00BFF84100203A -:1036F0004FF0B04208B5D2F8883003F00203C2F8A8 -:10370000883023B1044A93680BB1D0689847BDE86C -:103710000840FEF7F3BD00BFF84100204FF0B04273 -:1037200008B5D2F8883003F00403C2F8883023B11A -:10373000044A13690BB150699847BDE80840FEF789 -:10374000DDBD00BFF84100204FF0B04208B5D2F80F -:10375000883003F00803C2F8883023B1044A936923 -:103760000BB1D0699847BDE80840FEF7C7BD00BF60 -:10377000F84100204FF0B04208B5D2F8883003F08D -:103780001003C2F8883023B1044A136A0BB1506A9F -:103790009847BDE80840FEF7B1BD00BFF8410020E2 -:1037A0004FF0B04310B5D3F8884004F47872C3F8F2 -:1037B0008820A30604D5124A936A0BB1D06A9847B1 -:1037C000600604D50E4A136B0BB1506B9847210667 -:1037D00004D50B4A936B0BB1D06B9847E20504D527 -:1037E000074A136C0BB1506C9847A30504D5044AE3 -:1037F000936C0BB1D06C9847BDE81040FEF77EBDCE -:10380000F84100204FF0B04310B5D3F8884004F4DD -:103810007C42C3F88820620504D5164A136D0BB1AB -:10382000506D9847230504D5124A936D0BB1D06DA6 -:103830009847E00404D50F4A136E0BB1506E9847B9 -:10384000A10404D50B4A936E0BB1D06E9847620465 -:1038500004D5084A136F0BB1506F9847230404D561 -:10386000044A936F0BB1D06F9847BDE81040FEF744 -:1038700045BD00BFF841002008B5FFF7B5FDBDE824 -:103880000840FEF73BBD0000062108B50846FFF7DB -:10389000EDFA06210720FFF7E9FA06210820FFF7D5 -:1038A000E5FA06210920FFF7E1FA06210A20FFF7D1 -:1038B000DDFA06211720FFF7D9FA06212820FFF7A5 -:1038C000D5FA09217A20FFF7D1FA07213220BDE885 -:1038D0000840FFF7CBBA000008B5FFF79BFD00F0EA -:1038E0000BF8FDF721FDFDF7F3FBFFF751FDBDE8F8 -:1038F0000840FFF79BBC00000023054A194601332E -:10390000102BC2E9001102F10802F8D1704700BF84 -:10391000F841002010B501390244904201D1002045 -:1039200005E0037811F8014FA34201D0181B10BD28 -:103930000130F2E7034611F8012B03F8012B002AAE -:10394000F9D1704753544D333248373F3F3F00530E -:10395000544D3332483734332F37353300000000AD -:10396000000000004D100008391000087510000814 -:10397000611000086D10000859100008451000087B -:103980003110000881100008000000000100000054 -:10399000000000006D61696E0000000069646C65E4 -:1039A000000000009C390008F8230020702500204A -:1039B00001000000B11900080000000041726475A8 -:1039C00050696C6F740025424F415244252D424C82 -:1039D000002553455249414C2500000002000000DB -:1039E000000000006D120008DD12000840004000D9 -:1039F000183E0020283E00200200000000000000C9 -:103A00000300000000000000251300080000000073 -:103A100010000000383E00200000000001000000FF -:103A200000000000A8400020010102006D1D0008F8 -:103A30007D1C0008191D0008FD1C00084300000043 -:103A4000443A000809024300020100C032090400A0 -:103A500000010202010005240010010524010001FB -:103A6000042402020524060001070582030800FF62 -:103A700009040100020A00000007050102400000DD -:103A8000070581024000000012000000903A000883 -:103A90001201100102000040091241570002010208 -:103AA000030100000403090425424F41524425004C -:103AB0004B616B75746548370030313233343536BD -:103AC00037383941424344454600000000000000B9 -:103AD0007914000831170008DD1700084000400085 -:103AE000E0410020E041002001000000F041002002 -:103AF00080000000400100000800000000010000FC -:103B000000040000080000000001802A00000000FE -:103B1000AAAAAAAA00010000FFFF000000000000FE -:103B200000A00A000000000100000000AAAAAAAA42 -:103B300000000001FFFF0000000000000000000086 -:103B40001000000400000000AAAAAAAA00000008B1 -:103B5000FBDF00000000000000000000000000008B -:103B600000000000AAAAAAAA00000000FFFF0000AF -:103B70000000000000000000000100000000000044 -:103B8000AAAAAAAA00010000FFFF0000000000008E -:103B9000000000000000000000000000AAAAAAAA7D -:103BA00000000000FFFF0000000000000000000017 -:103BB0000000000000000000AAAAAAAA000000005D -:103BC000FFFF0000000000000000000000000000F7 -:103BD00000000000AAAAAAAA00000000FFFF00003F -:103BE00000000000000000000000000000000000D5 -:103BF000AAAAAAAA00000000FFFF0000000000001F -:103C0000000000000000000000000000AAAAAAAA0C -:103C100000000000FFFF00000000000000000000A6 -:103C20000000000000000000AAAAAAAA00000000EC -:103C3000FFFF000000000000000000000000000086 -:103C4000180400000000000000001A00000000003E -:103C5000FF00000000000000443900083F000000A1 -:103C6000500400004F3900083F000000009600009B -:103C7000000008009600000000080000040000009A -:103C8000A43A00080000000000000000000000004E -:0C3C900000000000000000000000000028 +:1019A000BDE81040FEF712BDB423002008B5FFF7D4 +:1019B000DDFF18B1BDE80840FFF7E4BF08BD000037 +:1019C000FFF7E0BFFEE7000010B50C4CFFF742FF49 +:1019D00000F0B4F880220A49204600F03BF80123C9 +:1019E00044F8180C037400F095FC002383F311886D +:1019F00062B60448BDE8104000F04CB8DC2300207B +:101A00004C3A00085C3A000800F01CB9EFF3118072 +:101A100020B9EFF30583202282F31188704700007C +:101A200010B530B9EFF30584C4F3080414B180F3A2 +:101A3000118810BDFFF7BAFF84F31188F9E70000A1 +:101A4000034A516853685B1A9842FBD8704700BF3D +:101A5000001000E082600222028270478368A3F1D6 +:101A60007C0243F80C2C026943F83C2C426943F891 +:101A7000382C074A43F81C2CC268A3F1180043F81D +:101A8000102C022203F8082C002203F8072C7047C0 +:101A9000E503000810B5202383F31188FFF7DEFF6C +:101AA00000210446FFF746FF002383F311882046F8 +:101AB00010BD0000024B1B6958610F20FFF70EBFDD +:101AC000B4230020202383F31188FFF7F3BF000025 +:101AD00008B50146202383F311880820FFF70CFF87 +:101AE000002383F3118808BD49B1064B42681B6986 +:101AF00018605A60136043600420FFF7FDBE4FF08A +:101B0000FF307047B42300200368984206D01A685B +:101B10000260506018465961FFF7A4BE704700008C +:101B200038B504460D462068844200D138BD0368AC +:101B300023605C604561FFF795FEF4E7054B4FF0CD +:101B4000FF3103F11402C3E905220022C3E90712A1 +:101B5000704700BFB423002070B51C4E05460C46EC +:101B6000C0E9032301F0AEFB334653F8142F9A4229 +:101B70000DD130620A2C2CBF00190A302A60C5E949 +:101B80000124C6E90555BDE8704001F085BB316A06 +:101B9000431AE31838BF1C469368A34202D90819B8 +:101BA00001F08AFB73699A6894420CD85A68AC6059 +:101BB0002B606A6015609A685D60121B9A604FF036 +:101BC000FF33F36170BDA41A1B68ECE7B423002057 +:101BD00038B51B4C636998420DD08168D0E900325A +:101BE00013605A600022C2609A680A449A604FF0FB +:101BF000FF33E36138BD03682246002142F8143FF9 +:101C000093425A60C16003D1BDE8384001F04EBB39 +:101C10009A688168256A0A449A6001F053FB6369F7 +:101C2000411B9A688A42E5D9AB181D1A206A092D12 +:101C300098BF01F10A02BDE83840104401F03CBBF6 +:101C4000B42300202DE9F041184C002704F11406BC +:101C5000656901F037FB236AAA68C11A8A4215D860 +:101C60001344D5F80C802362D5E9003213605A6022 +:101C70006369EF60B34201D101F018FB87F311886B +:101C80002869C047202383F31188E1E76169B142E5 +:101C900009D013441B1ABDE8F0410A2B2CBFC01811 +:101CA0000A3001F009BBBDE8F08100BFB423002079 +:101CB00000207047FEE70000704700004FF0FF3043 +:101CC0007047000002290CD0032904D001290748DD +:101CD00018BF00207047032A05D8054800EBC20052 +:101CE0007047044870470020704700BF403B000821 +:101CF0003C220020F43A000870B59AB00546084628 +:101D0000144601A900F0C2F801A8FFF785F8431CAA +:101D10000022C6B25B001046C5E9003423700323DD +:101D2000023404F8013C01ABD1B202348E4201D836 +:101D30001AB070BD13F8011B013204F8010C04F84D +:101D4000021CF1E708B5202383F311880348FFF74D +:101D500067FA002383F3118808BD00BF70250020B7 +:101D600090F8803003F01F02012A07D190F88120FB +:101D70000B2A03D10023C0E91D3315E003F06003F3 +:101D8000202B08D1B0F884302BB990F88120212A7B +:101D900003D81F2A04D8FFF725BA222AEBD0FAE786 +:101DA000034A426707228267C3670120704700BF6A +:101DB0003322002007B5052917D8DFE801F01916EE +:101DC00003191920202383F31188104A012101905F +:101DD000FFF7CEFA019802210D4AFFF7C9FA0D4824 +:101DE000FFF7EAF9002383F3118803B05DF804FBE1 +:101DF000202383F311880748FFF7B4F9F2E7202383 +:101E000083F311880348FFF7CBF9EBE7943A000816 +:101E1000B83A00087025002038B50C4D0C4C2A4605 +:101E20000C4904F10800FFF767FF05F1CA0204F14D +:101E300010000949FFF760FF05F5CA7204F11800A8 +:101E40000649BDE83840FFF757BF00BF483E0020B5 +:101E50003C220020743A00087E3A0008893A0008C3 +:101E600070B5044608460D46FEF7D6FFC6B22046BA +:101E7000013403780BB9184670BD32462946FEF787 +:101E8000B7FF0028F3D10120F6E700002DE9F84F55 +:101E900005460C46FEF7C0FF2A49C6B22846FFF7A2 +:101EA000DFFF08B10136F6B227492846FFF7D8FF11 +:101EB00008B11036F6B2632E0DD8DFF88890DFF83F +:101EC00088A0224FDFF88CB0DFF88C802E7846B9DE +:101ED0002670BDE8F88F29462046BDE8F84F01F08E +:101EE00085BD252E2AD1072249462846FEF780FFC8 +:101EF00050B9D8F800300735083444F8083CD8F811 +:101F0000043044F8043CE1E7082251462846FEF735 +:101F10006FFF98B9A21C0E4B197802320909C95DEE +:101F200002F8041C13F8011B01F00F015B45C95DA9 +:101F300002F8031CF0D118340835C7E7013504F85E +:101F4000016BC3E7603B0008893A0008713B000859 +:101F500000E8F11F0CE8F11F683B0008BFF34F8F4A +:101F6000044B1A695107FCD1D3F810215207F8D15C +:101F7000704700BF0020005208B50D4B1B78ABB96D +:101F8000FFF7ECFF0B4BDA68D10704D50A4A5A6019 +:101F900002F188325A60D3F80C21D20706D5064ADE +:101FA000C3F8042102F18832C3F8042108BD00BF40 +:101FB000A6400020002000522301674508B5114BC0 +:101FC0001B78F3B9104B1A69510703D5DA6842F050 +:101FD0004002DA60D3F81021520705D5D3F80C215E +:101FE00042F04002C3F80C21FFF7B8FF064BDA6855 +:101FF00042F00102DA60D3F80C2142F00102C3F88A +:102000000C2108BDA6400020002000520F289ABFD6 +:1020100000F5806040040020704700004FF400305D +:1020200070470000102070470F2808B50BD8FFF745 +:10203000EDFF00F500330268013204D10430834221 +:10204000F9D1012008BD0020FCE700000F2870B581 +:10205000054645D8FFF7DAFC224CFFF77FFF06461E +:10206000FFF78AFF4FF0FF33072D6361C4F8143187 +:1020700020D82361FFF772FF2B0243F02403E360B3 +:10208000E36843F08003E36023695A07FCD42846E1 +:10209000FFF764FF4FF40031FFF7B8FF00F002F9DB +:1020A0003046FFF78BFFFFF7BBFC2846BDE87040CA +:1020B000FFF7BABFC4F81031FFF750FFA5F10803CE +:1020C0001B0243F02403C4F80C31D4F80C3143F064 +:1020D0008003C4F80C31D4F810315B07FBD4D6E789 +:1020E000002070BD002000522DE9F84F40EA0203A5 +:1020F00005460C461746D80602D00020BDE8F88FEA +:1021000027F01F07DFF8D4B0FFF736FF2744BC42A3 +:1021100003D10120FFF752FFF0E720222946204695 +:1021200001F054FC10B920352034F0E72B4605F1BE +:1021300020021E68711CE0D104339A42F9D1FFF7E6 +:1021400065FC05F17843234AB3F5801F224B28BF75 +:102150009A4603F1040338BF9046A2F1080228BF53 +:102160009846A3F108033ABF9146DA469946FFF72D +:10217000F5FEC8F80060A5EB040CD9F8002004F1C6 +:102180001C0142F00202C9F80020221FDAF80060A8 +:1021900016F00506FAD152F8043F8A424CF8023094 +:1021A000F4D1BFF34F8FFFF7D9FE4FF0FF32C8F8DD +:1021B0000020D9F8002022F00202C9F80020FFF721 +:1021C0002FFC20222146284601F000FC0028AAD03E +:1021D00030469FE714200052102100521020005278 +:1021E00010B5084C237828B11BB9FFF7C5FE0123B1 +:1021F000237010BD002BFCD02070BDE81040FFF70D +:10220000DDBE00BFA64000200244074BD2B210B58D +:10221000904200D110BD441C00B253F8200041F898 +:10222000040BE0B2F4E700BF504000580E4B30B54D +:102230001C6F240405D41C6F1C671C6F44F40044FD +:102240001C670A4C02442368D2B243F480732360B3 +:10225000074B904200D130BD441C51F8045B00B2E2 +:1022600043F82050E0B2F4E7004402580048025816 +:102270005040005807B5012201A90020FFF7C4FF14 +:10228000019803B05DF804FB13B50446FFF7F2FFB5 +:10229000A04205D0012201A900200194FFF7C6FF4A +:1022A00002B010BD0144BFF34F8F064B884204D3E8 +:1022B000BFF34F8FBFF36F8F7047C3F85C022030BE +:1022C000F4E700BF00ED00E0034B1A681AB9034AB7 +:1022D000D2F8D0241A607047A8400020004002586D +:1022E00008B5FFF7F1FF024B1868C0F3806008BD26 +:1022F000A8400020EFF30983054968334A6B22F0B8 +:1023000001024A6383F30988002383F3118870472D +:1023100000EF00E0202080F3118862B60D4B0E4ADA +:10232000D96821F4E0610904090C0A430B49DA6019 +:10233000D3F8FC2042F08072C3F8FC20084AC2F8AF +:10234000B01F116841F0010111601022DA7783F8A3 +:102350002200704700ED00E00003FA0555CEACC541 +:10236000001000E0202310B583F311880E4B5B684A +:1023700013F4006314D0F1EE103AEFF309844FF038 +:102380008073683CE361094BDB6B236684F3098847 +:10239000FFF7ECFA10B1064BA36110BD054BFBE74C +:1023A00083F31188F9E700BF00ED00E000EF00E0E3 +:1023B000F7030008FA03000870B5BFF34F8FBFF3AF +:1023C0006F8F1A4A0021C2F85012BFF34F8FBFF32C +:1023D0006F8F536943F400335361BFF34F8FBFF3E3 +:1023E0006F8FC2F88410BFF34F8FD2F8803043F65E +:1023F000E074C3F3C900C3F34E335B0103EA040680 +:10240000014646EA81750139C2F86052F9D2203B93 +:1024100013F1200FF2D1BFF34F8F536943F4803390 +:102420005361BFF34F8FBFF36F8F70BD00ED00E0BE +:10243000FEE700000A4B0B480B4A90420BD30B4BB4 +:10244000C11EDA1C121A22F003028B4238BF00228E +:102450000021FEF7E9BC53F8041B40F8041BECE72D +:10246000543D00087C4200207C4200207C42002039 +:102470007047000070B5D0E9244300224FF0FF35CB +:102480009E6804EB42135101D3F80009002805DAD5 +:10249000D3F8000940F08040C3F80009D3F8000BDE +:1024A000002805DAD3F8000B40F08040C3F8000B99 +:1024B000013263189642C3F80859C3F8085BE0D2AA +:1024C0004FF00113C4F81C3870BD000000EB81030D +:1024D000D3F80CC02DE9F043DCF814204E1CD0F8E2 +:1024E0009050D2F800E005EB063605EB4118506835 +:1024F00070450AD30122D5F8343802FA01F123EAF3 +:102500000101C5F83418BDE8F083AEEB0003BCF858 +:102510001040A34228BF2346D8F81849A4B2B3EB11 +:10252000840FF0D89468A4F1040959F8047F376047 +:10253000A4EB09071F44042FF7D81C4403449460FC +:102540005360D4E7890141F02001016103699B06D2 +:10255000FCD41220FFF774BA10B50A4C2046FEF7DF +:10256000E5FE094BC4F89030084BC4F89430084C91 +:102570002046FEF7DBFE074BC4F89030064BC4F84C +:10258000943010BDAC40002000000840A83B00087B +:102590004841002000000440B43B000870B50378B7 +:1025A0000546012B5DD1494BD0F89040984259D156 +:1025B000474B0E216520D3F8D82042F00062C3F8C3 +:1025C000D820D3F8002142F00062C3F80021D3F8EC +:1025D0000021D3F8802042F00062C3F88020D3F8B5 +:1025E000802022F00062C3F88020D3F8803000F011 +:1025F00071FC384BE360384BC4F800380023D5F841 +:102600009060C4F8003EC02323604FF40413A3631A +:102610003369002BFCDA01230C203361FFF710FA39 +:102620003369DB07FCD41220FFF70AFA3369002B69 +:10263000FCDA00262846A660FFF71CFF6B68C4F88A +:102640001068DB68C4F81468C4F81C68002B3AD121 +:10265000224BA3614FF0FF336361A36843F0010392 +:10266000A36070BD1E4B9842C8D1194B0E214D205E +:10267000D3F8D82042F00072C3F8D820D3F8002154 +:1026800042F00072C3F80021D3F80021D3F8802073 +:1026900042F00072C3F88020D3F8802022F000724C +:1026A000C3F88020D3F88020D3F8D82022F08062AD +:1026B000C3F8D820D3F8002122F08062C3F80021AB +:1026C000D3F8003193E7074BC3E700BFAC400020CD +:1026D000004402584014004003002002003C30C077 +:1026E00048410020083C30C0F8B5D0F8904005467D +:1026F00000214FF000662046FFF724FFD5F8941024 +:1027000000234FF001128F684FF0FF30C4F83438C7 +:10271000C4F81C2804EB431201339F42C2F800693D +:10272000C2F8006BC2F80809C2F8080BF2D20B68B5 +:10273000D5F89020C5F898306362102313611669AC +:1027400016F01006FBD11220FFF77AF9D4F8003802 +:1027500023F4FE63C4F80038A36943F4402343F034 +:102760001003A3610923C4F81038C4F814380B4BC4 +:10277000EB604FF0C043C4F8103B094BC4F8003B7A +:10278000C4F81069C4F80039D5F8983003F1100284 +:1027900043F48013C5F89820A362F8BD843B000879 +:1027A00040800010D0F8902090F88A10D2F80038BD +:1027B00023F4FE6343EA0113C2F8003870470000B7 +:1027C0002DE9F84300EB8103D0F890500C46804689 +:1027D000DA680FFA81F94801166806F00306731EDD +:1027E000022B05EB41134FF0000194BFB604384EA5 +:1027F000C3F8101B4FF0010104F1100398BF06F15C +:10280000805601FA03F3916998BF06F50046002946 +:102810003AD0578A04F15801374349016F50D5F82F +:102820001C180B430021C5F81C382B180127C3F8CE +:102830001019A7405369611E9BB3138A928B9B08A2 +:10284000012A88BF5343D8F89820981842EA0343D6 +:1028500001F140022146C8F89800284605EB8202A3 +:102860005360FFF76FFE08EB8900C3681B8A43EAD9 +:10287000845348341E4364012E51D5F81C381F433D +:10288000C5F81C78BDE8F88305EB4917D7F8001B9D +:1028900021F40041C7F8001BD5F81C1821EA0303F6 +:1028A000C0E704F13F030B4A2846214605EB8303AA +:1028B0005A60FFF747FE05EB4910D0F8003923F4C2 +:1028C0000043C0F80039D5F81C3823EA0707D7E7DA +:1028D0000080001000040002D0F894201268C0F8B4 +:1028E0009820FFF7C7BD00005831D0F8903049015B +:1028F0005B5813F4004004D013F4001F0CBF0220F7 +:10290000012070474831D0F8903049015B5813F4EA +:10291000004004D013F4001F0CBF022001207047B8 +:1029200000EB8101CB68196A0B6813604B68536038 +:102930007047000000EB810330B5DD68AA691368B9 +:10294000D36019B9402B84BF402313606B8A14688D +:10295000D0F890201C4402EB4110013C09B2B4FBBA +:10296000F3F46343033323F0030343EAC44343F024 +:10297000C043C0F8103B2B6803F00303012B0ED1BA +:10298000D2F8083802EB411013F4807FD0F8003BF6 +:1029900014BF43F0805343F00053C0F8003B02EBF8 +:1029A0004112D2F8003B43F00443C2F8003B30BD73 +:1029B0002DE9F041D0F8906005460C4606EB411336 +:1029C000D3F8087B3A07C3F8087B08D5D6F8143843 +:1029D0001B0704D500EB8103DB685B689847FA07A7 +:1029E0001FD5D6F81438DB071BD505EB8403D9684F +:1029F000CCB98B69488A5A68B2FBF0F600FB162204 +:102A00008AB91868DA6890420DD2121AC3E9002414 +:102A1000202383F3118821462846FFF78BFF84F398 +:102A20001188BDE8F081012303FA04F26B8923EADF +:102A300002036B81CB68002BF3D021462846BDE80A +:102A4000F041184700EB81034A0170B5DD68D0F80A +:102A500090306C692668E66056BB1A444FF400203B +:102A6000C2F810092A6802F00302012A0AB20ED144 +:102A7000D3F8080803EB421410F4807FD4F800095F +:102A800014BF40F0805040F00050C4F8000903EB40 +:102A90004212D2F8000940F00440C2F800090122B5 +:102AA000D3F8340802FA01F10143C3F8341870BDB9 +:102AB00019B9402E84BF4020206020681A442E8A15 +:102AC0008419013CB4FBF6F440EAC44040F00050E5 +:102AD000C6E700002DE9F041D0F8906004460D46AD +:102AE00006EB4113D3F80879C3F80879FB071CD526 +:102AF000D6F81038DA0718D500EB8103D3F80CC0EC +:102B0000DCF81430D3F800E0DA6896451BD2A2EB6B +:102B10000E024FF000081A60C3F80480202383F3EC +:102B20001188FFF78FFF88F311883B0618D5012322 +:102B3000D6F83428AB40134212D029462046BDE8CF +:102B4000F041FFF7C3BC012303FA01F2038923EA32 +:102B500002030381DCF80830002BE6D09847E4E755 +:102B6000BDE8F0812DE9F84FD0F8905004466E6929 +:102B7000AB691E4016F480586E6103D0BDE8F84F73 +:102B8000FEF744BC002E12DAD5F8003E9F0705D0B0 +:102B9000D5F8003E23F00303C5F8003ED5F804380D +:102BA000204623F00103C5F80438FEF75BFC30052E +:102BB00005D52046FFF75EFC2046FEF743FCB10436 +:102BC0000CD5D5F8083813F0060FEB6823F47053D2 +:102BD0000CBF43F4105343F4A053EB60320704D509 +:102BE0006368DB680BB120469847F30200F1BA80B6 +:102BF000B70226D5D4F8909000274FF0010A09EBD0 +:102C00004712D2F8003B03F44023B3F5802F11D1D3 +:102C1000D2F8003B002B0DDA62890AFA07F322EAA8 +:102C20000303638104EB8703DB68DB6813B1394678 +:102C3000204698470137D4F89430FFB29B689F42F2 +:102C4000DDD9F00619D5D4F89000026AC2F30A174C +:102C500002F00F0302F4F012B2F5802F00F0CC80E6 +:102C6000B2F5402F09D104EB8303002200F5805018 +:102C7000DB681B6A974240F0B2803003D5F81858E1 +:102C800035D5E90303D500212046FFF791FEAA03BD +:102C900003D501212046FFF78BFE6B0303D50221EC +:102CA0002046FFF785FE2F0303D503212046FFF7BB +:102CB0007FFEE80203D504212046FFF779FEA90232 +:102CC00003D505212046FFF773FE6A0203D50621CE +:102CD0002046FFF76DFE2B0203D507212046FFF7A4 +:102CE00067FEEF0103D508212046FFF761FE700360 +:102CF00040F1A980E90703D500212046FFF7EAFE4D +:102D0000AA0703D501212046FFF7E4FE6B0703D590 +:102D100002212046FFF7DEFE2F0703D503212046C0 +:102D2000FFF7D8FEEE0603D504212046FFF7D2FEBA +:102D3000A80603D505212046FFF7CCFE690603D57A +:102D400006212046FFF7C6FE2A0603D507212046A6 +:102D5000FFF7C0FEEB0576D520460821BDE8F84F09 +:102D6000FFF7B8BED4F8909000274FF0010AD4F8CE +:102D700094305FFA87FB9B689B453FF639AF09EBC0 +:102D80004B13D3F8002902F44022B2F5802F24D14E +:102D9000D3F80029002A20DAD3F8002942F0904223 +:102DA000C3F80029D3F80029002AFBDB5946D4F8E0 +:102DB0009000FFF7C7FB22890AFA0BF322EA03030C +:102DC000238104EB8B03DB689B6813B159462046D3 +:102DD000984759462046FFF779FB0137C7E7910727 +:102DE00001D1D0F80080072A02F101029CBF03F84C +:102DF000018B4FEA18283DE704EB830300F5805070 +:102E0000DA68D2F818C0DCF80820DCE9001CA1EB75 +:102E10000C0C00218F4208D1DB689B699A683A4408 +:102E20009A605A683A445A6027E711F0030F01D1BB +:102E3000D0F800808C4501F1010184BF02F8018BBC +:102E40004FEA1828E6E7BDE8F88F000008B5034808 +:102E5000FFF788FEBDE80840FFF784BAAC400020C9 +:102E600008B50348FFF77EFEBDE80840FFF77ABAD1 +:102E700048410020D0F8903003EB4111D1F8003BDD +:102E800043F40013C1F8003B70470000D0F89030C5 +:102E900003EB4111D1F8003943F40013C1F80039B4 +:102EA00070470000D0F8903003EB4111D1F8003B9F +:102EB00023F40013C1F8003B70470000D0F89030B5 +:102EC00003EB4111D1F8003923F40013C1F80039A4 +:102ED00070470000090100F16043012203F56143DE +:102EE000C9B283F8001300F01F039A4043099B0006 +:102EF00003F1604303F56143C3F880211A60704712 +:102F000030B50433039C0172002104FB0325C1602A +:102F1000C0E90653049B0363059BC0E90000C0E9B8 +:102F20000422C0E90842C0E90A11436330BD000031 +:102F30000022416AC260C0E90411C0E90A226FF0B0 +:102F40000101FEF7EDBD0000D0E90432934201D14A +:102F5000C2680AB9181D70470020704703691960DC +:102F60000021C2680132C260C2691344826993427F +:102F7000036124BF436A0361FEF7C6BD38B504464A +:102F80000D46E3683BB162690020131D1268A3621D +:102F90001344E36207E0237A33B929462046FEF75B +:102FA000A3FD0028EDDA38BD6FF00100FBE700005B +:102FB000C368C269013BC360436913448269934299 +:102FC000436124BF436A436100238362036B03B1FF +:102FD0001847704770B52023044683F31188866A2A +:102FE0003EB9FFF7CBFF054618B186F31188284696 +:102FF00070BDA36AE26A13F8015B9342A36202D335 +:103000002046FFF7D5FF002383F31188EFE7000088 +:103010002DE9F84F04460E46174698464FF0200912 +:1030200089F311880025AA46D4F828B0BBF1000F17 +:1030300009D141462046FFF7A1FF20B18BF311884B +:103040002846BDE8F88FD4E90A12A7EB050B521AFF +:10305000934528BF9346BBF1400F1BD9334601F17E +:10306000400251F8040B914243F8040BF9D1A36AD2 +:10307000403640354033A362D4E90A239A4202D352 +:103080002046FFF795FF8AF31188BD42D8D289F315 +:103090001188C9E730465A46FDF7A0FEA36A5E4490 +:1030A0005D445B44A362E7E710B5029C0433017200 +:1030B00004FB0321C460C0E906130023C0E90A33FE +:1030C000039B0363049BC0E90000C0E90422C0E93C +:1030D0000842436310BD0000026A6FF00101C26044 +:1030E000426AC0E904220022C0E90A22FEF718BDA4 +:1030F000D0E904239A4201D1C26822B9184650F897 +:10310000043B0B607047002070470000C36800213B +:10311000C2690133C36043691344826993424361C6 +:1031200024BF436A4361FEF7EFBC000038B5044694 +:103130000D46E3683BB1236900201A1DA262E269D3 +:103140001344E36207E0237A33B929462046FEF7A9 +:10315000CBFC0028EDDA38BD6FF00100FBE7000082 +:1031600003691960C268013AC260C2691344826986 +:103170009342036124BF436A036100238362036BAC +:1031800003B118477047000070B520230D46044670 +:10319000114683F31188866A2EB9FFF7C7FF10B175 +:1031A00086F3118870BDA36A1D70A36AE26A0133B9 +:1031B0009342A36204D3E16920460439FFF7D0FFAC +:1031C000002080F31188EDE72DE9F84F04460D4605 +:1031D000904699464FF0200A8AF311880026B3469C +:1031E000A76A4FB949462046FFF7A0FF20B187F3F1 +:1031F00011883046BDE8F88FD4E90A073A1AA8EBDF +:103200000607974228BF1746402F1BD905F14003F8 +:1032100055F8042B9D4240F8042BF9D1A36A40369F +:103220004033A362D4E90A239A4204D3E1692046D9 +:103230000439FFF795FF8BF311884645D9D28AF3FD +:103240001188CDE729463A46FDF7C8FDA36A3D44FB +:103250003E443B44A362E5E7D0E904239A4217D1F8 +:10326000C3689BB1836A8BB1043B9B1A0ED0136079 +:10327000C368013BC360C3691A4483699A4202610F +:1032800024BF436A03610023836201231846704709 +:103290000023FBE700F0DAB8034B002258631A6101 +:1032A0000222DA60704700BF000C0040014B002290 +:1032B000DA607047000C0040014B5863704700BF54 +:1032C000000C0040014B586A704700BF000C0040E2 +:1032D0004B6843608B688360CB68C3600B69436154 +:1032E0004B6903628B6943620B680360704700009F +:1032F00008B53C4B40F2FF713B48D3F888200A43A5 +:10330000C3F88820D3F8882022F4FF6222F0070255 +:10331000C3F88820D3F88820D3F8E0200A43C3F804 +:10332000E020D3F808210A43C3F808212F4AD3F834 +:1033300008311146FFF7CCFF00F5806002F11C0157 +:10334000FFF7C6FF00F5806002F13801FFF7C0FF0C +:1033500000F5806002F15401FFF7BAFF00F58060CC +:1033600002F17001FFF7B4FF00F5806002F18C01FB +:10337000FFF7AEFF00F5806002F1A801FFF7A8FF9C +:1033800000F5806002F1C401FFF7A2FF00F5806044 +:1033900002F1E001FFF79CFF00F5806002F1FC0103 +:1033A000FFF796FF02F58C7100F58060FFF790FF44 +:1033B00000F000F90E4BD3F8902242F00102C3F85E +:1033C0009022D3F8942242F00102C3F894220522FD +:1033D000C3F898204FF06052C3F89C20054AC3F808 +:1033E000A02008BD0044025800000258C03B00085D +:1033F00000ED00E01F00080308B500F0C9FAFEF771 +:10340000E3FA0F4BD3F8DC2042F04002C3F8DC2093 +:10341000D3F8042122F04002C3F80421D3F8043188 +:10342000084B1A6842F008021A601A6842F0040257 +:103430001A60FEF749FFBDE80840FEF7EDBC00BF8B +:10344000004402580018024870470000114BD3F89E +:10345000E82042F00802C3F8E820D3F8102142F037 +:103460000802C3F810210C4AD3F81031D36B43F093 +:103470000803D363C722094B9A624FF0FF32DA6226 +:1034800000229A615A63DA605A6001225A611A6016 +:10349000704700BF004402580010005C000C004060 +:1034A000094A08B51169D3680B40D9B29B076FEA86 +:1034B0000101116107D5202383F31188FEF7A4FAD7 +:1034C000002383F3118808BD000C0040384B4FF0F7 +:1034D000FF31D3F88020C3F88010D3F88020002279 +:1034E000C3F88020D3F88000D3F88400C3F8841098 +:1034F000D3F88400C3F88420D3F88400D86F40F058 +:10350000FF4040F4FF0040F43F5040F03F00D867D8 +:10351000D86F20F0FF4020F4FF0020F43F5020F04F +:103520003F00D867D86FD3F888006FEA40506FEA41 +:103530005050C3F88800D3F88800C0F30A00C3F8DD +:103540008800D3F88800D3F89000C3F89010D3F81F +:103550009000C3F89020D3F89000D3F89400C3F8FB +:103560009410D3F89400C3F89420D3F89400D3F8BF +:103570009800C3F89810D3F89800C3F89820D3F8AF +:103580009800D3F88C00C3F88C10D3F88C00C3F8E3 +:103590008C20D3F88C00D3F89C00C3F89C10D3F88F +:1035A0009C10C3F89C20D3F89C3000F0C9B900BF30 +:1035B00000440258614B0122C3F80821604BD3F844 +:1035C000F42042F00202C3F8F420D3F81C2142F0A8 +:1035D0000202C3F81C210222D3F81C31594BDA60D5 +:1035E0005A689104FCD5584A1A6001229A60574AD9 +:1035F000DA6000221A614FF440429A61514B9A6995 +:103600009204FCD51A6842F480721A604C4B1A6F0F +:1036100012F4407F04D04FF480321A6700221A67F8 +:103620001A6842F001021A60454B1A685007FCD52F +:1036300000221A611A6912F03802FBD101211960C7 +:103640004FF0804159605A67414ADA62414A1A6133 +:103650001A6842F480321A60394B1A689103FCD51B +:103660001A6842F480521A601A689204FCD53A4AE9 +:103670003A499A6200225A6319633949DA639963B5 +:103680005A64384A1A64384ADA621A6842F0A85210 +:103690001A602B4B1A6802F02852B2F1285FF9D158 +:1036A00048229A614FF48862DA6140221A622F4AF6 +:1036B000DA644FF080521A652D4A5A652D4A9A6590 +:1036C00032232D4A1360136803F00F03022BFAD143 +:1036D0001B4B1A6942F003021A611A6902F03802A0 +:1036E000182AFAD1D3F8DC2042F00052C3F8DC20CB +:1036F000D3F8042142F00052C3F80421D3F8042186 +:10370000D3F8DC2042F08042C3F8DC20D3F8042157 +:1037100042F08042C3F80421D3F80421D3F8DC201E +:1037200042F00042C3F8DC20D3F8042142F000420A +:10373000C3F80421D3F80431704700BF0080005162 +:10374000004402580048025800C000F00200000186 +:103750000000FF0100889008121020006302090198 +:103760002C02040047040508FD0BFF012000002087 +:103770000010E00000010100002000524FF0B042B4 +:1037800008B5D2F8883003F00103C2F8883023B1BD +:10379000044A13680BB150689847BDE80840FEF72B +:1037A000E1BD00BFFC4100204FF0B04208B5D2F8A7 +:1037B000883003F00203C2F8883023B1044A9368CA +:1037C0000BB1D0689847BDE80840FEF7CBBD00BFFD +:1037D000FC4100204FF0B04208B5D2F8883003F029 +:1037E0000403C2F8883023B1044A13690BB150694D +:1037F0009847BDE80840FEF7B5BD00BFFC4100207A +:103800004FF0B04208B5D2F8883003F00803C2F890 +:10381000883023B1044A93690BB1D0699847BDE859 +:103820000840FEF79FBD00BFFC4100204FF0B042B2 +:1038300008B5D2F8883003F01003C2F8883023B1FD +:10384000044A136A0BB1506A9847BDE80840FEF776 +:1038500089BD00BFFC4100204FF0B04310B5D3F844 +:10386000884004F47872C3F88820A30604D5124A6D +:10387000936A0BB1D06A9847600604D50E4A136B61 +:103880000BB1506B9847210604D50B4A936B0BB1D3 +:10389000D06B9847E20504D5074A136C0BB1506C06 +:1038A0009847A30504D5044A936C0BB1D06C984794 +:1038B000BDE81040FEF756BDFC4100204FF0B0437C +:1038C00010B5D3F8884004F47C42C3F88820620520 +:1038D00004D5164A136D0BB1506D9847230504D5D6 +:1038E000124A936D0BB1D06D9847E00404D50F4A8E +:1038F000136E0BB1506E9847A10404D50B4A936E1A +:103900000BB1D06E9847620404D5084A136F0BB10F +:10391000506F9847230404D5044A936F0BB1D06FBE +:103920009847BDE81040FEF71DBD00BFFC410020D8 +:1039300008B5FFF7B5FDBDE80840FEF713BD000070 +:10394000062108B50846FFF7C5FA06210720FFF74C +:10395000C1FA06210820FFF7BDFA06210920FFF76A +:10396000B9FA06210A20FFF7B5FA06211720FFF75A +:10397000B1FA06212820FFF7ADFA09217A20FFF7D6 +:10398000A9FA07213220BDE80840FFF7A3BA0000DA +:1039900008B5FFF79BFD00F00BF8FDF7C5FCFDF740 +:1039A00097FBFFF751FDBDE80840FFF773BC00002F +:1039B0000023054A19460133102BC2E9001102F118 +:1039C0000802F8D1704700BFFC41002010B5013952 +:1039D0000244904201D1002005E0037811F8014F24 +:1039E000A34201D0181B10BD0130F2E7034611F8C5 +:1039F000012B03F8012B002AF9D1704753544D33A2 +:103A00003248373F3F3F0053544D33324837343309 +:103A10002F37353300000000000000004D10000873 +:103A20003910000875100008611000086D100008BA +:103A300059100008451000083110000881100008D6 +:103A40000000000001000000000000006D61696ED0 +:103A50000000000069646C6500000000543A000832 +:103A6000F82300207025002001000000C51900087F +:103A7000000000004172647550696C6F740025424B +:103A80004F415244252D424C002553455249414C4B +:103A90002500000002000000000000006D12000878 +:103AA000DD12000840004000183E0020283E0020A3 +:103AB0000200000000000000030000000000000001 +:103AC000251300080000000010000000383E002010 +:103AD000000000000100000000000000AC400020D9 +:103AE00001010200B51D0008C51C0008611D000889 +:103AF000451D000843000000FC3A0008090243008D +:103B0000020100C032090400000102020100052484 +:103B1000001001052401000104240202052406000E +:103B200001070582030800FF09040100020A0000E2 +:103B30000007050102400000070581024000000067 +:103B400012000000483B0008120110010200004072 +:103B50000912415700020102030100000403090495 +:103B600025424F41524425004B616B7574654837BF +:103B700000303132333435363738394142434445E9 +:103B8000460000000000000079140008311700080A +:103B9000DD17000840004000E4410020E44100201F +:103BA00001000000F44100208000000040010000FE +:103BB00008000000000100000004000008000000F0 +:103BC0000001802A00000000AAAAAAAA000100247D +:103BD000FFFF00000000000000A00A00000000013C +:103BE00000000000AAAAAAAA00000001FFFF00002E +:103BF00000000000000000001000000400000000B1 +:103C0000AAAAAAAA00000008FBDF0000000000002A +:103C1000000000000000000000000000AAAAAAAAFC +:103C200000000000FFFF0000000000000000000096 +:103C30000001000000000000AAAAAAAA00010000DA +:103C4000FFFF000000000000000000000000000076 +:103C500000000000AAAAAAAA00000000FFFF0000BE +:103C60000000000000000000000000000000000054 +:103C7000AAAAAAAA00000000FFFF0000000000009E +:103C8000000000000000000000000000AAAAAAAA8C +:103C900000000000FFFF0000000000000000000026 +:103CA0000000000000000000AAAAAAAA000000006C +:103CB000FFFF000000000000000000000000000006 +:103CC00000000000AAAAAAAA00000000FFFF00004E +:103CD00000000000000000000000000000000000E4 +:103CE000AAAAAAAA00000000FFFF0000000000002E +:103CF00000000000000000001804000000000000A8 +:103D000000001A0000000000FF000000000000009A +:103D1000FC3900083F00000050040000073A00088A +:103D20003F00000000960000000008009600000020 +:103D300000080000040000005C3B000800000000D8 +:103D40000000000000000000000000000000000073 +:043D5000000000006F :00000001FF diff --git a/Tools/bootloaders/KakuteH7v2_bl.bin b/Tools/bootloaders/KakuteH7v2_bl.bin new file mode 100644 index 00000000000..0575260833c Binary files /dev/null and b/Tools/bootloaders/KakuteH7v2_bl.bin differ diff --git a/Tools/bootloaders/KakuteH7v2_bl.hex b/Tools/bootloaders/KakuteH7v2_bl.hex new file mode 100644 index 00000000000..c423f0fc3e9 --- /dev/null +++ b/Tools/bootloaders/KakuteH7v2_bl.hex @@ -0,0 +1,983 @@ +:020000040800F2 +:1000000000060020A1020008AD0F00082D0F000817 +:10001000850F00082D0F0008590F0008A3020008E3 +:10002000A3020008A3020008A3020008FD220008A2 +:10003000A3020008A3020008A3020008A30200080C +:10004000A3020008A3020008A3020008A3020008FC +:10005000A3020008A30200086D37000899370008C2 +:10006000C5370008F13700081D380008A302000852 +:10007000A3020008A3020008A3020008A3020008CC +:10008000A3020008A3020008A3020008A3020008BC +:10009000A3020008A3020008A302000849380008D0 +:1000A000A3020008A3020008A3020008A30200089C +:1000B000A3020008A3020008A3020008A30200088C +:1000C000A3020008A3020008A3020008A30200087C +:1000D000A3020008A3020008A3020008A30200086C +:1000E000AD380008A3020008A3020008A30200081C +:1000F000A3020008A3020008A3020008A30200084C +:10010000A3020008A302000821390008A302000886 +:10011000A3020008A3020008A3020008A30200082B +:10012000A3020008A3020008A3020008A30200081B +:10013000A3020008A3020008A3020008A30200080B +:10014000A3020008A3020008A3020008A3020008FB +:10015000A3020008A3020008A3020008A3020008EB +:10016000A3020008A3020008A3020008A3020008DB +:10017000A3020008692E0008A3020008A3020008D9 +:10018000A3020008A3020008A3020008A3020008BB +:10019000A3020008A3020008A3020008A3020008AB +:1001A000A3020008A3020008A3020008A30200089B +:1001B000A3020008A3020008A3020008A30200088B +:1001C000A3020008A3020008A3020008A30200087B +:1001D000A3020008552E0008A3020008A30200088D +:1001E000A3020008A3020008A3020008A30200085B +:1001F000A3020008A3020008A3020008A30200084B +:10020000A3020008A3020008A3020008A30200083A +:10021000A3020008A3020008A3020008A30200082A +:10022000A3020008A3020008A3020008A30200081A +:10023000A3020008A3020008A3020008A30200080A +:10024000A3020008A3020008A3020008A3020008FA +:10025000A3020008A3020008A3020008A3020008EA +:10026000A3020008A3020008A3020008A3020008DA +:10027000A3020008A3020008A3020008A3020008CA +:10028000A3020008A3020008A3020008A3020008BA +:10029000A3020008A3020008A3020008A3020008AA +:1002A00002E000F000F8FEE772B63A4880F30888F2 +:1002B000394880F3098839484EF60851CEF20001DA +:1002C000086040F20000CCF200004EF63471CEF22D +:1002D00000010860BFF34F8FBFF36F8F40F2000043 +:1002E000C0F2F0004EF68851CEF200010860BFF374 +:1002F0004F8FBFF36F8F4FF00000E1EE100A4EF604 +:100300003C71CEF200010860062080F31488BFF330 +:100310006F8F02F0B1F802F053F802F0EDFF4FF0EA +:1003200055301F491B4A91423CBF41F8040BFAE784 +:100330001C49194A91423CBF41F8040BFAE71A499B +:100340001A4A1B4B9A423EBF51F8040B42F8040B69 +:10035000F8E700201749184A91423CBF41F8040BC6 +:10036000FAE702F06BF803F03FF8144C144DAC427E +:1003700003DA54F8041B8847F9E700F041F8114C00 +:10038000114DAC4203DA54F8041B8847F9E702F038 +:1003900053B80000000600200022002000000008E2 +:1003A0000000002000060020E83C00080022002099 +:1003B0005C220020602200207C420020A002000875 +:1003C000A0020008A0020008A00200082DE9F04FDA +:1003D0002DED108AC1F80CD0D0F80CD0BDEC108AED +:1003E000BDE8F08F002383F311882846A047002042 +:1003F00001F068FBFEE701F0E3FA00DFFEE7000032 +:1004000038B500F0CDFC30B1164B00220E211A7227 +:100410005A729972DA7201F031FF054601F064FFF9 +:100420000446D0B9104B9D4219D001339D4241F290 +:10043000883512BF044600250124002001F028FF62 +:100440000CB100F059F800F045FD00F0E3FB284640 +:1004500000F004F900F050F8F9E70025EDE7054653 +:10046000EBE700BF00220020010007B008B500F054 +:10047000A3FBA0F120035842584108BD07B541F243 +:100480001203022101A8ADF8043000F0B3FB03B061 +:100490005DF804FB202310B583F311881248C3686C +:1004A0000BB101F095FB0023104A4FF47A710E480E +:1004B00001F052FB002383F311880D4C236813B124 +:1004C0002368013B2360636813B16368013B636089 +:1004D000084B1B7833B9636823B9022000F074FC21 +:1004E0003223636010BD00BF602200209504000825 +:1004F0007C23002074220020F8B5514B514A1C4641 +:100500001968013100F09B8004339342F8D162688E +:100510004D4B9A4240F293804C4B9B6803F1006331 +:1005200003F500339A4280F08A80002000F098FBA7 +:100530000220474B187000F03DFC464B0021D3F8D9 +:10054000E820C3F8E810D3F81021C3F81011D3F84D +:100550001021D3F8EC20C3F8EC10D3F81421C3F821 +:100560001411D3F81421D3F8F020C3F8F010D3F805 +:100570001821C3F81811D3F81821D3F8802042F0BD +:100580000062C3F88020D3F8802022F00062C3F814 +:100590008020D3F88020D3F8802042F00072C3F886 +:1005A0008020D3F8802022F00072C3F88020D3F896 +:1005B000803072B64FF0E023C3F8084DD4E9000450 +:1005C000BFF34F8FBFF36F8F234AC2F88410BFF37E +:1005D0004F8F536923F480335361BFF34F8FD2F8A9 +:1005E000803043F6E076C3F3C905C3F34E335B01B5 +:1005F00003EA060C29464CEA81770139C2F8747285 +:10060000F9D2203B13F1200FF2D1BFF34F8FBFF38C +:100610006F8FBFF34F8FBFF36F8F536923F4003396 +:1006200053610023C2F85032BFF34F8FBFF36F8F77 +:10063000202383F31188854680F308882047F8BD7E +:100640000000020820000208FFFF0108002200202D +:10065000742200200044025800ED00E02DE9F04F24 +:1006600093B0A94B2022FF2100900AA89D6800F0BA +:10067000DBFBA64A1378A3B90121A5481170C3601A +:10068000202383F31188C3680BB101F0A1FA002382 +:10069000A04A4FF47A719E4801F05EFA002383F37A +:1006A0001188009B9C4A03B1136000239B49009C66 +:1006B00098469B461E469A460B705360012000F0F8 +:1006C00079FB24B1944B1B68002B00F016820020AC +:1006D00000F072FA0390039B002BF2DB012000F084 +:1006E00061FB039B213B162BE8D801A252F823F0B3 +:1006F0004D0700087507000809080008BD06000836 +:10070000BD060008BD0600089D0800086F0A000825 +:1007100089090008EB090008130A0008390A0008D3 +:10072000BD0600084B0A0008BD060008BD0A000807 +:10073000ED070008BD060008010B00085907000876 +:10074000ED070008BD060008EB0900080220FFF7CE +:100750008DFE002840F0FB81009B022105A8B8F126 +:10076000000F08BF1C4641F21233ADF8143000F000 +:1007700041FAA3E74FF47A7000F01EFA071EEBDB94 +:100780000220FFF773FE0028E6D0013F052F00F29C +:10079000E081DFE807F0030A0D101336052304217A +:1007A00005A8059300F026FA17E004215648F9E75A +:1007B00004215B48F6E704215A48F3E74FF01C098F +:1007C000484609F1040900F04DFA0421059005A8F6 +:1007D00000F010FAB9F12C0FF2D101204FF0000A0D +:1007E00000FA07F747EA0B0B5FFA8BFB00F068FB98 +:1007F00026B10BF00B030B2B08BF0024FFF73EFEC6 +:100800005CE704214848CDE7002EA5D00BF00B0390 +:100810000B2BA1D10220FFF729FE074600289BD011 +:1008200001203E4E00F01CFA4FF00008022030700C +:1008300000F0C0FA5FFA88F9484600F021FA044651 +:1008400090B1484608F1010800F02AFA0028F1D1D9 +:10085000B846044641F21213022105A83E46ADF8FF +:10086000143000F0C7F929E7012325460220337030 +:1008700000F098FA244B9B68AB4207D9284600F059 +:10088000F1F9013040F068810435F3E70025234B8E +:10089000B8463E461D70204B5D60A7E7002E3FF432 +:1008A0005BAF0BF00B030B2B7FF456AF02201B4BFF +:1008B000187000F07FFA322000F07EF9B0F10009E4 +:1008C000FFF64AAF19F003077FF446AF0E4A09EB73 +:1008D0000503926893423FF63FAFB9F5807F3FF73B +:1008E0003BAF124BB945019322DD4FF47A7000F013 +:1008F00063F90390039A002AFFF62EAF039A01379B +:10090000019B03F8012BEDE7002200207823002053 +:1009100060220020950400087C230020742200201F +:1009200004220020082200200C220020782200202F +:10093000C820FFF79BFD074600283FF40DAF1F2D91 +:1009400011D8C5F120020AAB25F0030084494A45BD +:10095000184428BF4A46019200F040FA019AFF214C +:100960007F4800F061FA4FEAA903C9F387027C4986 +:100970002846019300F060FA064600283FF46AAF6B +:10098000019B05EB830531E70220FFF76FFD00288F +:100990003FF4E2AE00F0A0F900283FF4DDAE0027FE +:1009A000B946704B9B68BB4218D91F2F11D80A9BC0 +:1009B00001330ED027F0030312AA134453F8203C4E +:1009C00005934846042205A9043700F0F1FA814650 +:1009D000E7E7384600F046F90590F2E7CDF81490C5 +:1009E000042105A800F006F900E70023642104A80B +:1009F000049300F0F5F800287FF4AEAE0220FFF774 +:100A000035FD00283FF4A8AE049800F05BF905908E +:100A1000E6E70023642104A8049300F0E1F800282D +:100A20007FF49AAE0220FFF721FD00283FF494AE38 +:100A3000049800F049F9EAE70220FFF717FD0028C3 +:100A40003FF48AAE00F058F9E1E70220FFF70EFD0F +:100A500000283FF481AE05A9142000F053F90746A1 +:100A60000421049004A800F0C5F83946B9E7322003 +:100A700000F0A2F8071EFFF66FAEBB077FF46CAE66 +:100A8000384A07EB0A03926893423FF665AE0220AC +:100A9000FFF7ECFC00283FF45FAE27F00307574454 +:100AA000BA453FF4A3AE50460AF1040A00F0DAF862 +:100AB0000421059005A800F09DF8F1E74FF47A7045 +:100AC000FFF7D4FC00283FF447AE00F005F90028FA +:100AD00044D00A9B01330BD008220AA9002000F061 +:100AE000ABF900283AD02022FF210AA800F09CF997 +:100AF000FFF7C4FC1C4800F0EBFF13B0BDE8F08F1B +:100B0000002E3FF429AE0BF00B030B2B7FF424AE29 +:100B10000023642105A8059300F062F80746002829 +:100B20007FF41AAE0220FFF7A1FC814600283FF4B3 +:100B300013AEFFF7A3FC41F2883000F0C9FF05981F +:100B400000F0F2F94E463C4600F0BAF9B6E506462A +:100B50004CE64FF0000AFFE5B8467BE6374679E6FB +:100B60007822002000220020A08601000F4B70B5E3 +:100B70001B780C460133DBB2012B11D80C4D4FF41E +:100B80007A732968A2FB033222460E6A0146284680 +:100B9000B047844204D1074B002201201A7070BD77 +:100BA0004FF4FA7000F094FF0020F8E710220020C4 +:100BB00070250020B0230020002307B50246012144 +:100BC0000DF107008DF80730FFF7D0FF20B19DF839 +:100BD000070003B05DF804FB4FF0FF30F9E70000B9 +:100BE0000A46042108B5FFF7C1FF80F00100C0B23A +:100BF000404208BD30B4054C0A46014623682046F1 +:100C0000DD69034BAC4630BC604700BF7025002057 +:100C1000A086010070B5104C0025104E01F006FAB8 +:100C200020803068238883420CD800252088013832 +:100C300001F0F8F923880544013BB5F5802F2380A6 +:100C4000F4D370BD01F0EEF9336805440133B5F516 +:100C5000003F3360E5D3E8E7B2230020842300207F +:100C600001F0C2BA00F1006000F500300068704782 +:100C700000F10060920000F5003001F039BA000088 +:100C8000054B1A68054B1B889B1A834202D91044F6 +:100C900001F0C8B90020704784230020B22300204F +:100CA00038B5074D04462868204401F0C1F928B939 +:100CB00028682044BDE8384001F0CCB938BD00BFF9 +:100CC000842300200020704700F1FF5000F58F10B2 +:100CD000D0F8000870470000064991F8243033B17D +:100CE00000230822086A81F82430FFF7C1BF0120E1 +:100CF000704700BF88230020014B1868704700BF71 +:100D00000010005C244BF0B51A680446234BC2F374 +:100D10000B06120C1F885868BE4293F9085028D061 +:100D20009F89BE4206D101200C2505FB003358687F +:100D300093F9085041F201039A421CD041F2030397 +:100D40009A421AD042F201039A4218D042F20303A7 +:100D50009A4208BF5625621E0B46441E0A4493421F +:100D60000FD214F9016F581C6EB1034600F8016CE4 +:100D7000F5E70020D8E75A25EDE75925EBE7582598 +:100D8000E9E7184605E02C2482421C7001D9981C22 +:100D90005D70401AF0BD00BF0010005C14220020FE +:100DA00000207047022802D1014B04229A6170474B +:100DB00000080258022803D1024B4FF480229A61A6 +:100DC000704700BF00080258022804D1024A536944 +:100DD00083F004035361704700080258002310B5E4 +:100DE000934203D0CC5CC4540133F9E710BD00003A +:100DF000013810B510F9013F3BB191F900409C4218 +:100E000003D11AB10131013AF4E71AB191F9002086 +:100E1000981A10BD1046FCE703460246D01A12F994 +:100E2000011B0029FAD1704702440346934202D0C5 +:100E300003F8011BFAE770472DE9F8431F4D1446EC +:100E40000746884695F8242052BBDFF870909CB383 +:100E500095F824302BB92022FF2148462F62FFF756 +:100E6000E3FF95F824004146C0F1080205EB80003D +:100E7000A24228BF2246D6B29200FFF7AFFF95F8F4 +:100E80002430A41B17441E449044E4B2F6B2082E4A +:100E900085F82460DBD1FFF71FFF0028D7D108E0D9 +:100EA0002B6A03EB82038342CFD0FFF715FF0028A4 +:100EB000CBD10020BDE8F8830120FBE78823002088 +:100EC000024B1A78024B1A70704700BFB023002003 +:100ED0001022002010B5104C104800F0FBF82146FD +:100EE0000E4800F023F924680D48D4F89020D2F879 +:100EF000043843F00203C2F8043800F0E9FD094960 +:100F0000204600F021FAD4F89020D2F8043823F0DB +:100F10000203C2F8043810BDCC3A00087025002046 +:100F200040420F00D43A00087047000000B59BB063 +:100F3000EFF3098168226846FFF750FFEFF305835E +:100F4000044B9A6BDA6A9A6A9A6A9A6A9A6A9A6AF5 +:100F50009B6AFEE700ED00E000B59BB0EFF309816E +:100F600068226846FFF73AFFEFF30583044B9A6B5C +:100F70009A6A9A6A9A6A9A6A9A6A9B6AFEE700BFB4 +:100F800000ED00E000B59BB0EFF3098168226846F0 +:100F9000FFF724FFEFF30583034B5A6B9A6A9A6AB3 +:100FA0009A6A9A6A9B6AFEE700ED00E0FEE700009D +:100FB00030B50A44084D91420DD011F8013B58401C +:100FC000082340F30004013B2C4013F0FF0384EAA4 +:100FD0005000F6D1EFE730BD2083B8ED02684368DA +:100FE0001143016003B118477047000013B5406B0F +:100FF00000F58054D4F8A4381A681178042914D163 +:10100000017C022911D11979012312898B401342E5 +:101010000BD101A94C3002F06FF8D4F8A448024675 +:10102000019B2179206800F0DFF902B010BD0000BB +:10103000143001F0F1BF00004FF0FF33143001F025 +:10104000EBBF00004C3002F0C3B800004FF0FF339C +:101050004C3002F0BDB80000143001F0BFBF0000FA +:101060004FF0FF31143001F0B9BF00004C3002F0F6 +:101070008FB800004FF0FF324C3002F089B800000A +:101080000020704710B500F58054D4F8A4381A68D1 +:101090001178042917D1017C022914D1597901232F +:1010A00052898B4013420ED1143001F051FF024699 +:1010B00048B1D4F8A4484FF4407361792068BDE882 +:1010C000104000F07FB910BD406BFFF7DBBF0000A0 +:1010D000704700007FB5124B0125042604460360CB +:1010E0000023057400F1840243602946C0E90233FD +:1010F0000C4B0290143001934FF44073009601F0B2 +:1011000003FF094B04F69442294604F14C00029473 +:10111000CDE900634FF4407301F0CAFF04B070BD25 +:10112000083A0008C9100008ED0F00080A682023DB +:1011300083F311880B790B3342F823004B79133377 +:1011400042F823008B7913B10B3342F8230000F5EA +:101150008053C3F8A41802230374002383F3118877 +:101160007047000038B5037F044613B190F854303F +:10117000ABB90125201D0221FFF730FF04F1140057 +:101180006FF00101257700F0CBFC04F14C0084F8EE +:1011900054506FF00101BDE8384000F0C1BC38BDCB +:1011A00010B5012104460430FFF718FF0023237710 +:1011B00084F8543010BD000038B5044600251430C2 +:1011C00001F0BAFE04F14C00257701F089FF201DE3 +:1011D00084F854500121FFF701FF2046BDE8384054 +:1011E000FFF750BF90F8803003F06003202B06D14A +:1011F00090F881200023212A03D81F2A06D8002036 +:101200007047222AFBD1C0E91D3303E0034A42673D +:1012100007228267C3670120704700BF2C2200208D +:1012200037B500F58055D5F8A4381A681178042927 +:101230001AD1017C022917D11979012312898B4017 +:10124000134211D100F14C04204602F009F858B1C4 +:1012500001A9204601F050FFD5F8A4480246019BA1 +:101260002179206800F0C0F803B030BD01F10B0314 +:10127000F0B550F8236085B004460D46FEB120233A +:1012800083F3118804EB8507301D0821FFF7A6FEC4 +:10129000FB6806F14C005B691B681BB1019001F013 +:1012A00039FF019803A901F027FF024648B1039BCB +:1012B0002946204600F098F8002383F3118805B0F2 +:1012C000F0BDFB685A691268002AF5D01B8A013B01 +:1012D0001340F1D104F18002EAE70000133138B580 +:1012E00050F82140ECB1202383F3118804F580539A +:1012F000D3F8A4281368527903EB8203DB689B6957 +:101300005D6845B104216018FFF768FE294604F1C5 +:10131000140001F027FE2046FFF7B4FE002383F3FC +:10132000118838BD7047000001F01AB9012340222E +:10133000002110B5044600F8303BFFF775FD00238F +:10134000C4E9013310BD000010B52023044683F327 +:1013500011882422416000210C30FFF765FD2046F2 +:1013600001F020F902232370002383F3118810BDBC +:1013700070B500EB8103054650690E461446DA60ED +:1013800018B110220021FFF74FFDA06918B11022FB +:101390000021FFF749FD31462846BDE8704001F0C5 +:1013A00013BA000083682022002103F0011310B556 +:1013B000044683601030FFF737FD2046BDE810403B +:1013C00001F08EBAF0B4012500EB810447898D400D +:1013D000E4683D43A469458123600023A260636003 +:1013E000F0BC01F0ABBA0000F0B4012500EB8104C1 +:1013F00007898D40E4683D436469058123600023CB +:10140000A2606360F0BC01F021BB000070B5022354 +:1014100000250446242203702946C0F888500C3069 +:1014200040F8045CFFF700FD204684F8705001F09E +:101430005FF963681B6823B129462046BDE8704008 +:10144000184770BD037880F88C300523037043681B +:101450001B6810B504460BB1042198470023A36014 +:1014600010BD000090F88C20436802701B680BB11F +:10147000052118477047000070B590F87030044699 +:1014800013B1002380F8703004F18002204601F08F +:101490004BFA63689B68B3B994F8803013F0600529 +:1014A00035D00021204601F0F5FC0021204601F056 +:1014B000E5FC63681B6813B10621204698470623A4 +:1014C00084F8703070BD204698470028E4D0B4F806 +:1014D0008630A26F9A4288BFA36794F98030A56FC7 +:1014E000002B4FF0200380F20381002D00F0F280EA +:1014F000092284F8702083F3118800212046D4E962 +:101500001D23FFF771FF002383F31188DAE794F8B6 +:10151000812003F07F0343EA022340F20232934228 +:1015200000F0C58021D8B3F5807F48D00DD8012BBD +:101530003FD0022B00F09380002BB2D104F188023F +:1015400062670222A267E367C1E7B3F5817F00F01B +:101550009B80B3F5407FA4D194F88230012BA0D1B9 +:10156000B4F8883043F0020332E0B3F5006F4DD099 +:1015700017D8B3F5A06F31D0A3F5C063012B90D875 +:101580006368204694F882205E6894F88310B4F86B +:101590008430B047002884D0436863670368A3673A +:1015A0001AE0B3F5106F36D040F6024293427FF452 +:1015B00078AF5C4B63670223A3670023C3E794F80B +:1015C0008230012B7FF46DAFB4F8883023F0020332 +:1015D000A4F88830C4E91D55E56778E7B4F8803091 +:1015E000B3F5A06F0ED194F88230204684F88A308B +:1015F00001F0DCF863681B6813B1012120469847AD +:10160000032323700023C4E91D339CE704F18B03FB +:1016100063670123C3E72378042B10D1202383F3CE +:1016200011882046FFF7BEFE85F311880321636809 +:1016300084F88B5021701B680BB12046984794F8B2 +:101640008230002BDED084F88B3004232370636853 +:101650001B68002BD6D0022120469847D2E794F889 +:10166000843020461D0603F00F010AD501F04EF923 +:10167000012804D002287FF414AF2B4B9AE72B4BA0 +:1016800098E701F035F9F3E794F88230002B7FF406 +:1016900008AF94F8843013F00F01B3D01A06204637 +:1016A00002D501F00FFCADE701F000FCAAE794F8C9 +:1016B0008230002B7FF4F5AE94F8843013F00F01E4 +:1016C000A0D01B06204602D501F0E4FB9AE701F00A +:1016D000D5FB97E7142284F8702083F311882B46FA +:1016E0002A4629462046FFF76DFE85F31188E9E674 +:1016F0005DB1152284F8702083F311880021204603 +:10170000D4E91D23FFF75EFEFDE60B2284F870206E +:1017100083F311882B462A4629462046FFF764FEAC +:10172000E3E700BF383A0008303A0008343A0008CE +:1017300038B590F870300446002B3ED0063BDAB244 +:101740000F2A34D80F2B32D8DFE803F037313108B5 +:10175000223231313131313131313737856FB0F8A3 +:1017600086309D4214D2C3681B8AB5FBF3F203FB9B +:1017700012556DB9202383F311882B462A4629463A +:10178000FFF732FE85F311880A2384F870300EE0EB +:10179000142384F87030202383F31188002320461B +:1017A0001A461946FFF70EFE002383F3118838BD51 +:1017B000C36F03B198470023E7E70021204601F0FB +:1017C00069FB0021204601F059FB63681B6813B1D7 +:1017D0000621204698470623D7E7000010B590F869 +:1017E00070300446142B29D017D8062B05D001D809 +:1017F0001BB110BD093B022BFBD80021204601F094 +:1018000049FB0021204601F039FB63681B6813B1D6 +:10181000062120469847062319E0152BE9D10B2312 +:1018200080F87030202383F3118800231A4619466C +:10183000FFF7DAFD002383F31188DAE7C3689B69B9 +:101840005B68002BD5D1C36F03B19847002384F8A0 +:101850007030CEE7024B0022C3E900339A60704734 +:10186000B4230020002382680374054B1B68996829 +:101870009142FBD25A680360426010605860704722 +:10188000B423002008B5202383F31188037C032BA5 +:1018900005D0042B0DD02BB983F3118808BD436903 +:1018A00000221A604FF0FF334361FFF7DBFF002394 +:1018B000F2E7D0E9003213605A60F3E70023826850 +:1018C0000374054B1B6899689142FBD85A68036002 +:1018D0004260106058607047B4230020054B1969BE +:1018E00008741868026853601A6018610123037451 +:1018F000FEF76CBDB42300204B1C30B5044687B006 +:101900000A4D10D02B6901A8094A00F025F920469C +:10191000FFF7E4FF049B13B101A800F059F92B690C +:10192000586907B030BDFFF7D9FFF8E7B4230020AE +:101930008518000838B50C4D044641612B69816853 +:101940009A68914203D8BDE83840FFF78BBF18462C +:10195000FFF7B4FF01232C61014623742046BDE844 +:101960003840FEF733BD00BFB4230020044B1A6893 +:101970001B6990689B68984294BF002001207047C3 +:10198000B423002010B5084C236820691A685460FD +:101990002260012223611A74FFF790FF014620693B +:1019A000BDE81040FEF712BDB423002008B5FFF7D4 +:1019B000DDFF18B1BDE80840FFF7E4BF08BD000037 +:1019C000FFF7E0BFFEE7000010B50C4CFFF742FF49 +:1019D00000F0B4F880220A49204600F03BF80123C9 +:1019E00044F8180C037400F099FC002383F3118869 +:1019F00062B60448BDE8104000F04CB8DC2300207B +:101A00003C3A00084C3A000800F01CB9EFF3118092 +:101A100020B9EFF30583202282F31188704700007C +:101A200010B530B9EFF30584C4F3080414B180F3A2 +:101A3000118810BDFFF7BAFF84F31188F9E70000A1 +:101A4000034A516853685B1A9842FBD8704700BF3D +:101A5000001000E082600222028270478368A3F1D6 +:101A60007C0243F80C2C026943F83C2C426943F891 +:101A7000382C074A43F81C2CC268A3F1180043F81D +:101A8000102C022203F8082C002203F8072C7047C0 +:101A9000E503000810B5202383F31188FFF7DEFF6C +:101AA00000210446FFF746FF002383F311882046F8 +:101AB00010BD0000024B1B6958610F20FFF70EBFDD +:101AC000B4230020202383F31188FFF7F3BF000025 +:101AD00008B50146202383F311880820FFF70CFF87 +:101AE000002383F3118808BD49B1064B42681B6986 +:101AF00018605A60136043600420FFF7FDBE4FF08A +:101B0000FF307047B42300200368984206D01A685B +:101B10000260506018465961FFF7A4BE704700008C +:101B200038B504460D462068844200D138BD0368AC +:101B300023605C604561FFF795FEF4E7054B4FF0CD +:101B4000FF3103F11402C3E905220022C3E90712A1 +:101B5000704700BFB423002070B51C4E05460C46EC +:101B6000C0E9032301F0B2FB334653F8142F9A4225 +:101B70000DD130620A2C2CBF00190A302A60C5E949 +:101B80000124C6E90555BDE8704001F089BB316A02 +:101B9000431AE31838BF1C469368A34202D90819B8 +:101BA00001F08EFB73699A6894420CD85A68AC6055 +:101BB0002B606A6015609A685D60121B9A604FF036 +:101BC000FF33F36170BDA41A1B68ECE7B423002057 +:101BD00038B51B4C636998420DD08168D0E900325A +:101BE00013605A600022C2609A680A449A604FF0FB +:101BF000FF33E36138BD03682246002142F8143FF9 +:101C000093425A60C16003D1BDE8384001F052BB35 +:101C10009A688168256A0A449A6001F057FB6369F3 +:101C2000411B9A688A42E5D9AB181D1A206A092D12 +:101C300098BF01F10A02BDE83840104401F040BBF2 +:101C4000B42300202DE9F041184C002704F11406BC +:101C5000656901F03BFB236AAA68C11A8A4215D85C +:101C60001344D5F80C802362D5E9003213605A6022 +:101C70006369EF60B34201D101F01CFB87F3118867 +:101C80002869C047202383F31188E1E76169B142E5 +:101C900009D013441B1ABDE8F0410A2B2CBFC01811 +:101CA0000A3001F00DBBBDE8F08100BFB423002075 +:101CB00000207047FEE70000704700004FF0FF3043 +:101CC0007047000002290CD0032904D001290748DD +:101CD00018BF00207047032A05D8054800EBC20052 +:101CE0007047044870470020704700BF303B000831 +:101CF0003C220020E43A000870B59AB00546084638 +:101D0000144601A900F0C2F801A8FFF785F8431CAA +:101D10000022C6B25B001046C5E9003423700323DD +:101D2000023404F8013C01ABD1B202348E4201D836 +:101D30001AB070BD13F8011B013204F8010C04F84D +:101D4000021CF1E708B5202383F311880348FFF74D +:101D500067FA002383F3118808BD00BF70250020B7 +:101D600090F8803003F01F02012A07D190F88120FB +:101D70000B2A03D10023C0E91D3315E003F06003F3 +:101D8000202B08D1B0F884302BB990F88120212A7B +:101D900003D81F2A04D8FFF725BA222AEBD0FAE786 +:101DA000034A426707228267C3670120704700BF6A +:101DB0003322002007B5052917D8DFE801F01916EE +:101DC00003191920202383F31188104A012101905F +:101DD000FFF7CEFA019802210D4AFFF7C9FA0D4824 +:101DE000FFF7EAF9002383F3118803B05DF804FBE1 +:101DF000202383F311880748FFF7B4F9F2E7202383 +:101E000083F311880348FFF7CBF9EBE7843A000826 +:101E1000A83A00087025002038B50C4D0C4C2A4615 +:101E20000C4904F10800FFF767FF05F1CA0204F14D +:101E300010000949FFF760FF05F5CA7204F11800A8 +:101E40000649BDE83840FFF757BF00BF483E0020B5 +:101E50003C220020643A00086E3A0008793A0008F3 +:101E600070B5044608460D46FEF7D6FFC6B22046BA +:101E7000013403780BB9184670BD32462946FEF787 +:101E8000B7FF0028F3D10120F6E700002DE9F84F55 +:101E900005460C46FEF7C0FF2C49C6B22846FFF7A0 +:101EA000DFFF08B10336F6B229492846FFF7D8FF0D +:101EB00008B11036F6B2632E0DD8DFF89080DFF847 +:101EC0009090244FDFF894A0DFF894B02E7846B9B4 +:101ED0002670BDE8F88F29462046BDE8F84F01F08E +:101EE0007DBD252E2ED1072241462846FEF780FFD4 +:101EF00070B9DBF8003007350A3444F80A3CDBF8E7 +:101F0000043044F8063CBBF8083024F8023CDDE716 +:101F1000082249462846FEF76BFF98B9A21C0E4BD3 +:101F2000197802320909C95D02F8041C13F8011B73 +:101F300001F00F015345C95D02F8031CF0D11834BC +:101F40000835C3E7013504F8016BBFE7503B0008D3 +:101F5000793A0008633B000800E8F11F0CE8F11F24 +:101F6000583B0008BFF34F8F044B1A695107FCD14F +:101F7000D3F810215207F8D1704700BF002000525B +:101F800008B50D4B1B78ABB9FFF7ECFF0B4BDA68CC +:101F9000D10704D50A4A5A6002F188325A60D3F850 +:101FA0000C21D20706D5064AC3F8042102F1883273 +:101FB000C3F8042108BD00BFA64000200020005245 +:101FC0002301674508B5114B1B78F3B9104B1A690B +:101FD000510703D5DA6842F04002DA60D3F81021E5 +:101FE000520705D5D3F80C2142F04002C3F80C216A +:101FF000FFF7B8FF064BDA6842F00102DA60D3F867 +:102000000C2142F00102C3F80C2108BDA6400020BB +:10201000002000520F289ABF00F580604004002085 +:10202000704700004FF400307047000010207047E8 +:102030000F2808B50BD8FFF7EDFF00F50033026855 +:10204000013204D104308342F9D1012008BD0020BF +:10205000FCE700000F2870B5054645D8FFF7D6FC11 +:10206000224CFFF77FFF0646FFF78AFF4FF0FF3352 +:10207000072D6361C4F8143120D82361FFF772FF84 +:102080002B0243F02403E360E36843F08003E36042 +:1020900023695A07FCD42846FFF764FF4FF4003148 +:1020A000FFF7B8FF00F002F93046FFF78BFFFFF7AC +:1020B000B7FC2846BDE87040FFF7BABFC4F810313E +:1020C000FFF750FFA5F108031B0243F02403C4F8F7 +:1020D0000C31D4F80C3143F08003C4F80C31D4F83F +:1020E00010315B07FBD4D6E7002070BD0020005202 +:1020F0002DE9F84F40EA020305460C461746D8067C +:1021000002D00020BDE8F88F27F01F07DFF8D4B019 +:10211000FFF736FF2744BC4203D10120FFF752FFEF +:10212000F0E720222946204601F048FC10B920356E +:102130002034F0E72B4605F120021E68711CE0D127 +:1021400004339A42F9D1FFF761FC05F17843234A41 +:10215000B3F5801F224B28BF9A4603F1040338BF12 +:102160009046A2F1080228BF9846A3F108033ABF9F +:102170009146DA469946FFF7F5FEC8F80060A5EBF0 +:10218000040CD9F8002004F11C0142F00202C9F845 +:102190000020221FDAF8006016F00506FAD152F886 +:1021A000043F8A424CF80230F4D1BFF34F8FFFF75F +:1021B000D9FE4FF0FF32C8F80020D9F8002022F0F5 +:1021C0000202C9F80020FFF72BFC202221462846F6 +:1021D00001F0F4FB0028AAD030469FE714200052FB +:1021E000102100521020005210B5084C237828B15D +:1021F0001BB9FFF7C5FE0123237010BD002BFCD0D7 +:102200002070BDE81040FFF7DDBE00BFA6400020F3 +:102210000244074BD2B210B5904200D110BD441C0D +:1022200000B253F8200041F8040BE0B2F4E700BF1D +:10223000504000580E4B30B51C6F240405D41C6F61 +:102240001C671C6F44F400441C670A4C024423685A +:10225000D2B243F480732360074B904200D130BD6B +:10226000441C51F8045B00B243F82050E0B2F4E79C +:1022700000440258004802585040005807B5012257 +:1022800001A90020FFF7C4FF019803B05DF804FB2B +:1022900013B50446FFF7F2FFA04205D0012201A9C1 +:1022A00000200194FFF7C6FF02B010BD0144BFF348 +:1022B0004F8F064B884204D3BFF34F8FBFF36F8F0E +:1022C0007047C3F85C022030F4E700BF00ED00E087 +:1022D000034B1A681AB9034AD2F8D0241A6070471F +:1022E000A84000200040025808B5FFF7F1FF024B5C +:1022F0001868C0F3806008BDA8400020EFF3098390 +:10230000054968334A6B22F001024A6383F3098866 +:10231000002383F31188704700EF00E0202080F352 +:10232000118862B60D4B0E4AD96821F4E0610904A8 +:10233000090C0A430B49DA60D3F8FC2042F08072A2 +:10234000C3F8FC20084AC2F8B01F116841F001012F +:1023500011601022DA7783F82200704700ED00E068 +:102360000003FA0555CEACC5001000E0202310B5DF +:1023700083F311880E4B5B6813F4006314D0F1EE05 +:10238000103AEFF309844FF08073683CE361094B26 +:10239000DB6B236684F30988FFF7E8FA10B1064B7C +:1023A000A36110BD054BFBE783F31188F9E700BF7C +:1023B00000ED00E000EF00E0F7030008FA0300087A +:1023C00070B5BFF34F8FBFF36F8F1A4A0021C2F869 +:1023D0005012BFF34F8FBFF36F8F536943F4003335 +:1023E0005361BFF34F8FBFF36F8FC2F88410BFF3F9 +:1023F0004F8FD2F8803043F6E074C3F3C900C3F3C3 +:102400004E335B0103EA0406014646EA8175013951 +:10241000C2F86052F9D2203B13F1200FF2D1BFF382 +:102420004F8F536943F480335361BFF34F8FBFF332 +:102430006F8F70BD00ED00E0FEE700000A4B0B4817 +:102440000B4A90420BD30B4BC11EDA1C121A22F01E +:1024500003028B4238BF00220021FEF7E5BC53F88F +:10246000041B40F8041BECE7443D00087C420020BC +:102470007C4200207C4200207047000070B5D0E90B +:10248000244300224FF0FF359E6804EB42135101B4 +:10249000D3F80009002805DAD3F8000940F080409D +:1024A000C3F80009D3F8000B002805DAD3F8000BB5 +:1024B00040F08040C3F8000B013263189642C3F825 +:1024C0000859C3F8085BE0D24FF00113C4F81C3878 +:1024D00070BD000000EB8103D3F80CC02DE9F04380 +:1024E000DCF814204E1CD0F89050D2F800E005EB38 +:1024F000063605EB4118506870450AD30122D5F81D +:10250000343802FA01F123EA0101C5F83418BDE8B4 +:10251000F083AEEB0003BCF81040A34228BF234673 +:10252000D8F81849A4B2B3EB840FF0D89468A4F19A +:10253000040959F8047F3760A4EB09071F44042FEE +:10254000F7D81C44034494605360D4E7890141F0F8 +:102550002001016103699B06FCD41220FFF770BAC9 +:1025600010B50A4C2046FEF7E1FE094BC4F8903046 +:10257000084BC4F89430084C2046FEF7D7FE074BB2 +:10258000C4F89030064BC4F8943010BDAC40002025 +:1025900000000840983B000848410020000004402B +:1025A000A43B000870B503780546012B5DD1494B6B +:1025B000D0F89040984259D1474B0E216520D3F86E +:1025C000D82042F00062C3F8D820D3F8002142F0AE +:1025D0000062C3F80021D3F80021D3F8802042F034 +:1025E0000062C3F88020D3F8802022F00062C3F894 +:1025F0008020D3F8803000F071FC384BE360384B1A +:10260000C4F800380023D5F89060C4F8003EC02319 +:1026100023604FF40413A3633369002BFCDA012316 +:102620000C203361FFF70CFA3369DB07FCD412206E +:10263000FFF706FA3369002BFCDA00262846A6606D +:10264000FFF71CFF6B68C4F81068DB68C4F81468F7 +:10265000C4F81C68002B3AD1224BA3614FF0FF3322 +:102660006361A36843F00103A36070BD1E4B9842F1 +:10267000C8D1194B0E214D20D3F8D82042F000725A +:10268000C3F8D820D3F8002142F00072C3F800212B +:10269000D3F80021D3F8802042F00072C3F88020E4 +:1026A000D3F8802022F00072C3F88020D3F8802075 +:1026B000D3F8D82022F08062C3F8D820D3F80021C4 +:1026C00022F08062C3F80021D3F8003193E7074B72 +:1026D000C3E700BFAC400020004402584014004053 +:1026E00003002002003C30C048410020083C30C0BC +:1026F000F8B5D0F89040054600214FF0006620461E +:10270000FFF724FFD5F8941000234FF001128F68D3 +:102710004FF0FF30C4F83438C4F81C2804EB4312DF +:1027200001339F42C2F80069C2F8006BC2F8080981 +:10273000C2F8080BF2D20B68D5F89020C5F8983093 +:10274000636210231361166916F01006FBD1122084 +:10275000FFF776F9D4F8003823F4FE63C4F80038A4 +:10276000A36943F4402343F01003A3610923C4F891 +:102770001038C4F814380B4BEB604FF0C043C4F86A +:10278000103B094BC4F8003BC4F81069C4F8003989 +:10279000D5F8983003F1100243F48013C5F898205F +:1027A000A362F8BD743B000840800010D0F8902070 +:1027B00090F88A10D2F8003823F4FE6343EA01133C +:1027C000C2F80038704700002DE9F84300EB8103A0 +:1027D000D0F890500C468046DA680FFA81F948012B +:1027E000166806F00306731E022B05EB41134FF02B +:1027F000000194BFB604384EC3F8101B4FF001011E +:1028000004F1100398BF06F1805601FA03F39169B1 +:1028100098BF06F5004600293AD0578A04F15801BE +:10282000374349016F50D5F81C180B430021C5F8F8 +:102830001C382B180127C3F81019A7405369611ED3 +:102840009BB3138A928B9B08012A88BF5343D8F805 +:102850009820981842EA034301F140022146C8F843 +:102860009800284605EB82025360FFF76FFE08EBE5 +:102870008900C3681B8A43EA845348341E436401B9 +:102880002E51D5F81C381F43C5F81C78BDE8F883D5 +:1028900005EB4917D7F8001B21F40041C7F8001BCE +:1028A000D5F81C1821EA0303C0E704F13F030B4AE3 +:1028B0002846214605EB83035A60FFF747FE05EBE8 +:1028C0004910D0F8003923F40043C0F80039D5F896 +:1028D0001C3823EA0707D7E7008000100004000235 +:1028E000D0F894201268C0F89820FFF7C7BD000008 +:1028F0005831D0F8903049015B5813F4004004D0AF +:1029000013F4001F0CBF0220012070474831D0F89B +:10291000903049015B5813F4004004D013F4001FB9 +:102920000CBF02200120704700EB8101CB68196ABF +:102930000B6813604B6853607047000000EB810325 +:1029400030B5DD68AA691368D36019B9402B84BF1C +:10295000402313606B8A1468D0F890201C4402EB6B +:102960004110013C09B2B4FBF3F46343033323F099 +:10297000030343EAC44343F0C043C0F8103B2B6851 +:1029800003F00303012B0ED1D2F8083802EB4110FB +:1029900013F4807FD0F8003B14BF43F0805343F022 +:1029A0000053C0F8003B02EB4112D2F8003B43F069 +:1029B0000443C2F8003B30BD2DE9F041D0F89060EF +:1029C00005460C4606EB4113D3F8087B3A07C3F8DB +:1029D000087B08D5D6F814381B0704D500EB810313 +:1029E000DB685B689847FA071FD5D6F81438DB0711 +:1029F0001BD505EB8403D968CCB98B69488A5A6822 +:102A0000B2FBF0F600FB16228AB91868DA68904229 +:102A10000DD2121AC3E90024202383F31188214622 +:102A20002846FFF78BFF84F31188BDE8F08101236E +:102A300003FA04F26B8923EA02036B81CB68002B53 +:102A4000F3D021462846BDE8F041184700EB81034A +:102A50004A0170B5DD68D0F890306C692668E66090 +:102A600056BB1A444FF40020C2F810092A6802F03D +:102A70000302012A0AB20ED1D3F8080803EB42146C +:102A800010F4807FD4F8000914BF40F0805040F06B +:102A90000050C4F8000903EB4212D2F8000940F0DC +:102AA0000440C2F800090122D3F8340802FA01F107 +:102AB0000143C3F8341870BD19B9402E84BF4020BB +:102AC000206020681A442E8A8419013CB4FBF6F475 +:102AD00040EAC44040F00050C6E700002DE9F04154 +:102AE000D0F8906004460D4606EB4113D3F8087900 +:102AF000C3F80879FB071CD5D6F81038DA0718D5C3 +:102B000000EB8103D3F80CC0DCF81430D3F800E0FC +:102B1000DA6896451BD2A2EB0E024FF000081A604D +:102B2000C3F80480202383F31188FFF78FFF88F315 +:102B300011883B0618D50123D6F83428AB40134240 +:102B400012D029462046BDE8F041FFF7C3BC01235F +:102B500003FA01F2038923EA02030381DCF8083057 +:102B6000002BE6D09847E4E7BDE8F0812DE9F84F67 +:102B7000D0F8905004466E69AB691E4016F4805838 +:102B80006E6103D0BDE8F84FFEF740BC002E12DAAC +:102B9000D5F8003E9F0705D0D5F8003E23F003038B +:102BA000C5F8003ED5F80438204623F00103C5F8E7 +:102BB0000438FEF757FC300505D52046FFF75EFCCC +:102BC0002046FEF73FFCB1040CD5D5F8083813F0C9 +:102BD000060FEB6823F470530CBF43F4105343F417 +:102BE000A053EB60320704D56368DB680BB1204665 +:102BF0009847F30200F1BA80B70226D5D4F8909036 +:102C000000274FF0010A09EB4712D2F8003B03F40A +:102C10004023B3F5802F11D1D2F8003B002B0DDA01 +:102C200062890AFA07F322EA0303638104EB87034C +:102C3000DB68DB6813B13946204698470137D4F882 +:102C40009430FFB29B689F42DDD9F00619D5D4F8C5 +:102C50009000026AC2F30A1702F00F0302F4F012A6 +:102C6000B2F5802F00F0CC80B2F5402F09D104EBF3 +:102C70008303002200F58050DB681B6A974240F016 +:102C8000B2803003D5F8185835D5E90303D50021B3 +:102C90002046FFF791FEAA0303D501212046FFF746 +:102CA0008BFE6B0303D502212046FFF785FE2F0321 +:102CB00003D503212046FFF77FFEE80203D5042158 +:102CC0002046FFF779FEA90203D505212046FFF72C +:102CD00073FE6A0203D506212046FFF76DFE2B0224 +:102CE00003D507212046FFF767FEEF0103D5082132 +:102CF0002046FFF761FE700340F1A980E90703D584 +:102D000000212046FFF7EAFEAA0703D5012120464D +:102D1000FFF7E4FE6B0703D502212046FFF7DEFE36 +:102D20002F0703D503212046FFF7D8FEEE0603D573 +:102D300004212046FFF7D2FEA80603D50521204630 +:102D4000FFF7CCFE690603D506212046FFF7C6FE35 +:102D50002A0603D507212046FFF7C0FEEB0576D5EE +:102D600020460821BDE8F84FFFF7B8BED4F8909090 +:102D700000274FF0010AD4F894305FFA87FB9B6874 +:102D80009B453FF639AF09EB4B13D3F8002902F40A +:102D90004022B2F5802F24D1D3F80029002A20DA6E +:102DA000D3F8002942F09042C3F80029D3F8002953 +:102DB000002AFBDB5946D4F89000FFF7C7FB2289B5 +:102DC0000AFA0BF322EA0303238104EB8B03DB688B +:102DD0009B6813B159462046984759462046FFF74D +:102DE00079FB0137C7E7910701D1D0F80080072AA6 +:102DF00002F101029CBF03F8018B4FEA18283DE75E +:102E000004EB830300F58050DA68D2F818C0DCF8D0 +:102E10000820DCE9001CA1EB0C0C00218F4208D13A +:102E2000DB689B699A683A449A605A683A445A60E7 +:102E300027E711F0030F01D1D0F800808C4501F194 +:102E4000010184BF02F8018B4FEA1828E6E7BDE8CC +:102E5000F88F000008B50348FFF788FEBDE808407A +:102E6000FFF784BAAC40002008B50348FFF77EFEA8 +:102E7000BDE80840FFF77ABA48410020D0F890300A +:102E800003EB4111D1F8003B43F40013C1F8003BC0 +:102E900070470000D0F8903003EB4111D1F80039B1 +:102EA00043F40013C1F8003970470000D0F89030A7 +:102EB00003EB4111D1F8003B23F40013C1F8003BB0 +:102EC00070470000D0F8903003EB4111D1F8003981 +:102ED00023F40013C1F8003970470000090100F124 +:102EE0006043012203F56143C9B283F8001300F087 +:102EF0001F039A4043099B0003F1604303F56143BC +:102F0000C3F880211A60704730B50433039C017206 +:102F1000002104FB0325C160C0E90653049B036341 +:102F2000059BC0E90000C0E90422C0E90842C0E9ED +:102F30000A11436330BD00000022416AC260C0E94B +:102F40000411C0E90A226FF00101FEF7E9BD00009B +:102F5000D0E90432934201D1C2680AB9181D704702 +:102F600000207047036919600021C2680132C26005 +:102F7000C269134482699342036124BF436A0361B7 +:102F8000FEF7C2BD38B504460D46E3683BB1626941 +:102F90000020131D1268A3621344E36207E0237A42 +:102FA00033B929462046FEF79FFD0028EDDA38BDEB +:102FB0006FF00100FBE70000C368C269013BC3601A +:102FC0004369134482699342436124BF436A436166 +:102FD00000238362036B03B11847704770B5202349 +:102FE000044683F31188866A3EB9FFF7CBFF054696 +:102FF00018B186F31188284670BDA36AE26A13F8F7 +:10300000015B9342A36202D32046FFF7D5FF002362 +:1030100083F31188EFE700002DE9F84F04460E46D0 +:10302000174698464FF0200989F311880025AA46D3 +:10303000D4F828B0BBF1000F09D141462046FFF774 +:10304000A1FF20B18BF311882846BDE8F88FD4E9A1 +:103050000A12A7EB050B521A934528BF9346BBF102 +:10306000400F1BD9334601F1400251F8040B914245 +:1030700043F8040BF9D1A36A403640354033A362CC +:10308000D4E90A239A4202D32046FFF795FF8AF338 +:103090001188BD42D8D289F31188C9E730465A4613 +:1030A000FDF79CFEA36A5E445D445B44A362E7E7D0 +:1030B00010B5029C0433017204FB0321C460C0E913 +:1030C00006130023C0E90A33039B0363049BC0E992 +:1030D0000000C0E90422C0E90842436310BD0000BB +:1030E000026A6FF00101C260426AC0E90422002254 +:1030F000C0E90A22FEF714BDD0E904239A4201D1A7 +:10310000C26822B9184650F8043B0B607047002093 +:1031100070470000C3680021C2690133C36043697E +:10312000134482699342436124BF436A4361FEF7BB +:10313000EBBC000038B504460D46E3683BB123699B +:1031400000201A1DA262E2691344E36207E0237AB9 +:1031500033B929462046FEF7C7FC0028EDDA38BD12 +:103160006FF00100FBE7000003691960C268013AD3 +:10317000C260C269134482699342036124BF436AF7 +:10318000036100238362036B03B11847704700009B +:1031900070B520230D460446114683F31188866AD4 +:1031A0002EB9FFF7C7FF10B186F3118870BDA36A6F +:1031B0001D70A36AE26A01339342A36204D3E169FA +:1031C00020460439FFF7D0FF002080F31188EDE797 +:1031D0002DE9F84F04460D46904699464FF0200AD7 +:1031E0008AF311880026B346A76A4FB9494620469C +:1031F000FFF7A0FF20B187F311883046BDE8F88FB4 +:10320000D4E90A073A1AA8EB0607974228BF1746DF +:10321000402F1BD905F1400355F8042B9D4240F87F +:10322000042BF9D1A36A40364033A362D4E90A23C0 +:103230009A4204D3E16920460439FFF795FF8BF3E6 +:1032400011884645D9D28AF31188CDE729463A46F6 +:10325000FDF7C4FDA36A3D443E443B44A362E5E759 +:10326000D0E904239A4217D1C3689BB1836A8BB11A +:10327000043B9B1A0ED01360C368013BC360C36953 +:103280001A4483699A42026124BF436A036100239E +:1032900083620123184670470023FBE700F0CEB895 +:1032A000034B002258631A610222DA60704700BFA4 +:1032B000000C0040014B0022DA607047000C004017 +:1032C000014B5863704700BF000C0040014B586A27 +:1032D000704700BF000C00404B6843608B68836000 +:1032E000CB68C3600B6943614B6903628B694362BE +:1032F0000B6803607047000008B5364B40F2FF7161 +:103300003548D3F888200A43C3F88820D3F88820AA +:1033100022F4FF6222F00702C3F88820D3F8882045 +:10332000D3F8E0200A43C3F8E020D3F808210A4389 +:10333000C3F80821294AD3F808311146FFF7CCFF1A +:1033400000F5806002F11C01FFF7C6FF00F5806008 +:1033500002F13801FFF7C0FF00F5806002F154016F +:10336000FFF7BAFF00F5806002F17001FFF7B4FFCC +:1033700000F5806002F18C01FFF7AEFF00F5806080 +:1033800002F1A801FFF7A8FF00F5806002F1C40177 +:10339000FFF7A2FF00F5806002F1E001FFF79CFF5C +:1033A00000F5806002F1FC01FFF796FF02F58C71D9 +:1033B00000F58060FFF790FF00F0F4F8084B05225D +:1033C000C3F898204FF06052C3F89C20054AC3F818 +:1033D000A02008BD0044025800000258B03B00087D +:1033E00000ED00E01F00080308B500F0C9FAFEF781 +:1033F000EBFA0F4BD3F8DC2042F04002C3F8DC209C +:10340000D3F8042122F04002C3F80421D3F8043198 +:10341000084B1A6842F008021A601A6842F0040267 +:103420001A60FEF755FFBDE80840FEF7F5BC00BF87 +:10343000004402580018024870470000114BD3F8AE +:10344000E82042F00802C3F8E820D3F8102142F047 +:103450000802C3F810210C4AD3F81031D36B43F0A3 +:103460000803D363C722094B9A624FF0FF32DA6236 +:1034700000229A615A63DA605A6001225A611A6026 +:10348000704700BF004402580010005C000C004070 +:10349000094A08B51169D3680B40D9B29B076FEA96 +:1034A0000101116107D5202383F31188FEF7ACFADF +:1034B000002383F3118808BD000C0040384B4FF007 +:1034C000FF31D3F88020C3F88010D3F88020002289 +:1034D000C3F88020D3F88000D3F88400C3F88410A8 +:1034E000D3F88400C3F88420D3F88400D86F40F068 +:1034F000FF4040F4FF0040F43F5040F03F00D867E9 +:10350000D86F20F0FF4020F4FF0020F43F5020F05F +:103510003F00D867D86FD3F888006FEA40506FEA51 +:103520005050C3F88800D3F88800C0F30A00C3F8ED +:103530008800D3F88800D3F89000C3F89010D3F82F +:103540009000C3F89020D3F89000D3F89400C3F80B +:103550009410D3F89400C3F89420D3F89400D3F8CF +:103560009800C3F89810D3F89800C3F89820D3F8BF +:103570009800D3F88C00C3F88C10D3F88C00C3F8F3 +:103580008C20D3F88C00D3F89C00C3F89C10D3F89F +:103590009C10C3F89C20D3F89C3000F0C9B900BF40 +:1035A00000440258614B0122C3F80821604BD3F854 +:1035B000F42042F00202C3F8F420D3F81C2142F0B8 +:1035C0000202C3F81C210222D3F81C31594BDA60E5 +:1035D0005A689104FCD5584A1A6001229A60574AE9 +:1035E000DA6000221A614FF440429A61514B9A69A5 +:1035F0009204FCD51A6842F480721A604C4B1A6F20 +:1036000012F4407F04D04FF480321A6700221A6708 +:103610001A6842F001021A60454B1A685007FCD53F +:1036200000221A611A6912F03802FBD101211960D7 +:103630004FF0804159605A67414ADA62414A1A6143 +:103640001A6842F480321A60394B1A689103FCD52B +:103650001A6842F480521A601A689204FCD53A4AF9 +:103660003A499A6200225A6319633949DA639963C5 +:103670005A64384A1A64384ADA621A6842F0A85220 +:103680001A602B4B1A6802F02852B2F1285FF9D168 +:1036900048229A614FF48862DA6140221A622F4A06 +:1036A000DA644FF000521A652D4A5A652D4A9A6520 +:1036B00032232D4A1360136803F00F03022BFAD153 +:1036C0001B4B1A6942F003021A611A6902F03802B0 +:1036D000182AFAD1D3F8DC2042F00052C3F8DC20DB +:1036E000D3F8042142F00052C3F80421D3F8042196 +:1036F000D3F8DC2042F08042C3F8DC20D3F8042168 +:1037000042F08042C3F80421D3F80421D3F8DC202E +:1037100042F00042C3F8DC20D3F8042142F000421A +:10372000C3F80421D3F80431704700BF0080005172 +:10373000004402580048025800C000F00200000196 +:103740000000FF01008890081210200063020701AA +:103750002C02040047040508FD0BFF012000002097 +:103760000010E00000010100002000524FF0B042C4 +:1037700008B5D2F8883003F00103C2F8883023B1CD +:10378000044A13680BB150689847BDE80840FEF73B +:10379000EDBD00BFFC4100204FF0B04208B5D2F8AB +:1037A000883003F00203C2F8883023B1044A9368DA +:1037B0000BB1D0689847BDE80840FEF7D7BD00BF01 +:1037C000FC4100204FF0B04208B5D2F8883003F039 +:1037D0000403C2F8883023B1044A13690BB150695D +:1037E0009847BDE80840FEF7C1BD00BFFC4100207E +:1037F0004FF0B04208B5D2F8883003F00803C2F8A1 +:10380000883023B1044A93690BB1D0699847BDE869 +:103810000840FEF7ABBD00BFFC4100204FF0B042B6 +:1038200008B5D2F8883003F01003C2F8883023B10D +:10383000044A136A0BB1506A9847BDE80840FEF786 +:1038400095BD00BFFC4100204FF0B04310B5D3F848 +:10385000884004F47872C3F88820A30604D5124A7D +:10386000936A0BB1D06A9847600604D50E4A136B71 +:103870000BB1506B9847210604D50B4A936B0BB1E3 +:10388000D06B9847E20504D5074A136C0BB1506C16 +:103890009847A30504D5044A936C0BB1D06C9847A4 +:1038A000BDE81040FEF762BDFC4100204FF0B04380 +:1038B00010B5D3F8884004F47C42C3F88820620530 +:1038C00004D5164A136D0BB1506D9847230504D5E6 +:1038D000124A936D0BB1D06D9847E00404D50F4A9E +:1038E000136E0BB1506E9847A10404D50B4A936E2A +:1038F0000BB1D06E9847620404D5084A136F0BB120 +:10390000506F9847230404D5044A936F0BB1D06FCE +:103910009847BDE81040FEF729BD00BFFC410020DC +:1039200008B5FFF7B5FDBDE80840FEF71FBD000074 +:10393000062108B50846FFF7D1FA06210720FFF750 +:10394000CDFA06210820FFF7C9FA06210920FFF762 +:10395000C5FA06210A20FFF7C1FA06211720FFF752 +:10396000BDFA06212820FFF7B9FA09217A20FFF7CE +:10397000B5FA07213220BDE80840FFF7AFBA0000D2 +:1039800008B5FFF79BFD00F00BF8FDF7CDFCFDF748 +:103990009FFBFFF751FDBDE80840FFF77FBC00002B +:1039A0000023054A19460133102BC2E9001102F128 +:1039B0000802F8D1704700BFFC41002010B5013962 +:1039C0000244904201D1002005E0037811F8014F34 +:1039D000A34201D0181B10BD0130F2E7034611F8D5 +:1039E000012B03F8012B002AF9D1704753544D33B2 +:1039F0003248373F3F3F0053544D3332483734331A +:103A00002F37353300000000000000004D10000883 +:103A10003910000875100008611000086D100008CA +:103A200059100008451000083110000881100008E6 +:103A30000000000001000000000000006D61696EE0 +:103A40000000000069646C6500000000443A000852 +:103A5000F82300207025002001000000C51900088F +:103A6000000000004172647550696C6F740025425B +:103A70004F415244252D424C002553455249414C5B +:103A80002500000002000000000000006D12000888 +:103A9000DD12000840004000183E0020283E0020B3 +:103AA0000200000000000000030000000000000011 +:103AB000251300080000000010000000383E002020 +:103AC000000000000100000000000000AC400020E9 +:103AD00001010200B51D0008C51C0008611D000899 +:103AE000451D000843000000EC3A000809024300AD +:103AF000020100C032090400000102020100052495 +:103B0000001001052401000104240202052406001E +:103B100001070582030800FF09040100020A0000F2 +:103B20000007050102400000070581024000000077 +:103B300012000000383B0008120110010200004092 +:103B400009124157000201020301000004030904A5 +:103B500025424F41524425004B616B7574654837CF +:103B600076320030313233343536373839414243DA +:103B70004445460000000000791400083117000891 +:103B8000DD17000840004000E4410020E44100202F +:103B900001000000F441002080000000400100000E +:103BA0000800000000010000000400000800000000 +:103BB0000001802A00000000AAAAAAAA000100248D +:103BC000FFFF00000000000000A00A00000040010C +:103BD00000000000AAAAAAAA00000001FFFF00003E +:103BE00000000000000000001000000400000000C1 +:103BF000AAAAAAAA00000008FBDF0000000000003B +:103C0000000000000000000000000000AAAAAAAA0C +:103C100000000000FFFF00000000000000000000A6 +:103C20000001000000000000AAAAAAAA00010000EA +:103C3000FFFF000000000000000000000000000086 +:103C400000000000AAAAAAAA00000000FFFF0000CE +:103C50000000000000000000000000000000000064 +:103C6000AAAAAAAA00000000FFFF000000000000AE +:103C7000000000000000000000000000AAAAAAAA9C +:103C800000000000FFFF0000000000000000000036 +:103C90000000000000000000AAAAAAAA000000007C +:103CA000FFFF000000000000000000000000000016 +:103CB00000000000AAAAAAAA00000000FFFF00005E +:103CC00000000000000000000000000000000000F4 +:103CD000AAAAAAAA00000000FFFF0000000000003E +:103CE00000000000000000001804000000000000B8 +:103CF00000001A0000000000FF00000000000000AB +:103D0000EC3900083F00000050040000F7390008BB +:103D10003F00000000960000000008009600000030 +:103D200000080000040000004C3B000800000000F8 +:103D30000000000000000000000000000000000083 +:043D4000000000007F +:00000001FF diff --git a/Tools/bootloaders/MambaF405-2022_bl.bin b/Tools/bootloaders/MambaF405-2022_bl.bin new file mode 100644 index 00000000000..6067ee8282b Binary files /dev/null and b/Tools/bootloaders/MambaF405-2022_bl.bin differ diff --git a/Tools/bootloaders/MambaF405-2022_bl.hex b/Tools/bootloaders/MambaF405-2022_bl.hex new file mode 100644 index 00000000000..6aa01bada2e --- /dev/null +++ b/Tools/bootloaders/MambaF405-2022_bl.hex @@ -0,0 +1,891 @@ +:020000040800F2 +:1000000000060020E1010008450E0008C50D0008AB +:100010001D0E0008C50D0008F10D0008E3010008E1 +:10002000E3010008E3010008E301000819210008CA +:10003000E3010008E3010008E3010008E301000810 +:10004000E3010008E3010008E3010008E301000800 +:10005000E3010008E3010008E13100080D32000867 +:10006000393200086532000891320008E3010008C7 +:10007000E3010008E3010008E3010008E3010008D0 +:10008000E3010008E3010008E3010008E3010008C0 +:10009000E3010008E3010008E3010008BD320008A5 +:1000A000E3010008E3010008E3010008E3010008A0 +:1000B00055300008E3010008E3010008E3010008EF +:1000C000E3010008E3010008E3010008E301000880 +:1000D000E3010008E3010008E3010008E301000870 +:1000E00025330008E3010008E3010008E3010008EC +:1000F000E3010008E3010008E3010008E301000850 +:10010000E3010008E3010008E3010008E30100083F +:10011000E3010008E3010008E3010008E30100082F +:10012000E3010008E3010008E3010008E30100081F +:10013000E3010008E3010008E3010008E30100080F +:10014000E3010008E3010008E3010008512800086A +:10015000E3010008E3010008E3010008E3010008EF +:10016000E3010008E3010008E3010008E3010008DF +:10017000E3010008E3010008E3010008E3010008CF +:10018000E3010008E3010008E3010008E3010008BF +:10019000E3010008E3010008E3010008E3010008AF +:1001A000E3010008E3010008E3010008E30100089F +:1001B000E3010008E3010008E3010008E30100088F +:1001C000E3010008E3010008E3010008E30100087F +:1001D000E3010008E3010008E3010008E30100086F +:1001E00002E000F000F8FEE772B63A4880F30888B3 +:1001F000394880F3098839484EF60851CEF200019B +:10020000086040F20000CCF200004EF63471CEF2ED +:1002100000010860BFF34F8FBFF36F8F40F2000003 +:10022000C0F2F0004EF68851CEF200010860BFF334 +:100230004F8FBFF36F8F4FF00000E1EE100A4EF6C4 +:100240003C71CEF200010860062080F31488BFF3F1 +:100250006F8F01F0E1FF01F0BDFF02F05FFE4FF094 +:1002600055301F491B4A91423CBF41F8040BFAE745 +:100270001C49194A91423CBF41F8040BFAE71A495C +:100280001A4A1B4B9A423EBF51F8040B42F8040B2A +:10029000F8E700201749184A91423CBF41F8040B87 +:1002A000FAE701F09BFF02F08DFE144C144DAC42B6 +:1002B00003DA54F8041B8847F9E700F041F8114CC1 +:1002C000114DAC4203DA54F8041B8847F9E701F0FA +:1002D00083BF00000006002000220020000000086C +:1002E00000000020000600205037000800220020F7 +:1002F0004022002040220020A82D0020E00100081C +:10030000E0010008E0010008E00100082DE9F04FDD +:100310002DED108AC1F80CD0C3689D46BDEC108A43 +:10032000BDE8F08F002383F311882846A047002002 +:1003300001F0FEFAFEE701F079FA00DFFEE70000C7 +:1003400038B501F0B9FE054601F0DCFE0446D8B927 +:100350000F4B9D421AD001339D4218BF044641F213 +:10036000883504BF01240025002001F0AFFE0CB148 +:1003700000F076F800F0FCFC00F0A0FB284600F04E +:10038000BFF800F06DF8F9E70025EDE70546EBE76B +:10039000010007B008B500F063FBA0F1200358424C +:1003A000584108BD07B541F21203022101A8ADF87A +:1003B000043000F073FB03B05DF804FB38B5202374 +:1003C00083F311881748C3680BB101F037FB164A55 +:1003D000144800234FF47A7101F0F4FA002383F3F8 +:1003E0001188124C236813B12368013B23606368B2 +:1003F00013B16368013B63600D4D2B7833B96368BB +:100400007BB9022000F036FC322363602B78032B8B +:1004100007D163682BB9022000F02CFC4FF47A73EB +:10042000636038BD40220020BD0300085C2300202B +:1004300054220020084B187003280CD8DFE800F085 +:1004400008050208022000F013BC022000F00EBCD8 +:10045000024B00225A607047542200205C23002087 +:10046000234B244A10B51C46196801313FD0043390 +:100470009342F9D16268A24239D31F4B9B6803F1C2 +:10048000006303F540439A4231D2002000F030FB74 +:100490000220FFF7CFFF194B1A6C00221A64196E65 +:1004A0001A66196E596C5A64596E5A665A6E5A69B0 +:1004B00042F080025A615A6922F080025A615A69F8 +:1004C0001A6942F000521A611A6922F000521A6148 +:1004D0001B6972B64FF0E0232021C3F8084DD4E920 +:1004E000003281F311889D4683F30888104710BDC0 +:1004F00000C0000820C00008002200200038024090 +:100500002DE9F04F93B0AA4B00902022FF210AA8BA +:100510009D6800F0D7FBA74A1378A3B9A64801212C +:10052000C3601170202383F31188C3680BB101F0FD +:1005300085FAA24AA04800234FF47A7101F042FAEA +:10054000002383F31188009B13B19D4B009A1A601E +:100550009C4A009C1378032B1EBF00231370984AFB +:100560004FF0000A18BF5360D3465646D1460120CB +:1005700000F07EFB24B1924B1B68002B00F011822F +:10058000002000F06DFA0390039B002BF2DB0120AA +:1005900000F06CFB039B213B162BE8D801A252F81C +:1005A00023F000BF0106000829060008BD06000868 +:1005B0006F0500086F0500086F0500084707000871 +:1005C000170900083108000893080008BB08000854 +:1005D000E10800086F050008F30800086F0500082F +:1005E00065090008A10600086F050008A9090008B0 +:1005F0000D060008A10600086F0500089308000812 +:100600000220FFF7C7FE002840F0F581009B022181 +:10061000BAF1000F08BF1C4605A841F21233ADF82D +:10062000143000F03BFAA2E74FF47A7000F018FAA9 +:10063000071EEBDB0220FFF7ADFE0028E6D0013FEE +:10064000052F00F2DA81DFE807F0030A0D101336F8 +:1006500005230593042105A800F020FA17E054486B +:100660000421F9E758480421F6E758480421F3E744 +:100670004FF01C08404600F03DFA08F104080590D0 +:10068000042105A800F00AFAB8F12C0FF2D10120DC +:1006900000FA07F747EA0B0B5FFA8BFB4FF00009F4 +:1006A00000F05CFB26B10BF00B030B2B08BF002402 +:1006B000FFF778FE5BE746480421CDE7002EA5D082 +:1006C0000BF00B030B2BA1D10220FFF763FE0746B3 +:1006D00000289BD0012000F00BFA0220FFF7AAFEB1 +:1006E00000265FFA86F8404600F012FA044690B100 +:1006F0000021404600F01CFA01360028F1D1BA462C +:10070000044641F21213022105A8ADF814303E460A +:1007100000F0C4F92BE70120FFF78CFE2546244B9F +:100720009B68AB4207D9284600F0E4F9013040F05D +:1007300067810435F3E7234B00251D70204BBA4633 +:100740005D603E46ACE7002E3FF460AF0BF00B035C +:100750000B2B7FF45BAF0220FFF76CFE322000F022 +:100760007FF9B0F10008FFF651AF18F003077FF4EE +:100770004DAF0F4A926808EB050393423FF646AF30 +:10078000B8F5807F3FF742AF124B0193B84523DDA8 +:100790004FF47A7000F064F90390039A002AFFF690 +:1007A00035AF019B039A03F8012B0137EDE700BF3A +:1007B000002200205823002040220020BD03000812 +:1007C0005C23002054220020042200200822002064 +:1007D0000C22002058220020C820FFF7DBFD07462E +:1007E00000283FF413AF1F2D11D8C5F12002424558 +:1007F0000AAB25F0030028BF424683490192184402 +:1008000000F03AFA019A8048FF2100F05BFA4FEAC3 +:10081000A8037D490193C8F38702284600F05AFADD +:10082000064600283FF46DAF019B05EB830537E7D3 +:100830000220FFF7AFFD00283FF4E8AE00F0A4F976 +:1008400000283FF4E3AE0027B846704B9B68BB42DC +:1008500018D91F2F11D80A9B01330ED027F003039C +:1008600012AA134453F8203C05934046042205A9DC +:1008700000F0EAFA04378046E7E7384600F03AF934 +:100880000590F2E7CDF81480042105A800F006F9E0 +:1008900006E70023642104A8049300F0F5F800287B +:1008A0007FF4B4AE0220FFF775FD00283FF4AEAE32 +:1008B000049800F051F90590E6E70023642104A8AC +:1008C000049300F0E1F800287FF4A0AE0220FFF7C7 +:1008D00061FD00283FF49AAE049800F04DF9EAE774 +:1008E0000220FFF757FD00283FF490AE00F05CF9BE +:1008F000E1E70220FFF74EFD00283FF487AE05A98F +:10090000142000F057F904210746049004A800F0D1 +:10091000C5F83946B9E7322000F0A2F8071EFFF605 +:1009200075AEBB077FF472AE384A926807EB0903D5 +:1009300093423FF66BAE0220FFF72CFD00283FF4F8 +:1009400065AE27F003074F44B9453FF4A9AE4846CA +:1009500000F0D0F80421059005A800F09FF809F1F7 +:100960000409F1E74FF47A70FFF714FD00283FF413 +:100970004DAE00F009F9002844D00A9B01330BD09A +:1009800008220AA9002000F0A5F900283AD0202268 +:10099000FF210AA800F096F9FFF704FD1C4800F0BB +:1009A000CDFF13B0BDE8F08F002E3FF42FAE0BF05B +:1009B0000B030B2B7FF42AAE0023642105A80593BB +:1009C00000F062F8074600287FF420AE0220FFF70F +:1009D000E1FC804600283FF419AEFFF7E3FC41F24A +:1009E000883000F0ABFF059800F0EAF9464600F0C9 +:1009F000B5F93C46BBE5064652E64FF0000905E670 +:100A0000BA467EE637467CE65822002000220020C7 +:100A1000A086010070B50F4B1B780133DBB2012BB0 +:100A20000C4611D80C4D29684FF47A730E6AA2FB5C +:100A30000332014622462846B047844204D1074B80 +:100A400000221A70012070BD4FF4FA7000F076FF9A +:100A50000020F8E7102200205025002090230020DD +:100A600007B50023024601210DF107008DF807307C +:100A7000FFF7D0FF20B19DF8070003B05DF804FB3D +:100A80004FF0FF30F9E700000A4608B50421FFF7F0 +:100A9000C1FF80F00100C0B2404208BD30B4054C37 +:100AA0002368DD69044B0A46AC460146204630BC4B +:100AB000604700BF50250020A086010070B501F0FE +:100AC000EDF9094E094D30800024286833888342AF +:100AD00008D901F0DDF92B6804440133B4F5404F27 +:100AE0002B60F2D370BD00BF92230020642300204E +:100AF00001F096BA00F1006000F5404000687047D0 +:100B000000F10060920000F5404001F015BA0000CD +:100B1000054B1A68054B1B889B1A834202D9104467 +:100B200001F0B6B900207047642300209223002012 +:100B300038B5084D044629B128682044BDE838403E +:100B400001F0C6B92868204401F0AAF90028F3D0C2 +:100B500038BD00BF6423002010F003030AD1B0F5B4 +:100B6000047F05D200F10050A0F51040D0F8003805 +:100B7000184670470023FBE700F10050A0F5104035 +:100B8000D0F8100A70470000064991F8243033B1BC +:100B90000023086A81F824300822FFF7B1BF012042 +:100BA000704700BF68230020014B1868704700BFE2 +:100BB000002004E070B52A4B1B68C3F30B02044607 +:100BC0001B0C62B140F21340824230D040F2194017 +:100BD00082422ED040F2214082422CD10322214D6C +:100BE0000C2000FB0252556842F20102934224D0CD +:100BF000B3F5805F23D041F20102934221D041F24C +:100C0000030293421FD041F20702934214BF3F23D5 +:100C10003123013C0C44013D0A46A24215D215F98C +:100C2000016F501C9EB100F8016C0246F5E70122ED +:100C3000D5E70222D3E70C4DD6E73323E9E741237A +:100C4000E7E75A23E5E75923E3E7104605E02C25BB +:100C50008442157001D9901C5370401A70BD00BFBA +:100C6000002004E0503400082434000870470000DD +:100C7000704700007047000010B50023934203D076 +:100C8000CC5CC4540133F9E710BD000010B5013845 +:100C900010F9013F3BB191F900409C4203D11AB1D8 +:100CA0000131013AF4E71AB191F90020981A10BD08 +:100CB0001046FCE703460246D01A12F9011B002930 +:100CC000FAD1704702440346934202D003F8011B55 +:100CD000FAE770472DE9F8431F4D144695F8242094 +:100CE0000746884652BBDFF870909CB395F82430D5 +:100CF0002BB92022FF2148462F62FFF7E3FF95F82A +:100D00002400C0F10802A24228BF2246D6B24146C2 +:100D1000920005EB8000FFF7AFFF95F82430A41B8D +:100D20001E44F6B2082E17449044E4B285F82460BD +:100D3000DBD1FFF729FF0028D7D108E02B6A03EBAE +:100D400082038342CFD0FFF71FFF0028CBD10020C2 +:100D5000BDE8F8830120FBE768230020024B1A78E6 +:100D6000024B1A70704700BF902300201022002011 +:100D700010B50F4C0F4800F0F7F821460D4800F071 +:100D80001FF924680C48626DD2F8043843F002035E +:100D9000C2F8043800F0D2FD0849204600F016FAE7 +:100DA000626DD2F8043823F00203C2F8043810BD93 +:100DB000443500085025002040420F004C35000803 +:100DC0007047000000B59BB0EFF3098168226846C8 +:100DD000FFF752FFEFF30583044B9A6BDA6A9A6AC6 +:100DE0009A6A9A6A9A6A9A6A9B6AFEE700ED00E03C +:100DF00000B59BB0EFF3098168226846FFF73CFF1E +:100E0000EFF30583044B9A6B9A6A9A6A9A6A9A6A14 +:100E10009A6A9B6AFEE700BF00ED00E000B59BB058 +:100E2000EFF3098168226846FFF726FFEFF3058399 +:100E3000034B5A6B9A6A9A6A9A6A9A6A9B6AFEE7A5 +:100E400000ED00E0FEE7000030B5094D0A44914294 +:100E50000DD011F8013B5840082340F30004013B3A +:100E60002C4013F0FF0384EA5000F6D1EFE730BDC9 +:100E70002083B8ED026843681143016003B118474D +:100E80007047000013B5446BD4F894341A68117895 +:100E9000042915D1217C022912D119791289012343 +:100EA0008B4013420CD101A904F14C0001F03CFF2E +:100EB000D4F89444019B21790246206800F0CEF9D1 +:100EC00002B010BD143001F0BFBE00004FF0FF3380 +:100ED000143001F0B9BE00004C3001F091BF0000A9 +:100EE0004FF0FF334C3001F08BBF0000143001F0A5 +:100EF0008DBE00004FF0FF31143001F087BE0000BE +:100F00004C3001F05DBF00004FF0FF324C3001F07B +:100F100057BF00000020704710B5D0F894341A680D +:100F200011780429044617D1017C022914D159797A +:100F3000528901238B4013420ED1143001F020FE60 +:100F4000024648B1D4F894444FF480736179206824 +:100F5000BDE8104000F070B910BD0000406BFFF715 +:100F6000DBBF0000704700007FB5124B0360002319 +:100F70004360C0E90233012502260F4B0574044685 +:100F80000290019300F18402294600964FF4807389 +:100F9000143001F0D1FD094B0294CDE9006304F552 +:100FA00023724FF48073294604F14C0001F098FE3F +:100FB00004B070BD803400085D0F0008850E000885 +:100FC0000B68202282F311880A7903EB8202906178 +:100FD0004A79093243F822008A7912B103EB82037D +:100FE000986102230374C0F89414002383F31188DA +:100FF0007047000038B5037F044613B190F85430B1 +:10100000ABB9201D01250221FFF734FF04F11400C4 +:1010100025776FF0010100F0B9FC84F8545004F119 +:101020004C006FF00101BDE8384000F0AFBC38BDA6 +:1010300010B5012104460430FFF71CFF002323777D +:1010400084F8543010BD000038B504460025143033 +:1010500001F08AFD04F14C00257701F059FE201DB6 +:1010600084F854500121FFF705FF2046BDE83840C1 +:10107000FFF752BF90F8443003F06003202B07D1F4 +:1010800090F84520212A4FF0000303D81F2A06D8E4 +:1010900000207047222AFBD1C0E90E3303E0034A47 +:1010A00082630722C263036401207047112200207B +:1010B00037B5D0F894341A681178042904461AD147 +:1010C000017C022917D11979128901238B4013421F +:1010D00011D100F14C05284601F0DAFE58B101A902 +:1010E000284601F021FED4F89444019B2179024660 +:1010F000206800F0B3F803B030BD0000F0B500EB9D +:10110000810385B09E6904460D46FEB1202383F31A +:10111000118804EB8507301D0821FFF7ABFEFB6843 +:101120005B691B6806F14C001BB1019001F00AFEDF +:10113000019803A901F0F8FD024648B1039B294636 +:10114000204600F08BF8002383F3118805B0F0BD32 +:10115000FB685A691268002AF5D01B8A013B1340CC +:10116000F1D104F14402EAE7093138B550F82140E1 +:10117000DCB1202383F31188D4F8942413685279C6 +:1011800003EB8203DB689B695D6845B1042160184D +:10119000FFF770FE294604F1140001F0FBFC204625 +:1011A000FFF7BAFE002383F3118838BD70470000B3 +:1011B00001F0A8B8012303700023C0E90133C36123 +:1011C00083620362C36243620363704738B50446B7 +:1011D000202383F311880025C0E90355C0E9055594 +:1011E000416001F09FF80223237085F3118838BD18 +:1011F00070B500EB810305465069DA600E4614466F +:1012000018B110220021FFF75DFDA06918B110226E +:101210000021FFF757FD31462846BDE8704001F038 +:101220004BB90000826802F0011282600022C0E91E +:101230000422826101F0CCB9F0B400EB810447894B +:10124000E4680125A4698D403D4345812360002366 +:10125000A2606360F0BC01F0E7B90000F0B400EBFD +:1012600081040789E468012564698D403D43058157 +:1012700023600023A2606360F0BC01F061BA00004B +:1012800070B50223002504460370C0E90255C0E989 +:101290000455C564856180F8345001F0A9F863688D +:1012A0001B6823B129462046BDE87040184770BD31 +:1012B000037880F850300523037043681B6810B52D +:1012C00004460BB1042198470023A36010BD000021 +:1012D00090F85020436802701B680BB10521184735 +:1012E0007047000070B590F83430044613B1002305 +:1012F00080F8343004F14402204601F08BF9636831 +:101300009B68B3B994F8443013F0600535D00021E0 +:10131000204601F0DDFB0021204601F0CFFB636891 +:101320001B6813B1062120469847062384F8343001 +:1013300070BD204698470028E4D0B4F84A30E26BEC +:101340009A4288BFE36394F94430E56B002B4FF079 +:10135000200380F20381002D00F0F280092284F83E +:10136000342083F311880021D4E90E232046FFF7AF +:1013700075FF002383F31188DAE794F8452003F022 +:101380007F0343EA022340F20232934200F0C58019 +:1013900021D8B3F5807F48D00DD8012B3FD0022B48 +:1013A00000F09380002BB2D104F14C02A263022220 +:1013B000E2632364C1E7B3F5817F00F09B80B3F55E +:1013C000407FA4D194F84630012BA0D1B4F84C3022 +:1013D00043F0020332E0B3F5006F4DD017D8B3F5F8 +:1013E000A06F31D0A3F5C063012B90D8636894F847 +:1013F00046205E6894F84710B4F848302046B0475D +:10140000002884D04368A3630368E3631AE0B3F55C +:10141000106F36D040F6024293427FF478AF5C4BB7 +:10142000A3630223E3630023C3E794F84630012B50 +:101430007FF46DAFB4F84C3023F00203C4E90E55CD +:10144000A4F84C30256478E7B4F84430B3F5A06FC5 +:101450000ED194F8463084F84E30204601F020F842 +:1014600063681B6813B1012120469847032323704A +:101470000023C4E90E339CE704F14F03A363012367 +:10148000C3E72378042B10D1202383F3118820464F +:10149000FFF7C8FE85F311880321636884F84F5075 +:1014A00021701B680BB12046984794F84630002BFA +:1014B000DED084F84F300423237063681B68002B50 +:1014C000D6D0022120469847D2E794F848301D062E +:1014D00003F00F0120460AD501F08EF8012804D050 +:1014E00002287FF414AF2B4B9AE72B4B98E701F0BF +:1014F00075F8F3E794F84630002B7FF408AF94F8C2 +:10150000483013F00F01B3D01A06204602D501F07F +:10151000F3FAADE701F0E6FAAAE794F84630002BBB +:101520007FF4F5AE94F8483013F00F01A0D01B06FD +:10153000204602D501F0CCFA9AE701F0BFFA97E70E +:10154000142284F8342083F311882B462A46294636 +:101550002046FFF771FE85F31188E9E65DB115229B +:1015600084F8342083F311880021D4E90E23204627 +:10157000FFF762FEFDE60B2284F8342083F3118826 +:101580002B462A4629462046FFF768FEE3E700BFC0 +:10159000B0340008A8340008AC34000838B590F81E +:1015A00034300446002B3ED0063BDAB20F2A34D842 +:1015B0000F2B32D8DFE803F03731310822323131D6 +:1015C0003131313131313737C56BB0F84A309D4256 +:1015D00014D2C3681B8AB5FBF3F203FB12556DB935 +:1015E000202383F311882B462A462946FFF736FE2F +:1015F00085F311880A2384F834300EE0142384F82C +:101600003430202383F3118800231A4619462046DC +:10161000FFF712FE002383F3118838BD036C03B17A +:1016200098470023E7E70021204601F051FA002106 +:10163000204601F043FA63681B6813B10621204677 +:1016400098470623D7E7000010B590F83430142BE4 +:10165000044629D017D8062B05D001D81BB110BDE0 +:10166000093B022BFBD80021204601F031FA002172 +:10167000204601F023FA63681B6813B10621204657 +:101680009847062319E0152BE9D10B2380F8343055 +:10169000202383F3118800231A461946FFF7DEFD45 +:1016A000002383F31188DAE7C3689B695B68002B2A +:1016B000D5D1036C03B19847002384F83430CEE7CA +:1016C000024B0022C3E900339A6070479423002044 +:1016D000002303748268054B1B6899689142FBD212 +:1016E0005A6803604260106058607047942300207D +:1016F00008B5202383F31188037C032B05D0042B2A +:101700000DD02BB983F3118808BD436900221A60FC +:101710004FF0FF334361FFF7DBFF0023F2E7D0E92F +:10172000003213605A60F3E7002303748268054BAC +:101730001B6899689142FBD85A6803604260106048 +:101740005860704794230020054B19690874186885 +:1017500002681A605360186101230374FEF7D6BD56 +:101760009423002030B54B1C0B4D87B0044610D09D +:101770002B690A4A01A800F025F92046FFF7E4FF8B +:10178000049B13B101A800F059F92B69586907B0FF +:1017900030BDFFF7D9FFF8E794230020F1160008C9 +:1017A00038B50C4D41612B6981689A6891420446B5 +:1017B00003D8BDE83840FFF78BBF1846FFF7B4FFEA +:1017C00001232C61014623742046BDE83840FEF712 +:1017D0009DBD00BF94230020044B1A681B699068CC +:1017E0009B68984294BF00200120704794230020FA +:1017F00010B5084C236820691A68226054600122E1 +:1018000023611A74FFF790FF01462069BDE810407C +:10181000FEF77CBD9423002008B5FFF7DDFF18B16B +:10182000BDE80840FFF7E4BF08BD0000FFF7E0BFD8 +:10183000FEE7000010B50C4CFFF742FF00F0B4F8D3 +:101840000A498022204600F03BF8012344F8180C96 +:10185000037400F071FC002383F3118862B604481E +:10186000BDE8104000F04CB8BC230020B4340008A0 +:10187000C434000800F01CB9EFF3118020B9EFF375 +:101880000583202282F311887047000010B530B91B +:10189000EFF30584C4F3080414B180F3118810BD7C +:1018A000FFF7BAFF84F31188F9E70000034A516893 +:1018B00053685B1A9842FBD8704700BF001000E0E5 +:1018C00082600222028270478368A3F17C0243F89F +:1018D0000C2C026943F83C2C426943F8382C074A27 +:1018E00043F81C2CC26843F8102C022203F8082C81 +:1018F000002203F8072CA3F1180070472503000805 +:1019000010B5202383F31188FFF7DEFF0021044682 +:10191000FFF746FF002383F31188204610BD000027 +:10192000024B1B6958610F20FFF70EBF9423002064 +:10193000202383F31188FFF7F3BF000008B50146A9 +:10194000202383F311880820FFF70CFF002383F383 +:10195000118808BD49B1064B42681B6918605A607E +:10196000136043600420FFF7FDBE4FF0FF30704767 +:10197000942300200368984206D01A6802605060E1 +:1019800059611846FFF7A4BE7047000038B50446F9 +:101990000D462068844200D138BD036823605C6036 +:1019A0004561FFF795FEF4E7054B03F11402C3E927 +:1019B00005224FF0FF310022C3E90712704700BF34 +:1019C0009423002070B51C4EC0E9032305460C4645 +:1019D00001F090FA334653F8142F9A420DD1306239 +:1019E000C5E901242A600A2C2CBF00190A30C6E977 +:1019F0000555BDE8704001F06BBA316A431AE3182F +:101A000038BF1C469368A34202D9081901F06EFA48 +:101A100073699A6894420CD85A68AC602B606A600B +:101A200015609A685D60121B9A604FF0FF33F36196 +:101A300070BD1B68A41AECE79423002038B51B4C3A +:101A4000636998420DD0D0E9003213605A600022D9 +:101A50008168C2609A680A449A604FF0FF33E3617C +:101A600038BD2246036842F8143F002193425A6071 +:101A7000C16003D1BDE8384001F032BA9A6881688C +:101A8000256A0A449A6001F035FA63699A68411B35 +:101A90008A42E5D9AB181D1A092D206A98BF01F1B9 +:101AA0000A02BDE83840104401F020BA9423002017 +:101AB0002DE9F041184C002704F11406656901F086 +:101AC00019FA236AAA68C11A8A4215D813442362F4 +:101AD000D5E9003213605A606369D5F80C80EF6075 +:101AE000B34201D101F0FCF987F311882869C0479E +:101AF000202383F31188E1E76169B14209D01344DF +:101B00001B1ABDE8F0410A2B2CBFC0180A3001F0A7 +:101B1000EDB9BDE8F08100BF94230020002070479C +:101B2000FEE70000704700004FF0FF3070470000F4 +:101B300002290CD0032904D00129074818BF00202E +:101B40007047032A05D8054800EBC20070470448D7 +:101B500070470020704700BFA835000820220020F1 +:101B60005C35000870B59AB00546084601A91446D0 +:101B700000F0C2F801A8FFF79DF8431C5B00C5E91F +:101B800000340022237003236370C6B201AB023419 +:101B90001046D1B28E4204F1020401D81AB070BDD1 +:101BA00013F8011B04F8021C04F8010C0132F0E7E1 +:101BB00008B5202383F311880348FFF779FA00233F +:101BC00083F3118808BD00BF5025002090F84430F1 +:101BD00003F01F02012A07D190F845200B2A03D1F8 +:101BE0000023C0E90E3315E003F06003202B08D179 +:101BF000B0F848302BB990F84520212A03D81F2A85 +:101C000004D8FFF737BA222AEBD0FAE7034A8263F7 +:101C10000722C26303640120704700BF182200201E +:101C200007B5052917D8DFE801F01916031919209F +:101C3000202383F31188104A01900121FFF7D8FA7D +:101C400001980E4A0221FFF7D3FA0D48FFF7FCF97D +:101C5000002383F3118803B05DF804FB202383F392 +:101C600011880748FFF7C6F9F2E7202383F31188AC +:101C70000348FFF7DDF9EBE7FC34000820350008E6 +:101C80005025002038B50C4D0C4C0D492A4604F166 +:101C90000800FFF767FF05F1CA0204F110000949C7 +:101CA000FFF760FF05F5CA7204F118000649BDE8A8 +:101CB0003840FFF757BF00BF182A0020202200201D +:101CC000DC340008E6340008F134000870B504463E +:101CD00008460D46FEF7EEFFC6B2204601340378F3 +:101CE0000BB9184670BD32462946FEF7CFFF0028D3 +:101CF000F3D10120F6E700002DE9F04705460C4638 +:101D0000FEF7D8FF2B49C6B22846FFF7DFFF08B120 +:101D10000736F6B228492846FFF7D8FF08B1103633 +:101D2000F6B2632E0BD8DFF88C80DFF88C90234F4F +:101D3000DFF894A02E7846B92670BDE8F0872946D2 +:101D40002046BDE8F04701F065BB252E2ED10722C5 +:101D500041462846FEF79AFF70B9194B224603F117 +:101D60000C0153F8040B42F8040B8B42F9D11B8889 +:101D7000138007350E34DDE7082249462846FEF772 +:101D800085FF98B90F4BA21C197809090232C95D69 +:101D900002F8041C13F8011B01F00F015345C95D43 +:101DA00002F8031CF0D118340835C3E704F8016BBE +:101DB0000135BFE7C8350008F1340008DF350008F9 +:101DC000D0350008107AFF1F1C7AFF1FBFF34F8F1A +:101DD000024AD368DB03FCD4704700BF003C0240DA +:101DE00008B5094B1B7873B9FFF7F0FF074B1A6969 +:101DF000002ABFBF064A5A6002F188325A601A6848 +:101E000022F480621A6008BD762C0020003C02405B +:101E10002301674508B50B4B1B7893B9FFF7D6FF35 +:101E2000094B1A6942F000421A611A6842F4805262 +:101E30001A601A6822F480521A601A6842F48062AA +:101E40001A6008BD762C0020003C02400B28F0B53B +:101E500016D80C4C0C4923787BB90C4D0E460C233C +:101E60004FF0006255F8047B46F8042B013B13F059 +:101E7000FF033A44F6D10123237051F82000F0BD4E +:101E80000020FCE7A82C0020782C0020F03500086A +:101E9000014B53F820007047F03500080C207047C4 +:101EA0000B2810B5044601D9002010BDFFF7CEFF66 +:101EB000064B53F824301844C21A0BB90120F4E73A +:101EC00012680132F0D1043BF6E700BFF03500089C +:101ED0000B2838B5044628D8FFF7CEFCFFF776FF6D +:101EE000FFF77EFF124AF323D360E300DBB243F433 +:101EF000007343F002031361136943F480331361E9 +:101F000005462046FFF762FFFFF7A0FF094B53F895 +:101F1000241000F0E9F82846FFF77CFFFFF7B6FC35 +:101F20002046BDE83840FFF7BBBF002038BD00BFEA +:101F3000003C0240F035000812F001032DE9F041A9 +:101F400005460E4614464BD18218B2F1016F61D896 +:101F5000314B1B6813F001035CD0304FFFF78CFC52 +:101F6000FFF73EFFF323FB60FFF730FF314640F2FF +:101F70000128032C18D824F00104284E0C446D1AB3 +:101F800040F20118A142336905EB01072AD123F081 +:101F900001033361FFF73EFFFFF778FC0120BDE846 +:101FA000F081043C0435E4E7AB07E4D13B6923F45A +:101FB00040733B613B6943EA08033B6151F8046BA2 +:101FC0002E60BFF34F8FFFF701FF2B689E42E8D0D2 +:101FD0003B6923F001033B61FFF71CFFFFF756FC51 +:101FE0000020DCE723F440733361336943EA0803DC +:101FF00033610B883B80BFF34F8FFFF7E7FE3F88CD +:1020000031F8023BBFB2BB42BCD0336923F00103BD +:102010003361E1E71846C2E700380240003C024065 +:10202000084908B50B7828B11BB9FFF7D9FE012381 +:102030000B7008BD002BFCD0BDE808400870FFF70E +:10204000E9BE00BF762C002010B50244064BD2B288 +:10205000904200D110BD441C00B253F8200041F85A +:10206000040BE0B2F4E700BF502800400F4B30B53E +:102070001C6F240407D41C6F44F400741C671C6F8D +:1020800044F400441C670A4C236843F480732360C3 +:102090000244084BD2B2904200D130BD441C00B281 +:1020A00051F8045B43F82050E0B2F4E700380240F6 +:1020B000007000405028004007B5012201A900200F +:1020C000FFF7C2FF019803B05DF804FB13B50446A7 +:1020D000FFF7F2FFA04205D0012201A900200194E0 +:1020E000FFF7C4FF02B010BD70470000034B1A6831 +:1020F0001AB9034AD2F874281A607047AC2C002031 +:102100000030024008B5FFF7F1FF024B1868C0F33A +:10211000407008BDAC2C0020EFF3098305494A6BE1 +:1021200022F001024A63683383F30988002383F3B2 +:102130001188704700EF00E0202080F3118862B61C +:102140000C4B0D4AD96821F4E0610904090C0A43DB +:10215000DA60D3F8FC20094942F08072C3F8FC2011 +:102160000A6842F001020A601022DA7783F822003E +:10217000704700BF00ED00E00003FA05001000E02A +:1021800010B5202383F311880E4B5B6813F40063B2 +:1021900014D0F1EE103AEFF30984683C4FF08073ED +:1021A000E361094BDB6B236684F30988FFF714FBBB +:1021B00010B1064BA36110BD054BFBE783F31188FB +:1021C000F9E700BF00ED00E000EF00E03703000892 +:1021D0003A03000870470000FEE700000A4B0B4876 +:1021E0000B4A90420BD30B4BDA1C121AC11E22F081 +:1021F00003028B4238BF00220021FEF763BD53F873 +:10220000041B40F8041BECE790370008A82D0020C1 +:10221000A82D0020A82D00207047000070B5D0E93F +:1022200015439E6800224FF0FF3504EB4213510125 +:10223000D3F800090028BEBFD3F8000940F0804061 +:10224000C3F80009D3F8000B0028BEBFD3F8000B79 +:1022500040F08040C3F8000B013263189642C3F887 +:102260000859C3F8085BE0D24FF00113C4F81C38DA +:1022700070BD00001D4B03EB80022DE9F043D2F846 +:102280000CC05D6DDCF81420461CD2F800E005EBB4 +:10229000063605EB4018516871450AD3D5F8343835 +:1022A000012202FA00F023EA0000C5F83408BDE874 +:1022B000F083BCF81040AEEB0103A34228BF2346D5 +:1022C000D8F81849A4B2B3EB840FF0D89468A4F1FD +:1022D000040959F8047F3760A4EB09071F44042F51 +:1022E000F7D81C440B4494605360D4E7B02C002012 +:1022F000890141F02001016103699B06FCD4122091 +:10230000FFF7D4BA10B5054C2046FEF753FF4FF047 +:10231000A0436365024BA36510BD00BFB02C002035 +:102320004436000870B50378012B054650D12A4B7E +:10233000446D98421BD1294B5A6B42F080025A637C +:102340005A6D42F080025A655A6D5A6942F0800215 +:102350005A615A6922F080025A610E2143205B695A +:1023600000F0D4FB1E4BE3601E4BC4F80038002382 +:10237000C4F8003EC02323606E6D4FF40413A363C2 +:102380003369002BFCDA012333610C20FFF78EFA4E +:102390003369DB07FCD41220FFF788FA3369002B7E +:1023A000FCDA0026A6602846FFF738FF6B68C4F801 +:1023B0001068DB68C4F81468C4F81C684BB90A4B91 +:1023C000A3614FF0FF336361A36843F00103A3608F +:1023D00070BD064BF4E700BFB02C0020003802406F +:1023E0004014004003002002003C30C0083C30C0D4 +:1023F000F8B5446D054600212046FFF779FFA96D29 +:1024000000234FF001128F68C4F834384FF0006693 +:10241000C4F81C284FF0FF3004EB431201339F42F5 +:10242000C2F80069C2F8006BC2F80809C2F8080BCC +:10243000F2D20B686A6DEB65636210231361166953 +:1024400016F01006FBD11220FFF730FAD4F800384E +:1024500023F4FE63C4F80038A36943F4402343F037 +:102460001003A3610923C4F81038C4F814380A4BC8 +:10247000EB604FF0C043C4F8103B084BC4F8003B7E +:10248000C4F81069C4F80039EB6D03F1100243F48D +:102490008013EA65A362F8BD203600084080001072 +:1024A000426D90F84E10D2F8003823F4FE6343EAF0 +:1024B0000113C2F8003870472DE9F84300EB81039F +:1024C000456DDA68166806F00306731E022B05EBED +:1024D00041130C4680460FFA81F94FEA41104FF044 +:1024E0000001C3F8101B4FF0010104F1100398BF65 +:1024F000B60401FA03F391698EBF334E06F180569C +:1025000006F5004600293AD0578A04F158014901DE +:1025100037436F50D5F81C180B43C5F81C382B18DF +:102520000021C3F8101953690127611EA7409BB30E +:10253000138A928B9B08012A88BF5343D8F85C20EA +:10254000981842EA034301F1400205EB8202C8F801 +:102550005C00214653602846FFF7CAFE08EB89005D +:10256000C3681B8A43EA8453483464011E432E51D6 +:10257000D5F81C381F43C5F81C78BDE8F88305EB77 +:102580004917D7F8001B21F40041C7F8001BD5F804 +:102590001C1821EA0303C0E704F13F0305EB8303A2 +:1025A0000A4A5A6028462146FFF7A2FE05EB491069 +:1025B000D0F8003923F40043C0F80039D5F81C38AE +:1025C00023EA0707D7E700BF0080001000040002DD +:1025D000826D1268C265FFF721BE00005831436D5D +:1025E00049015B5813F4004004D013F4001F0CBFE2 +:1025F00002200120704700004831436D49015B58BB +:1026000013F4004004D013F4001F0CBF022001207B +:102610007047000000EB8101CB68196A0B681360FA +:102620004B6853607047000000EB810330B5DD68F4 +:10263000AA691368D36019B9402B84BF4023136083 +:102640006B8A1468426D1C44013CB4FBF3F4634391 +:10265000033323F0030302EB411043EAC44343F086 +:10266000C043C0F8103B2B6803F00303012B09B2F1 +:102670000ED1D2F8083802EB411013F4807FD0F865 +:10268000003B14BF43F0805343F00053C0F8003BBD +:1026900002EB4112D2F8003B43F00443C2F8003B86 +:1026A00030BD00002DE9F041244D6E6D06EB401366 +:1026B0000446D3F8087BC3F8087B38070AD5D6F858 +:1026C0001438190706D505EB84032146DB68284634 +:1026D0005B689847FA071FD5D6F81438DB071BD577 +:1026E00005EB8403D968CCB98B69488A5A68B2FB78 +:1026F000F0F600FB16228AB91868DA6890420DD20B +:10270000121AC3E90024202383F311880B482146C1 +:10271000FFF78AFF84F31188BDE8F081012303FAF3 +:1027200004F26B8923EA02036B81CB68002BF3D0A0 +:1027300021460248BDE8F041184700BFB02C0020F8 +:1027400000EB810370B5DD68436D6C692668E66057 +:102750004A0156BB1A444FF40020C2F810092A68F7 +:1027600002F00302012A0AB20ED1D3F8080803EBE3 +:10277000421410F4807FD4F8000914BF40F0805058 +:1027800040F00050C4F8000903EB4212D2F80009EF +:1027900040F00440C2F80009D3F83408012202FADC +:1027A00001F10143C3F8341870BD19B9402E84BF3C +:1027B0004020206020682E8A8419013CB4FBF6F486 +:1027C00040EAC44040F000501A44C6E7F8B5044659 +:1027D0001E48456D05EB4413D3F80869C3F8086932 +:1027E000F10717D5D5F81038DA0713D500EB8403B5 +:1027F000D9684B691F68DA68974218D2D21B002744 +:102800001A605F60202383F311882146FFF798FF49 +:1028100087F31188330617D5D5F834280123A34050 +:10282000134211D02046BDE8F840FFF723BD012335 +:1028300003FA04F2038923EA020303818B68002B65 +:10284000E8D021469847E5E7F8BD00BFB02C00204E +:102850002DE9F74F984C666D7569B3691D4015F405 +:102860008058756107D02046FEF70AFD03B0BDE829 +:10287000F04FFFF785BC002D12DAD6F8003E8E48E7 +:102880009F071EBFD6F8003E23F00303C6F8003EA4 +:10289000D6F8043823F00103C6F80438FEF718FD13 +:1028A000280505D58448FFF7B9FC8348FEF700FDED +:1028B000A9040CD5D6F8083813F0060FF36823F4F2 +:1028C00070530CBF43F4105343F4A053F3602A0732 +:1028D00004D56368DB680BB177489847EB0274D482 +:1028E000AF0227D5D4F85490DFF8CCB100274FF0D1 +:1028F000010A09EB4712D2F8003B03F44023B3F579 +:10290000802F11D1D2F8003B002B0DDA62890AFA30 +:1029100007F322EA0303638104EB8703DB68DB68C8 +:1029200013B1394658469847A36D01379B68FFB2EB +:102930009F42DED9E80617D5676D3A6AC2F30A10DE +:1029400002F00F0302F4F012B2F5802F00F088803D +:10295000B2F5402F08D104EB83030022DB681B6A29 +:1029600007F5805790426DD12903D6F8184813D542 +:10297000E20302D50020FFF795FEA30302D5012054 +:10298000FFF790FE670302D50220FFF78BFE2603B8 +:1029900002D50320FFF786FE6D037FF567AFE007E2 +:1029A00002D50020FFF712FFA10702D50120FFF793 +:1029B0000DFF620702D50220FFF708FF23077FF50E +:1029C00055AF0320FFF702FF50E7636DDFF8E8B073 +:1029D000019300274FF0010AA36D9B685FFA87F906 +:1029E00099453FF67DAF019B03EB4913D3F80029CE +:1029F00002F44022B2F5802F22D1D3F80029002A18 +:102A00001EDAD3F8002942F09042C3F80029D3F827 +:102A10000029002AFBDB606D4946FFF769FC22892B +:102A20000AFA09F322EA0303238104EB8903DB6832 +:102A30009B6813B14946584698474846FFF71AFC29 +:102A40000137C9E7910708BFD7F80080072A98BF68 +:102A500003F8018B02F1010298BF4FEA182881E7C1 +:102A6000023304EB830207F580575268D2F818C08E +:102A7000DCF80820DCE9001CA1EB0C0C00218842EA +:102A80000AD104EB830463689B699A6802449A60E4 +:102A90005A6802445A6067E711F0030F08BFD7F87D +:102AA00000808C4588BF02F8018B01F1010188BFCD +:102AB0004FEA1828E3E700BFB02C0020436D03EB7A +:102AC0004111D1F8003B43F40013C1F8003B7047BB +:102AD000436D03EB4111D1F8003943F40013C1F801 +:102AE00000397047436D03EB4111D1F8003B23F4EB +:102AF0000013C1F8003B7047436D03EB4111D1F85F +:102B0000003923F40013C1F80039704700F1604325 +:102B100003F561430901C9B283F80013012200F0F3 +:102B20001F039A4043099B0003F1604303F561438F +:102B3000C3F880211A60704730B5039C01720433DA +:102B400004FB0325C0E90653049B03630021059B96 +:102B5000C160C0E90000C0E90422C0E90842C0E940 +:102B60000A11436330BD0000416A0022C0E904112C +:102B7000C0E90A22C2606FF00101FEF707BF000042 +:102B8000D0E90432934201D1C2680AB9181D7047D6 +:102B90000020704703691960C2680132C260C269CF +:102BA000134482690361934224BF436A0361002195 +:102BB000FEF7E0BE38B504460D46E3683BB16269F6 +:102BC000131D1268A3621344E362002007E0237A16 +:102BD00033B929462046FEF7BDFE0028EDDA38BDA0 +:102BE0006FF00100FBE70000C368C269013BC360EE +:102BF0004369134482694361934224BF436A43613A +:102C000000238362036B03B11847704770B520231C +:102C1000044683F31188866A3EB9FFF7CBFF054669 +:102C200018B186F31188284670BDA36AE26A13F8CA +:102C3000015BA362934202D32046FFF7D5FF002336 +:102C400083F31188EFE700002DE9F84F04460E46A4 +:102C5000174698464FF0200989F311880025AA46A7 +:102C6000D4F828B0BBF1000F09D141462046FFF748 +:102C7000A1FF20B18BF311882846BDE8F88FD4E975 +:102C80000A12A7EB050B521A934528BF9346BBF1D6 +:102C9000400F1BD9334601F1400251F8040B43F8B1 +:102CA000040B9142F9D1A36A40334036A362403508 +:102CB000D4E90A239A4202D32046FFF795FF8AF30C +:102CC0001188BD42D8D289F31188C9E730465A46E7 +:102CD000FDF7D2FFA36A5B445E44A3625D44E7E76D +:102CE00010B5029C0172043304FB0321C0E90613F2 +:102CF0000023C0E90A33039B0363049BC460C0E95B +:102D00000000C0E90422C0E90842436310BD00008E +:102D1000026AC260426AC0E904220022C0E90A22B3 +:102D20006FF00101FEF732BED0E904239A4201D1CF +:102D3000C26822B9184650F8043B0B607047002067 +:102D400070470000C368C2690133C360436913441C +:102D500082694361934224BF436A43610021FEF7C5 +:102D600009BE000038B504460D46E3683BB123694F +:102D70001A1DA262E2691344E362002007E0237A8D +:102D800033B929462046FEF7E5FD0028EDDA38BDC7 +:102D90006FF00100FBE7000003691960C268013AA7 +:102DA000C260C269134482690361934224BF436ACB +:102DB000036100238362036B03B11847704700006F +:102DC00070B520230D460446114683F31188866AA8 +:102DD0002EB9FFF7C7FF10B186F3118870BDA36A43 +:102DE0001D70A36AE26A01339342A36204D3E169CE +:102DF00020460439FFF7D0FF002080F31188EDE76B +:102E00002DE9F84F04460D46904699464FF0200AAA +:102E10008AF311880026B346A76A4FB9494620466F +:102E2000FFF7A0FF20B187F311883046BDE8F88F87 +:102E3000D4E90A073A1AA8EB0607974228BF1746B3 +:102E4000402F1BD905F1400355F8042B40F8042B03 +:102E50009D42F9D1A36A4033A3624036D4E90A23E4 +:102E60009A4204D3E16920460439FFF795FF8BF3BA +:102E700011884645D9D28AF31188CDE729463A46CA +:102E8000FDF7FAFEA36A3B443D44A3623E44E5E7F6 +:102E9000D0E904239A4217D1C3689BB1836A8BB1EE +:102EA000043B9B1A0ED01360C368013BC360C36927 +:102EB0001A44836902619A4224BF436A0361002372 +:102EC00083620123184670470023FBE700F088B8AF +:102ED0004FF08043002258631A610222DA60704783 +:102EE0004FF080430022DA60704700004FF08043CB +:102EF000586370474FF08043586A70474B6843608F +:102F00008B688360CB68C3600B6943614B69036264 +:102F10008B6943620B6803607047000008B5264B5D +:102F200026481A6940F2FF110A431A611A6922F40D +:102F3000FF7222F001021A611A691A6B0A431A63BE +:102F40001A6D0A431A651E4A1B6D1146FFF7D6FF1C +:102F500002F11C0100F58060FFF7D0FF02F138019B +:102F600000F58060FFF7CAFF02F1540100F58060B0 +:102F7000FFF7C4FF02F1700100F58060FFF7BEFFAC +:102F800002F18C0100F58060FFF7B8FF02F1A801A3 +:102F900000F58060FFF7B2FF02F1C40100F5806028 +:102FA000FFF7ACFF02F1E00100F58060FFF7A6FF3C +:102FB000BDE8084000F09AB8003802400000024026 +:102FC0005036000808B500F007FAFEF733FCFFF7AB +:102FD0008DF8BDE80840FEF755BE000070470000C0 +:102FE000104B1A6C42F001021A641A6E42F0010290 +:102FF0001A660D4A1B6E936843F0010393604FF00D +:10300000804353229A624FF0FF32DA6200229A61C3 +:103010005A63DA605A6001225A6108211A601C2042 +:10302000FFF774BD00380240002004E04FF08042FA +:1030300008B51169D3680B40D9B2C9439B07116128 +:1030400007D5202383F31188FEF714FC002383F3B4 +:10305000118808BD08B5FFF7E9FFBDE80840FFF794 +:103060008FB800001F4B1A696FEAC2526FEAD25242 +:103070001A611A69C2F308021A614FF0FF301A6927 +:103080005A69586100215A6959615A691A6A62F08D +:1030900080521A621A6A02F080521A621A6A5A6AD6 +:1030A00058625A6A59625A6A1A6C42F080521A641B +:1030B0001A6E42F080521A661A6E0B4A106840F47B +:1030C00080701060186F00F44070B0F5007F1EBF74 +:1030D0004FF4803018671967536823F40073536006 +:1030E00000F05AB90038024000700040334B4FF0F6 +:1030F00080521A64324A4FF4404111601A6842F01B +:1031000001021A601A689107FCD59A6822F003023E +:103110009A602A4B9A6812F00C02FBD1196801F0F0 +:10312000F90119609A601A6842F480321A601A68CC +:103130009203FCD55A6F42F001025A671F4B5A6F37 +:103140009007FCD51F4A5A601A6842F080721A60D4 +:103150001B4A53685904FCD5184B1A689201FCD5D8 +:10316000194A9A60194B1A68194B9A42194B21D186 +:10317000194A1168194A91421CD140F205121A608D +:10318000144A136803F00F03052BFAD10B4B9A680E +:1031900042F002029A609A6802F00C02082AFAD100 +:1031A0005A6C42F480425A645A6E42F480425A6623 +:1031B0005B6E704740F20572E1E700BF00380240E5 +:1031C000007000400854400700948838002004E054 +:1031D00011640020003C024000ED00E041C20F41BC +:1031E000084A08B5516913680B4003F001035361A5 +:1031F00023B1054A13680BB150689847BDE80840F1 +:10320000FEF7BEBF003C0140282D0020084A08B54B +:10321000516913680B4003F00203536123B1054A5F +:1032200093680BB1D0689847BDE80840FEF7A8BF87 +:10323000003C0140282D0020084A08B55169136858 +:103240000B4003F00403536123B1054A13690BB12A +:1032500050699847BDE80840FEF792BF003C014026 +:10326000282D0020084A08B5516913680B4003F067 +:103270000803536123B1054A93690BB1D06998479C +:10328000BDE80840FEF77CBF003C0140282D00202F +:10329000084A08B5516913680B4003F010035361E5 +:1032A00023B1054A136A0BB1506A9847BDE808403C +:1032B000FEF766BF003C0140282D0020174B10B5DB +:1032C0005A691C68144004F478725A61A30604D544 +:1032D000134A936A0BB1D06A9847600604D5104A26 +:1032E000136B0BB1506B9847210604D50C4A936BB6 +:1032F0000BB1D06B9847E20504D5094A136C0BB1AA +:10330000506C9847A30504D5054A936C0BB1D06C5B +:103310009847BDE81040FEF733BF00BF003C0140B6 +:10332000282D00201A4B10B55A691C68144004F46B +:103330007C425A61620504D5164A136D0BB1506D7B +:103340009847230504D5134A936D0BB1D06D984768 +:10335000E00404D50F4A136E0BB1506E9847A104D8 +:1033600004D50C4A936E0BB1D06E9847620404D515 +:10337000084A136F0BB1506F9847230404D5054AD0 +:10338000936F0BB1D06F9847BDE81040FEF7F8BEC1 +:10339000003C0140282D0020062108B50846FFF713 +:1033A000B5FB06210720FFF7B1FB06210820FFF738 +:1033B000ADFB06210920FFF7A9FB06210A20FFF734 +:1033C000A5FB06211720FFF7A1FBBDE80840062159 +:1033D0002820FFF79BBB000008B5FFF743FE00F075 +:1033E0000BF8FDF7E5FEFDF7BDFDFFF7F7FDBDE8C6 +:1033F0000840FFF76BBD00000023054A1946013362 +:10340000102BC2E9001102F10802F8D1704700BF89 +:10341000282D0020034611F8012B03F8012B002A68 +:10342000F9D1704753544D3332463F3F3F000000BF +:1034300053544D3332463430780053544D33324672 +:103440003432780053544D333246343436585800B1 +:1034500000000000243400083F00000013040000B6 +:10346000303400083F000000190400003A3400081E +:103470003F00000021040000443400083F00000029 +:1034800000000000E10E0008CD0E0008090F000842 +:10349000F50E0008010F0008ED0E0008D90E000817 +:1034A000C50E0008150F0008000000000100000014 +:1034B000000000006D61696E0000000069646C65C9 +:1034C00000000000BC340008D82300205025002054 +:1034D000010000003118000800000000417264750E +:1034E00050696C6F740025424F415244252D424C67 +:1034F000002553455249414C2500000002000000C0 +:1035000000000000FD1000086911000840004000A4 +:10351000E8290020F8290020020000000000000037 +:103520000300000000000000AD11000800000000D2 +:1035300010000000082A0020000000000100000028 +:1035400000000000B02C002001010200211C000836 +:10355000311B0008CD1B0008B11B00084300000010 +:103560006435000809024300020100C0320904006A +:1035700000010202010005240010010524010001E0 +:10358000042402020524060001070582030800FF47 +:1035900009040100020A00000007050102400000C2 +:1035A000070581024000000012000000B03500084D +:1035B00012011001020000400912415700020102ED +:1035C000030100000403090425424F415244250031 +:1035D0004D616D6261463430352D3230323200300B +:1035E0003132333435363738394142434445460069 +:1035F00000400000004000000040000000400000CB +:1036000000000100000002000000020000000200B3 +:1036100000000200000002000000020000000200A2 +:1036200000000000E51200089D150008491600087A +:1036300040004000102D0020102D0020010000004F +:10364000202D002080000000400100000300000049 +:103650000000800200000000AAAAAAAA0000000040 +:10366000FFFF00000000000000A00A0000000000B2 +:1036700000000000AAAAAAAA00000000FFFF0000A4 +:1036800000000000000000000004005000000000E6 +:10369000AAAAAAAA00000000FF3F00000000000044 +:1036A000000000000000000000000000AAAAAAAA72 +:1036B00000000000FFFF000000000000000000000C +:1036C0000000000000000000AAAAAAAA0000000052 +:1036D000FFFF0000000000000000000000000000EC +:1036E00000000000AAAAAAAA00000000FFFF000034 +:1036F00000000000000000000000000000000000CA +:10370000AAAAAAAA00000000FFFF00000000000013 +:103710000000000000000000000000000A0000009F +:103720000000000003000000000000000000000096 +:103730000000000000000000000000000000000089 +:103740000000000000000000000000000000000079 +:103750000E0400000000000000400F000000000008 +:10376000FF0096000000000800960000000008001E +:1037700004000000C4350008000000000000000044 +:103780000000000000000000000000000000000039 +:00000001FF diff --git a/Tools/bootloaders/MambaH743v4_bl.bin b/Tools/bootloaders/MambaH743v4_bl.bin new file mode 100644 index 00000000000..8208a65e31a Binary files /dev/null and b/Tools/bootloaders/MambaH743v4_bl.bin differ diff --git a/Tools/bootloaders/MambaH743v4_bl.hex b/Tools/bootloaders/MambaH743v4_bl.hex new file mode 100644 index 00000000000..f5201a0d35b --- /dev/null +++ b/Tools/bootloaders/MambaH743v4_bl.hex @@ -0,0 +1,990 @@ +:020000040800F2 +:1000000000060020A1020008F90F0008790F00087F +:10001000D10F0008790F0008A50F0008A3020008FF +:10002000A3020008A3020008A3020008512300084D +:10003000A3020008A3020008A3020008A30200080C +:10004000A3020008A3020008A3020008A3020008FC +:10005000A3020008A3020008D937000805380008E9 +:10006000313800085D38000889380008A30200080C +:10007000A3020008A3020008A3020008A3020008CC +:10008000A3020008A3020008A3020008A3020008BC +:10009000A3020008A3020008A3020008B538000864 +:1000A000A3020008A3020008A3020008A30200089C +:1000B000A3020008A3020008A3020008A30200088C +:1000C000A3020008A3020008A3020008A30200087C +:1000D000A3020008A3020008A3020008A30200086C +:1000E00019390008A3020008A3020008A3020008AF +:1000F000A3020008A3020008A3020008A30200084C +:10010000A3020008A30200088D390008A30200081A +:10011000A3020008A3020008A3020008A30200082B +:10012000A3020008A3020008A3020008A30200081B +:10013000A3020008A3020008A3020008A30200080B +:10014000A3020008A3020008A3020008A3020008FB +:10015000A3020008A3020008A3020008A3020008EB +:10016000A3020008A3020008A3020008A3020008DB +:10017000A3020008BD2E0008A3020008A302000885 +:10018000A3020008A3020008A3020008A3020008BB +:10019000A3020008A3020008A3020008A3020008AB +:1001A000A3020008A3020008A3020008A30200089B +:1001B000A3020008A3020008A3020008A30200088B +:1001C000A3020008A3020008A3020008A30200087B +:1001D000A3020008A92E0008A3020008A302000839 +:1001E000A3020008A3020008A3020008A30200085B +:1001F000A3020008A3020008A3020008A30200084B +:10020000A3020008A3020008A3020008A30200083A +:10021000A3020008A3020008A3020008A30200082A +:10022000A3020008A3020008A3020008A30200081A +:10023000A3020008A3020008A3020008A30200080A +:10024000A3020008A3020008A3020008A3020008FA +:10025000A3020008A3020008A3020008A3020008EA +:10026000A3020008A3020008A3020008A3020008DA +:10027000A3020008A3020008A3020008A3020008CA +:10028000A3020008A3020008A3020008A3020008BA +:10029000A3020008A3020008A3020008A3020008AA +:1002A00002E000F000F8FEE772B63A4880F30888F2 +:1002B000394880F3098839484EF60851CEF20001DA +:1002C000086040F20000CCF200004EF63471CEF22D +:1002D00000010860BFF34F8FBFF36F8F40F2000043 +:1002E000C0F2F0004EF68851CEF200010860BFF374 +:1002F0004F8FBFF36F8F4FF00000E1EE100A4EF604 +:100300003C71CEF200010860062080F31488BFF330 +:100310006F8F02F0DBF802F07DF803F017F84FF072 +:1003200055301F491B4A91423CBF41F8040BFAE784 +:100330001C49194A91423CBF41F8040BFAE71A499B +:100340001A4A1B4B9A423EBF51F8040B42F8040B69 +:10035000F8E700201749184A91423CBF41F8040BC6 +:10036000FAE702F095F803F075F8144C144DAC421E +:1003700003DA54F8041B8847F9E700F041F8114C00 +:10038000114DAC4203DA54F8041B8847F9E702F038 +:100390007DB80000000600200022002000000008B8 +:1003A0000000002000060020583D00080022002028 +:1003B0005C220020602200207C420020A002000875 +:1003C000A0020008A0020008A00200082DE9F04FDA +:1003D0002DED108AC1F80CD0D0F80CD0BDEC108AED +:1003E000BDE8F08F002383F311882846A047002042 +:1003F00001F08EFBFEE701F009FB00DFFEE70000E5 +:1004000038B501F08DFF30B1164B00220A211A7267 +:100410005A729972DA7201F059FF054601F08EFFA7 +:100420000446D0B9104B9D4219D001339D4241F290 +:10043000883512BF044600250124002001F050FF3A +:100440000CB100F079F800F06BFD00F015FC2846C7 +:1004500000F020F900F070F8F9E70025EDE7054617 +:10046000EBE700BF00220020010007B008B500F054 +:10047000D5FBA0F120035842584108BD07B541F211 +:100480001203022101A8ADF8043000F0E5FB03B02F +:100490005DF804FB38B5202383F311881748C3683F +:1004A0000BB101F0BBFB0023154A4FF47A711348DE +:1004B00001F078FB002383F31188124C236813B1F9 +:1004C0002368013B2360636813B16368013B636089 +:1004D0000D4D2B7833B963687BB9022000F09AFC8C +:1004E000322363602B78032B07D163682BB902207A +:1004F00000F090FC4FF47A73636038BD60220020F6 +:10050000950400087C23002074220020084B1870FA +:1005100003280CD8DFE800F008050208022000F0EC +:100520006FBC022000F064BC024B00225A6070478E +:10053000742200207C230020F8B5504B504A1C4602 +:100540001968013100F0998004339342F8D1626850 +:100550004C4B9A4240F291804B4B9B6803F10063F5 +:1005600003F5C0239A4280F08880002000F09EFBB3 +:100570000220FFF7CBFF454B0021D3F8E820C3F85A +:10058000E810D3F81021C3F81011D3F81021D3F8D4 +:10059000EC20C3F8EC10D3F81421C3F81411D3F8ED +:1005A0001421D3F8F020C3F8F010D3F81821C3F8C1 +:1005B0001811D3F81821D3F8802042F00062C3F854 +:1005C0008020D3F8802022F00062C3F88020D3F886 +:1005D0008020D3F8802042F00072C3F88020D3F846 +:1005E000802022F00072C3F88020D3F8803072B6E9 +:1005F0004FF0E023C3F8084DD4E90004BFF34F8F58 +:10060000BFF36F8F224AC2F88410BFF34F8F536934 +:1006100023F480335361BFF34F8FD2F8803043F619 +:10062000E076C3F3C905C3F34E335B0103EA060C5E +:1006300029464CEA81770139C2F87472F9D2203B1D +:1006400013F1200FF2D1BFF34F8FBFF36F8FBFF3C2 +:100650004F8FBFF36F8F536923F40033536100232F +:10066000C2F85032BFF34F8FBFF36F8F202383F355 +:100670001188854680F308882047F8BD00000608E9 +:1006800020000608FFFF0508002200200044025851 +:1006900000ED00E02DE9F04F93B0B44B2022FF2194 +:1006A00000900AA89D6800F0E5FBB14A1378A3B951 +:1006B0000121B0481170C360202383F31188C368FF +:1006C0000BB101F0ABFA0023AB4A4FF47A71A948A1 +:1006D00001F068FA002383F31188009B13B1A74B44 +:1006E000009A1A60A64A1378032B03D000231370D4 +:1006F000A24A53604FF0000A009CD3465646D146AA +:10070000012000F07DFB24B19C4B1B68002B00F006 +:100710002682002000F082FA0390039B002BF2DB7C +:10072000012000F065FB039B213B1F2BE8D801A2B1 +:1007300052F823F0B5070008DD070008710800082B +:100740000107000801070008010700080309000865 +:10075000D30A0008ED0900084F0A0008770A0008CC +:100760009D0A000801070008AF0A000801070008F9 +:10077000210B00085508000801070008650B000858 +:10078000C107000855080008010700084F0A0008C3 +:100790000107000801070008010700080107000819 +:1007A0000107000801070008010700080107000809 +:1007B000710800080220FFF759FE002840F0F98177 +:1007C000009B022105A8BAF1000F08BF1C4641F2A8 +:1007D0001233ADF8143000F03FFA91E74FF47A701D +:1007E00000F01CFA071EEBDB0220FFF73FFE00289B +:1007F000E6D0013F052F00F2DE81DFE807F0030AB3 +:100800000D1013360523042105A8059300F024FAE2 +:1008100017E004215548F9E704215A48F6E7042176 +:100820005948F3E74FF01C08404608F1040800F06F +:100830003FFA0421059005A800F00EFAB8F12C0F3C +:10084000F2D101204FF0000900FA07F747EA0B0B3D +:100850005FFA8BFB00F05AFB26B10BF00B030B2B5E +:1008600008BF0024FFF70AFE4AE704214748CDE706 +:10087000002EA5D00BF00B030B2BA1D10220FFF70C +:10088000F5FD074600289BD00120002600F00EFA57 +:100890000220FFF73BFE5FFA86F8404600F016FAAA +:1008A0000446B0B1039940460136A1F140025142DD +:1008B000514100F01BFA0028EDD1BA46044641F23E +:1008C0001213022105A83E46ADF8143000F0C4F919 +:1008D00016E725460120FFF719FE244B9B68AB4223 +:1008E00007D9284600F0E4F9013040F0678104356B +:1008F000F3E70025224BBA463E461D701F4B5D6054 +:10090000A8E7002E3FF45CAF0BF00B030B2B7FF43A +:1009100057AF0220FFF7FAFD322000F07FF9B0F167 +:100920000008FFF64DAF18F003077FF449AF0F4AF8 +:1009300008EB0503926893423FF642AFB8F5807F1B +:100940003FF73EAF124BB845019323DD4FF47A7069 +:1009500000F064F90390039A002AFFF631AF039A7E +:100960000137019B03F8012BEDE700BF00220020B7 +:100970007823002060220020950400087C230020BA +:100980007422002004220020082200200C220020D3 +:1009900078220020C820FFF769FD074600283FF4B1 +:1009A0000FAF1F2D11D8C5F120020AAB25F00300AF +:1009B00084494245184428BF4246019200F034FA67 +:1009C000019AFF217F4800F055FA4FEAA803C8F3C7 +:1009D00087027C492846019300F054FA0646002815 +:1009E0003FF46DAF019B05EB830533E70220FFF772 +:1009F0003DFD00283FF4E4AE00F096F900283FF4F6 +:100A0000DFAE0027B846704B9B68BB4218D91F2F3A +:100A100011D80A9B01330ED027F0030312AA134406 +:100A200053F8203C05934046042205A9043700F002 +:100A3000E5FA8046E7E7384600F03AF90590F2E734 +:100A4000CDF81480042105A800F006F902E7002380 +:100A5000642104A8049300F0F5F800287FF4B0AEF8 +:100A60000220FFF703FD00283FF4AAAE049800F02F +:100A700051F90590E6E70023642104A8049300F0EF +:100A8000E1F800287FF49CAE0220FFF7EFFC00287D +:100A90003FF496AE049800F03FF9EAE70220FFF732 +:100AA000E5FC00283FF48CAE00F04EF9E1E70220AF +:100AB000FFF7DCFC00283FF483AE05A9142000F00A +:100AC00049F907460421049004A800F0C5F8394606 +:100AD000B9E7322000F0A2F8071EFFF671AEBB079F +:100AE0007FF46EAE384A07EB0903926893423FF6F3 +:100AF00067AE0220FFF7BAFC00283FF461AE27F092 +:100B000003074F44B9453FF4A5AE484609F104092F +:100B100000F0CEF80421059005A800F09DF8F1E75B +:100B20004FF47A70FFF7A2FC00283FF449AE00F0C2 +:100B3000FBF8002844D00A9B01330BD008220AA9F5 +:100B4000002000F09FF900283AD02022FF210AA8B7 +:100B500000F090F9FFF792FC1C4800F0DFFF13B0A3 +:100B6000BDE8F08F002E3FF42BAE0BF00B030B2BE8 +:100B70007FF426AE0023642105A8059300F062F8F7 +:100B8000074600287FF41CAE0220FFF76FFC80466A +:100B900000283FF415AEFFF771FC41F2883000F0F9 +:100BA000BDFF059800F0E6F946463C4600F0AEF978 +:100BB000A6E506464EE64FF0000901E6BA467EE697 +:100BC00037467CE67822002000220020A086010023 +:100BD0000F4B70B51B780C460133DBB2012B11D8DB +:100BE0000C4D4FF47A732968A2FB033222460E6A39 +:100BF00001462846B047844204D1074B0022012019 +:100C00001A7070BD4FF4FA7000F088FF0020F8E70A +:100C10001022002070250020B0230020002307B5FB +:100C2000024601210DF107008DF80730FFF7D0FFD4 +:100C300020B19DF8070003B05DF804FB4FF0FF30D2 +:100C4000F9E700000A46042108B5FFF7C1FF80F06C +:100C50000100C0B2404208BD30B4054C0A4601460E +:100C600023682046DD69034BAC4630BC604700BFBB +:100C700070250020A086010070B50A4E00240A4DA0 +:100C800001F0FCF9308028683388834208D901F0EC +:100C9000F1F92B6804440133B4F5C02F2B60F2D373 +:100CA00070BD00BFB22300208423002001F0C4BA2D +:100CB00000F1006000F5C0200068704700F100609E +:100CC000920000F5C02001F03BBA0000054B1A6805 +:100CD000054B1B889B1A834202D9104401F0CAB904 +:100CE0000020704784230020B223002038B504463A +:100CF000074D29B128682044BDE8384001F0D2B939 +:100D00002868204401F0BCF90028F3D038BD00BFAA +:100D1000842300200020704700F1FF5000F58F1061 +:100D2000D0F8000870470000064991F8243033B12C +:100D300000230822086A81F82430FFF7BFBF012092 +:100D4000704700BF88230020014B1868704700BF20 +:100D50000010005C244BF0B51A680446234BC2F324 +:100D60000B06120C1F885868BE4293F9085028D011 +:100D70009F89BE4206D101200C2505FB003358682F +:100D800093F9085041F201039A421CD041F2030347 +:100D90009A421AD042F201039A4218D042F2030357 +:100DA0009A4208BF5625621E0B46441E0A449342CF +:100DB0000FD214F9016F581C6EB1034600F8016C94 +:100DC000F5E70020D8E75A25EDE75925EBE7582548 +:100DD000E9E7184605E02C2482421C7001D9981CD2 +:100DE0005D70401AF0BD00BF0010005C14220020AE +:100DF000022802D1014B20229A617047001002584C +:100E0000022803D1024B4FF400129A61704700BFD1 +:100E100000100258022804D1024A536983F02003CB +:100E20005361704700100258002310B5934203D05D +:100E3000CC5CC4540133F9E710BD0000013810B593 +:100E400010F9013F3BB191F900409C4203D11AB126 +:100E50000131013AF4E71AB191F90020981A10BD56 +:100E60001046FCE703460246D01A12F9011B00297E +:100E7000FAD1704702440346934202D003F8011BA3 +:100E8000FAE770472DE9F8431F4D14460746884698 +:100E900095F8242052BBDFF870909CB395F824306D +:100EA0002BB92022FF2148462F62FFF7E3FF95F878 +:100EB00024004146C0F1080205EB8000A24228BF91 +:100EC0002246D6B29200FFF7AFFF95F82430A41B5C +:100ED00017441E449044E4B2F6B2082E85F824600C +:100EE000DBD1FFF721FF0028D7D108E02B6A03EB05 +:100EF00082038342CFD0FFF717FF0028CBD1002019 +:100F0000BDE8F8830120FBE788230020024B1A7814 +:100F1000024B1A70704700BFB0230020102200203F +:100F200010B5104C104800F0FBF821460E4800F0B8 +:100F300023F924680D48D4F89020D2F8043843F0FF +:100F40000203C2F8043800F0E9FD0949204600F028 +:100F500021FAD4F89020D2F8043823F00203C2F822 +:100F6000043810BD383B00087025002040420F00B7 +:100F7000403B00087047000000B59BB0EFF30981CB +:100F800068226846FFF750FFEFF30583044B9A6B26 +:100F9000DA6A9A6A9A6A9A6A9A6A9A6A9B6AFEE70F +:100FA00000ED00E000B59BB0EFF3098168226846D0 +:100FB000FFF73AFFEFF30583044B9A6B9A6A9A6A3C +:100FC0009A6A9A6A9A6A9B6AFEE700BF00ED00E09F +:100FD00000B59BB0EFF3098168226846FFF724FF54 +:100FE000EFF30583034B5A6B9A6A9A6A9A6A9A6A74 +:100FF0009B6AFEE700ED00E0FEE7000030B50A4422 +:10100000084D91420DD011F8013B5840082340F3A0 +:101010000004013B2C4013F0FF0384EA5000F6D19A +:10102000EFE730BD2083B8ED0268436811430160EB +:1010300003B118477047000013B5406B00F58054AA +:10104000D4F8A4381A681178042914D1017C022933 +:1010500011D11979012312898B4013420BD101A9B7 +:101060004C3002F073F8D4F8A4480246019B217971 +:10107000206800F0DFF902B010BD0000143001F06C +:10108000F5BF00004FF0FF33143001F0EFBF000058 +:101090004C3002F0C7B800004FF0FF334C3002F084 +:1010A000C1B80000143001F0C3BF00004FF0FF31A1 +:1010B000143001F0BDBF00004C3002F093B80000C6 +:1010C0004FF0FF324C3002F08DB800000020704726 +:1010D00010B500F58054D4F8A4381A6811780429A2 +:1010E00017D1017C022914D15979012352898B40EF +:1010F00013420ED1143001F055FF024648B1D4F826 +:10110000A4484FF4407361792068BDE8104000F0B6 +:101110007FB910BD406BFFF7DBBF000070470000D8 +:101120007FB5124B01250426044603600023057495 +:1011300000F1840243602946C0E902330C4B02905F +:10114000143001934FF44073009601F007FF094BF0 +:1011500004F69442294604F14C000294CDE9006360 +:101160004FF4407301F0CEFF04B070BD743A000834 +:1011700015110008391000080A68202383F311882C +:101180000B790B3342F823004B79133342F82300D9 +:101190008B7913B10B3342F8230000F58053C3F869 +:1011A000A41802230374002383F3118870470000FE +:1011B00038B5037F044613B190F85430ABB901251C +:1011C000201D0221FFF730FF04F114006FF0010130 +:1011D000257700F0CBFC04F14C0084F854506FF0FC +:1011E0000101BDE8384000F0C1BC38BD10B5012197 +:1011F00004460430FFF718FF0023237784F85430A7 +:1012000010BD000038B504460025143001F0BEFEC4 +:1012100004F14C00257701F08DFF201D84F8545017 +:101220000121FFF701FF2046BDE83840FFF750BF1E +:1012300090F8803003F06003202B06D190F88120D5 +:101240000023212A03D81F2A06D800207047222A0B +:10125000FBD1C0E91D3303E0034A426707228267DE +:10126000C3670120704700BF2C22002037B500F56E +:101270008055D5F8A4381A68117804291AD1017C50 +:10128000022917D11979012312898B40134211D1F8 +:1012900000F14C04204602F00DF858B101A9204697 +:1012A00001F054FFD5F8A4480246019B217920683B +:1012B00000F0C0F803B030BD01F10B03F0B550F8F9 +:1012C000236085B004460D46FEB1202383F31188C8 +:1012D00004EB8507301D0821FFF7A6FEFB6806F129 +:1012E0004C005B691B681BB1019001F03DFF019848 +:1012F00003A901F02BFF024648B1039B2946204673 +:1013000000F098F8002383F3118805B0F0BDFB6866 +:101310005A691268002AF5D01B8A013B1340F1D1AB +:1013200004F18002EAE70000133138B550F821409B +:10133000ECB1202383F3118804F58053D3F8A4285B +:101340001368527903EB8203DB689B695D6845B1E2 +:1013500004216018FFF768FE294604F1140001F02B +:101360002BFE2046FFF7B4FE002383F3118838BD1F +:101370007047000001F01EB901234022002110B582 +:10138000044600F8303BFFF775FD0023C4E9013344 +:1013900010BD000010B52023044683F311882422D9 +:1013A000416000210C30FFF765FD204601F024F973 +:1013B00002232370002383F3118810BD70B500EB66 +:1013C0008103054650690E461446DA6018B11022B2 +:1013D0000021FFF74FFDA06918B110220021FFF78F +:1013E00049FD31462846BDE8704001F017BA0000BB +:1013F00083682022002103F0011310B504468360A6 +:101400001030FFF737FD2046BDE8104001F092BADA +:10141000F0B4012500EB810447898D40E4683D4329 +:10142000A469458123600023A2606360F0BC01F0E1 +:10143000AFBA0000F0B4012500EB810407898D40AC +:10144000E4683D436469058123600023A260636012 +:10145000F0BC01F025BB000070B502230025044656 +:10146000242203702946C0F888500C3040F8045CF0 +:10147000FFF700FD204684F8705001F063F96368BF +:101480001B6823B129462046BDE87040184770BD4F +:10149000037880F88C300523037043681B6810B50F +:1014A00004460BB1042198470023A36010BD00003F +:1014B00090F88C20436802701B680BB10521184717 +:1014C0007047000070B590F87030044613B10023E7 +:1014D00080F8703004F18002204601F04FFA636812 +:1014E0009B68B3B994F8803013F0600535D00021C3 +:1014F000204601F0F9FC0021204601F0E9FC636878 +:101500001B6813B1062120469847062384F87030E3 +:1015100070BD204698470028E4D0B4F88630A26F0A +:101520009A4288BFA36794F98030A56F002B4FF0D3 +:10153000200380F20381002D00F0F280092284F85C +:10154000702083F3118800212046D4E91D23FFF782 +:1015500071FF002383F31188DAE794F8812003F008 +:101560007F0343EA022340F20232934200F0C58037 +:1015700021D8B3F5807F48D00DD8012B3FD0022B66 +:1015800000F09380002BB2D104F18802626702223E +:10159000A267E367C1E7B3F5817F00F09B80B3F5F5 +:1015A000407FA4D194F88230012BA0D1B4F88830C8 +:1015B00043F0020332E0B3F5006F4DD017D8B3F516 +:1015C000A06F31D0A3F5C063012B90D8636820468B +:1015D00094F882205E6894F88310B4F88430B047A1 +:1015E000002884D0436863670368A3671AE0B3F5F3 +:1015F000106F36D040F6024293427FF478AF5C4BD6 +:1016000063670223A3670023C3E794F88230012BAA +:101610007FF46DAFB4F8883023F00203A4F888306B +:10162000C4E91D55E56778E7B4F88030B3F5A06FDD +:101630000ED194F88230204684F88A3001F0E0F828 +:1016400063681B6813B10121204698470323237068 +:101650000023C4E91D339CE704F18B036367012376 +:10166000C3E72378042B10D1202383F3118820466D +:10167000FFF7BEFE85F311880321636884F88B5061 +:1016800021701B680BB12046984794F88230002BDC +:10169000DED084F88B300423237063681B68002B32 +:1016A000D6D0022120469847D2E794F884302046CD +:1016B0001D0603F00F010AD501F052F9012804D0EC +:1016C00002287FF414AF2B4B9AE72B4B98E701F0DD +:1016D00039F9F3E794F88230002B7FF408AF94F8DF +:1016E000843013F00F01B3D01A06204602D501F062 +:1016F00013FCADE701F004FCAAE794F88230002B5C +:101700007FF4F5AE94F8843013F00F01A0D01B06DF +:10171000204602D501F0E8FB9AE701F0D9FB97E7F4 +:10172000142284F8702083F311882B462A46294618 +:101730002046FFF76DFE85F31188E9E65DB11522BD +:1017400084F8702083F3118800212046D4E91D23FA +:10175000FFF75EFEFDE60B2284F8702083F311880C +:101760002B462A4629462046FFF764FEE3E700BFE2 +:10177000A43A00089C3A0008A03A000838B590F84E +:1017800070300446002B3ED0063BDAB20F2A34D824 +:101790000F2B32D8DFE803F03731310822323131F4 +:1017A0003131313131313737856FB0F886309D4274 +:1017B00014D2C3681B8AB5FBF3F203FB12556DB953 +:1017C000202383F311882B462A462946FFF732FE51 +:1017D00085F311880A2384F870300EE0142384F80E +:1017E0007030202383F31188002320461A461946BF +:1017F000FFF70EFE002383F3118838BDC36F03B1DA +:1018000098470023E7E70021204601F06DFB002107 +:10181000204601F05DFB63681B6813B1062120467A +:1018200098470623D7E7000010B590F870300446BB +:10183000142B29D017D8062B05D001D81BB110BD09 +:10184000093B022BFBD80021204601F04DFB002173 +:10185000204601F03DFB63681B6813B1062120465A +:101860009847062319E0152BE9D10B2380F8703037 +:10187000202383F3118800231A461946FFF7DAFD67 +:10188000002383F31188DAE7C3689B695B68002B48 +:10189000D5D1C36F03B19847002384F87030CEE7E9 +:1018A000024B0022C3E900339A607047B423002042 +:1018B000002382680374054B1B6899689142FBD230 +:1018C0005A6803604260106058607047B42300207B +:1018D00008B5202383F31188037C032B05D0042B48 +:1018E0000DD02BB983F3118808BD436900221A601B +:1018F0004FF0FF334361FFF7DBFF0023F2E7D0E94E +:10190000003213605A60F3E7002382680374054BCA +:101910001B6899689142FBD85A6803604260106066 +:1019200058607047B4230020054B19690874186883 +:10193000026853601A60186101230374FEF746BD04 +:10194000B42300204B1C30B5044687B00A4D10D09C +:101950002B6901A8094A00F025F92046FFF7E4FFAA +:10196000049B13B101A800F059F92B69586907B01D +:1019700030BDFFF7D9FFF8E7B4230020D1180008E5 +:1019800038B50C4D044641612B6981689A689142D3 +:1019900003D8BDE83840FFF78BBF1846FFF7B4FF08 +:1019A00001232C61014623742046BDE83840FEF730 +:1019B0000DBD00BFB4230020044B1A681B6990685A +:1019C0009B68984294BF002001207047B4230020F8 +:1019D00010B5084C236820691A68546022600122FF +:1019E00023611A74FFF790FF01462069BDE810409B +:1019F000FEF7ECBCB423002008B5FFF7DDFF18B1FB +:101A0000BDE80840FFF7E4BF08BD0000FFF7E0BFF6 +:101A1000FEE7000010B50C4CFFF742FF00F0B4F8F1 +:101A200080220A49204600F03BF8012344F8180CB4 +:101A3000037400F09DFC002383F3118862B6044810 +:101A4000BDE8104000F04CB8DC230020A83A0008A4 +:101A5000B83A000800F01CB9EFF3118020B9EFF399 +:101A60000583202282F311887047000010B530B939 +:101A7000EFF30584C4F3080414B180F3118810BD9A +:101A8000FFF7BAFF84F31188F9E70000034A5168B1 +:101A900053685B1A9842FBD8704700BF001000E003 +:101AA00082600222028270478368A3F17C0243F8BD +:101AB0000C2C026943F83C2C426943F8382C074A45 +:101AC00043F81C2CC268A3F1180043F8102C022222 +:101AD00003F8082C002203F8072C7047E5030008E0 +:101AE00010B5202383F31188FFF7DEFF00210446A1 +:101AF000FFF746FF002383F31188204610BD000046 +:101B0000024B1B6958610F20FFF70EBFB423002062 +:101B1000202383F31188FFF7F3BF000008B50146C7 +:101B2000202383F311880820FFF70CFF002383F3A1 +:101B3000118808BD49B1064B42681B6918605A609C +:101B4000136043600420FFF7FDBE4FF0FF30704785 +:101B5000B42300200368984206D01A6802605060DF +:101B600018465961FFF7A4BE7047000038B5044617 +:101B70000D462068844200D138BD036823605C6054 +:101B80004561FFF795FEF4E7054B4FF0FF3103F198 +:101B90001402C3E905220022C3E90712704700BFFF +:101BA000B423002070B51C4E05460C46C0E9032343 +:101BB00001F0B6FB334653F8142F9A420DD1306230 +:101BC0000A2C2CBF00190A302A60C5E90124C6E995 +:101BD0000555BDE8704001F08DBB316A431AE3182A +:101BE00038BF1C469368A34202D9081901F092FB42 +:101BF00073699A6894420CD85A68AC602B606A602A +:101C000015609A685D60121B9A604FF0FF33F361B4 +:101C100070BDA41A1B68ECE7B423002038B51B4C38 +:101C2000636998420DD08168D0E9003213605A6030 +:101C30000022C2609A680A449A604FF0FF33E36161 +:101C400038BD03682246002142F8143F93425A608F +:101C5000C16003D1BDE8384001F056BB9A68816885 +:101C6000256A0A449A6001F05BFB6369411B9A682C +:101C70008A42E5D9AB181D1A206A092D98BF01F1D7 +:101C80000A02BDE83840104401F044BBB4230020F0 +:101C90002DE9F041184C002704F11406656901F0A4 +:101CA0003FFB236AAA68C11A8A4215D81344D5F8A3 +:101CB0000C802362D5E9003213605A606369EF60DB +:101CC000B34201D101F020FB87F311882869C04796 +:101CD000202383F31188E1E76169B14209D01344FD +:101CE0001B1ABDE8F0410A2B2CBFC0180A3001F0C6 +:101CF00011BBBDE8F08100BFB42300200020704775 +:101D0000FEE70000704700004FF0FF307047000012 +:101D100002290CD0032904D00129074818BF00204C +:101D20007047032A05D8054800EBC20070470448F5 +:101D300070470020704700BF9C3B00083C220020F9 +:101D4000503B000870B59AB005460846144601A9F4 +:101D500000F0C2F801A8FFF785F8431C0022C6B2C4 +:101D60005B001046C5E9003423700323023404F8F5 +:101D7000013C01ABD1B202348E4201D81AB070BD21 +:101D800013F8011B013204F8010C04F8021CF1E7FE +:101D900008B5202383F311880348FFF767FA00236F +:101DA00083F3118808BD00BF7025002090F88030B3 +:101DB00003F01F02012A07D190F881200B2A03D1DA +:101DC0000023C0E91D3315E003F06003202B08D188 +:101DD000B0F884302BB990F88120212A03D81F2A2B +:101DE00004D8FFF725BA222AEBD0FAE7034A426764 +:101DF00007228267C3670120704700BF332200209B +:101E000007B5052917D8DFE801F0191603191920BD +:101E1000202383F31188104A01210190FFF7CEFAA5 +:101E2000019802210D4AFFF7C9FA0D48FFF7EAF9B8 +:101E3000002383F3118803B05DF804FB202383F3B0 +:101E400011880748FFF7B4F9F2E7202383F31188DC +:101E50000348FFF7CBF9EBE7F03A0008143B000822 +:101E60007025002038B50C4D0C4C2A460C4904F165 +:101E70000800FFF767FF05F1CA0204F110000949E5 +:101E8000FFF760FF05F5CA7204F118000649BDE8C6 +:101E90003840FFF757BF00BF483E00203C220020DB +:101EA000D03A0008DA3A0008E53A000870B504466E +:101EB00008460D46FEF7D6FFC6B220460134037829 +:101EC0000BB9184670BD32462946FEF7B7FF002809 +:101ED000F3D10120F6E700002DE9F84F05460C4646 +:101EE000FEF7C0FF2D49C6B22846FFF7DFFF08B155 +:101EF0000436F6B22A492846FFF7D8FF08B1103653 +:101F0000F6B2632E0DD8DFF89490DFF894A0DFF8D6 +:101F10009C80DFF89CB0234F2E7846B92670BDE830 +:101F2000F88F29462046BDE8F84F01F08DBD252EDB +:101F300030D1072249462846FEF780FF70B93B683A +:101F400007350B3444F80B3C7B6844F8073C3B896D +:101F500024F8033CBB7A04F8013CDDE70822514633 +:101F60002846FEF76BFFA8B9A21C0F4B1978023266 +:101F7000090911F8081002F8041C13F8011B01F0FC +:101F80000F015B4511F8081002F8031CEED118345C +:101F90000835C1E7013504F8016BBDE7BC3B00081B +:101FA000E53A0008C43B000800E8F11FD03B0008F8 +:101FB0000CE8F11FBFF34F8F044B1A695107FCD196 +:101FC000D3F810215207F8D1704700BF002000520B +:101FD00008B50D4B1B78ABB9FFF7ECFF0B4BDA687C +:101FE000D10704D50A4A5A6002F188325A60D3F800 +:101FF0000C21D20706D5064AC3F8042102F1883223 +:10200000C3F8042108BD00BFA640002000200052F4 +:102010002301674508B5114B1B78F3B9104B1A69BA +:10202000510703D5DA6842F04002DA60D3F8102194 +:10203000520705D5D3F80C2142F04002C3F80C2119 +:10204000FFF7B8FF064BDA6842F00102DA60D3F816 +:102050000C2142F00102C3F80C2108BDA64000206B +:10206000002000520F289ABF00F580604004002035 +:10207000704700004FF40030704700001020704798 +:102080000F2808B50BD8FFF7EDFF00F50033026805 +:10209000013204D104308342F9D1012008BD00206F +:1020A000FCE700000F2870B5054645D8FFF7D4FCC3 +:1020B000224CFFF77FFF0646FFF78AFF4FF0FF3302 +:1020C000072D6361C4F8143120D82361FFF772FF34 +:1020D0002B0243F02403E360E36843F08003E360F2 +:1020E00023695A07FCD42846FFF764FF4FF40031F8 +:1020F000FFF7B8FF00F002F93046FFF78BFFFFF75C +:10210000B5FC2846BDE87040FFF7BABFC4F81031EF +:10211000FFF750FFA5F108031B0243F02403C4F8A6 +:102120000C31D4F80C3143F08003C4F80C31D4F8EE +:1021300010315B07FBD4D6E7002070BD00200052B1 +:102140002DE9F84F40EA020305460C461746D8062B +:1021500002D00020BDE8F88F27F01F07DFF8D4B0C9 +:10216000FFF736FF2744BC4203D10120FFF752FF9F +:10217000F0E720222946204601F056FC10B9203510 +:102180002034F0E72B4605F120021E68711CE0D1D7 +:1021900004339A42F9D1FFF75FFC05F17843234AF3 +:1021A000B3F5801F224B28BF9A4603F1040338BFC2 +:1021B0009046A2F1080228BF9846A3F108033ABF4F +:1021C0009146DA469946FFF7F5FEC8F80060A5EBA0 +:1021D000040CD9F8002004F11C0142F00202C9F8F5 +:1021E0000020221FDAF8006016F00506FAD152F836 +:1021F000043F8A424CF80230F4D1BFF34F8FFFF70F +:10220000D9FE4FF0FF32C8F80020D9F8002022F0A4 +:102210000202C9F80020FFF729FC202221462846A7 +:1022200001F002FC0028AAD030469FE7142000529B +:10223000102100521020005210B5084C237828B10C +:102240001BB9FFF7C5FE0123237010BD002BFCD086 +:102250002070BDE81040FFF7DDBE00BFA6400020A3 +:102260000244074BD2B210B5904200D110BD441CBD +:1022700000B253F8200041F8040BE0B2F4E700BFCD +:10228000504000580E4B30B51C6F240405D41C6F11 +:102290001C671C6F44F400441C670A4C024423680A +:1022A000D2B243F480732360074B904200D130BD1B +:1022B000441C51F8045B00B243F82050E0B2F4E74C +:1022C00000440258004802585040005807B5012207 +:1022D00001A90020FFF7C4FF019803B05DF804FBDB +:1022E00013B50446FFF7F2FFA04205D0012201A971 +:1022F00000200194FFF7C6FF02B010BD0144BFF3F8 +:102300004F8F064B884204D3BFF34F8FBFF36F8FBD +:102310007047C3F85C022030F4E700BF00ED00E036 +:1023200000207047034B1A681AB9034AD2F8D02428 +:102330001A607047A84000200040025808B5FFF717 +:10234000F1FF024B1868C0F3806008BDA840002070 +:10235000EFF30983054968334A6B22F001024A63AF +:1023600083F30988002383F31188704700EF00E0AE +:10237000202080F3118862B60D4B0E4AD96821F4F3 +:10238000E0610904090C0A430B49DA60D3F8FC2028 +:1023900042F08072C3F8FC20084AC2F8B01F1168EE +:1023A00041F0010111601022DA7783F822007047B2 +:1023B00000ED00E00003FA0555CEACC5001000E0CA +:1023C000202310B583F311880E4B5B6813F4006370 +:1023D00014D0F1EE103AEFF309844FF08073683CAB +:1023E000E361094BDB6B236684F30988FFF7E4FAAA +:1023F00010B1064BA36110BD054BFBE783F31188B9 +:10240000F9E700BF00ED00E000EF00E0F70300088F +:10241000FA03000870B5BFF34F8FBFF36F8F1A4AEE +:102420000021C2F85012BFF34F8FBFF36F8F536973 +:1024300043F400335361BFF34F8FBFF36F8FC2F884 +:102440008410BFF34F8FD2F8803043F6E074C3F3AB +:10245000C900C3F34E335B0103EA0406014646EAB2 +:1024600081750139C2F86052F9D2203B13F1200F77 +:10247000F2D1BFF34F8F536943F480335361BFF3FD +:102480004F8FBFF36F8F70BD00ED00E0FEE70000DF +:102490000A4B0B480B4A90420BD30B4BC11EDA1C64 +:1024A000121A22F003028B4238BF00220021FEF7ED +:1024B000E1BC53F8041B40F8041BECE7B43D0008F2 +:1024C0007C4200207C4200207C42002070470000BB +:1024D00070B5D0E9244300224FF0FF359E6804EB2D +:1024E00042135101D3F80009002805DAD3F8000996 +:1024F00040F08040C3F80009D3F8000B002805DA4B +:10250000D3F8000B40F08040C3F8000B0132631891 +:102510009642C3F80859C3F8085BE0D24FF00113A4 +:10252000C4F81C3870BD000000EB8103D3F80CC068 +:102530002DE9F043DCF814204E1CD0F89050D2F86E +:1025400000E005EB063605EB4118506870450AD3EC +:102550000122D5F8343802FA01F123EA0101C5F865 +:102560003418BDE8F083AEEB0003BCF81040A34282 +:1025700028BF2346D8F81849A4B2B3EB840FF0D88B +:102580009468A4F1040959F8047F3760A4EB0907A3 +:102590001F44042FF7D81C44034494605360D4E7CD +:1025A000890141F02001016103699B06FCD41220DE +:1025B000FFF76CBA10B50A4C2046FEF7DDFE094B5A +:1025C000C4F89030084BC4F89430084C2046FEF70D +:1025D000D3FE074BC4F89030064BC4F8943010BDBE +:1025E000AC40002000000840083C000848410020A2 +:1025F00000000440143C000870B503780546012B28 +:102600005DD1494BD0F89040984259D1474B0E21AB +:102610006520D3F8D82042F00062C3F8D820D3F860 +:10262000002142F00062C3F80021D3F80021D3F862 +:10263000802042F00062C3F88020D3F8802022F08E +:102640000062C3F88020D3F8803000F071FC384B72 +:10265000E360384BC4F800380023D5F89060C4F824 +:10266000003EC02323604FF40413A3633369002B9F +:10267000FCDA01230C203361FFF708FA3369DB072A +:10268000FCD41220FFF702FA3369002BFCDA002693 +:102690002846A660FFF71CFF6B68C4F81068DB686B +:1026A000C4F81468C4F81C68002B3AD1224BA3610B +:1026B0004FF0FF336361A36843F00103A36070BD73 +:1026C0001E4B9842C8D1194B0E214D20D3F8D8206B +:1026D00042F00072C3F8D820D3F8002142F0007213 +:1026E000C3F80021D3F80021D3F8802042F0007213 +:1026F000C3F88020D3F8802022F00072C3F8802035 +:10270000D3F88020D3F8D82022F08062C3F8D820F4 +:10271000D3F8002122F08062C3F80021D3F8003101 +:1027200093E7074BC3E700BFAC40002000440258CA +:102730004014004003002002003C30C0484100200B +:10274000083C30C0F8B5D0F89040054600214FF065 +:1027500000662046FFF724FFD5F8941000234FF0C1 +:1027600001128F684FF0FF30C4F83438C4F81C28C9 +:1027700004EB431201339F42C2F80069C2F8006BB8 +:10278000C2F80809C2F8080BF2D20B68D5F89020FD +:10279000C5F89830636210231361166916F01006AD +:1027A000FBD11220FFF772F9D4F8003823F4FE634E +:1027B000C4F80038A36943F4402343F01003A36135 +:1027C0000923C4F81038C4F814380B4BEB604FF0F1 +:1027D000C043C4F8103B094BC4F8003BC4F810696F +:1027E000C4F80039D5F8983003F1100243F480138F +:1027F000C5F89820A362F8BDE43B000840800010B3 +:10280000D0F8902090F88A10D2F8003823F4FE63B4 +:1028100043EA0113C2F80038704700002DE9F8437D +:1028200000EB8103D0F890500C468046DA680FFA2E +:1028300081F94801166806F00306731E022B05EBAA +:1028400041134FF0000194BFB604384EC3F8101B7B +:102850004FF0010104F1100398BF06F1805601FA10 +:1028600003F3916998BF06F5004600293AD0578ACC +:1028700004F15801374349016F50D5F81C180B4338 +:102880000021C5F81C382B180127C3F81019A740E0 +:102890005369611E9BB3138A928B9B08012A88BFE0 +:1028A0005343D8F89820981842EA034301F14002B4 +:1028B0002146C8F89800284605EB82025360FFF7CE +:1028C0006FFE08EB8900C3681B8A43EA84534834CF +:1028D0001E4364012E51D5F81C381F43C5F81C78DF +:1028E000BDE8F88305EB4917D7F8001B21F4004138 +:1028F000C7F8001BD5F81C1821EA0303C0E704F150 +:102900003F030B4A2846214605EB83035A60FFF735 +:1029100047FE05EB4910D0F8003923F40043C0F816 +:102920000039D5F81C3823EA0707D7E700800010E4 +:1029300000040002D0F894201268C0F89820FFF735 +:10294000C7BD00005831D0F8903049015B5813F4EE +:10295000004004D013F4001F0CBF02200120704778 +:102960004831D0F8903049015B5813F4004004D04E +:1029700013F4001F0CBF02200120704700EB8101FF +:10298000CB68196A0B6813604B685360704700008E +:1029900000EB810330B5DD68AA691368D36019B90B +:1029A000402B84BF402313606B8A1468D0F89020BA +:1029B0001C4402EB4110013C09B2B4FBF3F4634345 +:1029C000033323F0030343EAC44343F0C043C0F896 +:1029D000103B2B6803F00303012B0ED1D2F808380B +:1029E00002EB411013F4807FD0F8003B14BF43F09A +:1029F000805343F00053C0F8003B02EB4112D2F881 +:102A0000003B43F00443C2F8003B30BD2DE9F041E8 +:102A1000D0F8906005460C4606EB4113D3F8087BCE +:102A20003A07C3F8087B08D5D6F814381B0704D535 +:102A300000EB8103DB685B689847FA071FD5D6F87F +:102A40001438DB071BD505EB8403D968CCB98B6937 +:102A5000488A5A68B2FBF0F600FB16228AB9186859 +:102A6000DA6890420DD2121AC3E90024202383F3BE +:102A7000118821462846FFF78BFF84F31188BDE8B3 +:102A8000F081012303FA04F26B8923EA02036B81CC +:102A9000CB68002BF3D021462846BDE8F04118470B +:102AA00000EB81034A0170B5DD68D0F890306C69A5 +:102AB0002668E66056BB1A444FF40020C2F810099D +:102AC0002A6802F00302012A0AB20ED1D3F80808DC +:102AD00003EB421410F4807FD4F8000914BF40F0D7 +:102AE000805040F00050C4F8000903EB4212D2F8C5 +:102AF000000940F00440C2F800090122D3F834086C +:102B000002FA01F10143C3F8341870BD19B9402E1F +:102B100084BF4020206020681A442E8A8419013C1A +:102B2000B4FBF6F440EAC44040F00050C6E70000B1 +:102B30002DE9F041D0F8906004460D4606EB4113B4 +:102B4000D3F80879C3F80879FB071CD5D6F81038F4 +:102B5000DA0718D500EB8103D3F80CC0DCF8143089 +:102B6000D3F800E0DA6896451BD2A2EB0E024FF0D4 +:102B700000081A60C3F80480202383F31188FFF74C +:102B80008FFF88F311883B0618D50123D6F8342827 +:102B9000AB40134212D029462046BDE8F041FFF772 +:102BA000C3BC012303FA01F2038923EA0203038170 +:102BB000DCF80830002BE6D09847E4E7BDE8F08168 +:102BC0002DE9F84FD0F8905004466E69AB691E406D +:102BD00016F480586E6103D0BDE8F84FFEF73CBC98 +:102BE000002E12DAD5F8003E9F0705D0D5F8003E3A +:102BF00023F00303C5F8003ED5F80438204623F03F +:102C00000103C5F80438FEF753FC300505D520460E +:102C1000FFF75EFC2046FEF73BFCB1040CD5D5F86F +:102C2000083813F0060FEB6823F470530CBF43F41D +:102C3000105343F4A053EB60320704D56368DB689C +:102C40000BB120469847F30200F1BA80B70226D5AF +:102C5000D4F8909000274FF0010A09EB4712D2F800 +:102C6000003B03F44023B3F5802F11D1D2F8003B91 +:102C7000002B0DDA62890AFA07F322EA0303638163 +:102C800004EB8703DB68DB6813B1394620469847BD +:102C90000137D4F89430FFB29B689F42DDD9F0062B +:102CA00019D5D4F89000026AC2F30A1702F00F0394 +:102CB00002F4F012B2F5802F00F0CC80B2F5402F74 +:102CC00009D104EB8303002200F58050DB681B6A06 +:102CD000974240F0B2803003D5F8185835D5E90353 +:102CE00003D500212046FFF791FEAA0303D5012159 +:102CF0002046FFF78BFE6B0303D502212046FFF72A +:102D000085FE2F0303D503212046FFF77FFEE8024F +:102D100003D504212046FFF779FEA90203D505213A +:102D20002046FFF773FE6A0203D506212046FFF70F +:102D30006DFE2B0203D507212046FFF767FEEF014A +:102D400003D508212046FFF761FE700340F1A980FA +:102D5000E90703D500212046FFF7EAFEAA0703D5BD +:102D600001212046FFF7E4FE6B0703D50221204630 +:102D7000FFF7DEFE2F0703D503212046FFF7D8FE1D +:102D8000EE0603D504212046FFF7D2FEA80603D5A0 +:102D900005212046FFF7CCFE690603D50621204613 +:102DA000FFF7C6FE2A0603D507212046FFF7C0FE1F +:102DB000EB0576D520460821BDE8F84FFFF7B8BEF1 +:102DC000D4F8909000274FF0010AD4F894305FFABD +:102DD00087FB9B689B453FF639AF09EB4B13D3F854 +:102DE000002902F44022B2F5802F24D1D3F8002923 +:102DF000002A20DAD3F8002942F09042C3F80029D3 +:102E0000D3F80029002AFBDB5946D4F89000FFF7DD +:102E1000C7FB22890AFA0BF322EA0303238104EB9E +:102E20008B03DB689B6813B1594620469847594687 +:102E30002046FFF779FB0137C7E7910701D1D0F8AA +:102E40000080072A02F101029CBF03F8018B4FEAC0 +:102E500018283DE704EB830300F58050DA68D2F8C8 +:102E600018C0DCF80820DCE9001CA1EB0C0C0021E8 +:102E70008F4208D1DB689B699A683A449A605A6825 +:102E80003A445A6027E711F0030F01D1D0F80080CF +:102E90008C4501F1010184BF02F8018B4FEA18282B +:102EA000E6E7BDE8F88F000008B50348FFF788FEA5 +:102EB000BDE80840FFF784BAAC40002008B50348DD +:102EC000FFF77EFEBDE80840FFF77ABA48410020D0 +:102ED000D0F8903003EB4111D1F8003B43F40013DC +:102EE000C1F8003B70470000D0F8903003EB41116F +:102EF000D1F8003943F40013C1F8003970470000DD +:102F0000D0F8903003EB4111D1F8003B23F40013CB +:102F1000C1F8003B70470000D0F8903003EB41113E +:102F2000D1F8003923F40013C1F8003970470000CC +:102F3000090100F16043012203F56143C9B283F83E +:102F4000001300F01F039A4043099B0003F1604304 +:102F500003F56143C3F880211A60704730B504332C +:102F6000039C0172002104FB0325C160C0E90653E4 +:102F7000049B0363059BC0E90000C0E90422C0E98B +:102F80000842C0E90A11436330BD00000022416AD3 +:102F9000C260C0E90411C0E90A226FF00101FEF726 +:102FA000E5BD0000D0E90432934201D1C2680AB9FC +:102FB000181D704700207047036919600021C2681E +:102FC0000132C260C269134482699342036124BF23 +:102FD000436A0361FEF7BEBD38B504460D46E3689B +:102FE0003BB162690020131D1268A3621344E362BF +:102FF00007E0237A33B929462046FEF79BFD0028D7 +:10300000EDDA38BD6FF00100FBE70000C368C2696C +:10301000013BC3604369134482699342436124BF07 +:10302000436A436100238362036B03B1184770470F +:1030300070B52023044683F31188866A3EB9FFF7F2 +:10304000CBFF054618B186F31188284670BDA36AE8 +:10305000E26A13F8015B9342A36202D32046FFF7B2 +:10306000D5FF002383F31188EFE700002DE9F84F27 +:1030700004460E46174698464FF0200989F31188FA +:103080000025AA46D4F828B0BBF1000F09D141466B +:103090002046FFF7A1FF20B18BF311882846BDE839 +:1030A000F88FD4E90A12A7EB050B521A934528BFF3 +:1030B0009346BBF1400F1BD9334601F1400251F852 +:1030C000040B914243F8040BF9D1A36A4036403512 +:1030D0004033A362D4E90A239A4202D32046FFF781 +:1030E00095FF8AF31188BD42D8D289F31188C9E7C8 +:1030F00030465A46FDF798FEA36A5E445D445B4441 +:10310000A362E7E710B5029C0433017204FB0321BC +:10311000C460C0E906130023C0E90A33039B0363BC +:10312000049BC0E90000C0E90422C0E908424363EF +:1031300010BD0000026A6FF00101C260426AC0E97E +:1031400004220022C0E90A22FEF710BDD0E90423C0 +:103150009A4201D1C26822B9184650F8043B0B606C +:103160007047002070470000C3680021C269013326 +:10317000C3604369134482699342436124BF436A35 +:103180004361FEF7E7BC000038B504460D46E3682E +:103190003BB1236900201A1DA262E2691344E36275 +:1031A00007E0237A33B929462046FEF7C3FC0028FE +:1031B000EDDA38BD6FF00100FBE70000036919602C +:1031C000C268013AC260C2691344826993420361D2 +:1031D00024BF436A036100238362036B03B1184772 +:1031E0007047000070B520230D460446114683F356 +:1031F0001188866A2EB9FFF7C7FF10B186F31188D0 +:1032000070BDA36A1D70A36AE26A01339342A36290 +:1032100004D3E16920460439FFF7D0FF002080F392 +:103220001188EDE72DE9F84F04460D469046994682 +:103230004FF0200A8AF311880026B346A76A4FB9D7 +:1032400049462046FFF7A0FF20B187F3118830469A +:10325000BDE8F88FD4E90A073A1AA8EB06079742A7 +:1032600028BF1746402F1BD905F1400355F8042B02 +:103270009D4240F8042BF9D1A36A40364033A36243 +:10328000D4E90A239A4204D3E16920460439FFF7BE +:1032900095FF8BF311884645D9D28AF31188CDE783 +:1032A00029463A46FDF7C0FDA36A3D443E443B44EF +:1032B000A362E5E7D0E904239A4217D1C3689BB122 +:1032C000836A8BB1043B9B1A0ED01360C368013B29 +:1032D000C360C3691A4483699A42026124BF436A86 +:1032E0000361002383620123184670470023FBE734 +:1032F00000F0DAB8034B002258631A610222DA6048 +:10330000704700BF000C0040014B0022DA6070479C +:10331000000C0040014B5863704700BF000C004098 +:10332000014B586A704700BF000C00404B68436077 +:103330008B688360CB68C3600B6943614B69036230 +:103340008B6943620B6803607047000008B53C4B13 +:1033500040F2FF713B48D3F888200A43C3F8882025 +:10336000D3F8882022F4FF6222F00702C3F88820F5 +:10337000D3F88820D3F8E0200A43C3F8E020D3F83C +:1033800008210A43C3F808212F4AD3F8083111460F +:10339000FFF7CCFF00F5806002F11C01FFF7C6FFCC +:1033A00000F5806002F13801FFF7C0FF00F5806092 +:1033B00002F15401FFF7BAFF00F5806002F17001DD +:1033C000FFF7B4FF00F5806002F18C01FFF7AEFF5C +:1033D00000F5806002F1A801FFF7A8FF00F580600A +:1033E00002F1C401FFF7A2FF00F5806002F1E001E5 +:1033F000FFF79CFF00F5806002F1FC01FFF796FFEC +:1034000002F58C7100F58060FFF790FF00F000F985 +:103410000E4BD3F8902242F00102C3F89022D3F869 +:10342000942242F00102C3F894220522C3F89820A6 +:103430004FF06052C3F89C20054AC3F8A02008BD95 +:103440000044025800000258203C000800ED00E053 +:103450001F00080308B500F0C9FAFEF7DBFA0F4BAE +:10346000D3F8DC2042F04002C3F8DC20D3F804217A +:1034700022F04002C3F80421D3F80431084B1A6843 +:1034800042F008021A601A6842F004021A60FEF75D +:1034900049FFBDE80840FEF7E5BC00BF0044025804 +:1034A0000018024870470000114BD3F8E82042F0A2 +:1034B0000802C3F8E820D3F8102142F00802C3F84C +:1034C00010210C4AD3F81031D36B43F00803D363B7 +:1034D000C722094B9A624FF0FF32DA6200229A61EA +:1034E0005A63DA605A6001225A611A60704700BF5D +:1034F000004402580010005C000C0040094A08B566 +:103500001169D3680B40D9B29B076FEA01011161C1 +:1035100007D5202383F31188FEF79CFA002383F359 +:10352000118808BD000C0040384B4FF0FF31D3F834 +:103530008020C3F88010D3F880200022C3F88020B8 +:10354000D3F88000D3F88400C3F88410D3F8840043 +:10355000C3F88420D3F88400D86F40F0FF4040F4D3 +:10356000FF0040F43F5040F03F00D867D86F20F094 +:10357000FF4020F4FF0020F43F5020F03F00D867C8 +:10358000D86FD3F888006FEA40506FEA5050C3F804 +:103590008800D3F88800C0F30A00C3F88800D3F885 +:1035A0008800D3F89000C3F89010D3F89000C3F8C7 +:1035B0009020D3F89000D3F89400C3F89410D3F877 +:1035C0009400C3F89420D3F89400D3F89800C3F87B +:1035D0009810D3F89800C3F89820D3F89800D3F83F +:1035E0008C00C3F88C10D3F88C00C3F88C20D3F86F +:1035F0008C00D3F89C00C3F89C10D3F89C10C3F83F +:103600009C20D3F89C3000F0C9B900BF0044025898 +:10361000614B0122C3F80821604BD3F8F42042F03B +:103620000202C3F8F420D3F81C2142F00202C3F8CE +:103630001C210222D3F81C31594BDA605A689104DC +:10364000FCD5584A1A6001229A60574ADA60002273 +:103650001A614FF440429A61514B9A699204FCD529 +:103660001A6842F480721A604C4B1A6F12F4407F51 +:1036700004D04FF480321A6700221A671A6842F0A9 +:1036800001021A60454B1A685007FCD500221A61E6 +:103690001A6912F03802FBD1012119604FF0804104 +:1036A00059605A67414ADA62414A1A611A6842F41B +:1036B00080321A60394B1A689103FCD51A6842F4BB +:1036C00080521A601A689204FCD53A4A3A499A62C2 +:1036D00000225A6319633949DA6399635A64384A94 +:1036E0001A64384ADA621A6842F0A8521A602B4B00 +:1036F0001A6802F02852B2F1285FF9D148229A6183 +:103700004FF48862DA6140221A622F4ADA644FF07D +:1037100080521A652D4A5A652D4A9A6532232D4AE0 +:103720001360136803F00F03022BFAD11B4B1A69C5 +:1037300042F003021A611A6902F03802182AFAD11B +:10374000D3F8DC2042F00052C3F8DC20D3F8042187 +:1037500042F00052C3F80421D3F80421D3F8DC204E +:1037600042F08042C3F8DC20D3F8042142F08042CA +:10377000C3F80421D3F80421D3F8DC2042F000423E +:10378000C3F8DC20D3F8042142F00042C3F804213E +:10379000D3F80431704700BF008000510044025844 +:1037A0000048025800C000F0020000010000FF01C4 +:1037B0000088900812102000630209012C02040006 +:1037C00047040508FD0BFF01200000200010E00069 +:1037D00000010100002000524FF0B04208B5D2F8BD +:1037E000883003F00103C2F8883023B1044A13681B +:1037F0000BB150689847BDE80840FEF7E1BD00BF37 +:10380000FC4100204FF0B04208B5D2F8883003F0F8 +:103810000203C2F8883023B1044A93680BB1D06820 +:103820009847BDE80840FEF7CBBD00BFFC41002033 +:103830004FF0B04208B5D2F8883003F00403C2F864 +:10384000883023B1044A13690BB150699847BDE829 +:103850000840FEF7B5BD00BFFC4100204FF0B0426C +:1038600008B5D2F8883003F00803C2F8883023B1D5 +:10387000044A93690BB1D0699847BDE80840FEF748 +:103880009FBD00BFFC4100204FF0B04208B5D2F808 +:10389000883003F01003C2F8883023B1044A136A59 +:1038A0000BB1506A9847BDE80840FEF789BD00BFDC +:1038B000FC4100204FF0B04310B5D3F8884004F429 +:1038C0007872C3F88820A30604D5124A936A0BB114 +:1038D000D06A9847600604D50E4A136B0BB1506B43 +:1038E0009847210604D50B4A936B0BB1D06B9847D0 +:1038F000E20504D5074A136C0BB1506C9847A30539 +:1039000004D5044A936C0BB1D06C9847BDE81040C5 +:10391000FEF756BDFC4100204FF0B04310B5D3F880 +:10392000884004F47C42C3F88820620504D5164A16 +:10393000136D0BB1506D9847230504D5124A936D52 +:103940000BB1D06D9847E00404D50F4A136E0BB14C +:10395000506E9847A10404D50B4A936E0BB1D06EFC +:103960009847620404D5084A136F0BB1506F98470B +:10397000230404D5044A936F0BB1D06F9847BDE878 +:103980001040FEF71DBD00BFFC41002008B5FFF749 +:10399000B5FDBDE80840FEF713BD0000062108B5DF +:1039A0000846FFF7C5FA06210720FFF7C1FA0621EE +:1039B0000820FFF7BDFA06210920FFF7B9FA062112 +:1039C0000A20FFF7B5FA06211720FFF7B1FA062102 +:1039D0002820FFF7ADFA09217A20FFF7A9FA07217D +:1039E0003220BDE80840FFF7A3BA000008B5FFF792 +:1039F0009BFD00F00BF8FDF7BDFCFDF78FFBFFF71B +:103A000051FDBDE80840FFF773BC00000023054AE4 +:103A100019460133102BC2E9001102F10802F8D156 +:103A2000704700BFFC41002010B5013902449042AC +:103A300001D1002005E0037811F8014FA34201D025 +:103A4000181B10BD0130F2E7034611F8012B03F8F3 +:103A5000012B002AF9D1704753544D333248373F78 +:103A60003F3F0053544D3332483734332F373533CB +:103A700000000000000000009910000885100008F8 +:103A8000C1100008AD100008B9100008A51000080A +:103A9000911000087D100008CD1000080000000003 +:103AA00001000000000000006D61696E0000000070 +:103AB00069646C6500000000B03A0008F82300203B +:103AC0007025002001000000111A0008000000000D +:103AD0004172647550696C6F740025424F415244C5 +:103AE000252D424C002553455249414C25000000EC +:103AF0000200000000000000B912000829130008AD +:103B000040004000183E0020283E00200200000037 +:103B10000000000003000000000000007113000816 +:103B20000000000010000000383E002000000000EF +:103B30000100000000000000AC4000200101020074 +:103B4000011E0008111D0008AD1D0008911D000890 +:103B500043000000583B000809024300020100C076 +:103B600032090400000102020100052400100105D1 +:103B70002401000104240202052406000107058235 +:103B8000030800FF09040100020A00000007050104 +:103B90000240000007058102400000001200000002 +:103BA000A43B000812011001020000400912415715 +:103BB00000020102030100000403090425424F41F1 +:103BC000524425004D616D626148373433763400CC +:103BD0003031323334353637383941424344454643 +:103BE0000000000000000000C51400087D17000858 +:103BF0002918000840004000E4410020E441002072 +:103C000001000000F441002080000000400100009D +:103C1000080000000001000000040000080000008F +:103C20000001806A00000000AAAAAAAA000100649C +:103C3000FFFF00000000000000A00A0000000001DB +:103C400000000000AAAAAAAA00000001FFFF0000CD +:103C50000000000000000000000400000000000060 +:103C6000AAAAAAAA00000000FFFF000000000000AE +:103C7000000000000000000000000000AAAAAAAA9C +:103C800000000000FFFF0000000000000000000036 +:103C90004004400000000000AAAAAAAA8000400038 +:103CA000D7FF00000000000000000000000000003E +:103CB00000000000AAAAAAAA00000000FFFF00005E +:103CC00000000000000000000000000000000000F4 +:103CD000AAAAAAAA00000000FFFF0000000000003E +:103CE000000000000000000000000000AAAAAAAA2C +:103CF00000000000FFFF00000000000000000000C6 +:103D00000000000000000000AAAAAAAA000000000B +:103D1000FFFF0000000000000000000000000000A5 +:103D200000000000AAAAAAAA00000000FFFF0000ED +:103D30000000000000000000000000000000000083 +:103D4000AAAAAAAA00000000FFFF000000000000CD +:103D5000000000000000000031040000000000002E +:103D600000001A0000000000FF000000000000003A +:103D7000583A00083F00000050040000633A000871 +:103D80003F000000009600000000080096000000C0 +:103D90000008000004000000B83B0008000000001C +:103DA0000000000000000000000000000000000013 +:043DB000000000000F +:00000001FF diff --git a/Tools/bootloaders/MatekF405-STD_bl.bin b/Tools/bootloaders/MatekF405-STD_bl.bin index 5f07916aa53..2996c889c8c 100755 Binary files a/Tools/bootloaders/MatekF405-STD_bl.bin and b/Tools/bootloaders/MatekF405-STD_bl.bin differ diff --git a/Tools/bootloaders/MatekF405-STD_bl.elf b/Tools/bootloaders/MatekF405-STD_bl.elf index 1b66644b33b..c7683a9443e 100755 Binary files a/Tools/bootloaders/MatekF405-STD_bl.elf and b/Tools/bootloaders/MatekF405-STD_bl.elf differ diff --git a/Tools/bootloaders/MatekF405-STD_bl.hex b/Tools/bootloaders/MatekF405-STD_bl.hex index 8faf7af9b13..3633bca6c55 100644 --- a/Tools/bootloaders/MatekF405-STD_bl.hex +++ b/Tools/bootloaders/MatekF405-STD_bl.hex @@ -1,25 +1,25 @@ :020000040800F2 -:1000000000040020E1010008410E0008450E000830 -:10001000990E0008450E00086D0E0008E301000867 -:10002000E3010008E3010008E3010008712F000864 +:1000000000060020E1010008B10E0008310E0008D2 +:10001000890E0008310E00085D0E0008E30100089B +:10002000E3010008E3010008E3010008852100085E :10003000E3010008E3010008E3010008E301000810 :10004000E3010008E3010008E3010008E301000800 -:10005000E3010008E3010008D1310008FD31000888 -:10006000293200085532000881320008E3010008F7 +:10005000E3010008E30100084D320008793200088E +:10006000A5320008D1320008FD320008E301000883 :10007000E3010008E3010008E3010008E3010008D0 :10008000E3010008E3010008E3010008E3010008C0 -:10009000E3010008E3010008E3010008AD320008B5 +:10009000E3010008E3010008E30100082933000838 :1000A000E3010008E3010008E3010008E3010008A0 -:1000B000ED2F0008E3010008E3010008E301000858 +:1000B000C1300008E3010008E3010008E301000883 :1000C000E3010008E3010008E3010008E301000880 :1000D000E3010008E3010008E3010008E301000870 -:1000E00015330008E3010008E3010008E3010008FC +:1000E00091330008E3010008E3010008E301000880 :1000F000E3010008E3010008E3010008E301000850 :10010000E3010008E3010008E3010008E30100083F :10011000E3010008E3010008E3010008E30100082F :10012000E3010008E3010008E3010008E30100081F :10013000E3010008E3010008E3010008E30100080F -:10014000E3010008E3010008E3010008C5260008F8 +:10014000E3010008E3010008E3010008BD280008FE :10015000E3010008E3010008E3010008E3010008EF :10016000E3010008E3010008E3010008E3010008DF :10017000E3010008E3010008E3010008E3010008CF @@ -29,859 +29,870 @@ :1001B000E3010008E3010008E3010008E30100088F :1001C000E3010008E3010008E3010008E30100087F :1001D000E3010008E3010008E3010008E30100086F -:1001E00002E000F000F8FEE772B6394880F30888B4 -:1001F000384880F3098838484EF60851CEF200019D +:1001E00002E000F000F8FEE772B63A4880F30888B3 +:1001F000394880F3098839484EF60851CEF200019B :10020000086040F20000CCF200004EF63471CEF2ED :1002100000010860BFF34F8FBFF36F8F40F2000003 :10022000C0F2F0004EF68851CEF200010860BFF334 :100230004F8FBFF36F8F4FF00000E1EE100A4EF6C4 :100240003C71CEF200010860062080F31488BFF3F1 -:100250006F8F01F0FFFE02F021FE4FF055301F4975 -:100260001B4A91423CBF41F8040BFAE71C49194A6A -:1002700091423CBF41F8040BFAE71A491A4A1B4B5A -:100280009A423EBF51F8040B42F8040BF8E70020F5 -:100290001749184A91423CBF41F8040BFAE701F0B4 -:1002A000DDFE02F057FE144C144DAC4203DA54F854 -:1002B000041B8847F9E700F03FF8114C114DAC42A0 -:1002C00003DA54F8041B8847F9E701F0C5BE0000C3 -:1002D000000400200024002000000008000000208E -:1002E00000040020283700080024002028240020D3 -:1002F0002824002018300020E0010008E001000858 -:10030000E0010008E00100082DE9F04F2DED108A12 -:10031000C1F80CD0C3689D46BDEC108ABDE8F08FD3 -:10032000002383F311882846A047002001F016FB24 -:1003300001F0C6FA00DFFEE71A4B7D2270B50024FB -:100340001A700F225C709C70DC701C715C719C7167 -:10035000DC711C725C729A72DC7201F04DFE064612 -:1003600001F072FE054650B90F4B9E4217D0013383 -:100370009E4241F2883412BF054600240125002028 -:1003800001F044FE0DB100F0B5F800F02DFD00F0D5 -:10039000F5FB204600F00CF900F0ACF8F9E7044654 -:1003A000EDE700BF28240020010007B008B500F0E9 -:1003B00087FBA0F120035842584108BD07B5054B03 -:1003C00002211B88ADF8043001A800F0C7FB03B080 -:1003D0005DF804FBF8330008064991F8243033B186 -:1003E00000230822086A81F8243000F0E9BB0120CC -:1003F000704700BF482400202DE9F84F234C94F8A3 -:1004000024300546884617468BBB2E46DFF87C9085 -:10041000002F38D094F824A0BAF1000F05D1202283 -:10042000FF214846266200F0CDFCCAF10805BD4216 -:1004300028BF3D465FFA85FBAD0041462A4604EBE6 -:100440008A0000F095FC94F82430A7EB0B079B443E -:100450005FFA8BFBBBF1080F2E44A844FFB284F86F -:1004600024B0D5D1FFF7B8FF0028D1D108E0266A23 -:1004700006EB8306B042C9D0FFF7AEFF0028C4D117 -:100480000020BDE8F88F0120BDE8F88F4824002047 -:1004900010B5202383F311881248C3680BB101F013 -:1004A000E3FA0023104A0F484FF47A7101F0A0FAE2 -:1004B000002383F311880D4C236813B12368013B9B -:1004C0002360636813B16368013B6360084B1B786A -:1004D00033B9636823B9022000F036FC322363602D -:1004E00010BD00BF342400209104000878250020AE -:1004F0007024002010B5254B254953F8042F0132F4 -:1005000000D110BD8B42F8D1224C234B22689A4275 -:100510003AD9224B9B6803F1006303F580339A427A -:1005200032D2002000F044FB1D4B0220187000F076 -:10053000F9FB1C4B1A6C00221A64196E1A66196EAC -:10054000596C5A64596E5A665A6E5A6942F0800262 -:100550005A615A6922F080025A615A691A6942F056 -:1005600000521A611A6922F000521A611B6972B6B0 -:100570000D4A0E4B13601B682268202181F31188FD -:100580009D4683F30888104710BD00BFFCFF00089C -:100590001C00010804000108FFFF000828240020B7 -:1005A000702400200038024008ED00E0000001083F -:1005B0002DE9F04F99B0B34C01902022FF2110A8F3 -:1005C000A66800F0FFFBB04A1378A346A3B9AF4872 -:1005D0000121C3601170202383F31188C3680BB11C -:1005E00001F042FA0023AA4AA8484FF47A7101F0B8 -:1005F000FFF9002383F31188019B13B1A54B019AE6 -:100600001A60A54AA349019F0292002313704B6010 -:1006100099461C461D469846012000F083FB002F9A -:1006200000F012829B4B1B68002B40F00D8219B02A -:10063000BDE8F08F0220FFF7B9FE002840F0FB81F3 -:10064000019BB9F1000F08BF1F46944B1B88ADF802 -:100650002C3002210BA800F081FADDE74FF47A700C -:1006600000F02EFA031E0393EADB0220FFF79EFE42 -:1006700082460028E4D0039B581E042800F2DD8146 -:10068000DFE800F0030E1114170018A8052340F846 -:10069000343D042100F062FA54464FF0000856E061 -:1006A00004217848F6E704217D48F3E704217D48DA -:1006B000F0E71C24204600F07DFA04340B9004215E -:1006C0000BA800F04BFA2C2CF4D1E5E7002DB7D0A5 -:1006D000002CB5D00220FFF769FE0546002800F087 -:1006E000AF8101206C4C00F063FA0220207000F012 -:1006F00019FB4FF000095FFA89FA504600F068FADA -:10070000074658B1504600F073FA09F10109002874 -:10071000F1D12C46A9460027634B97E7012302201D -:10072000237000F0EDFA3E46DBF808309E4206D218 -:10073000304600F03FFA0130EBD10436F4E7029B7B -:1007400000261E70534BA9465E602C46374600F0CB -:1007500041FB15B1002C18BF0027FFF72FFE5BE708 -:10076000002D3FF46DAF002C3FF46AAF029B0220D6 -:10077000187000F0D7FA322000F0A2F9B0F1000AA8 -:10078000C0F25E811AF0030540F05A81DBF80820C0 -:1007900006EB0A03934200F25381BAF5807F00F220 -:1007A0004F8155450DDA4FF47A7000F089F90490C5 -:1007B000049B002BC0F244813C4A049BAB5401359E -:1007C000EFE7C820FFF7F2FD0546002800F038816A -:1007D0001F2E11D8C6F12004544528BF544610AB33 -:1007E00026F0030022463149184400F0C1FA22469F -:1007F000FF212E4800F0E6FA4FEAAA0A5FFA8AF2D1 -:100800002A493046FFF7F8FD0446002800F01A8117 -:1008100006EB8A0605469AE70220FFF7C7FD002887 -:100820003FF40EAFFFF7D8FD00283FF409AF4FF0BB -:10083000000A5346DBF8082092451CD2BAF11F0F7C -:1008400012D8109A01320FD02AF0030218A90A44D4 -:1008500052F8202C0B92184604220BA900F030FB12 -:100860000AF1040A0346E5E75046039300F0A2F9B3 -:10087000039B0B90EFE718A8042140F84C3D00F0D3 -:100880006DF964E72824002074250020342400201A -:10089000910400087825002070240020FA33000815 -:1008A0002C24002030240020FC3300087424002075 -:1008B00018A8002340F8343D642100F02BF90028EB -:1008C0007FF4BEAE0220FFF771FD00283FF4B8AE02 -:1008D0000B9800F09FF918AB43F8480D0421184617 -:1008E000CDE718A8002340F8343D642100F012F948 -:1008F00000287FF4A5AE0220FFF758FD00283FF442 -:100900009FAE0B9800F094F918AB43F8440DE5E75F -:100910000220FFF74BFD00283FF492AE00F08EF965 -:1009200018AB43F8400DD9E70220FFF73FFD002840 -:100930003FF486AE0BA9142000F086F9824618A871 -:10094000042140F83CAD00F009F951460BA896E7A8 -:10095000322000F0B5F8B0F1000AFFF671AE1AF0DF -:10096000030F7FF46DAEDBF808200AEB0803934217 -:100970003FF666AE0220FFF719FD00283FF460AE97 -:100980002AF0030AC244D0453FF4E1AE404600F0ED -:1009900011F904210A900AA800F0E0F808F104080F -:1009A000F1E74FF47A70FFF701FD00283FF448AEFD -:1009B000FFF712FD00283FF4AFAE109B01330CD0BF -:1009C000082210A90020FFF717FD00283FF4A4AE6D -:1009D0002022FF2110A800F0F5F9FFF7EFFC3748BF -:1009E00000F0C2FF23E6002D3FF42AAE002C3FF4B6 -:1009F00027AE18A8002340F8343D642100F08AF89F -:100A0000824600287FF41CAE0220FFF7CFFC0028AE -:100A10003FF416AE0390FFF7D1FC41F2883000F0AE -:100A2000A3FF0B9800F00AFA00F0D4F9039B574695 -:100A30001C461D46F0E5054689E64FF00008FFE537 -:100A40002546FDE52C4667E6002000F039F80490C5 -:100A5000049B002BFFF6E3AD012000F051F9049B4D -:100A6000213B122B3FF6D8AD01A252F823F000BF74 -:100A7000350600085D060008CD06000819060008C6 -:100A80001906000819060008610700085109000846 -:100A900019080008B1080008E30800081109000857 -:100AA000190600082909000819060008A30900080A -:100AB0004F07000819060008E7090008A086010092 -:100AC00037B5114B1A780132D2B20024012A0146FF -:100AD0008DF8074011D80D4803681D6A4FF47A73EA -:100AE0004B4301220DF10701A847012805D1084B0E -:100AF0009DF807001C7003B030BD4FF4FA7000F091 -:100B000033FF4FF0FF30F6E7002400204826002096 -:100B10008425002038B50E4B1A780132D2B2012A52 -:100B200005460ED80B4803681C6A4FF47A734B4392 -:100B300004222946A047042803D1074B002018703F -:100B400038BD4FF4FA7000F00FFF4FF0FF3038BDA2 -:100B500000240020482600208425002030B4054CC5 -:100B60002368DD69044B0A46AC460146204630BC8A -:100B7000604700BF48260020A086010070B501F044 -:100B80003FF9094C094E20700025306823788342D4 -:100B900008D901F02FF9336805440133B5F5803FDA -:100BA0003360F2D370BD00BF852500208025002072 -:100BB00001F0D4B900F1006000F5803000687047A2 -:100BC00000F10060920000F5803001F05FB9000094 -:100BD000054B1A68054B1B789B1A834202D91044B7 -:100BE00001F008B9002070478025002085250020ED -:100BF00038B5074D04462868204401F003F928B9A8 -:100C000028682044BDE8384001F014B938BD00BF61 -:100C10008025002010F0030308D1B0F5007F05D82F -:100C200000F10050A0F508400068704700207047B0 -:100C3000014BC058704700BF107AFF1F014B186866 -:100C4000704700BF002004E070B52A4B1C68C4F355 -:100C50000B03240C63B140F21342934231D040F2B3 -:100C6000194293422FD040F2214293422DD10323C7 -:100C7000214A0C2505FB03235D6893F9082042F205 -:100C800001039C4224D0B4F5805F23D041F20103DC -:100C90009C4221D041F203039C421FD041F2070342 -:100CA0009C4208BF3122441E0C44013D0B46A34226 -:100CB0001ED215F9016F581C96B1034600F8016C5D -:100CC000F5E70123D4E70223D2E73F220B4DD6E715 -:100CD0003322E3E74122E1E75A22E4E75922E2E73F -:100CE0002C2584421D7001D9981C5A70401A70BD81 -:100CF0001846FBE7002004E00C340008003400082C -:100D0000022804D1054B4FF000729A617047012808 -:100D1000FCD14FF08042024BF7E700BF00040240D5 -:100D200000000240022804D1054B4FF400729A6182 -:100D300070470128FCD14FF48042024BF7E700BF17 -:100D40000004024000000240022805D1064A53690F -:100D500083F40073536170470128FCD1034A53693F -:100D600083F48043F6E700BF000402400000024025 -:100D700010B50023934203D0CC5CC4540133F9E78F -:100D800010BD000030B5441E14F9010F0B4660B1D0 -:100D900093F90050854201F1010106D11AB993F986 -:100DA0000020801A30BD013AEEE7002AF7D1104644 -:100DB00030BD000002460346981A13F9011B0029B2 -:100DC000FAD1704702440346934202D003F8011B54 -:100DD000FAE77047024B1A78024B1A70704700BF4F -:100DE000842500200024002038B5104D104C2846E2 -:100DF00000F002F92146284600F02AF924680D483F -:100E0000626DD2F8043843F00203C2F8043800F0EF -:100E1000ABFD0949204600F027FA626DD2F804388C -:100E200023F00203C2F8043838BD00BF4826002072 -:100E3000D834000840420F00003500087047000019 -:100E4000FEE7000000B59BB0EFF309816822684619 -:100E5000FFF78EFFEFF30583034B9A6B9A6A9A6A4A -:100E60009A6A9A6A9B6AFEE700ED00E000B59BB0C3 -:100E7000EFF3098168226846FFF77AFFEFF30583F5 -:100E8000044B9A6B9A6A9A6A9A6A9A6A9A6A9B6AF5 -:100E9000FEE700BF00ED00E000B59BB0EFF3098175 -:100EA00068226846FFF764FFEFF30583034B5A6B34 -:100EB0009A6A9A6A9A6A9A6A9B6AFEE700ED00E06B -:100EC00030B5084D0A4491420BD011F8013B09247A -:100ED0005840013CF7D040F300032B4083EA500018 -:100EE000F7E730BD2083B8ED002304491A465A5075 -:100EF000C8180833802B4260F9D17047882500203C -:100F0000026843681143016003B11847704700004D -:100F100013B5446BD4F894341A681178042915D1A8 -:100F2000217C022912D11979128901238B401342A5 -:100F30000CD101A904F14C0001F02AFED4F894442C -:100F4000019B21790246206800F0DAF902B010BD59 -:100F5000143001F0ADBD00004FF0FF33143001F04C -:100F6000A7BD00004C3001F07FBE00004FF0FF3302 -:100F70004C3001F079BE0000143001F07BBD000060 -:100F80004FF0FF31143001F075BD00004C3001F01E -:100F90004BBE00004FF0FF324C3001F045BE000068 -:100FA000D0F8942438B5136819780429054601D07F -:100FB000012038BD017C0229FAD112795C89012017 -:100FC00090400440F4D105F1140001F00DFD0246FB -:100FD0000028EDD0D5F894544FF4807328686979CF -:100FE00000F07CF9204638BD406BFFF7D9BF000008 -:100FF00000207047704700007FB5124B036000234C -:1010000043608360C360012502260F4B05740446CC -:101010000290019300F18402294600964FF48073F8 -:10102000143001F0BDFC094B0193029400964FF47B -:10103000807304F52372294604F14C0001F084FD0D -:1010400004B070BD5C340008E90F0008110F0008FF -:101050000B68202282F311880A7903EB82029061E7 -:101060004A79093243F822008A7912B103EB8203EC -:10107000986102230374C0F89414002383F3118849 -:101080007047000038B5037F044613B190F8543020 -:10109000ABB9201D01250221FFF732FF04F1140036 -:1010A00025776FF0010100F087FC84F8545004F1BB -:1010B0004C006FF00101BDE8384000F07DBC38BD48 -:1010C00010B5012104460430FFF71AFF00232377EF -:1010D00084F8543010BD000038B5044600251430A3 -:1010E00001F076FC04F14C00257701F045FD201D50 -:1010F00084F854500121FFF703FF2046BDE8384033 -:10110000FFF74EBF90F8443003F06003202B19D155 -:1011100090F84520212A0AD0222A4FF000030ED051 -:10112000202A0FD1084A82630722C26304E0064BDB -:1011300083630723C3630023036401207047836331 -:10114000C363F9E70020704701240020D0F89434ED -:1011500037B51A681178042904461AD1017C02298E -:1011600017D11979128901238B40134211D100F153 -:101170004C05284601F0C0FD58B101A9284601F0F0 -:1011800007FDD4F89444019B21790246206800F0C1 -:10119000B7F803B030BD000000EB8103F7B59C69E0 -:1011A00005460E46F4B1202383F3118805EB86072C -:1011B000201D0821FFF7A4FEFB685B691B684C3407 -:1011C00013B1204601F0F2FC01A9204601F0E0FC39 -:1011D000024648B1019B3146284600F091F80023B1 -:1011E00083F3118803B0F0BDFB685A691268002AC6 -:1011F000F5D01B8A013B1340F1D105F14402EAE727 -:10120000093138B550F82140DCB1202383F311882F -:10121000D4F894241368527903EB8203DB689B694A -:101220005D6845B104216018FFF76AFE294604F1A4 -:10123000140001F0E3FB2046FFF7B2FE002383F326 -:10124000118838BD7047000000F08EBF0123037085 -:1012500000234360C36183620362C362436203632A -:10126000038143817047000038B50446202383F38F -:10127000118800254160C56005614561856100F008 -:1012800083FF0223237085F3118838BD70B500EB0E -:10129000810305465069DA600E46144618B11022E3 -:1012A0000021FFF78FFDA06918B110220021FFF780 -:1012B00089FD31462846BDE8704001F02FB8000096 -:1012C000028902F001020281428902F00102428198 -:1012D000002202614261826101F0B4B8F0B400EB17 -:1012E00081044789E4680125A4698D403D43458117 -:1012F00023600023A2606360F0BC01F0CFB800005F -:10130000F0B400EB81040789E468012564698D402D -:101310003D43058123600023A2606360F0BC01F0BF -:1013200049B9000070B50223002504460370A0F8F7 -:101330004C5080F84E5080F84F5005814581C56073 -:1013400005614561856180F8345000F083FF636872 -:101350001B6823B129462046BDE87040184770BD80 -:10136000436802781B6880F85020052202700BB198 -:101370000421184770470000436890F850201B680C -:1013800002700BB1052118477047000090F8343007 -:1013900070B5044613B1002380F8343004F14402E0 -:1013A000204601F071F863689B6863BB94F8445071 -:1013B00015F0600615D194F8453005F07F0545EA33 -:1013C000032540F202339D4200F00E815BD8022DCE -:1013D00000F0DC803FD8002D00F08780012D00F068 -:1013E000CF800021204601F0A7FA0021204601F01D -:1013F00099FA63681B6813B10621204698470623B3 -:1014000084F8343070BD204698470028CED094F838 -:101410004B2094F84A3043EA0223E26B934238BFF0 -:10142000E36394F94430E56B002B4FF0200380F226 -:10143000FD80002D00F0EC80092284F8342083F335 -:1014400011880021E36BA26B2046FFF759FF0023B0 -:1014500083F3118870BDB5F5817F00F0B180B5F5DB -:10146000407F49D0B5F5807FBBD194F84630012B41 -:10147000B7D1B4F84C3023F00203A4F84C30A66383 -:10148000E6632664C3E740F201639D421ED8B5F5CA -:10149000C06F3BD2B5F5A06FA3D1B4F84430B3F51B -:1014A000A06F0ED194F8463084F84E30204600F0FC -:1014B00029FF63681B6813B1012120469847032365 -:1014C00023700023A363E3632364A0E7B5F5106FE3 -:1014D00032D040F602439D4252D0B5F5006F80D124 -:1014E00004F14F03A363012324E004F14C03A3633D -:1014F0000223E36325648AE794F84630012B7FF4E6 -:1015000070AFB4F84C3043F00203B6E794F84920CA -:10151000616894F848304D6894F8471043EA022314 -:10152000204694F84620A84700283FF45AAF436865 -:10153000A3630368E363A4E72378042B10D120237B -:1015400083F311882046FFF7BBFE86F3118863689A -:1015500084F84F601B68032121700BB12046984727 -:1015600094F84630002BACD084F84F30042323701D -:1015700063681B68002BA4D0022120469847A0E78F -:10158000374BA3630223E36300239DE794F84810DD -:1015900011F0800F204601F00F010ED000F066FF21 -:1015A000012806D002287FF41CAF2E4BA363E06312 -:1015B00067E72D4BA363E56363E700F049FFEFE7BF -:1015C00094F84630002B7FF40CAF94F8483013F0B9 -:1015D0000F013FF476AF1A06204602D501F0C0F99C -:1015E0006FE701F0B3F96CE794F84630002B7FF415 -:1015F000F8AE94F8483013F00F013FF462AF1B06C9 -:10160000204602D501F098F95BE701F08BF958E725 -:10161000142284F8342083F311882B462A46294665 -:101620002046FFF75BFE85F3118870BD5DB1152282 -:1016300084F8342083F311880021E36BA26B2046E9 -:10164000FFF74CFE03E70B2284F8342083F3118864 -:101650002B462A4629462046FFF752FEE3E700BF05 -:101660008C340008843400088834000838B590F8B9 -:1016700034300446152B29D8DFE803F03E2828280B -:1016800028283E28280B29392828282828282828CF -:101690003E3E90F84B1090F84A20C36B42EA01227C -:1016A0009A4214D9C268128AB3FBF2F502FB1535CF -:1016B0006DB9202383F311882B462A462946FFF76C -:1016C0001FFE85F311880A2384F8343038BD1423B3 -:1016D00084F83430202383F3118800231A461946F6 -:1016E0002046FFF7FBFD002383F3118838BD036C10 -:1016F00003B198470023E7E7002101F01DF900211D -:10170000204601F00FF963681B6813B106212046DB -:1017100098470623D8E7000090F83420152A38B5FA -:10172000044622D80123934040F6416213421DD162 -:1017300013F480150FD19B0217D50B2380F834309A -:10174000202383F311882B462A462946FFF7D8FD2C -:1017500085F3118838BDC3689B695B682BB9036C3E -:1017600003B19847002384F8343038BD002101F0DC -:10177000E3F80021204601F0D5F863681B6813B137 -:101780000621204698470623EDE70000024B002281 -:101790001B605B609A60704708260020002303747A -:1017A0008268054B1B6899689142FBD25A680360B6 -:1017B00042601060586070470826002008B520235A -:1017C00083F31188037C032B05D0042B0DD02BB998 -:1017D00083F3118808BD436900221A604FF0FF337C -:1017E0004361FFF7DBFF0023F2E790E80C001A608B -:1017F00002685360F2E70000002303748268054B1F -:101800001B6899689142FBD85A6803604260106077 -:101810005860704708260020054B1969087418683D -:1018200002681A605360186101230374FEF76CBDEF -:101830000826002030B54B1C87B005460A4C10D056 -:1018400023690A4A01A800F0D3F82846FFF7E4FF0D -:10185000049B13B101A800F007F92369586907B088 -:1018600030BDFFF7D9FFF8E708260020BD170008B4 -:1018700038B50C4D41612B6981689A6891420446E4 -:1018800003D8BDE83840FFF789BF1846FFF786FF49 -:1018900001232C61014623742046BDE83840FEF741 -:1018A00033BD00BF08260020044B1A681B699068EE -:1018B0009B68984294BF00200120704708260020B2 -:1018C00010B5084C236820691A6822605460012210 -:1018D00023611A74FFF790FF01462069BDE81040AC -:1018E000FEF712BD08260020826002220274002248 -:1018F000427470478368A3F17C0243F80C2C0269A0 -:1019000043F83C2C426943F8382C074A43F81C2C16 -:10191000C26843F8102C022203F8082C002203F8B6 -:10192000072CA3F1180070472103000810B52023ED -:1019300083F31188FFF7DEFF00210446FFF798FFCD -:10194000002383F31188204610BD0000024B1B6961 -:1019500058610F20FFF760BF08260020202383F383 -:101960001188FFF7F3BF000008B50146202383F379 -:1019700011880820FFF75EFF002383F3118808BD5C -:1019800049B1064B42681B6918605A601360436096 -:101990000420FFF74FBF4FF0FF30704708260020AC -:1019A0000368984206D01A68026050605961184670 -:1019B000FFF7F4BE7047000038B504460D462068B6 -:1019C000844200D138BD036823605C604561FFF745 -:1019D000E5FEF4E7054B03F114025A619A614FF0FA -:1019E000FF32DA6100221A62704700BF0826002029 -:1019F000F8B503614FF08043C2605C6A194B1A4628 -:101A0000022952F8145F38BF0221954206461F464C -:101A10000AD1586198611C620560456081600819AF -:101A2000BDE8F84001F08AB9186AAB68241A0C19AD -:101A300002D3E41A2D6804E09C4202D2204401F053 -:101A40008BF9AB689C42F4D86B68736035601E609C -:101A50006E60B460A9684FF0FF33091BA960FB6199 -:101A6000F8BD00BF0826002010B41B4C234653F8D5 -:101A7000141F814210D0416802680A6002685160F8 -:101A80009A424FF00001C16003D0936881680B4413 -:101A900093605DF8044B70470A68626100209A42C7 -:101AA0005360C86003D15DF8044B01F04FB99368EF -:101AB0008868034493604FF08042206A526A121A89 -:101AC0009342E6D9991A012998BF931C18445DF8EE -:101AD000044B01F041B900BF0826002000207047E8 -:101AE000FEE70000704700004FF0FF307047000035 -:101AF000022906D0032906D00129064818BF002074 -:101B0000704705487047032A9ABF044800EBC2009B -:101B1000002070475C3500081035000808240020BC -:101B200070B59AB001AD064608462946144600F045 -:101B300095F82846FFF73EF9C0B2431C5B0086E8E3 -:101B40001800237003236370002302341946DAB2AD -:101B5000904204F1020401D81AB070BDEA5C04F8A6 -:101B6000022C04F8011C0133F1E7000008B5202322 -:101B700083F311880348FFF7E9FA002383F3118800 -:101B800008BD00BF4826002010B50446052916D818 -:101B9000DFE801F016150316161D202383F31188C4 -:101BA0000E4A0121FFF772FB20460D4A0221FFF782 -:101BB0006DFB0C48FFF790FA002383F3118810BDEA -:101BC000202383F311880748FFF75CFAF4E720230A -:101BD00083F311880348FFF773FAEDE790340008A8 -:101BE000B43400084826002038B50C4D0C4C0D4983 -:101BF0002A4604F10800FFF793FF05F1CA0204F139 -:101C000010000949FFF78CFF05F5CA7204F11800AE -:101C10000649BDE83840FFF783BF00BF102B002006 -:101C200008240020E0340008EA340008F5340008F5 -:101C300070B5044608460D46FFF7BCF8C6B220460C -:101C4000013403780BB9184670BD32462946FFF7B8 -:101C500099F80028F3D1012070BD00002DE9F0476C -:101C600004460D46FFF7A6F82C49C6B22046FFF7FA -:101C7000DFFF08B10636F6B229492046FFF7D8FF44 -:101C800008B11036F6B2632E0BD8DFF89080DFF87B -:101C90009090244FDFF898A0267846B92E70BDE8C2 -:101CA000F08721462846BDE8F04701F09DBB252E70 -:101CB0002FD1072241462046FFF764F870B91A4B2E -:101CC0002A4603F10C0153F8040B42F8040B8B4233 -:101CD000F9D11B78137007340D35DDE7082249462A -:101CE0002046FFF74FF8A0B9104BAA1C13F8011FAC -:101CF00009095345C95D02F8021C197801F00F016A -:101D000002F10202C95D02F8031CEFD11835083454 -:101D1000C2E72E7001340135BEE700BF7C350008F4 -:101D2000F534000892350008843500080F7AFF1F4B -:101D30001B7AFF1FBFF34F8F024AD368DB03FCD42B -:101D4000704700BF003C024008B5094B1B7873B9CF -:101D5000FFF7F0FF074B1A69002ABFBF064A5A6017 -:101D600002F188325A601A6822F480621A6008BD53 -:101D70006E2D0020003C02402301674508B50B4B47 -:101D80001B7893B9FFF7D6FF094B1A6942F000425E -:101D90001A611A6842F480521A601A6822F480525A -:101DA0001A601A6842F480621A6008BD6E2D002025 -:101DB000003C02400B2870B513D80B4A0B4C13782B -:101DC00063B90B4E4FF0006144F8231056F82350CE -:101DD00001330C2B2944F7D10123137054F8200050 -:101DE00070BD002070BD00BFA02D0020702D002010 -:101DF000A4350008014B53F820007047A4350008B3 -:101E00000C2070470B2810B5044601D9002010BDE6 -:101E1000FFF7D0FF064B53F824301844C21A0BB911 -:101E2000012010BD12680132F0D1043BF6E700BF7B -:101E3000A43500080B2810B5044621D8FFF77AFF17 -:101E4000FFF782FF0F4AF323D360C300DBB243F4F2 -:101E5000007343F002031361136943F48033136189 -:101E6000FFF768FFFFF7A6FF074B53F8241000F0B9 -:101E7000DDF8FFF783FF2046BDE81040FFF7C2BF43 -:101E8000002010BD003C0240A43500082DE9F843B5 -:101E900012F00103154640D18218B2F1016F3CD215 -:101EA0002C4B1B6813F0010337D02B4CFFF74CFF72 -:101EB000F323E360FFF73EFF40F20127032D01D932 -:101EC000830713D0244C0F46401A40F20118EB1B35 -:101ED0000B44012B00EB0706236924D823F00103F0 -:101EE0002361FFF74BFF0120BDE8F883236923F44A -:101EF0004073236123693B43236151F8046B0660FF -:101F0000BFF34F8FFFF716FF03689E4208D0236987 -:101F100023F001032361FFF731FF0020BDE8F883C0 -:101F2000043D0430CAE723F440732361236943EA84 -:101F300008032361B94637F8023B3380BFF34F8F64 -:101F4000FFF7F8FE3688B9F80030B6B2B342BED01B -:101F5000DDE700BF00380240003C0240084908B5F8 -:101F60000B7828B153B9FFF7EFFE01230B7008BDC2 -:101F700023B1BDE808400870FFF700BF08BD00BFEF -:101F80006E2D002010B50244064B0439D2B29042A7 -:101F900000D110BD441C00B253F8200041F8040FDA -:101FA000E0B2F4E750280040104B30B51C6F240419 -:101FB00007D41C6F44F400741C671C6F44F4004485 -:101FC0001C670B4C236843F4807323600244094B65 -:101FD0000439D2B2904200D130BD441C00B251F855 -:101FE000045F43F82050E0B2F4E700BF003802403D -:101FF000007000405028004007B5012201A90020D0 -:10200000FFF7C0FF019803B05DF804FB13B5044669 -:10201000FFF7F2FFA04206D002A9012241F8044DC9 -:102020000020FFF7C1FF02B010BD000070470000A4 -:10203000034B1B689B0042BF024B01221A70704782 -:1020400074380240A12D0020014B1878704700BF62 -:10205000A12D002070470000FEE70000084A094B50 -:1020600009498B4204D3094A0021934205D37047A2 -:1020700052F8040F43F8040BF3E743F8041BF4E7AA -:102080004C3700081830002018300020183000208D -:10209000836D30B500229D68446D11464FF0FF30CE -:1020A00004EB421301329542C3F80019C3F810192A -:1020B000C3F80809C3F8001BC3F8101BC3F8080BCA -:1020C000EED24FF00113C4F81C3830BD890141F045 -:1020D0002001016103699B06FCD4122000F0C4BEFC -:1020E000204B03EB80022DE9F047D2F80CE05D6D48 -:1020F000DEF81420461CD2F800C005EB063605EBCE -:102100004018516861450BD3D5F83428012303FAF0 -:1021100000F022EA0000C5F834081846BDE8F08750 -:10212000BEF81040ACEB0103A34228BF2346D8F809 -:102130001849A4B2B3EB840F10D894681F46A4F1D9 -:10214000040959F804AFC6F800A0042F01D9043FD0 -:10215000F7E71C440B4494605360D2E70020BDE8CD -:10216000F08700BFA42D002010B5054C2046FFF7D6 -:102170006DF84FF0A0436365024BA36510BD00BF2F -:10218000A42D0020F83500080378012B70B5054612 -:1021900050D12A4B446D98421BD1294B5A6B42F0C7 -:1021A00080025A635A6D42F080025A655A6D5A692C -:1021B00042F080025A615A6922F080025A610E216F -:1021C00043205B6900F0D6FB1E4BE3601E4BC4F856 -:1021D00000380023C4F8003EC02323606E6D4FF426 -:1021E0000413A3633369002BFCDA012333610C2051 -:1021F00000F03AFE3369DB07FCD4122000F034FE15 -:102200003369002BFCDA0026A6602846FFF740FF62 -:102210006B68C4F81068DB68C4F81468C4F81C68FC -:102220004BB90A4BA3614FF0FF336361A36843F0DE -:102230000103A36070BD064BF4E700BFA42D00208E -:10224000003802404014004003002002003C30C02F -:10225000083C30C0F8B5446D054600212046FFF724 -:1022600035FFA96D00234FF001128F68C4F8343890 -:102270004FF00066C4F81C284FF0FF3004EB431207 -:1022800001339F42C2F80069C2F8006BC2F8080926 -:10229000C2F8080BF2D20B686A6DEB65636210231B -:1022A0001361166916F01006FBD1122000F0DCFD58 -:1022B000D4F8003823F4FE63C4F80038A36943F46B -:1022C000402343F01003A3610923C4F81038C4F875 -:1022D00014380A4BEB604FF0C043C4F8103B084B76 -:1022E000C4F8003BC4F81069C4F80039EB6D03F181 -:1022F000100243F48013EA65A362F8BDD4350008E8 -:1023000040800010426D90F84E10D2F8003823F44F -:10231000FE6343EA0113C2F8003870472DE9F0412B -:102320000EB200EB86080D46D8F80C100F6807F0C7 -:102330000303022B50D0032B50D03D4A3D4F012BBD -:1023400018BF1746446D4FEA451E04EB0E030022EA -:10235000C3F8102B8A6905F1100C002A40D04A8A74 -:1023600005F158035B013A43E2500123D4F81C28DD -:1023700003FA0CF31343A6444A69C4F81C3800233B -:10238000CEF8103905F13F03002A39D00A8A898B2B -:102390009208012988BF4A43C16D04EB8303561894 -:1023A00041EA0242C66529465A602046FFF78EFE82 -:1023B000D8F80C301B8A43EA85531F4305F14803C4 -:1023C0005B01E7500123D4F81C2803FA05F51543F7 -:1023D000C4F81C58BDE8F081174FB3E7174FB1E7B9 -:1023E00004EB4613D3F8002B22F40042C3F8002B71 -:1023F000D4F81C28012303FA0CF322EA0303BAE7FA -:1024000004EB83030E4A5A6004EB46162946204625 -:10241000FFF75CFED6F8003923F40043C6F8003914 -:10242000D4F81C38012202FA05F523EA0505CFE7A6 -:1024300000800010008004100080081000800C1044 -:1024400000040002826D1268C265FFF721BE000021 -:102450005831436D49015B5813F4004004D013F424 -:10246000001F14BF01200220704700004831436D57 -:1024700049015B5813F4004004D013F4001F14BF4B -:10248000012002207047000000EB8101CB68196A2F -:102490000B6813604B6853607047000000EB8103CA -:1024A00030B5DD68AA691368D36019B9402B84BFC1 -:1024B000402313606B8A1468426D1C44013CB4FBDA -:1024C000F3F46343033323F0030302EB411043EAC5 -:1024D000C44343F0C043C0F8103B2B6803F0030330 -:1024E000012B09B20ED1D2F8083802EB411013F4D7 -:1024F000807FD0F8003B14BF43F0805343F000537B -:10250000C0F8003B02EB4112D2F8003B43F0044319 -:10251000C2F8003B30BD00002DE9F041244D6E6D46 -:1025200006EB40130446D3F8087BC3F8087B380752 -:102530000AD5D6F81438190706D505EB84032146C9 -:10254000DB6828465B689847FA072FD5D6F8143819 -:10255000DB072BD505EB8403D968CCB98B69488A96 -:102560005E68B6FBF0F200FB12628AB91868DA689E -:1025700090420DD2121A83E81400202383F31188AD -:102580000B482146FFF78AFF84F31188BDE8F081EC -:10259000012303FA04F26B8923EA02036B81CB68FF -:1025A00023B121460248BDE8F0411847BDE8F0815B -:1025B000A42D002000EB810370B5DD68436D6C69CC -:1025C0002668E6604A0156BB1A444FF40020C2F860 -:1025D00010092A6802F00302012A0AB20ED1D3F8C8 -:1025E000080803EB421410F4807FD4F8000914BFEC -:1025F00040F0805040F00050C4F8000903EB421254 -:10260000D2F8000940F00440C2F80009D3F83408B9 -:10261000012202FA01F10143C3F8341870BD19B95F -:10262000402E84BF4020206020682E8A841940F00C -:102630000050013C1A44B4FBF6F440EAC440C6E73B -:10264000F8B504461E48456D05EB4413D3F80869F8 -:10265000C3F80869F10717D5D5F81038DA0713D58C -:1026600000EB8403D9684B691F68DA68974218D277 -:10267000D21B00271A605F60202383F31188214654 -:10268000FFF798FF87F31188330617D5D5F834285C -:102690000123A340134211D02046BDE8F840FFF7C4 -:1026A0001FBD012303FA04F2038923EA0203038115 -:1026B0008B68002BE8D021469847E5E7F8BD00BFBE -:1026C000A42D002096482DE9F84F456D6E69AB6941 -:1026D0001E4016F4805F6E61044605D0FEF722FEB0 -:1026E000BDE8F84F00F054BC002E12DAD5F8003ED9 -:1026F0008B489B071EBFD5F8003E23F00303C5F8A7 -:10270000003ED5F8043823F00103C5F80438FEF77D -:1027100033FE370502D58248FEF722FEB0040CD501 -:10272000D5F8083813F0060FEB6823F470530CBF8C -:1027300043F4105343F4A053EB60310704D56368AE -:10274000DB680BB176489847F2025AD4B3020CD535 -:10275000D4F85480DFF8C8A100274FF00109A36D19 -:102760009B68F9B28B4280F08780F70619D5616DBE -:102770000A6AC2F30A1702F00F0302F4F012B2F56C -:10278000802F00F0A180B2F5402F0AD104EB830323 -:1027900001F58051DB68186A00231A469F4240F019 -:1027A00087803003D5F8184813D5E10302D50020FF -:1027B000FFF7B2FEA20302D50120FFF7ADFE6303CF -:1027C00002D50220FFF7A8FE270302D50320FFF75A -:1027D000A3FE750384D5E00702D50020FFF730FF84 -:1027E000A10702D50120FFF72BFF620702D50220C7 -:1027F000FFF726FF23077FF573AF0320FFF720FFC6 -:102800006EE7D4F85480DFF818A100274FF00109D3 -:10281000A36D9B685FFA87FB5B4597D308EB4B136F -:10282000D3F8002902F44022B2F5802F22D1D3F848 -:102830000029002A1EDAD3F8002942F09042C3F89A -:102840000029D3F80029002AFBDB5946606DFFF709 -:102850003DFC228909FA0BF322EA0303238104EBEE -:102860008B03DB689B6813B159465046984758461E -:10287000FFF736FC0137CBE708EB4112D2F8003BFB -:1028800003F44023B3F5802F10D1D2F8003B002B86 -:102890000CDA628909FA01F322EA0303638104EB8B -:1028A0008103DB68DB680BB150469847013756E778 -:1028B0009C0708BF0A68072B98BF027003F1010349 -:1028C0009CBF120A013069E7023304EB830201F571 -:1028D0008051526890690268D0F808C04068A2EB45 -:1028E000000E0022104697420AD104EB830463686D -:1028F0009B699A683A449A605A6817445F6050E747 -:1029000012F0030F08BF0868964588BF8CF80000D6 -:1029100002F1010284BF000A0CF1010CE3E700BFE1 -:10292000A42D0020436D03EB4111D1F8003B43F48B -:102930000013C1F8003B7047436D03EB4111D1F820 -:10294000003943F40013C1F800397047436D03EBBD -:102950004111D1F8003B23F40013C1F8003B70474C -:10296000436D03EB4111D1F8003923F40013C1F892 -:102970000039704700F1604300F01F02400903F581 -:10298000614309018000C9B200F1604083F800137F -:1029900000F5614001239340C0F880310360704727 -:1029A00030B5039C0172043304FB0325C361049B0F -:1029B00003630021059B00604060C16042610261C9 -:1029C0008561046242628162C162436330BD00007E -:1029D0000022416A41610161C2608262C2626FF09D -:1029E0000101FEF7E9BF000003694269934203D188 -:1029F000C2680AB100207047181D7047036919604A -:102A0000C2680132C260C2691344826903619342A1 -:102A100024BF436A03610021FEF7C2BF38B50446F4 -:102A20000D46E3683BB16269131D1268A36213444B -:102A3000E362002038BD237A33B929462046FEF7E9 -:102A40009FFF0028EDDA38BD6FF00100FBE70000C2 -:102A5000C368C269013BC36043691344826943612F -:102A6000934224BF436A436100238362036B03B133 -:102A70001847704770B52023044683F31188866A8F -:102A80003EB9FFF7CBFF054618B186F311882846FB -:102A900070BDA36AE26A13F8015BA362934202D39A -:102AA0002046FFF7D5FF002383F31188EFE70000EE -:102AB0002DE9F84F04460E4690469946202787F3A5 -:102AC00011880025AA46D4F828B0BBF1000F09D11F -:102AD00049462046FFF7A2FF20B18BF31188284614 -:102AE000BDE8F88FA16AE36AA8EB050B5B1A9B456A -:102AF00028BF9B46BBF1400F1BD9334601F1400272 -:102B000051F8040B43F8040B9142F9D1A36A403306 -:102B10004036A3624035A26AE36A9A4202D3204655 -:102B2000FFF796FF8AF311884545D8D287F31188BD -:102B3000C9E730465A46FEF71BF9A36A5B445E4478 -:102B4000A3625D44E7E7000010B5029C0172043304 -:102B500003FB0421C36100238362C362039B0363FD -:102B6000049B00604060C460426102618161046254 -:102B70004262436310BD0000026AC260426A426161 -:102B8000026100228262C2626FF00101FEF714BF8F -:102B9000436902699A4203D1C2680AB100207047B2 -:102BA000184650F8043B0B6070470000C368C269C8 -:102BB0000133C3604369134482694361934224BF74 -:102BC000436A43610021FEF7EBBE000038B50446BE -:102BD0000D46E3683BB123691A1DA262E269134402 -:102BE000E362002038BD237A33B929462046FEF738 -:102BF000C7FE0028EDDA38BD6FF00100FBE70000EA -:102C000003691960C268013AC260C26913448269EB -:102C10000361934224BF436A036100238362036B11 -:102C200003B118477047000070B5202304460E46D4 -:102C300083F31188856A35B91146FFF7C7FF10B1D4 -:102C400085F3118870BDA36A1E70A36AE26A01331E -:102C50009342A36204D3E16920460439FFF7D0FF11 -:102C6000002080F3118870BD2DE9F84F04460D4611 -:102C700091469A464FF0200888F311880026B34603 -:102C8000A76A4FB951462046FFF7A0FF20B187F34E -:102C900011883046BDE8F88FA06AE76AA9EB060301 -:102CA0003F1A9F4228BF1F46402F1BD905F1400302 -:102CB00055F8042B40F8042B9D42F9D1A36A403308 -:102CC000A3624036A26AE36A9A4204D3E1692046CD -:102CD0000439FFF795FF8BF311884E45D9D288F35D -:102CE0001188CDE729463A46FEF742F8A36A3B44ED -:102CF0003D44A3623E44E5E7026943699A4203D139 -:102D0000C3681BB9184670470023FBE7836A002B92 -:102D1000F8D0043B9B1AF5D01360C368013BC36035 -:102D2000C3691A44836902619A4224BF436A0361FA -:102D3000002383620123E5E700F06CB94FF0804384 -:102D4000002258631A610222DA6070474FF0804314 -:102D50000022DA60704700004FF0804358637047EC -:102D6000FEE7000010B5174CFEF710FDFEF732FE2F -:102D7000802215492046FEF7B7FD012344F8180CC0 -:102D80000374124B124AD96821F4E0610904090C5A -:102D90000A431049DA60CA6842F08072CA600E497C -:102DA0000A6842F001020A601022DA77202283F8D2 -:102DB0002220002383F3118862B60848BDE8104042 -:102DC000FEF7B4BD302600200436000800ED00E018 -:102DD0000003FA05F0ED00E0001000E00C360008FA -:102DE0002DE9F84F1F4C4FF00008656904F11407F6 -:102DF000C1464FF08043266A5B6AAA689E1B9642D2 -:102E00001DD34FF0200AAA68236AD5F80CB01344EA -:102E100023622B68BB425F60A6EB02066361C5F8C4 -:102E20000C8001D1FFF792FF89F311882869D847F8 -:102E30008AF311886569AB689E42E4D2D9E762697A -:102E4000BA420CD0916823628E1B9660A868022853 -:102E50002CBF1818981CBDE8F84FFFF77DBFBDE8E0 -:102E6000F88F00BF08260020034B59685A68521A91 -:102E70009042FBD8704700BF001000E04B684360F1 -:102E80008B688360CB68C3600B6943614B690362E5 -:102E90008B6943620B6803607047000008B5224BE2 -:102EA00022481A6940F2FF110A431A611A6922F492 -:102EB000FF7222F001021A611A691A6B0A431A633F -:102EC0001A6D0A431A651A4A1B6D1146FFF7D6FFA1 -:102ED000184802F11C01FFF7D1FF174802F1380131 -:102EE000FFF7CCFF154802F15401FFF7C7FF144864 -:102EF00002F17001FFF7C2FF124802F18C01FFF7E7 -:102F0000BDFF114802F1A801FFF7B8FF0F4802F119 -:102F1000C401FFF7B3FF0E4802F1E001FFF7AEFF77 -:102F2000BDE8084000F0E0B8003802400000024070 -:102F30002C3600080004024000080240000C024049 -:102F4000001002400014024000180240001C024021 -:102F50000020024008B500F037FAFFF703FFFFF743 -:102F600067F8BDE80840FEF73FBE0000704700006C -:102F7000064A536823F001035360EFF30983683373 -:102F800083F30988002383F31188704730EF00E052 -:102F900010B5202383F31188104B5B6813F4006392 -:102FA00018D0F1EE103AEFF309844FF0807344F833 -:102FB0004C3C0B4BDB6844F8083CA4F1680383F3FA -:102FC0000988FEF771FC18B1064B44F8503C10BD5F -:102FD000054BFAE783F3118810BD00BF00ED00E058 -:102FE00030EF00E031030008340300084FF0804365 -:102FF00010B51A69920708D500241C61202383F3B9 -:103000001188FFF7EDFE84F31188BDE81040FFF74B -:10301000BFBF0000104B1A6C42F001021A641A6E16 -:1030200042F001021A660D4A1B6E936843F00103D9 -:1030300093604FF0804353229A624FF0FF32DA627E -:1030400000229A615A63DA605A6001225A610821AB -:103050001A601C20FFF78EBC00380240002004E0FC -:103060001F4B1A696FEAC2526FEAD2521A611A698B -:10307000C2F308021A614FF0FF301A695A695861A9 -:1030800000215A6959615A691A6A62F080521A62BB -:103090001A6A02F080521A621A6A5A6A58625A6AA6 -:1030A00059625A6A1A6C42F080521A641A6E42F0DF -:1030B00080521A661A6E0B4A106840F480701060D5 -:1030C000186F00F44070B0F5007F1EBF4FF48030E1 -:1030D00018671967536823F40073536000F054B9FC -:1030E0000038024000700040304B4FF080521A64AC -:1030F0002F4A4FF4404111601A6842F001021A60F1 -:103100001A689207FCD59A6822F003029A60274B4E -:1031100019469A6812F00C02FBD1186800F0F90009 -:1031200018609A601A6842F480321A600B689B0338 -:10313000FCD54B6F43F001034B671C4B5A6F900754 -:10314000FCD51C4A5A601A6842F080721A60184A0C -:1031500053685904FCD5154B1A689201FCD5164AE0 -:103160009A60164B1A68164B9A42164B1BD1164A98 -:103170001168164A914216D140F205121A600B4BA3 -:103180009A6842F002029A609A6802F00C02082AD9 -:10319000FAD15A6C42F480425A645A6E42F4804228 -:1031A0005A665B6E704740F20572E7E700380240EE -:1031B000007000400854400700948838002004E064 -:1031C00011640020003C024000ED00E041C20F41CC -:1031D000084A08B5536911680B4003F001035361B5 -:1031E00023B1054A13680BB150689847BDE8084001 -:1031F000FFF7CEBE003C014088250020084A08B5F4 -:10320000536911680B4003F00203536123B1054A6F -:1032100093680BB1D0689847BDE80840FFF7B8BE87 -:10322000003C014088250020084A08B55369116810 -:103230000B4003F00403536123B1054A13690BB13A -:1032400050699847BDE80840FFF7A2BE003C014026 -:1032500088250020084A08B5536911680B4003F01F -:103260000803536123B1054A93690BB1D0699847AC -:10327000BDE80840FFF78CBE003C014088250020D7 -:10328000084A08B5536911680B4003F010035361F5 -:1032900023B1054A136A0BB1506A9847BDE808404C -:1032A000FFF776BE003C014088250020174B10B583 -:1032B0005C691A68144004F478725A61A30604D554 -:1032C000134A936A0BB1D06A9847600604D5104A36 -:1032D000136B0BB1506B9847210604D50C4A936BC6 -:1032E0000BB1D06B9847E20504D5094A136C0BB1BA -:1032F000506C9847A30504D5054A936C0BB1D06C6C -:103300009847BDE81040FFF743BE00BF003C0140B6 -:10331000882500201A4B10B55C691A68144004F423 -:103320007C425A61620504D5164A136D0BB1506D8B -:103330009847230504D5134A936D0BB1D06D984778 -:10334000E00404D50F4A136E0BB1506E9847A104E8 -:1033500004D50C4A936E0BB1D06E9847620404D525 -:10336000084A136F0BB1506F9847230404D5054AE0 -:10337000936F0BB1D06F9847BDE81040FFF708BEC0 -:10338000003C014088250020062108B50846FFF7CB -:10339000F1FA06210720FFF7EDFA06210820FFF7D2 -:1033A000E9FA06210920FFF7E5FA06210A20FFF7CE -:1033B000E1FA06211720FFF7DDFA06212820BDE8F3 -:1033C0000840FFF7D7BA000008B5FFF749FEFDF740 -:1033D0008BFDFDF739FFFDF70DFEFFF7C7FDBDE8DB -:1033E0000840FFF7A9BC0000034611F8012B03F8C1 -:1033F000012B002AF9D1704712101213121100008C -:1034000053544D3332463F3F3F0000000000000060 -:10341000003400083F000000130400003C340008A2 -:103420003F00000019040000463400083F0000007F -:1034300021040000503400083F00000053544D3375 -:1034400032463430780053544D33324634327800AB -:1034500053544D333246343436585800000000007F -:103460006D0F0008590F0008950F0008810F000824 -:103470008D0F0008790F0008650F0008510F000834 -:10348000F10F000800000000010000000000000033 -:10349000020000000000000099110008011200085D -:1034A00040004000E02A0020F02A00200200000036 -:1034B00000000000030000000000000045120008AA -:1034C0000000000010000000002B002000000000A1 -:1034D0000100000000000000A42D002001010200F6 -:1034E0004172647550696C6F740025424F415244BB -:1034F000252D424C002553455249414C25000000E2 -:10350000891B0008F11A0008051100086D1B00084E -:10351000430000001835000809024300020100C002 -:103520003209040000010202010005240010010517 -:10353000240100010424020205240600010705827B -:10354000030800FF09040100020A0000000705014A -:103550000240000007058102400000001200000048 -:1035600064350008120110010200004009124157A1 -:1035700000020102030100000403090425424F4137 -:10358000524425004D6174656B463430352D5354DB -:1035900044003031323334353637383941424344D0 -:1035A00045460000004000000040000000400000D0 -:1035B00000400000000001000000020000000200C6 -:1035C00000000200000002000000020000000200F3 -:1035D00000000200000000008D1300086D160008B6 -:1035E0001917000840004000042E0020042E00207F -:1035F00001000000142E00208000000040010000A7 -:10360000030000006D61696E0000000024360008B0 -:10361000202E00201830002001000000612D00083D -:103620000000000069646C6500000000000080126A -:1036300000000000AAAAAAAA00000000FFBF000024 -:103640000000000000A00A000000140000000000BC -:10365000AAAAAAAA00001000FFFD000000000000B6 -:10366000000000001500000000000000AAAAAAAA9D -:1036700015000000FFFF0000000000000000000037 -:103680000000000000000000AAAAAAAA0000000092 -:10369000FFFF00000000000000000000000000002C -:1036A00000000000AAAAAAAA00000000FFFF000074 -:1036B000000000000000000000000000000000000A -:1036C000AAAAAAAA00000000FFFF00000000000054 -:1036D000000000000000000000000000AAAAAAAA42 -:1036E00000000000FFFF00000000000000000000DC -:1036F00000000000000000000A00000000000000C0 -:1037000003000000000000000000000000000000B6 -:1037100000000000000000000000000000000000A9 -:103720000000000000000000FF00960000000008FC -:1037300004000000783500080000000000000000D0 +:100250006F8F02F017F801F0F3FF02F095FE4FF0F8 +:1002600055301F491B4A91423CBF41F8040BFAE745 +:100270001C49194A91423CBF41F8040BFAE71A495C +:100280001A4A1B4B9A423EBF51F8040B42F8040B2A +:10029000F8E700201749184A91423CBF41F8040B87 +:1002A000FAE701F0D1FF02F0C3FE144C144DAC424A +:1002B00003DA54F8041B8847F9E700F041F8114CC1 +:1002C000114DAC4203DA54F8041B8847F9E701F0FA +:1002D000B9BF000000060020002200200000000836 +:1002E0000000002000060020B8370008002200208F +:1002F0004022002040220020A82D0020E00100081C +:10030000E0010008E0010008E00100082DE9F04FDD +:100310002DED108AC1F80CD0C3689D46BDEC108A43 +:10032000BDE8F08F002383F311882846A047002002 +:1003300001F034FBFEE701F0AFFA00DFFEE700005A +:1003400038B501F0EFFE054601F012FF0446D8B9BA +:100350000F4B9D421AD001339D4218BF044641F213 +:10036000883504BF01240025002001F0E5FE0CB112 +:1003700000F076F800F032FD00F0A4FB284600F013 +:10038000C3F800F06DF8F9E70025EDE70546EBE767 +:10039000010007B008B500F067FBA0F12003584248 +:1003A000584108BD07B541F21203022101A8ADF87A +:1003B000043000F077FB03B05DF804FB38B5202370 +:1003C00083F311881748C3680BB101F06DFB164A1F +:1003D000144800234FF47A7101F02AFB002383F3C1 +:1003E0001188124C236813B12368013B23606368B2 +:1003F00013B16368013B63600D4D2B7833B96368BB +:100400007BB9022000F05AFC322363602B78032B67 +:1004100007D163682BB9022000F050FC4FF47A73C7 +:10042000636038BD40220020BD0300085C2300202B +:1004300054220020084B187003280CD8DFE800F085 +:1004400008050208022000F027BC022000F012BCC0 +:10045000024B00225A607047542200205C23002087 +:10046000244B254A10B51C461968013140D004338D +:100470009342F9D16268214B9A4239D9204B9B684B +:1004800003F1006303F580339A4231D2002000F07B +:1004900033FB0220FFF7CEFF1A4B1A6C00221A64BE +:1004A000196E1A66196E596C5A64596E5A665A6EEC +:1004B0005A6942F080025A615A6922F080025A61F8 +:1004C0005A691A6942F000521A611A6922F0005200 +:1004D0001A611B6972B64FF0E0232021C3F8084D62 +:1004E000D4E9003281F311889D4683F308881047D0 +:1004F00010BD00BF0000010820000108FFFF000838 +:1005000000220020003802402DE9F04F93B0AA4BA2 +:1005100000902022FF210AA89D6800F009FCA74A4C +:100520001378A3B9A6480121C3601170202383F377 +:100530001188C3680BB101F0B7FAA24AA0480023A2 +:100540004FF47A7101F074FA002383F31188009B51 +:1005500013B19D4B009A1A609C4A009C1378032BA0 +:100560001EBF00231370984A4FF0000A18BF536053 +:10057000D3465646D146012000F08EFB24B1924B63 +:100580001B68002B00F01182002000F06DFA039030 +:10059000039B002BF2DB012000F06CFB039B213B53 +:1005A000162BE8D801A252F823F000BF0906000874 +:1005B00031060008C5060008770500087705000821 +:1005C000770500084F0700081F09000839080008D0 +:1005D0009B080008C3080008E90800087705000820 +:1005E000FB080008770500086D090008A906000847 +:1005F00077050008B109000815060008A9060008DB +:10060000770500089B0800080220FFF7C3FE0028BA +:1006100040F0F581009B0221BAF1000F08BF1C4693 +:1006200005A841F21233ADF8143000F03BFAA2E70E +:100630004FF47A7000F018FA071EEBDB0220FFF788 +:10064000A9FE0028E6D0013F052F00F2DA81DFE89D +:1006500007F0030A0D10133605230593042105A89E +:1006600000F020FA17E054480421F9E75848042123 +:10067000F6E758480421F3E74FF01C08404600F025 +:100680003DFA08F104080590042105A800F00AFAD3 +:10069000B8F12C0FF2D1012000FA07F747EA0B0B53 +:1006A0005FFA8BFB4FF0000900F08EFB26B10BF0D8 +:1006B0000B030B2B08BF0024FFF774FE5BE74648D3 +:1006C0000421CDE7002EA5D00BF00B030B2BA1D1FD +:1006D0000220FFF75FFE074600289BD0012000F0B4 +:1006E0000BFA0220FFF7A6FE00265FFA86F84046C6 +:1006F00000F012FA044690B10021404600F01CFAC6 +:1007000001360028F1D1BA46044641F21213022103 +:1007100005A8ADF814303E4600F0C4F92BE70120DF +:10072000FFF788FE2546244B9B68AB4207D9284635 +:1007300000F0E4F9013040F067810435F3E7234B22 +:1007400000251D70204BBA465D603E46ACE7002E8A +:100750003FF460AF0BF00B030B2B7FF45BAF022079 +:10076000FFF768FE322000F07FF9B0F10008FFF6D5 +:1007700051AF18F003077FF44DAF0F4A926808EBB2 +:10078000050393423FF646AFB8F5807F3FF742AF8F +:10079000124B0193B84523DD4FF47A7000F064F9F1 +:1007A0000390039A002AFFF635AF019B039A03F8E2 +:1007B000012B0137EDE700BF002200205823002065 +:1007C00040220020BD0300085C23002054220020AA +:1007D00004220020082200200C22002058220020A1 +:1007E000C820FFF7D7FD074600283FF413AF1F2DA1 +:1007F00011D8C5F1200242450AAB25F0030028BFFD +:10080000424683490192184400F06CFA019A8048EC +:10081000FF2100F08DFA4FEAA8037D490193C8F348 +:100820008702284600F08CFA064600283FF46DAF98 +:10083000019B05EB830537E70220FFF7ABFD00289E +:100840003FF4E8AE00F0A4F900283FF4E3AE00273F +:10085000B846704B9B68BB4218D91F2F11D80A9B12 +:1008600001330ED027F0030312AA134453F8203C9F +:1008700005934046042205A900F01CFB043780467E +:10088000E7E7384600F03AF90590F2E7CDF8148032 +:10089000042105A800F006F906E70023642104A856 +:1008A000049300F0F5F800287FF4B4AE0220FFF7BF +:1008B00071FD00283FF4AEAE049800F051F90590A8 +:1008C000E6E70023642104A8049300F0E1F800287F +:1008D0007FF4A0AE0220FFF75DFD00283FF49AAE42 +:1008E000049800F04DF9EAE70220FFF753FD0028D5 +:1008F0003FF490AE00F05CF9E1E70220FFF74AFD1B +:1009000000283FF487AE05A9142000F057F9042110 +:100910000746049004A800F0C5F83946B9E732202C +:1009200000F0A2F8071EFFF675AEBB077FF472AEAB +:10093000384A926807EB090393423FF66BAE0220F8 +:10094000FFF728FD00283FF465AE27F003074F446A +:10095000B9453FF4A9AE484600F0D0F8042105900F +:1009600005A800F09FF809F10409F1E74FF47A7047 +:10097000FFF710FD00283FF44DAE00F009F9002804 +:1009800044D00A9B01330BD008220AA9002000F0B2 +:10099000D7F900283AD02022FF210AA800F0C8F990 +:1009A000FFF700FD1C4800F0FFFF13B0BDE8F08F1B +:1009B000002E3FF42FAE0BF00B030B2B7FF42AAE6F +:1009C0000023642105A8059300F062F8074600287B +:1009D0007FF420AE0220FFF7DDFC804600283FF4C4 +:1009E00019AEFFF7DFFC41F2883000F0DDFF05981B +:1009F00000F01CFA464600F0E7F93C46BBE5064627 +:100A000052E64FF0000905E6BA467EE637467CE638 +:100A10005822002000220020A086010070B50F4B54 +:100A20001B780133DBB2012B0C4611D80C4D296821 +:100A30004FF47A730E6AA2FB03320146224628461F +:100A4000B047844204D1074B00221A70012070BDC8 +:100A50004FF4FA7000F0A8FF0020F8E71022002001 +:100A6000502500209023002007B5002302460121D5 +:100A70000DF107008DF80730FFF7D0FF20B19DF88A +:100A8000070003B05DF804FB4FF0FF30F9E700000A +:100A90000A4608B50421FFF7C1FF80F00100C0B28B +:100AA000404208BD30B4054C2368DD69044B0A465A +:100AB000AC460146204630BC604700BF50250020B0 +:100AC000A086010070B501F01FFA094E094D308073 +:100AD000002428683388834208D901F00FFA2B6874 +:100AE00004440133B4F5803F2B60F2D370BD00BFE6 +:100AF000922300206423002001F0C8BA00F10060B6 +:100B000000F580300068704700F10060920000F549 +:100B1000803001F047BA0000054B1A68054B1B886E +:100B20009B1A834202D9104401F0E8B900207047B3 +:100B3000642300209223002038B5084D044629B1D3 +:100B400028682044BDE8384001F0F8B928682044FE +:100B500001F0DCF90028F3D038BD00BF6423002089 +:100B600010F003030AD1B0F5047F05D200F1005064 +:100B7000A0F51040D0F80038184670470023FBE776 +:100B800000F10050A0F51040D0F8100A70470000A6 +:100B9000064991F8243033B10023086A81F82430E3 +:100BA0000822FFF7B1BF0120704700BF6823002073 +:100BB000014B1868704700BF002004E070B52A4B55 +:100BC0001B68C3F30B0204461B0C62B140F21340D6 +:100BD000824230D040F2194082422ED040F2214071 +:100BE00082422CD10322214D0C2000FB0252556879 +:100BF00042F20102934224D0B3F5805F23D041F248 +:100C00000102934221D041F2030293421FD041F2EC +:100C10000702934214BF3F233123013C0C44013DA2 +:100C20000A46A24215D215F9016F501C9EB100F878 +:100C3000016C0246F5E70122D5E70222D3E70C4D0D +:100C4000D6E73323E9E74123E7E75A23E5E75923CA +:100C5000E3E7104605E02C258442157001D9901C6D +:100C60005370401A70BD00BF002004E0BC3400087F +:100C700090340008022804D1054B4FF000729A61AD +:100C800070470128FCD1034B4FF08042F7E700BFCB +:100C90000004024000000240022804D1054B4FF43A +:100CA00000729A6170470128FCD1034B4FF48042D7 +:100CB000F7E700BF0004024000000240022805D10F +:100CC000064A536983F40073536170470128FCD1CD +:100CD000034A536983F48043F6E700BF00040240EF +:100CE0000000024010B50023934203D0CC5CC454F2 +:100CF0000133F9E710BD000010B5013810F9013FCC +:100D00003BB191F900409C4203D11AB10131013A43 +:100D1000F4E71AB191F90020981A10BD1046FCE7CB +:100D200003460246D01A12F9011B0029FAD1704776 +:100D300002440346934202D003F8011BFAE77047CE +:100D40002DE9F8431F4D144695F8242007468846A0 +:100D500052BBDFF870909CB395F824302BB9202259 +:100D6000FF2148462F62FFF7E3FF95F82400C0F10A +:100D70000802A24228BF2246D6B24146920005EBA5 +:100D80008000FFF7AFFF95F82430A41B1E44F6B295 +:100D9000082E17449044E4B285F82460DBD1FFF7B5 +:100DA000F7FE0028D7D108E02B6A03EB82038342C9 +:100DB000CFD0FFF7EDFE0028CBD10020BDE8F883AF +:100DC0000120FBE768230020024B1A78024B1A70BF +:100DD000704700BF902300201022002010B50F4C58 +:100DE0000F4800F0F7F821460D4800F01FF924687D +:100DF0000C48626DD2F8043843F00203C2F804389C +:100E000000F0D2FD0849204600F016FA626DD2F8D3 +:100E1000043823F00203C2F8043810BDB0350008CE +:100E20005025002040420F00B835000870470000F0 +:100E300000B59BB0EFF3098168226846FFF752FFC7 +:100E4000EFF30583044B9A6BDA6A9A6A9A6A9A6A94 +:100E50009A6A9A6A9B6AFEE700ED00E000B59BB0D3 +:100E6000EFF3098168226846FFF73CFFEFF3058343 +:100E7000044B9A6B9A6A9A6A9A6A9A6A9A6A9B6A05 +:100E8000FEE700BF00ED00E000B59BB0EFF3098185 +:100E900068226846FFF726FFEFF30583034B5A6B82 +:100EA0009A6A9A6A9A6A9A6A9B6AFEE700ED00E07B +:100EB000FEE7000030B5094D0A4491420DD011F80B +:100EC000013B5840082340F30004013B2C4013F041 +:100ED000FF0384EA5000F6D1EFE730BD2083B8ED80 +:100EE000026843681143016003B11847704700006E +:100EF00013B5446BD4F894341A681178042915D1C9 +:100F0000217C022912D11979128901238B401342C5 +:100F10000CD101A904F14C0001F03CFFD4F8944439 +:100F2000019B21790246206800F0CEF902B010BD85 +:100F3000143001F0BFBE00004FF0FF33143001F059 +:100F4000B9BE00004C3001F091BF00004FF0FF33FC +:100F50004C3001F08BBF0000143001F08DBE00005A +:100F60004FF0FF31143001F087BE00004C3001F02B +:100F70005DBF00004FF0FF324C3001F057BF000062 +:100F80000020704710B5D0F894341A6811780429FD +:100F9000044617D1017C022914D1597952890123C1 +:100FA0008B4013420ED1143001F020FE024648B1AE +:100FB000D4F894444FF4807361792068BDE8104000 +:100FC00000F070B910BD0000406BFFF7DBBF000000 +:100FD000704700007FB5124B036000234360C0E9F7 +:100FE0000233012502260F4B05740446029001933B +:100FF00000F18402294600964FF48073143001F00A +:10100000D1FD094B0294CDE9006304F523724FF43E +:101010008073294604F14C0001F098FE04B070BDC5 +:10102000EC340008C90F0008F10E00080B682022FC +:1010300082F311880A7903EB820290614A790932BE +:1010400043F822008A7912B103EB820398610223EC +:101050000374C0F89414002383F3118870470000D0 +:1010600038B5037F044613B190F85430ABB9201D56 +:1010700001250221FFF734FF04F1140025776FF0FA +:10108000010100F0B9FC84F8545004F14C006FF0F9 +:101090000101BDE8384000F0AFBC38BD10B50121FA +:1010A00004460430FFF71CFF0023237784F85430F4 +:1010B00010BD000038B504460025143001F08AFD4B +:1010C00004F14C00257701F059FE201D84F854509E +:1010D0000121FFF705FF2046BDE83840FFF752BF6A +:1010E00090F8443003F06003202B07D190F845209E +:1010F000212A4FF0000303D81F2A06D8002070478A +:10110000222AFBD1C0E90E3303E0034A826307229F +:10111000C2630364012070471122002037B5D0F864 +:1011200094341A681178042904461AD1017C0229E2 +:1011300017D11979128901238B40134211D100F183 +:101140004C05284601F0DAFE58B101A9284601F005 +:1011500021FED4F89444019B21790246206800F0D6 +:10116000B3F803B030BD0000F0B500EB810385B0EB +:101170009E6904460D46FEB1202383F3118804EBDB +:101180008507301D0821FFF7ABFEFB685B691B6814 +:1011900006F14C001BB1019001F00AFE019803A971 +:1011A00001F0F8FD024648B1039B2946204600F0B5 +:1011B0008BF8002383F3118805B0F0BDFB685A69F2 +:1011C0001268002AF5D01B8A013B1340F1D104F1CB +:1011D0004402EAE7093138B550F82140DCB1202358 +:1011E00083F31188D4F894241368527903EB8203B3 +:1011F000DB689B695D6845B104216018FFF770FEEC +:10120000294604F1140001F0FBFC2046FFF7BAFE6A +:10121000002383F3118838BD7047000001F0A8B89F +:10122000012303700023C0E90133C36183620362B9 +:10123000C36243620363704738B50446202383F3D7 +:1012400011880025C0E90355C0E90555416001F04A +:101250009FF80223237085F3118838BD70B500EB29 +:10126000810305465069DA600E46144618B1102213 +:101270000021FFF75DFDA06918B110220021FFF7E2 +:1012800057FD31462846BDE8704001F04BB90000DB +:10129000826802F0011282600022C0E904228261A9 +:1012A00001F0CCB9F0B400EB81044789E468012572 +:1012B000A4698D403D43458123600023A2606360A3 +:1012C000F0BC01F0E7B90000F0B400EB810407893D +:1012D000E468012564698D403D4305812360002356 +:1012E000A2606360F0BC01F061BA000070B5022337 +:1012F000002504460370C0E90255C0E90455C564E1 +:10130000856180F8345001F0A9F863681B6823B147 +:1013100029462046BDE87040184770BD037880F824 +:1013200050300523037043681B6810B504460BB1A9 +:10133000042198470023A36010BD000090F85020BE +:10134000436802701B680BB1052118477047000005 +:1013500070B590F83430044613B1002380F834306F +:1013600004F14402204601F08BF963689B68B3B92D +:1013700094F8443013F0600535D00021204601F088 +:10138000DDFB0021204601F0CFFB63681B6813B131 +:10139000062120469847062384F8343070BD204645 +:1013A00098470028E4D0B4F84A30E26B9A4288BFEC +:1013B000E36394F94430E56B002B4FF0200380F297 +:1013C0000381002D00F0F280092284F8342083F399 +:1013D00011880021D4E90E232046FFF775FF002372 +:1013E00083F31188DAE794F8452003F07F0343EA9A +:1013F000022340F20232934200F0C58021D8B3F5B7 +:10140000807F48D00DD8012B3FD0022B00F0938075 +:10141000002BB2D104F14C02A2630222E2632364E6 +:10142000C1E7B3F5817F00F09B80B3F5407FA4D185 +:1014300094F84630012BA0D1B4F84C3043F00203AD +:1014400032E0B3F5006F4DD017D8B3F5A06F31D0AF +:10145000A3F5C063012B90D8636894F846205E68BA +:1014600094F84710B4F848302046B047002884D09C +:101470004368A3630368E3631AE0B3F5106F36D0E3 +:1014800040F6024293427FF478AF5C4BA3630223A1 +:10149000E3630023C3E794F84630012B7FF46DAF7C +:1014A000B4F84C3023F00203C4E90E55A4F84C30D4 +:1014B000256478E7B4F84430B3F5A06F0ED194F802 +:1014C000463084F84E30204601F020F863681B68EF +:1014D00013B1012120469847032323700023C4E958 +:1014E0000E339CE704F14F03A3630123C3E7237882 +:1014F000042B10D1202383F311882046FFF7C8FE68 +:1015000085F311880321636884F84F5021701B68AC +:101510000BB12046984794F84630002BDED084F873 +:101520004F300423237063681B68002BD6D0022140 +:1015300020469847D2E794F848301D0603F00F0183 +:1015400020460AD501F08EF8012804D002287FF445 +:1015500014AF2B4B9AE72B4B98E701F075F8F3E7A4 +:1015600094F84630002B7FF408AF94F8483013F01D +:101570000F01B3D01A06204602D501F0F3FAADE709 +:1015800001F0E6FAAAE794F84630002B7FF4F5AEB6 +:1015900094F8483013F00F01A0D01B06204602D566 +:1015A00001F0CCFA9AE701F0BFFA97E7142284F829 +:1015B000342083F311882B462A4629462046FFF71C +:1015C00071FE85F31188E9E65DB1152284F83420B7 +:1015D00083F311880021D4E90E232046FFF762FE31 +:1015E000FDE60B2284F8342083F311882B462A462B +:1015F00029462046FFF768FEE3E700BF1C350008D8 +:10160000143500081835000838B590F83430044611 +:10161000002B3ED0063BDAB20F2A34D80F2B32D83B +:10162000DFE803F0373131082232313131313131E5 +:1016300031313737C56BB0F84A309D4214D2C36898 +:101640001B8AB5FBF3F203FB12556DB9202383F31C +:1016500011882B462A462946FFF736FE85F3118866 +:101660000A2384F834300EE0142384F83430202325 +:1016700083F3118800231A4619462046FFF712FE0D +:10168000002383F3118838BD036C03B1984700230E +:10169000E7E70021204601F051FA0021204601F041 +:1016A00043FA63681B6813B1062120469847062356 +:1016B000D7E7000010B590F83430142B044629D039 +:1016C00017D8062B05D001D81BB110BD093B022B42 +:1016D000FBD80021204601F031FA0021204601F01C +:1016E00023FA63681B6813B1062120469847062336 +:1016F00019E0152BE9D10B2380F83430202383F334 +:10170000118800231A461946FFF7DEFD002383F3F4 +:101710001188DAE7C3689B695B68002BD5D1036C3D +:1017200003B19847002384F83430CEE7024B0022FF +:10173000C3E900339A6070479423002000230374A8 +:101740008268054B1B6899689142FBD25A68036016 +:1017500042601060586070479423002008B5202331 +:1017600083F31188037C032B05D0042B0DD02BB9F8 +:1017700083F3118808BD436900221A604FF0FF33DC +:101780004361FFF7DBFF0023F2E7D0E9003213608B +:101790005A60F3E7002303748268054B1B6899685D +:1017A0009142FBD85A6803604260106058607047ED +:1017B00094230020054B19690874186802681A60A0 +:1017C0005360186101230374FEF7A0BD9423002029 +:1017D00030B54B1C0B4D87B0044610D02B690A4A1C +:1017E00001A800F025F92046FFF7E4FF049B13B1A0 +:1017F00001A800F059F92B69586907B030BDFFF70F +:10180000D9FFF8E7942300205D17000838B50C4D88 +:1018100041612B6981689A689142044603D8BDE80A +:101820003840FFF78BBF1846FFF7B4FF01232C6148 +:10183000014623742046BDE83840FEF767BD00BF6F +:1018400094230020044B1A681B6990689B68984297 +:1018500094BF0020012070479423002010B5084C4D +:10186000236820691A6822605460012223611A7477 +:10187000FFF790FF01462069BDE81040FEF746BD26 +:101880009423002008B5FFF7DDFF18B1BDE808403C +:10189000FFF7E4BF08BD0000FFF7E0BFFEE7000070 +:1018A00010B50C4CFFF742FF00F0B4F80A49802253 +:1018B000204600F03BF8012344F8180C037400F0B4 +:1018C00071FC002383F3118862B60448BDE8104020 +:1018D00000F04CB8BC23002020350008303500084B +:1018E00000F01CB9EFF3118020B9EFF3058320223B +:1018F00082F311887047000010B530B9EFF305840A +:10190000C4F3080414B180F3118810BDFFF7BAFFC7 +:1019100084F31188F9E70000034A516853685B1AA1 +:101920009842FBD8704700BF001000E0826002229E +:10193000028270478368A3F17C0243F80C2C026991 +:1019400043F83C2C426943F8382C074A43F81C2CD6 +:10195000C26843F8102C022203F8082C002203F876 +:10196000072CA3F1180070472503000810B52023A9 +:1019700083F31188FFF7DEFF00210446FFF746FFDF +:10198000002383F31188204610BD0000024B1B6921 +:1019900058610F20FFF70EBF94230020202383F30C +:1019A0001188FFF7F3BF000008B50146202383F339 +:1019B00011880820FFF70CFF002383F3118808BD6E +:1019C00049B1064B42681B6918605A601360436056 +:1019D0000420FFF7FDBE4FF0FF3070479423002036 +:1019E0000368984206D01A68026050605961184630 +:1019F000FFF7A4BE7047000038B504460D462068C6 +:101A0000844200D138BD036823605C604561FFF704 +:101A100095FEF4E7054B03F11402C3E905224FF0EC +:101A2000FF310022C3E90712704700BF9423002052 +:101A300070B51C4EC0E9032305460C4601F090FA30 +:101A4000334653F8142F9A420DD13062C5E9012470 +:101A50002A600A2C2CBF00190A30C6E90555BDE8DA +:101A6000704001F06BBA316A431AE31838BF1C4664 +:101A70009368A34202D9081901F06EFA73699A6853 +:101A800094420CD85A68AC602B606A6015609A6802 +:101A90005D60121B9A604FF0FF33F36170BD1B68ED +:101AA000A41AECE79423002038B51B4C63699842D4 +:101AB0000DD0D0E9003213605A6000228168C26004 +:101AC0009A680A449A604FF0FF33E36138BD2246BA +:101AD000036842F8143F002193425A60C16003D169 +:101AE000BDE8384001F032BA9A688168256A0A4434 +:101AF0009A6001F035FA63699A68411B8A42E5D918 +:101B0000AB181D1A092D206A98BF01F10A02BDE821 +:101B10003840104401F020BA942300202DE9F04110 +:101B2000184C002704F11406656901F019FA236ABC +:101B3000AA68C11A8A4215D813442362D5E9003233 +:101B400013605A606369D5F80C80EF60B34201D12D +:101B500001F0FCF987F311882869C047202383F33B +:101B60001188E1E76169B14209D013441B1ABDE84D +:101B7000F0410A2B2CBFC0180A3001F0EDB9BDE8C6 +:101B8000F08100BF9423002000207047FEE7000092 +:101B9000704700004FF0FF307047000002290CD062 +:101BA000032904D00129074818BF00207047032AE1 +:101BB00005D8054800EBC200704704487047002074 +:101BC000704700BF1436000820220020C8350008E6 +:101BD00070B59AB00546084601A9144600F0C2F84F +:101BE00001A8FFF79DF8431C5B00C5E90034002203 +:101BF000237003236370C6B201AB02341046D1B226 +:101C00008E4204F1020401D81AB070BD13F8011B12 +:101C100004F8021C04F8010C0132F0E708B5202397 +:101C200083F311880348FFF779FA002383F31188BF +:101C300008BD00BF5025002090F8443003F01F027B +:101C4000012A07D190F845200B2A03D10023C0E9CF +:101C50000E3315E003F06003202B08D1B0F84830B4 +:101C60002BB990F84520212A03D81F2A04D8FFF762 +:101C700037BA222AEBD0FAE7034A82630722C2630B +:101C800003640120704700BF1822002007B5052912 +:101C900017D8DFE801F0191603191920202383F360 +:101CA0001188104A01900121FFF7D8FA01980E4AD5 +:101CB0000221FFF7D3FA0D48FFF7FCF9002383F365 +:101CC000118803B05DF804FB202383F311880748D3 +:101CD000FFF7C6F9F2E7202383F311880348FFF7E3 +:101CE000DDF9EBE7683500088C3500085025002049 +:101CF00038B50C4D0C4C0D492A4604F10800FFF78D +:101D000067FF05F1CA0204F110000949FFF760FFFF +:101D100005F5CA7204F118000649BDE83840FFF71E +:101D200057BF00BF182A0020202200204835000895 +:101D3000523500085D35000870B5044608460D466A +:101D4000FEF7EEFFC6B22046013403780BB9184601 +:101D500070BD32462946FEF7CFFF0028F3D101209F +:101D6000F6E700002DE9F04705460C46FEF7D8FFE0 +:101D70002B49C6B22846FFF7DFFF08B10636F6B298 +:101D800028492846FFF7D8FF08B11036F6B2632E6F +:101D90000BD8DFF88C80DFF88C90234FDFF894A00D +:101DA0002E7846B92670BDE8F08729462046BDE862 +:101DB000F04701F065BB252E2ED10722414628466B +:101DC000FEF79AFF70B9194B224603F10C0153F844 +:101DD000040B42F8040B8B42F9D11B7813700735C2 +:101DE0000D34DDE7082249462846FEF785FF98B9FD +:101DF0000F4BA21C197809090232C95D02F8041CB4 +:101E000013F8011B01F00F015345C95D02F8031CD3 +:101E1000F0D118340835C3E704F8016B0135BFE78A +:101E2000343600085D3500084A3600083C360008A4 +:101E3000107AFF1F1C7AFF1FBFF34F8F024AD3682F +:101E4000DB03FCD4704700BF003C024008B5094BDF +:101E50001B7873B9FFF7F0FF074B1A69002ABFBF61 +:101E6000064A5A6002F188325A601A6822F4806287 +:101E70001A6008BD762C0020003C02402301674513 +:101E800008B50B4B1B7893B9FFF7D6FF094B1A69BE +:101E900042F000421A611A6842F480521A601A68CD +:101EA00022F480521A601A6842F480621A6008BDF7 +:101EB000762C0020003C02400B28F0B516D80C4CC4 +:101EC0000C4923787BB90C4D0E460C234FF0006271 +:101ED00055F8047B46F8042B013B13F0FF033A440A +:101EE000F6D10123237051F82000F0BD0020FCE75B +:101EF000A82C0020782C00205C360008014B53F8F9 +:101F0000200070475C3600080C2070470B2810B585 +:101F1000044601D9002010BDFFF7CEFF064B53F851 +:101F200024301844C21A0BB90120F4E712680132B8 +:101F3000F0D1043BF6E700BF5C3600080B2838B54B +:101F4000044628D8FFF7CEFCFFF776FFFFF77EFFA9 +:101F5000124AF323D360E300DBB243F4007343F08F +:101F600002031361136943F480331361054620466D +:101F7000FFF762FFFFF7A0FF094B53F8241000F0B2 +:101F8000E9F82846FFF77CFFFFF7B6FC2046BDE8DE +:101F90003840FFF7BBBF002038BD00BF003C024007 +:101FA0005C36000812F001032DE9F04105460E46AB +:101FB00014464BD18218B2F1016F61D8314B1B68C6 +:101FC00013F001035CD0304FFFF78CFCFFF73EFFAE +:101FD000F323FB60FFF730FF314640F20128032C6A +:101FE00018D824F00104284E0C446D1A40F2011850 +:101FF000A142336905EB01072AD123F001033361C4 +:10200000FFF73EFFFFF778FC0120BDE8F081043CBC +:102010000435E4E7AB07E4D13B6923F440733B614B +:102020003B6943EA08033B6151F8046B2E60BFF340 +:102030004F8FFFF701FF2B689E42E8D03B6923F0EA +:1020400001033B61FFF71CFFFFF756FC0020DCE7B4 +:1020500023F440733361336943EA080333610B8827 +:102060003B80BFF34F8FFFF7E7FE3F8831F8023B1D +:10207000BFB2BB42BCD0336923F001033361E1E757 +:102080001846C2E700380240003C0240084908B543 +:102090000B7828B11BB9FFF7D9FE01230B7008BDDF +:1020A000002BFCD0BDE808400870FFF7E9BE00BF78 +:1020B000762C002010B50244064BD2B2904200D1DB +:1020C00010BD441C00B253F8200041F8040BE0B2EC +:1020D000F4E700BF502800400F4B30B51C6F2404BC +:1020E00007D41C6F44F400741C671C6F44F4004454 +:1020F0001C670A4C236843F4807323600244084B36 +:10210000D2B2904200D130BD441C00B251F8045B01 +:1021100043F82050E0B2F4E700380240007000407D +:102120005028004007B5012201A90020FFF7C2FF97 +:10213000019803B05DF804FB13B50446FFF7F2FF06 +:10214000A04205D0012201A900200194FFF7C4FF9D +:1021500002B010BD70470000034B1A681AB9034A59 +:10216000D2F874281A607047AC2C0020003002406E +:1021700008B5FFF7F1FF024B1868C0F3407008BDC7 +:10218000AC2C0020EFF3098305494A6B22F00102D1 +:102190004A63683383F30988002383F31188704707 +:1021A00000EF00E0202080F3118862B60C4B0D4A4E +:1021B000D96821F4E0610904090C0A43DA60D3F814 +:1021C000FC20094942F08072C3F8FC200A6842F002 +:1021D00001020A601022DA7783F82200704700BFFC +:1021E00000ED00E00003FA05001000E010B5202328 +:1021F00083F311880E4B5B6813F4006314D0F1EE87 +:10220000103AEFF30984683C4FF08073E361094BA7 +:10221000DB6B236684F30988FFF714FB10B1064BD0 +:10222000A36110BD054BFBE783F31188F9E700BFFD +:1022300000ED00E000EF00E0370300083A0300087B +:1022400070470000FEE700000A4B0B480B4A904223 +:102250000BD30B4BDA1C121AC11E22F003028B4265 +:1022600038BF00220021FEF763BD53F8041B40F87D +:10227000041BECE7F8370008A82D0020A82D00204B +:10228000A82D00207047000070B5D0E915439E6866 +:1022900000224FF0FF3504EB42135101D3F800093F +:1022A0000028BEBFD3F8000940F08040C3F8000901 +:1022B000D3F8000B0028BEBFD3F8000B40F08040DD +:1022C000C3F8000B013263189642C3F80859C3F8EB +:1022D000085BE0D24FF00113C4F81C3870BD000059 +:1022E0001D4B03EB80022DE9F043D2F80CC05D6D6D +:1022F000DCF81420461CD2F800E005EB063605EBAE +:102300004018516871450AD3D5F83438012202FAD1 +:1023100000F023EA0000C5F83408BDE8F083BCF8FB +:102320001040AEEB0103A34228BF2346D8F818495A +:10233000A4B2B3EB840FF0D89468A4F1040959F85F +:10234000047F3760A4EB09071F44042FF7D81C440F +:102350000B4494605360D4E7B02C0020890141F015 +:102360002001016103699B06FCD41220FFF7D4BA57 +:1023700010B5054C2046FEF753FF4FF0A0436365B0 +:10238000024BA36510BD00BFB02C0020B036000882 +:1023900070B50378012B054650D12A4B446D984205 +:1023A0001BD1294B5A6B42F080025A635A6D42F09E +:1023B00080025A655A6D5A6942F080025A615A6920 +:1023C00022F080025A610E2143205B6900F0D4FBA9 +:1023D0001E4BE3601E4BC4F800380023C4F8003ED7 +:1023E000C02323606E6D4FF40413A3633369002B85 +:1023F000FCDA012333610C20FFF78EFA3369DB0727 +:10240000FCD41220FFF788FA3369002BFCDA00268F +:10241000A6602846FFF738FF6B68C4F81068DB68D1 +:10242000C4F81468C4F81C684BB90A4BA3614FF098 +:10243000FF336361A36843F00103A36070BD064BE3 +:10244000F4E700BFB02C00200038024040140040E8 +:1024500003002002003C30C0083C30C0F8B5446D99 +:10246000054600212046FFF779FFA96D00234FF0B4 +:1024700001128F68C4F834384FF00066C4F81C2885 +:102480004FF0FF3004EB431201339F42C2F8006962 +:10249000C2F8006BC2F80809C2F8080BF2D20B6848 +:1024A0006A6DEB65636210231361166916F01006FE +:1024B000FBD11220FFF730FAD4F8003823F4FE6382 +:1024C000C4F80038A36943F4402343F01003A36128 +:1024D0000923C4F81038C4F814380A4BEB604FF0E5 +:1024E000C043C4F8103B084BC4F8003BC4F8106963 +:1024F000C4F80039EB6D03F1100243F48013EA6570 +:10250000A362F8BD8C36000840800010426D90F840 +:102510004E10D2F8003823F4FE6343EA0113C2F8E8 +:10252000003870472DE9F84300EB8103456DDA6808 +:10253000166806F00306731E022B05EB41130C46CA +:1025400080460FFA81F94FEA41104FF00001C3F8BD +:10255000101B4FF0010104F1100398BFB60401FAFB +:1025600003F391698EBF334E06F1805606F500469F +:1025700000293AD0578A04F15801490137436F5076 +:10258000D5F81C180B43C5F81C382B180021C3F8CC +:10259000101953690127611EA7409BB3138A928BC0 +:1025A0009B08012A88BF5343D8F85C20981842EA58 +:1025B000034301F1400205EB8202C8F85C002146AA +:1025C00053602846FFF7CAFE08EB8900C3681B8AE0 +:1025D00043EA8453483464011E432E51D5F81C3815 +:1025E0001F43C5F81C78BDE8F88305EB4917D7F8F9 +:1025F000001B21F40041C7F8001BD5F81C1821EA84 +:102600000303C0E704F13F0305EB83030A4A5A6062 +:1026100028462146FFF7A2FE05EB4910D0F8003905 +:1026200023F40043C0F80039D5F81C3823EA070723 +:10263000D7E700BF0080001000040002826D12681E +:10264000C265FFF721BE00005831436D49015B5858 +:1026500013F4004004D013F4001F0CBF022001202B +:10266000704700004831436D49015B5813F4004046 +:1026700004D013F4001F0CBF02200120704700009B +:1026800000EB8101CB68196A0B6813604B685360DB +:102690007047000000EB810330B5DD68AA6913685C +:1026A000D36019B9402B84BF402313606B8A146830 +:1026B000426D1C44013CB4FBF3F46343033323F049 +:1026C000030302EB411043EAC44343F0C043C0F8A4 +:1026D000103B2B6803F00303012B09B20ED1D2F893 +:1026E000083802EB411013F4807FD0F8003B14BF90 +:1026F00043F0805343F00053C0F8003B02EB41121B +:10270000D2F8003B43F00443C2F8003B30BD000068 +:102710002DE9F041244D6E6D06EB40130446D3F8CD +:10272000087BC3F8087B38070AD5D6F81438190790 +:1027300006D505EB84032146DB6828465B6898478D +:10274000FA071FD5D6F81438DB071BD505EB840331 +:10275000D968CCB98B69488A5A68B2FBF0F600FB9D +:1027600016228AB91868DA6890420DD2121AC3E9A3 +:102770000024202383F311880B482146FFF78AFFAA +:1027800084F31188BDE8F081012303FA04F26B8918 +:1027900023EA02036B81CB68002BF3D02146024869 +:1027A000BDE8F041184700BFB02C002000EB8103CA +:1027B00070B5DD68436D6C692668E6604A0156BBFA +:1027C0001A444FF40020C2F810092A6802F00302EC +:1027D000012A0AB20ED1D3F8080803EB421410F410 +:1027E000807FD4F8000914BF40F0805040F00050C2 +:1027F000C4F8000903EB4212D2F8000940F004408B +:10280000C2F80009D3F83408012202FA01F10143A9 +:10281000C3F8341870BD19B9402E84BF4020206021 +:1028200020682E8A8419013CB4FBF6F440EAC440C7 +:1028300040F000501A44C6E7F8B504461E48456DFE +:1028400005EB4413D3F80869C3F80869F10717D5F5 +:10285000D5F81038DA0713D500EB8403D9684B6933 +:102860001F68DA68974218D2D21B00271A605F608F +:10287000202383F311882146FFF798FF87F31188FF +:10288000330617D5D5F834280123A340134211D0BD +:102890002046BDE8F840FFF723BD012303FA04F208 +:1028A000038923EA020303818B68002BE8D02146C9 +:1028B0009847E5E7F8BD00BFB02C00202DE9F74FA1 +:1028C000984C666D7569B3691D4015F48058756143 +:1028D00007D02046FEF70AFD03B0BDE8F04FFFF732 +:1028E00085BC002D12DAD6F8003E8E489F071EBF29 +:1028F000D6F8003E23F00303C6F8003ED6F80438AD +:1029000023F00103C6F80438FEF718FD280505D5A5 +:102910008448FFF7B9FC8348FEF700FDA9040CD5F5 +:10292000D6F8083813F0060FF36823F470530CBF81 +:1029300043F4105343F4A053F3602A0704D56368AB +:10294000DB680BB177489847EB0274D4AF0227D508 +:10295000D4F85490DFF8CCB100274FF0010A09EB0E +:102960004712D2F8003B03F44023B3F5802F11D176 +:10297000D2F8003B002B0DDA62890AFA07F322EA4B +:102980000303638104EB8703DB68DB6813B139461B +:1029900058469847A36D01379B68FFB29F42DED926 +:1029A000E80617D5676D3A6AC2F30A1002F00F0302 +:1029B00002F4F012B2F5802F00F08880B2F5402FBB +:1029C00008D104EB83030022DB681B6A07F58057FC +:1029D00090426DD12903D6F8184813D5E20302D5E9 +:1029E0000020FFF795FEA30302D50120FFF790FE1C +:1029F000670302D50220FFF78BFE260302D50320D2 +:102A0000FFF786FE6D037FF567AFE00702D5002074 +:102A1000FFF712FFA10702D50120FFF70DFF6207A4 +:102A200002D50220FFF708FF23077FF555AF0320EB +:102A3000FFF702FF50E7636DDFF8E8B0019300276E +:102A40004FF0010AA36D9B685FFA87F999453FF63D +:102A50007DAF019B03EB4913D3F8002902F4402218 +:102A6000B2F5802F22D1D3F80029002A1EDAD3F83C +:102A7000002942F09042C3F80029D3F80029002A27 +:102A8000FBDB606D4946FFF769FC22890AFA09F30E +:102A900022EA0303238104EB8903DB689B6813B1FB +:102AA0004946584698474846FFF71AFC0137C9E798 +:102AB000910708BFD7F80080072A98BF03F8018B59 +:102AC00002F1010298BF4FEA182881E7023304EBB4 +:102AD000830207F580575268D2F818C0DCF8082046 +:102AE000DCE9001CA1EB0C0C002188420AD104EBAC +:102AF000830463689B699A6802449A605A68024436 +:102B00005A6067E711F0030F08BFD7F800808C45C3 +:102B100088BF02F8018B01F1010188BF4FEA182834 +:102B2000E3E700BFB02C0020436D03EB4111D1F867 +:102B3000003B43F40013C1F8003B7047436D03EBC7 +:102B40004111D1F8003943F40013C1F8003970473E +:102B5000436D03EB4111D1F8003B23F40013C1F89E +:102B6000003B7047436D03EB4111D1F8003923F46A +:102B70000013C1F80039704700F1604303F5614369 +:102B80000901C9B283F80013012200F01F039A4023 +:102B900043099B0003F1604303F56143C3F88021BF +:102BA0001A60704730B5039C0172043304FB03259F +:102BB000C0E90653049B03630021059BC160C0E983 +:102BC0000000C0E90422C0E90842C0E90A114363D9 +:102BD00030BD0000416A0022C0E90411C0E90A22A8 +:102BE000C2606FF00101FEF707BF0000D0E90432B8 +:102BF000934201D1C2680AB9181D7047002070477E +:102C000003691960C2680132C260C26913448269F3 +:102C10000361934224BF436A03610021FEF7E0BED3 +:102C200038B504460D46E3683BB16269131D12686E +:102C3000A3621344E362002007E0237A33B92946F4 +:102C40002046FEF7BDFE0028EDDA38BD6FF001002A +:102C5000FBE70000C368C269013BC36043691344DA +:102C600082694361934224BF436A436100238362C4 +:102C7000036B03B11847704770B52023044683F3F4 +:102C80001188866A3EB9FFF7CBFF054618B186F377 +:102C90001188284670BDA36AE26A13F8015BA3623B +:102CA000934202D32046FFF7D5FF002383F3118818 +:102CB000EFE700002DE9F84F04460E461746984608 +:102CC0004FF0200989F311880025AA46D4F828B0CE +:102CD000BBF1000F09D141462046FFF7A1FF20B10B +:102CE0008BF311882846BDE8F88FD4E90A12A7EBC8 +:102CF000050B521A934528BF9346BBF1400F1BD9D1 +:102D0000334601F1400251F8040B43F8040B9142A1 +:102D1000F9D1A36A40334036A3624035D4E90A238F +:102D20009A4202D32046FFF795FF8AF31188BD42ED +:102D3000D8D289F31188C9E730465A46FDF7D2FF49 +:102D4000A36A5B445E44A3625D44E7E710B5029C5E +:102D50000172043304FB0321C0E906130023C0E918 +:102D60000A33039B0363049BC460C0E90000C0E90D +:102D70000422C0E90842436310BD0000026AC26039 +:102D8000426AC0E904220022C0E90A226FF0010170 +:102D9000FEF732BED0E904239A4201D1C26822B9BB +:102DA000184650F8043B0B60704700207047000045 +:102DB000C368C2690133C3604369134482694361D4 +:102DC000934224BF436A43610021FEF709BE00001D +:102DD00038B504460D46E3683BB123691A1DA2626B +:102DE000E2691344E362002007E0237A33B92946FD +:102DF0002046FEF7E5FD0028EDDA38BD6FF0010052 +:102E0000FBE7000003691960C268013AC260C26949 +:102E1000134482690361934224BF436A0361002320 +:102E20008362036B03B118477047000070B520231D +:102E30000D460446114683F31188866A2EB9FFF7C2 +:102E4000C7FF10B186F3118870BDA36A1D70A36A15 +:102E5000E26A01339342A36204D3E1692046043954 +:102E6000FFF7D0FF002080F31188EDE72DE9F84F40 +:102E700004460D46904699464FF0200A8AF3118881 +:102E80000026B346A76A4FB949462046FFF7A0FF80 +:102E900020B187F311883046BDE8F88FD4E90A07DE +:102EA0003A1AA8EB0607974228BF1746402F1BD9AE +:102EB00005F1400355F8042B40F8042B9D42F9D14D +:102EC000A36A4033A3624036D4E90A239A4204D36A +:102ED000E16920460439FFF795FF8BF311884645D9 +:102EE000D9D28AF31188CDE729463A46FDF7FAFE92 +:102EF000A36A3B443D44A3623E44E5E7D0E9042392 +:102F00009A4217D1C3689BB1836A8BB1043B9B1A69 +:102F10000ED01360C368013BC360C3691A44836960 +:102F200002619A4224BF436A036100238362012342 +:102F3000184670470023FBE700F088B84FF0804345 +:102F4000002258631A610222DA6070474FF0804312 +:102F50000022DA60704700004FF0804358637047EA +:102F60004FF08043586A70474B6843608B688360BA +:102F7000CB68C3600B6943614B6903628B69436231 +:102F80000B6803607047000008B5264B26481A6995 +:102F900040F2FF110A431A611A6922F4FF7222F00B +:102FA00001021A611A691A6B0A431A631A6D0A43FD +:102FB0001A651E4A1B6D1146FFF7D6FF02F11C0170 +:102FC00000F58060FFF7D0FF02F1380100F5806066 +:102FD000FFF7CAFF02F1540100F58060FFF7C4FF5C +:102FE00002F1700100F58060FFF7BEFF02F18C0175 +:102FF00000F58060FFF7B8FF02F1A80100F58060DE +:10300000FFF7B2FF02F1C40100F58060FFF7ACFFEB +:1030100002F1E00100F58060FFF7A6FFBDE808407F +:1030200000F09AB80038024000000240BC360008A8 +:1030300008B500F007FAFEF733FCFFF78DF8BDE89E +:103040000840FEF755BE000070470000104B1A6C98 +:1030500042F001021A641A6E42F001021A660D4A29 +:103060001B6E936843F0010393604FF0804353223B +:103070009A624FF0FF32DA6200229A615A63DA6094 +:103080005A6001225A6108211A601C20FFF774BDA2 +:1030900000380240002004E04FF0804208B511697A +:1030A000D3680B40D9B2C9439B07116107D52023D0 +:1030B00083F31188FEF714FC002383F3118808BD05 +:1030C00008B5FFF7E9FFBDE80840FFF78FB800003B +:1030D0001F4B1A696FEAC2526FEAD2521A611A691B +:1030E000C2F308021A614FF0FF301A695A69586139 +:1030F00000215A6959615A691A6A62F080521A624B +:103100001A6A02F080521A621A6A5A6A58625A6A35 +:1031100059625A6A1A6C42F080521A641A6E42F06E +:1031200080521A661A6E0B4A106840F48070106064 +:10313000186F00F44070B0F5007F1EBF4FF4803070 +:1031400018671967536823F40073536000F05AB985 +:103150000038024000700040334B4FF080521A6438 +:10316000324A4FF4404111601A6842F001021A607D +:103170001A689107FCD59A6822F003029A602A4BDC +:103180009A6812F00C02FBD1196801F0F90119607C +:103190009A601A6842F480321A601A689203FCD569 +:1031A0005A6F42F001025A671F4B5A6F9007FCD5C5 +:1031B0001F4A5A601A6842F080721A601B4A5368AC +:1031C0005904FCD5184B1A689201FCD5194A9A602B +:1031D000194B1A68194B9A42194B21D1194A116897 +:1031E000194A91421CD140F205121A60144A136820 +:1031F00003F00F03052BFAD10B4B9A6842F0020241 +:103200009A609A6802F00C02082AFAD15A6C42F4C9 +:1032100080425A645A6E42F480425A665B6E70472E +:1032200040F20572E1E700BF003802400070004044 +:103230000854400700948838002004E011640020FE +:10324000003C024000ED00E041C20F41084A08B5D1 +:10325000516913680B4003F00103536123B1054A20 +:1032600013680BB150689847BDE80840FEF7BEBF31 +:10327000003C0140282D0020084A08B55169136818 +:103280000B4003F00203536123B1054A93680BB16D +:10329000D0689847BDE80840FEF7A8BF003C014051 +:1032A000282D0020084A08B5516913680B4003F027 +:1032B0000403536123B1054A13690BB15069984760 +:1032C000BDE80840FEF792BF003C0140282D0020D9 +:1032D000084A08B5516913680B4003F008035361AD +:1032E00023B1054A93690BB1D0699847BDE80840FE +:1032F000FEF77CBF003C0140282D0020084A08B59D +:10330000516913680B4003F01003536123B1054A60 +:10331000136A0BB1506A9847BDE80840FEF766BFD4 +:10332000003C0140282D0020174B10B55A691C683D +:10333000144004F478725A61A30604D5134A936AC0 +:103340000BB1D06A9847600604D5104A136B0BB1D5 +:10335000506B9847210604D50C4A936B0BB1D06B88 +:103360009847E20504D5094A136C0BB1506C984795 +:10337000A30504D5054A936C0BB1D06C9847BDE802 +:103380001040FEF733BF00BF003C0140282D002055 +:103390001A4B10B55A691C68144004F47C425A61F7 +:1033A000620504D5164A136D0BB1506D984723057D +:1033B00004D5134A936D0BB1D06D9847E00404D542 +:1033C0000F4A136E0BB1506E9847A10404D50C4AF6 +:1033D000936E0BB1D06E9847620404D5084A136F00 +:1033E0000BB1506F9847230404D5054A936F0BB176 +:1033F000D06F9847BDE81040FEF7F8BE003C014092 +:10340000282D0020062108B50846FFF7B5FB062148 +:103410000720FFF7B1FB06210820FFF7ADFB0621CF +:103420000920FFF7A9FB06210A20FFF7A5FB0621CB +:103430001720FFF7A1FBBDE8084006212820FFF771 +:103440009BBB000008B5FFF743FE00F00BF8FDF74B +:10345000E5FEFDF7BDFDFFF7F7FDBDE80840FFF70E +:103460006BBD00000023054A19460133102BC2E949 +:10347000001102F10802F8D1704700BF282D00208A +:10348000034611F8012B03F8012B002AF9D17047EC +:1034900053544D3332463F3F3F00000053544D33A9 +:1034A00032463430780053544D333246343278004B +:1034B00053544D333246343436585800000000001F +:1034C000903400083F000000130400009C34000802 +:1034D0003F00000019040000A63400083F0000006F +:1034E00021040000B03400083F000000000000008C +:1034F0004D0F0008390F0008750F0008610F000814 +:103500006D0F0008590F0008450F0008310F000823 +:10351000810F000800000000010000000000000012 +:103520006D61696E0000000069646C650000000058 +:1035300028350008D8230020502500200100000075 +:103540009D180008000000004172647550696C6F9E +:10355000740025424F415244252D424C00255345CD +:103560005249414C2500000002000000000000000C +:1035700069110008D511000840004000E82900202A +:10358000F8290020020000000000000003000000F5 +:1035900000000000191200080000000010000000E8 +:1035A000082A0020000000000100000000000000C8 +:1035B000B02C0020010102008D1C00089D1B00089A +:1035C000391C00081D1C000843000000D03500080D +:1035D00009024300020100C0320904000001020296 +:1035E0000100052400100105240100010424020249 +:1035F0000524060001070582030800FF09040100F5 +:10360000020A0000000705010240000007058102D0 +:1036100040000000120000001C36000812011001DA +:10362000020000400912415700020102030100009C +:103630000403090425424F41524425004D6174653D +:103640006B463430352D53544400303132333435E9 +:1036500036373839414243444546000000400000B7 +:103660000040000000400000004000000000010099 +:103670000000020000000200000002000000020042 +:103680000000020000000200000002000000000034 +:103690005113000809160008B51600084000400044 +:1036A000102D0020102D002001000000202D0020F2 +:1036B00080000000400100000300000000008012B4 +:1036C00000000000AAAAAAAA00000000FFBF000094 +:1036D0000000000000A00A0000001400000000002C +:1036E000AAAAAAAA00001000FFFD00000000000026 +:1036F000000000001500000000000000AAAAAAAA0D +:1037000015000000FFFF00000000000000000000A6 +:103710000000000000000000AAAAAAAA0000000001 +:10372000FFFF00000000000000000000000000009B +:1037300000000000AAAAAAAA00000000FFFF0000E3 :103740000000000000000000000000000000000079 +:10375000AAAAAAAA00000000FFFF000000000000C3 +:10376000000000000000000000000000AAAAAAAAB1 +:1037700000000000FFFF000000000000000000004B +:1037800000000000000000000A000000000000002F +:103790000300000000000000000000000000000026 +:1037A0000000000000000000000000000000000019 +:1037B00000000000000000007D000000000000008C +:1037C00000000F0000000000FF009600000000084D +:1037D00000960000000008000400000030360008D9 +:1037E00000000000000000000000000000000000D9 +:0837F0000000000000000000D1 :00000001FF diff --git a/Tools/bootloaders/MatekF405-TE_bl.bin b/Tools/bootloaders/MatekF405-TE_bl.bin old mode 100644 new mode 100755 index 396746f4d99..97785398a82 Binary files a/Tools/bootloaders/MatekF405-TE_bl.bin and b/Tools/bootloaders/MatekF405-TE_bl.bin differ diff --git a/Tools/bootloaders/MatekF405-TE_bl.hex b/Tools/bootloaders/MatekF405-TE_bl.hex index 199c78e2968..4389b11ae3d 100644 --- a/Tools/bootloaders/MatekF405-TE_bl.hex +++ b/Tools/bootloaders/MatekF405-TE_bl.hex @@ -1,25 +1,25 @@ :020000040800F2 :1000000000060020E1010008F90E0008790E000842 :10001000D10E0008790E0008A50E0008E3010008C3 -:10002000E3010008E3010008E30100084527000898 +:10002000E3010008E3010008E3010008B927000824 :10003000E3010008E3010008E3010008E301000810 :10004000E3010008E3010008E3010008E301000800 -:10005000E3010008E3010008E13700080D3800085B -:10006000393800086538000891380008E3010008B5 +:10005000E3010008E3010008553800088138000872 +:10006000AD380008D938000805390008E301000858 :10007000E3010008E3010008E3010008E3010008D0 :10008000E3010008E3010008E3010008E3010008C0 -:10009000E3010008E3010008E3010008BD3800089F +:10009000E3010008E3010008E3010008313900082A :1000A000E3010008E3010008E3010008E3010008A0 -:1000B00055360008E3010008E3010008E3010008E9 +:1000B000C9360008E3010008E3010008E301000875 :1000C000E3010008E3010008E3010008E301000880 :1000D000E3010008510F0008E3010008E3010008F4 -:1000E00025390008E3010008E3010008E3010008E6 +:1000E00099390008E3010008E3010008E301000872 :1000F000E3010008E3010008E3010008E301000850 :10010000E3010008E3010008E3010008E30100083F :10011000E3010008E3010008E3010008E30100082F :10012000E3010008E3010008E3010008E30100081F :10013000E3010008E3010008E3010008E30100080F -:10014000E3010008E3010008E30100087D2E000838 +:10014000E3010008E3010008E3010008F12E0008C4 :10015000E3010008E3010008E3010008E3010008EF :10016000E3010008E3010008E3010008E3010008DF :10017000E3010008E3010008E3010008E3010008CF @@ -36,31 +36,31 @@ :10022000C0F2F0004EF68851CEF200010860BFF334 :100230004F8FBFF36F8F4FF00000E1EE100A4EF6C4 :100240003C71CEF200010860062080F31488BFF3F1 -:100250006F8F02F0F7FA02F0D3FA03F05FF94FF074 +:100250006F8F02F031FB02F00DFB03F099F94FF0C4 :1002600055301F491B4A91423CBF41F8040BFAE745 :100270001C49194A91423CBF41F8040BFAE71A495C :100280001A4A1B4B9A423EBF51F8040B42F8040B2A :10029000F8E700201749184A91423CBF41F8040B87 -:1002A000FAE702F0B1FA03F08DF9144C144DAC42A8 +:1002A000FAE702F0EBFA03F0C7F9144C144DAC4234 :1002B00003DA54F8041B8847F9E700F041F8114CC1 :1002C000114DAC4203DA54F8041B8847F9E702F0F9 -:1002D00099BA00000006002000220020000000085B -:1002E0000000002000060020983D000800220020A9 -:1002F00040220020402200201C300020E0010008A5 +:1002D000D3BA000000060020002200200000000821 +:1002E0000000002000060020083E00080022002038 +:1002F000402200204022002020300020E0010008A1 :10030000E0010008E0010008E00100082DE9F04FDD :100310002DED108AC1F80CD0C3689D46BDEC108A43 :10032000BDE8F08F002383F311882846A047002002 -:1003300001F02AFEFEE701F0BFFD00DFFEE700004E -:1003400038B502F0D1F9054602F0F6F90446D8B9FD +:1003300001F04EFEFEE701F0C9FD00DFFEE7000020 +:1003400038B502F009FA054602F02CFA0446D8B98D :100350000F4B9D421AD001339D4218BF044641F213 -:10036000883504BF01240025002002F0C7F90CB134 +:10036000883504BF01240025002002F0FFF90CB1FC :1003700000F056F800F028FD00F0A2FB284600F03F :10038000A7F800F04DF8F9E70025EDE70546EBE7A3 :10039000010007B008B500F05FFBA0F12003584250 :1003A000584108BD07B541F21203022101A8ADF87A :1003B000043000F06FFB03B05DF804FB10B52023A0 -:1003C00083F311881248C3680BB101F063FE114A30 -:1003D0000F4800234FF47A7101F020FE002383F3CD +:1003C00083F311881248C3680BB101F087FE114A0C +:1003D0000F4800234FF47A7101F044FE002383F3A9 :1003E00011880D4C236813B12368013B23606368B7 :1003F00013B16368013B6360084B1B7833B96368D2 :1004000023B9022000F052FC3223636010BD00BF0C @@ -79,7 +79,7 @@ :1004D0002DE9F04F93B0A94B00902022FF210AA8EC :1004E0009D6800F01BFCA64A1378A3B9A54801211A :1004F000C3601170202383F31188C3680BB101F02E -:10050000C9FDA14A9F4800234FF47A7101F086FD8E +:10050000EDFDA14A9F4800234FF47A7101F0AAFD46 :10051000002383F31188009B9C4A03B113609C491C :10052000009C00230B70536098469B461E469A46DB :10053000012000F0ABFB24B1944B1B68002B00F0B2 @@ -149,12 +149,12 @@ :100930004FF47A70FFF72EFD00283FF447AE00F029 :1009400023F9002844D00A9B01330BD008220AA9BE :10095000002000F0EBF900283AD02022FF210AA85D -:1009600000F0DCF9FFF71EFD1C4801F013FB13B08B +:1009600000F0DCF9FFF71EFD1C4801F037FB13B067 :10097000BDE8F08F002E3FF429AE0BF00B030B2BDC :100980007FF424AE0023642105A8059300F078F8D5 :10099000074600287FF41AAE0220FFF7FBFC8146D1 :1009A00000283FF413AEFFF7FDFC41F2883001F060 -:1009B000F1FA059800F040FA4E4600F0FBF93C468B +:1009B00015FB059800F040FA4E4600F0FBF93C4666 :1009C000B6E506464CE64FF0000AFFE5B8467BE682 :1009D000374679E65822002000220020A086010038 :1009E000F7B5194E0C464FF47A7102FB01F396F9F4 @@ -163,23 +163,23 @@ :100A1000002AF1D096F90020511C01D0012A0DD1F5 :100A20000B4802682946166A2246B047844205D11F :100A30000123084A0120137003B0F0BD4FF4FA708F -:100A400001F0A8FA0020F7E710220020C8270020B4 +:100A400001F0CCFA0020F7E710220020C827002090 :100A5000A8230020A423002007B50023024601217B :100A60000DF107008DF80730FFF7BAFF20B19DF8B0 :100A7000070003B05DF804FB4FF0FF30F9E700001A :100A80000A4608B50421FFF7ABFF80F00100C0B2B1 :100A9000404208BD30B4074B0A461978064B53F85C :100AA00021402368DD69054B0146AC46204630BC39 -:100AB000604700BFA4230020843A0008A0860100FC -:100AC00070B501F017FD094E094D308000242868EB -:100AD0003388834208D901F007FD2B6804440133B1 +:100AB000604700BFA4230020F83A0008A086010088 +:100AC00070B501F03BFD094E094D308000242868C7 +:100AD0003388834208D901F02BFD2B68044401338D :100AE000B4F5803F2B60F2D370BD00BFA623002079 -:100AF0006423002001F0ACBD00F1006000F58030FF +:100AF0006423002001F0E4BD00F1006000F58030C7 :100B00000068704700F10060920000F5803001F04D -:100B100037BD0000054B1A68054B1B889B1A8342A2 -:100B200002D9104401F0E0BC00207047642300208B +:100B100063BD0000054B1A68054B1B889B1A834276 +:100B200002D9104401F004BD002070476423002066 :100B3000A623002038B5074D04462868204401F05C -:100B4000DBFC28B928682044BDE8384001F0ECBC43 +:100B4000FFFC28B928682044BDE8384001F010BDFA :100B500038BD00BF6423002010F003030AD1B0F5B4 :100B6000047F05D200F10050A0F51040D0F8003805 :100B7000184670470023FBE700F10050A0F5104035 @@ -197,7 +197,7 @@ :100C3000D5E70222D3E70C4DD6E73323E9E741237A :100C4000E7E75A23E5E75923E3E7104605E02C25BB :100C50008442157001D9901C5370401A70BD00BFBA -:100C6000002004E0543A0008283A0008022804D181 +:100C6000002004E0C83A00089C3A0008022804D199 :100C7000054B4FF080429A6170470128FCD1024B2E :100C80004FF00052F7E700BF00000240022804D1F5 :100C9000054B4FF480429A6170470128FCD1024B0A @@ -222,14 +222,14 @@ :100DC000A42300201022002038B5154C154D2046D4 :100DD00000F01AFC2946204600F042FC2D6812481B :100DE0006A6DD2F8043843F00203C2F8043801F007 -:100DF000D1F80E49284600F039FD6A6D0C48D2F84A +:100DF000F5F80E49284600F039FD6A6D0C48D2F826 :100E000004380C4923F00203C2F80438A0424FF41E :100E1000E1330B6003D0BDE8384000F055BB38BD6E -:100E2000C82700208C3B000840420F00943B00087C +:100E2000C8270020003C000840420F00083C000892 :100E3000A82300209023002038B50B4B1A780B4BC9 :100E400053F822500A4B9D4204460CD0094B002116 :100E500018461422FFF762FF046001462846BDE8E9 -:100E6000384000F031BB38BDA4230020843A00088C +:100E6000384000F031BB38BDA4230020F83A000818 :100E7000C82700209023002000B59BB0EFF3098124 :100E800068226846FFF724FFEFF30583044B9A6B53 :100E9000DA6A9A6A9A6A9A6A9A6A9A6A9B6AFEE710 @@ -255,7 +255,7 @@ :100FD0009A4209D1336C3BB127F040073F041020FF :100FE0003F0CFFF7A9FFEF60002383F31188D6F8C9 :100FF0006422D3680BB110699847BDE8F04101F055 -:10100000D5BB230712D014F0080F0CBF002080209E +:101000000FBC230712D014F0080F0CBF0020802063 :10101000E10748BF40F02000A20748BF40F0400071 :10102000630748BF40F48070FFF786FFA4066B6833 :1010300005D596F860124046194000F053FA2C6826 @@ -273,7 +273,7 @@ :1010F0000103536141F4045343F02C03D36001F422 :10110000A05100231360B1F5806F136853680CBFC2 :101110007F23FF2385F8603238BD0649D3E700BF3F -:101120008C3A0008A823002000380240001001403B +:10112000003B0008A82300200038024000100140C6 :1011300000BD010580DE800200F1604303F56143DC :101140000901C9B283F80013012200F01F039A407D :1011500043099B0003F1604303F56143C3F8802119 @@ -292,16 +292,16 @@ :10122000029B8460C0E90000C0E90511C160026151 :10123000036210BD08B5D0E90532934201D182683E :1012400082B98268013282605A1C42611970D0E909 -:1012500004329A4224BFC3684361002100F0B6FE05 +:1012500004329A4224BFC3684361002100F0DAFEE1 :10126000002008BD4FF0FF30FBE7000070B52023E1 :1012700004460E4683F31188A568A5B1A368A26948 :10128000013BA360531CA36115782269934224BFDC :10129000E368A361E3690BB120469847002383F319 -:1012A0001188284607E03146204600F07FFE0028DE +:1012A0001188284607E03146204600F0A3FE0028BA :1012B000E2DA85F3118870BD2DE9F74F04460E463A :1012C00017469846D0F81C904FF0200A8AF31188F0 :1012D0004FF0000B154665B12A4631462046FFF710 -:1012E00041FF034660B94146204600F05FFE0028FA +:1012E00041FF034660B94146204600F083FE0028D6 :1012F000F1D0002383F31188781B03B0BDE8F08F91 :10130000B9F1000F03D001902046C847019B8BF331 :101310001188ED1A1E448AF31188DCE7C0E9051133 @@ -310,14 +310,14 @@ :101340001188A768A7B1A368013BA36063695A1C11 :1013500062611D70D4E904329A4224BFE36863617C :10136000E3690BB120469847002080F3118807E01D -:101370003146204600F01AFE0028E2DA87F3118891 +:101370003146204600F03EFE0028E2DA87F311886D :10138000F8BD0000D0E905239A4210B501D182686A :101390007AB98268013282605A1C82611C780369C2 -:1013A0009A4224BFC3688361002100F00FFE2046EB +:1013A0009A4224BFC3688361002100F033FE2046C7 :1013B00010BD4FF0FF30FBE72DE9F74F04460E4616 :1013C00017469846D0F81C904FF0200A8AF31188EF :1013D0004FF0000B154665B12A4631462046FFF70F -:1013E000EFFE034660B94146204600F0DFFD0028CD +:1013E000EFFE034660B94146204600F003FE0028A8 :1013F000F1D0002383F31188781B03B0BDE8F08F90 :10140000B9F1000F03D001902046C847019B8BF330 :101410001188ED1A1E448AF31188DCE702684368DC @@ -331,7 +331,7 @@ :10149000C0E902220122044602740B46009000F1CA :1014A0005C014FF480721430FFF7B6FE00942B46B7 :1014B0004FF4807204F5AE7104F13800FFF72EFF8F -:1014C00003B030BDA03A000810B52023044683F3D2 +:1014C00003B030BD143B000810B52023044683F35D :1014D0001188FFF7CFFD02232374002383F31188C3 :1014E00010BD000038B5C36904460D461BB9042180 :1014F0000844FFF793FF294604F11400FFF79AFE12 @@ -339,34 +339,34 @@ :1015100085BF38BD026843681143016003B11847B5 :101520007047000013B5446BD4F894341A681178EE :10153000042915D1217C022912D11979128901239C -:101540008B4013420CD101A904F14C0001F0ECFED8 +:101540008B4013420CD101A904F14C0001F026FF9D :10155000D4F89444019B21790246206800F0CEF92A -:1015600002B010BD143001F06FBE00004FF0FF3329 -:10157000143001F069BE00004C3001F041BF0000A2 -:101580004FF0FF334C3001F03BBF0000143001F04E -:101590003DBE00004FF0FF31143001F037BE0000B7 -:1015A0004C3001F00DBF00004FF0FF324C3001F025 -:1015B00007BF00000020704710B5D0F894341A68B7 +:1015600002B010BD143001F0A9BE00004FF0FF33EF +:10157000143001F0A3BE00004C3001F07BBF00002E +:101580004FF0FF334C3001F075BF0000143001F014 +:1015900077BE00004FF0FF31143001F071BE000043 +:1015A0004C3001F047BF00004FF0FF324C3001F0EB +:1015B00041BF00000020704710B5D0F894341A687D :1015C00011780429044617D1017C022914D15979D4 -:1015D000528901238B4013420ED1143001F0D0FD0B +:1015D000528901238B4013420ED1143001F00AFED0 :1015E000024648B1D4F894444FF48073617920687E :1015F000BDE8104000F070B910BD0000406BFFF76F :10160000DBBF0000704700007FB5124B0360002372 :101610004360C0E90233012502260F4B05740446DE :101620000290019300F18402294600964FF48073E2 -:10163000143001F081FD094B0294CDE9006304F5FB -:1016400023724FF48073294604F14C0001F048FEE8 -:1016500004B070BDC83A0008FD1500082515000843 +:10163000143001F0BBFD094B0294CDE9006304F5C1 +:1016400023724FF48073294604F14C0001F082FEAE +:1016500004B070BD3C3B0008FD15000825150008CE :101660000B68202282F311880A7903EB82029061D1 :101670004A79093243F822008A7912B103EB8203D6 :10168000986102230374C0F89414002383F3118833 :101690007047000038B5037F044613B190F854300A :1016A000ABB9201D01250221FFF734FF04F114001E -:1016B00025776FF0010100F095FC84F8545004F197 -:1016C0004C006FF00101BDE8384000F08BBC38BD24 +:1016B00025776FF0010100F0B9FC84F8545004F173 +:1016C0004C006FF00101BDE8384000F0AFBC38BD00 :1016D00010B5012104460430FFF71CFF00232377D7 :1016E00084F8543010BD000038B50446002514308D -:1016F00001F03AFD04F14C00257701F009FE201DB0 +:1016F00001F074FD04F14C00257701F043FE201D3C :1017000084F854500121FFF705FF2046BDE838401A :10171000FFF752BF90F8443003F06003202B07D14D :1017200090F84520212A4FF0000303D81F2A06D83D @@ -374,43 +374,43 @@ :1017400082630722C26303640120704711220020D4 :1017500037B5D0F894341A681178042904461AD1A0 :10176000017C022917D11979128901238B40134278 -:1017700011D100F14C05284601F08AFE58B101A9AB -:10178000284601F0D1FDD4F89444019B217902460A +:1017700011D100F14C05284601F0C4FE58B101A971 +:10178000284601F00BFED4F89444019B21790246CF :10179000206800F0B3F803B030BD0000F0B500EBF6 :1017A000810385B09E6904460D46FEB1202383F374 :1017B000118804EB8507301D0821FFF7ABFEFB689D -:1017C0005B691B6806F14C001BB1019001F0BAFD8A -:1017D000019803A901F0A8FD024648B1039B2946E0 +:1017C0005B691B6806F14C001BB1019001F0F4FD50 +:1017D000019803A901F0E2FD024648B1039B2946A6 :1017E000204600F08BF8002383F3118805B0F0BD8C :1017F000FB685A691268002AF5D01B8A013B134026 :10180000F1D104F14402EAE7093138B550F821403A :10181000DCB1202383F31188D4F89424136852791F :1018200003EB8203DB689B695D6845B104216018A6 -:10183000FFF770FE294604F1140001F0ABFC2046CE +:10183000FFF770FE294604F1140001F0E5FC204694 :10184000FFF7BAFE002383F3118838BD704700000C -:1018500001F06EB8012303700023C0E90133C361B6 +:1018500001F0A8B8012303700023C0E90133C3617C :1018600083620362C36243620363704738B5044610 :10187000202383F311880025C0E90355C0E90555ED -:10188000416001F065F80223237085F3118838BDAB +:10188000416001F09FF80223237085F3118838BD71 :1018900070B500EB810305465069DA600E461446C8 :1018A00018B110220021FFF739FAA06918B11022EF :1018B0000021FFF733FA31462846BDE8704001F0B9 -:1018C00011B90000826802F0011282600022C0E9B2 -:1018D0000422826101F092B9F0B400EB81044789DF +:1018C0004BB90000826802F0011282600022C0E978 +:1018D0000422826101F0CCB9F0B400EB81044789A5 :1018E000E4680125A4698D403D43458123600023C0 -:1018F000A2606360F0BC01F0ADB90000F0B400EB91 +:1018F000A2606360F0BC01F0E7B90000F0B400EB57 :1019000081040789E468012564698D403D430581B0 -:1019100023600023A2606360F0BC01F027BA0000DE +:1019100023600023A2606360F0BC01F061BA0000A4 :1019200070B50223002504460370C0E90255C0E9E2 -:101930000455C564856180F8345001F06FF8636820 +:101930000455C564856180F8345001F0A9F86368E6 :101940001B6823B129462046BDE87040184770BD8A :10195000037880F850300523037043681B6810B586 :1019600004460BB1042198470023A36010BD00007A :1019700090F85020436802701B680BB1052118478E :101980007047000070B590F83430044613B100235E -:1019900080F8343004F14402204601F051F96368C4 +:1019900080F8343004F14402204601F08BF963688A :1019A0009B68B3B994F8443013F0600535D000213A -:1019B000204601F0A3FB0021204601F095FB63685F +:1019B000204601F0DDFB0021204601F0CFFB6368EB :1019C0001B6813B1062120469847062384F834305B :1019D00070BD204698470028E4D0B4F84A30E26B46 :1019E0009A4288BFE36394F94430E56B002B4FF0D3 @@ -430,7 +430,7 @@ :101AC000A3630223E3630023C3E794F84630012BAA :101AD0007FF46DAFB4F84C3023F00203C4E90E5527 :101AE000A4F84C30256478E7B4F84430B3F5A06F1F -:101AF0000ED194F8463084F84E30204600F0E6FFD0 +:101AF0000ED194F8463084F84E30204601F020F89C :101B000063681B6813B101212046984703232370A3 :101B10000023C4E90E339CE704F14F03A3630123C0 :101B2000C3E72378042B10D1202383F311882046A8 @@ -438,19 +438,19 @@ :101B400021701B680BB12046984794F84630002B53 :101B5000DED084F84F300423237063681B68002BA9 :101B6000D6D0022120469847D2E794F848301D0687 -:101B700003F00F0120460AD501F054F8012804D0E3 +:101B700003F00F0120460AD501F08EF8012804D0A9 :101B800002287FF414AF2B4B9AE72B4B98E701F018 -:101B90003BF8F3E794F84630002B7FF408AF94F855 +:101B900075F8F3E794F84630002B7FF408AF94F81B :101BA000483013F00F01B3D01A06204602D501F0D9 -:101BB000B9FAADE701F0ACFAAAE794F84630002B89 +:101BB000F3FAADE701F0E6FAAAE794F84630002B15 :101BC0007FF4F5AE94F8483013F00F01A0D01B0657 -:101BD000204602D501F092FA9AE701F085FA97E7DC +:101BD000204602D501F0CCFA9AE701F0BFFA97E768 :101BE000142284F8342083F311882B462A46294690 :101BF0002046FFF771FE85F31188E9E65DB11522F5 :101C000084F8342083F311880021D4E90E23204680 :101C1000FFF762FEFDE60B2284F8342083F311887F :101C20002B462A4629462046FFF768FEE3E700BF19 -:101C3000F83A0008F03A0008F43A000838B590F88D +:101C30006C3B0008643B0008683B000838B590F82E :101C400034300446002B3ED0063BDAB20F2A34D89B :101C50000F2B32D8DFE803F037313108223231312F :101C60003131313131313737C56BB0F84A309D42AF @@ -459,12 +459,12 @@ :101C900085F311880A2384F834300EE0142384F885 :101CA0003430202383F3118800231A461946204636 :101CB000FFF712FE002383F3118838BD036C03B1D4 -:101CC00098470023E7E70021204601F017FA00219A -:101CD000204601F009FA63681B6813B1062120460B +:101CC00098470023E7E70021204601F051FA002160 +:101CD000204601F043FA63681B6813B106212046D1 :101CE00098470623D7E7000010B590F83430142B3E :101CF000044629D017D8062B05D001D81BB110BD3A -:101D0000093B022BFBD80021204601F0F7F9002106 -:101D1000204601F0E9F963681B6813B106212046EB +:101D0000093B022BFBD80021204601F031FA0021CB +:101D1000204601F023FA63681B6813B106212046B0 :101D20009847062319E0152BE9D10B2380F83430AE :101D3000202383F3118800231A461946FFF7DEFD9E :101D4000002383F31188DAE7C3689B695B68002B83 @@ -480,8 +480,8 @@ :101DE0005860704710260020054B19690874186860 :101DF00002681A605360186101230374FEF786BA03 :101E00001026002030B54B1C0B4D87B0044610D077 -:101E10002B690A4A01A800F001F92046FFF7E4FF08 -:101E2000049B13B101A800F035F92B69586907B07C +:101E10002B690A4A01A800F025F92046FFF7E4FFE4 +:101E2000049B13B101A800F059F92B69586907B058 :101E300030BDFFF7D9FFF8E710260020911D0008FC :101E400038B50C4D41612B6981689A68914204460E :101E500003D8BDE83840FFF78BBF1846FFF7B4FF43 @@ -490,503 +490,510 @@ :101E80009B68984294BF00200120704710260020D4 :101E900010B5084C236820691A682260546001223A :101EA00023611A74FFF790FF01462069BDE81040D6 -:101EB000FEF72CBA10260020FFF7EABFFEE700006D -:101EC00010B50C4CFFF74CFF00F09AF80A4980223D -:101ED000204600F021F8012344F8180C037400F0A8 -:101EE00041FC002383F3118862B60448BDE810402A -:101EF00000F032B838260020FC3A00080C3B0008FD -:101F000000F002B9034A516853685B1A9842FBD843 -:101F1000704700BF001000E082600222028270471A -:101F20008368A3F17C0243F80C2C026943F83C2C33 -:101F3000426943F8382C074A43F81C2CC26843F81E -:101F4000102C022203F8082C002203F8072CA3F11E -:101F5000180070472503000810B5202383F311886B -:101F6000FFF7DEFF00210446FFF76AFF002383F33B -:101F70001188204610BD0000024B1B6958610F20DC -:101F8000FFF732BF10260020202383F31188FFF7CC -:101F9000F3BF000008B50146202383F31188082011 -:101FA000FFF730FF002383F3118808BD49B1064BCA -:101FB00042681B6918605A60136043600420FFF791 -:101FC00021BF4FF0FF307047102600200368984271 -:101FD00006D01A680260506059611846FFF7C8BE03 -:101FE0007047000038B504460D462068844200D191 -:101FF00038BD036823605C604561FFF7B9FEF4E714 -:10200000054B03F11402C3E905224FF0FF31002212 -:10201000C3E90712704700BF1026002070B51C4EA0 -:10202000C0E9032305460C4601F064FA334653F831 -:10203000142F9A420DD13062C5E901242A600A2C7E -:102040002CBF00190A30C6E90555BDE8704001F003 -:102050003FBA316A431AE31838BF1C469368A3425B -:1020600002D9081901F042FA73699A6894420CD8AF -:102070005A68AC602B606A6015609A685D60121BDC -:102080009A604FF0FF33F36170BD1B68A41AECE750 -:102090001026002038B51B4C636998420DD0D0E95A -:1020A000003213605A6000228168C2609A680A4454 -:1020B0009A604FF0FF33E36138BD2246036842F86F -:1020C000143F002193425A60C16003D1BDE83840FB -:1020D00001F006BA9A688168256A0A449A6001F09C -:1020E00009FA63699A68411B8A42E5D9AB181D1A3F -:1020F000092D206A98BF01F10A02BDE8384010445A -:1021000001F0F4B9102600202DE9F041184C002709 -:1021100004F11406656901F0EDF9236AAA68C11A91 -:102120008A4215D813442362D5E9003213605A60FD -:102130006369D5F80C80EF60B34201D101F0D0F9AA -:1021400087F311882869C047202383F31188E1E7CA -:102150006169B14209D013441B1ABDE8F0410A2B52 -:102160002CBFC0180A3001F0C1B9BDE8F08100BF32 -:102170001026002000207047FEE700007047000096 -:102180004FF0FF307047000002290CD0032904D023 -:102190000129074818BF00207047032A05D80548C1 -:1021A00000EBC2007047044870470020704700BF32 -:1021B000F03B000820220020A43B000870B59AB034 -:1021C0000546084601A9144600F0C2F801A8FEF72A -:1021D0009DFD431C5B00C5E90034002223700323EE -:1021E0006370C6B201AB02341046D1B28E4204F124 -:1021F000020401D81AB070BD13F8011B04F8021CC8 -:1022000004F8010C0132F0E708B5202383F31188AC -:102210000348FFF79DFA002383F3118808BD00BF30 -:10222000C827002090F8443003F01F02012A07D18C -:1022300090F845200B2A03D10023C0E90E3315E0A6 -:1022400003F06003202B08D1B0F848302BB990F888 -:102250004520212A03D81F2A04D8FFF75BBA222A77 -:10226000EBD0FAE7034A82630722C26303640120CA -:10227000704700BF1822002007B5052917D8DFE8EE -:1022800001F0191603191920202383F31188104A2D -:1022900001900121FFF7FCFA01980E4A0221FFF795 -:1022A000F7FA0D48FFF720FA002383F3118803B0F3 -:1022B0005DF804FB202383F311880748FFF7EAF950 -:1022C000F2E7202383F311880348FFF701FAEBE7D5 -:1022D000443B0008683B0008C827002038B50C4D77 -:1022E0000C4C0D492A4604F10800FFF767FF05F181 -:1022F000CA0204F110000949FFF760FF05F5CA7230 -:1023000004F118000649BDE83840FFF757BF00BF89 -:10231000902C002020220020243B00082E3B0008A7 -:10232000393B000870B5044608460D46FEF7EEFC42 -:10233000C6B22046013403780BB9184670BD324648 -:102340002946FEF7CFFC0028F3D10120F6E7000074 -:102350002DE9F84F05460C46FEF7D8FC2B49C6B2CE -:102360002846FFF7DFFF08B10536F6B228492846B0 -:10237000FFF7D8FF08B11036F6B2632E0DD8DFF89C -:102380008C80DFF88C90234FDFF890A0DFF890B0BE -:102390002E7846B92670BDE8F88F29462046BDE85C -:1023A000F84F01F039BB252E2BD107224146284694 -:1023B000FEF798FC58B9DBF800302360DBF80430F6 -:1023C0006360DBF80830A36007350C34E0E70822CF -:1023D00049462846FEF786FC98B90F4BA21C19788F -:1023E00009090232C95D02F8041C13F8011B01F04F -:1023F0000F015345C95D02F8031CF0D118340835AC -:10240000C6E704F8016B0135C2E700BF103C0008C5 -:10241000393B0008253C0008107AFF1F1C7AFF1F7B -:10242000183C0008BFF34F8F024AD368DB03FCD48B -:10243000704700BF003C024008B5094B1B7873B9D8 -:10244000FFF7F0FF074B1A69002ABFBF064A5A6020 -:1024500002F188325A601A6822F480621A6008BD5C -:10246000EE2E0020003C02402301674508B50B4BCF -:102470001B7893B9FFF7D6FF094B1A6942F0004267 -:102480001A611A6842F480521A601A6822F4805263 -:102490001A601A6842F480621A6008BDEE2E0020AD -:1024A000003C02400B28F0B516D80C4C0C492378A0 -:1024B0007BB90C4D0E460C234FF0006255F8047B9F -:1024C00046F8042B013B13F0FF033A44F6D10123F5 -:1024D000237051F82000F0BD0020FCE7202F0020E1 -:1024E000F02E0020383C0008014B53F820007047C4 -:1024F000383C00080C2070470B2810B5044601D961 -:10250000002010BDFFF7CEFF064B53F824301844CF -:10251000C21A0BB90120F4E712680132F0D1043B72 -:10252000F6E700BF383C00080B2810B5044621D858 -:10253000FFF778FFFFF780FF0F4AF323D360C30054 -:10254000DBB243F4007343F002031361136943F4F5 -:1025500080331361FFF766FFFFF7A4FF074B53F8C3 -:10256000241000F0D9F8FFF781FF2046BDE81040A5 -:10257000FFF7C2BF002010BD003C0240383C0008FD -:10258000F8B512F00103144642D18218B2F1016F7E -:1025900057D82D4B1B6813F0010352D02B4DFFF77A -:1025A0004BFFF323EB60FFF73DFF40F20127032CC5 -:1025B00015D824F001046618244C401A40F2011783 -:1025C000B142236900EB010524D123F0010323610B -:1025D000FFF74CFF0120F8BD043C0430E7E7830718 -:1025E000E7D12B6923F440732B612B693B432B61AB -:1025F00051F8046B0660BFF34F8FFFF713FF0368BA -:102600009E42E9D02B6923F001032B61FFF72EFFD7 -:102610000020E0E723F44073236123693B432361F7 -:102620000B882B80BFF34F8FFFF7FCFE2D8831F80E -:10263000023BADB2AB42C3D0236923F00103236157 -:10264000E4E71846C7E700BF00380240003C0240FC -:10265000084908B50B7828B11BB9FFF7EDFE012337 -:102660000B7008BD002BFCD0BDE808400870FFF7D8 -:10267000FDBE00BFEE2E002010B50244064BD2B2C4 -:10268000904200D110BD441C00B253F8200041F824 -:10269000040BE0B2F4E700BF502800400F4B30B508 -:1026A0001C6F240407D41C6F44F400741C671C6F57 -:1026B00044F400441C670A4C236843F4807323608D -:1026C0000244084BD2B2904200D130BD441C00B24B -:1026D00051F8045B43F82050E0B2F4E700380240C0 -:1026E000007000405028004007B5012201A90020D9 -:1026F000FFF7C2FF019803B05DF804FB13B5044671 -:10270000FFF7F2FFA04205D0012201A900200194A9 -:10271000FFF7C4FF02B010BD70470000044BD3F8B0 -:1027200074389B0042BF034B01221A70704700BFF0 -:1027300000300240212F0020014B1878704700BF65 -:10274000212F0020EFF3098305494A6B22F0010293 -:102750004A63683383F30988002383F31188704741 -:1027600000EF00E0202080F3118862B60C4B0D4A88 -:10277000D96821F4E0610904090C0A43DA60D3F84E -:10278000FC20094942F08072C3F8FC200A6842F03C -:1027900001020A601022DA7783F82200704700BF36 -:1027A00000ED00E00003FA05001000E010B5202362 -:1027B00083F311880E4B5B6813F4006314D0F1EEC1 -:1027C000103AEFF30984683C4FF08073E361094BE2 -:1027D000DB6B236684F30988FFF74EFB10B1064BD1 -:1027E000A36110BD054BFBE783F31188F9E700BF38 -:1027F00000ED00E000EF00E0370300083A030008B6 -:1028000070470000FEE700000A4B0B480B4A90425D -:102810000BD30B4BDA1C121AC11E22F003028B429F -:1028200038BF00220021FEF779BA53F8041B40F8A4 -:10283000041BECE7D83D00081C3000201C300020B1 -:102840001C3000207047000070B5D0E915439E6829 -:1028500000224FF0FF3504EB42135101D3F8000979 -:102860000028BEBFD3F8000940F08040C3F800093B -:10287000D3F8000B0028BEBFD3F8000B40F0804017 -:10288000C3F8000B013263189642C3F80859C3F825 -:10289000085BE0D24FF00113C4F81C3870BD000093 -:1028A0001D4B03EB80022DE9F043D2F80CC05D6DA7 -:1028B000DCF81420461CD2F800E005EB063605EBE8 -:1028C0004018516871450AD3D5F83438012202FA0C -:1028D00000F023EA0000C5F83408BDE8F083BCF836 -:1028E0001040AEEB0103A34228BF2346D8F8184995 -:1028F000A4B2B3EB840FF0D89468A4F1040959F89A -:10290000047F3760A4EB09071F44042FF7D81C4449 -:102910000B4494605360D4E7242F0020890141F0D8 -:102920002001016103699B06FCD41220FFF7EABA7B -:1029300010B5054C2046FEF78DFF4FF0A0436365B0 -:10294000024BA36510BD00BF242F00208C3C000863 -:1029500070B50378012B054650D12A4B446D98423F -:102960001BD1294B5A6B42F080025A635A6D42F0D8 -:1029700080025A655A6D5A6942F080025A615A695A -:1029800022F080025A610E2143205B69FEF7D4FBDE -:102990001E4BE3601E4BC4F800380023C4F8003E11 -:1029A000C02323606E6D4FF40413A3633369002BBF -:1029B000FCDA012333610C20FFF7A4FA3369DB074B -:1029C000FCD41220FFF79EFA3369002BFCDA0026B4 -:1029D000A6602846FFF738FF6B68C4F81068DB680C -:1029E000C4F81468C4F81C684BB90A4BA3614FF0D3 -:1029F000FF336361A36843F00103A36070BD064B1E -:102A0000F4E700BF242F00200038024040140040AB -:102A100003002002003C30C0083C30C0F8B5446DD3 -:102A2000054600212046FFF779FFA96D00234FF0EE -:102A300001128F68C4F834384FF00066C4F81C28BF -:102A40004FF0FF3004EB431201339F42C2F800699C -:102A5000C2F8006BC2F80809C2F8080BF2D20B6882 -:102A60006A6DEB65636210231361166916F0100638 -:102A7000FBD11220FFF746FAD4F8003823F4FE63A6 -:102A8000C4F80038A36943F4402343F01003A36162 -:102A90000923C4F81038C4F814380A4BEB604FF01F -:102AA000C043C4F8103B084BC4F8003BC4F810699D -:102AB000C4F80039EB6D03F1100243F48013EA65AA -:102AC000A362F8BD683C000840800010426D90F899 -:102AD0004E10D2F8003823F4FE6343EA0113C2F823 -:102AE000003870472DE9F84300EB8103456DDA6843 -:102AF000166806F00306731E022B05EB41130C4605 -:102B000080460FFA81F94FEA41104FF00001C3F8F7 -:102B1000101B4FF0010104F1100398BFB60401FA35 -:102B200003F391698EBF334E06F1805606F50046D9 -:102B300000293AD0578A04F15801490137436F50B0 -:102B4000D5F81C180B43C5F81C382B180021C3F806 -:102B5000101953690127611EA7409BB3138A928BFA -:102B60009B08012A88BF5343D8F85C20981842EA92 -:102B7000034301F1400205EB8202C8F85C002146E4 -:102B800053602846FFF7CAFE08EB8900C3681B8A1A -:102B900043EA8453483464011E432E51D5F81C384F -:102BA0001F43C5F81C78BDE8F88305EB4917D7F833 -:102BB000001B21F40041C7F8001BD5F81C1821EABE -:102BC0000303C0E704F13F0305EB83030A4A5A609D -:102BD00028462146FFF7A2FE05EB4910D0F8003940 -:102BE00023F40043C0F80039D5F81C3823EA07075E -:102BF000D7E700BF0080001000040002826D126859 -:102C0000C265FFF721BE00005831436D49015B5892 -:102C100013F4004004D013F4001F0CBF0220012065 -:102C2000704700004831436D49015B5813F4004080 -:102C300004D013F4001F0CBF0220012070470000D5 -:102C400000EB8101CB68196A0B6813604B68536015 -:102C50007047000000EB810330B5DD68AA69136896 -:102C6000D36019B9402B84BF402313606B8A14686A -:102C7000426D1C44013CB4FBF3F46343033323F083 -:102C8000030302EB411043EAC44343F0C043C0F8DE -:102C9000103B2B6803F00303012B09B20ED1D2F8CD -:102CA000083802EB411013F4807FD0F8003B14BFCA -:102CB00043F0805343F00053C0F8003B02EB411255 -:102CC000D2F8003B43F00443C2F8003B30BD0000A3 -:102CD0002DE9F041244D6E6D06EB40130446D3F808 -:102CE000087BC3F8087B38070AD5D6F814381907CB -:102CF00006D505EB84032146DB6828465B689847C8 -:102D0000FA071FD5D6F81438DB071BD505EB84036B -:102D1000D968CCB98B69488A5A68B2FBF0F600FBD7 -:102D200016228AB91868DA6890420DD2121AC3E9DD -:102D30000024202383F311880B482146FFF78AFFE4 -:102D400084F31188BDE8F081012303FA04F26B8952 -:102D500023EA02036B81CB68002BF3D021460248A3 -:102D6000BDE8F041184700BF242F002000EB81038D -:102D700070B5DD68436D6C692668E6604A0156BB34 -:102D80001A444FF40020C2F810092A6802F0030226 -:102D9000012A0AB20ED1D3F8080803EB421410F44A -:102DA000807FD4F8000914BF40F0805040F00050FC -:102DB000C4F8000903EB4212D2F8000940F00440C5 -:102DC000C2F80009D3F83408012202FA01F10143E4 -:102DD000C3F8341870BD19B9402E84BF402020605C -:102DE00020682E8A8419013CB4FBF6F440EAC44002 -:102DF00040F000501A44C6E7F8B504461E48456D39 -:102E000005EB4413D3F80869C3F80869F10717D52F -:102E1000D5F81038DA0713D500EB8403D9684B696D -:102E20001F68DA68974218D2D21B00271A605F60C9 -:102E3000202383F311882146FFF798FF87F3118839 -:102E4000330617D5D5F834280123A340134211D0F7 -:102E50002046BDE8F840FFF723BD012303FA04F242 -:102E6000038923EA020303818B68002BE8D0214603 -:102E70009847E5E7F8BD00BF242F00202DE9F74F64 -:102E8000984C666D7569B3691D4015F4805875617D -:102E900007D02046FEF744FD03B0BDE8F04FFFF732 -:102EA00085BC002D12DAD6F8003E8E489F071EBF63 -:102EB000D6F8003E23F00303C6F8003ED6F80438E7 -:102EC00023F00103C6F80438FEF752FD280505D5A6 -:102ED0008448FFF7B9FC8348FEF73AFDA9040CD5F6 -:102EE000D6F8083813F0060FF36823F470530CBFBC -:102EF00043F4105343F4A053F3602A0704D56368E6 -:102F0000DB680BB177489847EB0274D4AF0227D542 -:102F1000D4F85490DFF8CCB100274FF0010A09EB48 -:102F20004712D2F8003B03F44023B3F5802F11D1B0 -:102F3000D2F8003B002B0DDA62890AFA07F322EA85 -:102F40000303638104EB8703DB68DB6813B1394655 -:102F500058469847A36D01379B68FFB29F42DED960 -:102F6000E80617D5676D3A6AC2F30A1002F00F033C -:102F700002F4F012B2F5802F00F08880B2F5402FF5 -:102F800008D104EB83030022DB681B6A07F5805736 -:102F900090426DD12903D6F8184813D5E20302D523 -:102FA0000020FFF795FEA30302D50120FFF790FE56 -:102FB000670302D50220FFF78BFE260302D503200C -:102FC000FFF786FE6D037FF567AFE00702D50020AF -:102FD000FFF712FFA10702D50120FFF70DFF6207DF -:102FE00002D50220FFF708FF23077FF555AF032026 -:102FF000FFF702FF50E7636DDFF8E8B001930027A9 -:103000004FF0010AA36D9B685FFA87F999453FF677 -:103010007DAF019B03EB4913D3F8002902F4402252 -:10302000B2F5802F22D1D3F80029002A1EDAD3F876 -:10303000002942F09042C3F80029D3F80029002A61 -:10304000FBDB606D4946FFF769FC22890AFA09F348 -:1030500022EA0303238104EB8903DB689B6813B135 -:103060004946584698474846FFF71AFC0137C9E7D2 -:10307000910708BFD7F80080072A98BF03F8018B93 -:1030800002F1010298BF4FEA182881E7023304EBEE -:10309000830207F580575268D2F818C0DCF8082080 -:1030A000DCE9001CA1EB0C0C002188420AD104EBE6 -:1030B000830463689B699A6802449A605A68024470 -:1030C0005A6067E711F0030F08BFD7F800808C45FE -:1030D00088BF02F8018B01F1010188BF4FEA18286F -:1030E000E3E700BF242F0020436D03EB4111D1F82B -:1030F000003B43F40013C1F8003B7047436D03EB02 -:103100004111D1F8003943F40013C1F80039704778 -:10311000436D03EB4111D1F8003B23F40013C1F8D8 -:10312000003B7047436D03EB4111D1F8003923F4A4 -:103130000013C1F80039704730B5039C01720433A5 -:1031400004FB0325C0E90653049B03630021059B90 -:10315000C160C0E90000C0E90422C0E90842C0E93A -:103160000A11436330BD0000416A0022C0E9041126 -:10317000C0E90A22C2606FF00101FEF733BF000010 -:10318000D0E90432934201D1C2680AB9181D7047D0 -:103190000020704703691960C2680132C260C269C9 -:1031A000134482690361934224BF436A036100218F -:1031B000FEF70CBF38B504460D46E3683BB16269C3 -:1031C000131D1268A3621344E362002007E0237A10 -:1031D00033B929462046FEF7E9FE0028EDDA38BD6E -:1031E0006FF00100FBE70000C368C269013BC360E8 -:1031F0004369134482694361934224BF436A436134 -:1032000000238362036B03B11847704770B5202316 -:10321000044683F31188866A3EB9FFF7CBFF054663 -:1032200018B186F31188284670BDA36AE26A13F8C4 -:10323000015BA362934202D32046FFF7D5FF002330 -:1032400083F31188EFE700002DE9F84F04460E469E -:10325000174698464FF0200989F311880025AA46A1 -:10326000D4F828B0BBF1000F09D141462046FFF742 -:10327000A1FF20B18BF311882846BDE8F88FD4E96F -:103280000A12A7EB050B521A934528BF9346BBF1D0 -:10329000400F1BD9334601F1400251F8040B43F8AB -:1032A000040B9142F9D1A36A40334036A362403502 -:1032B000D4E90A239A4202D32046FFF795FF8AF306 -:1032C0001188BD42D8D289F31188C9E730465A46E1 -:1032D000FDF7FEFCA36A5B445E44A3625D44E7E73E -:1032E00010B5029C0172043304FB0321C0E90613EC -:1032F0000023C0E90A33039B0363049BC460C0E955 -:103300000000C0E90422C0E90842436310BD000088 -:10331000026AC260426AC0E904220022C0E90A22AD -:103320006FF00101FEF75EBED0E904239A4201D19D -:10333000C26822B9184650F8043B0B607047002061 -:1033400070470000C368C2690133C3604369134416 -:1033500082694361934224BF436A43610021FEF7BF -:1033600035BE000038B504460D46E3683BB123691D -:103370001A1DA262E2691344E362002007E0237A87 -:1033800033B929462046FEF711FE0028EDDA38BD94 -:103390006FF00100FBE7000003691960C268013AA1 -:1033A000C260C269134482690361934224BF436AC5 -:1033B000036100238362036B03B118477047000069 -:1033C00070B520230D460446114683F31188866AA2 -:1033D0002EB9FFF7C7FF10B186F3118870BDA36A3D -:1033E0001D70A36AE26A01339342A36204D3E169C8 -:1033F00020460439FFF7D0FF002080F31188EDE765 -:103400002DE9F84F04460D46904699464FF0200AA4 -:103410008AF311880026B346A76A4FB94946204669 -:10342000FFF7A0FF20B187F311883046BDE8F88F81 -:10343000D4E90A073A1AA8EB0607974228BF1746AD -:10344000402F1BD905F1400355F8042B40F8042BFD -:103450009D42F9D1A36A4033A3624036D4E90A23DE -:103460009A4204D3E16920460439FFF795FF8BF3B4 -:1034700011884645D9D28AF31188CDE729463A46C4 -:10348000FDF726FCA36A3B443D44A3623E44E5E7C6 -:10349000D0E904239A4217D1C3689BB1836A8BB1E8 -:1034A000043B9B1A0ED01360C368013BC360C36921 -:1034B0001A44836902619A4224BF436A036100236C -:1034C00083620123184670470023FBE700F088B8A9 -:1034D0004FF08043002258631A610222DA6070477D -:1034E0004FF080430022DA60704700004FF08043C5 -:1034F000586370474FF08043586A70474B68436089 -:103500008B688360CB68C3600B6943614B6903625E -:103510008B6943620B6803607047000008B5264B57 -:1035200026481A6940F2FF110A431A611A6922F407 -:10353000FF7222F001021A611A691A6B0A431A63B8 -:103540001A6D0A431A651E4A1B6D1146FFF7D6FF16 -:1035500002F11C0100F58060FFF7D0FF02F1380195 -:1035600000F58060FFF7CAFF02F1540100F58060AA -:10357000FFF7C4FF02F1700100F58060FFF7BEFFA6 -:1035800002F18C0100F58060FFF7B8FF02F1A8019D -:1035900000F58060FFF7B2FF02F1C40100F5806022 -:1035A000FFF7ACFF02F1E00100F58060FFF7A6FF36 -:1035B000BDE8084000F09AB8003802400000024020 -:1035C000983C000808B500F007FAFEF779FCFFF711 -:1035D000A5F8BDE80840FEF781BE00007047000076 -:1035E000104B1A6C42F001021A641A6E42F001028A -:1035F0001A660D4A1B6E936843F0010393604FF007 -:10360000804353229A624FF0FF32DA6200229A61BD -:103610005A63DA605A6001225A6108211A601C203C -:10362000FDF78ABD00380240002004E04FF08042E0 -:1036300008B51169D3680B40D9B2C9439B07116122 -:1036400007D5202383F31188FEF75AFC002383F368 -:10365000118808BD08B5FFF7E9FFBDE80840FFF78E -:10366000A5B800001F4B1A696FEAC2526FEAD25226 -:103670001A611A69C2F308021A614FF0FF301A6921 -:103680005A69586100215A6959615A691A6A62F087 -:1036900080521A621A6A02F080521A621A6A5A6AD0 -:1036A00058625A6A59625A6A1A6C42F080521A6415 -:1036B0001A6E42F080521A661A6E0B4A106840F475 -:1036C00080701060186F00F44070B0F5007F1EBF6E -:1036D0004FF4803018671967536823F40073536000 -:1036E00000F05AB90038024000700040334B4FF0F0 -:1036F00080521A64324A4FF4404111601A6842F015 -:1037000001021A601A689107FCD59A6822F0030238 -:103710009A602A4B9A6812F00C02FBD1196801F0EA -:10372000F90119609A601A6842F480321A601A68C6 -:103730009203FCD55A6F42F001025A671F4B5A6F31 -:103740009007FCD51F4A5A601A6842F080721A60CE -:103750001B4A53685904FCD5184B1A689201FCD5D2 -:10376000194A9A60194B1A68194B9A42194B21D180 -:10377000194A1168194A91421CD140F205121A6087 -:10378000144A136803F00F03052BFAD10B4B9A6808 -:1037900042F002029A609A6802F00C02082AFAD1FA -:1037A0005A6C42F480425A645A6E42F480425A661D -:1037B0005B6E704740F20572E1E700BF00380240DF -:1037C000007000400854400700948838002004E04E -:1037D00011640020003C024000ED00E041C20F41B6 -:1037E000084A08B5516913680B4003F0010353619F -:1037F00023B1054A13680BB150689847BDE80840EB -:10380000FEF7D4BF003C01409C2F0020084A08B5B9 -:10381000516913680B4003F00203536123B1054A59 -:1038200093680BB1D0689847BDE80840FEF7BEBF6B -:10383000003C01409C2F0020084A08B551691368DC -:103840000B4003F00403536123B1054A13690BB124 -:1038500050699847BDE80840FEF7A8BF003C01400A -:103860009C2F0020084A08B5516913680B4003F0EB -:103870000803536123B1054A93690BB1D069984796 -:10388000BDE80840FEF792BF003C01409C2F00209D -:10389000084A08B5516913680B4003F010035361DF -:1038A00023B1054A136A0BB1506A9847BDE8084036 -:1038B000FEF77CBF003C01409C2F0020174B10B549 -:1038C0005A691C68144004F478725A61A30604D53E -:1038D000134A936A0BB1D06A9847600604D5104A20 -:1038E000136B0BB1506B9847210604D50C4A936BB0 -:1038F0000BB1D06B9847E20504D5094A136C0BB1A4 -:10390000506C9847A30504D5054A936C0BB1D06C55 -:103910009847BDE81040FEF749BF00BF003C01409A -:103920009C2F00201A4B10B55A691C68144004F4EF -:103930007C425A61620504D5164A136D0BB1506D75 -:103940009847230504D5134A936D0BB1D06D984762 -:10395000E00404D50F4A136E0BB1506E9847A104D2 -:1039600004D50C4A936E0BB1D06E9847620404D50F -:10397000084A136F0BB1506F9847230404D5054ACA -:10398000936F0BB1D06F9847BDE81040FEF70EBFA4 -:10399000003C01409C2F0020062108B50846FDF799 -:1039A000CBFB06210720FDF7C7FB06210820FDF70A -:1039B000C3FB06210920FDF7BFFB06210A20FDF706 -:1039C000BBFB06211720FDF7B7FBBDE80840062129 -:1039D0002820FDF7B1BB000008B5FFF743FE00F05B -:1039E0000DF8FDF74DFDFDF733FFFDF70BFEFFF77B -:1039F000F5FDBDE80840FFF769BD00000023054A5A -:103A000019460133102BC2E9001102F10802F8D166 -:103A1000704700BF9C2F0020034611F8012B03F8CC -:103A2000012B002AF9D1704753544D3332463F3FA2 -:103A30003F00000053544D33324634307800535425 -:103A40004D3332463432780053544D333246343499 -:103A50003658580000000000283A00083F000000D7 -:103A600013040000343A00083F000000190400006D -:103A70003E3A00083F00000021040000483A0008D8 -:103A80003F000000C8270020A82300200096000067 -:103A90000000000000000000000000000000000026 -:103AA00000000000491400083514000871140008D3 -:103AB0005D1400086914000855140008411400083A -:103AC0002D1400087D140008000000008115000876 -:103AD0006D150008A915000895150008A115000826 -:103AE0008D1500087915000865150008B515000842 -:103AF0000000000001000000000000006D61696E20 -:103B00000000000069646C6500000000043B0008D0 -:103B100050260020C827002001000000BD1E00081C -:103B2000000000004172647550696C6F740025429A -:103B30004F415244252D424C002553455249414C9A -:103B40002500000002000000000000009D17000892 -:103B50000918000840004000602C0020702C002054 -:103B60000200000000000000030000000000000050 -:103B70004D1800080000000010000000802C0020FC -:103B8000000000000100000000000000242F0020C1 -:103B9000010102007922000889210008252200087D -:103BA0000922000843000000AC3B00080902430062 -:103BB000020100C0320904000001020201000524D4 -:103BC000001001052401000104240202052406005E -:103BD00001070582030800FF09040100020A000032 -:103BE00000070501024000000705810240000000B7 -:103BF00012000000F83B0008120110010200004012 -:103C000009124157000201020301000004030904E4 -:103C100025424F41524425004D6174656B46343056 -:103C2000352D54450030313233343536373839414B -:103C300042434445460000000040000000400000B0 -:103C400000400000004000000000010000000200F1 -:103C5000000002000000020000000200000002005C -:103C600000000200000002000000000085190008AA -:103C70003D1C0008E91C000840004000842F002083 -:103C8000842F002001000000942F002080000000FD -:103C900040010000030000000000A8160000000022 -:103CA000AAAAAAAA00001400FF9F000000000000BA -:103CB00070A70A000000000100000000AAAAAAAA3A -:103CC00000000001FFFF00000000000000000000F5 -:103CD0000400001400000000AAAAAAAA040000140C -:103CE000FFFF0000000000000000000000000000D6 -:103CF00000000000AAAAAAAA00000000FFFF00001E -:103D000000000000000000000000000000000000B3 -:103D1000AAAAAAAA00000000FFFF000000000000FD -:103D2000000000000000000000000000AAAAAAAAEB -:103D300000000000FFFF0000000000000000000085 -:103D40000000000000000000AAAAAAAA00000000CB -:103D5000FFFF000000000000000000000000000065 -:103D6000000000000A000000000000000300000046 -:103D70000000000000000000000000000000000043 -:103D80000000000000000000000000000000000033 -:103D900000000000000000001E0400000000000001 -:103DA00000000F0000000000FF0096000000000867 -:103DB0000096000000000800040000000C3C000811 -:103DC00000000000000000000000000000000000F3 -:083DD0000000000000000000EB +:101EB000FEF72CBA1026002008B5FFF7DDFF18B199 +:101EC000BDE80840FFF7E4BF08BD0000FFF7E0BF32 +:101ED000FEE7000010B50C4CFFF742FF00F0B4F82D +:101EE0000A498022204600F03BF8012344F8180CF0 +:101EF000037400F071FC002383F3118862B6044878 +:101F0000BDE8104000F04CB838260020703B0008B7 +:101F1000803B000800F01CB9EFF3118020B9EFF30B +:101F20000583202282F311887047000010B530B974 +:101F3000EFF30584C4F3080414B180F3118810BDD5 +:101F4000FFF7BAFF84F31188F9E70000034A5168EC +:101F500053685B1A9842FBD8704700BF001000E03E +:101F600082600222028270478368A3F17C0243F8F8 +:101F70000C2C026943F83C2C426943F8382C074A80 +:101F800043F81C2CC26843F8102C022203F8082CDA +:101F9000002203F8072CA3F118007047250300085E +:101FA00010B5202383F31188FFF7DEFF00210446DC +:101FB000FFF746FF002383F31188204610BD000081 +:101FC000024B1B6958610F20FFF70EBF102600203F +:101FD000202383F31188FFF7F3BF000008B5014603 +:101FE000202383F311880820FFF70CFF002383F3DD +:101FF000118808BD49B1064B42681B6918605A60D8 +:10200000136043600420FFF7FDBE4FF0FF307047C0 +:10201000102600200368984206D01A6802605060BB +:1020200059611846FFF7A4BE7047000038B5044652 +:102030000D462068844200D138BD036823605C608F +:102040004561FFF795FEF4E7054B03F11402C3E980 +:1020500005224FF0FF310022C3E90712704700BF8D +:102060001026002070B51C4EC0E9032305460C461F +:1020700001F07AFA334653F8142F9A420DD13062A8 +:10208000C5E901242A600A2C2CBF00190A30C6E9D0 +:102090000555BDE8704001F055BA316A431AE3189E +:1020A00038BF1C469368A34202D9081901F058FAB8 +:1020B00073699A6894420CD85A68AC602B606A6065 +:1020C00015609A685D60121B9A604FF0FF33F361F0 +:1020D00070BD1B68A41AECE71026002038B51B4C15 +:1020E000636998420DD0D0E9003213605A60002233 +:1020F0008168C2609A680A449A604FF0FF33E361D6 +:1021000038BD2246036842F8143F002193425A60CA +:10211000C16003D1BDE8384001F01CBA9A688168FB +:10212000256A0A449A6001F01FFA63699A68411BA4 +:102130008A42E5D9AB181D1A092D206A98BF01F112 +:102140000A02BDE83840104401F00ABA1026002007 +:102150002DE9F041184C002704F11406656901F0DF +:1021600003FA236AAA68C11A8A4215D81344236263 +:10217000D5E9003213605A606369D5F80C80EF60CE +:10218000B34201D101F0E6F987F311882869C0470D +:10219000202383F31188E1E76169B14209D0134438 +:1021A0001B1ABDE8F0410A2B2CBFC0180A3001F001 +:1021B000D7B9BDE8F08100BF10260020002070478D +:1021C000FEE70000704700004FF0FF30704700004E +:1021D00002290CD0032904D00129074818BF002088 +:1021E0007047032A05D8054800EBC2007047044831 +:1021F00070470020704700BF643C00082022002088 +:10220000183C000870B59AB00546084601A9144666 +:1022100000F0C2F801A8FEF779FD431C5B00C5E998 +:1022200000340022237003236370C6B201AB023472 +:102230001046D1B28E4204F1020401D81AB070BD2A +:1022400013F8011B04F8021C04F8010C0132F0E73A +:1022500008B5202383F311880348FFF779FA002398 +:1022600083F3118808BD00BFC827002090F84430D0 +:1022700003F01F02012A07D190F845200B2A03D151 +:102280000023C0E90E3315E003F06003202B08D1D2 +:10229000B0F848302BB990F84520212A03D81F2ADE +:1022A00004D8FFF737BA222AEBD0FAE7034A826351 +:1022B0000722C26303640120704700BF1822002078 +:1022C00007B5052917D8DFE801F0191603191920F9 +:1022D000202383F31188104A01900121FFF7D8FAD7 +:1022E00001980E4A0221FFF7D3FA0D48FFF7FCF9D7 +:1022F000002383F3118803B05DF804FB202383F3EC +:1023000011880748FFF7C6F9F2E7202383F3118805 +:102310000348FFF7DDF9EBE7B83B0008DC3B0008BA +:10232000C827002038B50C4D0C4C0D492A4604F145 +:102330000800FFF767FF05F1CA0204F11000094920 +:10234000FFF760FF05F5CA7204F118000649BDE801 +:102350003840FFF757BF00BF902C002020220020FC +:10236000983B0008A23B0008AD3B000870B504464E +:1023700008460D46FEF7CAFCC6B220460134037873 +:102380000BB9184670BD32462946FEF7ABFC002853 +:10239000F3D10120F6E700002DE9F84F05460C4681 +:1023A000FEF7B4FC2B49C6B22846FFF7DFFF08B1A1 +:1023B0000536F6B228492846FFF7D8FF08B110368F +:1023C000F6B2632E0DD8DFF88C80DFF88C90234FA7 +:1023D000DFF890A0DFF890B02E7846B92670BDE8FF +:1023E000F88F29462046BDE8F84F01F04FBB252E57 +:1023F0002BD1072241462846FEF774FC58B9DBF87A +:1024000000302360DBF804306360DBF80830A36041 +:1024100007350C34E0E7082249462846FEF762FCFF +:1024200098B90F4BA21C197809090232C95D02F84C +:10243000041C13F8011B01F00F015345C95D02F89C +:10244000031CF0D118340835C6E704F8016B0135D8 +:10245000C2E700BF843C0008AD3B0008993C00087F +:10246000107AFF1F1C7AFF1F8C3C0008BFF34F8FB0 +:10247000024AD368DB03FCD4704700BF003C024033 +:1024800008B5094B1B7873B9FFF7F0FF074B1A69C2 +:10249000002ABFBF064A5A6002F188325A601A68A1 +:1024A00022F480621A6008BDEE2E0020003C02403B +:1024B0002301674508B50B4B1B7893B9FFF7D6FF8F +:1024C000094B1A6942F000421A611A6842F48052BC +:1024D0001A601A6822F480521A601A6842F4806204 +:1024E0001A6008BDEE2E0020003C02400B28F0B51B +:1024F00016D80C4C0C4923787BB90C4D0E460C2396 +:102500004FF0006255F8047B46F8042B013B13F0B2 +:10251000FF033A44F6D10123237051F82000F0BDA7 +:102520000020FCE7202F0020F02E0020AC3C00080B +:10253000014B53F820007047AC3C00080C2070475A +:102540000B2810B5044601D9002010BDFFF7CEFFBF +:10255000064B53F824301844C21A0BB90120F4E793 +:1025600012680132F0D1043BF6E700BFAC3C000832 +:102570000B2838B5044628D8FFF7CEFCFFF776FFC6 +:10258000FFF77EFF124AF323D360E300DBB243F48C +:10259000007343F002031361136943F48033136142 +:1025A00005462046FFF762FFFFF7A0FF094B53F8EF +:1025B000241000F0E9F82846FFF77CFFFFF7B6FC8F +:1025C0002046BDE83840FFF7BBBF002038BD00BF44 +:1025D000003C0240AC3C000812F001032DE9F04140 +:1025E00005460E4614464BD18218B2F1016F61D8F0 +:1025F000314B1B6813F001035CD0304FFFF78CFCAC +:10260000FFF73EFFF323FB60FFF730FF314640F258 +:102610000128032C18D824F00104284E0C446D1A0C +:1026200040F20118A142336905EB01072AD123F0DA +:1026300001033361FFF73EFFFFF778FC0120BDE89F +:10264000F081043C0435E4E7AB07E4D13B6923F4B3 +:1026500040733B613B6943EA08033B6151F8046BFB +:102660002E60BFF34F8FFFF701FF2B689E42E8D02B +:102670003B6923F001033B61FFF71CFFFFF756FCAA +:102680000020DCE723F440733361336943EA080335 +:1026900033610B883B80BFF34F8FFFF7E7FE3F8826 +:1026A00031F8023BBFB2BB42BCD0336923F0010317 +:1026B0003361E1E71846C2E700380240003C0240BF +:1026C000084908B50B7828B11BB9FFF7D9FE0123DB +:1026D0000B7008BD002BFCD0BDE808400870FFF768 +:1026E000E9BE00BFEE2E002010B50244064BD2B268 +:1026F000904200D110BD441C00B253F8200041F8B4 +:10270000040BE0B2F4E700BF502800400F4B30B597 +:102710001C6F240407D41C6F44F400741C671C6FE6 +:1027200044F400441C670A4C236843F4807323601C +:102730000244084BD2B2904200D130BD441C00B2DA +:1027400051F8045B43F82050E0B2F4E7003802404F +:10275000007000405028004007B5012201A9002068 +:10276000FFF7C2FF019803B05DF804FB13B5044600 +:10277000FFF7F2FFA04205D0012201A90020019439 +:10278000FFF7C4FF02B010BD70470000034B1A688A +:102790001AB9034AD2F874281A607047242F00200F +:1027A0000030024008B5FFF7F1FF024B1868C0F394 +:1027B000407008BD242F0020EFF3098305494A6BC0 +:1027C00022F001024A63683383F30988002383F30C +:1027D0001188704700EF00E0202080F3118862B676 +:1027E0000C4B0D4AD96821F4E0610904090C0A4335 +:1027F000DA60D3F8FC20094942F08072C3F8FC206B +:102800000A6842F001020A601022DA7783F8220097 +:10281000704700BF00ED00E00003FA05001000E083 +:1028200010B5202383F311880E4B5B6813F400630B +:1028300014D0F1EE103AEFF30984683C4FF0807346 +:10284000E361094BDB6B236684F30988FFF714FB14 +:1028500010B1064BA36110BD054BFBE783F3118854 +:10286000F9E700BF00ED00E000EF00E037030008EB +:102870003A03000870470000FEE700000A4B0B48CF +:102880000B4A90420BD30B4BDA1C121AC11E22F0DA +:1028900003028B4238BF00220021FEF73FBA53F8F3 +:1028A000041B40F8041BECE7483E000820300020E1 +:1028B00020300020203000207047000070B5D0E9A3 +:1028C00015439E6800224FF0FF3504EB421351017F +:1028D000D3F800090028BEBFD3F8000940F08040BB +:1028E000C3F80009D3F8000B0028BEBFD3F8000BD3 +:1028F00040F08040C3F8000B013263189642C3F8E1 +:102900000859C3F8085BE0D24FF00113C4F81C3833 +:1029100070BD00001D4B03EB80022DE9F043D2F89F +:102920000CC05D6DDCF81420461CD2F800E005EB0D +:10293000063605EB4018516871450AD3D5F834388E +:10294000012202FA00F023EA0000C5F83408BDE8CD +:10295000F083BCF81040AEEB0103A34228BF23462E +:10296000D8F81849A4B2B3EB840FF0D89468A4F156 +:10297000040959F8047F3760A4EB09071F44042FAA +:10298000F7D81C440B4494605360D4E7282F0020F0 +:10299000890141F02001016103699B06FCD41220EA +:1029A000FFF7D4BA10B5054C2046FEF753FF4FF0A1 +:1029B000A0436365024BA36510BD00BF282F002014 +:1029C000003D000870B50378012B054650D12A4B15 +:1029D000446D98421BD1294B5A6B42F080025A63D6 +:1029E0005A6D42F080025A655A6D5A6942F080026F +:1029F0005A615A6922F080025A610E2143205B69B4 +:102A0000FEF79AFB1E4BE3601E4BC4F80038002310 +:102A1000C4F8003EC02323606E6D4FF40413A3631B +:102A20003369002BFCDA012333610C20FFF78EFAA7 +:102A30003369DB07FCD41220FFF788FA3369002BD7 +:102A4000FCDA0026A6602846FFF738FF6B68C4F85A +:102A50001068DB68C4F81468C4F81C684BB90A4BEA +:102A6000A3614FF0FF336361A36843F00103A360E8 +:102A700070BD064BF4E700BF282F0020003802404D +:102A80004014004003002002003C30C0083C30C02D +:102A9000F8B5446D054600212046FFF779FFA96D82 +:102AA00000234FF001128F68C4F834384FF00066ED +:102AB000C4F81C284FF0FF3004EB431201339F424F +:102AC000C2F80069C2F8006BC2F80809C2F8080B26 +:102AD000F2D20B686A6DEB656362102313611669AD +:102AE00016F01006FBD11220FFF730FAD4F80038A8 +:102AF00023F4FE63C4F80038A36943F4402343F091 +:102B00001003A3610923C4F81038C4F814380A4B21 +:102B1000EB604FF0C043C4F8103B084BC4F8003BD7 +:102B2000C4F81069C4F80039EB6D03F1100243F4E6 +:102B30008013EA65A362F8BDDC3C00084080001009 +:102B4000426D90F84E10D2F8003823F4FE6343EA49 +:102B50000113C2F8003870472DE9F84300EB8103F8 +:102B6000456DDA68166806F00306731E022B05EB46 +:102B700041130C4680460FFA81F94FEA41104FF09D +:102B80000001C3F8101B4FF0010104F1100398BFBE +:102B9000B60401FA03F391698EBF334E06F18056F5 +:102BA00006F5004600293AD0578A04F15801490138 +:102BB00037436F50D5F81C180B43C5F81C382B1839 +:102BC0000021C3F8101953690127611EA7409BB368 +:102BD000138A928B9B08012A88BF5343D8F85C2044 +:102BE000981842EA034301F1400205EB8202C8F85B +:102BF0005C00214653602846FFF7CAFE08EB8900B7 +:102C0000C3681B8A43EA8453483464011E432E512F +:102C1000D5F81C381F43C5F81C78BDE8F88305EBD0 +:102C20004917D7F8001B21F40041C7F8001BD5F85D +:102C30001C1821EA0303C0E704F13F0305EB8303FB +:102C40000A4A5A6028462146FFF7A2FE05EB4910C2 +:102C5000D0F8003923F40043C0F80039D5F81C3807 +:102C600023EA0707D7E700BF008000100004000236 +:102C7000826D1268C265FFF721BE00005831436DB6 +:102C800049015B5813F4004004D013F4001F0CBF3B +:102C900002200120704700004831436D49015B5814 +:102CA00013F4004004D013F4001F0CBF02200120D5 +:102CB0007047000000EB8101CB68196A0B68136054 +:102CC0004B6853607047000000EB810330B5DD684E +:102CD000AA691368D36019B9402B84BF40231360DD +:102CE0006B8A1468426D1C44013CB4FBF3F46343EB +:102CF000033323F0030302EB411043EAC44343F0E0 +:102D0000C043C0F8103B2B6803F00303012B09B24A +:102D10000ED1D2F8083802EB411013F4807FD0F8BE +:102D2000003B14BF43F0805343F00053C0F8003B16 +:102D300002EB4112D2F8003B43F00443C2F8003BDF +:102D400030BD00002DE9F041244D6E6D06EB4013BF +:102D50000446D3F8087BC3F8087B38070AD5D6F8B1 +:102D60001438190706D505EB84032146DB6828468D +:102D70005B689847FA071FD5D6F81438DB071BD5D0 +:102D800005EB8403D968CCB98B69488A5A68B2FBD1 +:102D9000F0F600FB16228AB91868DA6890420DD264 +:102DA000121AC3E90024202383F311880B4821461B +:102DB000FFF78AFF84F31188BDE8F081012303FA4D +:102DC00004F26B8923EA02036B81CB68002BF3D0FA +:102DD00021460248BDE8F041184700BF282F0020D7 +:102DE00000EB810370B5DD68436D6C692668E660B1 +:102DF0004A0156BB1A444FF40020C2F810092A6851 +:102E000002F00302012A0AB20ED1D3F8080803EB3C +:102E1000421410F4807FD4F8000914BF40F08050B1 +:102E200040F00050C4F8000903EB4212D2F8000948 +:102E300040F00440C2F80009D3F83408012202FA35 +:102E400001F10143C3F8341870BD19B9402E84BF95 +:102E50004020206020682E8A8419013CB4FBF6F4DF +:102E600040EAC44040F000501A44C6E7F8B50446B2 +:102E70001E48456D05EB4413D3F80869C3F808698B +:102E8000F10717D5D5F81038DA0713D500EB84030E +:102E9000D9684B691F68DA68974218D2D21B00279D +:102EA0001A605F60202383F311882146FFF798FFA3 +:102EB00087F31188330617D5D5F834280123A340AA +:102EC000134211D02046BDE8F840FFF723BD01238F +:102ED00003FA04F2038923EA020303818B68002BBF +:102EE000E8D021469847E5E7F8BD00BF282F00202D +:102EF0002DE9F74F984C666D7569B3691D4015F45F +:102F00008058756107D02046FEF70AFD03B0BDE882 +:102F1000F04FFFF785BC002D12DAD6F8003E8E4840 +:102F20009F071EBFD6F8003E23F00303C6F8003EFD +:102F3000D6F8043823F00103C6F80438FEF718FD6C +:102F4000280505D58448FFF7B9FC8348FEF700FD46 +:102F5000A9040CD5D6F8083813F0060FF36823F44B +:102F600070530CBF43F4105343F4A053F3602A078B +:102F700004D56368DB680BB177489847EB0274D4DB +:102F8000AF0227D5D4F85490DFF8CCB100274FF02A +:102F9000010A09EB4712D2F8003B03F44023B3F5D2 +:102FA000802F11D1D2F8003B002B0DDA62890AFA8A +:102FB00007F322EA0303638104EB8703DB68DB6822 +:102FC00013B1394658469847A36D01379B68FFB245 +:102FD0009F42DED9E80617D5676D3A6AC2F30A1038 +:102FE00002F00F0302F4F012B2F5802F00F0888097 +:102FF000B2F5402F08D104EB83030022DB681B6A83 +:1030000007F5805790426DD12903D6F8184813D59B +:10301000E20302D50020FFF795FEA30302D50120AD +:10302000FFF790FE670302D50220FFF78BFE260311 +:1030300002D50320FFF786FE6D037FF567AFE0073B +:1030400002D50020FFF712FFA10702D50120FFF7EC +:103050000DFF620702D50220FFF708FF23077FF567 +:1030600055AF0320FFF702FF50E7636DDFF8E8B0CC +:10307000019300274FF0010AA36D9B685FFA87F95F +:1030800099453FF67DAF019B03EB4913D3F8002927 +:1030900002F44022B2F5802F22D1D3F80029002A71 +:1030A0001EDAD3F8002942F09042C3F80029D3F881 +:1030B0000029002AFBDB606D4946FFF769FC228985 +:1030C0000AFA09F322EA0303238104EB8903DB688C +:1030D0009B6813B14946584698474846FFF71AFC83 +:1030E0000137C9E7910708BFD7F80080072A98BFC2 +:1030F00003F8018B02F1010298BF4FEA182881E71B +:10310000023304EB830207F580575268D2F818C0E7 +:10311000DCF80820DCE9001CA1EB0C0C0021884243 +:103120000AD104EB830463689B699A6802449A603D +:103130005A6802445A6067E711F0030F08BFD7F8D6 +:1031400000808C4588BF02F8018B01F1010188BF26 +:103150004FEA1828E3E700BF282F0020436D03EB58 +:103160004111D1F8003B43F40013C1F8003B704714 +:10317000436D03EB4111D1F8003943F40013C1F85A +:1031800000397047436D03EB4111D1F8003B23F444 +:103190000013C1F8003B7047436D03EB4111D1F8B8 +:1031A000003923F40013C1F80039704730B5039C8F +:1031B0000172043304FB0325C0E90653049B036337 +:1031C0000021059BC160C0E90000C0E90422C0E9FC +:1031D0000842C0E90A11436330BD0000416A002281 +:1031E000C0E90411C0E90A22C2606FF00101FEF7D4 +:1031F0001DBF0000D0E90432934201D1C2680AB970 +:10320000181D70470020704703691960C2680132B9 +:10321000C260C269134482690361934224BF436A56 +:1032200003610021FEF7F6BE38B504460D46E3689B +:103230003BB16269131D1268A3621344E36200206C +:1032400007E0237A33B929462046FEF7D3FE00284B +:10325000EDDA38BD6FF00100FBE70000C368C2691A +:10326000013BC3604369134482694361934224BFB5 +:10327000436A436100238362036B03B118477047BD +:1032800070B52023044683F31188866A3EB9FFF7A0 +:10329000CBFF054618B186F31188284670BDA36A96 +:1032A000E26A13F8015BA362934202D32046FFF760 +:1032B000D5FF002383F31188EFE700002DE9F84FD5 +:1032C00004460E46174698464FF0200989F31188A8 +:1032D0000025AA46D4F828B0BBF1000F09D1414619 +:1032E0002046FFF7A1FF20B18BF311882846BDE8E7 +:1032F000F88FD4E90A12A7EB050B521A934528BFA1 +:103300009346BBF1400F1BD9334601F1400251F8FF +:10331000040B43F8040B9142F9D1A36A40334036C1 +:10332000A3624035D4E90A239A4202D32046FFF72C +:1033300095FF8AF31188BD42D8D289F31188C9E775 +:1033400030465A46FDF7C4FCA36A5B445E44A36260 +:103350005D44E7E710B5029C0172043304FB0321CE +:10336000C0E906130023C0E90A33039B0363049BEF +:10337000C460C0E90000C0E90422C0E90842436318 +:1033800010BD0000026AC260426AC0E90422002245 +:10339000C0E90A226FF00101FEF748BED0E904231C +:1033A0009A4201D1C26822B9184650F8043B0B601A +:1033B0007047002070470000C368C2690133C360D2 +:1033C0004369134482694361934224BF436A436162 +:1033D0000021FEF71FBE000038B504460D46E36825 +:1033E0003BB123691A1DA262E2691344E362002023 +:1033F00007E0237A33B929462046FEF7FBFD002873 +:10340000EDDA38BD6FF00100FBE7000003691960D9 +:10341000C268013AC260C26913448269036193427F +:1034200024BF436A036100238362036B03B118471F +:103430007047000070B520230D460446114683F303 +:103440001188866A2EB9FFF7C7FF10B186F311887D +:1034500070BDA36A1D70A36AE26A01339342A3623E +:1034600004D3E16920460439FFF7D0FF002080F340 +:103470001188EDE72DE9F84F04460D469046994630 +:103480004FF0200A8AF311880026B346A76A4FB985 +:1034900049462046FFF7A0FF20B187F31188304648 +:1034A000BDE8F88FD4E90A073A1AA8EB0607974255 +:1034B00028BF1746402F1BD905F1400355F8042BB0 +:1034C00040F8042B9D42F9D1A36A4033A3624036F1 +:1034D000D4E90A239A4204D3E16920460439FFF76C +:1034E00095FF8BF311884645D9D28AF31188CDE731 +:1034F00029463A46FDF7ECFBA36A3B443D44A362F0 +:103500003E44E5E7D0E904239A4217D1C3689BB152 +:10351000836A8BB1043B9B1A0ED01360C368013BD6 +:10352000C360C3691A44836902619A4224BF436A33 +:103530000361002383620123184670470023FBE7E1 +:1035400000F088B84FF08043002258631A610222CD +:10355000DA6070474FF080430022DA607047000065 +:103560004FF08043586370474FF08043586A70476C +:103570004B6843608B688360CB68C3600B694361B1 +:103580004B6903628B6943620B68036070470000FC +:1035900008B5264B26481A6940F2FF110A431A6102 +:1035A0001A6922F4FF7222F001021A611A691A6B79 +:1035B0000A431A631A6D0A431A651E4A1B6D1146A7 +:1035C000FFF7D6FF02F11C0100F58060FFF7D0FF86 +:1035D00002F1380100F58060FFF7CAFF02F15401E3 +:1035E00000F58060FFF7C4FF02F1700100F5806014 +:1035F000FFF7BEFF02F18C0100F58060FFF7B8FF16 +:1036000002F1A80100F58060FFF7B2FF02F1C401EA +:1036100000F58060FFF7ACFF02F1E00100F580608B +:10362000FFF7A6FFBDE8084000F09AB80038024056 +:10363000000002400C3D000808B500F007FAFEF754 +:1036400049FCFFF7A3F8BDE80840FEF76BBE000099 +:1036500070470000104B1A6C42F001021A641A6E97 +:1036600042F001021A660D4A1B6E936843F0010393 +:1036700093604FF0804353229A624FF0FF32DA6238 +:1036800000229A615A63DA605A6001225A61082165 +:103690001A601C20FDF750BD00380240002004E0F5 +:1036A0004FF0804208B51169D3680B40D9B2C943C5 +:1036B0009B07116107D5202383F31188FEF72AFCAD +:1036C000002383F3118808BD08B5FFF7E9FFBDE8C3 +:1036D0000840FFF7A5B800001F4B1A696FEAC252F5 +:1036E0006FEAD2521A611A69C2F308021A614FF0E6 +:1036F000FF301A695A69586100215A6959615A693B +:103700001A6A62F080521A621A6A02F080521A62D1 +:103710001A6A5A6A58625A6A59625A6A1A6C42F0AC +:1037200080521A641A6E42F080521A661A6E0B4A60 +:10373000106840F480701060186F00F44070B0F5AD +:10374000007F1EBF4FF4803018671967536823F459 +:103750000073536000F05AB9003802400070004016 +:10376000334B4FF080521A64324A4FF4404111609B +:103770001A6842F001021A601A689107FCD59A682B +:1037800022F003029A602A4B9A6812F00C02FBD1D5 +:10379000196801F0F90119609A601A6842F48032E0 +:1037A0001A601A689203FCD55A6F42F001025A67F8 +:1037B0001F4B5A6F9007FCD51F4A5A601A6842F097 +:1037C00080721A601B4A53685904FCD5184B1A685A +:1037D0009201FCD5194A9A60194B1A68194B9A4202 +:1037E000194B21D1194A1168194A91421CD140F252 +:1037F00005121A60144A136803F00F03052BFAD15F +:103800000B4B9A6842F002029A609A6802F00C022E +:10381000082AFAD15A6C42F480425A645A6E42F431 +:1038200080425A665B6E704740F20572E1E700BF66 +:103830000038024000700040085440070094883867 +:10384000002004E011640020003C024000ED00E094 +:1038500041C20F41084A08B5516913680B4003F093 +:103860000103536123B1054A13680BB150689847AF +:10387000BDE80840FEF7D4BF003C0140A02F002067 +:10388000084A08B5516913680B4003F002035361FD +:1038900023B1054A93680BB1D0689847BDE808404A +:1038A000FEF7BEBF003C0140A02F0020084A08B52B +:1038B000516913680B4003F00403536123B1054AB7 +:1038C00013690BB150699847BDE80840FEF7A8BFDF +:1038D000003C0140A02F0020084A08B55169136838 +:1038E0000B4003F00803536123B1054A93690BB100 +:1038F000D0699847BDE80840FEF792BF003C014000 +:10390000A02F0020084A08B5516913680B4003F046 +:103910001003536123B1054A136A0BB1506A9847EB +:10392000BDE80840FEF77CBF003C0140A02F00200E +:10393000174B10B55A691C68144004F478725A6128 +:10394000A30604D5134A936A0BB1D06A9847600660 +:1039500004D5104A136B0BB1506B9847210604D560 +:103960000C4A936B0BB1D06B9847E20504D5094A1A +:10397000136C0BB1506C9847A30504D5054A936CA2 +:103980000BB1D06C9847BDE81040FEF749BF00BFAF +:10399000003C0140A02F00201A4B10B55A691C684A +:1039A000144004F47C425A61620504D5164A136D32 +:1039B0000BB1506D9847230504D5134A936D0BB195 +:1039C000D06D9847E00404D50F4A136E0BB1506ECA +:1039D0009847A10404D50C4A936E0BB1D06E98475A +:1039E000620404D5084A136F0BB1506F9847230443 +:1039F00004D5054A936F0BB1D06F9847BDE81040CE +:103A0000FEF70EBF003C0140A02F0020062108B5A4 +:103A10000846FDF791FB06210720FDF78DFB0621E7 +:103A20000820FDF789FB06210920FDF785FB06210B +:103A30000A20FDF781FB06211720FDF77DFBBDE87D +:103A4000084006212820FDF777BB000008B5FFF7E6 +:103A500043FE00F00DF8FDF713FDFDF7F9FEFDF74D +:103A6000D1FDFFF7F5FDBDE80840FFF769BD000097 +:103A70000023054A19460133102BC2E9001102F157 +:103A80000802F8D1704700BFA02F0020034611F8AC +:103A9000012B03F8012B002AF9D1704753544D3301 +:103AA00032463F3F3F00000053544D3332463430DE +:103AB000780053544D3332463432780053544D33EA +:103AC0003246343436585800000000009C3A000852 +:103AD0003F00000013040000A83A00083F00000067 +:103AE00019040000B23A00083F0000002104000061 +:103AF000BC3A00083F000000C8270020A82300208F +:103B0000009600000000000000000000000000001F +:103B100000000000000000004914000835140008EF +:103B2000711400085D140008691400085514000899 +:103B3000411400082D1400087D1400080000000046 +:103B4000811500086D150008A915000895150008D5 +:103B5000A11500088D1500087915000865150008E5 +:103B6000B515000800000000010000000000000082 +:103B70006D61696E0000000069646C650000000002 +:103B8000783B000850260020C827002001000000D4 +:103B9000D11E0008000000004172647550696C6F0E +:103BA000740025424F415244252D424C0025534577 +:103BB0005249414C250000000200000000000000B6 +:103BC0009D1700080918000840004000602C0020E4 +:103BD000702C002002000000000000000300000024 +:103BE000000000004D180008000000001000000058 +:103BF000802C0020000000000100000000000000F8 +:103C0000282F002001010200C1220008D121000854 +:103C10006D2200085122000843000000203C0008EB +:103C200009024300020100C032090400000102023F +:103C300001000524001001052401000104240202F2 +:103C40000524060001070582030800FF090401009E +:103C5000020A00000007050102400000070581027A +:103C600040000000120000006C3C0008120110012E +:103C70000200004009124157000201020301000046 +:103C80000403090425424F41524425004D617465E7 +:103C90006B463430352D54450030313233343536AF +:103CA0003738394142434445460000000040000097 +:103CB0000040000000400000004000000000010043 +:103CC00000000200000002000000020000000200EC +:103CD00000000200000002000000020000000000DE +:103CE000851900083D1C0008E91C00084000400040 +:103CF000882F0020882F002001000000982F00202E +:103D00008000000040010000030000000001A81630 +:103D100000000000AAAAAAAA00001400EF9F000059 +:103D20000000000070A70A0000040001000000006D +:103D3000AAAAAAAA00000001DFFF000000000000FC +:103D4000000000000400001400000000AAAAAAAAB3 +:103D500004000014FFFF000000000000000000004D +:103D60000000000000000000AAAAAAAA00000000AB +:103D7000FFFF000000000000000000000000000045 +:103D800000000000AAAAAAAA00000000FFFF00008D +:103D90000000000000000000000000000000000023 +:103DA000AAAAAAAA00000000FFFF0000000000006D +:103DB000000000000000000000000000AAAAAAAA5B +:103DC00000000000FFFF00000000000000000000F5 +:103DD00000000000000000000A00000000000000D9 +:103DE00003000000000000000000000000000000D0 +:103DF00000000000000000000000000000000000C3 +:103E000000000000000000001E0400000000000090 +:103E100000000F0000000000FF00960000000008F6 +:103E2000009600000000080004000000803C00082C +:103E30000000000000000000000000000000000082 +:083E400000000000000000007A :00000001FF diff --git a/Tools/bootloaders/MatekF405-Wing-bdshot_bl.bin b/Tools/bootloaders/MatekF405-Wing-bdshot_bl.bin new file mode 100755 index 00000000000..85f34a0298d Binary files /dev/null and b/Tools/bootloaders/MatekF405-Wing-bdshot_bl.bin differ diff --git a/Tools/bootloaders/MatekF405-bdshot_bl.bin b/Tools/bootloaders/MatekF405-bdshot_bl.bin old mode 100644 new mode 100755 index 9579c7e5c4e..dd04ff19b0c Binary files a/Tools/bootloaders/MatekF405-bdshot_bl.bin and b/Tools/bootloaders/MatekF405-bdshot_bl.bin differ diff --git a/Tools/bootloaders/MatekF765-SE_bl.bin b/Tools/bootloaders/MatekF765-SE_bl.bin index dd2103adaa3..7e75d6344e1 100755 Binary files a/Tools/bootloaders/MatekF765-SE_bl.bin and b/Tools/bootloaders/MatekF765-SE_bl.bin differ diff --git a/Tools/bootloaders/MatekF765-SE_bl.elf b/Tools/bootloaders/MatekF765-SE_bl.elf index e97524f568c..1dd23bd1158 100755 Binary files a/Tools/bootloaders/MatekF765-SE_bl.elf and b/Tools/bootloaders/MatekF765-SE_bl.elf differ diff --git a/Tools/bootloaders/MatekF765-SE_bl.hex b/Tools/bootloaders/MatekF765-SE_bl.hex index 426063133ca..983d5a90dfd 100644 --- a/Tools/bootloaders/MatekF765-SE_bl.hex +++ b/Tools/bootloaders/MatekF765-SE_bl.hex @@ -1,29 +1,29 @@ :020000040800F2 -:100000000006022001020008150F0008190F000861 -:10001000710F0008190F0008450F000803020008BF -:10002000030200080302000803020008FD2700087D +:100000000006022001020008B50F0008350F0008A5 +:100010008D0F0008350F0008610F0008030200086B +:100020000302000803020008030200083928000840 :10003000030200080302000803020008030200088C :10004000030200080302000803020008030200087C -:10005000030200080302000891390008B9390008BA -:10006000E1390008093A0008313A000803020008A3 +:1000500003020008030200089D390008C5390008A2 +:10006000ED390008153A00083D3A0008030200087F :10007000030200080302000803020008030200084C :10008000030200080302000803020008030200083C -:10009000030200080302000803020008593A00089E +:10009000030200080302000803020008653A000892 :1000A000030200080302000803020008030200081C -:1000B000413B000803020008030200080302000895 +:1000B0004D3B000803020008030200080302000889 :1000C00003020008030200080302000803020008FC :1000D00003020008030200080302000803020008EC -:1000E000BD3A0008030200080302000803020008EA +:1000E000C93A0008030200080302000803020008DE :1000F00003020008030200080302000803020008CC :1001000003020008030200080302000803020008BB :1001100003020008030200080302000803020008AB :10012000030200080302000803020008030200089B :10013000030200080302000803020008030200088B -:10014000030200080302000803020008CD2F000884 +:10014000030200080302000803020008ED2F000864 :10015000030200080302000803020008030200086B :10016000030200080302000803020008030200085B :10017000030200080302000803020008030200084B -:1001800003020008030200082D3B000803020008D8 +:100180000302000803020008393B000803020008CC :10019000030200080302000803020008030200082B :1001A000030200080302000803020008030200081B :1001B000030200080302000803020008030200080B @@ -31,992 +31,994 @@ :1001D00003020008030200080302000803020008EB :1001E00003020008030200080302000803020008DB :1001F00003020008030200080302000803020008CB -:1002000002E000F000F8FEE772B6394880F3088893 -:10021000384880F3098838484EF60851CEF200017C +:1002000002E000F000F8FEE772B63A4880F3088892 +:10021000394880F3098839484EF60851CEF200017A :10022000086040F20000CCF200004EF63471CEF2CD :1002300000010860BFF34F8FBFF36F8F40F20000E3 :10024000C0F2F0004EF68851CEF200010860BFF314 :100250004F8FBFF36F8F4FF00000E1EE100A4EF6A4 :100260003C71CEF200010860062080F31488BFF3D1 -:100270006F8F02F027FB03F021FA4FF055301F4932 -:100280001B4A91423CBF41F8040BFAE71C49194A4A -:1002900091423CBF41F8040BFAE71A491A4A1B4B3A -:1002A0009A423EBF51F8040B42F8040BF8E70020D5 -:1002B0001749184A91423CBF41F8040BFAE702F093 -:1002C00045FB03F065FA144C144DAC4203DA54F8C4 -:1002D000041B8847F9E700F041F8114C114DAC427E -:1002E00003DA54F8041B8847F9E702F02DBB00003D -:1002F0000006022000220220000000080000022068 -:1003000000060220583F0008002202205C22022042 -:10031000602202205C300220000200080002000877 -:1003200000020008000200082DE9F04F2DED108AB0 -:10033000C1F80CD0D0F80CD0BDEC108ABDE8F08F1D -:10034000002383F311882846A047002001F080FE97 -:10035000FEE701F001FE00DFFEE7000038B500F027 -:10036000DBFC40B1174B6FF07F01002259720E2168 -:100370001A729972DA7202F003FA044602F038FA3D -:100380000546D0B9104B9C4219D001339C4241F232 -:10039000883412BF054600240125002002F0FAF936 -:1003A0000DB100F05BF800F05DFD00F0F9FB2046B8 -:1003B00000F0F4F800F052F8F9E70024EDE7044605 -:1003C000EBE700BF00220220010007B008B500F0F3 -:1003D000B3FBA0F120035842584108BD054B07B5B7 -:1003E0001B88022101A8ADF8043000F0C3FB03B064 -:1003F0005DF804FBD43B000810B5202383F311887B -:100400001248C3680BB101F0BFFE0023104A4FF43D -:100410007A710E4801F066FE002383F311880D4CBB +:100270006F8F02F09FFB02F041FB03F031FA4FF069 +:1002800055301F491B4A91423CBF41F8040BFAE725 +:100290001C49194A91423CBF41F8040BFAE71A493C +:1002A0001A4A1B4B9A423EBF51F8040B42F8040B0A +:1002B000F8E700201749184A91423CBF41F8040B67 +:1002C000FAE702F059FB03F06BFA144C144DAC4200 +:1002D00003DA54F8041B8847F9E700F041F8114CA1 +:1002E000114DAC4203DA54F8041B8847F9E702F0D9 +:1002F00041BB00000006022000220220000000088E +:100300000000022000060220783F000800220220A0 +:1003100068220220682202207834022000020008AD +:100320000002000800020008000200082DE9F04F5A +:100330002DED108AC1F80CD0D0F80CD0BDEC108A8D +:10034000BDE8F08F002383F311882846A0470020E2 +:1003500001F07AFEFEE701F0F5FD00DFFEE70000A8 +:1003600038B502F051FA40B1174B6FF07F0100220F +:1003700059720E211A729972DA7202F01BFA05464E +:1003800002F050FA0446D0B9104B9D4219D0013307 +:100390009D4241F2883512BF044600250124002009 +:1003A00002F012FA0CB100F079F800F06BFD00F0E9 +:1003B0000DFC284600F0FCF800F070F8F9E7002585 +:1003C000EDE70546EBE700BF00220220010007B081 +:1003D00008B500F0C7FBA0F120035842584108BD02 +:1003E00007B541F21203022101A8ADF8043000F074 +:1003F000D7FB03B05DF804FB38B5202383F31188E5 +:100400001748C3680BB101F0A5FE0023154A4FF44D +:100410007A71134801F062FE002383F31188124CB5 :10042000236813B12368013B2360636813B16368D9 -:10043000013B6360084B1B7833B9636823B9022022 -:1004400000F080FC3223636010BD00BF60220220F8 -:10045000F90300087C23022074220220454B464900 -:100460002DE9F04153F8042F013201D1BDE8F081AC -:100470008B42F7D1414C424B22689A4278D9414B8A -:100480009B6803F1006303F5C0339A4270D20020E9 -:1004900000F0A2FB02203C4B187000F049FC3B4BE3 -:1004A0001A6C00221A64196E1A66196E596C5A6415 -:1004B000596E5A66596E596941F0800159615969FE -:1004C00021F0800159615969196941F000511961A0 -:1004D000196921F0005119611B6972B62C4B2D4925 -:1004E0000B601D682468BFF34F8FBFF36F8F2A4BDB -:1004F000C3F88420BFF34F8F5A6922F480325A61C7 -:10050000BFF34F8FD3F8802043F6E07EC2F3C906D5 -:10051000C2F34E32B707520102EA0E08384631469E -:10052000013948EA000C00F14040B1F1FF3FC3F847 -:1005300074C2F5D1203A12F1200FEDD1BFF34F8FE5 -:10054000BFF36F8FBFF34F8FBFF36F8F5A6922F4E2 -:1005500000325A610022C3F85022BFF34F8FBFF31D -:100560006F8F202383F31188AD4685F308882047D9 -:10057000BDE8F081FC7F01081C80010804800108AF -:10058000FF7F01080022022074220220003802406E -:100590000080010808ED00E000ED00E02DE9F04FDB -:1005A00099B0B94D2022FF21009010A8AC6800F04E -:1005B000FBFBB64A01951378A3B90121B448117029 -:1005C000C360202383F31188C3680BB101F0DCFD05 -:1005D0000023B04A4FF47A71AD4801F083FD002347 -:1005E00083F31188009BAC4A03B113600026AB4B28 -:1005F000009DB2463746B1461E70566002930120F8 -:1006000000F096FB002D00F02582A34B1B68002B09 -:1006100040F0208219B0BDE8F08F0220FFF7D6FE2F -:10062000002840F01082009B02210BA8002E08BF7A -:100630001D469B4B1B88ADF82C3000F09BFADEE783 -:100640004FF47A7000F078FAB0F10008EBDB02208A -:10065000FFF7BCFE0028E6D008F1FF38B8F1040F20 -:1006600000F2F381DFE808F0031E2124270018A818 -:100670000523042140F8343D00F07CFA01234FF0BB -:10068000000903FA08F848EA0A0A5FFA8AFA00F051 -:10069000DFFB27B10AF00B030B2B08BF0025FFF788 -:1006A0009DFEACE704217848E6E704217D48E3E7B6 -:1006B00004217D48E0E74FF01C09484609F1040990 -:1006C00000F08CFA04210B900BA800F053FAB9F15A -:1006D0002C0FF2D1D2E7002FA5D00AF00B030B2B81 -:1006E000A1D10220FFF772FE804600289BD0012096 -:1006F0006A4E00F071FA00270220307000F018FBFB -:100700005FFA87FB584600F077FA054688B15846ED -:10071000013700F081FA0028F2D146460025634BEC -:1007200002210BA847461B88ADF82C3000F022FAB6 -:1007300065E701232C460220337000F0EFFA019B9D -:100740009B689C4206D2204600F048FA0130E4D172 -:100750000434F4E70024029B464647461C702546B5 -:100760004D4B5C6093E7002F3FF45DAF0AF00B0345 -:100770000B2B7FF458AF0220029B187000F0D8FAC0 -:10078000322000F0D9F9B0F1000BFFF64CAF1BF0AE -:1007900003087FF448AF019B04EB0B0299688A427F -:1007A0003FF641AFBBF5807F3FF63DAF404AD845AD -:1007B00003920FDA4FF47A7000F0BEF904900499B6 -:1007C0000029FFF630AF0499039A08F8021008F1E7 -:1007D0000108ECE7C820FFF7F9FD804600283FF448 -:1007E00022AF1F2C11D8C4F1200710AB24F0030056 -:1007F0002F495F45184428BF5F463A4600F0ACFADF -:100800003A46FF212A4800F0CFFA4FEAAB032849C5 -:100810002046DAB2039300F0CFFA074600283FF4EF -:100820007EAF039B04EB830431E70220FFF7CEFD8C -:1008300000283FF4F8AE00F015FA00283FF4F3AEBC -:100840004FF000084346019A9268904532D2B8F1C1 -:100850001F0F12D8109A01320FD028F0030218A9E6 -:100860000A4452F8202C0B92184604220BA908F1D6 -:10087000040800F091FB0346E5E74046039300F0CF -:10088000ADF9039B0B90EFE70022022078230220B2 -:1008900060220220F90300087C2302207422022037 -:1008A000D63B00080422022008220220D83B000880 -:1008B0007822022018A8042140F84C3D00F05AF993 -:1008C000E5E618A80023642140F8343D00F048F91B -:1008D00000287FF4A8AE0220FFF778FD00283FF43F -:1008E000A2AE0B9800F0AAF918AB43F8480D04210A -:1008F0001846E3E718A80023642140F8343D00F0CF -:100900002FF900287FF48FAE0220FFF75FFD00284B -:100910003FF489AE0B9800F09FF918AB43F8440DF3 -:10092000E5E70220FFF752FD00283FF47CAE00F01F -:10093000A9F918AB43F8400DD9E70220FFF746FDAF -:1009400000283FF470AE0BA9142000F0A1F98046F6 -:1009500018A8042140F83C8D00F00CF941460BA882 -:10096000ACE7322000F0E8F8B0F10008FFF65BAE2B -:1009700018F0030F7FF457AE019A08EB0903926851 -:1009800093423FF650AE0220FFF720FD00283FF4CF -:100990004AAE28F00308C844C1453FF478AE484643 -:1009A00009F1040900F01AF904210A900AA800F0DC -:1009B000E1F8F1E74FF47A70FFF708FD00283FF403 -:1009C00032AE00F04FF9002842D0109B01330BD01B -:1009D000082210A9002000F0EFF9002838D02022CA -:1009E000FF2110A800F0E0F9FFF7F8FC364801F00D -:1009F00035FB0FE6002F3FF416AE0AF00B030B2B6E -:100A00007FF411AE18A80023642140F8343D00F0B3 -:100A1000A7F8804600287FF406AE0220FFF7D6FC38 -:100A200000283FF400AE0390FFF7D8FC41F2883075 -:100A3000454601F013FB0B9800F04CFA00F008FA61 -:100A4000039B1F46DBE5074621E64FF00009EAE578 -:100A5000B84664E6002000F06FF80490049B002B79 -:100A6000FFF6D0AD012000F059F9049B213B122B79 -:100A70003FF6C5AD01A252F823F000BF1B060008E7 -:100A800041060008D7060008FF050008FF0500081A -:100A9000FF05000867070008630900082B08000825 -:100AA000C3080008F508000823090008FF0500082E -:100AB0003B090008FF050008B50900088F0600087B -:100AC000FF050008F5090008A08601002DE9F84F90 -:100AD0004FF47A7507460E4600245543DFF85080E0 -:100AE000DFF8509098F900305FFA84FA5A1C01D070 -:100AF000A34210D159F82400324639460368D3F88E -:100B000020B02B46D847864205D1084B012083F8F8 -:100B100000A0BDE8F88F0134022CE3D14FF4FA7045 -:100B200001F09CFA0020BDE8F88F00BFC823022026 -:100B30000C220220DC3B000807B5002202AB012199 -:100B400003F8012D02461846FFF7C0FF20B19DF8BB -:100B5000070003B05DF804FB4FF0FF30F9E7000039 -:100B60000A46042108B5FFF7B1FF80F00100C0B2CA -:100B7000404208BD074B30B41A78074B53F8224067 -:100B80000A46014623682046DD69044BAC4630BC6A -:100B9000604700BFC8230220DC3B0008A08601009C -:100BA000F8B50A4C00250A4E01F0F0FC094F2080F0 -:100BB00030682388834207D901F0E2FC336805449A -:100BC0000133BD423360F3D9F8BD00BFCA23022010 -:100BD00084230220FF7F010001F084BD00F100604A -:100BE00000F5C0300068704700F10060920000F529 -:100BF000C03001F011BD0000054B1A68054B1B8881 -:100C00009B1A834202D9104401F0BABC00207047FD -:100C100084230220CA23022038B5074D04462868E1 -:100C2000204401F0B5FC28B928682044BDE83840CC -:100C300001F0C6BC38BD00BF8423022010F00303BE -:100C400008D1B0F5846F05D200F10050A0F57120F5 -:100C50000068704700207047014BC058704700BFC4 -:100C600020F4F01F064991F8243033B10023082204 -:100C7000086A81F82430FFF7B7BF0120704700BF32 -:100C800088230220014B1868704700BF002004E051 -:100C90001F4BF0B51E681F4BC6F30B02360C1F88A6 -:100CA0005D68BA4293F9084022D09F89BA4221D0A8 -:100CB0001F8BBA4206D102220C2404FB02335D686A -:100CC00093F90840B6F5805F16D041F201039E42C9 -:100CD00008BF5A24421E013D0B460A44934215D2D6 -:100CE00015F9016F581C4EB1034600F8016CF5E789 -:100CF0000022E1E70122DFE74124EBE72C258242D5 -:100D00001D7001D9981C5C70401AF0BD1846FBE7B5 -:100D1000002004E01022022000207047022803D1A6 -:100D20004FF08062014B9A61704700BF000C024097 -:100D3000022803D14FF48062014B9A61704700BFD3 -:100D4000000C0240022804D1024A536983F48063F4 -:100D500053617047000C0240002310B5934203D04A -:100D6000CC5CC4540133F9E710BD000030B5441E1B -:100D700014F9010F0B4658B193F900500131854227 -:100D800006D11AB993F90020801A30BD013AEFE775 -:100D9000002AF7D1104630BD02460346981A13F9CF -:100DA000011B0029FAD1704702440346934202D046 -:100DB00003F8011BFAE770472DE9F047234C05467D -:100DC0008846174694F8243083BB2E46DFF87C9083 -:100DD000C7B394F824302BB92022FF21484626625D -:100DE000FFF7E2FF94F824004146C0F1080504EB48 -:100DF0008000BD4228BF3D465FFA85FAAD00A7EBF3 -:100E00000A072A462E44FFF7A7FF94F82430A84487 -:100E1000FFB29A445FFA8AFABAF1080F84F824A064 -:100E2000D6D1FFF71FFF0028D2D108E0266A06EBD3 -:100E30008306B042CAD0FFF715FF0028C5D10020B5 -:100E4000BDE8F0870120BDE8F08700BF88230220BD -:100E5000024B1A78024B1A70704700BFC823022059 -:100E60000C22022038B5154C154D204600F004FC2C -:100E70002946204600F02CFC2D681248EA6ED2F874 -:100E8000043843F00203C2F8043801F0E7F80E49D1 -:100E9000284600F02BFDEA6E0C48D2F804380C49C5 -:100EA000A04223F00203C2F804384FF4E1330B6090 -:100EB00003D0BDE8384000F03DBB38BD70280220AB -:100EC000F43C000840420F001C3D00084C24022066 -:100ED000B023022038B50B4B05461A780A4B53F85D -:100EE00022400A4B9C420CD0094B00211822184684 -:100EF000FFF75AFF056001462046BDE8384000F084 -:100F000019BB38BDC8230220DC3B00087028022032 -:100F1000B0230220FEE7000000B59BB0EFF309818B -:100F200068226846FFF718FFEFF30583044B9A6BBE -:100F3000DA6A9A6A9A6A9A6A9A6A9A6A9B6AFEE76F -:100F400000ED00E000B59BB0EFF309816822684630 -:100F5000FFF702FFEFF30583044B9A6B9A6A9A6AD4 -:100F60009A6A9A6A9A6A9B6AFEE700BF00ED00E0FF -:100F700000B59BB0EFF3098168226846FFF7ECFEED -:100F8000EFF30583034B5A6B9A6A9A6A9A6A9A6AD4 -:100F90009B6AFEE700ED00E030B50A44074D914240 -:100FA0000BD011F8013B09245840013CF7D040F325 -:100FB00000032B4083EA5000F7E730BD2083B8EDF3 -:100FC000002304491A465A50C81808334260802B3F -:100FD000F9D17047CC2302200268436811430160B5 -:100FE00003B1184770470000024A136843F0C0037A -:100FF000136070470078004013B50E4C204600F097 -:101000008DFA04F11400009400234FF480720A4911 -:1010100000F04EF90094094B4FF48072084904F136 -:10102000380000F0C7F9074BE365074B236602B0B1 -:1010300010BD00BF4C240220B8240220E90F000894 -:10104000B82502200078004080F93703224B0029A0 -:1010500008BF1946037C012B30B50CD11F4B9842B9 -:1010600009D11F4B1A6C42F080421A641A6E42F08A -:1010700080421A661B6E0A68036EC46D03EB52034E -:101080008166B3FBF2F34A68150442BF23F00705FB -:1010900003F0070343EA4503E3608B6843F0400332 -:1010A0006360CB68510543F00103A36042F496737B -:1010B00043F0010323604FF0FF33236205D512F0A4 -:1010C000102205D0B2F1805F04D080F8643030BDCA -:1010D0007F23FAE73F23F8E7103C00084C24022066 -:1010E000003802402DE9F047C66D05463768F469BF -:1010F000200734621AD014F0080F0CBF00218021A1 -:10110000E20748BF41F02001A3074FF0200348BF8A -:1011100041F04001600748BF41F4807183F31188BA -:10112000281DFFF759FF002383F31188E2050AD534 -:10113000202383F311884FF40071281DFFF74CFF23 -:10114000002383F311884FF020094FF0000A14F0B8 -:10115000200831D13B0616D54FF0200905F1380A99 -:10116000200610D589F31188504600F057F9002861 -:101170002FDA0821281DFFF72FFF27F080033360A7 -:10118000002383F3118879060DD562060BD5202341 -:1011900083F31188EA6C2B6D9A4201D12B6CEBB969 -:1011A000002383F31188E30620D5AA6E1369EBB1FF -:1011B0005069BDE8F047184789F31188736A2846DB -:1011C00095F86410194000F0C3F98AF31188F469A6 -:1011D000BDE7B06288F31188F469C1E727F04007E2 -:1011E0001021281DFFF7F8FE3760D9E7BDE8F0872A -:1011F000F8B51546826804460B46AA4200D28568B7 -:10120000A1692669761AB54207D218462A46FFF721 -:10121000A3FDA3692B44A3610DE011D9AF1B324696 -:101220001846FFF799FD3A46E1683044FFF794FD10 -:10123000E2683A44A261A36828465B1BA360F8BD3C -:1012400018462A46FFF788FDE368E4E7836893427F -:101250002DE9F04104460F46154600D285686069C5 -:101260002669361AB54207D22A463946FFF774FD79 -:1012700063692B4463610EE013D9A5EB060832467F -:101280003946FFF769FD4246B919E068FFF764FD8A -:10129000E26842446261A36828465B1BA360BDE824 -:1012A000F0812A463946FFF757FDE368E2E7000080 -:1012B00010B50A440024C361029B00604060846052 -:1012C000C160816141610261036210BD08B582693C -:1012D0004369934201D1826882B982680132826097 -:1012E0005A1C42611970426903699A4201D3C3686A -:1012F0004361002100F0CEFE002008BD4FF0FF301A -:1013000008BD000070B5202304460E4683F3118803 -:10131000A568A5B1A368A269013BA360531CA361A2 -:1013200015782269934224BFE368A361E3690BB196 -:1013300020469847002383F31188284670BD314624 -:10134000204600F097FE0028E2DA85F3118870BD90 -:101350002DE9F74F05460F4690469A46D0F81C9067 -:10136000202686F311884FF0000B144664B1224604 -:1013700039462846FFF73CFF034668B951462846E0 -:1013800000F078FE0028F1D0002383F31188A8EB49 -:10139000040003B0BDE8F08FB9F1000F03D0019055 -:1013A0002846C847019B8BF31188E41A1F4486F333 -:1013B0001188DBE7C160816141611144C361009B19 -:1013C000006040608260016103627047F8B50446C6 -:1013D0000E461746202383F31188A568A5B1A3689C -:1013E000013BA36063695A1C62611E7023696269D4 -:1013F0009A4224BFE3686361E3690BB120469847D2 -:10140000002080F31188F8BD3946204600F032FEF6 -:101410000028E2DA85F31188F8BD0000836942698B -:101420009A4210B501D182687AB98268013282602D -:101430005A1C82611C7803699A4201D3C368836194 -:10144000002100F027FE204610BD4FF0FF3010BDF8 -:101450002DE9F74F05460F4690469A46D0F81C9066 -:10146000202686F311884FF0000B144664B1224603 -:1014700039462846FFF7EAFE034668B95146284632 -:1014800000F0F8FD0028F1D0002383F31188A8EBC9 -:10149000040003B0BDE8F08FB9F1000F03D0019054 -:1014A0002846C847019B8BF31188E41A1F4486F332 -:1014B0001188DBE7026843681143016003B11847F4 -:1014C000704700001430FFF743BF00004FF0FF33B8 -:1014D0001430FFF73DBF00003830FFF7B9BF000000 -:1014E0004FF0FF333830FFF7B3BF00001430FFF781 -:1014F00009BF00004FF0FF311430FFF703BF0000B9 -:101500003830FFF763BF00004FF0FF323830FFF78D -:101510005DBF000000207047FFF76EBD044B036005 -:10152000002343608360C36001230374704700BFDE -:10153000283C000810B52023044683F31188FFF7E8 -:1015400085FD02232374002383F3118810BD00005E -:1015500038B5C36904460D461BB904210844FFF79A -:10156000A9FF294604F11400FFF7B0FE002806DAAF -:10157000201D4FF48061BDE83840FFF79BBF38BDA8 -:10158000026843681143016003B1184770470000C7 -:1015900013B5446BD4F894341A681178042915D122 -:1015A000217C022912D11979012312898B4013421F -:1015B0000CD101A904F14C0001F084FFD4F894444B -:1015C0000246019B2179206800F0E0F902B010BDCD -:1015D000143001F007BF00004FF0FF33143001F06A -:1015E00001BF00004C3001F0D9BF00004FF0FF33C5 -:1015F0004C3001F0D3BF0000143001F0D5BE000024 -:101600004FF0FF31143001F0CFBE00004C3001F03C -:10161000A5BF00004FF0FF324C3001F09FBF00002B -:10162000D0F8942438B5136805461978042901D0F8 -:10163000012038BD017C0229FAD1127901205C8990 -:1016400090400440F4D105F1140001F067FE024619 -:101650000028EDD0D5F894544FF480732868697948 -:1016600000F082F9204638BD406BFFF7D9BF00007B -:1016700000207047704700007FB5124B01250226FD -:10168000044603600023057400F184024360294688 -:101690008360C3600C4B0290143001934FF480734D -:1016A000009601F017FE094B04F5237229460193B9 -:1016B00004F14C004FF480730294009601F0DEFEBA -:1016C00004B070BD503C0008691600089115000870 -:1016D0000B68202282F311880A7903EB82021062E0 -:1016E0004A790D3243F822008A7912B103EB820362 -:1016F00018620223C0F894140374002383F3118842 -:101700007047000038B5037F044613B190F8543099 -:10171000ABB90125201D0221FFF732FF04F11400AF -:1017200025776FF0010100F0C1FC84F8545004F1FA -:101730004C006FF00101BDE8384000F0B7BC38BD87 -:1017400010B5012104460430FFF71AFF0023237768 -:1017500084F8543010BD000038B50446002514301C -:1017600001F0D0FD04F14C00257701F09FFE201D13 -:1017700084F854500121FFF703FF2046BDE83840AC -:10178000FFF74EBF90F85C3003F06003202B19D1B7 -:1017900090F85D20212A0AD0222A4FF000030ED0B3 -:1017A000202A0FD1084A02650722426504E0064B51 -:1017B00003650723436500238365012070470365A4 -:1017C0004365F9E70020704734220220D0F89434B2 -:1017D00037B51A680446117804291AD1017C022908 -:1017E00017D11979012312898B40134211D100F1CD -:1017F0004C05284601F01AFF58B101A9284601F00E -:1018000061FED4F894440246019B2179206800F0DF -:10181000BDF803B030BD000000EB8103F7B51C6AD2 -:1018200005460E46F4B1202383F3118805EB8607A5 -:10183000201D08214C34FFF7A3FEFB685B691B6881 -:1018400013B1204601F04CFE01A9204601F03AFEFA -:10185000024648B1019B3146284600F097F8002324 -:1018600083F3118803B0F0BDFB685A691268002A3F -:10187000F5D01B8A013B1340F1D105F15C02EAE788 -:101880000D3138B550F82140DCB1202383F31188A5 -:10189000D4F894241368527903EB8203DB689B69C4 -:1018A0005D6845B104216018FFF76AFE294604F11E -:1018B000140001F03DFD2046FFF7B2FE002383F344 -:1018C000118838BD7047000001F0D2B8012300F143 -:1018D000240200F1380103700023436042F8043B06 -:1018E0008A421361FAD103814381704738B50446B7 -:1018F000202383F3118800254160C560056145619F -:101900008561C561056201F0C3F80223237085F388 -:10191000118838BD70B500EB8103054650690E464D -:101920001446DA6018B110220021FFF73DFAA069D1 -:1019300018B110220021FFF737FA31462846BDE8DA -:10194000704001F06FB90000028902F001020281CB -:10195000428902F0010242810022026142618261F9 -:10196000C261026201F0F2B9F0B4012500EB81041A -:1019700047898D40E4683D43A46945812360002385 -:10198000A2606360F0BC01F00DBA0000F0B4012564 -:1019900000EB810407898D40E4683D43646905815B -:1019A00023600023A2606360F0BC01F087BA0000EE -:1019B00070B50223002504460370A0F8645080F837 -:1019C000665080F8675005814581C56005614561B5 -:1019D0008561C561056280F84C5001F0BFF863680D -:1019E0001B6823B129462046BDE87040184770BDEA -:1019F000037880F868300523037043681B6810B5CE -:101A000004460BB10421984700232381638110BD54 -:101A1000436890F868201B6802700BB105211847D5 -:101A20007047000090F84C3070B5044613B10023A5 -:101A300080F84C3004F15C02204601F0A9F963689B -:101A40009B6863BB94F85C5015F0600615D194F860 -:101A50005D3005F07F0545EA032540F202339D42E3 -:101A600000F00E815BD8022D00F0DC803FD8002D05 -:101A700000F08780012D00F0CF800021204601F08A -:101A8000F5FB0021204601F0E7FB63681B6813B1FA -:101A9000062120469847062384F84C3070BD204626 -:101AA00098470028CED094F8632094F8623043EA37 -:101AB0000223626D934238BF636594F95C30656DB3 -:101AC000002B4FF0200380F2FD80002D00F0EC8011 -:101AD000092284F84C2083F311880021636D226D64 -:101AE0002046FFF753FF002383F3118870BDB5F53F -:101AF000817F00F0B180B5F5407F49D0B5F5807F9A -:101B0000BBD194F85E30012BB7D1B4F8643023F028 -:101B10000203A4F8643026656665A665C3E740F253 -:101B200001639D421ED8B5F5C06F3BD2B5F5A06FDD -:101B3000A3D1B4F85C30B3F5A06F0ED194F85E3049 -:101B4000204684F8663001F061F863681B6813B1C1 -:101B500001212046984703232370002323656365F2 -:101B6000A365A0E7B5F5106F32D040F602439D4261 -:101B700052D0B5F5006F80D104F1670323650123CE -:101B800024E004F16403A5652365022363658AE705 -:101B900094F85E30012B7FF470AFB4F8643043F0FA -:101BA0000203B6E794F861202046616894F860303B -:101BB0004D6843EA022394F85F1094F85E20A8472A -:101BC00000283FF45AAF4368236503686365A4E7C0 -:101BD0002378042B10D1202383F311882046FFF7AC -:101BE000B3FE86F311886368032184F867601B687D -:101BF00021700BB12046984794F85E30002BACD092 -:101C000084F867300423237063681B68002BA4D01A -:101C1000022120469847A0E7374B236502236365DE -:101C200000239DE794F86010204611F0800F01F02A -:101C30000F010ED001F09EF8012806D002287FF493 -:101C40001CAF2E4B6065236567E72D4B65652365EB -:101C500063E701F081F8EFE794F85E30002B7FF442 -:101C60000CAF94F8603013F00F013FF476AF1A0612 -:101C7000204602D501F00EFB6FE701F001FB6CE797 -:101C800094F85E30002B7FF4F8AE94F8603013F0D7 -:101C90000F013FF462AF1B06204602D501F0E6FAC1 -:101CA0005BE701F0D9FA58E7142284F84C2083F35B -:101CB00011882B462A4629462046FFF755FE85F314 -:101CC000118870BD5DB1152284F84C2083F3118812 -:101CD0000021636D226D2046FFF746FE03E70B22CD -:101CE00084F84C2083F311882B462A462946204647 -:101CF000FFF74CFEE3E700BF803C0008783C00089B -:101D00007C3C000838B590F84C300446152B29D897 -:101D1000DFE803F03E28282828283E28280B293908 -:101D200028282828282828283E3E90F8631090F874 -:101D30006220436D42EA01229A4214D9C268128A93 -:101D4000B3FBF2F502FB15356DB9202383F311883F -:101D50002B462A462946FFF719FE85F311880A23E8 -:101D600084F84C3038BD142384F84C30202383F39E -:101D70001188002320461A461946FFF7F5FD002377 -:101D800083F3118838BD836D03B198470023E7E7DB -:101D9000002101F06BFA0021204601F05DFA636832 -:101DA0001B6813B10621204698470623D8E7000098 -:101DB00090F84C20152A38B5044622D801239340C8 -:101DC00040F6416213421DD113F480150FD19B02DE -:101DD00017D50B2380F84C30202383F311882B4632 -:101DE0002A462946FFF7D2FD85F3118838BDC3681E -:101DF0009B695B682BB9836D03B19847002384F816 -:101E00004C3038BD002101F031FA0021204601F0AC -:101E100023FA63681B6813B10621204698470623FE -:101E2000EDE70000024B00221B605B609A60704788 -:101E3000B8260220002382680374054B1B6899684A -:101E40009142FBD25A68036042601060586070474C -:101E5000B826022008B5202383F31188037C032BC6 -:101E600005D0042B0DD02BB983F3118808BD43692D -:101E700000221A604FF0FF334361FFF7DBFF0023BE -:101E8000F2E790E80C001A6002685360F2E7000085 -:101E9000002382680374054B1B6899689142FBD844 -:101EA0005A6803604260106058607047B82602208C -:101EB000054B196908741868026853601A60186144 -:101EC00001230374FEF730BAB82602204B1C30B54C -:101ED000054687B00A4C10D0236901A8094A00F0D2 -:101EE00001F92846FFF7E4FF049B13B101A800F0B5 -:101EF0004BF92369586907B030BDFFF7D9FFF8E700 -:101F0000B8260220551E000838B50C4D0446416124 -:101F10002B6981689A68914203D8BDE83840FFF781 -:101F200089BF1846FFF7B4FF01232C6101462374D3 -:101F30002046BDE83840FEF7F7B900BFB8260220BA -:101F4000044B1A681B6990689B68984294BF0020F4 -:101F500001207047B826022010B5084C236820697C -:101F60001A6854602260012223611A74FFF790FFFF -:101F700001462069BDE81040FEF7D6B9B826022018 -:101F8000FEE7000010B50C4CFFF74CFF00F09CF88A -:101F900080220A49204600F021F8012344F8180C59 -:101FA000037400F03BFC002383F3118862B60448FD -:101FB000BDE8104000F034B8E0260220843C000860 -:101FC0008C3C000800F01AB9034B59685A68521A41 -:101FD0009042FBD8704700BF001000E082600222F0 -:101FE00002740022427470478368A3F17C0243F8B4 -:101FF0000C2C026943F83C2C426943F8382C074A00 -:1020000043F81C2CC268A3F1180043F8102C0222DC -:1020100003F8082C002203F8072C7047410300083E -:1020200010B5202383F31188FFF7DEFF002104465B -:10203000FFF76AFF002383F31188204610BD0000DC -:10204000024B1B6958610F20FFF732BFB8260220F0 -:10205000202383F31188FFF7F3BF000008B5014682 -:10206000202383F311880820FFF730FF002383F338 -:10207000118808BD49B1064B42681B6918605A6057 -:10208000136043600420FFF721BF4FF0FF3070471B -:10209000B82602200368984206D01A680260506091 -:1020A00018465961FFF7C6BE7047000038B50446B0 -:1020B0000D462068844200D138BD036823605C600F -:1020C0004561FFF7B7FEF4E7054B03F114025A61CF -:1020D0009A614FF0FF32DA6100221A62704700BF46 -:1020E000B8260220F8B5274F0D4603610446C260AA -:1020F0003E4601F0CFFA3B46022D294653F8142FF5 -:1021000038BF02219A421D460AD1386208447C61D8 -:10211000BC6122606260A160BDE8F84001F0A8BA2D -:10212000D7F820E0A0EB0E035F181FD300279068BC -:10213000834217D8376AAA421F44376201D0C01AB7 -:10214000906073699A68914219D85A6823606260F6 -:1021500014605C60A1609868411A99604FF0FF3389 -:10216000F361F8BD97601B1A1268E0E793689F421D -:1021700003D20EEB070001F089FA3946E1E7891A2C -:102180001B68DFE7B826022038B51B4B01685A6987 -:102190001D46904203F114020CD0446821600021D6 -:1021A000036893425C60C16025D09A6881680A44E4 -:1021B0009A6038BD59614A6000215B69C1609342F1 -:1021C00003D1BDE8384001F05BBA9A6881680A44DF -:1021D0009A602C6A01F05EFA6A69001B926882427A -:1021E00009D9111A012998BF821C286ABDE8384014 -:1021F000104401F04BBA38BDB82602202DE9F84F43 -:10220000204C0027656904F11406B84601F042FA33 -:10221000236AA0EB030AAB6853451DD84FF0200991 -:10222000236AAA68D5F80CB013442362AB68AAEB02 -:10223000030A2B68B3425E606361EF6001D101F075 -:102240001FFA88F311882869D84789F311886569CE -:10225000AB689A45E4D2D9E76369B34210D02062F3 -:102260009A68A2EB0A029A60226AAB68821A9B1AE9 -:10227000022B2CBFC0180230BDE8F84F01F006BA9F -:10228000BDE8F88FB826022000207047FEE7000066 -:10229000704700004FF0FF3070470000022906D061 -:1022A000032906D00129064818BF002070470548B9 -:1022B0007047032A9ABF044800EBC2000020704711 -:1022C000783D00082C3D00083C22022070B59AB0F1 -:1022D00006460846144601AD294600F095F8284602 -:1022E000FEF75AFDC0B2431C5B0086E8180023705D -:1022F0000323023404F8013C00231946DAB2023405 -:10230000904201D81AB070BDEA5C013304F8011C98 -:1023100004F8022CF2E7000008B5202383F31188AB -:102320000348FFF753FA002383F3118808BD00BF69 -:102330007028022010B50446052916D8DFE801F000 -:1023400016150316161D202383F311880E4A01214A -:10235000FFF7E0FA20460D4A0221FFF7DBFA0C48AE -:10236000FFF7FAF9002383F3118810BD202383F3CC -:1023700011880748FFF7C6F9F4E7202383F3118893 -:102380000348FFF7DDF9EDE7AC3C0008D03C00085E -:102390007028022038B50C4D0C4C2A460C4904F12B -:1023A0000800FFF793FF05F1CA0204F11000094984 -:1023B000FFF78CFF05F5CA7204F118000649BDE865 -:1023C0003840FFF783BF00BF382D02203C22022097 -:1023D000FC3C0008063D0008113D000870B50446AD -:1023E00008460D46FEF7D8FCC6B2204601340378F5 -:1023F0000BB9184670BD32462946FEF7B7FC0028D7 -:10240000F3D1012070BD00002DE9F84F05460C46C0 -:10241000FEF7C2FC2C49C6B22846FFF7DFFF08B121 -:102420000536F6B229492846FFF7D8FF08B110361D -:10243000F6B2632E0DD8DFF89080DFF89090244F2D -:10244000DFF894A0DFF894B02E7846B92670BDE886 -:10245000F88F29462046BDE8F84F01F0B3BB252E82 -:102460002ED1072241462846FEF780FC70B9DBF8E2 -:10247000003007350C3444F80C3CDBF8043044F8E9 -:10248000083CDBF8083044F8043CDDE70822494604 -:102490002846FEF76BFC98B9A21C0E4B13F8011FDF -:1024A000023209095345C95D02F8041C197801F08C -:1024B0000F01C95D02F8031CF0D118340835C3E7D9 -:1024C000267001350134BFE7983D0008113D000832 -:1024D000AD3D00081FF4F01F2BF4F01FA03D0008D5 -:1024E000BFF34F8F024AD368DB03FCD4704700BFB1 -:1024F000003C024008B5074B1B7853B9FFF7F0FFCB -:10250000054B1A69002A04DA044A5A6002F188323B -:102510005A6008BD962F0220003C02402301674507 -:1025200008B5054B1B7833B9FFF7DAFF034A136987 -:1025300043F00043136108BD962F0220003C024087 -:102540000B2870B513D80B4A0B4C137863B94FF0B6 -:1025500000610A4E44F8231056F8235001330C2B27 -:102560002944F7D10123137054F8200070BD0020D6 -:1025700070BD00BFC82F0220982F0220C03D000868 -:10258000014B53F820007047C03D00080C207047F5 -:102590000B2810B5044601D9002010BDFFF7D0FF6D -:1025A000064B53F824301844C21A0BB9012010BD51 -:1025B00012680132F0D1043BF6E700BFC03D0008CD -:1025C0000B2810B5044621D8FFF78AFFFFF792FFCA -:1025D0000F4AF323D360C300DBB243F4007343F02C -:1025E00002031361136943F480331361FFF778FF2B -:1025F000FFF7A6FF074B53F8241000F0DBF8FFF7B6 -:102600008FFF2046BDE81040FFF7C2BF002010BD7D -:10261000003C0240C03D00082DE9F84312F00103E0 -:1026200015463FD18218B2F1026F3BD22B4B1B688B -:1026300013F0010336D0FFF75DFF294CF32340F27E -:102640000127E360FFF74CFF032D01D9830712D068 -:102650000F46401A224C40F20118EB1BC6190B44DE -:10266000012B236924D823F001032361FFF758FFCE -:102670000120BDE8F883236923F4407323612369B3 -:102680003B43236151F8046B0660BFF34F8FFFF7A4 -:1026900027FF03689E4208D0236923F001032361CA -:1026A000FFF73EFF0020BDE8F883043D0430CBE790 -:1026B00023F44073B9462361236943EA0803236185 -:1026C00037F8023B3380BFF34F8FFFF709FF36889F -:1026D000B6B2B9F80030B342BFD0DDE700380240EF -:1026E000003C0240084908B50B7828B153B9FFF700 -:1026F00001FF01230B7008BD23B10870BDE808403D -:10270000FFF70EBF08BD00BF962F02200244043918 -:10271000064BD2B210B5904200D110BD441C00B29D -:1027200053F8200041F8040FE0B2F4E750280040CD -:10273000104B30B51C6F240407D41C6F44F4007494 -:102740001C671C6F44F400441C670B4C02440439A2 -:102750002368D2B243F480732360084B904200D1C7 -:1027600030BD441C51F8045F00B243F82050E0B281 -:10277000F4E700BF003802400070004050280040DD -:1027800007B5012201A90020FFF7C0FF019803B09F -:102790005DF804FB13B50446FFF7F2FFA04206D034 -:1027A00002A90122002041F8044DFFF7C1FF02B049 -:1027B00010BD00000144BFF34F8F064B884204D385 -:1027C000BFF34F8FBFF36F8F7047C3F85C022030A9 -:1027D000F4E700BF00ED00E0034B1B689B0042BF25 -:1027E0000122024B1A70704774380240C92F022030 -:1027F000014B1878704700BFC92F0220EFF30983FF -:10280000054968334A6822F001024A6083F3098867 -:10281000002383F31188704730EF00E0202080F31D -:10282000118862B60D4B0E4AD96821F4E0610904A3 -:10283000090C0A430B49DA60CA6842F08072CA6028 -:10284000094A0A49C2F8B01F116841F0010111603C -:102850001022DA7783F82200704700BF00ED00E015 -:102860000003FA05F0ED00E0001000E055CEACC525 -:1028700010B5202383F311880E4B5B6813F40063BB -:1028800014D0F1EE103AEFF309844FF08073683CF6 -:10289000E361094BDB68236684F30988FFF750FB8B -:1028A00010B1064BA36110BD054BFBE783F3118804 -:1028B00010BD00BF00ED00E030EF00E05303000862 -:1028C00056030008F0B5BFF34F8FBFF36F8F1D4B5A -:1028D0000021C3F85012BFF34F8FBFF36F8F5A69B7 -:1028E00042F400325A61BFF34F8FBFF36F8FC3F8CA -:1028F0008410BFF34F8FD3F8802043F6E076C2F305 -:10290000C904C2F34E32A507520102EA060E284658 -:1029100021464EEA0007013900F14040C3F86072D9 -:102920004F1CF6D1203A12F1200FEED1BFF34F8F9A -:102930005A6942F480325A61BFF34F8FBFF36F8FF1 -:10294000F0BD00BF00ED00E0FEE70000084A094BC3 -:1029500009498B4204D3094A0021934205D37047A9 -:1029600052F8040F43F8040BF3E743F8041BF4E7B1 -:10297000B03F00085C3002205C3002205C30022056 -:10298000036F002170B5C46E4FF0FF359E684A0199 -:10299000A318D3F80009002805DAD3F8000940F09D -:1029A0008040C3F80009D3F8000B002805DAD3F8FB -:1029B000000B40F08040C3F8000B0131A3188E4299 -:1029C000C3F80859C3F8085BE1D24FF00113C4F80B -:1029D0001C3870BD890141F02001016103699B062B -:1029E000FCD41220FFF7F0BA204B03EB80022DE954 -:1029F000F047D2F80CE0461CDD6EDEF8142005EB43 -:102A00000636D2F800C005EB4018516861450BD37B -:102A10000123D5F8342803FA00F022EA0000C5F8B3 -:102A200034081846BDE8F087ACEB0103BEF810404F -:102A3000A34228BF2346D8F81849A4B2B3EB840FA9 -:102A400010D894681F46A4F1040959F804AF042F64 -:102A5000C6F800A001D9043FF7E71C440B4494607A -:102A60005360D2E70020BDE8F08700BFCC2F0220E2 -:102A700010B5054C2046FEF729FF4FF0A043E36652 -:102A8000024B236710BD00BFCC2F0220143E00086C -:102A90000378012B70B5054650D12A4BC46E98427D -:102AA0001BD1294B0E2143205A6B42F080025A63FE -:102AB0005A6D42F080025A655A6D5A6942F080029E -:102AC0005A615A6922F080025A615B6900F0ECFB9E -:102AD0001E4BE3601E4BC4F800380023EE6EC4F8B2 -:102AE000003EC02323604FF40413A3633369002B1B -:102AF000FCDA01230C203361FFF766FA3369DB0748 -:102B0000FCD41220FFF760FA3369002BFCDA0026B0 -:102B10002846A660FFF734FF6B68C4F81068DB68CE -:102B2000C4F81468C4F81C684BB90A4BA3614FF091 -:102B3000FF336361A36843F00103A36070BD064BDC -:102B4000F4E700BFCC2F02200038024040140040C0 -:102B500003002002003C30C0083C30C0F8B5C46E11 -:102B6000054600214FF000662046FFF733FF296F2E -:102B700000234FF001128F684FF0FF30C4F8343853 -:102B8000C4F81C2804EB431201339F42C2F80069C9 -:102B9000C2F8006BC2F80809C2F8080BF2D20B6841 -:102BA000EA6E6B67636210231361166916F01006F4 -:102BB000FBD11220FFF708FAD4F8003823F4FE63A3 -:102BC000C4F80038A36943F4402343F01003A36121 -:102BD0000923C4F81038C4F814380A4BEB604FF0DE -:102BE000C043C4F8103B084BC4F8003BC4F810695C -:102BF000C4F800396B6F03F1100243F480136A6765 -:102C0000A362F8BDF03D000840800010C26E90F84D -:102C10006610D2F8003823F4FE6343EA0113C2F8C9 -:102C2000003870472DE9F0410EB20D4600EB8608E2 -:102C3000D8F80C100F6807F00303022B50D0032BB9 -:102C400050D03D4A3D4F012B18BF1746C46E4FEA86 -:102C5000451E002205F1100C04EB0E03C3F8102BE7 -:102C60008A69002A40D04A8A05F158033A435B0139 -:102C7000E2500123D4F81C2803FA0CF31343C4F8E0 -:102C80001C38A64400234A69CEF8103905F13F03E9 -:102C9000002A39D00A8A04EB8303898B9208012920 -:102CA00088BF4A43416F561841EA024229464667A7 -:102CB00020465A60FFF78EFED8F80C301B8A43EA94 -:102CC00085531F4305F148035B01E7500123D4F806 -:102CD0001C2803FA05F51543C4F81C58BDE8F0811B -:102CE000174FB3E7174FB1E704EB4613D3F8002BA8 -:102CF00022F40042C3F8002B0123D4F81C2803FA65 -:102D00000CF322EA0303BAE704EB83030E4A04EB55 -:102D1000461629465A602046FFF75CFED6F8003971 -:102D2000012223F4004302FA05F5C6F80039D4F86D -:102D30001C3823EA0505CFE700800010008004104E -:102D40000080081000800C1000040002026F12685E -:102D50004267FFF715BE00005831C36E49015B584A -:102D600013F4004004D013F4001F14BF012002200C -:102D7000704700004831C36E49015B5813F40040AE -:102D800004D013F4001F14BF01200220704700007C -:102D900000EB8101CB68196A0B6813604B685360C4 -:102DA0007047000000EB810330B5DD68AA69136845 -:102DB000D36019B9402B84BF402313606B8A146819 -:102DC000C26E1C4402EB4110013C09B2B4FBF3F4A7 -:102DD0006343033323F0030343EAC44343F0C04394 -:102DE000C0F8103B2B6803F00303012B0ED1D2F87F -:102DF000083802EB411013F4807FD0F8003B14BF79 -:102E000043F0805343F00053C0F8003B02EB411203 -:102E1000D2F8003B43F00443C2F8003B30BD000051 -:102E20002DE9F041244D0446EE6E06EB4013D3F835 -:102E3000087B3807C3F8087B0AD5D6F81438190779 -:102E400006D505EB840321462846DB685B68984776 -:102E5000FA072FD5D6F81438DB072BD505EB8403FA -:102E6000D968CCB98B69488A5E68B6FBF0F200FB82 -:102E700012628AB91868DA6890420DD2121A83E891 -:102E80001400202383F311880B482146FFF78AFFA3 -:102E900084F31188BDE8F081012303FA04F26B8901 -:102EA00023EA02036B81CB6823B121460248BDE8C7 -:102EB000F0411847BDE8F081CC2F022000EB8103E0 -:102EC0004A0170B5DD68C36E6C692668E66056BB62 -:102ED0001A444FF40020C2F810092A6802F00302D5 -:102EE000012A0AB20ED1D3F8080803EB421410F4F9 -:102EF000807FD4F8000914BF40F0805040F00050AB -:102F0000C4F8000903EB4212D2F8000940F0044073 -:102F1000C2F800090122D3F8340802FA01F1014392 -:102F2000C3F8341870BD19B9402E84BF402020600A -:102F300020681A442E8A841940F00050013CB4FBEA -:102F4000F6F440EAC440C6E7F8B504461E48C56E2C -:102F500005EB4413D3F80869F107C3F8086917D5DE -:102F6000D5F81038DA0713D500EB8403D9684B691C -:102F70001F68DA68974218D2D21B00271A605F6078 -:102F8000202383F311882146FFF798FF87F31188E8 -:102F9000330617D50123D5F83428A340134211D0A6 -:102FA0002046BDE8F840FFF71FBD012303FA04F2F5 -:102FB000038923EA020303818B68002BE8D02146B2 -:102FC0009847E5E7F8BD00BFCC2F0220A1482DE9C6 -:102FD000F84FC56E04466E69AB691E4016F4805FFB -:102FE0006E6105D0FEF7E4FCBDE8F84FFFF740BC8A -:102FF000002E12DAD5F8003E9B0705D0D5F8003E2A -:1030000023F00303C5F8003ED5F80438914823F0B7 -:103010000103C5F80438FEF7FBFC370505D58D48DC -:10302000FFF7AEFC8B48FEF7E3FCB0040CD5D5F8F7 -:10303000083813F0060FEB6823F470530CBF43F409 -:10304000105343F4A053EB60310704D56368DB6889 -:103050000BB180489847F2026FD4B3020CD5D4F874 -:103060006C8000274FF00109DFF8E8A1236FF9B267 -:103070009B688B4280F09C80F70619D5E16E0A6A46 -:10308000C2F30A1702F00F0302F4F012B2F5802F18 -:1030900000F0B580B2F5402F0AD104EB830301F5AF -:1030A0008051DB68186A00231A469F4240F09C80DA -:1030B0003303D5F818481DD5E70302D50020FFF7E4 -:1030C000AFFEA50302D50120FFF7AAFE600302D5DB -:1030D0000220FFF7A5FE210302D50320FFF7A0FE83 -:1030E000E20202D50420FFF79BFEA30202D50520D1 -:1030F000FFF796FE77037FF577AFE60702D500204E -:10310000FFF722FFA50702D50120FFF71DFF60078B -:1031100002D50220FFF718FF210702D50320FFF791 -:1031200013FFE20602D50420FFF70EFFA3067FF58A -:103130005BAF0520FFF708FF56E7D4F86C80002747 -:103140004FF00109DFF80CA1236F5FFA87FB9B6842 -:103150005B4582D308EB4B13D3F8002902F44022DD -:10316000B2F5802F22D1D3F80029002A1EDAD3F835 -:10317000002942F09042C3F80029D3F80029002A20 -:10318000FBDB5946E06EFFF725FC228909FA0BF3B9 -:1031900022EA0303238104EB8B03DB689B6813B1F2 -:1031A0005946504698475846FFF71EFC0137CBE773 -:1031B00008EB4112D2F8003B03F44023B3F5802F13 -:1031C00010D1D2F8003B002B0CDA628909FA01F326 -:1031D00022EA0303638104EB8103DB68DB680BB144 -:1031E00050469847013741E79C0700D10A68072BF2 -:1031F00003F101039EBF0270120A013055E702334A -:1032000001F5805104EB8302526890690268D0F89E -:1032100008C04068A2EB000E0022104697420AD177 -:1032200004EB830463689B699A683A449A605A681D -:1032300017445F603CE712F0030F00D10868964521 -:1032400002F1010282BF8CF80000000A0CF1010CAF -:10325000E4E700BFCC2F0220C36E03EB4111D1F88D -:10326000003B43F40013C1F8003B7047C36E03EB0F -:103270004111D1F8003943F40013C1F80039704707 -:10328000C36E03EB4111D1F8003B23F40013C1F8E6 -:10329000003B7047C36E03EB4111D1F8003923F4B2 -:1032A0000013C1F80039704700F1604300F01F02BD -:1032B0000901400903F56143C9B2800083F8001396 -:1032C000012300F16040934000F56140C0F8803177 -:1032D0000360704730B50433039C0172002104FB86 -:1032E0000325C361049B00600363059B4060C160CC -:1032F000426102618561046242628162C16243632C -:1033000030BD00000022416AC260416101616FF07E -:1033100001018262C262FEF7C9BE00000369426910 -:10332000934203D1C2680AB100207047181D70474C -:10333000036919600021C2680132C260C269134486 -:1033400082699342036124BF436A0361FEF7A2BE10 -:1033500038B504460D46E3683BB162690020131D91 -:103360001268A3621344E36238BD237A33B9294655 -:103370002046FEF77FFE0028EDDA38BD6FF0010031 -:10338000FBE70000C368C269013BC36043691344A3 -:1033900082699342436124BF436A4361002383628D -:1033A000036B03B11847704770B52023044683F3BD -:1033B0001188866A3EB9FFF7CBFF054618B186F340 -:1033C0001188284670BDA36AE26A13F8015B934234 -:1033D000A36202D32046FFF7D5FF002383F31188B1 -:1033E000EFE700002DE9F84F04460E469046994657 -:1033F000202787F311880025AA46D4F828B0BBF10E -:10340000000F09D149462046FFF7A2FF20B18BF3F8 -:1034100011882846BDE8F88FA16AA8EB050BE36A7E -:103420005B1A9B4528BF9B46BBF1400F1BD9334617 -:1034300001F1400251F8040B914243F8040BF9D119 -:10344000A36A403640354033A362A26AE36A9A42D7 -:1034500002D32046FFF796FF8AF311884545D8D25C -:1034600087F31188C9E730465A46FDF775FCA36A11 -:103470005E445D445B44A362E7E7000010B5029C34 -:1034800004330172C36103FB0421002300608362E3 -:10349000C362039B40600363049BC460426102619A -:1034A000816104624262436310BD0000026A6FF0F2 -:1034B0000101C260426A4261026100228262C2620C -:1034C000FEF7F4BD436902699A4203D1C2680AB1AA -:1034D00000207047184650F8043B0B60704700000E -:1034E000C3680021C2690133C36043691344826920 -:1034F0009342436124BF436A4361FEF7CBBD0000A2 -:1035000038B504460D46E3683BB1236900201A1D17 -:10351000A262E2691344E36238BD237A33B92946D3 -:103520002046FEF7A7FD0028EDDA38BD6FF0010058 -:10353000FBE7000003691960C268013AC260C26912 -:10354000134482699342036124BF436A03610023E9 -:103550008362036B03B118477047000070B52023E6 -:1035600004460E4683F31188856A35B91146FFF784 -:10357000C7FF10B185F3118870BDA36A1E70A36ADE -:10358000E26A01339342A36204D3E169204604391D -:10359000FFF7D0FF002080F3118870BD2DE9F84FB0 -:1035A00004460D4691469A464FF0200888F311884C -:1035B0000026B346A76A4FB951462046FFF7A0FF41 -:1035C00020B187F311883046BDE8F88FA06AA9EBD7 -:1035D0000603E76A3F1A9F4228BF1F46402F1BD9A8 -:1035E00005F1400355F8042B9D4240F8042BF9D116 -:1035F000A36A40364033A362A26AE36A9A4204D3C4 -:10360000E16920460439FFF795FF8BF311884E4599 -:10361000D9D288F31188CDE729463A46FDF79CFBBD -:10362000A36A3D443E443B44A362E5E70269436923 -:103630009A4203D1C3681BB9184670470023FBE7C1 -:10364000836A002BF8D0043B9B1AF5D01360C36843 -:10365000013BC360C3691A4483699A42026124BF73 -:10366000436A0361002383620123E5E700F09EB80B -:103670004FF08043002258631A610222DA607047DB -:1036800000224FF08043DA60704700004FF0804323 -:10369000586370474FF08043586A70474B684360E7 -:1036A0008B688360CB68C3600B6943614B690362BD -:1036B0008B6943620B6803607047000008B5274BB5 -:1036C00040F2FF7126481A690A431A611A6922F406 -:1036D000FF6222F007021A611A691A6B0A431A6321 -:1036E0001A6D0A431A651F4A1B6D1146FFF7D6FF74 -:1036F0001D4802F11C01FFF7D1FF1C4802F13801FF -:10370000FFF7CCFF1A4802F15401FFF7C7FF194831 -:1037100002F17001FFF7C2FF174802F18C01FFF7B9 -:10372000BDFF164802F1A801FFF7B8FF144802F1E7 -:10373000C401FFF7B3FF134802F1E001FFF7AEFF4A -:10374000114802F1FC01FFF7A9FF104802F58C7146 -:10375000FFF7A4FFBDE8084000F09EB80038024023 -:1037600000000240203E0008000402400008024021 -:10377000000C0240001002400014024000180240F9 -:10378000001C0240002002400024024000280240A9 -:1037900008B500F005FAFEF7F5FBFFF71DF8BDE8E8 -:1037A0000840FEF7F7BD0000704700000F4B1A6C91 -:1037B00042F001021A641A6E42F001021A660C4AC3 -:1037C0001B6E936843F0010393604FF080436B22BC -:1037D0009A624FF0FF32DA6200229A615A63DA602D -:1037E0005A6001225A611A60704700BF00380240D7 -:1037F000002004E04FF0804208B51369D1680B4007 -:10380000D9B29B076FEA0101116107D5202383F329 -:103810001188FEF7D7FB002383F3118808BD000051 -:103820001B4B4FF0FF3000211A696FEA42526FEADA -:1038300052521A611A69C2F30A021A611A695A6964 -:1038400058615A6959615A691A6A62F080521A625B -:103850001A6A02F080521A621A6A5A6A58625A6ADE -:1038600059625A6A0B4A106840F480701060186FF1 -:1038700000F44070B0F5007F03D04FF4803018673B -:103880001967536823F40073536000F061B900BFF7 -:103890000038024000700040374B4FF44041374A37 -:1038A0001A64374A11601A6842F001021A601A68F5 -:1038B0009207FCD59A6822F003029A602E4B1946B3 -:1038C0009A6812F00C02FBD1186800F0F900186039 -:1038D0009A601A6842F480321A600B689B03FCD528 -:1038E0004B6F43F001034B67234B5A6F9007FCD596 -:1038F000244A5A601A6842F080721A60204B1A46B5 -:1039000059684904FCD5196841F48031196053683D -:10391000D803FCD5136843F400331360184A536886 -:103920009903FCD5144B1A689201FCD5164A9A608B -:1039300040F20112C3F88C200022C3F8902040F21C -:103940000732124B1A601A6802F00F02072AFAD1E6 -:10395000094B9A6842F002029A609A6802F00C02DF -:10396000082AFAD15A6C42F480425A645A6E42F4E0 -:1039700080425A665B6E70470038024000040010B7 -:1039800000700040086C400900948838003C0240F8 -:10399000074A08B5536903F00103536123B1054A8F -:1039A00013680BB150689847BDE80840FEF760BF48 -:1039B000003C0140CC230220074A08B5536903F0BC -:1039C0000203536123B1054A93680BB1D06898474D -:1039D000BDE80840FEF74CBF003C0140CC2302206C -:1039E000074A08B5536903F00403536123B1054A3C -:1039F00013690BB150699847BDE80840FEF738BF1E -:103A0000003C0140CC230220074A08B5536903F06B -:103A10000803536123B1054A93690BB1D0699847F4 -:103A2000BDE80840FEF724BF003C0140CC23022043 -:103A3000074A08B5536903F01003536123B1054ADF -:103A4000136A0BB1506A9847BDE80840FEF710BFF3 -:103A5000003C0140CC230220164B10B55C6904F4F5 -:103A600078725A61A30604D5134A936A0BB1D06ADF -:103A70009847600604D5104A136B0BB1506B9847FA -:103A8000210604D50C4A936B0BB1D06B9847E20525 -:103A900004D5094A136C0BB1506C9847A30504D5A3 -:103AA000054A936C0BB1D06C9847BDE81040FEF707 -:103AB000DFBE00BF003C0140CC230220194B10B5F3 -:103AC0005C6904F47C425A61620504D5164A136DA0 -:103AD0000BB1506D9847230504D5134A936D0BB174 -:103AE000D06D9847E00404D50F4A136E0BB1506EA9 -:103AF0009847A10404D50C4A936E0BB1D06E984739 -:103B0000620404D5084A136F0BB1506F9847230421 -:103B100004D5054A936F0BB1D06F9847BDE81040AC -:103B2000FEF7A6BE003C0140CC23022008B50348A6 -:103B3000FDF7D8FABDE80840FEF79ABE4C240220F3 -:103B400008B5FFF757FEBDE80840FEF791BE00003C -:103B5000062108B50846FFF7A7FB06210720FFF757 -:103B6000A3FB06210820FFF79FFB06210920FFF792 -:103B70009BFB06210A20FFF797FB06211720FFF782 -:103B800093FB06212820FFF78FFB07211C20FFF75E -:103B90008BFB0C215220BDE80840FFF785BB0000DD -:103BA00008B5FFF73DFEFDF70BFAFDF7B5FCFDF795 -:103BB0008BFEFDF75FFDFFF7F7FDBDE80840FFF75F -:103BC00055BD0000034611F8012B03F8012B002A14 -:103BD000F9D1704712101213121100007028022040 -:103BE0004C24022053544D3332463F3F3F3F3F3F2A -:103BF0000053544D333246375B347C355D78005387 -:103C0000544D333246375B367C375D780000000018 -:103C1000009600000000000000000000000000000E -:103C2000000000000000000000000000E114000897 -:103C3000CD14000809150008F51400080115000846 -:103C4000ED140008D9140008C51400081515000863 -:103C500000000000ED150008D91500081516000831 -:103C6000011600080D160008F9150008E5150008F2 -:103C7000D1150008711600080000000001000000C6 -:103C8000000000006D61696E00000000A43C0008A7 -:103C9000F82602207028022001000000811F000881 -:103CA0000000000069646C65000000000200000074 -:103CB00000000000191800088118000840004000AA -:103CC000082D0220182D0220020000000000000034 -:103CD0000300000000000000C518000800000000FC -:103CE00010000000282D022000000000010000004C -:103CF00000000000CC2F0220010102004172647517 -:103D000050696C6F740025424F415244252D424C3E -:103D1000002553455249414C250000003523000839 -:103D20009D220008851700081923000843000000A1 -:103D3000343D000809024300020100C032090400BA -:103D40000001020201000524001001052401000108 -:103D5000042402020524060001070582030800FF6F -:103D600009040100020A00000007050102400000EA -:103D7000070581024000000012000000803D00089D -:103D80001201100102000040091241570002010215 -:103D9000030100000403090425424F415244250059 -:103DA0004D6174656B463736352D534500303132E1 -:103DB00033343536373839414243444546000000F4 -:103DC00000800000008000000080000000800000F3 -:103DD00000000200000004000000040000000400D5 -:103DE00000000400000004000000040000000400C3 -:103DF00000000000251A0008051D0008B11D00087C -:103E00004000400044300220443002200100000005 -:103E10005430022080000000400100000500000036 -:103E20000000802A00000000AAAAAAAA0000000040 -:103E3000FFFF00000000000000A00A0000000001D9 -:103E400000000000AAAAAAAA00000001FFFF0000CB -:103E50000000000000000000000100000000000061 -:103E6000AAAAAAAA00010000FFFF000000000000AB -:103E7000000000000040100000000000AAAAAAAA4A -:103E800000400000FFFB00000000000000000000F8 -:103E90000080420000000000AAAAAAAA0040410037 -:103EA000FFFF00000000008008000000000000008C -:103EB00000000000AAAAAAAA00000000FFFF00005C -:103EC00000000000000000000000000000000000F2 -:103ED000AAAAAAAA00000000FFFF0000000000003C -:103EE000000000000000000000000000AAAAAAAA2A -:103EF00000000000FFFF00000000000000000000C4 -:103F00000000000000000000AAAAAAAA0000000009 -:103F1000FFFF0000000000000000000000000000A3 -:103F20000000000000000000000000000000000091 -:103F30000000000000000000000000000000000081 +:10043000013B63600D4D2B7833B963687BB90220B3 +:1004400000F09AFC322363602B78032B07D163689A +:100450002BB9022000F090FC4FF47A73636038BD32 +:1004600068220220F9030008842302207C22022053 +:10047000084B187003280CD8DFE800F008050208C4 +:10048000022000F06FBC022000F062BC024B002290 +:100490005A6070477C22022084230220F8B53F4B2B +:1004A0003F4A1C461968013177D004339342F9D191 +:1004B0006268A24271D33B4B9B6803F1006303F572 +:1004C000C0339A4269D2002000F09AFB0220FFF765 +:1004D000CFFF354B00211A6C19641A6E19661A6E1B +:1004E0005A6C59645A6E59665A6E5A6942F08002C3 +:1004F0005A615A6922F080025A615A691A6942F0B7 +:1005000000521A611A6922F000521A611B6972B610 +:100510004FF0E023C3F8084DD4E90004BFF34F8F38 +:10052000BFF36F8F214AC2F88410BFF34F8F536916 +:1005300023F480335361BFF34F8FD2F8803043F6FA +:10054000E076C3F3C905C3F34E335B0103EA060C3F +:1005500029464CEA81770139C2F87472F9D2203BFE +:1005600013F1200FF2D1BFF34F8FBFF36F8FBFF3A3 +:100570004F8FBFF36F8F536923F400335361002310 +:10058000C2F85032BFF34F8FBFF36F8F202383F336 +:100590001188854680F308882047F8BD008001084F +:1005A00020800108002202200038024000ED00E017 +:1005B0002DE9F04F93B0B44B2022FF2100900AA800 +:1005C0009D6800F009FCB14A1378A3B90121B04835 +:1005D0001170C360202383F31188C3680BB101F04D +:1005E000B9FD0023AB4A4FF47A71A94801F076FDBA +:1005F000002383F31188009B13B1A74B009A1A6064 +:10060000A64A1378032B03D000231370A24A536029 +:100610004FF0000A009CD3465646D146012000F018 +:10062000A1FB24B19C4B1B68002B00F0268200200C +:1006300000F098FA0390039B002BF2DB012000F0FE +:1006400087FB039B213B1F2BE8D801A252F823F024 +:10065000D1060008F90600088D0700081D060008ED +:100660001D0600081D0600081F080008EF09000805 +:10067000090900086B09000893090008B909000876 +:100680001D060008CB0900081D0600083D0A0008E9 +:10069000710700081D060008810A0008DD06000831 +:1006A000710700081D0600086B0900081D060008F8 +:1006B0001D0600081D0600081D0600081D0600088E +:1006C0001D0600081D0600081D0600088D0700080D +:1006D0000220FFF77DFE002840F0F981009B0221F7 +:1006E00005A8BAF1000F08BF1C4641F21233ADF85D +:1006F000143000F055FA91E74FF47A7000F032FAB6 +:10070000071EEBDB0220FFF763FE0028E6D0013F67 +:10071000052F00F2DE81DFE807F0030A0D10133623 +:100720000523042105A8059300F03AFA17E00421F7 +:100730005548F9E704215A48F6E704215948F3E7F8 +:100740004FF01C08404608F1040800F05BFA042151 +:10075000059005A800F024FAB8F12C0FF2D1012081 +:100760004FF0000900FA07F747EA0B0B5FFA8BFB23 +:1007700000F07EFB26B10BF00B030B2B08BF00240F +:10078000FFF72EFE4AE704214748CDE7002EA5D00B +:100790000BF00B030B2BA1D10220FFF719FE07462C +:1007A00000289BD00120002600F02AFA0220FFF743 +:1007B0005FFE5FFA86F8404600F032FA0446B0B1B8 +:1007C000039940460136A1F140025142514100F0E7 +:1007D00037FA0028EDD1BA46044641F2121302213D +:1007E00005A83E46ADF8143000F0DAF916E72546C4 +:1007F0000120FFF73DFE244B9B68AB4207D92846FA +:1008000000F000FA013040F067810435F3E700257D +:10081000224BBA463E461D701F4B5D60A8E7002E76 +:100820003FF45CAF0BF00B030B2B7FF457AF0220B0 +:10083000FFF71EFE322000F095F9B0F10008FFF638 +:100840004DAF18F003077FF449AF0F4A08EB0503DB +:10085000926893423FF642AFB8F5807F3FF73EAFD4 +:10086000124BB845019323DD4FF47A7000F07AF90A +:100870000390039A002AFFF631AF039A0137019BD8 +:1008800003F8012BEDE700BF0022022080230220A5 +:1008900068220220F9030008842302207C2202201F +:1008A00004220220082202200C22022080220220A0 +:1008B000C820FFF78DFD074600283FF40FAF1F2D1E +:1008C00011D8C5F120020AAB25F003008449424546 +:1008D000184428BF4246019200F058FA019AFF21BD +:1008E0007F4800F079FA4FEAA803C8F387027C49F1 +:1008F0002846019300F078FA064600283FF46DAFD1 +:10090000019B05EB830533E70220FFF761FD00281B +:100910003FF4E4AE00F0C0F900283FF4DFAE00275A +:10092000B846704B9B68BB4218D91F2F11D80A9B41 +:1009300001330ED027F0030312AA134453F8203CCE +:1009400005934046042205A9043700F035FB804694 +:10095000E7E7384600F056F90590F2E7CDF8148045 +:10096000042105A800F01CF902E70023642104A873 +:10097000049300F00BF900287FF4B0AE0220FFF7DB +:1009800027FD00283FF4AAAE049800F06DF9059009 +:10099000E6E70023642104A8049300F0F7F8002898 +:1009A0007FF49CAE0220FFF713FD00283FF496AEC3 +:1009B000049800F069F9EAE70220FFF709FD002832 +:1009C0003FF48CAE00F078F9E1E70220FFF700FD7C +:1009D00000283FF483AE05A9142000F073F9074600 +:1009E0000421049004A800F0DBF83946B9E732206E +:1009F00000F0B8F8071EFFF671AEBB077FF46EAECD +:100A0000384A07EB0903926893423FF667AE02202B +:100A1000FFF7DEFC00283FF461AE27F003074F44E8 +:100A2000B9453FF4A5AE484609F1040900F0EAF8DB +:100A30000421059005A800F0B3F8F1E74FF47A70AF +:100A4000FFF7C6FC00283FF449AE00F025F9002866 +:100A500044D00A9B01330BD008220AA9002000F0E1 +:100A6000C3F900283AD02022FF210AA800F0B4F9E7 +:100A7000FFF7B6FC1C4801F0EDFA13B0BDE8F08FAB +:100A8000002E3FF42BAE0BF00B030B2B7FF426AEA6 +:100A90000023642105A8059300F078F80746002894 +:100AA0007FF41CAE0220FFF793FC804600283FF441 +:100AB00015AEFFF795FC41F2883001F0CBFA0598AE +:100AC00000F018FA46463C4600F0D2F9A6E5064684 +:100AD0004EE64FF0000901E6BA467EE637467CE670 +:100AE0008022022000220220A0860100F7B50C46D9 +:100AF000184E4FF47A71054602FB01F396F9002077 +:100B0000501C0BD11448294601930268176A2246EB +:100B1000B8478442019B03D1002310E0002AF1D0A2 +:100B200096F90020511C01D0012A0DD10B4829460D +:100B30000268166A2246B047844205D10123084A5A +:100B40000120137003B0F0BD4FF4FA7001F082FA87 +:100B50000020F7E710220220F8270220D4230220E9 +:100B6000D0230220002307B5024601210DF1070022 +:100B70008DF80730FFF7BAFF20B19DF8070003B0EA +:100B80005DF804FB4FF0FF30F9E700000A4604214E +:100B900008B5FFF7ABFF80F00100C0B2404208BDCE +:100BA000074B0A4630B41978064B53F821400146EA +:100BB00023682046DD69044BAC4630BC604700BF6B +:100BC000D0230220283C0008A086010070B50A4E00 +:100BD00000240A4D01F0E0FC30802868338883420D +:100BE00008D901F0D3FC2B6804440133B4F5C03FAD +:100BF0002B60F2D370BD00BFD22302208C230220D1 +:100C000001F08CBD00F1006000F5C0300068704755 +:100C100000F10060920000F5C03001F00BBD000053 +:100C2000054B1A68054B1B889B1A834202D9104456 +:100C300001F0ACBC002070478C230220D22302209C +:100C400038B50446074D29B128682044BDE838402E +:100C500001F0BCBC2868204401F0A0FC0028F3D0BF +:100C600038BD00BF8C23022010F0030309D1B0F57A +:100C7000846F04D200F10050A0F57120036818467B +:100C800070470023FBE7000000F10050A0F5712041 +:100C9000D0F8200470470000064991F8243033B1A1 +:100CA00000230822086A81F82430FFF7B1BF012031 +:100CB000704700BF90230220014B1868704700BFA7 +:100CC000002004E0204B0246F0B518681F4BC0F32B +:100CD0000B06000C1F885D68BE4293F9084022D0C5 +:100CE0009F89BE4221D01F8BBE4206D102240C2513 +:100CF00005FB04335D6893F90840B0F5805F16D0BA +:100D000041F20103984208BF5A24013A013D0B46C3 +:100D10000A4493420DD215F9016F581C5EB1034687 +:100D200000F8016CF5E70024E1E70124DFE7412446 +:100D3000EBE7184605E02C2590421D7001D2981C67 +:100D40005C70401AF0BD00BF002004E014220220B5 +:100D5000022803D1024B4FF080629A61704700BFB6 +:100D6000000C0240022803D1024B4FF480629A61CA +:100D7000704700BF000C0240022804D1024A5369A8 +:100D800083F4806353617047000C0240002310B568 +:100D9000934203D0CC5CC4540133F9E710BD00008A +:100DA000013810B510F9013F3BB191F900409C4268 +:100DB00003D11AB10131013AF4E71AB191F90020D7 +:100DC000981A10BD1046FCE703460246D01A12F9E5 +:100DD000011B0029FAD1704702440346934202D016 +:100DE00003F8011BFAE770472DE9F8431F4D14463D +:100DF0000746884695F8242052BBDFF870909CB3D4 +:100E000095F824302BB92022FF2148462F62FFF7A6 +:100E1000E3FF95F824004146C0F1080205EB80008D +:100E2000A24228BF2246D6B29200FFF7AFFF95F844 +:100E30002430A41B17441E449044E4B2F6B2082E9A +:100E400085F82460DBD1FFF727FF0028D7D108E021 +:100E50002B6A03EB82038342CFD0FFF71DFF0028EC +:100E6000CBD10020BDE8F8830120FBE790230220CE +:100E7000024B1A78024B1A70704700BFD023022031 +:100E80001022022038B5154C154D204600F0F0FB1D +:100E90002946204600F018FC2D681248EA6ED2F868 +:100EA000043843F00203C2F8043801F0D3F80E49C5 +:100EB000284600F011FDEA6E0C48D2F804380C49BF +:100EC000A04223F00203C2F804384FF4E1330B6070 +:100ED00003D0BDE8384000F02BBB38BDF827022016 +:100EE000343D000840420F003C3D0008D42302205E +:100EF000B823022038B50B4B04461A780A4B53F836 +:100F000022500A4B9D420CD0094B00211822184652 +:100F1000FFF762FF046001462846BDE8384000F054 +:100F200007BB38BDD0230220283C0008F827022048 +:100F3000B823022000B59BB0EFF309816822684610 +:100F4000FFF724FFEFF30583044B9A6BDA6A9A6A82 +:100F50009A6A9A6A9A6A9A6A9B6AFEE700ED00E0CA +:100F600000B59BB0EFF3098168226846FFF70EFFDA +:100F7000EFF30583044B9A6B9A6A9A6A9A6A9A6AA3 +:100F80009A6A9B6AFEE700BF00ED00E000B59BB0E7 +:100F9000EFF3098168226846FFF7F8FEEFF3058357 +:100FA000034B5A6B9A6A9A6A9A6A9A6A9B6AFEE734 +:100FB00000ED00E0FEE7000030B50A44084D914224 +:100FC0000DD011F8013B5840082340F30004013BC9 +:100FD0002C4013F0FF0384EA5000F6D1EFE730BD58 +:100FE0002083B8ED026843681143016003B11847DC +:100FF00070470000024A136843F0C0031360704753 +:101000000078004013B50E4C204600F085FA04F13C +:10101000140000234FF480720A49009400F046F94E +:10102000094B4FF48072094904F13800009400F034 +:10103000BFF9074A074BC4E9172302B010BD00BF30 +:10104000D423022040240220F50F0008402502206E +:101050000078004080F93703037C30B5214C00292B +:1010600018BF0C46012B0CD11F4B984209D11F4BC6 +:101070001A6C42F080421A641A6E42F080421A667C +:101080001B6E2268036EC16D03EB52038466B3FBD3 +:10109000F2F36268150442BF23F0070503F007036B +:1010A00043EA4503CB60A36843F040034B60E36829 +:1010B00043F001038B6042F4967343F001030B602D +:1010C0004FF0FF330B62510505D512F0102205D009 +:1010D000B2F1805F04D080F8643030BD7F23FAE73E +:1010E0003F23F8E7303C0008D423022000380240B8 +:1010F0002DE9F047C66D05463768F469210734626B +:1011000019D014F0080118BF8021E20748BF41F050 +:101110002001A3074FF0200348BF41F040016007C2 +:1011200048BF41F4807183F31188281DFFF75AFFEF +:10113000002383F31188E2050AD5202383F3118865 +:101140004FF40071281DFFF74DFF002383F3118832 +:101150004FF020094FF0000A14F0200838D13B0668 +:1011600016D54FF0200905F1380A200610D589F36D +:101170001188504600F050F9002836DA0821281D61 +:10118000FFF730FF27F080033360002383F31188DB +:10119000790614D5620612D5202383F31188D5E988 +:1011A00013239A4208D12B6C33B127F0400710214A +:1011B000281DFFF717FF3760002383F31188E3062C +:1011C00018D5AA6E1369ABB15069BDE8F04718474E +:1011D00089F31188736A284695F86410194000F065 +:1011E000B5F98AF31188F469B6E7B06288F311881B +:1011F000F469BAE7BDE8F087F8B515468268044699 +:101200000B46AA4200D28568A1692669761AB542C2 +:101210000BD218462A46FFF7B9FDA3692B44A361F8 +:101220002846A3685B1BA360F8BD0CD9AF1B18460A +:101230003246FFF7ABFD3A46E1683044FFF7A6FDC2 +:10124000E3683B44EBE718462A46FFF79FFDE36857 +:10125000E5E7000083689342F7B50446154600D2DF +:101260008568D4E90460361AB5420BD22A46FFF7E6 +:101270008DFD63692B4463612846A3685B1BA360F3 +:1012800003B0F0BD0DD93246AF1B0191FFF77EFDD3 +:1012900001993A46E0683144FFF778FDE3683B4442 +:1012A000E9E72A46FFF772FDE368E4E710B50A4470 +:1012B0000024C361029B8460C16002610362C0E9D3 +:1012C0000000C0E9051110BD08B5D0E90532934210 +:1012D00001D1826882B98268013282605A1C4261FF +:1012E00019700021D0E904329A4224BFC3684361D7 +:1012F00000F0CCFE002008BD4FF0FF30FBE70000FF +:1013000070B5202304460E4683F31188A568A5B165 +:10131000A368A269013BA360531CA36115782269ED +:10132000934224BFE368A361E3690BB12046984769 +:10133000002383F31188284607E03146204600F059 +:1013400095FE0028E2DA85F3118870BD2DE9F74F8C +:1013500004460E4617469846D0F81C904FF0200AD7 +:101360008AF311884FF0000B154665B12A463146C5 +:101370002046FFF741FF034660B94146204600F092 +:1013800075FE0028F1D0002383F31188781B03B089 +:10139000BDE8F08FB9F1000F03D001902046C84797 +:1013A000019B8BF31188ED1A1E448AF31188DCE748 +:1013B000C160C361009B82600362C0E905111144F2 +:1013C000C0E9000001617047F8B504460D461646B5 +:1013D000202383F31188A768A7B1A368013BA3600A +:1013E00063695A1C62611D70D4E904329A4224BFB9 +:1013F000E3686361E3690BB120469847002080F3FE +:10140000118807E03146204600F030FE0028E2DA7D +:1014100087F31188F8BD0000D0E9052310B59A4282 +:1014200001D182687AB982680021013282605A1C37 +:1014300082611C7803699A4224BFC368836100F00B +:1014400025FE204610BD4FF0FF30FBE72DE9F74F9A +:1014500004460E4617469846D0F81C904FF0200AD6 +:101460008AF311884FF0000B154665B12A463146C4 +:101470002046FFF7EFFE034660B94146204600F0E4 +:10148000F5FD0028F1D0002383F31188781B03B009 +:10149000BDE8F08FB9F1000F03D001902046C84796 +:1014A000019B8BF31188ED1A1E448AF31188DCE747 +:1014B000026843681143016003B118477047000098 +:1014C0001430FFF743BF00004FF0FF331430FFF735 +:1014D0003DBF00003830FFF7B9BF00004FF0FF33C9 +:1014E0003830FFF7B3BF00001430FFF709BF00002A +:1014F0004FF0FF311430FFF703BF00003830FFF723 +:1015000063BF00004FF0FF323830FFF75DBF0000CF +:1015100000207047FFF776BD044B03600023436053 +:10152000C0E9023301230374704700BF483C000840 +:1015300010B52023044683F31188FFF78DFD0223A5 +:101540002374002383F3118810BD000038B5C369EC +:1015500004460D461BB904210844FFF7A9FF29469C +:1015600004F11400FFF7B0FE002806DA201D4FF446 +:101570008061BDE83840FFF79BBF38BD0268436813 +:101580001143016003B118477047000013B5446B65 +:10159000D4F8A4381A681178042915D1217C0229BD +:1015A00012D11979012312898B4013420CD101A960 +:1015B00004F14C0001F09AFFD4F8A4480246019BC4 +:1015C0002179206800F0D4F902B010BD143001F088 +:1015D0001DBF00004FF0FF33143001F017BF0000B3 +:1015E0004C3001F0EFBF00004FF0FF334C3001F002 +:1015F000E9BF0000143001F0EBBE00004FF0FF31F6 +:10160000143001F0E5BE00004C3001F0BBBF00001B +:101610004FF0FF324C3001F0B5BF000000207047A2 +:10162000D0F8A4381A6810B511780446042917D1E7 +:10163000017C022914D15979012352898B4013422C +:101640000ED1143001F07EFE024648B1D4F8A44811 +:101650004FF4807361792068BDE8104000F076B9DE +:1016600010BD0000406BFFF7DBBF000070470000BB +:101670007FB5124B01250426044603600023057440 +:1016800000F1840243602946C0E902330C4B02900A +:10169000143001934FF48073009601F02FFE094B34 +:1016A00004F29442294604F14C000294CDE900630F +:1016B0004FF4807301F0F6FE04B070BD703C00087A +:1016C000651600088D1500080B68202282F311882A +:1016D0000A7903EB820210624A790D3243F8220044 +:1016E0008A7912B103EB820318620223C0F8A418AE +:1016F0000374002383F311887047000038B5037F1B +:10170000044613B190F85430ABB90125201D0221D5 +:10171000FFF734FF04F114006FF00101257700F0AA +:10172000C1FC04F14C0084F854506FF00101BDE895 +:10173000384000F0B7BC38BD10B501210446043074 +:10174000FFF71CFF0023237784F8543010BD0000FE +:1017500038B504460025143001F0E8FD04F14C00D2 +:10176000257701F0B7FE201D84F854500121FFF7C2 +:1017700005FF2046BDE83840FFF752BF90F85C30C7 +:1017800003F06003202B06D190F85D200023212A6E +:1017900003D81F2A06D800207047222AFBD1C0E9AF +:1017A000143303E0034A0265072242658365012082 +:1017B000704700BF38220220D0F8A43837B51A6825 +:1017C0000446117804291AD1017C022917D119790C +:1017D000012312898B40134211D100F14C05284698 +:1017E00001F038FF58B101A9284601F07FFED4F876 +:1017F000A4480246019B2179206800F0B9F803B0A3 +:1018000030BD000000EB8103F0B51E6A85B00446D0 +:101810000D46FEB1202383F3118804EB8507301DAC +:101820000821FFF7ABFEFB6806F14C005B691B6803 +:101830001BB1019001F068FE019803A901F056FE6A +:10184000024648B1039B2946204600F091F8002348 +:1018500083F3118805B0F0BDFB685A691268002A4D +:10186000F5D01B8A013B1340F1D104F15C02EAE799 +:101870000D3138B550F82140DCB1202383F31188B5 +:10188000D4F8A4281368527903EB8203DB689B69C0 +:101890005D6845B104216018FFF770FE294604F128 +:1018A000140001F059FD2046FFF7BAFE002383F330 +:1018B000118838BD7047000001F0F2B801232822DA +:1018C000002110B5044600F8243BFFF785FA0023F9 +:1018D000C4E9013310BD000038B50446202383F36A +:1018E000118800254160C0E90355C0E90555C0E9EC +:1018F000075501F0E5F80223237085F3118838BD00 +:1019000070B500EB8103054650690E461446DA6057 +:1019100018B110220021FFF75FFAA06918B1102258 +:101920000021FFF759FA31462846BDE8704001F022 +:1019300091B90000826802F0011282600022C0E9C1 +:101940000422C0E90622026201F010BAF0B40125B7 +:1019500000EB810447898D40E4683D43A4694581DB +:1019600023600023A2606360F0BC01F02BBA00008A +:10197000F0B4012500EB810407898D40E4683D4304 +:101980006469058123600023A2606360F0BC01F0FC +:10199000A5BA000070B50223002504460370456611 +:1019A000056280F84C50C0E90255C0E90455C0E911 +:1019B000065501F0EBF863681B6823B12946204601 +:1019C000BDE87040184770BD037880F86830052383 +:1019D000037043681B6810B504460BB10421984797 +:1019E0000023A36010BD000090F8682043680270D7 +:1019F0001B680BB1052118477047000070B590F8BF +:101A00004C30044613B1002380F84C3004F15C02E2 +:101A1000204601F0CDF963689B68B3B994F85C3057 +:101A200013F0600535D00021204601F033FC002181 +:101A3000204601F025FC63681B6813B1062120468F +:101A40009847062384F84C3070BD204698470028FC +:101A5000E4D0B4F86230626D9A4288BF636594F94D +:101A60005C30656D002B4FF0200380F20381002D68 +:101A700000F0F280092284F84C2083F311880021C1 +:101A80002046D4E91423FFF773FF002383F3118862 +:101A9000DAE794F85D2003F07F0343EA022340F283 +:101AA0000232934200F0C58021D8B3F5807F48D040 +:101AB0000DD8012B3FD0022B00F09380002BB2D128 +:101AC00004F16402226502226265A365C1E7B3F5F1 +:101AD000817F00F09B80B3F5407FA4D194F85E3005 +:101AE000012BA0D1B4F8643043F0020332E0B3F527 +:101AF000006F4DD017D8B3F5A06F31D0A3F5C063F8 +:101B0000012B90D86368204694F85E205E6894F8B4 +:101B10005F10B4F86030B047002884D04368236574 +:101B2000036863651AE0B3F5106F36D040F60242E1 +:101B300093427FF478AF5C4B2365022363650023F7 +:101B4000C3E794F85E30012B7FF46DAFB4F86430D6 +:101B500023F00203A4F86430C4E91455A56578E7BE +:101B6000B4F85C30B3F5A06F0ED194F85E30204627 +:101B700084F8663001F062F863681B6813B10121D4 +:101B800020469847032323700023C4E914339CE7BD +:101B900004F1670323650123C3E72378042B10D1E5 +:101BA000202383F311882046FFF7C4FE85F31188B4 +:101BB0000321636884F8675021701B680BB12046CD +:101BC000984794F85E30002BDED084F86730042309 +:101BD000237063681B68002BD6D0022120469847EB +:101BE000D2E794F8603020461D0603F00F010AD5B5 +:101BF00001F0D0F8012804D002287FF414AF2B4B59 +:101C00009AE72B4B98E701F0B7F8F3E794F85E30CA +:101C1000002B7FF408AF94F8603013F00F01B3D0BD +:101C20001A06204602D501F049FBADE701F03CFB66 +:101C3000AAE794F85E30002B7FF4F5AE94F860309C +:101C400013F00F01A0D01B06204602D501F022FBA5 +:101C50009AE701F015FB97E7142284F84C2083F3F0 +:101C600011882B462A4629462046FFF76FFE85F34A +:101C70001188E9E65DB1152284F84C2083F31188C0 +:101C800000212046D4E91423FFF760FEFDE60B2275 +:101C900084F84C2083F311882B462A462946204697 +:101CA000FFF766FEE3E700BFA03C0008983C000891 +:101CB0009C3C000838B590F84C300446002B3ED0D0 +:101CC000063BDAB20F2A34D80F2B32D8DFE803F004 +:101CD0003731310822323131313131313131373719 +:101CE000456DB0F862309D4214D2C3681B8AB5FBC3 +:101CF000F3F203FB12556DB9202383F311882B46B1 +:101D00002A462946FFF734FE85F311880A2384F812 +:101D10004C300EE0142384F84C30202383F31188D8 +:101D2000002320461A461946FFF710FE002383F3CE +:101D3000118838BD836D03B198470023E7E7002180 +:101D4000204601F0A7FA0021204601F099FA6368C5 +:101D50001B6813B10621204698470623D7E70000E9 +:101D600010B590F84C300446142B29D017D8062B08 +:101D700005D001D81BB110BD093B022BFBD80021B7 +:101D8000204601F087FA0021204601F079FA6368C5 +:101D90001B6813B1062120469847062319E0152B2E +:101DA000E9D10B2380F84C30202383F311880023E2 +:101DB0001A461946FFF7DCFD002383F31188DAE7A2 +:101DC000C3689B695B68002BD5D1836D03B19847CD +:101DD000002384F84C30CEE7024B0022C3E90033E5 +:101DE0009A60704740260220002382680374054BE6 +:101DF0001B6899689142FBD25A6803604260106088 +:101E0000586070474026022008B5202383F31188CC +:101E1000037C032B05D0042B0DD02BB983F3118841 +:101E200008BD436900221A604FF0FF334361FFF79A +:101E3000DBFF0023F2E7D0E9003213605A60F3E7DA +:101E4000002382680374054B1B6899689142FBD894 +:101E50005A68036042601060586070474026022054 +:101E6000054B196908741868026853601A60186194 +:101E700001230374FEF75ABA402602204B1C30B5EA +:101E8000044687B00A4D10D02B6901A8094A00F01A +:101E900025F92046FFF7E4FF049B13B101A800F0E9 +:101EA00059F92B69586907B030BDFFF7D9FFF8E73A +:101EB00040260220091E000838B50C4D0446416139 +:101EC0002B6981689A68914203D8BDE83840FFF7D2 +:101ED0008BBF1846FFF7B4FF01232C610146237422 +:101EE0002046BDE83840FEF721BA00BF4026022058 +:101EF000044B1A681B6990689B68984294BF002045 +:101F0000012070474026022010B5084C2368206944 +:101F10001A6854602260012223611A74FFF790FF4F +:101F200001462069BDE81040FEF700BA40260220B5 +:101F300008B5FFF7DDFF18B1BDE80840FFF7E4BFC3 +:101F400008BD0000FFF7E0BFFEE7000010B50C4C35 +:101F5000FFF742FF00F0B4F880220A49204600F063 +:101F60003BF8012344F8180C037400F075FC0023BF +:101F700083F3118862B60448BDE8104000F04CB805 +:101F800068260220A43C0008B43C000800F01CB9FC +:101F9000EFF3118020B9EFF30583202282F311883B +:101FA0007047000010B530B9EFF30584C4F308049E +:101FB00014B180F3118810BDFFF7BAFF84F31188C4 +:101FC000F9E70000034A516853685B1A9842FBD84E +:101FD000704700BF001000E082600222028270475A +:101FE0008368A3F17C0243F80C2C026943F83C2C73 +:101FF000426943F8382C074A43F81C2CC268A3F105 +:10200000180043F8102C022203F8082C002203F8D1 +:10201000072C70474503000810B5202383F311886F +:10202000FFF7DEFF00210446FFF746FF002383F39E +:102030001188204610BD0000024B1B6958610F201B +:10204000FFF70EBF40260220202383F31188FFF7FD +:10205000F3BF000008B50146202383F31188082050 +:10206000FFF70CFF002383F3118808BD49B1064B2D +:1020700042681B6918605A60136043600420FFF7D0 +:10208000FDBE4FF0FF3070474026022003689842A3 +:1020900006D01A680260506018465961FFF7A4BE66 +:1020A0007047000038B504460D462068844200D1D0 +:1020B00038BD036823605C604561FFF795FEF4E777 +:1020C000054B4FF0FF3103F11402C3E90522002252 +:1020D000C3E90712704700BF4026022070B51C4EAE +:1020E00005460C46C0E9032301F0E6FA334653F8EF +:1020F000142F9A420DD130620A2C2CBF00190A30DD +:102100002A60C5E90124C6E90555BDE8704001F023 +:10211000C1BA316A431AE31838BF1C469368A34218 +:1021200002D9081901F0C4FA73699A6894420CD86C +:102130005A68AC602B606A6015609A685D60121B1B +:102140009A604FF0FF33F36170BDA41A1B68ECE78F +:102150004026022038B51B4C636998420DD0816837 +:10216000D0E9003213605A600022C2609A680A44C3 +:102170009A604FF0FF33E36138BD036822460021C7 +:1021800042F8143F93425A60C16003D1BDE8384021 +:1021900001F088BA9A688168256A0A449A6001F059 +:1021A0008BFA6369411B9A688A42E5D9AB181D1AFC +:1021B000206A092D98BF01F10A02BDE83840104499 +:1021C00001F076BA402602202DE9F041184C002794 +:1021D00004F11406656901F06FFA236AAA68C11A4E +:1021E0008A4215D81344D5F80C802362D5E9003211 +:1021F00013605A606369EF60B34201D101F052FA93 +:1022000087F311882869C047202383F31188E1E709 +:102210006169B14209D013441B1ABDE8F0410A2B91 +:102220002CBFC0180A3001F043BABDE8F08100BFEE +:102230004026022000207047FEE7000070470000A3 +:102240004FF0FF307047000002290CD0032904D062 +:102250000129074818BF00207047032A05D8054800 +:1022600000EBC2007047044870470020704700BF71 +:10227000983D0008482202204C3D000870B59AB0F5 +:1022800005460846144601A900F0C2F801A8FEF769 +:102290009BFD431C0022C6B25B001046C5E900341A +:1022A00023700323023404F8013C01ABD1B20234A1 +:1022B0008E4201D81AB070BD13F8011B013204F828 +:1022C000010C04F8021CF1E708B5202383F3118800 +:1022D0000348FFF771FA002383F3118808BD00BF9C +:1022E000F827022090F85C3003F01F02012A07D182 +:1022F00090F85D200B2A03D10023C0E9143315E0C8 +:1023000003F06003202B08D1B0F860302BB990F8AF +:102310005D20212A03D81F2A04D8FFF72FBA222ACA +:10232000EBD0FAE7034A0265072242658365012084 +:10233000704700BF3F22022007B5052917D8DFE804 +:1023400001F0191603191920202383F31188104A6C +:1023500001210190FFF7D4FA019802210D4AFFF7FD +:10236000CFFA0D48FFF7F4F9002383F3118803B087 +:102370005DF804FB202383F311880748FFF7BEF9BB +:10238000F2E7202383F311880348FFF7D5F9EBE741 +:10239000EC3C0008103D0008F827022038B50C4D31 +:1023A0000C4C2A460C4904F10800FFF767FF05F1C1 +:1023B000CA0204F110000949FFF760FF05F5CA726F +:1023C00004F118000649BDE83840FFF757BF00BFC9 +:1023D000D030022048220220CC3C0008D63C000825 +:1023E000E13C000870B5044608460D46FEF7ECFCDB +:1023F000C6B22046013403780BB9184670BD324688 +:102400002946FEF7CDFC0028F3D10120F6E70000B5 +:102410002DE9F84F05460C46FEF7D6FC2C49C6B20E +:102420002846FFF7DFFF08B10536F6B229492846EE +:10243000FFF7D8FF08B11036F6B2632E0DD8DFF8DB +:102440009080DFF89090244FDFF894A0DFF894B0EC +:102450002E7846B92670BDE8F88F29462046BDE89B +:10246000F84F01F0C3BB252E2ED107224146284646 +:10247000FEF796FC70B9DBF8003007350C3444F8F1 +:102480000C3CDBF8043044F8083CDBF8083044F836 +:10249000043CDDE7082249462846FEF781FC98B94E +:1024A000A21C0E4B197802320909C95D02F8041CFE +:1024B00013F8011B01F00F015345C95D02F8031C1D +:1024C000F0D118340835C3E7013504F8016BBFE7D4 +:1024D000B83D0008E13C0008CD3D000820F4F01FA5 +:1024E0002CF4F01FC03D0008BFF34F8F024AD368A1 +:1024F000DB03FCD4704700BF003C024008B5074B2B +:102500001B7853B9FFF7F0FF054B1A69002A04DA6C +:10251000044A5A6002F188325A6008BD2E33022004 +:10252000003C02402301674508B5054B1B7833B9D1 +:10253000FFF7DAFF034A136943F00043136108BD54 +:102540002E330220003C02400B28F0B516D80C4C6C +:102550000C4923787BB90E460B4D0C234FF00062DB +:10256000013B55F8047B46F8042B13F0FF033A4473 +:10257000F6D10123237051F82000F0BD0020FCE7C4 +:102580006033022030330220E03D0008014B53F855 +:1025900020007047E03D00080C2070470B2810B564 +:1025A000044601D9002010BDFFF7CEFF064B53F8BB +:1025B00024301844C21A0BB90120F4E71268013222 +:1025C000F0D1043BF6E700BFE03D00080B2838B52A +:1025D000044628D8FFF7DCFC0546FFF785FF2046B8 +:1025E000FFF78CFF114AF323D360E300DBB243F41F +:1025F000007343F002031361136943F480331361E2 +:10260000FFF772FFFFF7A0FF094B53F8241000F00B +:10261000E9F82846FFF788FFFFF7C4FC2046BDE82D +:102620003840FFF7BBBF002038BD00BF003C024070 +:10263000E03D000812F001032DE9F04105460E4689 +:1026400014464BD18218B2F1026F61D8314B1B682E +:1026500013F001035CD0FFF79BFC2F4FFFF74EFFF9 +:10266000F323314640F20128FB60FFF73DFF032CC6 +:1026700018D824F001046D1A274E40F201180C44BA +:10268000A14205EB010733692AD123F0010333612D +:10269000FFF74AFFFFF786FC0120BDE8F081043C0C +:1026A0000435E4E7AB07E4D13B6923F440733B61B5 +:1026B0003B6943EA08033B6151F8046B2E60BFF3AA +:1026C0004F8FFFF711FF2B689E42E8D03B6923F044 +:1026D00001033B61FFF728FFFFF764FC0020DCE704 +:1026E00023F440733361336943EA080333610B8891 +:1026F0003B80BFF34F8FFFF7F7FE3F88BFB231F843 +:10270000023BBB42BCD0336923F001033361E1E7F4 +:102710001846C2E700380240003C0240084908B5AC +:102720000B7828B11BB9FFF7E9FE01230B7008BD38 +:10273000002BFCD00870BDE80840FFF7F5BE00BFD5 +:102740002E3302200244074BD2B210B5904200D182 +:1027500010BD441C00B253F8200041F8040BE0B255 +:10276000F4E700BF502800400F4B30B51C6F240425 +:1027700007D41C6F44F400741C671C6F44F40044BD +:102780001C670A4C02442368D2B243F4807323606E +:10279000074B904200D130BD441C51F8045B00B29D +:1027A00043F82050E0B2F4E70038024000700040E7 +:1027B0005028004007B5012201A90020FFF7C2FF01 +:1027C000019803B05DF804FB13B50446FFF7F2FF70 +:1027D000A04205D0012201A900200194FFF7C4FF07 +:1027E00002B010BD0144BFF34F8F064B884204D3A3 +:1027F000BFF34F8FBFF36F8F7047C3F85C02203079 +:10280000F4E700BF00ED00E000207047034B1A68BA +:102810001AB9034AD2F874281A6070476433022048 +:102820000030024008B5FFF7F1FF024B1868C0F313 +:10283000407008BD64330220EFF309830549683313 +:102840004A6B22F001024A6383F30988002383F371 +:102850001188704700EF00E0202080F3118862B6F5 +:102860000D4B0E4AD96821F4E0610904090C0A43B2 +:102870000B49DA60D3F8FC2042F08072C3F8FC20E8 +:10288000084AC2F8B01F116841F00101116010221E +:10289000DA7783F82200704700ED00E00003FA05C4 +:1028A00055CEACC5001000E0202310B583F311888D +:1028B0000E4B5B6813F4006314D0F1EE103AEFF3A3 +:1028C00009844FF08073683CE361094BDB6B23663E +:1028D00084F30988FFF70CFB10B1064BA36110BD10 +:1028E000054BFBE783F31188F9E700BF00ED00E03B +:1028F00000EF00E0570300085A03000870B5BFF36B +:102900004F8FBFF36F8F1A4A0021C2F85012BFF3E6 +:102910004F8FBFF36F8F536943F400335361BFF39D +:102920004F8FBFF36F8FC2F88410BFF34F8FD2F871 +:10293000803043F6E074C3F3C900C3F34E335B0148 +:1029400003EA0406014646EA81750139C2F860527D +:10295000F9D2203B13F1200FF2D1BFF34F8F53690F +:1029600043F480335361BFF34F8FBFF36F8F70BD5C +:1029700000ED00E0FEE700000A4B0B480B4A9042D6 +:102980000BD30B4BC11EDA1C121A22F003028B422E +:1029900038BF00220021FEF71FBA53F8041B40F88D +:1029A000041BECE7E03F0008783402207834022072 +:1029B000783402207047000070B5D0E91B43002234 +:1029C0004FF0FF359E6804EB42135101D3F8000924 +:1029D000002805DAD3F8000940F08040C3F8000968 +:1029E000D3F8000B002805DAD3F8000B40F0804044 +:1029F000C3F8000B013263189642C3F80859C3F8B4 +:102A0000085BE0D24FF00113C4F81C3870BD000021 +:102A10001D4B03EB8002D2F80CC02DE9F043DCF82B +:102A20001420461CDD6ED2F800E005EB063605EBFF +:102A30004018516871450AD30122D5F8343802FA9A +:102A400000F023EA0000C5F83408BDE8F083AEEBDF +:102A50000103BCF81040A34228BF2346D8F8184908 +:102A6000A4B2B3EB840FF0D89468A4F1040959F828 +:102A7000047F3760A4EB09071F44042FF7D81C44D8 +:102A80000B4494605360D4E768330220890141F01D +:102A90002001016103699B06FCD41220FFF792BA62 +:102AA00010B5054C2046FEF709FF4FF0A043E36642 +:102AB000024B236710BD00BF68330220343E00087C +:102AC00070B503780546012B50D12A4BC46E98424D +:102AD0001BD1294B0E2143205A6B42F080025A63CE +:102AE0005A6D42F080025A655A6D5A6942F080026E +:102AF0005A615A6922F080025A615B6900F0E8FB72 +:102B00001E4BE3601E4BC4F800380023EE6EC4F881 +:102B1000003EC02323604FF40413A3633369002BEA +:102B2000FCDA01230C203361FFF74CFA3369DB0731 +:102B3000FCD41220FFF746FA3369002BFCDA00269A +:102B40002846A660FFF738FF6B68C4F81068DB689A +:102B5000C4F81468C4F81C684BB90A4BA3614FF061 +:102B6000FF336361A36843F00103A36070BD064BAC +:102B7000F4E700BF683302200038024040140040F0 +:102B800003002002003C30C0083C30C0F8B5C46EE1 +:102B9000054600214FF000662046FFF777FF296FBA +:102BA00000234FF001128F684FF0FF30C4F8343823 +:102BB000C4F81C2804EB431201339F42C2F8006999 +:102BC000C2F8006BC2F80809C2F8080BF2D20B6811 +:102BD000EA6E6B67636210231361166916F01006C4 +:102BE000FBD11220FFF7EEF9D4F8003823F4FE638E +:102BF000C4F80038A36943F4402343F01003A361F1 +:102C00000923C4F81038C4F814380A4BEB604FF0AD +:102C1000C043C4F8103B084BC4F8003BC4F810692B +:102C2000C4F800396B6F03F1100243F480136A6734 +:102C3000A362F8BD103E000840800010C26E90F8FC +:102C40006610D2F8003823F4FE6343EA0113C2F899 +:102C5000003870472DE9F84300EB8103C56E0C4640 +:102C60008046DA680FFA81F94801166806F0030613 +:102C7000731E022B05EB41134FF0000194BFB60405 +:102C8000384EC3F8101B4FF0010104F1100398BF38 +:102C900006F1805601FA03F3916998BF06F50046E4 +:102CA00000293AD0578A04F15801374349016F503F +:102CB000D5F81C180B430021C5F81C382B18012728 +:102CC000C3F81019A7405369611E9BB3138A928BF6 +:102CD0009B08012A88BF5343D8F87420981842EA09 +:102CE000034301F140022146C8F87400284605EB71 +:102CF00082025360FFF7CAFE08EB8900C3681B8A93 +:102D000043EA845348341E4364012E51D5F81C38DD +:102D10001F43C5F81C78BDE8F88305EB4917D7F8C1 +:102D2000001B21F40041C7F8001BD5F81C1821EA4C +:102D30000303C0E704F13F030B4A2846214605EB95 +:102D400083035A60FFF7A2FE05EB4910D0F8003963 +:102D500023F40043C0F80039D5F81C3823EA0707EC +:102D6000D7E700BF0080001000040002026F126865 +:102D70004267FFF721BE00005831C36E49015B581E +:102D800013F4004004D013F4001F0CBF02200120F4 +:102D9000704700004831C36E49015B5813F400408E +:102DA00004D013F4001F0CBF022001207047000064 +:102DB00000EB8101CB68196A0B6813604B685360A4 +:102DC0007047000000EB810330B5DD68AA69136825 +:102DD000D36019B9402B84BF402313606B8A1468F9 +:102DE000C26E1C4402EB4110013C09B2B4FBF3F487 +:102DF0006343033323F0030343EAC44343F0C04374 +:102E0000C0F8103B2B6803F00303012B0ED1D2F85E +:102E1000083802EB411013F4807FD0F8003B14BF58 +:102E200043F0805343F00053C0F8003B02EB4112E3 +:102E3000D2F8003B43F00443C2F8003B30BD000031 +:102E40002DE9F041244D0446EE6E06EB4013D3F815 +:102E5000087B3807C3F8087B0AD5D6F81438190759 +:102E600006D505EB840321462846DB685B68984756 +:102E7000FA071FD5D6F81438DB071BD505EB8403FA +:102E8000D968CCB98B69488A5A68B2FBF0F600FB66 +:102E900016228AB91868DA6890420DD2121AC3E96C +:102EA0000024202383F311880B482146FFF78AFF73 +:102EB00084F31188BDE8F081012303FA04F26B89E1 +:102EC00023EA02036B81CB68002BF3D02146024832 +:102ED000BDE8F041184700BF6833022000EB8103D2 +:102EE0004A0170B5DD68C36E6C692668E66056BB42 +:102EF0001A444FF40020C2F810092A6802F00302B5 +:102F0000012A0AB20ED1D3F8080803EB421410F4D8 +:102F1000807FD4F8000914BF40F0805040F000508A +:102F2000C4F8000903EB4212D2F8000940F0044053 +:102F3000C2F800090122D3F8340802FA01F1014372 +:102F4000C3F8341870BD19B9402E84BF40202060EA +:102F500020681A442E8A8419013CB4FBF6F440EA36 +:102F6000C44040F00050C6E7F8B504461E48C56EA0 +:102F700005EB4413D3F80869F107C3F8086917D5BE +:102F8000D5F81038DA0713D500EB8403D9684B69FC +:102F90001F68DA68974218D2D21B00271A605F6058 +:102FA000202383F311882146FFF798FF87F31188C8 +:102FB000330617D50123D5F83428A340134211D086 +:102FC0002046BDE8F840FFF723BD012303FA04F2D1 +:102FD000038923EA020303818B68002BE8D0214692 +:102FE0009847E5E7F8BD00BF683302202DE9F74FA9 +:102FF000A24CE66E7569B3691D4015F48058756181 +:1030000007D02046FEF7C6FC03B0BDE8F04FFFF73F +:103010004BBC002D12DAD6F8003E9F0705D0D6F83B +:10302000003E23F00303C6F8003ED6F80438934868 +:1030300023F00103C6F80438FEF7D6FC280505D5B1 +:103040008E48FFF7B9FC8D48FEF7BEFCA9040CD5ED +:10305000D6F8083813F0060FF36823F470530CBF4A +:1030600043F4105343F4A053F3602A0704D5636874 +:10307000DB680BB181489847EB0200F18A80AF0210 +:1030800027D5D4F86C9000274FF0010ADFF8ECB197 +:1030900009EB4712D2F8003B03F44023B3F5802F2D +:1030A00011D1D2F8003B002B0DDA62890AFA07F33E +:1030B00022EA0303638104EB8703DB68DB6813B157 +:1030C0003946584698470137236FFFB29B689F42A5 +:1030D000DED9E80618D5E76E3A6AC2F30A1002F0A4 +:1030E0000F0302F4F012B2F5802F00F09C80B2F5CD +:1030F000402F09D104EB8303002207F58057DB68DA +:103100001B6A904240F082802B03D6F818481DD5E8 +:10311000E70302D50020FFF793FEA60302D50120A6 +:10312000FFF78EFE600302D50220FFF789FE210320 +:1031300002D50320FFF784FEE20202D50420FFF748 +:103140007FFEA30202D50520FFF77AFE6F037FF50D +:103150005BAFE60702D50020FFF706FFA50702D503 +:103160000120FFF701FF600702D50220FFF7FCFEF8 +:10317000210702D50320FFF7F7FEE20602D504205F +:10318000FFF7F2FEA3067FF53FAF0520FFF7ECFE49 +:103190003AE7E36E00274FF0010ADFF8E0B0019351 +:1031A000236F5FFA87F99B6899453FF668AF019BEB +:1031B00003EB4913D3F8002902F44022B2F5802F23 +:1031C00022D1D3F80029002A1EDAD3F8002942F0D0 +:1031D0009042C3F80029D3F80029002AFBDB4946B6 +:1031E000E06EFFF753FC22890AFA09F322EA03038F +:1031F000238104EB8903DB689B6813B14946584679 +:1032000098474846FFF704FC0137C9E7910701D109 +:10321000D7F80080072A02F101029CBF03F8018B56 +:103220004FEA18286DE7023307F5805704EB830255 +:103230005268D2F818C0DCF80820DCE9001CA1EBC9 +:103240000C0C002188420AD104EB830463689B695B +:103250009A6802449A605A6802445A6054E711F02E +:10326000030F01D1D7F800808C4501F1010184BF23 +:1032700002F8018B4FEA1828E4E700BF6833022008 +:10328000C36E03EB4111D1F8003B43F40013C1F8C6 +:10329000003B7047C36E03EB4111D1F8003943F492 +:1032A0000013C1F800397047C36E03EB4111D1F828 +:1032B000003B23F40013C1F8003B7047C36E03EBDF +:1032C0004111D1F8003923F40013C1F800397047D7 +:1032D000090100F16043012203F56143C9B283F89B +:1032E000001300F01F039A4043099B0003F1604361 +:1032F00003F56143C3F880211A60704730B5043389 +:10330000039C0172002104FB0325C160C0E9065340 +:10331000049B0363059BC0E90000C0E90422C0E9E7 +:103320000842C0E90A11436330BD00000022416A2F +:10333000C260C0E90411C0E90A226FF00101FEF782 +:10334000B1BE0000D0E90432934201D1C2680AB98B +:10335000181D704700207047036919600021C2687A +:103360000132C260C269134482699342036124BF7F +:10337000436A0361FEF78ABE38B504460D46E3682A +:103380003BB162690020131D1268A3621344E3621B +:1033900007E0237A33B929462046FEF767FE002866 +:1033A000EDDA38BD6FF00100FBE70000C368C269C9 +:1033B000013BC3604369134482699342436124BF64 +:1033C000436A436100238362036B03B1184770476C +:1033D00070B52023044683F31188866A3EB9FFF74F +:1033E000CBFF054618B186F31188284670BDA36A45 +:1033F000E26A13F8015B9342A36202D32046FFF70F +:10340000D5FF002383F31188EFE700002DE9F84F83 +:1034100004460E46174698464FF0200989F3118856 +:103420000025AA46D4F828B0BBF1000F09D14146C7 +:103430002046FFF7A1FF20B18BF311882846BDE895 +:10344000F88FD4E90A12A7EB050B521A934528BF4F +:103450009346BBF1400F1BD9334601F1400251F8AE +:10346000040B914243F8040BF9D1A36A403640356E +:103470004033A362D4E90A239A4202D32046FFF7DD +:1034800095FF8AF31188BD42D8D289F31188C9E724 +:1034900030465A46FDF77AFCA36A5E445D445B44BD +:1034A000A362E7E710B5029C0433017204FB032119 +:1034B000C460C0E906130023C0E90A33039B036319 +:1034C000049BC0E90000C0E90422C0E9084243634C +:1034D00010BD0000026A6FF00101C260426AC0E9DB +:1034E00004220022C0E90A22FEF7DCBDD0E9042351 +:1034F0009A4201D1C26822B9184650F8043B0B60C9 +:103500007047002070470000C3680021C269013382 +:10351000C3604369134482699342436124BF436A91 +:103520004361FEF7B3BD000038B504460D46E368BD +:103530003BB1236900201A1DA262E2691344E362D1 +:1035400007E0237A33B929462046FEF78FFD00288D +:10355000EDDA38BD6FF00100FBE700000369196088 +:10356000C268013AC260C26913448269934203612E +:1035700024BF436A036100238362036B03B11847CE +:103580007047000070B520230D460446114683F3B2 +:103590001188866A2EB9FFF7C7FF10B186F311882C +:1035A00070BDA36A1D70A36AE26A01339342A362ED +:1035B00004D3E16920460439FFF7D0FF002080F3EF +:1035C0001188EDE72DE9F84F04460D4690469946DF +:1035D0004FF0200A8AF311880026B346A76A4FB934 +:1035E00049462046FFF7A0FF20B187F311883046F7 +:1035F000BDE8F88FD4E90A073A1AA8EB0607974204 +:1036000028BF1746402F1BD905F1400355F8042B5E +:103610009D4240F8042BF9D1A36A40364033A3629F +:10362000D4E90A239A4204D3E16920460439FFF71A +:1036300095FF8BF311884645D9D28AF31188CDE7DF +:1036400029463A46FDF7A2FBA36A3D443E443B446B +:10365000A362E5E7D0E904239A4217D1C3689BB17E +:10366000836A8BB1043B9B1A0ED01360C368013B85 +:10367000C360C3691A4483699A42026124BF436AE2 +:103680000361002383620123184670470023FBE790 +:1036900000F094B84FF08043002258631A61022270 +:1036A000DA6070474FF080430022DA607047000014 +:1036B0004FF08043586370474FF08043586A70471B +:1036C0004B6843608B688360CB68C3600B69436160 +:1036D0004B6903628B6943620B68036070470000AB +:1036E00008B52C4B40F2FF712B481A690A431A6146 +:1036F0001A6922F4FF6222F007021A611A691A6B32 +:103700000A431A631A6D0A431A65244A1B6D11464F +:10371000FFF7D6FF00F5806002F11C01FFF7D0FF34 +:1037200000F5806002F13801FFF7CAFF00F5806004 +:1037300002F15401FFF7C4FF00F5806002F170014F +:10374000FFF7BEFF00F5806002F18C01FFF7B8FFC4 +:1037500000F5806002F1A801FFF7B2FF00F580607C +:1037600002F1C401FFF7ACFF00F5806002F1E00157 +:10377000FFF7A6FF00F5806002F1FC01FFF7A0FF54 +:1037800002F58C7100F58060FFF79AFFBDE80840F4 +:1037900000F08AB80038024000000240403E0008B5 +:1037A00008B500F003FAFEF7D1FBFFF72FF8BDE8EC +:1037B0000840FEF7F3BD0000704700000F4B1A6C85 +:1037C00042F001021A641A6E42F001021A660C4AB3 +:1037D0001B6E936843F0010393604FF080436B22AC +:1037E0009A624FF0FF32DA6200229A615A63DA601D +:1037F0005A6001225A611A60704700BF00380240C7 +:10380000002004E04FF0804208B51169D3680B40F6 +:10381000D9B29B076FEA0101116107D5202383F319 +:103820001188FEF7B3FB002383F3118808BD000065 +:103830001B4B4FF0FF3000211A696FEA42526FEACA +:1038400052521A611A69C2F30A021A611A695A6954 +:1038500058615A6959615A691A6A62F080521A624B +:103860001A6A02F080521A621A6A5A6A58625A6ACE +:1038700059625A6A0B4A106840F480701060186FE1 +:1038800000F44070B0F5007F03D04FF4803018672B +:103890001967536823F40073536000F05FB900BFE9 +:1038A0000038024000700040364B4FF44041364A29 +:1038B0001A64364A11601A6842F001021A601A68E6 +:1038C0009207FCD59A6822F003029A602D4B9A6801 +:1038D00012F00C02FBD1196801F0F90119609A602D +:1038E0001A6842F480321A601A689003FCD55A6F45 +:1038F00042F001025A67234B5A6F9107FCD5244AC4 +:103900005A601A6842F080721A60204B5A6852045A +:10391000FCD51A6842F480321A605A68D003FCD58C +:103920001A6842F400321A60184A53689903FCD5A9 +:10393000144B1A689201FCD5164A9A6040F20112A3 +:10394000C3F88C200022C3F8902040F20733124ABB +:103950001360136803F00F03072BFAD1094B9A6821 +:1039600042F002029A609A6802F00C02082AFAD128 +:103970005A6C42F480425A645A6E42F480425A664B +:103980005B6E704700380240000400100070004079 +:10399000086C400900948838003C0240074A08B58A +:1039A000536903F00103536123B1054A13680BB156 +:1039B00050689847BDE80840FEF776BF003C0140DC +:1039C000F8330220074A08B5536903F00203536134 +:1039D00023B1054A93680BB1D0689847BDE8084009 +:1039E000FEF762BF003C0140F8330220074A08B5E9 +:1039F000536903F00403536123B1054A13690BB102 +:103A000050699847BDE80840FEF74EBF003C0140B2 +:103A1000F8330220074A08B5536903F008035361DD +:103A200023B1054A93690BB1D0699847BDE80840B6 +:103A3000FEF73ABF003C0140F8330220074A08B5C0 +:103A4000536903F01003536123B1054A136A0BB1A4 +:103A5000506A9847BDE80840FEF726BF003C014089 +:103A6000F8330220164B10B55C6904F478725A6181 +:103A7000A30604D5134A936A0BB1D06A984760062F +:103A800004D5104A136B0BB1506B9847210604D52F +:103A90000C4A936B0BB1D06B9847E20504D5094AE9 +:103AA000136C0BB1506C9847A30504D5054A936C71 +:103AB0000BB1D06C9847BDE81040FEF7F5BE00BFD3 +:103AC000003C0140F8330220194B10B55C6904F446 +:103AD0007C425A61620504D5164A136D0BB1506DD4 +:103AE0009847230504D5134A936D0BB1D06D9847C1 +:103AF000E00404D50F4A136E0BB1506E9847A10431 +:103B000004D50C4A936E0BB1D06E9847620404D56D +:103B1000084A136F0BB1506F9847230404D5054A28 +:103B2000936F0BB1D06F9847BDE81040FEF7BCBE55 +:103B3000003C0140F833022008B50348FDF7D8FAED +:103B4000BDE80840FEF7B0BED423022008B5FFF759 +:103B500059FEBDE80840FEF7A7BE0000062108B5E3 +:103B60000846FFF7B5FB06210720FFF7B1FB06214A +:103B70000820FFF7ADFB06210920FFF7A9FB06216E +:103B80000A20FFF7A5FB06211720FFF7A1FB06215E +:103B90002820FFF79DFB07211C20FFF799FB0C2134 +:103BA0005220BDE80840FFF793BB000008B5FFF7BF +:103BB0003FFE00F00DF8FDF7ADFCFDF77DFEFDF7D3 +:103BC00055FDFFF7F9FDBDE80840FFF761BD0000B6 +:103BD0000023054A19460133102BC2E9001102F1F6 +:103BE0000802F8D1704700BFF8330220034611F8ED +:103BF000012B03F8012B002AF9D1704753544D33A0 +:103C000032463F3F3F3F3F3F0053544D33324637EC +:103C10005B347C355D780053544D333246375B3628 +:103C20007C375D7800000000F8270220D4230220B2 +:103C300000960000000000000000000000000000EE +:103C4000000000000000000000000000DD1400087B +:103C5000C914000805150008F1140008FD14000837 +:103C6000E9140008D5140008C11400081115000853 +:103C700000000000E9150008D5150008111600081D +:103C8000FD15000809160008F5150008E1150008E3 +:103C9000CD1500081D1600080000000001000000FE +:103CA000000000006D61696E0000000069646C65D1 +:103CB00000000000AC3C000880260220F82702200B +:103CC00001000000491F00080000000041726475F7 +:103CD00050696C6F740025424F415244252D424C6F +:103CE000002553455249414C2500000002000000C8 +:103CF000000000000518000871180008400040008E +:103D0000A0300220B03002200200000000000000BD +:103D10000300000000000000B518000800000000CB +:103D200010000000C0300220000000000100000070 +:103D3000000000006833022001010200392300085E +:103D400049220008E5220008C922000843000000BB +:103D5000543D000809024300020100C0320904007A +:103D600000010202010005240010010524010001E8 +:103D7000042402020524060001070582030800FF4F +:103D800009040100020A00000007050102400000CA +:103D9000070581024000000012000000A03D00085D +:103DA00012011001020000400912415700020102F5 +:103DB000030100000403090425424F415244250039 +:103DC0004D6174656B463736352D534500303132C1 +:103DD00033343536373839414243444546000000D4 +:103DE00000800000008000000080000000800000D3 +:103DF00000000200000004000000040000000400B5 +:103E000000000400000004000000040000000400A2 +:103E100000000000FD190008B51C0008611D000825 +:103E200040004000E0330220E033022001000000A7 +:103E3000F033022080000000400100000500000077 +:103E40000000802A00000000AAAAAAAA00000024FC +:103E5000FFFF00000000000000A00A0000000001B9 +:103E600000000000AAAAAAAA00000001FFFF0000AB +:103E70000000000000000000000100000000000041 +:103E8000AAAAAAAA00010000FFFF0000000000008B +:103E9000000000000040100000000000AAAAAAAA2A +:103EA00000400000FFFB00000000000000000000D8 +:103EB0000081420000000000AAAAAAAA0040410016 +:103EC000EFFF00000000008008000000000000007C +:103ED00000000000AAAAAAAA00000000FFFF00003C +:103EE00000000000000000000000000000000000D2 +:103EF000AAAAAAAA00000000FFFF0000000000001C +:103F0000000000000000000000000000AAAAAAAA09 +:103F100000000000FFFF00000000000000000000A3 +:103F20000000000000000000AAAAAAAA00000000E9 +:103F3000FFFF000000000000000000000000000083 :103F40000000000000000000000000000000000071 -:103F500000000000000000008F00000000000000D2 -:103F600000801E00FF00000000000000E43B00088D -:103F70003F00000049040000F13B00083F00000042 -:103F800051040000FF3B00083F00000000960000C5 -:103F90000000080004000000943D0008000000003C -:103FA0000000000000000000000000000000000011 -:043FB000000000000D +:103F50000000000000000000000000000000000061 +:103F60000000000000000000000000000000000051 +:103F700000000000000000008F00000000000000B2 +:103F800000801E0000000000FF0000000000000094 +:103F9000FC3B00083F00000049040000093C000809 +:103FA0003F00000051040000173C00083F000000E3 +:103FB00000960000000008009600000000080000C5 +:103FC00004000000B43D00080000000000000000F4 +:103FD00000000000000000000000000000000000E1 :00000001FF diff --git a/Tools/bootloaders/MatekF765-Wing-bdshot_bl.bin b/Tools/bootloaders/MatekF765-Wing-bdshot_bl.bin new file mode 100755 index 00000000000..55a0eff4253 Binary files /dev/null and b/Tools/bootloaders/MatekF765-Wing-bdshot_bl.bin differ diff --git a/Tools/bootloaders/MatekF765-Wing-bdshot_bl.hex b/Tools/bootloaders/MatekF765-Wing-bdshot_bl.hex new file mode 100644 index 00000000000..a9a2d0a81ae --- /dev/null +++ b/Tools/bootloaders/MatekF765-Wing-bdshot_bl.hex @@ -0,0 +1,1024 @@ +:020000040800F2 +:100000000006022001020008B50F0008350F0008A5 +:100010008D0F0008350F0008610F0008030200086B +:100020000302000803020008030200083528000844 +:10003000030200080302000803020008030200088C +:10004000030200080302000803020008030200087C +:10005000030200080302000899390008C1390008AA +:10006000E9390008113A0008393A0008030200088B +:10007000030200080302000803020008030200084C +:10008000030200080302000803020008030200083C +:10009000030200080302000803020008613A000896 +:1000A000030200080302000803020008030200081C +:1000B000493B00080302000803020008030200088D +:1000C00003020008030200080302000803020008FC +:1000D00003020008030200080302000803020008EC +:1000E000C53A0008030200080302000803020008E2 +:1000F00003020008030200080302000803020008CC +:1001000003020008030200080302000803020008BB +:1001100003020008030200080302000803020008AB +:10012000030200080302000803020008030200089B +:10013000030200080302000803020008030200088B +:10014000030200080302000803020008E92F000868 +:10015000030200080302000803020008030200086B +:10016000030200080302000803020008030200085B +:10017000030200080302000803020008030200084B +:100180000302000803020008353B000803020008D0 +:10019000030200080302000803020008030200082B +:1001A000030200080302000803020008030200081B +:1001B000030200080302000803020008030200080B +:1001C00003020008030200080302000803020008FB +:1001D00003020008030200080302000803020008EB +:1001E00003020008030200080302000803020008DB +:1001F00003020008030200080302000803020008CB +:1002000002E000F000F8FEE772B63A4880F3088892 +:10021000394880F3098839484EF60851CEF200017A +:10022000086040F20000CCF200004EF63471CEF2CD +:1002300000010860BFF34F8FBFF36F8F40F20000E3 +:10024000C0F2F0004EF68851CEF200010860BFF314 +:100250004F8FBFF36F8F4FF00000E1EE100A4EF6A4 +:100260003C71CEF200010860062080F31488BFF3D1 +:100270006F8F02F09DFB02F03FFB03F02FFA4FF06F +:1002800055301F491B4A91423CBF41F8040BFAE725 +:100290001C49194A91423CBF41F8040BFAE71A493C +:1002A0001A4A1B4B9A423EBF51F8040B42F8040B0A +:1002B000F8E700201749184A91423CBF41F8040B67 +:1002C000FAE702F057FB03F069FA144C144DAC4204 +:1002D00003DA54F8041B8847F9E700F041F8114CA1 +:1002E000114DAC4203DA54F8041B8847F9E702F0D9 +:1002F0003FBB000000060220002202200000000890 +:100300000000022000060220783F000800220220A0 +:1003100068220220682202207834022000020008AD +:100320000002000800020008000200082DE9F04F5A +:100330002DED108AC1F80CD0D0F80CD0BDEC108A8D +:10034000BDE8F08F002383F311882846A0470020E2 +:1003500001F07AFEFEE701F0F5FD00DFFEE70000A8 +:1003600038B502F04FFA40B1174B6FF07F01002211 +:1003700059720E211A729972DA7202F019FA054650 +:1003800002F04EFA0446D0B9104B9D4219D0013309 +:100390009D4241F2883512BF044600250124002009 +:1003A00002F010FA0CB100F079F800F06BFD00F0EB +:1003B0000DFC284600F0FCF800F070F8F9E7002585 +:1003C000EDE70546EBE700BF00220220010007B081 +:1003D00008B500F0C7FBA0F120035842584108BD02 +:1003E00007B541F21203022101A8ADF8043000F074 +:1003F000D7FB03B05DF804FB38B5202383F31188E5 +:100400001748C3680BB101F0A5FE0023154A4FF44D +:100410007A71134801F062FE002383F31188124CB5 +:10042000236813B12368013B2360636813B16368D9 +:10043000013B63600D4D2B7833B963687BB90220B3 +:1004400000F09AFC322363602B78032B07D163689A +:100450002BB9022000F090FC4FF47A73636038BD32 +:1004600068220220F9030008842302207C22022053 +:10047000084B187003280CD8DFE800F008050208C4 +:10048000022000F06FBC022000F062BC024B002290 +:100490005A6070477C22022084230220F8B53F4B2B +:1004A0003F4A1C461968013177D004339342F9D191 +:1004B0006268A24271D33B4B9B6803F1006303F572 +:1004C000C0339A4269D2002000F09AFB0220FFF765 +:1004D000CFFF354B00211A6C19641A6E19661A6E1B +:1004E0005A6C59645A6E59665A6E5A6942F08002C3 +:1004F0005A615A6922F080025A615A691A6942F0B7 +:1005000000521A611A6922F000521A611B6972B610 +:100510004FF0E023C3F8084DD4E90004BFF34F8F38 +:10052000BFF36F8F214AC2F88410BFF34F8F536916 +:1005300023F480335361BFF34F8FD2F8803043F6FA +:10054000E076C3F3C905C3F34E335B0103EA060C3F +:1005500029464CEA81770139C2F87472F9D2203BFE +:1005600013F1200FF2D1BFF34F8FBFF36F8FBFF3A3 +:100570004F8FBFF36F8F536923F400335361002310 +:10058000C2F85032BFF34F8FBFF36F8F202383F336 +:100590001188854680F308882047F8BD008001084F +:1005A00020800108002202200038024000ED00E017 +:1005B0002DE9F04F93B0B44B2022FF2100900AA800 +:1005C0009D6800F009FCB14A1378A3B90121B04835 +:1005D0001170C360202383F31188C3680BB101F04D +:1005E000B9FD0023AB4A4FF47A71A94801F076FDBA +:1005F000002383F31188009B13B1A74B009A1A6064 +:10060000A64A1378032B03D000231370A24A536029 +:100610004FF0000A009CD3465646D146012000F018 +:10062000A1FB24B19C4B1B68002B00F0268200200C +:1006300000F098FA0390039B002BF2DB012000F0FE +:1006400087FB039B213B1F2BE8D801A252F823F024 +:10065000D1060008F90600088D0700081D060008ED +:100660001D0600081D0600081F080008EF09000805 +:10067000090900086B09000893090008B909000876 +:100680001D060008CB0900081D0600083D0A0008E9 +:10069000710700081D060008810A0008DD06000831 +:1006A000710700081D0600086B0900081D060008F8 +:1006B0001D0600081D0600081D0600081D0600088E +:1006C0001D0600081D0600081D0600088D0700080D +:1006D0000220FFF77DFE002840F0F981009B0221F7 +:1006E00005A8BAF1000F08BF1C4641F21233ADF85D +:1006F000143000F055FA91E74FF47A7000F032FAB6 +:10070000071EEBDB0220FFF763FE0028E6D0013F67 +:10071000052F00F2DE81DFE807F0030A0D10133623 +:100720000523042105A8059300F03AFA17E00421F7 +:100730005548F9E704215A48F6E704215948F3E7F8 +:100740004FF01C08404608F1040800F05BFA042151 +:10075000059005A800F024FAB8F12C0FF2D1012081 +:100760004FF0000900FA07F747EA0B0B5FFA8BFB23 +:1007700000F07EFB26B10BF00B030B2B08BF00240F +:10078000FFF72EFE4AE704214748CDE7002EA5D00B +:100790000BF00B030B2BA1D10220FFF719FE07462C +:1007A00000289BD00120002600F02AFA0220FFF743 +:1007B0005FFE5FFA86F8404600F032FA0446B0B1B8 +:1007C000039940460136A1F140025142514100F0E7 +:1007D00037FA0028EDD1BA46044641F2121302213D +:1007E00005A83E46ADF8143000F0DAF916E72546C4 +:1007F0000120FFF73DFE244B9B68AB4207D92846FA +:1008000000F000FA013040F067810435F3E700257D +:10081000224BBA463E461D701F4B5D60A8E7002E76 +:100820003FF45CAF0BF00B030B2B7FF457AF0220B0 +:10083000FFF71EFE322000F095F9B0F10008FFF638 +:100840004DAF18F003077FF449AF0F4A08EB0503DB +:10085000926893423FF642AFB8F5807F3FF73EAFD4 +:10086000124BB845019323DD4FF47A7000F07AF90A +:100870000390039A002AFFF631AF039A0137019BD8 +:1008800003F8012BEDE700BF0022022080230220A5 +:1008900068220220F9030008842302207C2202201F +:1008A00004220220082202200C22022080220220A0 +:1008B000C820FFF78DFD074600283FF40FAF1F2D1E +:1008C00011D8C5F120020AAB25F003008449424546 +:1008D000184428BF4246019200F058FA019AFF21BD +:1008E0007F4800F079FA4FEAA803C8F387027C49F1 +:1008F0002846019300F078FA064600283FF46DAFD1 +:10090000019B05EB830533E70220FFF761FD00281B +:100910003FF4E4AE00F0C0F900283FF4DFAE00275A +:10092000B846704B9B68BB4218D91F2F11D80A9B41 +:1009300001330ED027F0030312AA134453F8203CCE +:1009400005934046042205A9043700F035FB804694 +:10095000E7E7384600F056F90590F2E7CDF8148045 +:10096000042105A800F01CF902E70023642104A873 +:10097000049300F00BF900287FF4B0AE0220FFF7DB +:1009800027FD00283FF4AAAE049800F06DF9059009 +:10099000E6E70023642104A8049300F0F7F8002898 +:1009A0007FF49CAE0220FFF713FD00283FF496AEC3 +:1009B000049800F069F9EAE70220FFF709FD002832 +:1009C0003FF48CAE00F078F9E1E70220FFF700FD7C +:1009D00000283FF483AE05A9142000F073F9074600 +:1009E0000421049004A800F0DBF83946B9E732206E +:1009F00000F0B8F8071EFFF671AEBB077FF46EAECD +:100A0000384A07EB0903926893423FF667AE02202B +:100A1000FFF7DEFC00283FF461AE27F003074F44E8 +:100A2000B9453FF4A5AE484609F1040900F0EAF8DB +:100A30000421059005A800F0B3F8F1E74FF47A70AF +:100A4000FFF7C6FC00283FF449AE00F025F9002866 +:100A500044D00A9B01330BD008220AA9002000F0E1 +:100A6000C3F900283AD02022FF210AA800F0B4F9E7 +:100A7000FFF7B6FC1C4801F0EDFA13B0BDE8F08FAB +:100A8000002E3FF42BAE0BF00B030B2B7FF426AEA6 +:100A90000023642105A8059300F078F80746002894 +:100AA0007FF41CAE0220FFF793FC804600283FF441 +:100AB00015AEFFF795FC41F2883001F0CBFA0598AE +:100AC00000F018FA46463C4600F0D2F9A6E5064684 +:100AD0004EE64FF0000901E6BA467EE637467CE670 +:100AE0008022022000220220A0860100F7B50C46D9 +:100AF000184E4FF47A71054602FB01F396F9002077 +:100B0000501C0BD11448294601930268176A2246EB +:100B1000B8478442019B03D1002310E0002AF1D0A2 +:100B200096F90020511C01D0012A0DD10B4829460D +:100B30000268166A2246B047844205D10123084A5A +:100B40000120137003B0F0BD4FF4FA7001F082FA87 +:100B50000020F7E710220220F8270220D4230220E9 +:100B6000D0230220002307B5024601210DF1070022 +:100B70008DF80730FFF7BAFF20B19DF8070003B0EA +:100B80005DF804FB4FF0FF30F9E700000A4604214E +:100B900008B5FFF7ABFF80F00100C0B2404208BDCE +:100BA000074B0A4630B41978064B53F821400146EA +:100BB00023682046DD69044BAC4630BC604700BF6B +:100BC000D0230220243C0008A086010070B50A4E04 +:100BD00000240A4D01F0DEFC30802868338883420F +:100BE00008D901F0D1FC2B6804440133B4F5C03FAF +:100BF0002B60F2D370BD00BFD22302208C230220D1 +:100C000001F08ABD00F1006000F5C0300068704757 +:100C100000F10060920000F5C03001F009BD000055 +:100C2000054B1A68054B1B889B1A834202D9104456 +:100C300001F0AABC002070478C230220D22302209E +:100C400038B50446074D29B128682044BDE838402E +:100C500001F0BABC2868204401F09EFC0028F3D0C3 +:100C600038BD00BF8C23022010F0030309D1B0F57A +:100C7000846F04D200F10050A0F57120036818467B +:100C800070470023FBE7000000F10050A0F5712041 +:100C9000D0F8200470470000064991F8243033B1A1 +:100CA00000230822086A81F82430FFF7B1BF012031 +:100CB000704700BF90230220014B1868704700BFA7 +:100CC000002004E0204B0246F0B518681F4BC0F32B +:100CD0000B06000C1F885D68BE4293F9084022D0C5 +:100CE0009F89BE4221D01F8BBE4206D102240C2513 +:100CF00005FB04335D6893F90840B0F5805F16D0BA +:100D000041F20103984208BF5A24013A013D0B46C3 +:100D10000A4493420DD215F9016F581C5EB1034687 +:100D200000F8016CF5E70024E1E70124DFE7412446 +:100D3000EBE7184605E02C2590421D7001D2981C67 +:100D40005C70401AF0BD00BF002004E014220220B5 +:100D5000022803D1024B4FF080629A61704700BFB6 +:100D6000000C0240022803D1024B4FF480629A61CA +:100D7000704700BF000C0240022804D1024A5369A8 +:100D800083F4806353617047000C0240002310B568 +:100D9000934203D0CC5CC4540133F9E710BD00008A +:100DA000013810B510F9013F3BB191F900409C4268 +:100DB00003D11AB10131013AF4E71AB191F90020D7 +:100DC000981A10BD1046FCE703460246D01A12F9E5 +:100DD000011B0029FAD1704702440346934202D016 +:100DE00003F8011BFAE770472DE9F8431F4D14463D +:100DF0000746884695F8242052BBDFF870909CB3D4 +:100E000095F824302BB92022FF2148462F62FFF7A6 +:100E1000E3FF95F824004146C0F1080205EB80008D +:100E2000A24228BF2246D6B29200FFF7AFFF95F844 +:100E30002430A41B17441E449044E4B2F6B2082E9A +:100E400085F82460DBD1FFF727FF0028D7D108E021 +:100E50002B6A03EB82038342CFD0FFF71DFF0028EC +:100E6000CBD10020BDE8F8830120FBE790230220CE +:100E7000024B1A78024B1A70704700BFD023022031 +:100E80001022022038B5154C154D204600F0F0FB1D +:100E90002946204600F018FC2D681248EA6ED2F868 +:100EA000043843F00203C2F8043801F0D3F80E49C5 +:100EB000284600F011FDEA6E0C48D2F804380C49BF +:100EC000A04223F00203C2F804384FF4E1330B6070 +:100ED00003D0BDE8384000F02BBB38BDF827022016 +:100EE000303D000840420F00383D0008D423022066 +:100EF000B823022038B50B4B04461A780A4B53F836 +:100F000022500A4B9D420CD0094B00211822184652 +:100F1000FFF762FF046001462846BDE8384000F054 +:100F200007BB38BDD0230220243C0008F82702204C +:100F3000B823022000B59BB0EFF309816822684610 +:100F4000FFF724FFEFF30583044B9A6BDA6A9A6A82 +:100F50009A6A9A6A9A6A9A6A9B6AFEE700ED00E0CA +:100F600000B59BB0EFF3098168226846FFF70EFFDA +:100F7000EFF30583044B9A6B9A6A9A6A9A6A9A6AA3 +:100F80009A6A9B6AFEE700BF00ED00E000B59BB0E7 +:100F9000EFF3098168226846FFF7F8FEEFF3058357 +:100FA000034B5A6B9A6A9A6A9A6A9A6A9B6AFEE734 +:100FB00000ED00E0FEE7000030B50A44084D914224 +:100FC0000DD011F8013B5840082340F30004013BC9 +:100FD0002C4013F0FF0384EA5000F6D1EFE730BD58 +:100FE0002083B8ED026843681143016003B11847DC +:100FF00070470000024A136843F0C0031360704753 +:101000000078004013B50E4C204600F085FA04F13C +:10101000140000234FF480720A49009400F046F94E +:10102000094B4FF48072094904F13800009400F034 +:10103000BFF9074A074BC4E9172302B010BD00BF30 +:10104000D423022040240220F50F0008402502206E +:101050000078004080F93703037C30B5214C00292B +:1010600018BF0C46012B0CD11F4B984209D11F4BC6 +:101070001A6C42F080421A641A6E42F080421A667C +:101080001B6E2268036EC16D03EB52038466B3FBD3 +:10109000F2F36268150442BF23F0070503F007036B +:1010A00043EA4503CB60A36843F040034B60E36829 +:1010B00043F001038B6042F4967343F001030B602D +:1010C0004FF0FF330B62510505D512F0102205D009 +:1010D000B2F1805F04D080F8643030BD7F23FAE73E +:1010E0003F23F8E72C3C0008D423022000380240BC +:1010F0002DE9F047C66D05463768F469210734626B +:1011000019D014F0080118BF8021E20748BF41F050 +:101110002001A3074FF0200348BF41F040016007C2 +:1011200048BF41F4807183F31188281DFFF75AFFEF +:10113000002383F31188E2050AD5202383F3118865 +:101140004FF40071281DFFF74DFF002383F3118832 +:101150004FF020094FF0000A14F0200838D13B0668 +:1011600016D54FF0200905F1380A200610D589F36D +:101170001188504600F050F9002836DA0821281D61 +:10118000FFF730FF27F080033360002383F31188DB +:10119000790614D5620612D5202383F31188D5E988 +:1011A00013239A4208D12B6C33B127F0400710214A +:1011B000281DFFF717FF3760002383F31188E3062C +:1011C00018D5AA6E1369ABB15069BDE8F04718474E +:1011D00089F31188736A284695F86410194000F065 +:1011E000B5F98AF31188F469B6E7B06288F311881B +:1011F000F469BAE7BDE8F087F8B515468268044699 +:101200000B46AA4200D28568A1692669761AB542C2 +:101210000BD218462A46FFF7B9FDA3692B44A361F8 +:101220002846A3685B1BA360F8BD0CD9AF1B18460A +:101230003246FFF7ABFD3A46E1683044FFF7A6FDC2 +:10124000E3683B44EBE718462A46FFF79FFDE36857 +:10125000E5E7000083689342F7B50446154600D2DF +:101260008568D4E90460361AB5420BD22A46FFF7E6 +:101270008DFD63692B4463612846A3685B1BA360F3 +:1012800003B0F0BD0DD93246AF1B0191FFF77EFDD3 +:1012900001993A46E0683144FFF778FDE3683B4442 +:1012A000E9E72A46FFF772FDE368E4E710B50A4470 +:1012B0000024C361029B8460C16002610362C0E9D3 +:1012C0000000C0E9051110BD08B5D0E90532934210 +:1012D00001D1826882B98268013282605A1C4261FF +:1012E00019700021D0E904329A4224BFC3684361D7 +:1012F00000F0CCFE002008BD4FF0FF30FBE70000FF +:1013000070B5202304460E4683F31188A568A5B165 +:10131000A368A269013BA360531CA36115782269ED +:10132000934224BFE368A361E3690BB12046984769 +:10133000002383F31188284607E03146204600F059 +:1013400095FE0028E2DA85F3118870BD2DE9F74F8C +:1013500004460E4617469846D0F81C904FF0200AD7 +:101360008AF311884FF0000B154665B12A463146C5 +:101370002046FFF741FF034660B94146204600F092 +:1013800075FE0028F1D0002383F31188781B03B089 +:10139000BDE8F08FB9F1000F03D001902046C84797 +:1013A000019B8BF31188ED1A1E448AF31188DCE748 +:1013B000C160C361009B82600362C0E905111144F2 +:1013C000C0E9000001617047F8B504460D461646B5 +:1013D000202383F31188A768A7B1A368013BA3600A +:1013E00063695A1C62611D70D4E904329A4224BFB9 +:1013F000E3686361E3690BB120469847002080F3FE +:10140000118807E03146204600F030FE0028E2DA7D +:1014100087F31188F8BD0000D0E9052310B59A4282 +:1014200001D182687AB982680021013282605A1C37 +:1014300082611C7803699A4224BFC368836100F00B +:1014400025FE204610BD4FF0FF30FBE72DE9F74F9A +:1014500004460E4617469846D0F81C904FF0200AD6 +:101460008AF311884FF0000B154665B12A463146C4 +:101470002046FFF7EFFE034660B94146204600F0E4 +:10148000F5FD0028F1D0002383F31188781B03B009 +:10149000BDE8F08FB9F1000F03D001902046C84796 +:1014A000019B8BF31188ED1A1E448AF31188DCE747 +:1014B000026843681143016003B118477047000098 +:1014C0001430FFF743BF00004FF0FF331430FFF735 +:1014D0003DBF00003830FFF7B9BF00004FF0FF33C9 +:1014E0003830FFF7B3BF00001430FFF709BF00002A +:1014F0004FF0FF311430FFF703BF00003830FFF723 +:1015000063BF00004FF0FF323830FFF75DBF0000CF +:1015100000207047FFF776BD044B03600023436053 +:10152000C0E9023301230374704700BF443C000844 +:1015300010B52023044683F31188FFF78DFD0223A5 +:101540002374002383F3118810BD000038B5C369EC +:1015500004460D461BB904210844FFF7A9FF29469C +:1015600004F11400FFF7B0FE002806DA201D4FF446 +:101570008061BDE83840FFF79BBF38BD0268436813 +:101580001143016003B118477047000013B5446B65 +:10159000D4F8A4381A681178042915D1217C0229BD +:1015A00012D11979012312898B4013420CD101A960 +:1015B00004F14C0001F098FFD4F8A4480246019BC6 +:1015C0002179206800F0D4F902B010BD143001F088 +:1015D0001BBF00004FF0FF33143001F015BF0000B7 +:1015E0004C3001F0EDBF00004FF0FF334C3001F004 +:1015F000E7BF0000143001F0E9BE00004FF0FF31FA +:10160000143001F0E3BE00004C3001F0B9BF00001F +:101610004FF0FF324C3001F0B3BF000000207047A4 +:10162000D0F8A4381A6810B511780446042917D1E7 +:10163000017C022914D15979012352898B4013422C +:101640000ED1143001F07CFE024648B1D4F8A44813 +:101650004FF4807361792068BDE8104000F076B9DE +:1016600010BD0000406BFFF7DBBF000070470000BB +:101670007FB5124B01250426044603600023057440 +:1016800000F1840243602946C0E902330C4B02900A +:10169000143001934FF48073009601F02DFE094B36 +:1016A00004F29442294604F14C000294CDE900630F +:1016B0004FF4807301F0F4FE04B070BD6C3C000880 +:1016C000651600088D1500080B68202282F311882A +:1016D0000A7903EB820210624A790D3243F8220044 +:1016E0008A7912B103EB820318620223C0F8A418AE +:1016F0000374002383F311887047000038B5037F1B +:10170000044613B190F85430ABB90125201D0221D5 +:10171000FFF734FF04F114006FF00101257700F0AA +:10172000C1FC04F14C0084F854506FF00101BDE895 +:10173000384000F0B7BC38BD10B501210446043074 +:10174000FFF71CFF0023237784F8543010BD0000FE +:1017500038B504460025143001F0E6FD04F14C00D4 +:10176000257701F0B5FE201D84F854500121FFF7C4 +:1017700005FF2046BDE83840FFF752BF90F85C30C7 +:1017800003F06003202B06D190F85D200023212A6E +:1017900003D81F2A06D800207047222AFBD1C0E9AF +:1017A000143303E0034A0265072242658365012082 +:1017B000704700BF38220220D0F8A43837B51A6825 +:1017C0000446117804291AD1017C022917D119790C +:1017D000012312898B40134211D100F14C05284698 +:1017E00001F036FF58B101A9284601F07DFED4F87A +:1017F000A4480246019B2179206800F0B9F803B0A3 +:1018000030BD000000EB8103F0B51E6A85B00446D0 +:101810000D46FEB1202383F3118804EB8507301DAC +:101820000821FFF7ABFEFB6806F14C005B691B6803 +:101830001BB1019001F066FE019803A901F054FE6E +:10184000024648B1039B2946204600F091F8002348 +:1018500083F3118805B0F0BDFB685A691268002A4D +:10186000F5D01B8A013B1340F1D104F15C02EAE799 +:101870000D3138B550F82140DCB1202383F31188B5 +:10188000D4F8A4281368527903EB8203DB689B69C0 +:101890005D6845B104216018FFF770FE294604F128 +:1018A000140001F057FD2046FFF7BAFE002383F332 +:1018B000118838BD7047000001F0F0B801232822DC +:1018C000002110B5044600F8243BFFF785FA0023F9 +:1018D000C4E9013310BD000038B50446202383F36A +:1018E000118800254160C0E90355C0E90555C0E9EC +:1018F000075501F0E3F80223237085F3118838BD02 +:1019000070B500EB8103054650690E461446DA6057 +:1019100018B110220021FFF75FFAA06918B1102258 +:101920000021FFF759FA31462846BDE8704001F022 +:101930008FB90000826802F0011282600022C0E9C3 +:101940000422C0E90622026201F00EBAF0B40125B9 +:1019500000EB810447898D40E4683D43A4694581DB +:1019600023600023A2606360F0BC01F029BA00008C +:10197000F0B4012500EB810407898D40E4683D4304 +:101980006469058123600023A2606360F0BC01F0FC +:10199000A3BA000070B50223002504460370456613 +:1019A000056280F84C50C0E90255C0E90455C0E911 +:1019B000065501F0E9F863681B6823B12946204603 +:1019C000BDE87040184770BD037880F86830052383 +:1019D000037043681B6810B504460BB10421984797 +:1019E0000023A36010BD000090F8682043680270D7 +:1019F0001B680BB1052118477047000070B590F8BF +:101A00004C30044613B1002380F84C3004F15C02E2 +:101A1000204601F0CBF963689B68B3B994F85C3059 +:101A200013F0600535D00021204601F031FC002183 +:101A3000204601F023FC63681B6813B10621204691 +:101A40009847062384F84C3070BD204698470028FC +:101A5000E4D0B4F86230626D9A4288BF636594F94D +:101A60005C30656D002B4FF0200380F20381002D68 +:101A700000F0F280092284F84C2083F311880021C1 +:101A80002046D4E91423FFF773FF002383F3118862 +:101A9000DAE794F85D2003F07F0343EA022340F283 +:101AA0000232934200F0C58021D8B3F5807F48D040 +:101AB0000DD8012B3FD0022B00F09380002BB2D128 +:101AC00004F16402226502226265A365C1E7B3F5F1 +:101AD000817F00F09B80B3F5407FA4D194F85E3005 +:101AE000012BA0D1B4F8643043F0020332E0B3F527 +:101AF000006F4DD017D8B3F5A06F31D0A3F5C063F8 +:101B0000012B90D86368204694F85E205E6894F8B4 +:101B10005F10B4F86030B047002884D04368236574 +:101B2000036863651AE0B3F5106F36D040F60242E1 +:101B300093427FF478AF5C4B2365022363650023F7 +:101B4000C3E794F85E30012B7FF46DAFB4F86430D6 +:101B500023F00203A4F86430C4E91455A56578E7BE +:101B6000B4F85C30B3F5A06F0ED194F85E30204627 +:101B700084F8663001F060F863681B6813B10121D6 +:101B800020469847032323700023C4E914339CE7BD +:101B900004F1670323650123C3E72378042B10D1E5 +:101BA000202383F311882046FFF7C4FE85F31188B4 +:101BB0000321636884F8675021701B680BB12046CD +:101BC000984794F85E30002BDED084F86730042309 +:101BD000237063681B68002BD6D0022120469847EB +:101BE000D2E794F8603020461D0603F00F010AD5B5 +:101BF00001F0CEF8012804D002287FF414AF2B4B5B +:101C00009AE72B4B98E701F0B5F8F3E794F85E30CC +:101C1000002B7FF408AF94F8603013F00F01B3D0BD +:101C20001A06204602D501F047FBADE701F03AFB6A +:101C3000AAE794F85E30002B7FF4F5AE94F860309C +:101C400013F00F01A0D01B06204602D501F020FBA7 +:101C50009AE701F013FB97E7142284F84C2083F3F2 +:101C600011882B462A4629462046FFF76FFE85F34A +:101C70001188E9E65DB1152284F84C2083F31188C0 +:101C800000212046D4E91423FFF760FEFDE60B2275 +:101C900084F84C2083F311882B462A462946204697 +:101CA000FFF766FEE3E700BF9C3C0008943C000899 +:101CB000983C000838B590F84C300446002B3ED0D4 +:101CC000063BDAB20F2A34D80F2B32D8DFE803F004 +:101CD0003731310822323131313131313131373719 +:101CE000456DB0F862309D4214D2C3681B8AB5FBC3 +:101CF000F3F203FB12556DB9202383F311882B46B1 +:101D00002A462946FFF734FE85F311880A2384F812 +:101D10004C300EE0142384F84C30202383F31188D8 +:101D2000002320461A461946FFF710FE002383F3CE +:101D3000118838BD836D03B198470023E7E7002180 +:101D4000204601F0A5FA0021204601F097FA6368C9 +:101D50001B6813B10621204698470623D7E70000E9 +:101D600010B590F84C300446142B29D017D8062B08 +:101D700005D001D81BB110BD093B022BFBD80021B7 +:101D8000204601F085FA0021204601F077FA6368C9 +:101D90001B6813B1062120469847062319E0152B2E +:101DA000E9D10B2380F84C30202383F311880023E2 +:101DB0001A461946FFF7DCFD002383F31188DAE7A2 +:101DC000C3689B695B68002BD5D1836D03B19847CD +:101DD000002384F84C30CEE7024B0022C3E90033E5 +:101DE0009A60704740260220002382680374054BE6 +:101DF0001B6899689142FBD25A6803604260106088 +:101E0000586070474026022008B5202383F31188CC +:101E1000037C032B05D0042B0DD02BB983F3118841 +:101E200008BD436900221A604FF0FF334361FFF79A +:101E3000DBFF0023F2E7D0E9003213605A60F3E7DA +:101E4000002382680374054B1B6899689142FBD894 +:101E50005A68036042601060586070474026022054 +:101E6000054B196908741868026853601A60186194 +:101E700001230374FEF75ABA402602204B1C30B5EA +:101E8000044687B00A4D10D02B6901A8094A00F01A +:101E900025F92046FFF7E4FF049B13B101A800F0E9 +:101EA00059F92B69586907B030BDFFF7D9FFF8E73A +:101EB00040260220091E000838B50C4D0446416139 +:101EC0002B6981689A68914203D8BDE83840FFF7D2 +:101ED0008BBF1846FFF7B4FF01232C610146237422 +:101EE0002046BDE83840FEF721BA00BF4026022058 +:101EF000044B1A681B6990689B68984294BF002045 +:101F0000012070474026022010B5084C2368206944 +:101F10001A6854602260012223611A74FFF790FF4F +:101F200001462069BDE81040FEF700BA40260220B5 +:101F300008B5FFF7DDFF18B1BDE80840FFF7E4BFC3 +:101F400008BD0000FFF7E0BFFEE7000010B50C4C35 +:101F5000FFF742FF00F0B4F880220A49204600F063 +:101F60003BF8012344F8180C037400F073FC0023C1 +:101F700083F3118862B60448BDE8104000F04CB805 +:101F800068260220A03C0008B03C000800F01CB904 +:101F9000EFF3118020B9EFF30583202282F311883B +:101FA0007047000010B530B9EFF30584C4F308049E +:101FB00014B180F3118810BDFFF7BAFF84F31188C4 +:101FC000F9E70000034A516853685B1A9842FBD84E +:101FD000704700BF001000E082600222028270475A +:101FE0008368A3F17C0243F80C2C026943F83C2C73 +:101FF000426943F8382C074A43F81C2CC268A3F105 +:10200000180043F8102C022203F8082C002203F8D1 +:10201000072C70474503000810B5202383F311886F +:10202000FFF7DEFF00210446FFF746FF002383F39E +:102030001188204610BD0000024B1B6958610F201B +:10204000FFF70EBF40260220202383F31188FFF7FD +:10205000F3BF000008B50146202383F31188082050 +:10206000FFF70CFF002383F3118808BD49B1064B2D +:1020700042681B6918605A60136043600420FFF7D0 +:10208000FDBE4FF0FF3070474026022003689842A3 +:1020900006D01A680260506018465961FFF7A4BE66 +:1020A0007047000038B504460D462068844200D1D0 +:1020B00038BD036823605C604561FFF795FEF4E777 +:1020C000054B4FF0FF3103F11402C3E90522002252 +:1020D000C3E90712704700BF4026022070B51C4EAE +:1020E00005460C46C0E9032301F0E4FA334653F8F1 +:1020F000142F9A420DD130620A2C2CBF00190A30DD +:102100002A60C5E90124C6E90555BDE8704001F023 +:10211000BFBA316A431AE31838BF1C469368A3421A +:1021200002D9081901F0C2FA73699A6894420CD86E +:102130005A68AC602B606A6015609A685D60121B1B +:102140009A604FF0FF33F36170BDA41A1B68ECE78F +:102150004026022038B51B4C636998420DD0816837 +:10216000D0E9003213605A600022C2609A680A44C3 +:102170009A604FF0FF33E36138BD036822460021C7 +:1021800042F8143F93425A60C16003D1BDE8384021 +:1021900001F086BA9A688168256A0A449A6001F05B +:1021A00089FA6369411B9A688A42E5D9AB181D1AFE +:1021B000206A092D98BF01F10A02BDE83840104499 +:1021C00001F074BA402602202DE9F041184C002796 +:1021D00004F11406656901F06DFA236AAA68C11A50 +:1021E0008A4215D81344D5F80C802362D5E9003211 +:1021F00013605A606369EF60B34201D101F050FA95 +:1022000087F311882869C047202383F31188E1E709 +:102210006169B14209D013441B1ABDE8F0410A2B91 +:102220002CBFC0180A3001F041BABDE8F08100BFF0 +:102230004026022000207047FEE7000070470000A3 +:102240004FF0FF307047000002290CD0032904D062 +:102250000129074818BF00207047032A05D8054800 +:1022600000EBC2007047044870470020704700BF71 +:10227000943D000848220220483D000870B59AB0FD +:1022800005460846144601A900F0C2F801A8FEF769 +:102290009BFD431C0022C6B25B001046C5E900341A +:1022A00023700323023404F8013C01ABD1B20234A1 +:1022B0008E4201D81AB070BD13F8011B013204F828 +:1022C000010C04F8021CF1E708B5202383F3118800 +:1022D0000348FFF771FA002383F3118808BD00BF9C +:1022E000F827022090F85C3003F01F02012A07D182 +:1022F00090F85D200B2A03D10023C0E9143315E0C8 +:1023000003F06003202B08D1B0F860302BB990F8AF +:102310005D20212A03D81F2A04D8FFF72FBA222ACA +:10232000EBD0FAE7034A0265072242658365012084 +:10233000704700BF3F22022007B5052917D8DFE804 +:1023400001F0191603191920202383F31188104A6C +:1023500001210190FFF7D4FA019802210D4AFFF7FD +:10236000CFFA0D48FFF7F4F9002383F3118803B087 +:102370005DF804FB202383F311880748FFF7BEF9BB +:10238000F2E7202383F311880348FFF7D5F9EBE741 +:10239000E83C00080C3D0008F827022038B50C4D39 +:1023A0000C4C2A460C4904F10800FFF767FF05F1C1 +:1023B000CA0204F110000949FFF760FF05F5CA726F +:1023C00004F118000649BDE83840FFF757BF00BFC9 +:1023D000D030022048220220C83C0008D23C00082D +:1023E000DD3C000870B5044608460D46FEF7ECFCDF +:1023F000C6B22046013403780BB9184670BD324688 +:102400002946FEF7CDFC0028F3D10120F6E70000B5 +:102410002DE9F04705460C46FEF7D6FC2B49C6B21F +:102420002846FFF7DFFF08B10E36F6B228492846E6 +:10243000FFF7D8FF08B11036F6B2632E0BD8DFF8DD +:102440008C80DFF88C90234FDFF894A02E7846B96B +:102450002670BDE8F08729462046BDE8F04701F028 +:10246000C3BB252E2ED1072241462846FEF798FCF5 +:1024700070B9194B224603F1140153F8040B8B4237 +:1024800042F8040BF9D11B78073515341370DDE7DA +:10249000082249462846FEF783FC98B9A21C0F4B38 +:1024A000197802320909C95D02F8041C13F8011BEE +:1024B00001F00F015345C95D02F8031CF0D1183437 +:1024C0000835C3E7013504F8016BBFE7B43D0008E8 +:1024D000DD3C0008D23D0008BC3D000820F4F01FA0 +:1024E0002CF4F01FBFF34F8F024AD368DB03FCD4F8 +:1024F000704700BF003C024008B5074B1B7853B93A +:10250000FFF7F0FF054B1A69002A04DA044A5A6003 +:1025100002F188325A6008BD2E330220003C02408E +:102520002301674508B5054B1B7833B9FFF7DAFF80 +:10253000034A136943F00043136108BD2E330220A0 +:10254000003C02400B28F0B516D80C4C0C492378FF +:102550007BB90E460B4D0C234FF00062013B55F842 +:10256000047B46F8042B13F0FF033A44F6D1012311 +:10257000237051F82000F0BD0020FCE760330220FA +:1025800030330220E43D0008014B53F8200070472F +:10259000E43D00080C2070470B2810B5044601D913 +:1025A000002010BDFFF7CEFF064B53F8243018442F +:1025B000C21A0BB90120F4E712680132F0D1043BD2 +:1025C000F6E700BFE43D00080B2838B5044628D8DC +:1025D000FFF7DEFC0546FFF785FF2046FFF78CFF7F +:1025E000114AF323D360E300DBB243F4007343F0FA +:1025F00002031361136943F480331361FFF772FF21 +:10260000FFF7A0FF094B53F8241000F0E9F8284623 +:10261000FFF788FFFFF7C6FC2046BDE83840FFF70C +:10262000BBBF002038BD00BF003C0240E43D0008B5 +:1026300012F001032DE9F04105460E4614464BD138 +:102640008218B2F1026F61D8314B1B6813F001039D +:102650005CD0FFF79DFC2F4FFFF74EFFF323314671 +:1026600040F20128FB60FFF73DFF032C18D824F04F +:1026700001046D1A274E40F201180C44A14205EBEB +:10268000010733692AD123F001033361FFF74AFFC1 +:10269000FFF788FC0120BDE8F081043C0435E4E745 +:1026A000AB07E4D13B6923F440733B613B6943EAE8 +:1026B00008033B6151F8046B2E60BFF34F8FFFF7A7 +:1026C00011FF2B689E42E8D03B6923F001033B6178 +:1026D000FFF728FFFFF766FC0020DCE723F44073D8 +:1026E0003361336943EA080333610B883B80BFF3EE +:1026F0004F8FFFF7F7FE3F88BFB231F8023BBB4276 +:10270000BCD0336923F001033361E1E71846C2E727 +:1027100000380240003C0240084908B50B7828B157 +:102720001BB9FFF7E9FE01230B7008BD002BFCD09D +:102730000870BDE80840FFF7F5BE00BF2E33022049 +:102740000244074BD2B210B5904200D110BD441CD8 +:1027500000B253F8200041F8040BE0B2F4E700BFE8 +:10276000502800400F4B30B51C6F240407D41C6F59 +:1027700044F400741C671C6F44F400441C670A4C4A +:1027800002442368D2B243F480732360074B904223 +:1027900000D130BD441C51F8045B00B243F8205016 +:1027A000E0B2F4E7003802400070004050280040DA +:1027B00007B5012201A90020FFF7C2FF019803B06D +:1027C0005DF804FB13B50446FFF7F2FFA04205D005 +:1027D000012201A900200194FFF7C4FF02B010BD3F +:1027E0000144BFF34F8F064B884204D3BFF34F8F92 +:1027F000BFF36F8F7047C3F85C022030F4E700BF6F +:1028000000ED00E000207047034B1A681AB9034A34 +:10281000D2F874281A6070476433022000300240F6 +:1028200008B5FFF7F1FF024B1868C0F3407008BD10 +:1028300064330220EFF30983054968334A6B22F0C1 +:1028400001024A6383F30988002383F311887047E8 +:1028500000EF00E0202080F3118862B60D4B0E4A95 +:10286000D96821F4E0610904090C0A430B49DA60D4 +:10287000D3F8FC2042F08072C3F8FC20084AC2F86A +:10288000B01F116841F0010111601022DA7783F85E +:102890002200704700ED00E00003FA0555CEACC5FC +:1028A000001000E0202310B583F311880E4B5B6805 +:1028B00013F4006314D0F1EE103AEFF309844FF0F3 +:1028C0008073683CE361094BDB6B236684F3098802 +:1028D000FFF70EFB10B1064BA36110BD054BFBE7E4 +:1028E00083F31188F9E700BF00ED00E000EF00E09E +:1028F000570300085A03000870B5BFF34F8FBFF3AA +:102900006F8F1A4A0021C2F85012BFF34F8FBFF3E6 +:102910006F8F536943F400335361BFF34F8FBFF39D +:102920006F8FC2F88410BFF34F8FD2F8803043F618 +:10293000E074C3F3C900C3F34E335B0103EA04063A +:10294000014646EA81750139C2F86052F9D2203B4E +:1029500013F1200FF2D1BFF34F8F536943F480334B +:102960005361BFF34F8FBFF36F8F70BD00ED00E079 +:10297000FEE700000A4B0B480B4A90420BD30B4B6F +:10298000C11EDA1C121A22F003028B4238BF002249 +:102990000021FEF721BA53F8041B40F8041BECE7B2 +:1029A000E03F000878340220783402207834022096 +:1029B0007047000070B5D0E91B4300224FF0FF358F +:1029C0009E6804EB42135101D3F80009002805DA90 +:1029D000D3F8000940F08040C3F80009D3F8000B99 +:1029E000002805DAD3F8000B40F08040C3F8000B54 +:1029F000013263189642C3F80859C3F8085BE0D265 +:102A00004FF00113C4F81C3870BD00001D4B03EBE0 +:102A10008002D2F80CC02DE9F043DCF81420461CEB +:102A2000DD6ED2F800E005EB063605EB4018516884 +:102A300071450AD30122D5F8343802FA00F023EAAE +:102A40000000C5F83408BDE8F083AEEB0103BCF824 +:102A50001040A34228BF2346D8F81849A4B2B3EBCC +:102A6000840FF0D89468A4F1040959F8047F376002 +:102A7000A4EB09071F44042FF7D81C440B449460AF +:102A80005360D4E768330220890141F020010161DD +:102A900003699B06FCD41220FFF794BA10B5054CCD +:102AA0002046FEF70BFF4FF0A043E366024B23677F +:102AB00010BD00BF68330220383E000870B50378AF +:102AC0000546012B50D12A4BC46E98421BD1294B8D +:102AD0000E2143205A6B42F080025A635A6D42F035 +:102AE00080025A655A6D5A6942F080025A615A69E9 +:102AF00022F080025A615B6900F0E8FB1E4BE36044 +:102B00001E4BC4F800380023EE6EC4F8003EC0230C +:102B100023604FF40413A3633369002BFCDA012311 +:102B20000C203361FFF74EFA3369DB07FCD4122027 +:102B3000FFF748FA3369002BFCDA00262846A66026 +:102B4000FFF738FF6B68C4F81068DB68C4F81468D6 +:102B5000C4F81C684BB90A4BA3614FF0FF336361A3 +:102B6000A36843F00103A36070BD064BF4E700BF08 +:102B70006833022000380240401400400300200265 +:102B8000003C30C0083C30C0F8B5C46E054600219A +:102B90004FF000662046FFF777FF296F00234FF0C4 +:102BA00001128F684FF0FF30C4F83438C4F81C2885 +:102BB00004EB431201339F42C2F80069C2F8006B74 +:102BC000C2F80809C2F8080BF2D20B68EA6E6B670C +:102BD000636210231361166916F01006FBD11220F0 +:102BE000FFF7F0F9D4F8003823F4FE63C4F8003896 +:102BF000A36943F4402343F01003A3610923C4F8FD +:102C00001038C4F814380A4BEB604FF0C043C4F8D6 +:102C1000103B084BC4F8003BC4F81069C4F80039F5 +:102C20006B6F03F1100243F480136A67A362F8BD6F +:102C3000143E000840800010C26E90F86610D2F872 +:102C4000003823F4FE6343EA0113C2F800387047EA +:102C50002DE9F84300EB8103C56E0C468046DA6827 +:102C60000FFA81F94801166806F00306731E022B5D +:102C700005EB41134FF0000194BFB604384EC3F882 +:102C8000101B4FF0010104F1100398BF06F18056AC +:102C900001FA03F3916998BF06F5004600293AD07E +:102CA000578A04F15801374349016F50D5F81C1871 +:102CB0000B430021C5F81C382B180127C3F8101945 +:102CC000A7405369611E9BB3138A928B9B08012A0C +:102CD00088BF5343D8F87420981842EA034301F19F +:102CE00040022146C8F87400284605EB8202536072 +:102CF000FFF7CAFE08EB8900C3681B8A43EA8453C6 +:102D000048341E4364012E51D5F81C381F43C5F8C2 +:102D10001C78BDE8F88305EB4917D7F8001B21F4B0 +:102D20000041C7F8001BD5F81C1821EA0303C0E7CF +:102D300004F13F030B4A2846214605EB83035A6002 +:102D4000FFF7A2FE05EB4910D0F8003923F4004349 +:102D5000C0F80039D5F81C3823EA0707D7E700BFC9 +:102D60000080001000040002026F12684267FFF743 +:102D700021BE00005831C36E49015B5813F4004076 +:102D800004D013F4001F0CBF022001207047000084 +:102D90004831C36E49015B5813F4004004D013F46A +:102DA000001F0CBF022001207047000000EB8101D2 +:102DB000CB68196A0B6813604B685360704700005A +:102DC00000EB810330B5DD68AA691368D36019B9D7 +:102DD000402B84BF402313606B8A1468C26E1C446E +:102DE00002EB4110013C09B2B4FBF3F4634303333B +:102DF00023F0030343EAC44343F0C043C0F8103B4D +:102E00002B6803F00303012B0ED1D2F8083802EB34 +:102E1000411013F4807FD0F8003B14BF43F080537F +:102E200043F00053C0F8003B02EB4112D2F8003BE4 +:102E300043F00443C2F8003B30BD00002DE9F041EF +:102E4000244D0446EE6E06EB4013D3F8087B38079A +:102E5000C3F8087B0AD5D6F81438190706D505EB50 +:102E6000840321462846DB685B689847FA071FD52C +:102E7000D6F81438DB071BD505EB8403D968CCB929 +:102E80008B69488A5A68B2FBF0F600FB16228AB9B1 +:102E90001868DA6890420DD2121AC3E90024202380 +:102EA00083F311880B482146FFF78AFF84F31188CA +:102EB000BDE8F081012303FA04F26B8923EA0203DF +:102EC0006B81CB68002BF3D021460248BDE8F0416E +:102ED000184700BF6833022000EB81034A0170B538 +:102EE000DD68C36E6C692668E66056BB1A444FF411 +:102EF0000020C2F810092A6802F00302012A0AB26F +:102F00000ED1D3F8080803EB421410F4807FD4F8F4 +:102F1000000914BF40F0805040F00050C4F8000990 +:102F200003EB4212D2F8000940F00440C2F8000955 +:102F30000122D3F8340802FA01F10143C3F834182E +:102F400070BD19B9402E84BF4020206020681A440B +:102F50002E8A8419013CB4FBF6F440EAC44040F0E8 +:102F60000050C6E7F8B504461E48C56E05EB44138D +:102F7000D3F80869F107C3F8086917D5D5F81038F0 +:102F8000DA0713D500EB8403D9684B691F68DA6848 +:102F9000974218D2D21B00271A605F60202383F368 +:102FA00011882146FFF798FF87F31188330617D55C +:102FB0000123D5F83428A340134211D02046BDE8A0 +:102FC000F840FFF723BD012303FA04F2038923EA43 +:102FD000020303818B68002BE8D021469847E5E780 +:102FE000F8BD00BF683302202DE9F74FA24CE66E12 +:102FF0007569B3691D4015F48058756107D0204686 +:10300000FEF7C8FC03B0BDE8F04FFFF74BBC002D46 +:1030100012DAD6F8003E9F0705D0D6F8003E23F01E +:103020000303C6F8003ED6F80438934823F00103A2 +:10303000C6F80438FEF7D8FC280505D58E48FFF7FA +:10304000B9FC8D48FEF7C0FCA9040CD5D6F80838A9 +:1030500013F0060FF36823F470530CBF43F41053BE +:1030600043F4A053F3602A0704D56368DB680BB10F +:1030700081489847EB0200F18A80AF0227D5D4F847 +:103080006C9000274FF0010ADFF8ECB109EB471212 +:10309000D2F8003B03F44023B3F5802F11D1D2F8CE +:1030A000003B002B0DDA62890AFA07F322EA0303D8 +:1030B000638104EB8703DB68DB6813B1394658464C +:1030C00098470137236FFFB29B689F42DED9E8061D +:1030D00018D5E76E3A6AC2F30A1002F00F0302F441 +:1030E000F012B2F5802F00F09C80B2F5402F09D18C +:1030F00004EB8303002207F58057DB681B6A9042CC +:1031000040F082802B03D6F818481DD5E70302D57E +:103110000020FFF793FEA60302D50120FFF78EFEE5 +:10312000600302D50220FFF789FE210302D50320A8 +:10313000FFF784FEE20202D50420FFF77FFEA30220 +:1031400002D50520FFF77AFE6F037FF55BAFE60738 +:1031500002D50020FFF706FFA50702D50120FFF7E3 +:1031600001FF600702D50220FFF7FCFE210702D510 +:103170000320FFF7F7FEE20602D50420FFF7F2FE78 +:10318000A3067FF53FAF0520FFF7ECFE3AE7E36EBD +:1031900000274FF0010ADFF8E0B00193236F5FFAD8 +:1031A00087F99B6899453FF668AF019B03EB49138C +:1031B000D3F8002902F44022B2F5802F22D1D3F8AF +:1031C0000029002A1EDAD3F8002942F09042C3F801 +:1031D0000029D3F80029002AFBDB4946E06EFFF7FF +:1031E00053FC22890AFA09F322EA0303238104EB40 +:1031F0008903DB689B6813B149465846984748469F +:10320000FFF704FC0137C9E7910701D1D7F8008027 +:10321000072A02F101029CBF03F8018B4FEA18282C +:103220006DE7023307F5805704EB83025268D2F84A +:1032300018C0DCF80820DCE9001CA1EB0C0C002114 +:1032400088420AD104EB830463689B699A6802444C +:103250009A605A6802445A6054E711F0030F01D192 +:10326000D7F800808C4501F1010184BF02F8018B81 +:103270004FEA1828E4E700BF68330220C36E03EB6F +:103280004111D1F8003B43F40013C1F8003B7047F3 +:10329000C36E03EB4111D1F8003943F40013C1F8B8 +:1032A00000397047C36E03EB4111D1F8003B23F4A2 +:1032B0000013C1F8003B7047C36E03EB4111D1F816 +:1032C000003923F40013C1F800397047090100F1F7 +:1032D0006043012203F56143C9B283F8001300F093 +:1032E0001F039A4043099B0003F1604303F56143C8 +:1032F000C3F880211A60704730B50433039C017213 +:10330000002104FB0325C160C0E90653049B03634D +:10331000059BC0E90000C0E90422C0E90842C0E9F9 +:103320000A11436330BD00000022416AC260C0E957 +:103330000411C0E90A226FF00101FEF7B3BE0000DC +:10334000D0E90432934201D1C2680AB9181D70470E +:1033500000207047036919600021C2680132C26011 +:10336000C269134482699342036124BF436A0361C3 +:10337000FEF78CBE38B504460D46E3683BB1626982 +:103380000020131D1268A3621344E36207E0237A4E +:1033900033B929462046FEF769FE0028EDDA38BD2C +:1033A0006FF00100FBE70000C368C269013BC36026 +:1033B0004369134482699342436124BF436A436172 +:1033C00000238362036B03B11847704770B5202355 +:1033D000044683F31188866A3EB9FFF7CBFF0546A2 +:1033E00018B186F31188284670BDA36AE26A13F803 +:1033F000015B9342A36202D32046FFF7D5FF00236F +:1034000083F31188EFE700002DE9F84F04460E46DC +:10341000174698464FF0200989F311880025AA46DF +:10342000D4F828B0BBF1000F09D141462046FFF780 +:10343000A1FF20B18BF311882846BDE8F88FD4E9AD +:103440000A12A7EB050B521A934528BF9346BBF10E +:10345000400F1BD9334601F1400251F8040B914251 +:1034600043F8040BF9D1A36A403640354033A362D8 +:10347000D4E90A239A4202D32046FFF795FF8AF344 +:103480001188BD42D8D289F31188C9E730465A461F +:10349000FDF77CFCA36A5E445D445B44A362E7E7FE +:1034A00010B5029C0433017204FB0321C460C0E91F +:1034B00006130023C0E90A33039B0363049BC0E99E +:1034C0000000C0E90422C0E90842436310BD0000C7 +:1034D000026A6FF00101C260426AC0E90422002260 +:1034E000C0E90A22FEF7DEBDD0E904239A4201D1E9 +:1034F000C26822B9184650F8043B0B6070470020A0 +:1035000070470000C3680021C2690133C36043698A +:10351000134482699342436124BF436A4361FEF7C7 +:10352000B5BD000038B504460D46E3683BB12369DC +:1035300000201A1DA262E2691344E36207E0237AC5 +:1035400033B929462046FEF791FD0028EDDA38BD53 +:103550006FF00100FBE7000003691960C268013ADF +:10356000C260C269134482699342036124BF436A03 +:10357000036100238362036B03B1184770470000A7 +:1035800070B520230D460446114683F31188866AE0 +:103590002EB9FFF7C7FF10B186F3118870BDA36A7B +:1035A0001D70A36AE26A01339342A36204D3E16906 +:1035B00020460439FFF7D0FF002080F31188EDE7A3 +:1035C0002DE9F84F04460D46904699464FF0200AE3 +:1035D0008AF311880026B346A76A4FB949462046A8 +:1035E000FFF7A0FF20B187F311883046BDE8F88FC0 +:1035F000D4E90A073A1AA8EB0607974228BF1746EC +:10360000402F1BD905F1400355F8042B9D4240F88B +:10361000042BF9D1A36A40364033A362D4E90A23CC +:103620009A4204D3E16920460439FFF795FF8BF3F2 +:1036300011884645D9D28AF31188CDE729463A4602 +:10364000FDF7A4FBA36A3D443E443B44A362E5E787 +:10365000D0E904239A4217D1C3689BB1836A8BB126 +:10366000043B9B1A0ED01360C368013BC360C3695F +:103670001A4483699A42026124BF436A03610023AA +:1036800083620123184670470023FBE700F094B8DB +:103690004FF08043002258631A610222DA607047BB +:1036A0004FF080430022DA60704700004FF0804303 +:1036B000586370474FF08043586A70474B684360C7 +:1036C0008B688360CB68C3600B6943614B6903629D +:1036D0008B6943620B6803607047000008B52C4B90 +:1036E00040F2FF712B481A690A431A611A6922F4E1 +:1036F000FF6222F007021A611A691A6B0A431A6301 +:103700001A6D0A431A65244A1B6D1146FFF7D6FF4E +:1037100000F5806002F11C01FFF7D0FF00F580602A +:1037200002F13801FFF7CAFF00F5806002F1540191 +:10373000FFF7C4FF00F5806002F17001FFF7BEFFE4 +:1037400000F5806002F18C01FFF7B8FF00F58060A2 +:1037500002F1A801FFF7B2FF00F5806002F1C40199 +:10376000FFF7ACFF00F5806002F1E001FFF7A6FF74 +:1037700000F5806002F1FC01FFF7A0FF02F58C71FB +:1037800000F58060FFF79AFFBDE8084000F08AB8B6 +:103790000038024000000240443E000808B500F036 +:1037A00003FAFEF7D3FBFFF72FF8BDE80840FEF75A +:1037B000F5BD0000704700000F4B1A6C42F001028B +:1037C0001A641A6E42F001021A660C4A1B6E936864 +:1037D00043F0010393604FF080436B229A624FF0F5 +:1037E000FF32DA6200229A615A63DA605A6001227B +:1037F0005A611A60704700BF00380240002004E0A0 +:103800004FF0804208B51169D3680B40D9B29B07CD +:103810006FEA0101116107D5202383F31188FEF7B8 +:10382000B5FB002383F3118808BD00001B4B4FF04C +:10383000FF3000211A696FEA42526FEA52521A6150 +:103840001A69C2F30A021A611A695A6958615A69F7 +:1038500059615A691A6A62F080521A621A6A02F051 +:1038600080521A621A6A5A6A58625A6A59625A6AC5 +:103870000B4A106840F480701060186F00F44070BC +:10388000B0F5007F03D04FF4803018671967536894 +:1038900023F40073536000F05FB900BF00380240AA +:1038A00000700040364B4FF44041364A1A64364AA5 +:1038B00011601A6842F001021A601A689207FCD57A +:1038C0009A6822F003029A602D4B9A6812F00C025B +:1038D000FBD1196801F0F90119609A601A6842F485 +:1038E00080321A601A689003FCD55A6F42F00102C8 +:1038F0005A67234B5A6F9107FCD5244A5A601A68BD +:1039000042F080721A60204B5A685204FCD51A6843 +:1039100042F480321A605A68D003FCD51A6842F427 +:1039200000321A60184A53689903FCD5144B1A6880 +:103930009201FCD5164A9A6040F20112C3F88C201D +:103940000022C3F8902040F20733124A1360136834 +:1039500003F00F03072BFAD1094B9A6842F00202D9 +:103960009A609A6802F00C02082AFAD15A6C42F462 +:1039700080425A645A6E42F480425A665B6E7047C7 +:10398000003802400004001000700040086C40093C +:1039900000948838003C0240074A08B5536903F098 +:1039A0000103536123B1054A13680BB1506898476E +:1039B000BDE80840FEF776BF003C0140F833022026 +:1039C000074A08B5536903F00203536123B1054A5E +:1039D00093680BB1D0689847BDE80840FEF762BF16 +:1039E000003C0140F8330220074A08B5536903F050 +:1039F0000403536123B1054A13690BB15069984719 +:103A0000BDE80840FEF74EBF003C0140F8330220FD +:103A1000074A08B5536903F00803536123B1054A07 +:103A200093690BB1D0699847BDE80840FEF73ABFEB +:103A3000003C0140F8330220074A08B5536903F0FF +:103A40001003536123B1054A136A0BB1506A9847BA +:103A5000BDE80840FEF726BF003C0140F8330220D5 +:103A6000164B10B55C6904F478725A61A30604D54C +:103A7000134A936A0BB1D06A9847600604D5104A7E +:103A8000136B0BB1506B9847210604D50C4A936B0E +:103A90000BB1D06B9847E20504D5094A136C0BB102 +:103AA000506C9847A30504D5054A936C0BB1D06CB4 +:103AB0009847BDE81040FEF7F5BE00BF003C01404E +:103AC000F8330220194B10B55C6904F47C425A614A +:103AD000620504D5164A136D0BB1506D9847230546 +:103AE00004D5134A936D0BB1D06D9847E00404D50B +:103AF0000F4A136E0BB1506E9847A10404D50C4ABF +:103B0000936E0BB1D06E9847620404D5084A136FC8 +:103B10000BB1506F9847230404D5054A936F0BB13E +:103B2000D06F9847BDE81040FEF7BCBE003C014096 +:103B3000F833022008B50348FDF7DAFABDE808407B +:103B4000FEF7B0BED423022008B5FFF759FEBDE84A +:103B50000840FEF7A7BE0000062108B50846FFF79B +:103B6000B5FB06210720FFF7B1FB06210820FFF770 +:103B7000ADFB06210920FFF7A9FB06210A20FFF76C +:103B8000A5FB06211720FFF7A1FB06212820FFF740 +:103B90009DFB07211C20FFF799FB0C215220BDE85B +:103BA0000840FFF793BB000008B5FFF73FFE00F0A9 +:103BB0000DF8FDF7AFFCFDF77FFEFDF757FDFFF7B2 +:103BC000F9FDBDE80840FFF761BD00000023054A8C +:103BD00019460133102BC2E9001102F10802F8D195 +:103BE000704700BFF8330220034611F8012B03F899 +:103BF000012B002AF9D1704753544D3332463F3FD1 +:103C00003F3F3F3F0053544D333246375B347C35A2 +:103C10005D780053544D333246375B367C375D78E0 +:103C200000000000F8270220D423022000960000A4 +:103C30000000000000000000000000000000000084 +:103C40000000000000000000DD140008C914000896 +:103C500005150008F1140008FD140008E914000817 +:103C6000D5140008C1140008111500080000000058 +:103C7000E9150008D515000811160008FD15000803 +:103C800009160008F5150008E1150008CD15000813 +:103C90001D160008000000000100000000000000E8 +:103CA0006D61696E0000000069646C6500000000D1 +:103CB000A83C000880260220F8270220010000000E +:103CC000491F0008000000004172647550696C6F64 +:103CD000740025424F415244252D424C0025534546 +:103CE0005249414C25000000020000000000000085 +:103CF000051800087118000840004000A03002209C +:103D0000B0300220020000000000000003000000AC +:103D100000000000B51800080000000010000000BE +:103D2000C030022000000000010000000000000080 +:103D300068330220010102003923000849220008EB +:103D4000E5220008C922000843000000503D000899 +:103D500009024300020100C032090400000102020E +:103D600001000524001001052401000104240202C1 +:103D70000524060001070582030800FF090401006D +:103D8000020A000000070501024000000705810249 +:103D900040000000120000009C3D000812011001CC +:103DA0000200004009124157000201020301000015 +:103DB0000403090425424F41524425004D617465B6 +:103DC0006B463736352D57696E672D626473686FA1 +:103DD0007400303132333435363738394142434458 +:103DE00045460000008000000080000000800000C8 +:103DF0000080000000000200000004000000040039 +:103E000000000400000004000000040000000400A2 +:103E10000000040000000000FD190008B51C0008A7 +:103E2000611D000840004000E0330220E033022022 +:103E300001000000F033022080000000400100007B +:103E4000050000000000802A00000000AAAAAAAA1B +:103E500000000024FFFF00000000000000A00A0096 +:103E60000000000100000000AAAAAAAA00000001A8 +:103E7000FFFF000000000000000000000001000043 +:103E800000000000AAAAAAAA00010000FFFF00008B +:103E900000000000000000000040100000000000D2 +:103EA000AAAAAAAA00400000FFFB00000000000030 +:103EB000000000000081420000000000AAAAAAAA97 +:103EC00000404100EFFF00000000008008000000FB +:103ED0000000000000000000AAAAAAAA000000003A +:103EE000FFFF0000000000000000000000000000D4 +:103EF00000000000AAAAAAAA00000000FFFF00001C +:103F000000000000000000000000000000000000B1 +:103F1000AAAAAAAA00000000FFFF000000000000FB +:103F2000000000000000000000000000AAAAAAAAE9 +:103F300000000000FFFF0000000000000000000083 +:103F40000000000000000000000000000000000071 +:103F50000000000000000000000000000000000061 +:103F60000000000000000000000000000000000051 +:103F700000000000000000008F00000000000000B2 +:103F800000801E0000000000FF0000000000000094 +:103F9000F83B00083F00000049040000053C000811 +:103FA0003F00000051040000133C00083F000000E7 +:103FB00000960000000008009600000000080000C5 +:103FC00004000000B03D00080000000000000000F8 +:103FD00000000000000000000000000000000000E1 +:00000001FF diff --git a/Tools/bootloaders/MatekF765-Wing_bl.bin b/Tools/bootloaders/MatekF765-Wing_bl.bin index 4aed4b829ad..9b3982b6b74 100755 Binary files a/Tools/bootloaders/MatekF765-Wing_bl.bin and b/Tools/bootloaders/MatekF765-Wing_bl.bin differ diff --git a/Tools/bootloaders/MatekF765-Wing_bl.hex b/Tools/bootloaders/MatekF765-Wing_bl.hex index 50309eca251..fb1591e21cf 100644 --- a/Tools/bootloaders/MatekF765-Wing_bl.hex +++ b/Tools/bootloaders/MatekF765-Wing_bl.hex @@ -1,29 +1,29 @@ :020000040800F2 -:100000000004022001020008690F00086D0F0008BB -:10001000C10F00086D0F0008950F000803020008CB -:100020000302000803020008030200086D2700080D +:100000000006022001020008510F0008D10E00086E +:10001000290F0008D10E0008FD0E00080302000899 +:10002000030200080302000803020008CD270008AD :10003000030200080302000803020008030200088C :10004000030200080302000803020008030200087C -:1000500003020008030200087D390008A9390008DE -:10006000D5390008013A00082D3A000803020008BB +:10005000030200080302000831390008593900087A +:1000600081390008A9390008D139000803020008C5 :10007000030200080302000803020008030200084C :10008000030200080302000803020008030200083C -:10009000030200080302000803020008593A00089E +:10009000030200080302000803020008F9390008FF :1000A000030200080302000803020008030200081C -:1000B000A137000803020008030200080302000839 +:1000B000E13A0008030200080302000803020008F6 :1000C00003020008030200080302000803020008FC :1000D00003020008030200080302000803020008EC -:1000E000C13A0008030200080302000803020008E6 +:1000E0005D3A00080302000803020008030200084A :1000F00003020008030200080302000803020008CC :1001000003020008030200080302000803020008BB :1001100003020008030200080302000803020008AB :10012000030200080302000803020008030200089B :10013000030200080302000803020008030200088B -:10014000030200080302000803020008D92E000879 +:10014000030200080302000803020008812F0008D0 :10015000030200080302000803020008030200086B :10016000030200080302000803020008030200085B :10017000030200080302000803020008030200084B -:1001800003020008030200085110000803020008DF +:100180000302000803020008CD3A00080302000839 :10019000030200080302000803020008030200082B :1001A000030200080302000803020008030200081B :1001B000030200080302000803020008030200080B @@ -31,948 +31,948 @@ :1001D00003020008030200080302000803020008EB :1001E00003020008030200080302000803020008DB :1001F00003020008030200080302000803020008CB -:1002000002E000F000F8FEE772B6394880F3088893 -:10021000384880F3098838484EF60851CEF200017C +:1002000002E000F000F8FEE772B63A4880F3088892 +:10021000394880F3098839484EF60851CEF200017A :10022000086040F20000CCF200004EF63471CEF2CD :1002300000010860BFF34F8FBFF36F8F40F20000E3 :10024000C0F2F0004EF68851CEF200010860BFF314 :100250004F8FBFF36F8F4FF00000E1EE100A4EF6A4 :100260003C71CEF200010860062080F31488BFF3D1 -:100270006F8F02F0B9FA03F01BFA4FF055301F49A7 -:100280001B4A91423CBF41F8040BFAE71C49194A4A -:1002900091423CBF41F8040BFAE71A491A4A1B4B3A -:1002A0009A423EBF51F8040B42F8040BF8E70020D5 -:1002B0001749184A91423CBF41F8040BFAE702F093 -:1002C000D7FA03F05FFA144C144DAC4203DA54F839 -:1002D000041B8847F9E700F03FF8114C114DAC4280 -:1002E00003DA54F8041B8847F9E702F0BFBA0000AC -:1002F0000004022000240220000000080000022068 -:1003000000040220303F0008002402205024022074 -:1003100050240220D8340220000200080002000805 -:1003200000020008000200082DE9F04F2DED108AB0 -:10033000C1F80CD0D0F80CD0BDEC108ABDE8F08F1D -:10034000002383F311882846A047002001F096FE81 -:1003500001F046FE00DFFEE770B56FF070031F4C42 -:1003600000256FF07F0623701E236570A570E57071 -:1003700025716571A571E57125726672A372E572CA -:1003800000F02AFD20B10E2325726672A372E57279 -:1003900002F0AEF9044602F0E3F90546D0B9104B7D -:1003A0009C4219D001339C4241F2883412BF054669 -:1003B00000240125002002F0A5F90DB100F0B6F8E7 -:1003C00000F07AFD00F05CFC204600F04FF900F0F0 -:1003D000ADF8F9E70024EDE70446EBE750240220EE -:1003E000010007B008B500F0C9FBA0F12003584296 -:1003F000584108BD054B07B51B88022101A8ADF87F -:10040000043000F027FC03B05DF804FBA83B0008B3 -:10041000064991F8243033B100230822086A81F894 -:10042000243000F051BC0120704700BF702402202E -:100430002DE9F84F234C05468846174694F824309A -:100440008BBB2E46DFF87C90002F38D094F824A088 -:10045000BAF1000F05D12022FF214846266200F0A4 -:1004600019FDCAF10805414604EB8A00BD4228BFC8 -:100470003D465FFA85FBAD00A7EB0B072A462E44ED -:1004800000F0E0FC94F82430A844FFB29B445FFAEB -:100490008BFBBBF1080F84F824B0D5D1FFF7B8FF70 -:1004A0000028D1D108E0266A06EB8306B042C9D005 -:1004B000FFF7AEFF0028C4D10020BDE8F88F01206F -:1004C000BDE8F88F7024022010B5202383F3118833 -:1004D0001248C3680BB101F057FE0023104A4FF4D5 -:1004E0007A710E4801F014FE002383F311880D4C3D -:1004F000236813B12368013B2360636813B1636809 -:10050000013B6360084B1B7833B9636823B9022051 -:1005100000F08EFC3223636010BD00BF5C2402201B -:10052000C9040008A025022098240220454B464912 -:100530002DE9F04153F8042F013201D1BDE8F081DB -:100540008B42F7D1414C424B22689A4278D9414BB9 -:100550009B6803F1006303F5C0339A4270D2002018 -:1005600000F0AAFB02203C4B187000F057FC3B4BFC -:100570001A6C00221A64196E1A66196E596C5A6444 -:10058000596E5A66596E596941F08001596159692D -:1005900021F0800159615969196941F000511961CF -:1005A000196921F0005119611B6972B62C4B2D4954 -:1005B0000B601D682468BFF34F8FBFF36F8F2A4B0A -:1005C000C3F88420BFF34F8F5A6922F480325A61F6 -:1005D000BFF34F8FD3F8802043F6E07EC2F3C90605 -:1005E000C2F34E32B707520102EA0E0838463146CE -:1005F000013948EA000C00F14040B1F1FF3FC3F877 -:1006000074C2F5D1203A12F1200FEDD1BFF34F8F14 -:10061000BFF36F8FBFF34F8FBFF36F8F5A6922F411 -:1006200000325A610022C3F85022BFF34F8FBFF34C -:100630006F8F202383F31188AD4685F30888204708 -:10064000BDE8F081FC7F01081C80010804800108DE -:10065000FF7F010850240220982402200038024025 -:100660000080010808ED00E000ED00E02DE9F04F0A -:1006700099B0B34C2022FF21019010A8A66800F089 -:1006800009FCB04AA3461378A3B90121AE48117002 -:10069000C360202383F31188C3680BB101F074FD9C -:1006A0000023AA4A4FF47A71A74801F031FD0023D4 -:1006B00083F31188019B13B1A54B019A1A600023A3 -:1006C000A44AA349019F99461C461D4698461370AB -:1006D0004B600292012000F0A1FB002F00F012827B -:1006E0009B4B1B68002B40F00D8219B0BDE8F08FCA -:1006F0000220FFF777FE002840F0FB81019BB9F153 -:10070000000F08BF1F46944B1B8802210BA8ADF8B1 -:100710002C3000F09FFADDE74FF47A7000F02EFAEB -:10072000031E0393EADB0220FFF75CFE82460028EB -:10073000E4D0039B581E042800F2DD81DFE800F0BE -:10074000030E1114170018A80523042140F8343DA6 -:1007500000F080FA54464FF0000856E00421784833 -:10076000F6E704217D48F3E704217D48F0E71C24E7 -:100770002046043400F0A2FA04210B900BA800F0EC -:1007800069FA2C2CF4D1E5E7002DB7D0002CB5D0B8 -:100790000220FFF727FE0546002800F0AF81012068 -:1007A0006C4C00F089FA4FF000090220207000F034 -:1007B00035FB5FFA89FA504600F08EFA074658B1C9 -:1007C000504609F1010900F097FA0028F1D12C46B2 -:1007D000A9460027634B97E701233E46022023707A -:1007E00000F012FBDBF808309E4206D2304600F0E3 -:1007F00065FA0130EBD10436F4E70026029BA946E6 -:100800002C461E703746524B5E6000F04BFB15B114 -:10081000002C18BF0027FFF7EDFD5BE7002D3FF42C -:100820006DAF002C3FF46AAF0220029B187000F0FD -:10083000F5FA322000F0A2F9B0F1000AC0F25E81B0 -:100840001AF0030540F05A8106EB0A03DBF8082092 -:10085000934200F25381BAF5807F00F24F815545F3 -:100860000DDA4FF47A7000F089F90490049B002BA4 -:10087000C0F24481049B3C4AAB540135EFE7C820E9 -:10088000FFF7B0FD0546002800F038811F2E11D873 -:10089000C6F1200410AB26F0030033495445184438 -:1008A00028BF5446224600F0CDFA2246FF212E48AA -:1008B00000F0F0FA4FEAAA0A2B4930465FFA8AF2B2 -:1008C000FFF7B6FD0446002800F01A8106EB8A0601 -:1008D00005469AE70220FFF785FD00283FF40EAF9A -:1008E000FFF796FD00283FF409AF4FF0000A53468A -:1008F000DBF8082092451CD2BAF11F0F12D8109ACB -:1009000001320FD02AF0030218A90A4452F8202C11 -:100910000B92184604220BA90AF1040A00F064FBAA -:100920000346E5E75046039300F0C8F9039B0B909C -:10093000EFE718A8042140F84C3D00F08BF964E77C -:10094000502402209C2502205C240220C9040008B7 -:10095000A025022098240220AA3B0008542402204B -:1009600058240220AC3B00089C24022018A8002335 -:10097000642140F8343D00F039F900287FF4BEAE20 -:100980000220FFF72FFD00283FF4B8AE0B9800F0CF -:10099000C5F918AB43F8480D04211846CDE718A84F -:1009A0000023642140F8343D00F020F900287FF452 -:1009B000A5AE0220FFF716FD00283FF49FAE0B986E -:1009C00000F0BAF918AB43F8440DE5E70220FFF751 -:1009D00009FD00283FF492AE00F0B4F918AB43F8DB -:1009E000400DD9E70220FFF7FDFC00283FF486AE5A -:1009F0000BA9142000F0ACF9824618A8042140F895 -:100A00003CAD00F027F951460BA896E7322000F0E4 -:100A1000B5F8B0F1000AFFF671AE1AF0030F7FF4DB -:100A20006DAE0AEB0803DBF8082093423FF666AE92 -:100A30000220FFF7D7FC00283FF460AE2AF0030A3B -:100A4000C244D0453FF4E1AE404608F1040800F04E -:100A500035F904210A900AA800F0FCF8F1E74FF4F8 -:100A60007A70FFF7BFFC00283FF448AEFFF7D0FCD8 -:100A700000283FF4AFAE109B01330CD0082210A920 -:100A80000020FFF7D5FC00283FF4A4AE2022FF2170 -:100A900010A800F0FFF9FFF7ADFC374801F0F4FAB9 -:100AA00023E6002D3FF42AAE002C3FF427AE18A811 -:100AB0000023642140F8343D00F098F88246002875 -:100AC0007FF41CAE0220FFF78DFC00283FF416AE29 -:100AD0000390FFF78FFC41F28830574601F0D4FABB -:100AE0000B9800F021FA00F0DDF9039B1C461D462F -:100AF000F0E5054689E64FF00008FFE52546FDE5EF -:100B00002C4667E6002000F039F80490049B002B87 -:100B1000FFF6E3AD012000F077F9049B213B122B97 -:100B20003FF6D8AD01A252F823F000BFF10600084D -:100B30001907000889070008D5060008D50600082F -:100B4000D50600081D0800080D0A0008D508000891 -:100B50006D0900089F090008CD090008D5060008A6 -:100B6000E5090008D50600085F0A00080B08000820 -:100B7000D5060008A30A0008A08601002DE9F34766 -:100B80004FF47A75002402AE154F4543DFF85880C4 -:100B900006F8014D97F900305FFA84F95A1C01D02C -:100BA000A34212D158F82400012231460368D3F839 -:100BB00020A02B46D047012807D10A4B9DF80700FB -:100BC00083F8009002B0BDE8F0870134022CE1D137 -:100BD0004FF4FA7001F058FA4FF0FF30F2E700BF1F -:100BE00000240220C4250220B83B00082DE9F0476C -:100BF0004FF47A7506460024134F4D43DFF85080BA -:100C000097F900305FFA84F95A1C01D0A34210D141 -:100C100058F82400042231460368D3F820A02B465C -:100C2000D047042805D1094B002083F80090BDE887 -:100C3000F0870134022CE3D14FF4FA7001F024FA6A -:100C40004FF0FF30BDE8F08700240220C4250220C9 -:100C5000B83B0008074B30B41A78074B53F82240D2 -:100C60000A46014623682046DD69044BAC4630BC89 -:100C7000604700BFC4250220B83B0008A0860100E1 -:100C8000F8B50A4C00250A4E01F038FC094F2070D7 -:100C900030682378834207D901F02AFC3368054481 -:100CA0000133BD423360F3D9F8BD00BFC525022032 -:100CB000A8250220FF7F010001F0CCBC00F10060FC -:100CC00000F5C0300068704700F10060920000F548 -:100CD000C03001F059BC0000054B1A68054B1B7869 -:100CE0009B1A834202D9104401F002BC00207047D5 -:100CF000A8250220C525022038B5074D04462868DE -:100D0000204401F0FDFB28B928682044BDE83840A4 -:100D100001F00EBC38BD00BFA825022010F003036F -:100D200008D1B0F5806F05D800F10050A0F5712012 -:100D30000068704700207047014BC058704700BFE3 -:100D400020F4F01F014B1868704700BF002004E03A -:100D50001F4BF0B51E681F4BC6F30B02360C1F88E5 -:100D60005D68BA4293F9084022D09F89BA4221D0E7 -:100D70001F8BBA4206D102220C2404FB02335D68A9 -:100D800093F90840B6F5805F16D041F201039E4208 -:100D900008BF5A24421E013D0B460A44934215D215 -:100DA00015F9016F581C4EB1034600F8016CF5E7C8 -:100DB0000022E1E70122DFE74124EBE72C25824214 -:100DC0001D7001D9981C5C70401AF0BD1846FBE7F5 -:100DD000002004E004240220094B5B88B3F5805F07 -:100DE00009D041F20102934207D10122054B03EBE6 -:100DF0008203D87870470022F8E70020704700BFD0 -:100E0000002004E0B03B0008022803D14FF08062CC -:100E1000014B9A61704700BF000C0240022803D1C9 -:100E20004FF48062014B9A61704700BF000C024092 -:100E3000022804D1024A536983F4806353617047E6 -:100E4000000C0240002310B5934203D0CC5CC45484 -:100E50000133F9E710BD000030B5441E14F9010F4D -:100E60000B4658B193F900500131854206D11AB9A9 -:100E700093F90020801A30BD013AEFE7002AF7D13C -:100E8000104630BD02460346981A13F9011B00298B -:100E9000FAD1704702440346934202D003F8011B83 -:100EA000FAE77047024B1A78024B1A70704700BF7E -:100EB000C42502200024022038B5154C154D2046CB -:100EC00000F022FC2946204600F04AFC2D6812481A -:100ED000EA6ED2F8043843F00203C2F8043801F095 -:100EE000D3F80E49284600F049FDEA6E0C48D2F8C6 -:100EF00004380C49A04223F00203C2F804384FF42E -:100F0000E1330B6003D0BDE8384000F05BBB38BD77 -:100F1000F42A0220A83C000840420F00D03C000800 -:100F200048260220AC25022038B50B4B05461A781E -:100F30000A4B53F822400A4B9C420CD0094B00212B -:100F400018221846FFF7A6FF056001462046BDE8B7 -:100F5000384000F037BB38BDC4250220B83B00083C -:100F6000F42A0220AC250220FEE7000000B59BB069 -:100F7000EFF3098168226846FFF764FFEFF305830A -:100F8000034B9A6B9A6A9A6A9A6A9A6A9B6AFEE714 -:100F900000ED00E000B59BB0EFF3098168226846E0 -:100FA000FFF750FFEFF30583044B9A6B9A6A9A6A36 -:100FB0009A6A9A6A9A6A9B6AFEE700BF00ED00E0AF -:100FC00000B59BB0EFF3098168226846FFF73AFF4E -:100FD000EFF30583034B5A6B9A6A9A6A9A6A9A6A84 -:100FE0009B6AFEE700ED00E030B50A44074D9142F0 -:100FF0000BD011F8013B09245840013CF7D040F3D5 -:1010000000032B4083EA5000F7E730BD2083B8EDA2 -:10101000002304491A465A50C81808334260802BEE -:10102000F9D17047C8250220024A136843F0C00373 -:101030001360704700780040044B5A6810439A6868 -:1010400058600AB1181D1047704700BF482602209B -:101050002DE9F84F404EF56D2F68EC6921072C62A1 -:1010600019D014F0080F0CBF00208020E20748BF01 -:1010700040F02000A3074FF0200348BF40F040009D -:10108000610748BF40F4807083F31188FFF7D4FFF5 -:10109000002383F31188E20509D5202383F3118807 -:1010A0004FF40070FFF7C8FF002383F311884FF05F -:1010B0002009DFF8A4A04FF0000B14F0200832D173 -:1010C0003B0615D54FF02009DFF890A020060FD57C -:1010D00089F31188504600F0E9F9002830DA082039 -:1010E000FFF7AAFF27F080032B60002383F311880A -:1010F00079060DD562060BD5202383F31188F26C97 -:10110000336D9A4201D1336CFBB9002383F311880C -:10111000E30604D5B26E13690BB150699847BDE878 -:10112000F84F01F033BB89F311886B6A504696F88B -:101130006410194000F054FA8BF31188EC69BCE795 -:10114000A86288F31188EC69C0E727F040071020F7 -:10115000FFF772FF2F60D8E7482602208026022082 -:1011600013B5104C204600F021FA04F1140000944D -:1011700000234FF400720C4900F0E2F804F138004B -:1011800000944FF40072094B094900F05BF9094BD8 -:101190000B215220E365084B236602B0BDE81040E6 -:1011A00000F058B848260220B42602202910000872 -:1011B000B42802200078004080F93703224B002930 -:1011C00008BF1946037C012B816630B50CD11F4B3B -:1011D000984209D11E4B1A6C42F080421A641A6E72 -:1011E00042F080421A661B6E0A68036EC46D03EB00 -:1011F0005203B3FBF2F34A68150442BF23F007051C -:1012000003F0070343EA4503E3608B6843F04003C0 -:101210006360CB68510543F00103A36042F4967309 -:1012200043F0010323604FF0FF33236205D512F032 -:10123000102205D0B2F1805F04D080F8643030BD58 -:101240007F23FAE73F23F8E7EC3B0008482602201B -:101250000038024000F1604300F01F02090140091C -:1012600003F56143C9B2800083F80013012300F144 -:101270006040934000F56140C0F8803103607047E2 -:10128000F8B51546826804460B46AA4200D2856826 -:10129000A1692669761AB54207D218462A46FFF791 -:1012A000D1FDA3692B44A3610DE011D9AF1B3246D8 -:1012B0001846FFF7C7FD3A46E1683044FFF7C2FD24 -:1012C000E2683A44A261A36828465B1BA360F8BDAC -:1012D00018462A46FFF7B6FDE368E4E783689342C1 -:1012E0002DE9F04104460F46154600D28568606935 -:1012F0002669361AB54207D22A463946FFF7A2FDBB -:1013000063692B4463610EE013D9A5EB06083246EE -:101310003946FFF797FD4246B919E068FFF792FD9D -:10132000E26842446261A36828465B1BA360BDE893 -:10133000F0812A463946FFF785FDE368E2E70000C1 -:1013400010B50A440024C361029B006040608460C1 -:10135000C160816141610261036210BD08B58269AB -:101360004369934201D1826882B982680132826006 -:101370005A1C42611970426903699A4201D3C368D9 -:101380004361002100F09CFE002008BD4FF0FF30BB -:1013900008BD000070B5202304460E4683F3118873 -:1013A000A568A5B1A368A269013BA360531CA36112 -:1013B00015782269934224BFE368A361E3690BB106 -:1013C00020469847002383F31188284670BD314694 -:1013D000204600F065FE0028E2DA85F3118870BD32 -:1013E0002DE9F74F05460F4690469A46D0F81C90D7 -:1013F000202686F311884FF0000B144664B1224674 -:1014000039462846FFF73CFF034668B9514628464F -:1014100000F046FE0028F1D0002383F31188A8EBEA -:10142000040003B0BDE8F08FB9F1000F03D00190C4 -:101430002846C847019B8BF31188E41A1F4486F3A2 -:101440001188DBE7C160816141611144C361009B88 -:10145000006040608260016103627047F8B5044635 -:101460000E461746202383F31188A568A5B1A3680B -:10147000013BA36063695A1C62611E702369626943 -:101480009A4224BFE3686361E3690BB12046984741 -:10149000002080F31188F8BD3946204600F000FE98 -:1014A0000028E2DA85F31188F8BD000083694269FB -:1014B0009A4210B501D182687AB98268013282609D -:1014C0005A1C82611C7803699A4201D3C368836104 -:1014D000002100F0F5FD204610BD4FF0FF3010BD9B -:1014E0002DE9F74F05460F4690469A46D0F81C90D6 -:1014F000202686F311884FF0000B144664B1224673 -:1015000039462846FFF7EAFE034668B951462846A1 -:1015100000F0C6FD0028F1D0002383F31188A8EB6A -:10152000040003B0BDE8F08FB9F1000F03D00190C3 -:101530002846C847019B8BF31188E41A1F4486F3A1 -:101540001188DBE7026843681143016003B1184763 -:10155000704700001430FFF743BF00004FF0FF3327 -:101560001430FFF73DBF00003830FFF7B9BF00006F -:101570004FF0FF333830FFF7B3BF00001430FFF7F0 -:1015800009BF00004FF0FF311430FFF703BF000028 -:101590003830FFF763BF00004FF0FF323830FFF7FD -:1015A0005DBF000000207047FFF7DABD044B036009 -:1015B000002343608360C36001230374704700BF4E -:1015C000043C000810B52023044683F31188FFF77C -:1015D000F5FD02232374002383F3118810BD00005E -:1015E00038B5C36904460D461BB904210844FFF70A -:1015F000A9FF294604F11400FFF7B0FE002806DA1F -:10160000201D4FF48061BDE83840FFF79BBF38BD17 -:10161000026843681143016003B118477047000036 -:1016200013B5446BD4F894341A681178042915D191 -:10163000217C022912D11979012312898B4013428E -:101640000CD101A904F14C0001F0A8FED4F8944497 -:101650000246019B2179206800F0E0F902B010BD3C -:10166000143001F02BBE00004FF0FF33143001F0B6 -:1016700025BE00004C3001F0FDBE00004FF0FF33EE -:101680004C3001F0F7BE0000143001F0F9BD00004D -:101690004FF0FF31143001F0F3BD00004C3001F089 -:1016A000C9BE00004FF0FF324C3001F0C3BE000055 -:1016B000D0F8942438B5136805461978042901D068 -:1016C000012038BD017C0229FAD1127901205C8900 -:1016D00090400440F4D105F1140001F08BFD024666 -:1016E0000028EDD0D5F894544FF4807328686979B8 -:1016F00000F082F9204638BD406BFFF7D9BF0000EB -:1017000000207047704700007FB5124B012502266C -:10171000044603600023057400F1840243602946F7 -:101720008360C3600C4B0290143001934FF48073BC -:10173000009601F03BFD094B04F523722946019305 -:1017400004F14C004FF480730294009601F002FE05 -:1017500004B070BD2C3C0008F916000821160008E2 -:101760000B68202282F311880A7903EB820210624F -:101770004A790D3243F822008A7912B103EB8203D1 -:1017800018620223C0F894140374002383F31188B1 -:101790007047000038B5037F044613B190F8543009 -:1017A000ABB90125201D0221FFF732FF04F114001F -:1017B00025776FF0010100F08FFC84F8545004F19C -:1017C0004C006FF00101BDE8384000F085BC38BD29 -:1017D00010B5012104460430FFF71AFF00232377D8 -:1017E00084F8543010BD000038B50446002514308C -:1017F00001F0F4FC04F14C00257701F0C3FD201D3D -:1018000084F854500121FFF703FF2046BDE838401B -:10181000FFF74EBF90F85C3003F06003202B19D126 -:1018200090F85D20212A0AD0222A4FF000030ED022 -:10183000202A0FD1084A02650722426504E0064BC0 -:101840000365072343650023836501207047036513 -:101850004365F9E70020704728240220D0F894342B -:1018600037B51A680446117804291AD1017C022977 -:1018700017D11979012312898B40134211D100F13C -:101880004C05284601F03EFE58B101A9284601F05A -:1018900085FDD4F894440246019B2179206800F02C -:1018A000BDF803B030BD000000EB8103F7B51C6A42 -:1018B00005460E46F4B1202383F3118805EB860715 -:1018C000201D08214C34FFF7A3FEFB685B691B68F1 -:1018D00013B1204601F070FD01A9204601F05EFD24 -:1018E000024648B1019B3146284600F097F8002394 -:1018F00083F3118803B0F0BDFB685A691268002AAF -:10190000F5D01B8A013B1340F1D105F15C02EAE7F7 -:101910000D3138B550F82140DCB1202383F3118814 -:10192000D4F894241368527903EB8203DB689B6933 -:101930005D6845B104216018FFF76AFE294604F18D -:10194000140001F061FC2046FFF7B2FE002383F390 -:10195000118838BD7047000001F010B8012300F174 -:10196000240200F1380103700023436042F8043B75 -:101970008A421361FAD103814381704738B5044626 -:10198000202383F3118800254160C560056145610E -:101990008561C561056201F001F80223237085F3BA -:1019A000118838BD70B500EB8103054650690E46BD -:1019B0001446DA6018B110220021FFF76BFAA06913 -:1019C00018B110220021FFF765FA31462846BDE81C -:1019D000704001F0ADB80000028902F001020281FE -:1019E000428902F001024281002202614261826169 -:1019F000C261026201F030B9F0B4012500EB81044C -:101A000047898D40E4683D43A469458123600023F4 -:101A1000A2606360F0BC01F04BB90000F0B4012596 -:101A200000EB810407898D40E4683D4364690581CA -:101A300023600023A2606360F0BC01F0C5B9000020 -:101A400070B50223002504460370A0F8645080F8A6 -:101A5000665080F8675005814581C5600561456124 -:101A60008561C561056280F84C5000F0FDFF636838 -:101A70001B6823B129462046BDE87040184770BD59 -:101A80000278436880F8682005221B6802700BB159 -:101A90000421184770470000436890F868201B68CD -:101AA00002700BB1052118477047000090F84C30C8 -:101AB00070B5044613B1002380F84C3004F15C0289 -:101AC000204601F0EBF863689B6863BB94F85C50B8 -:101AD00015F0600615D194F85D3005F07F0545EAF4 -:101AE000032540F202339D4200F00E815BD8022DA7 -:101AF00000F0DC803FD8002D00F08780012D00F041 -:101B0000CF800021204601F033FB0021204601F068 -:101B100025FB63681B6813B10621204698470623FE -:101B200084F84C3070BD204698470028CED094F8F9 -:101B3000632094F8623043EA0223626D934238BF17 -:101B4000636594F95C30656D002B4FF0200380F2E3 -:101B5000FD80002D00F0EC80092284F84C2083F3F6 -:101B600011880021636D226D2046FFF757FF002387 -:101B700083F3118870BDB5F5817F00F0B180B5F5B4 -:101B8000407F49D0B5F5807FBBD194F85E30012B02 -:101B9000B7D1B4F8643023F00203A4F864302665AA -:101BA0006665A665C3E740F201639D421ED8B5F5A0 -:101BB000C06F3BD2B5F5A06FA3D1B4F85C30B3F5DC -:101BC000A06F0ED194F85E30204684F8663000F0A5 -:101BD000A3FF63681B6813B10121204698470323C4 -:101BE0002370002323656365A365A0E7B5F5106F37 -:101BF00032D040F602439D4252D0B5F5006F80D1FD -:101C000004F167032365012324E004F16403A5655F -:101C10002365022363658AE794F85E30012B7FF425 -:101C200070AFB4F8643043F00203B6E794F8612073 -:101C30002046616894F860304D6843EA022394F8C6 -:101C40005F1094F85E20A84700283FF45AAF43681D -:101C5000236503686365A4E72378042B10D1202350 -:101C600083F311882046FFF7B7FE86F31188636877 -:101C7000032184F867601B6821700BB120469847E8 -:101C800094F85E30002BACD084F8673004232370C6 -:101C900063681B68002BA4D0022120469847A0E768 -:101CA000374B23650223636500239DE794F860109A -:101CB000204611F0800F01F00F010ED000F0E0FF80 -:101CC000012806D002287FF41CAF2E4B60652365E7 -:101CD00067E72D4B6565236563E700F0C3FFEFE71A -:101CE00094F85E30002B7FF40CAF94F8603013F062 -:101CF0000F013FF476AF1A06204602D501F04CFAE8 -:101D00006FE701F03FFA6CE794F85E30002B7FF448 -:101D1000F8AE94F8603013F00F013FF462AF1B0689 -:101D2000204602D501F024FA5BE701F017FA58E7E4 -:101D3000142284F84C2083F311882B462A46294626 -:101D40002046FFF759FE85F3118870BD5DB115225D -:101D500084F84C2083F311880021636D226D2046A6 -:101D6000FFF74AFE03E70B2284F84C2083F3118827 -:101D70002B462A4629462046FFF750FEE3E700BFE0 -:101D80005C3C0008543C0008583C000838B590F80A -:101D90004C300446152B29D8DFE803F03E282828CC -:101DA00028283E28280B29392828282828282828A8 -:101DB0003E3E90F8631090F86220436D42EA0122A3 -:101DC0009A4214D9C268128AB3FBF2F502FB1535A8 -:101DD0006DB9202383F311882B462A462946FFF745 -:101DE0001DFE85F311880A2384F84C3038BD142376 -:101DF00084F84C30202383F31188002320461A46B0 -:101E00001946FFF7F9FD002383F3118838BD836D70 -:101E100003B198470023E7E7002101F0A9F9002169 -:101E2000204601F09BF963681B6813B10621204628 -:101E300098470623D8E7000090F84C20152A38B5BB -:101E4000044622D80123934040F6416213421DD13B -:101E500013F480150FD19B0217D50B2380F84C305B -:101E6000202383F311882B462A462946FFF7D6FD07 -:101E700085F3118838BDC3689B695B682BB9836D96 -:101E800003B19847002384F84C3038BD002101F09D -:101E90006FF90021204601F061F963681B6813B1F6 -:101EA0000621204698470623EDE70000024B00225A -:101EB0001B605B609A607047B42A0220002382682E -:101EC0000374054B1B6899689142FBD25A68036002 -:101ED0004260106058607047B42A022008B5202381 -:101EE00083F31188037C032B05D0042B0DD02BB971 -:101EF00083F3118808BD436900221A604FF0FF3355 -:101F00004361FFF7DBFF0023F2E790E80C001A6063 -:101F100002685360F2E70000002382680374054BF7 -:101F20001B6899689142FBD85A6803604260106050 -:101F300058607047B42A0220054B19690874186864 -:101F4000026853601A60186101230374FEF7ECB94C -:101F5000B42A02204B1C30B5054687B00A4C10D07D -:101F6000236901A8094A00F0D3F82846FFF7E4FFE7 -:101F7000049B13B101A800F007F92369586907B061 -:101F800030BDFFF7D9FFF8E7B42A0220DD1E0008B4 -:101F900038B50C4D044641612B6981689A689142BD -:101FA00003D8BDE83840FFF789BF1846FFF786FF22 -:101FB00001232C61014623742046BDE83840FEF71A -:101FC000B3B900BFB42A0220044B1A681B69906899 -:101FD0009B68984294BF002001207047B42A0220D9 -:101FE00010B5084C236820691A68546022600122E9 -:101FF00023611A74FFF790FF01462069BDE8104085 -:10200000FEF792B9B42A02208260022202740022F2 -:10201000427470478368A3F17C0243F80C2C026978 -:1020200043F83C2C426943F8382C074A43F81C2CEF -:10203000C268A3F1180043F8102C022203F8082C00 -:10204000002203F8072C70474103000810B5202335 -:1020500083F31188FFF7DEFF00210446FFF798FFA6 -:10206000002383F31188204610BD0000024B1B693A -:1020700058610F20FFF760BFB42A0220202383F3AA -:102080001188FFF7F3BF000008B50146202383F352 -:1020900011880820FFF75EFF002383F3118808BD35 -:1020A00049B1064B42681B6918605A60136043606F -:1020B0000420FFF74FBF4FF0FF307047B42A0220D3 -:1020C0000368984206D01A68026050601846596149 -:1020D000FFF7F4BE7047000038B504460D4620688F -:1020E000844200D138BD036823605C604561FFF71E -:1020F000E5FEF4E7054B03F114025A619A614FF0D3 -:10210000FF32DA6100221A62704700BFB42A02204F -:10211000F8B503614FF08043C26002295C6A06464D -:10212000184B38BF02211A461F4652F8145F9542D9 -:102130000AD1586198611C62056045608160081988 -:10214000BDE8F84001F000BA186AAB68241A0C190F -:1021500002D3E41A2D6804E09C4202D2204401F02C -:1021600001FAAB689C42F4D86B68356073601E60FE -:102170004FF0FF336E60B460A968091BA960FB6172 -:10218000F8BD00BFB42A022010B41B4C234653F8FC -:10219000141F814210D0416802680A6002685160D1 -:1021A0009A424FF00001C16003D0936881680B44EC -:1021B00093605DF8044B70470A6800209A426261A0 -:1021C0005360C86003D15DF8044B01F0C5B9936852 -:1021D00088680344206A93604FF08042526A121A62 -:1021E0009342E6D9991A5DF8044B012998BF931CD4 -:1021F000184401F0B7B900BFB42A0220002070478C -:10220000FEE70000704700004FF0FF30704700000D -:10221000022906D0032906D00129064818BF00204C -:10222000704705487047032A9ABF044800EBC20074 -:10223000002070472C3D0008E03C000830240220BC -:1022400070B59AB006460846144601AD294600F01E -:1022500095F82846FEF716FEC0B2431C5B0086E8E0 -:10226000180023700323023404F8013C00231946AC -:10227000DAB20234904201D81AB070BDEA5C013380 -:1022800004F8011C04F8022CF2E7000008B5202332 -:1022900083F311880348FFF7E1FA002383F31188E1 -:1022A00008BD00BFF42A022010B50446052916D83F -:1022B000DFE801F016150316161D202383F311889D -:1022C0000E4A0121FFF76EFB20460D4A0221FFF75F -:1022D00069FB0C48FFF788FA002383F3118810BDCF -:1022E000202383F311880748FFF754FAF4E72023EB -:1022F00083F311880348FFF76BFAEDE7603C0008B1 -:10230000843C0008F42A022038B50C4D0C4C2A46B7 -:102310000C4904F10800FFF793FF05F1CA0204F12C -:1023200010000949FFF78CFF05F5CA7204F1180087 -:102330000649BDE83840FFF783BF00BFBC2F02202D -:1023400030240220B03C0008BA3C0008C53C00081C -:1023500070B5044608460D46FEF794FDC6B2204609 -:10236000013403780BB9184670BD32462946FEF792 -:1023700073FD0028F3D1012070BD00002DE9F04766 -:1023800004460D46FEF77EFD2B49C6B22046FFF7F8 -:10239000DFFF08B10736F6B228492046FFF7D8FF1D -:1023A00008B11036F6B2632E0BD8DFF88C80DFF858 -:1023B0008C90234FDFF894A0267846B92E70BDE8A4 -:1023C000F08721462846BDE8F04701F0E5BB252E01 -:1023D0002ED1072241462046FEF73EFD70B9194B2B -:1023E0002A4603F10C0153F8040B8B4242F8040B0C -:1023F000F9D11B8807340E351380DDE708224946E2 -:102400002046FEF729FD98B9AA1C0F4B13F8011FAF -:10241000023209095345C95D02F8041C197801F01C -:102420000F01C95D02F8031CF0D118350834C3E769 -:102430002E7001340135BFE74C3D0008C53C000853 -:10244000633D0008543D00081FF4F01F2BF4F01FFB -:10245000BFF34F8F024AD368DB03FCD4704700BF41 -:10246000003C024008B5074B1B7853B9FFF7F0FF5B -:10247000054B1A69002A04DA044A5A6002F18832CC -:102480005A6008BD1A320220003C02402301674511 -:1024900008B5054B1B7833B9FFF7DAFF034A136918 -:1024A00043F00043136108BD1A320220003C024091 -:1024B0000B2870B513D80B4A0B4C137863B94FF047 -:1024C00000610A4E44F8231056F8235001330C2BB8 -:1024D0002944F7D10123137054F8200070BD002067 -:1024E00070BD00BF4C3202201C320220743D000837 -:1024F000014B53F820007047743D00080C207047D2 -:102500000B2810B5044601D9002010BDFFF7D0FFFD -:10251000064B53F824301844C21A0BB9012010BDE1 -:1025200012680132F0D1043BF6E700BF743D0008A9 -:102530000B2810B5044621D8FFF78AFFFFF792FF5A -:102540000F4AF323D360C300DBB243F4007343F0BC -:1025500002031361136943F480331361FFF778FFBB -:10256000FFF7A6FF074B53F8241000F0DBF8FFF746 -:102570008FFF2046BDE81040FFF7C2BF002010BD0E -:10258000003C0240743D00082DE9F84312F00103BD -:1025900015463FD18218B2F1026F3BD22B4B1B681C -:1025A00013F0010336D0FFF75DFF294CF32340F20F -:1025B0000127E360FFF74CFF032D01D9830712D0F9 -:1025C0000F46401A224C40F20118EB1BC6190B446F -:1025D000012B236924D823F001032361FFF758FF5F -:1025E0000120BDE8F883236923F440732361236944 -:1025F0003B43236151F8046B0660BFF34F8FFFF735 -:1026000027FF03689E4208D0236923F0010323615A -:10261000FFF73EFF0020BDE8F883043D0430CBE720 -:1026200023F44073B9462361236943EA0803236115 -:1026300037F8023B3380BFF34F8FFFF709FF36882F -:10264000B6B2B9F80030B342BFD0DDE7003802407F -:10265000003C0240084908B50B7828B153B9FFF790 -:1026600001FF01230B7008BD23B10870BDE80840CD -:10267000FFF70EBF08BD00BF1A3202200244043922 -:10268000064BD2B210B5904200D110BD441C00B22E -:1026900053F8200041F8040FE0B2F4E7502800405E -:1026A000104B30B51C6F240407D41C6F44F4007425 -:1026B0001C671C6F44F400441C670B4C0244043933 -:1026C0002368D2B243F480732360084B904200D158 -:1026D00030BD441C51F8045F00B243F82050E0B212 -:1026E000F4E700BF0038024000700040502800406E -:1026F00007B5012201A90020FFF7C0FF019803B030 -:102700005DF804FB13B50446FFF7F2FFA04206D0C4 -:1027100002A90122002041F8044DFFF7C1FF02B0D9 -:1027200010BD00000144BFF34F8F064B884204D315 -:10273000BFF34F8FBFF36F8F7047C3F85C02203039 -:10274000F4E700BF00ED00E0034B1B689B0042BFB5 -:102750000122024B1A707047743802404D32022039 -:10276000014B1878704700BF4D320220064A53686B -:1027700023F001035360EFF30983683383F309887F -:10278000002383F31188704730EF00E010B5202359 -:1027900083F31188104B5B6813F4006318D0F1EEDB -:1027A000103AEFF309844FF0807344F84C3C0B4B24 -:1027B000DB6844F8083CA4F1680383F30988FFF759 -:1027C00003FC18B1064B44F8503C10BD054BFAE72A -:1027D00083F3118810BD00BF00ED00E030EF00E092 -:1027E0005103000854030008F0B5BFF34F8FBFF347 -:1027F0006F8F1D4B0021C3F85012BFF34F8FBFF3F3 -:102800006F8F5A6942F400325A61BFF34F8FBFF3A2 -:102810006F8FC3F88410BFF34F8FD3F8802043F637 -:10282000E076C2F3C904C2F34E32A507520102EAB0 -:10283000060E284621464EEA0007013900F14040C5 -:10284000C3F860724F1CF6D1203A12F1200FEED17E -:10285000BFF34F8F5A6942F480325A61BFF34F8FF2 -:10286000BFF36F8FF0BD00BF00ED00E0FEE700009A -:10287000084A094B09498B4204D3094A0021934273 -:1028800005D3704752F8040F43F8040BF3E743F8FD -:10289000041BF4E77C3F0008D8340220D83402201F -:1028A000D8340220036F002230B51146C46E9D68F3 -:1028B0004FF0FF3004EB421301329542C3F8001988 -:1028C000C3F81019C3F80809C3F8001BC3F8101B9C -:1028D000C3F8080BEED24FF00113C4F81C3830BD1A -:1028E000890141F02001016103699B06FCD412209B -:1028F00000F0C4BE204B03EB80022DE9F047D2F874 -:102900000CE0461CDD6EDEF8142005EB0636D2F82E -:1029100000C005EB4018516861450BD30123D5F881 -:10292000342803FA00F022EA0000C5F834081846FB -:10293000BDE8F087ACEB0103BEF81040A34228BF0E -:102940002346D8F81849A4B2B3EB840F10D8946882 -:102950001F46A4F1040959F804AF042FC6F800A0DB -:1029600001D9043FF7E71C440B4494605360D2E75D -:102970000020BDE8F08700BF5032022010B5054CA2 -:102980002046FEF7EBFF4FF0A043E366024B2367C0 -:1029900010BD00BF50320220C83D00080378012B53 -:1029A00070B5054650D12A4BC46E98421BD1294BB5 -:1029B0000E2143205A6B42F080025A635A6D42F056 -:1029C00080025A655A6D5A6942F080025A615A690A -:1029D00022F080025A615B69FEF73CFC1E4BE3600B -:1029E0001E4BC4F800380023EE6EC4F8003EC0232E -:1029F00023604FF40413A3633369002BFCDA012333 -:102A00000C20336100F03AFE3369DB07FCD412205E -:102A100000F034FE3369002BFCDA00262846A6605D -:102A2000FFF740FF6B68C4F81068DB68C4F81468EF -:102A3000C4F81C684BB90A4BA3614FF0FF336361C4 -:102A4000A36843F00103A36070BD064BF4E700BF29 -:102A5000503202200038024040140040030020029F -:102A6000003C30C0083C30C0F8B5C46E05460021BB -:102A70004FF000662046FFF733FF296F00234FF029 -:102A800001128F684FF0FF30C4F83438C4F81C28A6 -:102A900004EB431201339F42C2F80069C2F8006B95 -:102AA000C2F80809C2F8080BF2D20B68EA6E6B672D -:102AB000636210231361166916F01006FBD1122011 -:102AC00000F0DCFDD4F8003823F4FE63C4F80038CD -:102AD000A36943F4402343F01003A3610923C4F81E -:102AE0001038C4F814380A4BEB604FF0C043C4F8F8 -:102AF000103B084BC4F8003BC4F81069C4F8003917 -:102B00006B6F03F1100243F480136A67A362F8BD90 -:102B1000A43D000840800010C26E90F86610D2F804 -:102B2000003823F4FE6343EA0113C2F8003870470B -:102B30002DE9F0410EB20D4600EB8608D8F80C10D6 -:102B40000F6807F00303022B50D0032B50D03D4AEF -:102B50003D4F012B18BF1746C46E4FEA451E002299 -:102B600005F1100C04EB0E03C3F8102B8A69002A40 -:102B700040D04A8A05F158033A435B01E2500123F1 -:102B8000D4F81C2803FA0CF31343C4F81C38A644E9 -:102B900000234A69CEF8103905F13F03002A39D0E5 -:102BA0000A8A04EB8303898B9208012988BF4A4370 -:102BB000416F561841EA02422946466720465A604C -:102BC000FFF78EFED8F80C301B8A43EA85531F436B -:102BD00005F148035B01E7500123D4F81C2803FAF0 -:102BE00005F51543C4F81C58BDE8F081174FB3E74D -:102BF000174FB1E704EB4613D3F8002B22F4004241 -:102C0000C3F8002B0123D4F81C2803FA0CF322EAA2 -:102C10000303BAE704EB83030E4A04EB4616294686 -:102C20005A602046FFF75CFED6F80039012223F4F3 -:102C3000004302FA05F5C6F80039D4F81C3823EA37 -:102C40000505CFE700800010008004100080081008 -:102C500000800C1000040002026F12684267FFF748 -:102C600021BE00005831C36E49015B5813F4004087 -:102C700004D013F4001F14BF01200220704700008D -:102C80004831C36E49015B5813F4004004D013F47B -:102C9000001F14BF012002207047000000EB8101DB -:102CA000CB68196A0B6813604B685360704700006B -:102CB00000EB810330B5DD68AA691368D36019B9E8 -:102CC000402B84BF402313606B8A1468C26E1C447F -:102CD00002EB4110013C09B2B4FBF3F4634303334C -:102CE00023F0030343EAC44343F0C043C0F8103B5E -:102CF0002B6803F00303012B0ED1D2F8083802EB46 -:102D0000411013F4807FD0F8003B14BF43F0805390 -:102D100043F00053C0F8003B02EB4112D2F8003BF5 -:102D200043F00443C2F8003B30BD00002DE9F04100 -:102D3000244D0446EE6E06EB4013D3F8087B3807AB -:102D4000C3F8087B0AD5D6F81438190706D505EB61 -:102D5000840321462846DB685B689847FA072FD52D -:102D6000D6F81438DB072BD505EB8403D968CCB92A -:102D70008B69488A5E68B6FBF0F200FB12628AB982 -:102D80001868DA6890420DD2121A83E814002023E2 -:102D900083F311880B482146FFF78AFF84F31188DB -:102DA000BDE8F081012303FA04F26B8923EA0203F0 -:102DB0006B81CB6823B121460248BDE8F04118473A -:102DC000BDE8F0815032022000EB81034A0170B56A -:102DD000DD68C36E6C692668E66056BB1A444FF422 -:102DE0000020C2F810092A6802F00302012A0AB280 -:102DF0000ED1D3F8080803EB421410F4807FD4F806 -:102E0000000914BF40F0805040F00050C4F80009A1 -:102E100003EB4212D2F8000940F00440C2F8000966 -:102E20000122D3F8340802FA01F10143C3F834183F -:102E300070BD19B9402E84BF4020206020681A441C -:102E40002E8A841940F00050013CB4FBF6F440EAAD -:102E5000C440C6E7F8B504461E48C56E05EB4413EA -:102E6000D3F80869F107C3F8086917D5D5F8103801 -:102E7000DA0713D500EB8403D9684B691F68DA6859 -:102E8000974218D2D21B00271A605F60202383F379 -:102E900011882146FFF798FF87F31188330617D56D -:102EA0000123D5F83428A340134211D02046BDE8B1 -:102EB000F840FFF71FBD012303FA04F2038923EA58 -:102EC000020303818B68002BE8D021469847E5E791 -:102ED000F8BD00BF503202209F482DE9F84FC56E63 -:102EE00004466E69AB691E4016F4805F6E6105D0C2 -:102EF000FEF7A6FDBDE8F84FFFF748BC002E12DA3A -:102F0000D5F8003E9B0705D0D5F8003E23F003031B -:102F1000C5F8003ED5F804388F4823F00103C5F802 -:102F20000438FEF7B9FD370502D58B48FEF7A8FD3A -:102F3000B0040CD5D5F8083813F0060FEB6823F46D -:102F400070530CBF43F4105343F4A053EB603107AC -:102F500004D56368DB680BB17F489847F2026FD4F1 -:102F6000B3020CD5D4F86C8000274FF00109DFF8CC -:102F7000E8A1236FF9B29B688B4280F09C80F70632 -:102F800019D5E16E0A6AC2F30A1702F00F0302F4C0 -:102F9000F012B2F5802F00F0B580B2F5402F0AD1C3 -:102FA00004EB830301F58051DB68186A00231A469D -:102FB0009F4240F09C803303D5F818481DD5E703A5 -:102FC00002D50020FFF7B2FEA50302D50120FFF7CE -:102FD000ADFE600302D50220FFF7A8FE210302D553 -:102FE0000320FFF7A3FEE20202D50420FFF79EFEB6 -:102FF000A30202D50520FFF799FE77037FF57AAF8C -:10300000E60702D50020FFF725FFA50702D501201E -:10301000FFF720FF600702D50220FFF71BFF210703 -:1030200002D50320FFF716FFE20602D50420FFF7C2 -:1030300011FFA3067FF55EAF0520FFF70BFF59E7F1 -:10304000D4F86C8000274FF00109DFF80CA1236F42 -:103050005FFA87FB9B685B4582D308EB4B13D3F881 -:10306000002902F44022B2F5802F22D1D3F80029A2 -:10307000002A1EDAD3F8002942F09042C3F8002952 -:10308000D3F80029002AFBDB5946E06EFFF728FC45 -:10309000228909FA0BF322EA0303238104EB8B0351 -:1030A000DB689B6813B15946504698475846FFF76E -:1030B00021FC0137CBE708EB4112D2F8003B03F4C7 -:1030C0004023B3F5802F10D1D2F8003B002B0CDA4F -:1030D000628909FA01F322EA0303638104EB8103A5 -:1030E000DB68DB680BB150469847013741E79C0726 -:1030F00000D10A68072B03F101039EBF0270120A78 -:10310000013055E7023301F5805104EB8302526828 -:1031100090690268D0F808C04068A2EB000E002257 -:10312000104697420AD104EB830463689B699A684E -:103130003A449A605A6817445F603CE712F0030F04 -:1031400000D10868964502F1010282BF8CF80000A8 -:10315000000A0CF1010CE4E750320220C36E03EBCD -:103160004111D1F8003B43F40013C1F8003B704714 -:10317000C36E03EB4111D1F8003943F40013C1F8D9 -:1031800000397047C36E03EB4111D1F8003B23F4C3 -:103190000013C1F8003B7047C36E03EB4111D1F837 -:1031A000003923F40013C1F80039704730B50433F7 -:1031B000039C0172002104FB0325C361049B006092 -:1031C0000363059B4060C1604261026185610462E6 -:1031D00042628162C162436330BD00000022416AE5 -:1031E000C260416101616FF001018262C262FEF75B -:1031F00073BF000003694269934203D1C2680AB1F8 -:1032000000207047181D7047036919600021C268CB -:103210000132C260C269134482699342036124BFD0 -:10322000436A0361FEF74CBF38B504460D46E368B8 -:103230003BB162690020131D1268A3621344E3626C -:1032400038BD237A33B929462046FEF729FF0028E6 -:10325000EDDA38BD6FF00100FBE70000C368C2691A -:10326000013BC3604369134482699342436124BFB5 -:10327000436A436100238362036B03B118477047BD -:1032800070B52023044683F31188866A3EB9FFF7A0 -:10329000CBFF054618B186F31188284670BDA36A96 -:1032A000E26A13F8015B9342A36202D32046FFF760 -:1032B000D5FF002383F31188EFE700002DE9F84FD5 -:1032C00004460E4690469946202787F3118800252C -:1032D000AA46D4F828B0BBF1000F09D149462046D0 -:1032E000FFF7A2FF20B18BF311882846BDE8F88FC5 -:1032F000A16AA8EB050BE36A5B1A9B4528BF9B46B6 -:10330000BBF1400F1BD9334601F1400251F8040BC9 -:10331000914243F8040BF9D1A36A4036403540335B -:10332000A362A26AE36A9A4202D32046FFF796FF9D -:103330008AF311884545D8D287F31188C9E730460A -:103340005A46FDF77FFDA36A5E445D445B44A36279 -:10335000E7E7000010B5029C04330172C36103FB70 -:103360000421002300608362C362039B4060036307 -:10337000049BC460426102618161046242624363F2 -:1033800010BD0000026A6FF00101C260426A426132 -:10339000026100228262C262FEF79EBE4369026938 -:1033A0009A4203D1C2680AB100207047184650F80B -:1033B000043B0B6070470000C3680021C269013301 -:1033C000C3604369134482699342436124BF436AE3 -:1033D0004361FEF775BE000038B504460D46E3684C -:1033E0003BB1236900201A1DA262E2691344E36223 -:1033F00038BD237A33B929462046FEF751FE00280E -:10340000EDDA38BD6FF00100FBE7000003691960D9 -:10341000C268013AC260C26913448269934203617F -:1034200024BF436A036100238362036B03B118471F -:103430007047000070B5202304460E4683F31188C0 -:10344000856A35B91146FFF7C7FF10B185F31188BA -:1034500070BDA36A1E70A36AE26A01339342A3623D -:1034600004D3E16920460439FFF7D0FF002080F340 -:10347000118870BD2DE9F84F04460D4691469A46D5 -:103480004FF0200888F311880026B346A76A4FB989 -:1034900051462046FFF7A0FF20B187F31188304640 -:1034A000BDE8F88FA06AA9EB0603E76A3F1A9F42BE -:1034B00028BF1F46402F1BD905F1400355F8042BA8 -:1034C0009D4240F8042BF9D1A36A40364033A362F1 -:1034D000A26AE36A9A4204D3E16920460439FFF7FD -:1034E00095FF8BF311884E45D9D288F31188CDE72B -:1034F00029463A46FDF7A6FCA36A3D443E443B44B8 -:10350000A362E5E7026943699A4203D1C3681BB924 -:10351000184670470023FBE7836A002BF8D0043B72 -:103520009B1AF5D01360C368013BC360C3691A449A -:1035300083699A42026124BF436A03610023836264 -:103540000123E5E700F040B94FF0804300225863C3 -:103550001A610222DA60704700224FF08043DA607D -:10356000704700004FF0804358637047FEE700004B -:1035700010B5194CFEF79AFCFEF7BCFD80221749E6 -:103580002046FEF741FD012344F8180C0374144B48 -:10359000144AD96821F4E0610904090C0A4312496C -:1035A000DA60CA6842F08072CA60104A1049C2F8F4 -:1035B000B01F116841F0010111601022DA7720225A -:1035C00083F82220002383F3118862B60948BDE8FE -:1035D0001040FEF73BBD00BFDC2A0220D43D0008AE -:1035E00000ED00E00003FA05F0ED00E0001000E05F -:1035F00055CEACC5DC3D00082DE9F84F1E4C4FF010 -:103600000008656904F11407C1464FF08043266A3B -:10361000AA685B6A9E1B96421CD34FF0200AAA68D8 -:10362000236AD5F80CB0B61A134423622B68BB4248 -:103630005F606361C5F80C8001D1FFF78DFF89F3EE -:1036400011882869D8478AF311886569AB689E425A -:10365000E5D2DAE76269BA420CD0916823628E1B28 -:103660009660A86802282CBF1818981CBDE8F84F6F -:10367000FFF778BFBDE8F88FB42A0220034B5968E2 -:103680005A68521A9042FBD8704700BF001000E001 -:103690004B6843608B688360CB68C3600B69436190 -:1036A0004B6903628B6943620B68036070470000DB -:1036B00008B5274B40F2FF7126481A690A431A6180 -:1036C0001A6922F4FF6222F007021A611A691A6B62 -:1036D0000A431A631A6D0A431A651F4A1B6D114685 -:1036E000FFF7D6FF1D4802F11C01FFF7D1FF1C4870 -:1036F00002F13801FFF7CCFF1A4802F15401FFF73D -:10370000C7FF194802F17001FFF7C2FF174802F125 -:103710008C01FFF7BDFF164802F1A801FFF7B8FFC3 -:10372000144802F1C401FFF7B3FF134802F1E001AE -:10373000FFF7AEFF114802F1FC01FFF7A9FF1048A7 -:1037400002F58C71FFF7A4FFBDE8084000F09EB8B9 -:103750000038024000000240FC3D00080004024026 -:1037600000080240000C0240001002400014024019 -:1037700000180240001C02400020024000240240C9 -:103780000028024008B500F0F5F9FFF7F1FEFEF75A -:10379000DBFFBDE80840FEF7B7BD00007047000042 -:1037A0004FF080431A69920710B508D500241C61B8 -:1037B000202383F31188FFF71FFF84F31188BDE8EE -:1037C0001040FEF7E3BF0000104B08211C201A6CCC -:1037D00042F001021A641A6E42F001021A660C4AA3 -:1037E0001B6E936843F0010393604FF080436B229C -:1037F0009A624FF0FF32DA6200229A615A63DA600D -:103800005A6001225A611A60FDF724BD0038024057 -:10381000002004E01B4B4FF0FF3000211A696FEAD3 -:1038200042526FEA52521A611A69C2F30A021A61CD -:103830001A695A6958615A6959615A691A6A62F073 -:1038400080521A621A6A02F080521A621A6A5A6A1E -:1038500058625A6A59625A6A0B4A106840F480707A -:103860001060186F00F44070B0F5007F03D04FF483 -:10387000803018671967536823F40073536000F0B1 -:1038800059B900BF0038024000700040354B4FF47A -:103890004041354A1A64354A11601A6842F0010203 -:1038A0001A601A689207FCD59A6822F003029A609F -:1038B0002C4B19469A6812F00C02FBD1186800F0E4 -:1038C000F90018609A601A6842F480321A600B6836 -:1038D0009B03FCD54B6F43F001034B67214B5A6FA1 -:1038E0009007FCD5224A5A601A6842F080721A602A -:1038F0001E4B1A4659684904FCD5196841F48031B9 -:1039000019605368D803FCD5136843F4003313607F -:10391000164A53689903FCD5124B1A689201FCD5DC -:10392000144A40F207319A6040F20112C3F88C2029 -:103930000022C3F89020104A11609A6842F00202F7 -:103940009A60084B9A6802F00C02082AFAD15A6C65 -:1039500042F480425A645A6E42F480425A665B6E68 -:10396000704700BF003802400004001000700040A3 -:10397000086C400900948838003C0240084A08B5A9 -:10398000536911680B4003F00103536123B1054AE9 -:1039900013680BB150689847BDE80840FEF7F6BEC3 -:1039A000003C0140C8250220084A08B55369116847 -:1039B0000B4003F00203536123B1054A93680BB136 -:1039C000D0689847BDE80840FEF7E0BE003C0140E3 -:1039D000C8250220084A08B5536911680B4003F056 -:1039E0000403536123B1054A13690BB15069984729 -:1039F000BDE80840FEF7CABE003C0140C8250220D1 -:103A0000084A08B5536911680B4003F00803536175 -:103A100023B1054A93690BB1D0699847BDE80840C6 -:103A2000FEF7B4BE003C0140C8250220084A08B594 -:103A3000536911680B4003F01003536123B1054A29 -:103A4000136A0BB1506A9847BDE80840FEF79EBE66 -:103A5000003C0140C8250220174B10B55C691A686C -:103A6000144004F478725A61A30604D5134A936A89 -:103A70000BB1D06A9847600604D5104A136B0BB19E -:103A8000506B9847210604D50C4A936B0BB1D06B51 -:103A90009847E20504D5094A136C0BB1506C98475E -:103AA000A30504D5054A936C0BB1D06C9847BDE8CB -:103AB0001040FEF76BBE00BF003C0140C82502204D -:103AC0001A4B10B55C691A68144004F47C425A61C0 -:103AD000620504D5164A136D0BB1506D9847230546 -:103AE00004D5134A936D0BB1D06D9847E00404D50B -:103AF0000F4A136E0BB1506E9847A10404D50C4ABF -:103B0000936E0BB1D06E9847620404D5084A136FC8 -:103B10000BB1506F9847230404D5054A936F0BB13E -:103B2000D06F9847BDE81040FEF730BE003C014022 -:103B3000C8250220062108B50846FDF78BFB0621A3 -:103B40000720FDF787FB06210820FDF783FB0621F0 -:103B50000920FDF77FFB06210A20FDF77BFB0621EC -:103B60001720FDF777FB06212820BDE80840FDF768 -:103B700071BB000008B5FFF74DFEFDF749FAFDF7F0 -:103B800013FDFDF7E9FEFDF7BDFDFFF707FEBDE8FC -:103B90000840FFF7D7BC0000034611F8012B03F8DB -:103BA000012B002AF9D170471210121312110000D4 -:103BB0000010410001105A00F42A02204826022079 -:103BC00053544D3332463F3F3F3F3F3F0053544DE8 -:103BD000333246375B347C355D780053544D333295 -:103BE00046375B367C375D780000000000960000A9 -:103BF00000000000000000000000000000000000C5 -:103C00000000000000000000711500085D150008AC -:103C10009915000885150008911500087D15000804 -:103C20006915000855150008A515000800000000DA -:103C30007D16000869160008A516000891160008F0 -:103C40009D16000889160008751600086116000800 -:103C50000117000800000000010000000000000043 -:103C60000200000000000000A91800081119000857 -:103C7000400040008C2F02209C2F022002000000F8 -:103C800000000000030000000000000055190008BB -:103C90000000000010000000AC2F02200000000017 -:103CA000010000000000000050320220010102006B -:103CB0004172647550696C6F740025424F415244E3 -:103CC000252D424C002553455249414C250000000A -:103CD000A922000811220008151800088D220008EA +:100270006F8F02F069FB02F00BFB03F0FBF94FF00C +:1002800055301F491B4A91423CBF41F8040BFAE725 +:100290001C49194A91423CBF41F8040BFAE71A493C +:1002A0001A4A1B4B9A423EBF51F8040B42F8040B0A +:1002B000F8E700201749184A91423CBF41F8040B67 +:1002C000FAE702F023FB03F035FA144C144DAC426C +:1002D00003DA54F8041B8847F9E700F041F8114CA1 +:1002E000114DAC4203DA54F8041B8847F9E702F0D9 +:1002F0000BBB0000000602200022022000000008C4 +:100300000000022000060220083F00080022022010 +:1003100068220220682202207834022000020008AD +:100320000002000800020008000200082DE9F04F5A +:100330002DED108AC1F80CD0D0F80CD0BDEC108A8D +:10034000BDE8F08F002383F311882846A0470020E2 +:1003500001F048FEFEE701F0C3FD00DFFEE700000C +:1003600038B500F0C1FC40B1174B6FF07F0100229F +:1003700059720E211A729972DA7202F0E7F9054683 +:1003800002F01AFA0446D0B9104B9D4219D001333D +:100390009D4241F2883512BF044600250124002009 +:1003A00002F0DEF90CB100F059F800F039FD00F070 +:1003B000DBFB284600F0E0F800F050F8F9E70025F4 +:1003C000EDE70546EBE700BF00220220010007B081 +:1003D00008B500F095FBA0F120035842584108BD34 +:1003E00007B541F21203022101A8ADF8043000F074 +:1003F000A5FB03B05DF804FB202310B583F311883F +:100400001248C3680BB101F073FE0023104A4FF489 +:100410007A710E4801F030FE002383F311880D4CF1 +:10042000236813B12368013B2360636813B16368D9 +:10043000013B6360084B1B7833B9636823B9022022 +:1004400000F068FC3223636010BD00BF6822022008 +:10045000F9030008842302207C220220F8B5404BD7 +:10046000404A1C461968013179D004339342F9D1CE +:100470006268A24273D33C4B9B6803F1006303F5AF +:10048000C0339A426BD2002000F088FB0220374B29 +:10049000187000F035FC364B00211A6C19641A6E86 +:1004A00019661A6E5A6C59645A6E59665A6E5A69B0 +:1004B00042F080025A615A6922F080025A615A69F8 +:1004C0001A6942F000521A611A6922F000521A6148 +:1004D0001B6972B64FF0E023C3F8084DD4E900045D +:1004E000BFF34F8FBFF36F8F224AC2F88410BFF360 +:1004F0004F8F536923F480335361BFF34F8FD2F88A +:10050000803043F6E076C3F3C905C3F34E335B0195 +:1005100003EA060C29464CEA81770139C2F8747265 +:10052000F9D2203B13F1200FF2D1BFF34F8FBFF36D +:100530006F8FBFF34F8FBFF36F8F536923F4003377 +:1005400053610023C2F85032BFF34F8FBFF36F8F58 +:10055000202383F31188854680F308882047F8BD5F +:100560000080010820800108002202207C22022055 +:100570000038024000ED00E02DE9F04F93B0A94BA8 +:100580002022FF2100900AA89D6800F0F3FBA64AF4 +:100590001378A3B90121A5481170C360202383F308 +:1005A0001188C3680BB101F0A3FD0023A04A4FF4EA +:1005B0007A719E4801F060FD002383F31188009B4F +:1005C0009C4A03B1136000239B49009C98469B46BC +:1005D0001E469A460B705360012000F091FB24B137 +:1005E000944B1B68002B00F01682002000F088FA64 +:1005F0000390039B002BF2DB012000F077FB039BB1 +:10060000213B162BE8D801A252F823F06906000816 +:100610009106000825070008D9050008D90500083B +:10062000D9050008B90700088B090008A5080008CB +:10063000070900082F09000855090008D905000816 +:1006400067090008D9050008D9090008090700084A +:10065000D90500081D0A00087506000809070008EA +:10066000D9050008070900080220FFF7B1FE00289D +:1006700040F0FB81009B022105A8B8F1000F08BFE4 +:100680001C4641F21233ADF8143000F057FAA3E7DC +:100690004FF47A7000F034FA071EEBDB0220FFF70C +:1006A00097FE0028E6D0013F052F00F2E081DFE849 +:1006B00007F0030A0D1013360523042105A805933E +:1006C00000F03CFA17E004215648F9E704215B48A2 +:1006D000F6E704215A48F3E74FF01C09484609F1B0 +:1006E000040900F05DFA0421059005A800F026FA3F +:1006F000B9F12C0FF2D101204FF0000A00FA07F7F0 +:1007000047EA0B0B5FFA8BFB00F080FB26B10BF086 +:100710000B030B2B08BF0024FFF762FE5CE70421EC +:100720004848CDE7002EA5D00BF00B030B2BA1D131 +:100730000220FFF74DFE074600289BD001203E4EC9 +:1007400000F02CFA4FF000080220307000F0D8FAC8 +:100750005FFA88F9484600F031FA044690B14846FD +:1007600008F1010800F03AFA0028F1D1B846044631 +:1007700041F21213022105A83E46ADF8143000F0F4 +:10078000DDF929E7012325460220337000F0AEFA97 +:10079000244B9B68AB4207D9284600F001FA013090 +:1007A00040F068810435F3E70025234BB8463E4608 +:1007B0001D70204B5D60A7E7002E3FF45BAF0BF090 +:1007C0000B030B2B7FF456AF02201B4B187000F06D +:1007D00097FA322000F094F9B0F10009FFF64AAF21 +:1007E00019F003077FF446AF0E4A09EB0503926840 +:1007F00093423FF63FAFB9F5807F3FF73BAF124BD7 +:10080000B945019322DD4FF47A7000F079F9039035 +:10081000039A002AFFF62EAF039A0137019B03F8D3 +:10082000012BEDE700220220802302206822022013 +:10083000F9030008842302207C22022004220220E3 +:10084000082202200C22022080220220C820FFF76A +:10085000BFFD074600283FF40DAF1F2D11D8C5F18D +:1008600020020AAB25F0030084494A45184428BFFA +:100870004A46019200F058FA019AFF217F4800F0A1 +:1008800079FA4FEAA903C9F387027C492846019304 +:1008900000F078FA064600283FF46AAF019B05EBAA +:1008A000830531E70220FFF793FD00283FF4E2AE15 +:1008B00000F0BEF900283FF4DDAE0027B946704BCA +:1008C0009B68BB4218D91F2F11D80A9B01330ED049 +:1008D00027F0030312AA134453F8203C059348461B +:1008E000042205A9043700F035FB8146E7E73846C6 +:1008F00000F056F90590F2E7CDF81490042105A810 +:1009000000F01CF900E70023642104A8049300F020 +:100910000BF900287FF4AEAE0220FFF759FD002846 +:100920003FF4A8AE049800F06BF90590E6E70023C9 +:10093000642104A8049300F0F7F800287FF49AAE2D +:100940000220FFF745FD00283FF494AE049800F024 +:1009500067F9EAE70220FFF73BFD00283FF48AAE83 +:1009600000F076F9E1E70220FFF732FD00283FF4BE +:1009700081AE05A9142000F071F907460421049006 +:1009800004A800F0DBF83946B9E7322000F0B8F8E7 +:10099000071EFFF66FAEBB077FF46CAE384A07EB5D +:1009A0000A03926893423FF665AE0220FFF710FDFE +:1009B00000283FF45FAE27F003075744BA453FF4E1 +:1009C000A3AE50460AF1040A00F0EAF804210590AB +:1009D00005A800F0B3F8F1E74FF47A70FFF7F8FCE0 +:1009E00000283FF447AE00F023F9002844D00A9BCA +:1009F00001330BD008220AA9002000F0C3F9002817 +:100A00003AD02022FF210AA800F0B4F9FFF7E8FC51 +:100A10001C4801F0EDFA13B0BDE8F08F002E3FF452 +:100A200029AE0BF00B030B2B7FF424AE00236421C3 +:100A300005A8059300F078F8074600287FF41AAE61 +:100A40000220FFF7C5FC814600283FF413AEFFF7F4 +:100A5000C7FC41F2883001F0CBFA059800F018FA93 +:100A60004E463C4600F0D2F9B6E506464CE64FF05D +:100A7000000AFFE5B8467BE6374679E68022022089 +:100A800000220220A0860100F7B50C46184E4FF454 +:100A90007A71054602FB01F396F90020501C0BD138 +:100AA0001448294601930268176A2246B8478442CF +:100AB000019B03D1002310E0002AF1D096F9002019 +:100AC000511C01D0012A0DD10B4829460268166A33 +:100AD0002246B047844205D10123084A0120137001 +:100AE00003B0F0BD4FF4FA7001F082FA0020F7E78E +:100AF00010220220F8270220D4230220D023022033 +:100B0000002307B5024601210DF107008DF80730DB +:100B1000FFF7BAFF20B19DF8070003B05DF804FBB2 +:100B20004FF0FF30F9E700000A46042108B5FFF74F +:100B3000ABFF80F00100C0B2404208BD074B0A463F +:100B400030B41978064B53F82140014623682046FB +:100B5000DD69044BAC4630BC604700BFD0230220A7 +:100B6000BC3B0008A086010070B50A4E00240A4D67 +:100B700001F0DEFC308028683388834208D901F018 +:100B8000D1FC2B6804440133B4F5C03F2B60F2D391 +:100B900070BD00BFD22302208C23022001F08ABD49 +:100BA00000F1006000F5C0300068704700F100609F +:100BB000920000F5C03001F009BD0000054B1A6835 +:100BC000054B1B889B1A834202D9104401F0AABC32 +:100BD000002070478C230220D223022038B5074D15 +:100BE00004462868204401F0A5FC28B92868204460 +:100BF000BDE8384001F0B6BC38BD00BF8C230220F0 +:100C000010F0030309D1B0F5846F04D200F1005055 +:100C1000A0F571200368184670470023FBE7000029 +:100C200000F10050A0F57120D0F8200470470000BA +:100C3000064991F8243033B100230822086A81F86C +:100C40002430FFF7B3BF0120704700BF902302207C +:100C5000014B1868704700BF002004E0204B02469B +:100C6000F0B518681F4BC0F30B06000C1F885D68B9 +:100C7000BE4293F9084022D09F89BE4221D01F8BEB +:100C8000BE4206D102240C2505FB04335D6893F9AE +:100C90000840B0F5805F16D041F20103984208BFCA +:100CA0005A24013A013D0B460A4493420DD215F9EC +:100CB000016F581C5EB1034600F8016CF5E7002493 +:100CC000E1E70124DFE74124EBE7184605E02C25A6 +:100CD00090421D7001D2981C5C70401AF0BD00BF9C +:100CE000002004E01422022000207047022803D1D3 +:100CF000024B4FF080629A61704700BF000C0240C7 +:100D0000022803D1024B4FF480629A61704700BF02 +:100D1000000C0240022804D1024A536983F4806324 +:100D200053617047000C0240002310B5934203D07A +:100D3000CC5CC4540133F9E710BD0000013810B594 +:100D400010F9013F3BB191F900409C4203D11AB127 +:100D50000131013AF4E71AB191F90020981A10BD57 +:100D60001046FCE703460246D01A12F9011B00297F +:100D7000FAD1704702440346934202D003F8011BA4 +:100D8000FAE770472DE9F8431F4D14460746884699 +:100D900095F8242052BBDFF870909CB395F824306E +:100DA0002BB92022FF2148462F62FFF7E3FF95F879 +:100DB00024004146C0F1080205EB8000A24228BF92 +:100DC0002246D6B29200FFF7AFFF95F82430A41B5D +:100DD00017441E449044E4B2F6B2082E85F824600D +:100DE000DBD1FFF725FF0028D7D108E02B6A03EB02 +:100DF00082038342CFD0FFF71BFF0028CBD1002016 +:100E0000BDE8F8830120FBE790230220024B1A780B +:100E1000024B1A70704700BFD0230220102202201C +:100E200038B5154C154D204600F0F0FB29462046FC +:100E300000F018FC2D681248EA6ED2F8043843F02E +:100E40000203C2F8043801F0D3F80E49284600F036 +:100E500011FDEA6E0C48D2F804380C49A04223F088 +:100E60000203C2F804384FF4E1330B6003D0BDE84D +:100E7000384000F02BBB38BDF8270220C83C0008E2 +:100E800040420F00D03C0008D4230220B8230220A7 +:100E900038B50B4B04461A780A4B53F822500A4BCC +:100EA0009D420CD0094B002118221846FFF762FF23 +:100EB000046001462846BDE8384000F007BB38BD55 +:100EC000D0230220BC3B0008F8270220B8230220D0 +:100ED00000B59BB0EFF3098168226846FFF724FF55 +:100EE000EFF30583044B9A6BDA6A9A6A9A6A9A6AF4 +:100EF0009A6A9A6A9B6AFEE700ED00E000B59BB033 +:100F0000EFF3098168226846FFF70EFFEFF30583D0 +:100F1000044B9A6B9A6A9A6A9A6A9A6A9A6A9B6A64 +:100F2000FEE700BF00ED00E000B59BB0EFF30981E4 +:100F300068226846FFF7F8FEEFF30583034B5A6B10 +:100F40009A6A9A6A9A6A9A6A9B6AFEE700ED00E0DA +:100F5000FEE7000030B50A44084D91420DD011F86B +:100F6000013B5840082340F30004013B2C4013F0A0 +:100F7000FF0384EA5000F6D1EFE730BD2083B8EDDF +:100F8000026843681143016003B1184770470000CD +:100F9000024A136843F0C0031360704700780040B2 +:100FA00013B50E4C204600F085FA04F1140000231E +:100FB0004FF480720A49009400F046F9094B4FF44F +:100FC0008072094904F13800009400F0BFF9074A23 +:100FD000074BC4E9172302B010BD00BFD423022081 +:100FE00040240220910F0008402502200078004094 +:100FF00080F93703037C30B5214C002918BF0C461B +:10100000012B0CD11F4B984209D11F4B1A6C42F097 +:1010100080421A641A6E42F080421A661B6E226881 +:10102000036EC16D03EB52038466B3FBF2F3626897 +:10103000150442BF23F0070503F0070343EA450305 +:10104000CB60A36843F040034B60E36843F00103C7 +:101050008B6042F4967343F001030B604FF0FF3353 +:101060000B62510505D512F0102205D0B2F1805F58 +:1010700004D080F8643030BD7F23FAE73F23F8E7DF +:10108000C43B0008D4230220003802402DE9F04779 +:10109000C66D05463768F4692107346219D014F02B +:1010A000080118BF8021E20748BF41F02001A307D3 +:1010B0004FF0200348BF41F04001600748BF41F4B2 +:1010C000807183F31188281DFFF75AFF002383F3F3 +:1010D0001188E2050AD5202383F311884FF40071AB +:1010E000281DFFF74DFF002383F311884FF02009DF +:1010F0004FF0000A14F0200838D13B0616D54FF007 +:10110000200905F1380A200610D589F311885046C8 +:1011100000F050F9002836DA0821281DFFF730FFCB +:1011200027F080033360002383F31188790614D5F8 +:10113000620612D5202383F31188D5E913239A423E +:1011400008D12B6C33B127F040071021281DFFF781 +:1011500017FF3760002383F31188E30618D5AA6EC2 +:101160001369ABB15069BDE8F047184789F311889E +:10117000736A284695F86410194000F0B5F98AF3AF +:101180001188F469B6E7B06288F31188F469BAE7A8 +:10119000BDE8F087F8B51546826804460B46AA42BA +:1011A00000D28568A1692669761AB5420BD2184625 +:1011B0002A46FFF7B9FDA3692B44A3612846A3681B +:1011C0005B1BA360F8BD0CD9AF1B18463246FFF776 +:1011D000ABFD3A46E1683044FFF7A6FDE3683B44C7 +:1011E000EBE718462A46FFF79FFDE368E5E70000B6 +:1011F00083689342F7B50446154600D28568D4E962 +:101200000460361AB5420BD22A46FFF78DFD63699A +:101210002B4463612846A3685B1BA36003B0F0BD49 +:101220000DD93246AF1B0191FFF77EFD01993A4679 +:10123000E0683144FFF778FDE3683B44E9E72A467C +:10124000FFF772FDE368E4E710B50A440024C361C8 +:10125000029B8460C16002610362C0E90000C0E9D2 +:10126000051110BD08B5D0E90532934201D182685D +:1012700082B98268013282605A1C42611970002171 +:10128000D0E904329A4224BFC368436100F0CCFE27 +:10129000002008BD4FF0FF30FBE7000070B52023B1 +:1012A00004460E4683F31188A568A5B1A368A26918 +:1012B000013BA360531CA36115782269934224BFAC +:1012C000E368A361E3690BB120469847002383F3E9 +:1012D0001188284607E03146204600F095FE002898 +:1012E000E2DA85F3118870BD2DE9F74F04460E460A +:1012F00017469846D0F81C904FF0200A8AF31188C0 +:101300004FF0000B154665B12A4631462046FFF7DF +:1013100041FF034660B94146204600F075FE0028B3 +:10132000F1D0002383F31188781B03B0BDE8F08F60 +:10133000B9F1000F03D001902046C847019B8BF301 +:101340001188ED1A1E448AF31188DCE7C160C3617D +:10135000009B82600362C0E905111144C0E90000EE +:1013600001617047F8B504460D461646202383F305 +:101370001188A768A7B1A368013BA36063695A1CE1 +:1013800062611D70D4E904329A4224BFE36863614C +:10139000E3690BB120469847002080F3118807E0ED +:1013A0003146204600F030FE0028E2DA87F311884B +:1013B000F8BD0000D0E9052310B59A4201D182683A +:1013C0007AB982680021013282605A1C82611C78DD +:1013D00003699A4224BFC368836100F025FE20465A +:1013E00010BD4FF0FF30FBE72DE9F74F04460E46E6 +:1013F00017469846D0F81C904FF0200A8AF31188BF +:101400004FF0000B154665B12A4631462046FFF7DE +:10141000EFFE034660B94146204600F0F5FD002886 +:10142000F1D0002383F31188781B03B0BDE8F08F5F +:10143000B9F1000F03D001902046C847019B8BF300 +:101440001188ED1A1E448AF31188DCE702684368AC +:101450001143016003B11847704700001430FFF7D3 +:1014600043BF00004FF0FF331430FFF73DBF0000D3 +:101470003830FFF7B9BF00004FF0FF333830FFF7C7 +:10148000B3BF00001430FFF709BF00004FF0FF3179 +:101490001430FFF703BF00003830FFF763BF0000D0 +:1014A0004FF0FF323830FFF75DBF0000002070477B +:1014B000FFF776BD044B036000234360C0E90233AD +:1014C00001230374704700BFDC3B000810B52023E4 +:1014D000044683F31188FFF78DFD02232374002354 +:1014E00083F3118810BD000038B5C36904460D466A +:1014F0001BB904210844FFF7A9FF294604F1140091 +:10150000FFF7B0FE002806DA201D4FF48061BDE829 +:101510003840FFF79BBF38BD026843681143016044 +:1015200003B118477047000013B5446BD4F8A438D2 +:101530001A681178042915D1217C022912D1197950 +:10154000012312898B4013420CD101A904F14C00F4 +:1015500001F096FFD4F8A4480246019B2179206847 +:1015600000F0D4F902B010BD143001F019BF000032 +:101570004FF0FF33143001F013BF00004C3001F086 +:10158000EBBF00004FF0FF334C3001F0E5BF00002F +:10159000143001F0E7BE00004FF0FF31143001F0CD +:1015A000E1BE00004C3001F0B7BF00004FF0FF3249 +:1015B0004C3001F0B1BF000000207047D0F8A438D3 +:1015C0001A6810B511780446042917D1017C022944 +:1015D00014D15979012352898B4013420ED1143012 +:1015E00001F07AFE024648B1D4F8A4484FF4807363 +:1015F00061792068BDE8104000F076B910BD0000A8 +:10160000406BFFF7DBBF0000704700007FB5124B57 +:1016100001250426044603600023057400F18402BA +:1016200043602946C0E902330C4B02901430019309 +:101630004FF48073009601F02BFE094B04F29442A4 +:10164000294604F14C000294CDE900634FF4807305 +:1016500001F0F2FE04B070BD043C00080116000861 +:10166000291500080B68202282F311880A7903EB00 +:10167000820210624A790D3243F822008A7912B14F +:1016800003EB820318620223C0F8A418037400233A +:1016900083F311887047000038B5037F044613B107 +:1016A00090F85430ABB90125201D0221FFF734FF1B +:1016B00004F114006FF00101257700F0C1FC04F182 +:1016C0004C0084F854506FF00101BDE8384000F040 +:1016D000B7BC38BD10B5012104460430FFF71CFF2C +:1016E0000023237784F8543010BD000038B5044639 +:1016F0000025143001F0E4FD04F14C00257701F0E1 +:10170000B3FE201D84F854500121FFF705FF204649 +:10171000BDE83840FFF752BF90F85C3003F060033B +:10172000202B06D190F85D200023212A03D81F2A00 +:1017300006D800207047222AFBD1C0E9143303E009 +:10174000034A02650722426583650120704700BF96 +:1017500038220220D0F8A43837B51A680446117828 +:1017600004291AD1017C022917D119790123128980 +:101770008B40134211D100F14C05284601F034FF93 +:1017800058B101A9284601F07BFED4F8A4480246CE +:10179000019B2179206800F0B9F803B030BD00004A +:1017A00000EB8103F0B51E6A85B004460D46FEB11C +:1017B000202383F3118804EB8507301D0821FFF7F0 +:1017C000ABFEFB6806F14C005B691B681BB1019026 +:1017D00001F064FE019803A901F052FE024648B1EF +:1017E000039B2946204600F091F8002383F31188DB +:1017F00005B0F0BDFB685A691268002AF5D01B8A53 +:10180000013B1340F1D104F15C02EAE70D3138B538 +:1018100050F82140DCB1202383F31188D4F8A428A8 +:101820001368527903EB8203DB689B695D6845B1FD +:1018300004216018FFF770FE294604F1140001F03E +:1018400055FD2046FFF7BAFE002383F3118838BD0B +:101850007047000001F0EEB801232822002110B5E6 +:10186000044600F8243BFFF785FA0023C4E901335E +:1018700010BD000038B50446202383F311880025ED +:101880004160C0E90355C0E90555C0E9075501F0BD +:10189000E1F80223237085F3118838BD70B500EBA1 +:1018A0008103054650690E461446DA6018B11022CD +:1018B0000021FFF75FFAA06918B110220021FFF79D +:1018C00059FA31462846BDE8704001F08DB9000054 +:1018D000826802F0011282600022C0E90422C0E99D +:1018E0000622026201F00CBAF0B4012500EB81047B +:1018F00047898D40E4683D43A46945812360002306 +:10190000A2606360F0BC01F027BA0000F0B40125CA +:1019100000EB810407898D40E4683D4364690581DB +:1019200023600023A2606360F0BC01F0A1BA000054 +:1019300070B502230025044603704566056280F8F1 +:101940004C50C0E90255C0E90455C0E9065501F004 +:10195000E7F863681B6823B129462046BDE870405C +:10196000184770BD037880F868300523037043681A +:101970001B6810B504460BB1042198470023A360EF +:1019800010BD000090F86820436802701B680BB11E +:10199000052118477047000070B590F84C30044698 +:1019A00013B1002380F84C3004F15C02204601F0B2 +:1019B000C9F963689B68B3B994F85C3013F06005AB +:1019C00035D00021204601F02FFC0021204601F0F7 +:1019D00021FC63681B6813B1062120469847062343 +:1019E00084F84C3070BD204698470028E4D0B4F805 +:1019F0006230626D9A4288BF636594F95C30656DB0 +:101A0000002B4FF0200380F20381002D00F0F280C4 +:101A1000092284F84C2083F3118800212046D4E960 +:101A20001423FFF773FF002383F31188DAE794F898 +:101A30005D2003F07F0343EA022340F20232934227 +:101A400000F0C58021D8B3F5807F48D00DD8012B98 +:101A50003FD0022B00F09380002BB2D104F164023E +:101A6000226502226265A365C1E7B3F5817F00F0BC +:101A70009B80B3F5407FA4D194F85E30012BA0D1B8 +:101A8000B4F8643043F0020332E0B3F5006F4DD098 +:101A900017D8B3F5A06F31D0A3F5C063012B90D850 +:101AA0006368204694F85E205E6894F85F10B4F88E +:101AB0006030B047002884D04368236503686365BD +:101AC0001AE0B3F5106F36D040F6024293427FF42D +:101AD00078AF5C4B2365022363650023C3E794F86A +:101AE0005E30012B7FF46DAFB4F8643023F0020355 +:101AF000A4F86430C4E91455A56578E7B4F85C30FF +:101B0000B3F5A06F0ED194F85E30204684F86630AD +:101B100001F05EF863681B6813B101212046984705 +:101B2000032323700023C4E914339CE704F1670303 +:101B300023650123C3E72378042B10D1202383F3EB +:101B400011882046FFF7C4FE85F3118803216368DE +:101B500084F8675021701B680BB12046984794F8B1 +:101B60005E30002BDED084F8673004232370636876 +:101B70001B68002BD6D0022120469847D2E794F864 +:101B8000603020461D0603F00F010AD501F0CCF8A5 +:101B9000012804D002287FF414AF2B4B9AE72B4B7B +:101BA00098E701F0B3F8F3E794F85E30002B7FF488 +:101BB00008AF94F8603013F00F01B3D01A06204636 +:101BC00002D501F045FBADE701F038FBAAE794F838 +:101BD0005E30002B7FF4F5AE94F8603013F00F0107 +:101BE000A0D01B06204602D501F01EFB9AE701F0AB +:101BF00011FB97E7142284F84C2083F311882B46BD +:101C00002A4629462046FFF76FFE85F31188E9E64C +:101C10005DB1152284F84C2083F311880021204601 +:101C2000D4E91423FFF760FEFDE60B2284F84C2074 +:101C300083F311882B462A4629462046FFF766FE85 +:101C4000E3E700BF343C00082C3C0008303C0008AF +:101C500038B590F84C300446002B3ED0063BDAB243 +:101C60000F2A34D80F2B32D8DFE803F03731310890 +:101C7000223231313131313131313737456DB0F8C0 +:101C800062309D4214D2C3681B8AB5FBF3F203FB9A +:101C900012556DB9202383F311882B462A46294615 +:101CA000FFF734FE85F311880A2384F84C300EE0E8 +:101CB000142384F84C30202383F31188002320461A +:101CC0001A461946FFF710FE002383F3118838BD2A +:101CD000836D03B198470023E7E70021204601F018 +:101CE000A3FA0021204601F095FA63681B6813B13E +:101CF0000621204698470623D7E7000010B590F844 +:101D00004C300446142B29D017D8062B05D001D807 +:101D10001BB110BD093B022BFBD80021204601F06E +:101D200083FA0021204601F075FA63681B6813B13D +:101D3000062120469847062319E0152BE9D10B23ED +:101D400080F84C30202383F3118800231A4619466B +:101D5000FFF7DCFD002383F31188DAE7C3689B6992 +:101D60005B68002BD5D1836D03B19847002384F8BD +:101D70004C30CEE7024B0022C3E900339A60704733 +:101D800040260220002382680374054B1B68996873 +:101D90009142FBD25A6803604260106058607047FD +:101DA0004026022008B5202383F31188037C032BEF +:101DB00005D0042B0DD02BB983F3118808BD4369DE +:101DC00000221A604FF0FF334361FFF7DBFF00236F +:101DD000F2E7D0E9003213605A60F3E7002382682B +:101DE0000374054B1B6899689142FBD85A680360DD +:101DF000426010605860704740260220054B196908 +:101E000008741868026853601A601861012303742B +:101E1000FEF78CBA402602204B1C30B5044687B032 +:101E20000A4D10D02B6901A8094A00F025F9204677 +:101E3000FFF7E4FF049B13B101A800F059F92B69E7 +:101E4000586907B030BDFFF7D9FFF8E740260220F8 +:101E5000A51D000838B50C4D044641612B69816809 +:101E60009A68914203D8BDE83840FFF78BBF184607 +:101E7000FFF7B4FF01232C61014623742046BDE81F +:101E80003840FEF753BA00BF40260220044B1A68C0 +:101E90001B6990689B68984294BF0020012070479E +:101EA0004026022010B5084C236820691A68546047 +:101EB0002260012223611A74FFF790FF0146206916 +:101EC000BDE81040FEF732BA4026022008B5FFF701 +:101ED000DDFF18B1BDE80840FFF7E4BF08BD000012 +:101EE000FFF7E0BFFEE7000010B50C4CFFF742FF24 +:101EF00000F0B4F880220A49204600F03BF80123A4 +:101F000044F8180C037400F071FC002383F311886B +:101F100062B60448BDE8104000F04CB868260220C4 +:101F2000383C0008483C000800F01CB9EFF3118071 +:101F300020B9EFF30583202282F311887047000057 +:101F400010B530B9EFF30584C4F3080414B180F37D +:101F5000118810BDFFF7BAFF84F31188F9E700007C +:101F6000034A516853685B1A9842FBD8704700BF18 +:101F7000001000E082600222028270478368A3F1B1 +:101F80007C0243F80C2C026943F83C2C426943F86C +:101F9000382C074A43F81C2CC268A3F1180043F8F8 +:101FA000102C022203F8082C002203F8072C70479B +:101FB0004503000810B5202383F31188FFF7DEFFE7 +:101FC00000210446FFF746FF002383F311882046D3 +:101FD00010BD0000024B1B6958610F20FFF70EBFB8 +:101FE00040260220202383F31188FFF7F3BF00006F +:101FF00008B50146202383F311880820FFF70CFF62 +:10200000002383F3118808BD49B1064B42681B6960 +:1020100018605A60136043600420FFF7FDBE4FF064 +:10202000FF307047402602200368984206D01A68A5 +:102030000260506018465961FFF7A4BE7047000067 +:1020400038B504460D462068844200D138BD036887 +:1020500023605C604561FFF795FEF4E7054B4FF0A8 +:10206000FF3103F11402C3E905220022C3E907127C +:10207000704700BF4026022070B51C4E05460C4636 +:10208000C0E9032301F0E2FA334653F8142F9A42D1 +:102090000DD130620A2C2CBF00190A302A60C5E924 +:1020A0000124C6E90555BDE8704001F0BDBA316AAA +:1020B000431AE31838BF1C469368A34202D9081993 +:1020C00001F0C0FA73699A6894420CD85A68AC60FF +:1020D0002B606A6015609A685D60121B9A604FF011 +:1020E000FF33F36170BDA41A1B68ECE740260220A1 +:1020F00038B51B4C636998420DD08168D0E9003235 +:1021000013605A600022C2609A680A449A604FF0D5 +:10211000FF33E36138BD03682246002142F8143FD3 +:1021200093425A60C16003D1BDE8384001F084BADF +:102130009A688168256A0A449A6001F087FA63699F +:10214000411B9A688A42E5D9AB181D1A206A092DED +:1021500098BF01F10A02BDE83840104401F072BA9C +:10216000402602202DE9F041184C002704F1140606 +:10217000656901F06BFA236AAA68C11A8A4215D808 +:102180001344D5F80C802362D5E9003213605A60FD +:102190006369EF60B34201D101F04EFA87F3118811 +:1021A0002869C047202383F31188E1E76169B142C0 +:1021B00009D013441B1ABDE8F0410A2B2CBFC018EC +:1021C0000A3001F03FBABDE8F08100BF402602208E +:1021D00000207047FEE70000704700004FF0FF301E +:1021E0007047000002290CD0032904D001290748B8 +:1021F00018BF00207047032A05D8054800EBC2002D +:102200007047044870470020704700BF2C3D00080D +:1022100048220220E03C000870B59AB00546084606 +:10222000144601A900F0C2F801A8FEF79BFD431C6B +:102230000022C6B25B001046C5E9003423700323B8 +:10224000023404F8013C01ABD1B202348E4201D811 +:102250001AB070BD13F8011B013204F8010C04F828 +:10226000021CF1E708B5202383F311880348FFF728 +:1022700071FA002383F3118808BD00BFF8270220FC +:1022800090F85C3003F01F02012A07D190F85D201E +:102290000B2A03D10023C0E9143315E003F06003D7 +:1022A000202B08D1B0F860302BB990F85D20212A9E +:1022B00003D81F2A04D8FFF72FBA222AEBD0FAE757 +:1022C000034A02650722426583650120704700BF0B +:1022D0003F22022007B5052917D8DFE801F01916BB +:1022E00003191920202383F31188104A012101903A +:1022F000FFF7D4FA019802210D4AFFF7CFFA0D48F3 +:10230000FFF7F4F9002383F3118803B05DF804FBB1 +:10231000202383F311880748FFF7BEF9F2E7202353 +:1023200083F311880348FFF7D5F9EBE7803C0008F9 +:10233000A43C0008F827022038B50C4D0C4C2A4666 +:102340000C4904F10800FFF767FF05F1CA0204F128 +:1023500010000949FFF760FF05F5CA7204F1180083 +:102360000649BDE83840FFF757BF00BFD030022014 +:1023700048220220603C00086A3C0008753C0008C6 +:1023800070B5044608460D46FEF7ECFCC6B2204682 +:10239000013403780BB9184670BD32462946FEF762 +:1023A000CDFC0028F3D10120F6E700002DE9F0472D +:1023B00005460C46FEF7D6FC2B49C6B22846FFF769 +:1023C000DFFF08B10736F6B228492846FFF7D8FFE5 +:1023D00008B11036F6B2632E0BD8DFF88C80DFF828 +:1023E0008C90234FDFF894A02E7846B92670BDE874 +:1023F000F08729462046BDE8F04701F0C1BB252EF5 +:102400002ED1072241462846FEF798FC70B9194B99 +:10241000224603F10C0153F8040B8B4242F8040BE3 +:10242000F9D11B8807350E341380DDE708224946B1 +:102430002846FEF783FC98B9A21C0F4B197802328C +:102440000909C95D02F8041C13F8011B01F00F0112 +:102450005345C95D02F8031CF0D118340835C3E7B1 +:10246000013504F8016BBFE74C3D0008753C0008DE +:10247000633D0008543D000820F4F01F2CF4F01FC9 +:10248000BFF34F8F024AD368DB03FCD4704700BF11 +:10249000003C024008B5074B1B7853B9FFF7F0FF2B +:1024A000054B1A69002A04DA044A5A6002F188329C +:1024B0005A6008BD2E330220003C024023016745CC +:1024C00008B5054B1B7833B9FFF7DAFF034A1369E8 +:1024D00043F00043136108BD2E330220003C02404C +:1024E0000B28F0B516D80C4C0C4923787BB90E4656 +:1024F0000B4D0C234FF00062013B55F8047B46F86E +:10250000042B13F0FF033A44F6D10123237051F852 +:102510002000F0BD0020FCE76033022030330220B1 +:10252000743D0008014B53F820007047743D0008CB +:102530000C2070470B2810B5044601D9002010BDAF +:10254000FFF7CEFF064B53F824301844C21A0BB9DC +:102550000120F4E712680132F0D1043BF6E700BF36 +:10256000743D00080B2838B5044628D8FFF7DEFC78 +:102570000546FFF785FF2046FFF78CFF114AF3233E +:10258000D360E300DBB243F4007343F00203136152 +:10259000136943F480331361FFF772FFFFF7A0FF65 +:1025A000094B53F8241000F0E9F82846FFF788FF9C +:1025B000FFF7C6FC2046BDE83840FFF7BBBF002050 +:1025C00038BD00BF003C0240743D000812F001031A +:1025D0002DE9F04105460E4614464BD18218B2F162 +:1025E000026F61D8314B1B6813F001035CD0FFF719 +:1025F0009DFC2F4FFFF74EFFF323314640F2012899 +:10260000FB60FFF73DFF032C18D824F001046D1A7E +:10261000274E40F201180C44A14205EB0107336933 +:102620002AD123F001033361FFF74AFFFFF788FC4B +:102630000120BDE8F081043C0435E4E7AB07E4D1B8 +:102640003B6923F440733B613B6943EA08033B6108 +:1026500051F8046B2E60BFF34F8FFFF711FF2B680B +:102660009E42E8D03B6923F001033B61FFF728FF5E +:10267000FFF766FC0020DCE723F440733361336925 +:1026800043EA080333610B883B80BFF34F8FFFF7AA +:10269000F7FE3F88BFB231F8023BBB42BCD0336982 +:1026A00023F001033361E1E71846C2E70038024036 +:1026B000003C0240084908B50B7828B11BB9FFF768 +:1026C000E9FE01230B7008BD002BFCD00870BDE8AB +:1026D0000840FFF7F5BE00BF2E3302200244074B2F +:1026E000D2B210B5904200D110BD441C00B253F8D4 +:1026F000200041F8040BE0B2F4E700BF502800408E +:102700000F4B30B51C6F240407D41C6F44F40074C5 +:102710001C671C6F44F400441C670A4C0244236885 +:10272000D2B243F480732360074B904200D130BD96 +:10273000441C51F8045B00B243F82050E0B2F4E7C7 +:1027400000380240007000405028004007B50122C8 +:1027500001A90020FFF7C2FF019803B05DF804FB58 +:1027600013B50446FFF7F2FFA04205D0012201A9EC +:1027700000200194FFF7C4FF02B010BD0144BFF375 +:102780004F8F064B884204D3BFF34F8FBFF36F8F39 +:102790007047C3F85C022030F4E700BF00ED00E0B2 +:1027A000034B1A681AB9034AD2F874281A607047A2 +:1027B000643302200030024008B5FFF7F1FF024BFE +:1027C0001868C0F3407008BD64330220EFF309833A +:1027D000054968334A6B22F001024A6383F3098892 +:1027E000002383F31188704700EF00E0202080F37E +:1027F000118862B60D4B0E4AD96821F4E0610904D4 +:10280000090C0A430B49DA60D3F8FC2042F08072CD +:10281000C3F8FC20084AC2F8B01F116841F001015A +:1028200011601022DA7783F82200704700ED00E093 +:102830000003FA0555CEACC5001000E0202310B50A +:1028400083F311880E4B5B6813F4006314D0F1EE30 +:10285000103AEFF309844FF08073683CE361094B51 +:10286000DB6B236684F30988FFF710FB10B1064B7E +:10287000A36110BD054BFBE783F31188F9E700BFA7 +:1028800000ED00E000EF00E0570300085A030008E5 +:1028900070B5BFF34F8FBFF36F8F1A4A0021C2F894 +:1028A0005012BFF34F8FBFF36F8F536943F4003360 +:1028B0005361BFF34F8FBFF36F8FC2F88410BFF324 +:1028C0004F8FD2F8803043F6E074C3F3C900C3F3EE +:1028D0004E335B0103EA0406014646EA817501397D +:1028E000C2F86052F9D2203B13F1200FF2D1BFF3AE +:1028F0004F8F536943F480335361BFF34F8FBFF35E +:102900006F8F70BD00ED00E0FEE700000A4B0B4842 +:102910000B4A90420BD30B4BC11EDA1C121A22F049 +:1029200003028B4238BF00220021FEF723BA53F87E +:10293000041B40F8041BECE7703F000878340220C9 +:1029400078340220783402207047000070B5D0E956 +:102950001B4300224FF0FF359E6804EB42135101E8 +:10296000D3F80009002805DAD3F8000940F08040C8 +:10297000C3F80009D3F8000B002805DAD3F8000BE0 +:1029800040F08040C3F8000B013263189642C3F850 +:102990000859C3F8085BE0D24FF00113C4F81C38A3 +:1029A00070BD00001D4B03EB8002D2F80CC02DE976 +:1029B000F043DCF81420461CDD6ED2F800E005EB95 +:1029C000063605EB4018516871450AD30122D5F847 +:1029D000343802FA00F023EA0000C5F83408BDE8F4 +:1029E000F083AEEB0103BCF81040A34228BF23469E +:1029F000D8F81849A4B2B3EB840FF0D89468A4F1C6 +:102A0000040959F8047F3760A4EB09071F44042F19 +:102A1000F7D81C440B4494605360D4E76833022019 +:102A2000890141F02001016103699B06FCD4122059 +:102A3000FFF796BA10B5054C2046FEF70DFF4FF094 +:102A4000A043E366024B236710BD00BF683302203A +:102A5000C83D000870B503780546012B50D12A4BBC +:102A6000C46E98421BD1294B0E2143205A6B42F071 +:102A700080025A635A6D42F080025A655A6D5A6953 +:102A800042F080025A615A6922F080025A615B6901 +:102A900000F0E8FB1E4BE3601E4BC4F80038002337 +:102AA000EE6EC4F8003EC02323604FF40413A3630A +:102AB0003369002BFCDA01230C203361FFF750FA55 +:102AC0003369DB07FCD41220FFF74AFA3369002B85 +:102AD000FCDA00262846A660FFF738FF6B68C4F8CA +:102AE0001068DB68C4F81468C4F81C684BB90A4B5A +:102AF000A3614FF0FF336361A36843F00103A36058 +:102B000070BD064BF4E700BF683302200038024076 +:102B10004014004003002002003C30C0083C30C09C +:102B2000F8B5C46E054600214FF000662046FFF759 +:102B300077FF296F00234FF001128F684FF0FF30AD +:102B4000C4F83438C4F81C2804EB431201339F4204 +:102B5000C2F80069C2F8006BC2F80809C2F8080B95 +:102B6000F2D20B68EA6E6B67636210231361166919 +:102B700016F01006FBD11220FFF7F2F9D4F8003856 +:102B800023F4FE63C4F80038A36943F4402343F000 +:102B90001003A3610923C4F81038C4F814380A4B91 +:102BA000EB604FF0C043C4F8103B084BC4F8003B47 +:102BB000C4F81069C4F800396B6F03F1100243F4D4 +:102BC00080136A67A362F8BDA43D0008408000102E +:102BD000C26E90F86610D2F8003823F4FE6343EA20 +:102BE0000113C2F8003870472DE9F84300EB810368 +:102BF000C56E0C468046DA680FFA81F948011668FE +:102C000006F00306731E022B05EB41134FF0000183 +:102C100094BFB604384EC3F8101B4FF0010104F105 +:102C2000100398BF06F1805601FA03F3916998BF2B +:102C300006F5004600293AD0578A04F15801374377 +:102C400049016F50D5F81C180B430021C5F81C38FA +:102C50002B180127C3F81019A7405369611E9BB3B5 +:102C6000138A928B9B08012A88BF5343D8F874209B +:102C7000981842EA034301F140022146C8F8740063 +:102C8000284605EB82025360FFF7CAFE08EB890075 +:102C9000C3681B8A43EA845348341E4364012E519F +:102CA000D5F81C381F43C5F81C78BDE8F88305EB40 +:102CB0004917D7F8001B21F40041C7F8001BD5F8CD +:102CC0001C1821EA0303C0E704F13F030B4A28461E +:102CD000214605EB83035A60FFF7A2FE05EB49107E +:102CE000D0F8003923F40043C0F80039D5F81C3877 +:102CF00023EA0707D7E700BF0080001000040002A6 +:102D0000026F12684267FFF721BE00005831C36EA0 +:102D100049015B5813F4004004D013F4001F0CBFAA +:102D200002200120704700004831C36E49015B5802 +:102D300013F4004004D013F4001F0CBF0220012044 +:102D40007047000000EB8101CB68196A0B681360C3 +:102D50004B6853607047000000EB810330B5DD68BD +:102D6000AA691368D36019B9402B84BF402313604C +:102D70006B8A1468C26E1C4402EB4110013C09B21C +:102D8000B4FBF3F46343033323F0030343EAC44384 +:102D900043F0C043C0F8103B2B6803F00303012B42 +:102DA0000ED1D2F8083802EB411013F4807FD0F82E +:102DB000003B14BF43F0805343F00053C0F8003B86 +:102DC00002EB4112D2F8003B43F00443C2F8003B4F +:102DD00030BD00002DE9F041244D0446EE6E06EBB7 +:102DE0004013D3F8087B3807C3F8087B0AD5D6F818 +:102DF0001438190706D505EB840321462846DB68FD +:102E00005B689847FA071FD5D6F81438DB071BD53F +:102E100005EB8403D968CCB98B69488A5A68B2FB40 +:102E2000F0F600FB16228AB91868DA6890420DD2D3 +:102E3000121AC3E90024202383F311880B4821468A +:102E4000FFF78AFF84F31188BDE8F081012303FABC +:102E500004F26B8923EA02036B81CB68002BF3D069 +:102E600021460248BDE8F041184700BF6833022000 +:102E700000EB81034A0170B5DD68C36E6C6926689A +:102E8000E66056BB1A444FF40020C2F810092A68C5 +:102E900002F00302012A0AB20ED1D3F8080803EBAC +:102EA000421410F4807FD4F8000914BF40F0805021 +:102EB00040F00050C4F8000903EB4212D2F80009B8 +:102EC00040F00440C2F800090122D3F8340802FAA5 +:102ED00001F10143C3F8341870BD19B9402E84BF05 +:102EE0004020206020681A442E8A8419013CB4FBDB +:102EF000F6F440EAC44040F00050C6E7F8B5044696 +:102F00001E48C56E05EB4413D3F80869F107C3F8F2 +:102F1000086917D5D5F81038DA0713D500EB840304 +:102F2000D9684B691F68DA68974218D2D21B00270C +:102F30001A605F60202383F311882146FFF798FF12 +:102F400087F31188330617D50123D5F83428A34019 +:102F5000134211D02046BDE8F840FFF723BD0123FE +:102F600003FA04F2038923EA020303818B68002B2E +:102F7000E8D021469847E5E7F8BD00BF6833022056 +:102F80002DE9F74FA24CE66E7569B3691D4015F443 +:102F90008058756107D02046FEF7CAFC03B0BDE833 +:102FA000F04FFFF74BBC002D12DAD6F8003E9F071A +:102FB00005D0D6F8003E23F00303C6F8003ED6F84D +:102FC0000438934823F00103C6F80438FEF7DAFC0E +:102FD000280505D58E48FFF7B9FC8D48FEF7C2FCE1 +:102FE000A9040CD5D6F8083813F0060FF36823F4BB +:102FF00070530CBF43F4105343F4A053F3602A07FB +:1030000004D56368DB680BB181489847EB0200F197 +:103010008A80AF0227D5D4F86C9000274FF0010AC0 +:10302000DFF8ECB109EB4712D2F8003B03F4402380 +:10303000B3F5802F11D1D2F8003B002B0DDA628955 +:103040000AFA07F322EA0303638104EB8703DB68D0 +:10305000DB6813B13946584698470137236FFFB2F2 +:103060009B689F42DED9E80618D5E76E3A6AC2F33C +:103070000A1002F00F0302F4F012B2F5802F00F0F4 +:103080009C80B2F5402F09D104EB8303002207F5A1 +:103090008057DB681B6A904240F082802B03D6F891 +:1030A00018481DD5E70302D50020FFF793FEA603BD +:1030B00002D50120FFF78EFE600302D50220FFF744 +:1030C00089FE210302D50320FFF784FEE20202D528 +:1030D0000420FFF77FFEA30202D50520FFF77AFE4A +:1030E0006F037FF55BAFE60702D50020FFF706FF11 +:1030F000A50702D50120FFF701FF600702D50220D6 +:10310000FFF7FCFE210702D50320FFF7F7FEE206DA +:1031100002D50420FFF7F2FEA3067FF53FAF05209E +:10312000FFF7ECFE3AE7E36E00274FF0010ADFF805 +:10313000E0B00193236F5FFA87F99B6899453FF6EA +:1031400068AF019B03EB4913D3F8002902F4402236 +:10315000B2F5802F22D1D3F80029002A1EDAD3F845 +:10316000002942F09042C3F80029D3F80029002A30 +:10317000FBDB4946E06EFFF753FC22890AFA09F3AC +:1031800022EA0303238104EB8903DB689B6813B104 +:103190004946584698474846FFF704FC0137C9E7B7 +:1031A000910701D1D7F80080072A02F101029CBFE4 +:1031B00003F8018B4FEA18286DE7023307F58057B3 +:1031C00004EB83025268D2F818C0DCF80820DCE96E +:1031D000001CA1EB0C0C002188420AD104EB8304F3 +:1031E00063689B699A6802449A605A6802445A600C +:1031F00054E711F0030F01D1D7F800808C4501F19D +:10320000010184BF02F8018B4FEA1828E4E700BFF0 +:1032100068330220C36E03EB4111D1F8003B43F445 +:103220000013C1F8003B7047C36E03EB4111D1F8A6 +:10323000003943F40013C1F800397047C36E03EB43 +:103240004111D1F8003B23F40013C1F8003B704753 +:10325000C36E03EB4111D1F8003923F40013C1F818 +:1032600000397047090100F16043012203F5614311 +:10327000C9B283F8001300F01F039A4043099B0072 +:1032800003F1604303F56143C3F880211A6070477E +:1032900030B50433039C0172002104FB0325C16097 +:1032A000C0E90653049B0363059BC0E90000C0E925 +:1032B0000422C0E90842C0E90A11436330BD00009E +:1032C0000022416AC260C0E90411C0E90A226FF01D +:1032D0000101FEF7B5BE0000D0E90432934201D1EE +:1032E000C2680AB9181D7047002070470369196049 +:1032F0000021C2680132C260C269134482699342EC +:10330000036124BF436A0361FEF78EBE38B50446ED +:103310000D46E3683BB162690020131D1268A36289 +:103320001344E36207E0237A33B929462046FEF7C7 +:103330006BFE0028EDDA38BD6FF00100FBE70000FE +:10334000C368C269013BC360436913448269934205 +:10335000436124BF436A436100238362036B03B16B +:103360001847704770B52023044683F31188866A96 +:103370003EB9FFF7CBFF054618B186F31188284602 +:1033800070BDA36AE26A13F8015B9342A36202D3A1 +:103390002046FFF7D5FF002383F31188EFE70000F5 +:1033A0002DE9F84F04460E46174698464FF020097F +:1033B00089F311880025AA46D4F828B0BBF1000F84 +:1033C00009D141462046FFF7A1FF20B18BF31188B8 +:1033D0002846BDE8F88FD4E90A12A7EB050B521A6C +:1033E000934528BF9346BBF1400F1BD9334601F1EB +:1033F000400251F8040B914243F8040BF9D1A36A3F +:10340000403640354033A362D4E90A239A4202D3BE +:103410002046FFF795FF8AF31188BD42D8D289F381 +:103420001188C9E730465A46FDF77EFCA36A5E4420 +:103430005D445B44A362E7E710B5029C043301726C +:1034400004FB0321C460C0E906130023C0E90A336A +:10345000039B0363049BC0E90000C0E90422C0E9A8 +:103460000842436310BD0000026A6FF00101C260B0 +:10347000426AC0E904220022C0E90A22FEF7E0BD48 +:10348000D0E904239A4201D1C26822B9184650F803 +:10349000043B0B607047002070470000C3680021A8 +:1034A000C2690133C3604369134482699342436133 +:1034B00024BF436A4361FEF7B7BD000038B5044638 +:1034C0000D46E3683BB1236900201A1DA262E26940 +:1034D0001344E36207E0237A33B929462046FEF716 +:1034E00093FD0028EDDA38BD6FF00100FBE7000026 +:1034F00003691960C268013AC260C26913448269F3 +:103500009342036124BF436A036100238362036B18 +:1035100003B118477047000070B520230D460446DC +:10352000114683F31188866A2EB9FFF7C7FF10B1E1 +:1035300086F3118870BDA36A1D70A36AE26A013325 +:103540009342A36204D3E16920460439FFF7D0FF18 +:10355000002080F31188EDE72DE9F84F04460D4671 +:10356000904699464FF0200A8AF311880026B34608 +:10357000A76A4FB949462046FFF7A0FF20B187F35D +:1035800011883046BDE8F88FD4E90A073A1AA8EB4B +:103590000607974228BF1746402F1BD905F1400365 +:1035A00055F8042B9D4240F8042BF9D1A36A40360C +:1035B0004033A362D4E90A239A4204D3E169204646 +:1035C0000439FFF795FF8BF311884645D9D28AF36A +:1035D0001188CDE729463A46FDF7A6FBA36A3D448C +:1035E0003E443B44A362E5E7D0E904239A4217D165 +:1035F000C3689BB1836A8BB1043B9B1A0ED01360E6 +:10360000C368013BC360C3691A4483699A4202617B +:1036100024BF436A03610023836201231846704775 +:103620000023FBE700F094B84FF08043002258637A +:103630001A610222DA6070474FF080430022DA609C +:10364000704700004FF08043586370474FF080434D +:10365000586A70474B6843608B688360CB68C3606F +:103660000B6943614B6903628B6943620B680360BA +:103670007047000008B52C4B40F2FF712B481A69C7 +:103680000A431A611A6922F4FF6222F007021A61E2 +:103690001A691A6B0A431A631A6D0A431A65244A97 +:1036A0001B6D1146FFF7D6FF00F5806002F11C018B +:1036B000FFF7D0FF00F5806002F13801FFF7CAFF85 +:1036C00000F5806002F15401FFF7C4FF00F580604F +:1036D00002F17001FFF7BEFF00F5806002F18C017E +:1036E000FFF7B8FF00F5806002F1A801FFF7B2FF15 +:1036F00000F5806002F1C401FFF7ACFF00F58060C7 +:1037000002F1E001FFF7A6FF00F5806002F1FC0185 +:10371000FFF7A0FF02F58C7100F58060FFF79AFFBC +:10372000BDE8084000F08AB80038024000000240BE +:10373000D43D000808B500F003FAFEF7D5FBFFF70B +:103740002FF8BDE80840FEF7F7BD00007047000005 +:103750000F4B1A6C42F001021A641A6E42F0010219 +:103760001A660C4A1B6E936843F0010393604FF096 +:1037700080436B229A624FF0FF32DA6200229A6134 +:103780005A63DA605A6001225A611A60704700BFBA +:1037900000380240002004E04FF0804208B5116973 +:1037A000D3680B40D9B29B076FEA0101116107D5BD +:1037B000202383F31188FEF7B7FB002383F31188DE +:1037C00008BD00001B4B4FF0FF3000211A696FEA63 +:1037D00042526FEA52521A611A69C2F30A021A611E +:1037E0001A695A6958615A6959615A691A6A62F0C4 +:1037F00080521A621A6A02F080521A621A6A5A6A6F +:1038000058625A6A59625A6A0B4A106840F48070CA +:103810001060186F00F44070B0F5007F03D04FF4D3 +:10382000803018671967536823F40073536000F001 +:103830005FB900BF0038024000700040364B4FF4C3 +:103840004041364A1A64364A11601A6842F0010251 +:103850001A601A689207FCD59A6822F003029A60EF +:103860002D4B9A6812F00C02FBD1196801F0F90196 +:1038700019609A601A6842F480321A601A689003DC +:10388000FCD55A6F42F001025A67234B5A6F9107D9 +:10389000FCD5244A5A601A6842F080721A60204BA4 +:1038A0005A685204FCD51A6842F480321A605A6889 +:1038B000D003FCD51A6842F400321A60184A5368E3 +:1038C0009903FCD5144B1A689201FCD5164A9A60EC +:1038D00040F20112C3F88C200022C3F8902040F27D +:1038E0000733124A1360136803F00F03072BFAD152 +:1038F000094B9A6842F002029A609A6802F00C0240 +:10390000082AFAD15A6C42F480425A645A6E42F440 +:1039100080425A665B6E7047003802400004001017 +:1039200000700040086C400900948838003C024058 +:10393000074A08B5536903F00103536123B1054AEF +:1039400013680BB150689847BDE80840FEF776BF92 +:10395000003C0140F8330220074A08B5536903F0E0 +:103960000203536123B1054A93680BB1D0689847AD +:10397000BDE80840FEF762BF003C0140F83302207A +:10398000074A08B5536903F00403536123B1054A9C +:1039900013690BB150699847BDE80840FEF74EBF68 +:1039A000003C0140F8330220074A08B5536903F090 +:1039B0000803536123B1054A93690BB1D069984755 +:1039C000BDE80840FEF73ABF003C0140F833022052 +:1039D000074A08B5536903F01003536123B1054A40 +:1039E000136A0BB1506A9847BDE80840FEF726BF3E +:1039F000003C0140F8330220164B10B55C6904F41A +:103A000078725A61A30604D5134A936A0BB1D06A3F +:103A10009847600604D5104A136B0BB1506B98475A +:103A2000210604D50C4A936B0BB1D06B9847E20585 +:103A300004D5094A136C0BB1506C9847A30504D503 +:103A4000054A936C0BB1D06C9847BDE81040FEF767 +:103A5000F5BE00BF003C0140F8330220194B10B501 +:103A60005C6904F47C425A61620504D5164A136D00 +:103A70000BB1506D9847230504D5134A936D0BB1D4 +:103A8000D06D9847E00404D50F4A136E0BB1506E09 +:103A90009847A10404D50C4A936E0BB1D06E984799 +:103AA000620404D5084A136F0BB1506F9847230482 +:103AB00004D5054A936F0BB1D06F9847BDE810400D +:103AC000FEF7BCBE003C0140F833022008B50348B5 +:103AD000FDF7DCFABDE80840FEF7B0BED4230220B3 +:103AE00008B5FFF759FEBDE80840FEF7A7BE000085 +:103AF000062108B50846FFF7B5FB06210720FFF7AA +:103B0000B1FB06210820FFF7ADFB06210920FFF7D6 +:103B1000A9FB06210A20FFF7A5FB06211720FFF7C6 +:103B2000A1FB06212820FFF79DFB07211C20FFF7A2 +:103B300099FB0C215220BDE80840FFF793BB000021 +:103B400008B5FFF73FFE00F00DF8FDF7B1FCFDF7FB +:103B500081FEFDF759FDFFF7F9FDBDE80840FFF7CD +:103B600061BD00000023054A19460133102BC2E94C +:103B7000001102F10802F8D1704700BFF8330220AB +:103B8000034611F8012B03F8012B002AF9D17047E5 +:103B900053544D3332463F3F3F3F3F3F0053544D18 +:103BA000333246375B347C355D780053544D3332C5 +:103BB00046375B367C375D7800000000F82702202E +:103BC000D423022000960000000000000000000046 +:103BD00000000000000000000000000000000000E5 +:103BE0007914000865140008A11400088D14000859 +:103BF0009914000885140008711400085D14000869 +:103C0000AD140008000000008515000871150008BB +:103C1000AD15000899150008A515000891150008B4 +:103C20007D15000869150008B9150008000000009E +:103C300001000000000000006D61696E00000000DE +:103C400069646C6500000000403C0008802602208A +:103C5000F827022001000000E51E00080000000017 +:103C60004172647550696C6F740025424F41524433 +:103C7000252D424C002553455249414C250000005A +:103C80000200000000000000A11700080D18000845 +:103C900040004000A0300220B030022002000000AE +:103CA00000000000030000000000000051180008A0 +:103CB0000000000010000000C030022000000000E2 +:103CC0000100000000000000683302200101020032 +:103CD000D5220008E521000881220008652200089D :103CE00043000000E83C000809024300020100C054 :103CF0003209040000010202010005240010010540 :103D000024010001042402020524060001070582A3 @@ -985,34 +985,33 @@ :103D700044454600008000000080000000800000F4 :103D800000800000000002000000040000000400A9 :103D90000000040000000400000004000000040013 -:103DA0000000040000000000AD1A00088D1D00088E -:103DB000391E000840004000C8320220C8320220EC -:103DC00001000000D8320220800000004001000005 -:103DD000050000006D61696E00000000F43D000800 -:103DE000E0320220D8340220010000006D350008C6 -:103DF0000000000069646C65000000000000802A7B -:103E000000000000AAAAAAAA00000000FFFF00000C -:103E10000000000000A00A000000000100000000F7 -:103E2000AAAAAAAA00000001FFFF000000000000EB -:103E3000000000000001000000000000AAAAAAAAD9 -:103E400000010000FFFF0000000000000000000073 -:103E50000040100000000000AAAAAAAA004000002A -:103E6000FFFB000000000000000000000080420096 -:103E700000000000AAAAAAAA00404100FFFF00001B -:103E800000000080080000000000000000000000AA -:103E9000AAAAAAAA00000000FFFF0000000000007C -:103EA000000000000000000000000000AAAAAAAA6A -:103EB00000000000FFFF0000000000000000000004 -:103EC0000000000000000000AAAAAAAA000000004A -:103ED000FFFF0000000000000000000000000000E4 -:103EE00000000000AAAAAAAA00000000FFFF00002C +:103DA000000004000000000099190008511C0008E0 +:103DB000FD1C000840004000E0330220E0330220F8 +:103DC00001000000F03302208000000040010000EC +:103DD000050000000000802A00000000AAAAAAAA8C +:103DE00000000024FFFF00000000000000A00A0007 +:103DF0000000000100000000AAAAAAAA0000000119 +:103E0000FFFF0000000000000000000000010000B3 +:103E100000000000AAAAAAAA00010000FFFF0000FB +:103E20000000000000000000004010000000000042 +:103E3000AAAAAAAA00400000FFFB000000000000A0 +:103E4000000000000081420000000000AAAAAAAA07 +:103E500000404100EFFF000000000080080000006B +:103E60000000000000000000AAAAAAAA00000000AA +:103E7000FFFF000000000000000000000000000044 +:103E800000000000AAAAAAAA00000000FFFF00008C +:103E90000000000000000000000000000000000022 +:103EA000AAAAAAAA00000000FFFF0000000000006C +:103EB000000000000000000000000000AAAAAAAA5A +:103EC00000000000FFFF00000000000000000000F4 +:103ED00000000000000000000000000000000000E2 +:103EE00000000000000000000000000000000000D2 :103EF00000000000000000000000000000000000C2 -:103F000000000000000000000000000000000000B1 -:103F100000000000000000000000000000000000A1 -:103F20000000000000000000000000000000000091 -:103F3000FF00000000000000C03B00083F00000040 -:103F400049040000CD3B00083F0000005104000080 -:103F5000DB3B00083F000000009600000000080066 -:103F600004000000483D00080000000000000000C0 -:103F70000000000000000000000000000000000041 +:103F000000000000000000008F0000000000000022 +:103F100000801E0000000000FF0000000000000004 +:103F2000903B00083F000000490400009D3B000852 +:103F30003F00000051040000AB3B00083F000000C0 +:103F40000096000000000800960000000008000035 +:103F500004000000483D00080000000000000000D0 +:103F60000000000000000000000000000000000051 :00000001FF diff --git a/Tools/bootloaders/MatekH743-bdshot_bl.bin b/Tools/bootloaders/MatekH743-bdshot_bl.bin old mode 100644 new mode 100755 index 854bcd761fe..6c17c3e04f6 Binary files a/Tools/bootloaders/MatekH743-bdshot_bl.bin and b/Tools/bootloaders/MatekH743-bdshot_bl.bin differ diff --git a/Tools/bootloaders/MatekH743-bdshot_bl.hex b/Tools/bootloaders/MatekH743-bdshot_bl.hex new file mode 100644 index 00000000000..d3b55fee300 --- /dev/null +++ b/Tools/bootloaders/MatekH743-bdshot_bl.hex @@ -0,0 +1,1089 @@ +:020000040800F2 +:1000000000060020A102000829100008A90F00081E +:1000100001100008A90F0008D50F0008A30200086E +:10002000A3020008A3020008A30200081529000883 +:10003000A3020008A3020008A3020008A30200080C +:10004000A3020008A3020008A3020008A3020008FC +:10005000A3020008A30200089D3D0008C93D000856 +:10006000F53D0008213E00084D3E0008A3020008AF +:10007000A3020008A3020008A3020008A3020008CC +:10008000A3020008A3020008A3020008A3020008BC +:10009000A3020008A3020008A3020008793E00089A +:1000A000A3020008A3020008A3020008A30200089C +:1000B000A3020008A3020008A3020008A30200088C +:1000C000A3020008A3020008A3020008A30200087C +:1000D000A3020008A3020008A3020008A30200086C +:1000E000DD3E0008A3020008A3020008A3020008E6 +:1000F000A3020008A3020008A3020008A30200084C +:10010000A3020008A3020008653F0008A30200083C +:10011000A3020008A3020008A3020008A30200082B +:10012000A3020008A3020008A3020008A30200081B +:10013000A3020008A3020008A3020008A30200080B +:10014000A3020008A3020008A3020008A3020008FB +:10015000A3020008A3020008A3020008A3020008EB +:10016000A3020008A3020008A3020008A3020008DB +:10017000A302000881340008A3020008A3020008BB +:10018000A3020008A3020008513F0008A3020008D0 +:10019000A3020008A3020008A3020008A3020008AB +:1001A000A3020008A3020008A3020008A30200089B +:1001B000A3020008A3020008A3020008A30200088B +:1001C000A3020008A3020008A3020008A30200087B +:1001D000A30200086D340008A3020008A30200086F +:1001E000A3020008A3020008A3020008A30200085B +:1001F000A3020008A3020008A3020008A30200084B +:10020000A3020008A3020008A3020008A30200083A +:10021000A3020008A3020008A3020008A30200082A +:10022000A3020008A3020008A3020008A30200081A +:10023000A3020008A3020008A3020008A30200080A +:10024000A3020008A3020008A3020008A3020008FA +:10025000A3020008A3020008A3020008A3020008EA +:10026000A3020008A3020008A3020008A3020008DA +:10027000A3020008A3020008A3020008A3020008CA +:10028000A3020008A3020008A3020008A3020008BA +:10029000A3020008A3020008A3020008A3020008AA +:1002A00002E000F000F8FEE772B63A4880F30888F2 +:1002B000394880F3098839484EF60851CEF20001DA +:1002C000086040F20000CCF200004EF63471CEF22D +:1002D00000010860BFF34F8FBFF36F8F40F2000043 +:1002E000C0F2F0004EF68851CEF200010860BFF374 +:1002F0004F8FBFF36F8F4FF00000E1EE100A4EF604 +:100300003C71CEF200010860062080F31488BFF330 +:100310006F8F02F0BDFB02F05FFB03F0F9FA4FF0C4 +:1003200055301F491B4A91423CBF41F8040BFAE784 +:100330001C49194A91423CBF41F8040BFAE71A499B +:100340001A4A1B4B9A423EBF51F8040B42F8040B69 +:10035000F8E700201749184A91423CBF41F8040BC6 +:10036000FAE702F077FB03F057FB144C144DAC4254 +:1003700003DA54F8041B8847F9E700F041F8114C00 +:10038000114DAC4203DA54F8041B8847F9E702F038 +:100390005FBB0000000600200022002000000008D3 +:1003A00000000020000600208843000800220020F2 +:1003B0005C22002060220020FC460020A0020008F1 +:1003C000A0020008A0020008A00200082DE9F04FDA +:1003D0002DED108AC1F80CD0D0F80CD0BDEC108AED +:1003E000BDE8F08F002383F311882846A047002042 +:1003F00001F078FEFEE701F0F3FD00DFFEE700000C +:1004000038B500F0DDFC30B1164B00220E211A7217 +:100410005A729972DA7202F03DFA054602F070FAE9 +:100420000446D0B9104B9D4219D001339D4241F290 +:10043000883512BF044600250124002002F034FA5A +:100440000CB100F059F800F055FD00F0FFFB284614 +:1004500000F004F900F050F8F9E70025EDE7054653 +:10046000EBE700BF00220020010007B008B500F054 +:10047000B9FBA0F120035842584108BD07B541F22D +:100480001203022101A8ADF8043000F0C9FB03B04B +:100490005DF804FB202310B583F311881248C3686C +:1004A0000BB101F0A5FE0023104A4FF47A710E48FB +:1004B00001F062FE002383F311880D4C236813B111 +:1004C0002368013B2360636813B16368013B636089 +:1004D000084B1B7833B9636823B9022000F084FC11 +:1004E0003223636010BD00BF602200209504000825 +:1004F0007C23002074220020F8B5514B514A1C4641 +:100500001968013100F09B8004339342F8D162688E +:100510004D4B9A4240F293804C4B9B6803F1006331 +:1005200003F500339A4280F08A80002000F0A8FB97 +:100530000220474B187000F04FFC464B0021D3F8C7 +:10054000E820C3F8E810D3F81021C3F81011D3F84D +:100550001021D3F8EC20C3F8EC10D3F81421C3F821 +:100560001411D3F81421D3F8F020C3F8F010D3F805 +:100570001821C3F81811D3F81821D3F8802042F0BD +:100580000062C3F88020D3F8802022F00062C3F814 +:100590008020D3F88020D3F8802042F00072C3F886 +:1005A0008020D3F8802022F00072C3F88020D3F896 +:1005B000803072B64FF0E023C3F8084DD4E9000450 +:1005C000BFF34F8FBFF36F8F234AC2F88410BFF37E +:1005D0004F8F536923F480335361BFF34F8FD2F8A9 +:1005E000803043F6E076C3F3C905C3F34E335B01B5 +:1005F00003EA060C29464CEA81770139C2F8747285 +:10060000F9D2203B13F1200FF2D1BFF34F8FBFF38C +:100610006F8FBFF34F8FBFF36F8F536923F4003396 +:1006200053610023C2F85032BFF34F8FBFF36F8F77 +:10063000202383F31188854680F308882047F8BD7E +:100640000000020820000208FFFF0108002200202D +:10065000742200200044025800ED00E02DE9F04F24 +:1006600093B0A94B2022FF2100900AA89D6800F0BA +:10067000EBFBA64A1378A3B90121A5481170C3600A +:10068000202383F31188C3680BB101F0B1FD00236F +:10069000A04A4FF47A719E4801F06EFD002383F367 +:1006A0001188009B9C4A03B1136000239B49009C66 +:1006B00098469B461E469A460B705360012000F0F8 +:1006C0008BFB24B1944B1B68002B00F0168200209A +:1006D00000F088FA0390039B002BF2DB012000F06E +:1006E00071FB039B213B162BE8D801A252F823F0A3 +:1006F0004D0700087507000809080008BD06000836 +:10070000BD060008BD0600089D0800086F0A000825 +:1007100089090008EB090008130A0008390A0008D3 +:10072000BD0600084B0A0008BD060008BD0A000807 +:10073000ED070008BD060008010B00085907000876 +:10074000ED070008BD060008EB0900080220FFF7CE +:100750008DFE002840F0FB81009B022105A8B8F126 +:10076000000F08BF1C4641F21233ADF8143000F000 +:1007700057FAA3E74FF47A7000F034FA071EEBDB68 +:100780000220FFF773FE0028E6D0013F052F00F29C +:10079000E081DFE807F0030A0D101336052304217A +:1007A00005A8059300F03CFA17E004215648F9E744 +:1007B00004215B48F6E704215A48F3E74FF01C098F +:1007C000484609F1040900F05DFA0421059005A8E6 +:1007D00000F026FAB9F12C0FF2D101204FF0000AF7 +:1007E00000FA07F747EA0B0B5FFA8BFB00F078FB88 +:1007F00026B10BF00B030B2B08BF0024FFF73EFEC6 +:100800005CE704214848CDE7002EA5D00BF00B0390 +:100810000B2BA1D10220FFF729FE074600289BD011 +:1008200001203E4E00F02CFA4FF0000802203070FC +:1008300000F0D2FA5FFA88F9484600F031FA04462F +:1008400090B1484608F1010800F03AFA0028F1D1C9 +:10085000B846044641F21213022105A83E46ADF8FF +:10086000143000F0DDF929E701232546022033701A +:1008700000F0A8FA244B9B68AB4207D9284600F049 +:1008800001FA013040F068810435F3E70025234B7D +:10089000B8463E461D70204B5D60A7E7002E3FF432 +:1008A0005BAF0BF00B030B2B7FF456AF02201B4BFF +:1008B000187000F091FA322000F094F9B0F10009BC +:1008C000FFF64AAF19F003077FF446AF0E4A09EB73 +:1008D0000503926893423FF63FAFB9F5807F3FF73B +:1008E0003BAF124BB945019322DD4FF47A7000F013 +:1008F00079F90390039A002AFFF62EAF039A013785 +:10090000019B03F8012BEDE7002200207823002053 +:1009100060220020950400087C230020742200201F +:1009200004220020082200200C220020782200202F +:10093000C820FFF79BFD074600283FF40DAF1F2D91 +:1009400011D8C5F120020AAB25F0030084494A45BD +:10095000184428BF4A46019200F050FA019AFF213C +:100960007F4800F071FA4FEAA903C9F387027C4976 +:100970002846019300F070FA064600283FF46AAF5B +:10098000019B05EB830531E70220FFF76FFD00288F +:100990003FF4E2AE00F0B0F900283FF4DDAE0027EE +:1009A000B946704B9B68BB4218D91F2F11D80A9BC0 +:1009B00001330ED027F0030312AA134453F8203C4E +:1009C00005934846042205A9043700F02FFB814611 +:1009D000E7E7384600F056F90590F2E7CDF81490B5 +:1009E000042105A800F01CF900E70023642104A8F5 +:1009F000049300F00BF900287FF4AEAE0220FFF75D +:100A000035FD00283FF4A8AE049800F06BF905907E +:100A1000E6E70023642104A8049300F0F7F8002817 +:100A20007FF49AAE0220FFF721FD00283FF494AE38 +:100A3000049800F059F9EAE70220FFF717FD0028B3 +:100A40003FF48AAE00F068F9E1E70220FFF70EFDFF +:100A500000283FF481AE05A9142000F063F9074691 +:100A60000421049004A800F0DBF83946B9E73220ED +:100A700000F0B8F8071EFFF66FAEBB077FF46CAE50 +:100A8000384A07EB0A03926893423FF665AE0220AC +:100A9000FFF7ECFC00283FF45FAE27F00307574454 +:100AA000BA453FF4A3AE50460AF1040A00F0EAF852 +:100AB0000421059005A800F0B3F8F1E74FF47A702F +:100AC000FFF7D4FC00283FF447AE00F015F90028EA +:100AD00044D00A9B01330BD008220AA9002000F061 +:100AE000BBF900283AD02022FF210AA800F0ACF977 +:100AF000FFF7C4FC1C4801F0FBFA13B0BDE8F08F0F +:100B0000002E3FF429AE0BF00B030B2B7FF424AE29 +:100B10000023642105A8059300F078F80746002813 +:100B20007FF41AAE0220FFF7A1FC814600283FF4B3 +:100B300013AEFFF7A3FC41F2883001F0D9FA059813 +:100B400000F012FA4E463C4600F0CAF9B6E50646F9 +:100B50004CE64FF0000AFFE5B8467BE6374679E6FB +:100B60007822002000220020A0860100F7B50C4664 +:100B7000184E4FF47A71054602FB01F396F90020F6 +:100B8000501C0BD11448294601930268176A22466B +:100B9000B8478442019B03D1002310E0002AF1D022 +:100BA00096F90020511C01D0012A0DD10B4829468D +:100BB0000268166A2246B047844205D10123084ADA +:100BC0000120137003B0F0BD4FF4FA7001F090FAF9 +:100BD0000020F7E710220020F0290020CC2300207D +:100BE000C8230020002307B5024601210DF10700AC +:100BF0008DF80730FFF7BAFF20B19DF8070003B06A +:100C00005DF804FB4FF0FF30F9E700000A460421CD +:100C100008B5FFF7ABFF80F00100C0B2404208BD4D +:100C2000074B0A4630B41978064B53F82140014669 +:100C300023682046DD69044BAC4630BC604700BFEA +:100C4000C823002058400008A086010070B50A4E55 +:100C500000240A4D01F0F6FC308028683388834276 +:100C600008D901F0EBFC2B6804440133B4F5003FD4 +:100C70002B60F2D370BD00BFCA2300208423002064 +:100C800001F0BEBD00F1006000F500300068704763 +:100C900000F10060920000F5003001F035BD000069 +:100CA000054B1A68054B1B889B1A834202D91044D6 +:100CB00001F0C4BC0020704784230020CA23002018 +:100CC00038B5074D04462868204401F0BDFC28B91A +:100CD00028682044BDE8384001F0C8BC38BD00BFDA +:100CE000842300200020704700F1FF5000F58F1092 +:100CF000D0F8000870470000064991F8243033B15D +:100D000000230822086A81F82430FFF7C1BF0120C0 +:100D1000704700BF88230020014B1868704700BF50 +:100D20000010005C244BF0B51A680446234BC2F354 +:100D30000B06120C1F885868BE4293F9085028D041 +:100D40009F89BE4206D101200C2505FB003358685F +:100D500093F9085041F201039A421CD041F2030377 +:100D60009A421AD042F201039A4218D042F2030387 +:100D70009A4208BF5625621E0B46441E0A449342FF +:100D80000FD214F9016F581C6EB1034600F8016CC4 +:100D9000F5E70020D8E75A25EDE75925EBE7582578 +:100DA000E9E7184605E02C2482421C7001D9981C02 +:100DB0005D70401AF0BD00BF0010005C14220020DE +:100DC00000207047022803D1024B4FF400229A61A1 +:100DD000704700BF00100258022802D1014B0822C0 +:100DE0009A61704700100258022804D1024A5369E0 +:100DF00083F008035361704700100258002310B5B8 +:100E0000934203D0CC5CC4540133F9E710BD000019 +:100E1000013810B510F9013F3BB191F900409C42F7 +:100E200003D11AB10131013AF4E71AB191F9002066 +:100E3000981A10BD1046FCE703460246D01A12F974 +:100E4000011B0029FAD1704702440346934202D0A5 +:100E500003F8011BFAE770472DE9F8431F4D1446CC +:100E60000746884695F8242052BBDFF870909CB363 +:100E700095F824302BB92022FF2148462F62FFF736 +:100E8000E3FF95F824004146C0F1080205EB80001D +:100E9000A24228BF2246D6B29200FFF7AFFF95F8D4 +:100EA0002430A41B17441E449044E4B2F6B2082E2A +:100EB00085F82460DBD1FFF71FFF0028D7D108E0B9 +:100EC0002B6A03EB82038342CFD0FFF715FF002884 +:100ED000CBD10020BDE8F8830120FBE78823002068 +:100EE000024B1A78024B1A70704700BFC8230020CB +:100EF0001022002038B5164C164D204600F0FAFBA3 +:100F00002946204600F022FC2D681348D5F8902091 +:100F1000D2F8043843F00203C2F8043801F0E8F8CC +:100F20000E49284600F020FDD5F890200C48D2F854 +:100F300004380C49A04223F00203C2F804384FF4ED +:100F4000E1330B6003D0BDE8384000F031BB38BD61 +:100F5000F02900206441000840420F006C41000865 +:100F6000CC230020B023002038B50B4B04461A7860 +:100F70000A4B53F822500A4B9D420CD0094B0021DA +:100F800018221846FFF760FF046001462846BDE8B6 +:100F9000384000F00DBB38BDC82300205840000881 +:100FA000F0290020B023002000B59BB0EFF30981A9 +:100FB00068226846FFF722FFEFF30583044B9A6B24 +:100FC000DA6A9A6A9A6A9A6A9A6A9A6A9B6AFEE7DF +:100FD00000ED00E000B59BB0EFF3098168226846A0 +:100FE000FFF70CFFEFF30583044B9A6B9A6A9A6A3A +:100FF0009A6A9A6A9A6A9B6AFEE700BF00ED00E06F +:1010000000B59BB0EFF3098168226846FFF7F6FE52 +:10101000EFF30583034B5A6B9A6A9A6A9A6A9A6A43 +:101020009B6AFEE700ED00E0FEE7000030B50A44F1 +:10103000084D91420DD011F8013B5840082340F370 +:101040000004013B2C4013F0FF0384EA5000F6D16A +:10105000EFE730BD2083B8ED0268436811430160BB +:1010600003B1184770470000024A136843F0C003F9 +:10107000136070470078004013B50E4C204600F016 +:101080008BFA04F1140000234FF400720A49009413 +:1010900000F04CF9094B4FF40072094904F1380093 +:1010A000009400F0C5F9074A074BC4E9172302B0C2 +:1010B00010BD00BFCC230020382400206910000898 +:1010C000382600200078004000E1F505037C30B5AB +:1010D000244C002918BF0C46012B11D1224B9842F9 +:1010E0000ED1224BD3F8E82042F08042C3F8E8202A +:1010F000D3F8102142F08042C3F81021D3F8103108 +:101100002268036EC16D03EB52038466B3FBF2F3F6 +:101110006268150442BF23F0070503F0070343EAA2 +:101120004503CB60A36843F040034B60E36843F0A2 +:1011300001038B6042F4967343F001030B604FF0A0 +:10114000FF330B62510505D512F0102205D0B2F124 +:10115000805F04D080F8643030BD7F23FAE73F23FE +:10116000F8E700BF60400008CC230020004402588C +:101170002DE9F047C66D05463768F46921073462EA +:1011800019D014F0080118BF8021E20748BF41F0D0 +:101190002001A3074FF0200348BF41F04001600742 +:1011A00048BF41F4807183F31188281DFFF754FF75 +:1011B000002383F31188E2050AD5202383F31188E5 +:1011C0004FF40071281DFFF747FF002383F31188B8 +:1011D0004FF020094FF0000A14F0200838D13B06E8 +:1011E00016D54FF0200905F1380A200610D589F3ED +:1011F0001188504600F050F9002836DA0821281DE1 +:10120000FFF72AFF27F080033360002383F3118860 +:10121000790614D5620612D5202383F31188D5E907 +:1012200013239A4208D12B6C33B127F040071021C9 +:10123000281DFFF711FF3760002383F31188E306B1 +:1012400018D5AA6E1369ABB15069BDE8F0471847CD +:1012500089F31188736A284695F86410194000F0E4 +:10126000B5F98AF31188F469B6E7B06288F311889A +:10127000F469BAE7BDE8F087F8B515468268044618 +:101280000B46AA4200D28568A1692669761AB54242 +:101290000BD218462A46FFF7B1FDA3692B44A36180 +:1012A0002846A3685B1BA360F8BD0CD9AF1B18468A +:1012B0003246FFF7A3FD3A46E1683044FFF79EFD52 +:1012C000E3683B44EBE718462A46FFF797FDE368DF +:1012D000E5E7000083689342F7B50446154600D25F +:1012E0008568D4E90460361AB5420BD22A46FFF766 +:1012F00085FD63692B4463612846A3685B1BA3607B +:1013000003B0F0BD0DD93246AF1B0191FFF776FD5A +:1013100001993A46E0683144FFF770FDE3683B44C9 +:10132000E9E72A46FFF76AFDE368E4E710B50A44F7 +:101330000024C361029B8460C16002610362C0E952 +:101340000000C0E9051110BD08B5D0E9053293428F +:1013500001D1826882B98268013282605A1C42617E +:1013600019700021D0E904329A4224BFC368436156 +:1013700000F0DAFE002008BD4FF0FF30FBE7000070 +:1013800070B5202304460E4683F31188A568A5B1E5 +:10139000A368A269013BA360531CA361157822696D +:1013A000934224BFE368A361E3690BB120469847E9 +:1013B000002383F31188284607E03146204600F0D9 +:1013C000A3FE0028E2DA85F3118870BD2DE9F74FFE +:1013D00004460E4617469846D0F81C904FF0200A57 +:1013E0008AF311884FF0000B154665B12A46314645 +:1013F0002046FFF741FF034660B94146204600F012 +:1014000083FE0028F1D0002383F31188781B03B0FA +:10141000BDE8F08FB9F1000F03D001902046C84716 +:10142000019B8BF31188ED1A1E448AF31188DCE7C7 +:10143000C160C361009B82600362C0E90511114471 +:10144000C0E9000001617047F8B504460D46164634 +:10145000202383F31188A768A7B1A368013BA36089 +:1014600063695A1C62611D70D4E904329A4224BF38 +:10147000E3686361E3690BB120469847002080F37D +:10148000118807E03146204600F03EFE0028E2DAEF +:1014900087F31188F8BD0000D0E9052310B59A4202 +:1014A00001D182687AB982680021013282605A1CB7 +:1014B00082611C7803699A4224BFC368836100F08B +:1014C00033FE204610BD4FF0FF30FBE72DE9F74F0C +:1014D00004460E4617469846D0F81C904FF0200A56 +:1014E0008AF311884FF0000B154665B12A46314644 +:1014F0002046FFF7EFFE034660B94146204600F064 +:1015000003FE0028F1D0002383F31188781B03B079 +:10151000BDE8F08FB9F1000F03D001902046C84715 +:10152000019B8BF31188ED1A1E448AF31188DCE7C6 +:10153000026843681143016003B118477047000017 +:101540001430FFF743BF00004FF0FF331430FFF7B4 +:101550003DBF00003830FFF7B9BF00004FF0FF3348 +:101560003830FFF7B3BF00001430FFF709BF0000A9 +:101570004FF0FF311430FFF703BF00003830FFF7A2 +:1015800063BF00004FF0FF323830FFF75DBF00004F +:1015900000207047FFF770BD044B036000234360D9 +:1015A000C0E9023301230374704700BF784000088C +:1015B00010B52023044683F31188FFF787FD02232B +:1015C0002374002383F3118810BD000038B5C3696C +:1015D00004460D461BB904210844FFF7A9FF29461C +:1015E00004F11400FFF7B0FE002806DA201D4FF4C6 +:1015F0008061BDE83840FFF79BBF38BD0268436893 +:101600001143016003B118477047000013B5406BE8 +:1016100000F58054D4F8A4381A681178042914D13C +:10162000017C022911D11979012312898B401342BF +:101630000BD101A94C3002F06BF8D4F8A448024653 +:10164000019B2179206800F0DFF902B010BD000095 +:10165000143001F0EDBF00004FF0FF33143001F003 +:10166000E7BF00004C3002F0BFB800004FF0FF337E +:101670004C3002F0B9B80000143001F0BBBF0000DC +:101680004FF0FF31143001F0B5BF00004C3002F0D4 +:101690008BB800004FF0FF324C3002F085B80000EC +:1016A0000020704710B500F58054D4F8A4381A68AB +:1016B0001178042917D1017C022914D15979012309 +:1016C00052898B4013420ED1143001F04DFF024677 +:1016D00048B1D4F8A4484FF4407361792068BDE85C +:1016E000104000F07FB910BD406BFFF7DBBF00007A +:1016F000704700007FB5124B0125042604460360A5 +:101700000023057400F1840243602946C0E90233D6 +:101710000C4B0290143001934FF44073009601F08B +:10172000FFFE094B04F69442294604F14C00029452 +:10173000CDE900634FF4407301F0C6FF04B070BD03 +:10174000A0400008E91600080D1600080A682023CA +:1017500083F311880B790B3342F823004B79133351 +:1017600042F823008B7913B10B3342F8230000F5C4 +:101770008053C3F8A41802230374002383F3118851 +:101780007047000038B5037F044613B190F8543019 +:10179000ABB90125201D0221FFF730FF04F1140031 +:1017A0006FF00101257700F0CBFC04F14C0084F8C8 +:1017B00054506FF00101BDE8384000F0C1BC38BDA5 +:1017C00010B5012104460430FFF718FF00232377EA +:1017D00084F8543010BD000038B50446002514309C +:1017E00001F0B6FE04F14C00257701F085FF201DC5 +:1017F00084F854500121FFF701FF2046BDE838402E +:10180000FFF750BF90F8803003F06003202B06D123 +:1018100090F881200023212A03D81F2A06D800200F +:101820007047222AFBD1C0E91D3303E0034A426717 +:1018300007228267C3670120704700BF2C22002067 +:1018400037B500F58055D5F8A4381A681178042901 +:101850001AD1017C022917D11979012312898B40F1 +:10186000134211D100F14C04204602F005F858B1A2 +:1018700001A9204601F04CFFD5F8A4480246019B7F +:101880002179206800F0C0F803B030BD01F10B03EE +:10189000F0B550F8236085B004460D46FEB1202314 +:1018A00083F3118804EB8507301D0821FFF7A6FE9E +:1018B000FB6806F14C005B691B681BB1019001F0ED +:1018C00035FF019803A901F023FF024648B1039BAD +:1018D0002946204600F098F8002383F3118805B0CC +:1018E000F0BDFB685A691268002AF5D01B8A013BDB +:1018F0001340F1D104F18002EAE70000133138B55A +:1019000050F82140ECB1202383F3118804F5805373 +:10191000D3F8A4281368527903EB8203DB689B6930 +:101920005D6845B104216018FFF768FE294604F19F +:10193000140001F023FE2046FFF7B4FE002383F3DA +:10194000118838BD7047000001F016B9012340220C +:10195000002110B5044600F8303BFFF775FA00236C +:10196000C4E9013310BD000010B52023044683F301 +:1019700011882422416000210C30FFF765FA2046CF +:1019800001F01CF902232370002383F3118810BD9A +:1019900070B500EB8103054650690E461446DA60C7 +:1019A00018B110220021FFF74FFAA06918B11022D8 +:1019B0000021FFF749FA31462846BDE8704001F0A2 +:1019C0000FBA000083682022002103F0011310B534 +:1019D000044683601030FFF737FA2046BDE8104018 +:1019E00001F08ABAF0B4012500EB810447898D40EB +:1019F000E4683D43A469458123600023A2606360DD +:101A0000F0BC01F0A7BA0000F0B4012500EB81049E +:101A100007898D40E4683D436469058123600023A4 +:101A2000A2606360F0BC01F01DBB000070B5022332 +:101A300000250446242203702946C0F888500C3043 +:101A400040F8045CFFF700FA204684F8705001F07B +:101A50005BF963681B6823B129462046BDE87040E6 +:101A6000184770BD037880F88C30052303704368F5 +:101A70001B6810B504460BB1042198470023A360EE +:101A800010BD000090F88C20436802701B680BB1F9 +:101A9000052118477047000070B590F87030044673 +:101AA00013B1002380F8703004F18002204601F069 +:101AB00047FA63689B68B3B994F8803013F0600507 +:101AC00035D00021204601F0F1FC0021204601F034 +:101AD000E1FC63681B6813B1062120469847062382 +:101AE00084F8703070BD204698470028E4D0B4F8E0 +:101AF0008630A26F9A4288BFA36794F98030A56FA1 +:101B0000002B4FF0200380F20381002D00F0F280C3 +:101B1000092284F8702083F3118800212046D4E93B +:101B20001D23FFF771FF002383F31188DAE794F890 +:101B3000812003F07F0343EA022340F20232934202 +:101B400000F0C58021D8B3F5807F48D00DD8012B97 +:101B50003FD0022B00F09380002BB2D104F1880219 +:101B600062670222A267E367C1E7B3F5817F00F0F5 +:101B70009B80B3F5407FA4D194F88230012BA0D193 +:101B8000B4F8883043F0020332E0B3F5006F4DD073 +:101B900017D8B3F5A06F31D0A3F5C063012B90D84F +:101BA0006368204694F882205E6894F88310B4F845 +:101BB0008430B047002884D0436863670368A36714 +:101BC0001AE0B3F5106F36D040F6024293427FF42C +:101BD00078AF5C4B63670223A3670023C3E794F8E5 +:101BE0008230012B7FF46DAFB4F8883023F002030C +:101BF000A4F88830C4E91D55E56778E7B4F880306B +:101C0000B3F5A06F0ED194F88230204684F88A3064 +:101C100001F0D8F863681B6813B10121204698478A +:101C2000032323700023C4E91D339CE704F18B03D5 +:101C300063670123C3E72378042B10D1202383F3A8 +:101C400011882046FFF7BEFE85F3118803216368E3 +:101C500084F88B5021701B680BB12046984794F88C +:101C60008230002BDED084F88B300423237063682D +:101C70001B68002BD6D0022120469847D2E794F863 +:101C8000843020461D0603F00F010AD501F04AF901 +:101C9000012804D002287FF414AF2B4B9AE72B4B7A +:101CA00098E701F031F9F3E794F88230002B7FF4E4 +:101CB00008AF94F8843013F00F01B3D01A06204611 +:101CC00002D501F00BFCADE701F0FCFBAAE794F8AC +:101CD0008230002B7FF4F5AE94F8843013F00F01BE +:101CE000A0D01B06204602D501F0E0FB9AE701F0E8 +:101CF000D1FB97E7142284F8702083F311882B46D8 +:101D00002A4629462046FFF76DFE85F31188E9E64D +:101D10005DB1152284F8702083F3118800212046DC +:101D2000D4E91D23FFF75EFEFDE60B2284F8702048 +:101D300083F311882B462A4629462046FFF764FE86 +:101D4000E3E700BFD0400008C8400008CC400008CE +:101D500038B590F870300446002B3ED0063BDAB21E +:101D60000F2A34D80F2B32D8DFE803F0373131088F +:101D7000223231313131313131313737856FB0F87D +:101D800086309D4214D2C3681B8AB5FBF3F203FB75 +:101D900012556DB9202383F311882B462A46294614 +:101DA000FFF732FE85F311880A2384F870300EE0C5 +:101DB000142384F87030202383F3118800232046F5 +:101DC0001A461946FFF70EFE002383F3118838BD2B +:101DD000C36F03B198470023E7E70021204601F0D5 +:101DE00065FB0021204601F055FB63681B6813B1B9 +:101DF0000621204698470623D7E7000010B590F843 +:101E000070300446142B29D017D8062B05D001D8E2 +:101E10001BB110BD093B022BFBD80021204601F06D +:101E200045FB0021204601F035FB63681B6813B1B8 +:101E3000062120469847062319E0152BE9D10B23EC +:101E400080F87030202383F3118800231A46194646 +:101E5000FFF7DAFD002383F31188DAE7C3689B6993 +:101E60005B68002BD5D1C36F03B19847002384F87A +:101E70007030CEE7024B0022C3E900339A6070470E +:101E800038280020002382680374054B1B6899687A +:101E90009142FBD25A6803604260106058607047FC +:101EA0003828002008B5202383F31188037C032BF6 +:101EB00005D0042B0DD02BB983F3118808BD4369DD +:101EC00000221A604FF0FF334361FFF7DBFF00236E +:101ED000F2E7D0E9003213605A60F3E7002382682A +:101EE0000374054B1B6899689142FBD85A680360DC +:101EF000426010605860704738280020054B19690F +:101F000008741868026853601A601861012303742A +:101F1000FEF75CBA382800204B1C30B5044687B069 +:101F20000A4D10D02B6901A8094A00F025F9204676 +:101F3000FFF7E4FF049B13B101A800F059F92B69E6 +:101F4000586907B030BDFFF7D9FFF8E738280020FF +:101F5000A51E000838B50C4D044641612B69816807 +:101F60009A68914203D8BDE83840FFF78BBF184606 +:101F7000FFF7B4FF01232C61014623742046BDE81E +:101F80003840FEF723BA00BF38280020044B1A68F7 +:101F90001B6990689B68984294BF0020012070479D +:101FA0003828002010B5084C236820691A6854604E +:101FB0002260012223611A74FFF790FF0146206915 +:101FC000BDE81040FEF702BA3828002008B5FFF738 +:101FD000DDFF18B1BDE80840FFF7E4BF08BD000011 +:101FE000FFF7E0BFFEE7000010B50C4CFFF742FF23 +:101FF00000F0B4F880220A49204600F03BF80123A3 +:1020000044F8180C037400F095FC002383F3118846 +:1020100062B60448BDE8104000F04CB860280020CB +:10202000D4400008E440000800F01CB9EFF3118030 +:1020300020B9EFF30583202282F311887047000056 +:1020400010B530B9EFF30584C4F3080414B180F37C +:10205000118810BDFFF7BAFF84F31188F9E700007B +:10206000034A516853685B1A9842FBD8704700BF17 +:10207000001000E082600222028270478368A3F1B0 +:102080007C0243F80C2C026943F83C2C426943F86B +:10209000382C074A43F81C2CC268A3F1180043F8F7 +:1020A000102C022203F8082C002203F8072C70479A +:1020B000E503000810B5202383F31188FFF7DEFF46 +:1020C00000210446FFF746FF002383F311882046D2 +:1020D00010BD0000024B1B6958610F20FFF70EBFB7 +:1020E00038280020202383F31188FFF7F3BF000076 +:1020F00008B50146202383F311880820FFF70CFF61 +:10210000002383F3118808BD49B1064B42681B695F +:1021100018605A60136043600420FFF7FDBE4FF063 +:10212000FF307047382800200368984206D01A68AC +:102130000260506018465961FFF7A4BE7047000066 +:1021400038B504460D462068844200D138BD036886 +:1021500023605C604561FFF795FEF4E7054B4FF0A7 +:10216000FF3103F11402C3E905220022C3E907127B +:10217000704700BF3828002070B51C4E05460C463D +:10218000C0E9032301F0AEFB334653F8142F9A4203 +:102190000DD130620A2C2CBF00190A302A60C5E923 +:1021A0000124C6E90555BDE8704001F085BB316AE0 +:1021B000431AE31838BF1C469368A34202D9081992 +:1021C00001F08AFB73699A6894420CD85A68AC6033 +:1021D0002B606A6015609A685D60121B9A604FF010 +:1021E000FF33F36170BDA41A1B68ECE738280020A8 +:1021F00038B51B4C636998420DD08168D0E9003234 +:1022000013605A600022C2609A680A449A604FF0D4 +:10221000FF33E36138BD03682246002142F8143FD2 +:1022200093425A60C16003D1BDE8384001F04EBB13 +:102230009A688168256A0A449A6001F053FB6369D1 +:10224000411B9A688A42E5D9AB181D1A206A092DEC +:1022500098BF01F10A02BDE83840104401F03CBBD0 +:10226000382800202DE9F041184C002704F114060D +:10227000656901F037FB236AAA68C11A8A4215D83A +:102280001344D5F80C802362D5E9003213605A60FC +:102290006369EF60B34201D101F018FB87F3118845 +:1022A0002869C047202383F31188E1E76169B142BF +:1022B00009D013441B1ABDE8F0410A2B2CBFC018EB +:1022C0000A3001F009BBBDE8F08100BF38280020CA +:1022D00000207047FEE70000704700004FF0FF301D +:1022E0007047000002290CD0032904D001290748B7 +:1022F00018BF00207047032A05D8054800EBC2002C +:102300007047044870470020704700BFC84100086C +:102310003C2200207C41000870B59AB00546084672 +:10232000144601A900F0C2F801A8FEF785FD431C80 +:102330000022C6B25B001046C5E9003423700323B7 +:10234000023404F8013C01ABD1B202348E4201D810 +:102350001AB070BD13F8011B013204F8010C04F827 +:10236000021CF1E708B5202383F311880348FFF727 +:1023700067FA002383F3118808BD00BFF02900200D +:1023800090F8803003F01F02012A07D190F88120D5 +:102390000B2A03D10023C0E91D3315E003F06003CD +:1023A000202B08D1B0F884302BB990F88120212A55 +:1023B00003D81F2A04D8FFF725BA222AEBD0FAE760 +:1023C000034A426707228267C3670120704700BF44 +:1023D0003322002007B5052917D8DFE801F01916C8 +:1023E00003191920202383F31188104A0121019039 +:1023F000FFF7CEFA019802210D4AFFF7C9FA0D48FE +:10240000FFF7EAF9002383F3118803B05DF804FBBA +:10241000202383F311880748FFF7B4F9F2E720235C +:1024200083F311880348FFF7CBF9EBE71C41000861 +:1024300040410008F029002038B50C4D0C4C2A46CC +:102440000C4904F10800FFF767FF05F1CA0204F127 +:1024500010000949FFF760FF05F5CA7204F1180082 +:102460000649BDE83840FFF757BF00BFC84200200B +:102470003C220020FC4000080641000811410008F1 +:1024800070B5044608460D46FEF7D6FCC6B2204697 +:10249000013403780BB9184670BD32462946FEF761 +:1024A000B7FC0028F3D10120F6E700002DE9F04742 +:1024B00005460C46FEF7C0FC2A49C6B22846FFF77F +:1024C000DFFF08B10936F6B227492846FFF7D8FFE3 +:1024D00008B11036F6B2632E0BD8DFF88880DFF82B +:1024E0008890224FDFF890A02E7846B92670BDE87C +:1024F000F08729462046BDE8F04701F097BD252E1C +:102500002CD1072241462846FEF782FC60B9184BC1 +:10251000224603F1100153F8040B8B4242F8040BDE +:10252000F9D107351034DFE7082249462846FEF77F +:102530006FFC98B9A21C0F4B197802320909C95DCA +:1025400002F8041C13F8011B01F00F015345C95D8B +:1025500002F8031CF0D118340835C5E7013504F83A +:10256000016BC1E7E8410008114100080142000881 +:10257000F041000800E8F11F0CE8F11FBFF34F8F96 +:10258000044B1A695107FCD1D3F810215207F8D136 +:10259000704700BF0020005208B50D4B1B78ABB947 +:1025A000FFF7ECFF0B4BDA68D10704D50A4A5A60F3 +:1025B00002F188325A60D3F80C21D20706D5064AB8 +:1025C000C3F8042102F18832C3F8042108BD00BF1A +:1025D00026450020002000522301674508B5114B15 +:1025E0001B78F3B9104B1A69510703D5DA6842F02A +:1025F0004002DA60D3F81021520705D5D3F80C2138 +:1026000042F04002C3F80C21FFF7B8FF064BDA682E +:1026100042F00102DA60D3F80C2142F00102C3F863 +:102620000C2108BD26450020002000520F289ABF2B +:1026300000F5806040040020704700004FF4003037 +:1026400070470000102070470F2808B50BD8FFF71F +:10265000EDFF00F500330268013204D104308342FB +:10266000F9D1012008BD0020FCE700000F2870B55B +:10267000054645D8FFF7DAFC224CFFF77FFF0646F8 +:10268000FFF78AFF4FF0FF33072D6361C4F8143161 +:1026900020D82361FFF772FF2B0243F02403E3608D +:1026A000E36843F08003E36023695A07FCD42846BB +:1026B000FFF764FF4FF40031FFF7B8FF00F002F9B5 +:1026C0003046FFF78BFFFFF7BBFC2846BDE87040A4 +:1026D000FFF7BABFC4F81031FFF750FFA5F10803A8 +:1026E0001B0243F02403C4F80C31D4F80C3143F03E +:1026F0008003C4F80C31D4F810315B07FBD4D6E763 +:10270000002070BD002000522DE9F84F40EA02037E +:1027100005460C461746D80602D00020BDE8F88FC3 +:1027200027F01F07DFF8D4B0FFF736FF2744BC427D +:1027300003D10120FFF752FFF0E72022294620466F +:1027400001F064FC10B920352034F0E72B4605F188 +:1027500020021E68711CE0D104339A42F9D1FFF7C0 +:1027600065FC05F17843234AB3F5801F224B28BF4F +:102770009A4603F1040338BF9046A2F1080228BF2D +:102780009846A3F108033ABF9146DA469946FFF707 +:10279000F5FEC8F80060A5EB040CD9F8002004F1A0 +:1027A0001C0142F00202C9F80020221FDAF8006082 +:1027B00016F00506FAD152F8043F8A424CF802306E +:1027C000F4D1BFF34F8FFFF7D9FE4FF0FF32C8F8B7 +:1027D0000020D9F8002022F00202C9F80020FFF7FB +:1027E0002FFC20222146284601F010FC0028AAD008 +:1027F00030469FE714200052102100521020005252 +:1028000010B5084C237828B11BB9FFF7C5FE01238A +:10281000237010BD002BFCD02070BDE81040FFF7E6 +:10282000DDBE00BF264500200244074BD2B210B5E2 +:10283000904200D110BD441C00B253F8200041F872 +:10284000040BE0B2F4E700BF504000580E4B30B527 +:102850001C6F240405D41C6F1C671C6F44F40044D7 +:102860001C670A4C02442368D2B243F4807323608D +:10287000074B904200D130BD441C51F8045B00B2BC +:1028800043F82050E0B2F4E70044025800480258F0 +:102890005040005807B5012201A90020FFF7C4FFEE +:1028A000019803B05DF804FB13B50446FFF7F2FF8F +:1028B000A04205D0012201A900200194FFF7C6FF24 +:1028C00002B010BD0144BFF34F8F064B884204D3C2 +:1028D000BFF34F8FBFF36F8F7047C3F85C02203098 +:1028E000F4E700BF00ED00E0034B1A681AB9034A91 +:1028F000D2F8D0241A6070472845002000400258C2 +:1029000008B5FFF7F1FF024B1868C0F3806008BDFF +:1029100028450020EFF30983054968334A6B22F00C +:1029200001024A6383F30988002383F31188704707 +:1029300000EF00E0202080F3118862B60D4B0E4AB4 +:10294000D96821F4E0610904090C0A430B49DA60F3 +:10295000D3F8FC2042F08072C3F8FC20084AC2F889 +:10296000B01F116841F0010111601022DA7783F87D +:102970002200704700ED00E00003FA0555CEACC51B +:10298000001000E0202310B583F311880E4B5B6824 +:1029900013F4006314D0F1EE103AEFF309844FF012 +:1029A0008073683CE361094BDB6B236684F3098821 +:1029B000FFF7ECFA10B1064BA36110BD054BFBE726 +:1029C00083F31188F9E700BF00ED00E000EF00E0BD +:1029D000F7030008FA03000870B5BFF34F8FBFF389 +:1029E0006F8F1A4A0021C2F85012BFF34F8FBFF306 +:1029F0006F8F536943F400335361BFF34F8FBFF3BD +:102A00006F8FC2F88410BFF34F8FD2F8803043F637 +:102A1000E074C3F3C900C3F34E335B0103EA040659 +:102A2000014646EA81750139C2F86052F9D2203B6D +:102A300013F1200FF2D1BFF34F8F536943F480336A +:102A40005361BFF34F8FBFF36F8F70BD00ED00E098 +:102A5000FEE700000A4B0B480B4A90420BD30B4B8E +:102A6000C11EDA1C121A22F003028B4238BF002268 +:102A70000021FEF7E9B953F8041B40F8041BECE70A +:102A8000E4430008FC460020FC460020FC460020F1 +:102A90007047000070B5D0E9244300224FF0FF35A5 +:102AA0009E6804EB42135101D3F80009002805DAAF +:102AB000D3F8000940F08040C3F80009D3F8000BB8 +:102AC000002805DAD3F8000B40F08040C3F8000B73 +:102AD000013263189642C3F80859C3F8085BE0D284 +:102AE0004FF00113C4F81C3870BD000000EB8103E7 +:102AF000D3F80CC02DE9F043DCF814204E1CD0F8BC +:102B00009050D2F800E005EB063605EB411850680E +:102B100070450AD30122D5F8343802FA01F123EACC +:102B20000101C5F83418BDE8F083AEEB0003BCF832 +:102B30001040A34228BF2346D8F81849A4B2B3EBEB +:102B4000840FF0D89468A4F1040959F8047F376021 +:102B5000A4EB09071F44042FF7D81C4403449460D6 +:102B60005360D4E7890141F02001016103699B06AC +:102B7000FCD41220FFF774BA10B50A4C2046FEF7B9 +:102B8000E5FE094BC4F89030084BC4F89430084C6B +:102B90002046FEF7DBFE074BC4F89030064BC4F826 +:102BA000943010BD2C450020000008403842000839 +:102BB000C8450020000004404442000870B5037876 +:102BC0000546012B5DD1494BD0F89040984259D130 +:102BD000474B0E216520D3F8D82042F00062C3F89D +:102BE000D820D3F8002142F00062C3F80021D3F8C6 +:102BF0000021D3F8802042F00062C3F88020D3F88F +:102C0000802022F00062C3F88020D3F8803000F0EA +:102C100071FC384BE360384BC4F800380023D5F81A +:102C20009060C4F8003EC02323604FF40413A363F4 +:102C30003369002BFCDA01230C203361FFF710FA13 +:102C40003369DB07FCD41220FFF70AFA3369002B43 +:102C5000FCDA00262846A660FFF71CFF6B68C4F864 +:102C60001068DB68C4F81468C4F81C68002B3AD1FB +:102C7000224BA3614FF0FF336361A36843F001036C +:102C8000A36070BD1E4B9842C8D1194B0E214D2038 +:102C9000D3F8D82042F00072C3F8D820D3F800212E +:102CA00042F00072C3F80021D3F80021D3F880204D +:102CB00042F00072C3F88020D3F8802022F0007226 +:102CC000C3F88020D3F88020D3F8D82022F0806287 +:102CD000C3F8D820D3F8002122F08062C3F8002185 +:102CE000D3F8003193E7074BC3E700BF2C45002022 +:102CF000004402584014004003002002003C30C051 +:102D0000C8450020083C30C0F8B5D0F890400546D2 +:102D100000214FF000662046FFF724FFD5F89410FD +:102D200000234FF001128F684FF0FF30C4F83438A1 +:102D3000C4F81C2804EB431201339F42C2F8006917 +:102D4000C2F8006BC2F80809C2F8080BF2D20B688F +:102D5000D5F89020C5F89830636210231361166986 +:102D600016F01006FBD11220FFF77AF9D4F80038DC +:102D700023F4FE63C4F80038A36943F4402343F00E +:102D80001003A3610923C4F81038C4F814380B4B9E +:102D9000EB604FF0C043C4F8103B094BC4F8003B54 +:102DA000C4F81069C4F80039D5F8983003F110025E +:102DB00043F48013C5F89820A362F8BD14420008BC +:102DC00040800010D0F8902090F88A10D2F8003897 +:102DD00023F4FE6343EA0113C2F800387047000091 +:102DE0002DE9F84300EB8103D0F890500C46804663 +:102DF000DA680FFA81F94801166806F00306731EB7 +:102E0000022B05EB41134FF0000194BFB604384E7E +:102E1000C3F8101B4FF0010104F1100398BF06F135 +:102E2000805601FA03F3916998BF06F50046002920 +:102E30003AD0578A04F15801374349016F50D5F809 +:102E40001C180B430021C5F81C382B180127C3F8A8 +:102E50001019A7405369611E9BB3138A928B9B087C +:102E6000012A88BF5343D8F89820981842EA0343B0 +:102E700001F140022146C8F89800284605EB82027D +:102E80005360FFF76FFE08EB8900C3681B8A43EAB3 +:102E9000845348341E4364012E51D5F81C381F4317 +:102EA000C5F81C78BDE8F88305EB4917D7F8001B77 +:102EB00021F40041C7F8001BD5F81C1821EA0303D0 +:102EC000C0E704F13F030B4A2846214605EB830384 +:102ED0005A60FFF747FE05EB4910D0F8003923F49C +:102EE0000043C0F80039D5F81C3823EA0707D7E7B4 +:102EF0000080001000040002D0F894201268C0F88E +:102F00009820FFF7C7BD00005831D0F89030490134 +:102F10005B5813F4004004D013F4001F0CBF0220D0 +:102F2000012070474831D0F8903049015B5813F4C4 +:102F3000004004D013F4001F0CBF02200120704792 +:102F400000EB8101CB68196A0B6813604B68536012 +:102F50007047000000EB810330B5DD68AA69136893 +:102F6000D36019B9402B84BF402313606B8A146867 +:102F7000D0F890201C4402EB4110013C09B2B4FB94 +:102F8000F3F46343033323F0030343EAC44343F0FE +:102F9000C043C0F8103B2B6803F00303012B0ED194 +:102FA000D2F8083802EB411013F4807FD0F8003BD0 +:102FB00014BF43F0805343F00053C0F8003B02EBD2 +:102FC0004112D2F8003B43F00443C2F8003B30BD4D +:102FD0002DE9F041D0F8906005460C4606EB411310 +:102FE000D3F8087B3A07C3F8087B08D5D6F814381D +:102FF0001B0704D500EB8103DB685B689847FA0781 +:103000001FD5D6F81438DB071BD505EB8403D96828 +:10301000CCB98B69488A5A68B2FBF0F600FB1622DD +:103020008AB91868DA6890420DD2121AC3E90024EE +:10303000202383F3118821462846FFF78BFF84F372 +:103040001188BDE8F081012303FA04F26B8923EAB9 +:1030500002036B81CB68002BF3D021462846BDE8E4 +:10306000F041184700EB81034A0170B5DD68D0F8E4 +:1030700090306C692668E66056BB1A444FF4002015 +:10308000C2F810092A6802F00302012A0AB20ED11E +:10309000D3F8080803EB421410F4807FD4F8000939 +:1030A00014BF40F0805040F00050C4F8000903EB1A +:1030B0004212D2F8000940F00440C2F8000901228F +:1030C000D3F8340802FA01F10143C3F8341870BD93 +:1030D00019B9402E84BF4020206020681A442E8AEF +:1030E0008419013CB4FBF6F440EAC44040F00050BF +:1030F000C6E700002DE9F041D0F8906004460D4687 +:1031000006EB4113D3F80879C3F80879FB071CD5FF +:10311000D6F81038DA0718D500EB8103D3F80CC0C5 +:10312000DCF81430D3F800E0DA6896451BD2A2EB45 +:103130000E024FF000081A60C3F80480202383F3C6 +:103140001188FFF78FFF88F311883B0618D50123FC +:10315000D6F83428AB40134212D029462046BDE8A9 +:10316000F041FFF7C3BC012303FA01F2038923EA0C +:1031700002030381DCF80830002BE6D09847E4E72F +:10318000BDE8F0812DE9F84FD0F8905004466E6903 +:10319000AB691E4016F480586E6103D0BDE8F84F4D +:1031A000FEF744BC002E12DAD5F8003E9F0705D08A +:1031B000D5F8003E23F00303C5F8003ED5F80438E7 +:1031C000204623F00103C5F80438FEF75BFC300508 +:1031D00005D52046FFF75EFC2046FEF743FCB10410 +:1031E0000CD5D5F8083813F0060FEB6823F47053AC +:1031F0000CBF43F4105343F4A053EB60320704D5E3 +:103200006368DB680BB120469847F30200F1BA808F +:10321000B70226D5D4F8909000274FF0010A09EBA9 +:103220004712D2F8003B03F44023B3F5802F11D1AD +:10323000D2F8003B002B0DDA62890AFA07F322EA82 +:103240000303638104EB8703DB68DB6813B1394652 +:10325000204698470137D4F89430FFB29B689F42CC +:10326000DDD9F00619D5D4F89000026AC2F30A1726 +:1032700002F00F0302F4F012B2F5802F00F0CC80C0 +:10328000B2F5402F09D104EB8303002200F58050F2 +:10329000DB681B6A974240F0B2803003D5F81858BB +:1032A00035D5E90303D500212046FFF791FEAA0397 +:1032B00003D501212046FFF78BFE6B0303D50221C6 +:1032C0002046FFF785FE2F0303D503212046FFF795 +:1032D0007FFEE80203D504212046FFF779FEA9020C +:1032E00003D505212046FFF773FE6A0203D50621A8 +:1032F0002046FFF76DFE2B0203D507212046FFF77E +:1033000067FEEF0103D508212046FFF761FE700339 +:1033100040F1A980E90703D500212046FFF7EAFE26 +:10332000AA0703D501212046FFF7E4FE6B0703D56A +:1033300002212046FFF7DEFE2F0703D5032120469A +:10334000FFF7D8FEEE0603D504212046FFF7D2FE94 +:10335000A80603D505212046FFF7CCFE690603D554 +:1033600006212046FFF7C6FE2A0603D50721204680 +:10337000FFF7C0FEEB0576D520460821BDE8F84FE3 +:10338000FFF7B8BED4F8909000274FF0010AD4F8A8 +:1033900094305FFA87FB9B689B453FF639AF09EB9A +:1033A0004B13D3F8002902F44022B2F5802F24D128 +:1033B000D3F80029002A20DAD3F8002942F09042FD +:1033C000C3F80029D3F80029002AFBDB5946D4F8BA +:1033D0009000FFF7C7FB22890AFA0BF322EA0303E6 +:1033E000238104EB8B03DB689B6813B159462046AD +:1033F000984759462046FFF779FB0137C7E7910701 +:1034000001D1D0F80080072A02F101029CBF03F825 +:10341000018B4FEA18283DE704EB830300F5805049 +:10342000DA68D2F818C0DCF80820DCE9001CA1EB4F +:103430000C0C00218F4208D1DB689B699A683A44E2 +:103440009A605A683A445A6027E711F0030F01D195 +:10345000D0F800808C4501F1010184BF02F8018B96 +:103460004FEA1828E6E7BDE8F88F000008B50348E2 +:10347000FFF788FEBDE80840FFF784BA2C4500201E +:1034800008B50348FFF77EFEBDE80840FFF77ABAAB +:10349000C8450020D0F8903003EB4111D1F8003B33 +:1034A00043F40013C1F8003B70470000D0F890309F +:1034B00003EB4111D1F8003943F40013C1F800398E +:1034C00070470000D0F8903003EB4111D1F8003B79 +:1034D00023F40013C1F8003B70470000D0F890308F +:1034E00003EB4111D1F8003923F40013C1F800397E +:1034F00070470000090100F16043012203F56143B8 +:10350000C9B283F8001300F01F039A4043099B00DF +:1035100003F1604303F56143C3F880211A607047EB +:1035200030B50433039C0172002104FB0325C16004 +:10353000C0E90653049B0363059BC0E90000C0E992 +:103540000422C0E90842C0E90A11436330BD00000B +:103550000022416AC260C0E90411C0E90A226FF08A +:103560000101FEF7EDBD0000D0E90432934201D124 +:10357000C2680AB9181D70470020704703691960B6 +:103580000021C2680132C260C26913448269934259 +:10359000036124BF436A0361FEF7C6BD38B5044624 +:1035A0000D46E3683BB162690020131D1268A362F7 +:1035B0001344E36207E0237A33B929462046FEF735 +:1035C000A3FD0028EDDA38BD6FF00100FBE7000035 +:1035D000C368C269013BC360436913448269934273 +:1035E000436124BF436A436100238362036B03B1D9 +:1035F0001847704770B52023044683F31188866A04 +:103600003EB9FFF7CBFF054618B186F3118828466F +:1036100070BDA36AE26A13F8015B9342A36202D30E +:103620002046FFF7D5FF002383F31188EFE7000062 +:103630002DE9F84F04460E46174698464FF02009EC +:1036400089F311880025AA46D4F828B0BBF1000FF1 +:1036500009D141462046FFF7A1FF20B18BF3118825 +:103660002846BDE8F88FD4E90A12A7EB050B521AD9 +:10367000934528BF9346BBF1400F1BD9334601F158 +:10368000400251F8040B914243F8040BF9D1A36AAC +:10369000403640354033A362D4E90A239A4202D32C +:1036A0002046FFF795FF8AF31188BD42D8D289F3EF +:1036B0001188C9E730465A46FDF7A0FBA36A5E446D +:1036C0005D445B44A362E7E710B5029C04330172DA +:1036D00004FB0321C460C0E906130023C0E90A33D8 +:1036E000039B0363049BC0E90000C0E90422C0E916 +:1036F0000842436310BD0000026A6FF00101C2601E +:10370000426AC0E904220022C0E90A22FEF718BD7D +:10371000D0E904239A4201D1C26822B9184650F870 +:10372000043B0B607047002070470000C368002115 +:10373000C2690133C36043691344826993424361A0 +:1037400024BF436A4361FEF7EFBC000038B504466E +:103750000D46E3683BB1236900201A1DA262E269AD +:103760001344E36207E0237A33B929462046FEF783 +:10377000CBFC0028EDDA38BD6FF00100FBE700005C +:1037800003691960C268013AC260C2691344826960 +:103790009342036124BF436A036100238362036B86 +:1037A00003B118477047000070B520230D4604464A +:1037B000114683F31188866A2EB9FFF7C7FF10B14F +:1037C00086F3118870BDA36A1D70A36AE26A013393 +:1037D0009342A36204D3E16920460439FFF7D0FF86 +:1037E000002080F31188EDE72DE9F84F04460D46DF +:1037F000904699464FF0200A8AF311880026B34676 +:10380000A76A4FB949462046FFF7A0FF20B187F3CA +:1038100011883046BDE8F88FD4E90A073A1AA8EBB8 +:103820000607974228BF1746402F1BD905F14003D2 +:1038300055F8042B9D4240F8042BF9D1A36A403679 +:103840004033A362D4E90A239A4204D3E1692046B3 +:103850000439FFF795FF8BF311884645D9D28AF3D7 +:103860001188CDE729463A46FDF7C8FAA36A3D44D8 +:103870003E443B44A362E5E7D0E904239A4217D1D2 +:10388000C3689BB1836A8BB1043B9B1A0ED0136053 +:10389000C368013BC360C3691A4483699A420261E9 +:1038A00024BF436A036100238362012318467047E3 +:1038B0000023FBE700F0DAB8034B002258631A61DB +:1038C0000222DA60704700BF000C0040014B00226A +:1038D000DA607047000C0040014B5863704700BF2E +:1038E000000C0040014B586A704700BF000C0040BC +:1038F0004B6843608B688360CB68C3600B6943612E +:103900004B6903628B6943620B6803607047000078 +:1039100008B53C4B40F2FF713B48D3F888200A437E +:10392000C3F88820D3F8882022F4FF6222F007022F +:10393000C3F88820D3F88820D3F8E0200A43C3F8DE +:10394000E020D3F808210A43C3F808212F4AD3F80E +:1039500008311146FFF7CCFF00F5806002F11C0131 +:10396000FFF7C6FF00F5806002F13801FFF7C0FFE6 +:1039700000F5806002F15401FFF7BAFF00F58060A6 +:1039800002F17001FFF7B4FF00F5806002F18C01D5 +:10399000FFF7AEFF00F5806002F1A801FFF7A8FF76 +:1039A00000F5806002F1C401FFF7A2FF00F580601E +:1039B00002F1E001FFF79CFF00F5806002F1FC01DD +:1039C000FFF796FF02F58C7100F58060FFF790FF1E +:1039D00000F000F90E4BD3F8902242F00102C3F838 +:1039E0009022D3F8942242F00102C3F894220522D7 +:1039F000C3F898204FF06052C3F89C20054AC3F8E2 +:103A0000A02008BD0044025800000258504200089F +:103A100000ED00E01F00080308B500F0D7FAFEF73C +:103A2000E3FA0F4BD3F8DC2042F04002C3F8DC206D +:103A3000D3F8042122F04002C3F80421D3F8043162 +:103A4000084B1A6842F008021A601A6842F0040231 +:103A50001A60FEF749FFBDE80840FEF7EDBC00BF65 +:103A6000004402580018024870470000114BD3F878 +:103A7000E82042F00802C3F8E820D3F8102142F011 +:103A80000802C3F810210C4AD3F81031D36B43F06D +:103A90000803D363C722094B9A624FF0FF32DA6200 +:103AA00000229A615A63DA605A6001225A611A60F0 +:103AB000704700BF004402580010005C000C00403A +:103AC000094A08B51169D3680B40D9B29B076FEA60 +:103AD0000101116107D5202383F31188FEF7A4FAB1 +:103AE000002383F3118808BD000C0040384B4FF0D1 +:103AF000FF31D3F88020C3F88010D3F88020002253 +:103B0000C3F88020D3F88000D3F88400C3F8841071 +:103B1000D3F88400C3F88420D3F88400D86F40F031 +:103B2000FF4040F4FF0040F43F5040F03F00D867B2 +:103B3000D86F20F0FF4020F4FF0020F43F5020F029 +:103B40003F00D867D86FD3F888006FEA40506FEA1B +:103B50005050C3F88800D3F88800C0F30A00C3F8B7 +:103B60008800D3F88800D3F89000C3F89010D3F8F9 +:103B70009000C3F89020D3F89000D3F89400C3F8D5 +:103B80009410D3F89400C3F89420D3F89400D3F899 +:103B90009800C3F89810D3F89800C3F89820D3F889 +:103BA0009800D3F88C00C3F88C10D3F88C00C3F8BD +:103BB0008C20D3F88C00D3F89C00C3F89C10D3F869 +:103BC0009C10C3F89C20D3F89C3000F0D3B900BF00 +:103BD00000440258614B0122C3F80821604BD3F81E +:103BE000F42042F00202C3F8F420D3F81C2142F082 +:103BF0000202C3F81C210222D3F81C31594BDA60AF +:103C00005A689104FCD5584A1A6001229A60574AB2 +:103C1000DA6000221A614FF440429A61514B9A696E +:103C20009204FCD51A6842F480721A604C4B1A6FE9 +:103C300012F4407F04D04FF480321A6700221A67D2 +:103C40001A6842F001021A60454B1A685007FCD509 +:103C500000221A611A6912F03802FBD101211960A1 +:103C60004FF0804159605A67414ADA62414A1A610D +:103C70001A6842F480321A60394B1A689103FCD5F5 +:103C80001A6842F480521A601A689204FCD53A4AC3 +:103C90003A499A6200225A6319633949DA6399638F +:103CA0005A64384A1A64384ADA621A6842F0A852EA +:103CB0001A602B4B1A6802F02852B2F1285FF9D132 +:103CC00048229A614FF48862DA6140221A622F4AD0 +:103CD000DA644FF080521A652D4A5A652D4A9A656A +:103CE00032232D4A1360136803F00F03022BFAD11D +:103CF0001B4B1A6942F003021A611A6902F038027A +:103D0000182AFAD1D3F8DC2042F00052C3F8DC20A4 +:103D1000D3F8042142F00052C3F80421D3F804215F +:103D2000D3F8DC2042F08042C3F8DC20D3F8042131 +:103D300042F08042C3F80421D3F80421D3F8DC20F8 +:103D400042F00042C3F8DC20D3F8042142F00042E4 +:103D5000C3F80421D3F80431704700BF008000513C +:103D6000004402580048025800C000F00200000160 +:103D70000000FF0100889008121020006302090172 +:103D80002C02040047040508FD0BFF012000002061 +:103D90000010E00000010100002000524FF0B0428E +:103DA00008B5D2F8883003F00103C2F8883023B197 +:103DB000044A13680BB150689847BDE80840FEF705 +:103DC000E1BD00BF7C4600204FF0B04208B5D2F8FC +:103DD000883003F00203C2F8883023B1044A9368A4 +:103DE0000BB1D0689847BDE80840FEF7CBBD00BFD7 +:103DF0007C4600204FF0B04208B5D2F8883003F07E +:103E00000403C2F8883023B1044A13690BB1506926 +:103E10009847BDE80840FEF7B5BD00BF7C460020CE +:103E20004FF0B04208B5D2F8883003F00803C2F86A +:103E3000883023B1044A93690BB1D0699847BDE833 +:103E40000840FEF79FBD00BF7C4600204FF0B04207 +:103E500008B5D2F8883003F01003C2F8883023B1D7 +:103E6000044A136A0BB1506A9847BDE80840FEF750 +:103E700089BD00BF7C4600204FF0B04310B5D3F899 +:103E8000884004F47872C3F88820A30604D5124A47 +:103E9000936A0BB1D06A9847600604D50E4A136B3B +:103EA0000BB1506B9847210604D50B4A936B0BB1AD +:103EB000D06B9847E20504D5074A136C0BB1506CE0 +:103EC0009847A30504D5044A936C0BB1D06C98476E +:103ED000BDE81040FEF756BD7C4600204FF0B043D1 +:103EE00010B5D3F8884004F47C42C3F888206205FA +:103EF00004D5164A136D0BB1506D9847230504D5B0 +:103F0000124A936D0BB1D06D9847E00404D50F4A67 +:103F1000136E0BB1506E9847A10404D50B4A936EF3 +:103F20000BB1D06E9847620404D5084A136F0BB1E9 +:103F3000506F9847230404D5044A936F0BB1D06F98 +:103F40009847BDE81040FEF71DBD00BF7C4600202D +:103F500008B50348FDF70CF9BDE80840FEF712BDAF +:103F6000CC23002008B5FFF7ABFDBDE80840FEF705 +:103F700009BD0000062108B50846FFF7BBFA062177 +:103F80000720FFF7B7FA06210820FFF7B3FA06214A +:103F90000920FFF7AFFA06210A20FFF7ABFA062146 +:103FA0001720FFF7A7FA06212820FFF7A3FA092117 +:103FB0007A20FFF79FFA07213220FFF79BFA0C21A6 +:103FC0005220BDE80840FFF795BA000008B5FFF79A +:103FD0008DFD00F00DF8FDF7DDFAFDF7B5FCFDF7FE +:103FE00087FBFFF741FDBDE80840FFF763BC000019 +:103FF0000023054A19460133102BC2E9001102F1D2 +:104000000802F8D1704700BF7C46002010B5013986 +:104010000244904201D1002005E0037811F8014FDD +:10402000A34201D0181B10BD0130F2E7034611F87E +:10403000012B03F8012B002AF9D1704753544D335B +:104040003248373F3F3F0053544D333248373433C3 +:104050002F37353300000000F0290020CC2300204A +:1040600000960000000000000000000000000000BA +:104070000000000000000000000000005D150008C6 +:104080004915000885150008711500087D15000800 +:10409000691500085515000841150008911500081C +:1040A000000000006D16000859160008951600085B +:1040B000811600088D16000879160008651600089C +:1040C00051160008A11600080000000001000000C1 +:1040D000000000006D61696E0000000069646C659D +:1040E00000000000DC40000878280020F0290020B3 +:1040F00001000000E51F0008000000004172647527 +:1041000050696C6F740025424F415244252D424C3A +:10411000002553455249414C250000000200000093 +:10412000000000008D180008FD1800084000400045 +:1041300098420020A8420020020000000000000079 +:104140000300000000000000451900080000000006 +:1041500010000000B8420020000000000100000034 +:10416000000000002C45002001010200D5230008BA +:10417000E5220008812300086523000843000000B1 +:104180008441000809024300020100C03209040012 +:1041900000010202010005240010010524010001B4 +:1041A000042402020524060001070582030800FF1B +:1041B00009040100020A0000000705010240000096 +:1041C000070581024000000012000000D0410008F5 +:1041D00012011001020000400912415700020102C1 +:1041E000030100000403090425424F415244250005 +:1041F0004D6174656B483734332D626473686F7436 +:104200000030313233343536373839414243444552 +:104210004600000000000000991A0008511D000827 +:10422000FD1D000840004000644600206446002058 +:1042300001000000744600208000000040010000E2 +:104240000800000000010000000400000800000059 +:104250000000802A00000000AAAAAAAA00000024E8 +:10426000FFFF00000000000000A00A0000000001A5 +:1042700000000000AAAAAAAA00000001FFFF000097 +:1042800000000000000000000000004400000000EA +:10429000AAAAAAAA00000044FFFF00000000000034 +:1042A000000000000001100000000000AAAAAAAA55 +:1042B00000010000FFFB0000000000000000000003 +:1042C0005080420000000000AAAAAAAA10404100A3 +:1042D000F7FF000000000070070000000000000071 +:1042E00000000000AAAAAAAA00000000FFFF000028 +:1042F00000000000000000000000000000000000BE +:10430000AAAAAAAA00000000FFFF00000000000007 +:10431000000000000000000000000000AAAAAAAAF5 +:1043200000000000FFFF000000000000000000008F +:104330000000000000000000AAAAAAAA00000000D5 +:10434000FFFF00000000000000000000000000006F +:1043500000000000AAAAAAAA00000000FFFF0000B7 +:10436000000000000000000000000000000000004D +:10437000AAAAAAAA00000000FFFF00000000000097 +:104380000000000000000000F50300000000000035 +:1043900000001E0000000000FF0000000000000000 +:1043A0003C4000083F000000500400004740000867 +:1043B0003F0000000096000000000800960000008A +:1043C0000008000004000000E441000800000000B4 +:1043D00000000000000000000000000000000000DD +:0443E00000000000D9 +:00000001FF diff --git a/Tools/bootloaders/MatekH743_bl.bin b/Tools/bootloaders/MatekH743_bl.bin index 854bcd761fe..219dce8292b 100755 Binary files a/Tools/bootloaders/MatekH743_bl.bin and b/Tools/bootloaders/MatekH743_bl.bin differ diff --git a/Tools/bootloaders/MatekH743_bl.hex b/Tools/bootloaders/MatekH743_bl.hex index dffbf38da1d..0bc58e0da27 100644 --- a/Tools/bootloaders/MatekH743_bl.hex +++ b/Tools/bootloaders/MatekH743_bl.hex @@ -1,34 +1,34 @@ :020000040800F2 -:1000000000040020A1020008791000087D100008FB -:10001000D11000087D100008A5100008A3020008F8 -:10002000A3020008A3020008A30200080529000893 +:1000000000060020A102000841100008C10F0008EE +:1000100019100008C10F0008ED0F0008A302000826 +:10002000A3020008A3020008A30200083529000863 :10003000A3020008A3020008A3020008A30200080C :10004000A3020008A3020008A3020008A3020008FC -:10005000A3020008A3020008493E0008753E0008FC -:10006000A13E0008CD3E0008F93E0008A3020008AA +:10005000A3020008A3020008BD3D0008E93D000816 +:10006000153E0008413E00086D3E0008A30200084E :10007000A3020008A3020008A3020008A3020008CC :10008000A3020008A3020008A3020008A3020008BC -:10009000A3020008A3020008A3020008253F0008ED +:10009000A3020008A3020008A3020008993E00087A :1000A000A3020008A3020008A3020008A30200089C :1000B000A3020008A3020008A3020008A30200088C :1000C000A3020008A3020008A3020008A30200087C :1000D000A3020008A3020008A3020008A30200086C -:1000E0008D3F0008A3020008A3020008A302000835 +:1000E000FD3E0008A3020008A3020008A3020008C6 :1000F000A3020008A3020008A3020008A30200084C -:10010000A3020008A3020008C53A0008A3020008E1 +:10010000A3020008A3020008853F0008A30200081C :10011000A3020008A3020008A3020008A30200082B :10012000A3020008A3020008A3020008A30200081B :10013000A3020008A3020008A3020008A30200080B :10014000A3020008A3020008A3020008A3020008FB :10015000A3020008A3020008A3020008A3020008EB :10016000A3020008A3020008A3020008A3020008DB -:10017000A30200083D340008A3020008A3020008FF -:10018000A3020008A302000861110008A3020008EE +:10017000A3020008A1340008A3020008A30200089B +:10018000A3020008A3020008713F0008A3020008B0 :10019000A3020008A3020008A3020008A3020008AB :1001A000A3020008A3020008A3020008A30200089B :1001B000A3020008A3020008A3020008A30200088B :1001C000A3020008A3020008A3020008A30200087B -:1001D000A302000829340008A3020008A3020008B3 +:1001D000A30200088D340008A3020008A30200084F :1001E000A3020008A3020008A3020008A30200085B :1001F000A3020008A3020008A3020008A30200084B :10020000A3020008A3020008A3020008A30200083A @@ -41,1054 +41,1050 @@ :10027000A3020008A3020008A3020008A3020008CA :10028000A3020008A3020008A3020008A3020008BA :10029000A3020008A3020008A3020008A3020008AA -:1002A00002E000F000F8FEE772B6394880F30888F3 -:1002B000384880F3098838484EF60851CEF20001DC +:1002A00002E000F000F8FEE772B63A4880F30888F2 +:1002B000394880F3098839484EF60851CEF20001DA :1002C000086040F20000CCF200004EF63471CEF22D :1002D00000010860BFF34F8FBFF36F8F40F2000043 :1002E000C0F2F0004EF68851CEF200010860BFF374 :1002F0004F8FBFF36F8F4FF00000E1EE100A4EF604 :100300003C71CEF200010860062080F31488BFF330 -:100310006F8F02F035FB03F053FB4FF055301F4950 -:100320001B4A91423CBF41F8040BFAE71C49194AA9 -:1003300091423CBF41F8040BFAE71A491A4A1B4B99 -:100340009A423EBF51F8040B42F8040BF8E7002034 -:100350001749184A91423CBF41F8040BFAE702F0F2 -:1003600053FB03F0A1FB144C144DAC4203DA54F8D8 -:10037000041B8847F9E700F03FF8114C114DAC42DF -:1003800003DA54F8041B8847F9E702F03BBB00008E -:1003900000040020002400200000000800000020CD -:1003A00000040020F0430008002400204424002022 -:1003B0004824002060350020A0020008A0020008A8 -:1003C000A0020008A00200082DE9F04F2DED108AD0 -:1003D000C1F80CD0D0F80CD0BDEC108ABDE8F08F7D -:1003E000002383F311882846A047002001F0E4FE93 -:1003F00001F094FE00DFFEE738B5204C6FF00A03F1 -:10040000002523700323A57063701A23E5702571FE -:100410006571A571E57125726572A372E57200F0D0 -:1004200055FD20B10E2325726572A372E57202F0AC -:100430002BFA044602F060FA0546D0B9104B9C42F4 -:1004400019D001339C4241F2883412BF0546002482 -:100450000125002002F022FA0DB100F0B7F800F0FB -:10046000B1FD00F07DFC204600F070F900F0AEF820 -:10047000F9E70024EDE70446EBE700BF482400203D -:10048000010007B008B500F0E9FBA0F120035842D5 -:10049000584108BD054B07B51B88022101A8ADF8DE -:1004A000043000F047FC03B05DF804FB9440000802 -:1004B000064991F8243033B100230822086A81F8F4 -:1004C000243000F07FBC0120704700BF682400206A -:1004D0002DE9F84F234C05468846174694F82430FA -:1004E0008BBB2E46DFF87C90002F38D094F824A0E8 -:1004F000BAF1000F05D12022FF214846266200F004 -:100500004FFDCAF10805414604EB8A00BD4228BFF1 -:100510003D465FFA85FBAD00A7EB0B072A462E444C -:1005200000F016FD94F82430A844FFB29B445FFA13 -:100530008BFBBBF1080F84F824B0D5D1FFF7B8FFCF -:100540000028D1D108E0266A06EB8306B042C9D064 -:10055000FFF7AEFF0028C4D10020BDE8F88F0120CE -:10056000BDE8F88F6824002010B5202383F311889C -:100570001248C3680BB101F0A5FE0023104A4FF4E6 -:100580007A710E4801F062FE002383F311880D4C4E -:10059000236813B12368013B2360636813B1636868 -:1005A000013B6360084B1B7833B9636823B90220B1 -:1005B00000F0C4FC3223636010BD00BF542400204F -:1005C000690500089825002090240020554B5649C5 -:1005D0002DE9F04153F8042F013201D1BDE8F0813B -:1005E0008B42F7D1514C524B22689A4240F298808C -:1005F000504B9B6803F1006303F500339A4280F08F -:100600008F80002000F0D6FB02204B4B187000F0CA -:100610008DFC4A4BD3F8E8200022C3F8E820D3F839 -:100620001011C3F81021D3F81011D3F8EC10C3F84F -:10063000EC20D3F81411C3F81421D3F81411D3F813 -:10064000F010C3F8F020D3F81811C3F81821D3F82C -:100650001811D3F8801041F00061C3F88010D3F86E -:10066000801021F00061C3F88010D3F88010D3F817 -:10067000801041F00071C3F88010D3F8801021F091 -:100680000071C3F88010D3F8803072B62C4B2D491E -:100690000B601D682468BFF34F8FBFF36F8F2A4B29 -:1006A000C3F88420BFF34F8F5A6922F480325A6115 -:1006B000BFF34F8FD3F8802043F6E07EC2F3C90624 -:1006C000C2F34E32B707520102EA0E0838463146ED -:1006D000013948EA000C00F14040B1F1FF3FC3F896 -:1006E00074C2F5D1203A12F1200FEDD1BFF34F8F34 -:1006F000BFF36F8FBFF34F8FBFF36F8F5A6922F431 -:1007000000325A610022C3F85022BFF34F8FBFF36B -:100710006F8F202383F31188AD4685F30888204727 -:10072000BDE8F081FCFF01081C000208040002087B -:10073000FFFF0108482400209024002000440258B4 -:100740000000020808ED00E000ED00E02DE9F04FA8 -:1007500099B0B34C2022FF21019010A8A66800F0A8 -:100760001FFCB04AA3461378A3B90121AE4811700B -:10077000C360202383F31188C3680BB101F0A2FD8D -:100780000023AA4A4FF47A71A74801F05FFD0023C5 -:1007900083F31188019B13B1A54B019A1A600023C2 -:1007A000A44AA349019F99461C461D4698461370CA -:1007B0004B600292012000F0B9FB002F00F0128282 -:1007C0009B4B1B68002B40F00D8219B0BDE8F08FE9 -:1007D0000220FFF757FE002840F0FB81019BB9F192 -:1007E000000F08BF1F46944B1B8802210BA8ADF8D1 -:1007F0002C3000F09FFADDE74FF47A7000F02EFA0B -:10080000031E0393EADB0220FFF73CFE824600282A -:10081000E4D0039B581E042800F2DD81DFE800F0DD -:10082000030E1114170018A80523042140F8343DC5 -:1008300000F080FA54464FF0000856E00421784852 -:10084000F6E704217D48F3E704217D48F0E71C2406 -:100850002046043400F0B0FA04210B900BA800F0FD -:1008600069FA2C2CF4D1E5E7002DB7D0002CB5D0D7 -:100870000220FFF707FE0546002800F0AF810120A7 -:100880006C4C00F097FA4FF000090220207000F045 -:100890004DFB5FFA89FA504600F09CFA074658B1C2 -:1008A000504609F1010900F0A5FA0028F1D12C46C3 -:1008B000A9460027634B97E701233E460220237099 -:1008C00000F02AFBDBF808309E4206D2304600F0EA -:1008D00073FA0130EBD10436F4E70026029BA946F7 -:1008E0002C461E703746524B5E6000F061FB15B11E -:1008F000002C18BF0027FFF7CDFD5BE7002D3FF46C -:100900006DAF002C3FF46AAF0220029B187000F01C -:100910000DFB322000F0A2F9B0F1000AC0F25E81B6 -:100920001AF0030540F05A8106EB0A03DBF80820B1 -:10093000934200F25381BAF5807F00F24F81554512 -:100940000DDA4FF47A7000F089F90490049B002BC3 -:10095000C0F24481049B3C4AAB540135EFE7C82008 -:10096000FFF790FD0546002800F038811F2E11D8B2 -:10097000C6F1200410AB26F0030033495445184457 -:1009800028BF5446224600F0E3FA2246FF212E48B3 -:1009900000F006FB4FEAAA0A2B4930465FFA8AF2BA -:1009A000FFF796FD0446002800F01A8106EB8A0640 -:1009B00005469AE70220FFF765FD00283FF40EAFD9 -:1009C000FFF776FD00283FF409AF4FF0000A5346C9 -:1009D000DBF8082092451CD2BAF11F0F12D8109AEA -:1009E00001320FD02AF0030218A90A4452F8202C31 -:1009F0000B92184604220BA90AF1040A00F07CFBB2 -:100A00000346E5E75046039300F0D6F9039B0B90AD -:100A1000EFE718A8042140F84C3D00F08BF964E79B -:100A20004824002094250020542400206905000853 -:100A30009825002090240020964000084C24002097 -:100A400050240020984000089424002018A8002377 -:100A5000642140F8343D00F039F900287FF4BEAE3F -:100A60000220FFF70FFD00283FF4B8AE0B9800F00E -:100A7000D3F918AB43F8480D04211846CDE718A860 -:100A80000023642140F8343D00F020F900287FF471 -:100A9000A5AE0220FFF7F6FC00283FF49FAE0B98AE -:100AA00000F0BCF918AB43F8440DE5E70220FFF76E -:100AB000E9FC00283FF492AE00F0B6F918AB43F819 -:100AC000400DD9E70220FFF7DDFC00283FF486AE99 -:100AD0000BA9142000F0AEF9824618A8042140F8B2 -:100AE0003CAD00F027F951460BA896E7322000F004 -:100AF000B5F8B0F1000AFFF671AE1AF0030F7FF4FB -:100B00006DAE0AEB0803DBF8082093423FF666AEB1 -:100B10000220FFF7B7FC00283FF460AE2AF0030A7A -:100B2000C244D0453FF4E1AE404608F1040800F06D -:100B300043F904210A900AA800F0FCF8F1E74FF409 -:100B40007A70FFF79FFC00283FF448AEFFF7B0FC37 -:100B500000283FF4AFAE109B01330CD0082210A93F -:100B60000020FFF7B5FC00283FF4A4AE2022FF21AF -:100B700010A800F015FAFFF78DFC374801F022FBB2 -:100B800023E6002D3FF42AAE002C3FF427AE18A830 -:100B90000023642140F8343D00F098F88246002894 -:100BA0007FF41CAE0220FFF76DFC00283FF416AE68 -:100BB0000390FFF76FFC41F28830574601F002FBCB -:100BC0000B9800F039FA00F0F3F9039B1C461D4620 -:100BD000F0E5054689E64FF00008FFE52546FDE50E -:100BE0002C4667E6002000F039F80490049B002BA7 -:100BF000FFF6E3AD012000F08FF9049B213B122B9F -:100C00003FF6D8AD01A252F823F000BFD10700088B -:100C1000F907000869080008B5070008B5070008CB -:100C2000B5070008FD080008ED0A0008B50900082E -:100C30004D0A00087F0A0008AD0A0008B507000841 -:100C4000C50A0008B50700083F0B0008EB080008BC -:100C5000B5070008830B0008A08601002DE9F347C3 -:100C60004FF47A75002402AE154F4543DFF85880E3 -:100C700006F8014D97F900305FFA84F95A1C01D04B -:100C8000A34212D158F82400012231460368D3F858 -:100C900020A02B46D047012807D10A4B9DF807001A -:100CA00083F8009002B0BDE8F0870134022CE1D156 -:100CB0004FF4FA7001F086FA4FF0FF30F2E700BF10 -:100CC00000240020BC250020AC4000082DE9F0479E -:100CD0004FF47A7506460024134F4D43DFF85080D9 -:100CE00097F900305FFA84F95A1C01D0A34210D161 -:100CF00058F82400042231460368D3F820A02B467C -:100D0000D047042805D1094B002083F80090BDE8A6 -:100D1000F0870134022CE3D14FF4FA7001F052FA5B -:100D20004FF0FF30BDE8F08700240020BC250020F4 -:100D3000AC400008074B30B41A78074B53F82240F8 -:100D40000A46014623682046DD69044BAC4630BCA8 -:100D5000604700BFBC250020AC400008A086010011 -:100D6000F8B5104C0025104E01F076FC0F4F2070A6 -:100D70003068237883420CD800250D4E2078013846 -:100D800001F066FC23780544013BB5422370F5D998 -:100D9000F8BD01F05DFC336805440133BD423360AA -:100DA000E6D9E9E7BD250020A0250020FFFF0100CE -:100DB000FFFF030001F01CBD00F1006000F50030F2 -:100DC0000068704700F10060920000F5003001F00B -:100DD0009FBC0000054B1A68054B1B789B1A834289 -:100DE00002D9104401F034BC00207047A025002037 -:100DF000BD25002038B5074D04462868204401F081 -:100E00002DFC28B928682044BDE8384001F038BCE2 -:100E100038BD00BFA025002000207047014BC058FE -:100E2000704700BF00E8F11F014B1868704700BF12 -:100E30000010005C234BF0B5234C1B682788C3F3DC -:100E40000B0665681B0C94F90820BE4228D0A789C0 -:100E5000BE4206D101220C2505FB0244656894F9C7 -:100E6000082041F20104A3421CD041F20304A34232 -:100E70001AD042F20104A34218D042F20304A34262 -:100E800008BF5622441E013D0B460C44A34217D214 -:100E900015F9016F581C5EB1034600F8016CF5E7C7 -:100EA0000022D8E75A22EDE75922EBE75822E9E77A -:100EB0002C2584421D7001D9981C5A70401AF0BD2F -:100EC0001846FBE70010005C04240020104B41F2A0 -:100ED00001015B888B429AB211D041F203018B422F -:100EE0000FD042F201039A420DD042F203039A421C -:100EF0000BD10323074A02EB8303D8787047002302 -:100F0000F8E70123F6E70223F4E70020704700BF6B -:100F10000010005C9C400008022803D14FF400221E -:100F2000014B9A61704700BF00100258022802D19D -:100F30000822014B9A61704700100258022804D120 -:100F4000024A536983F00803536170470010025846 -:100F5000002310B5934203D0CC5CC4540133F9E7AD -:100F600010BD000030B5441E14F9010F0B4658B1F6 -:100F700093F900500131854206D11AB993F9002046 -:100F8000801A30BD013AEFE7002AF7D1104630BD94 -:100F900002460346981A13F9011B0029FAD170473B -:100FA00002440346934202D003F8011BFAE770475C -:100FB000024B1A78024B1A70704700BFBC25002004 -:100FC0000024002038B5164C164D204600F02CFCAD -:100FD0002946204600F054FC2D681348D5F890208F -:100FE000D2F8043843F00203C2F8043801F0EAF8FA -:100FF0000E49284600F054FDD5F890200C48D2F850 -:1010000004380C49A04223F00203C2F804384FF41C -:10101000E1330B6003D0BDE8384000F063BB38BD5E -:10102000EC2A00208C41000840420F00B441000827 -:1010300040260020A425002038B50B4B05461A7821 -:101040000A4B53F822400A4B9C420CD0094B00211A -:1010500018221846FFF7A4FF056001462046BDE8A8 -:10106000384000F03FBB38BDBC250020AC40000834 -:10107000EC2A0020A4250020FEE7000000B59BB06C -:10108000EFF3098168226846FFF762FFEFF30583FB -:10109000034B9A6B9A6A9A6A9A6A9A6A9B6AFEE703 -:1010A00000ED00E000B59BB0EFF3098168226846CF -:1010B000FFF74EFFEFF30583044B9A6B9A6A9A6A27 -:1010C0009A6A9A6A9A6A9B6AFEE700BF00ED00E09E -:1010D00000B59BB0EFF3098168226846FFF738FF3F -:1010E000EFF30583034B5A6B9A6A9A6A9A6A9A6A73 -:1010F0009B6AFEE700ED00E030B50A44074D9142DF -:101100000BD011F8013B09245840013CF7D040F3C3 -:1011100000032B4083EA5000F7E730BD2083B8ED91 -:10112000002304491A465A50C81808334260802BDD -:10113000F9D17047C0250020024A136843F0C0036C -:101140001360704700780040044B5A6810439A6857 -:1011500058600AB1181D1047704700BF4026002094 -:101160002DE9F84F414EF56D2F68EC6921072C628F -:1011700019D014F0080F0CBF00208020E20748BFF0 -:1011800040F02000A3074FF0200348BF40F040008C -:10119000610748BF40F4807083F31188FFF7D4FFE4 -:1011A000002383F31188E20509D5202383F31188F6 -:1011B0004FF40070FFF7C8FF002383F311884FF04E -:1011C0002009DFF8A8A04FF0000B14F0200832D15E -:1011D0003B0615D54FF02009DFF894A020060FD567 -:1011E00089F31188504600F0F1F9002830DA082020 -:1011F000FFF7AAFF27F080032B60002383F31188F9 -:1012000079060DD562060BD5202383F31188F26C85 -:10121000336D9A4201D1336C03BB002383F31188F1 -:10122000E30604D5B26E13690BB150699847BDE867 -:10123000F84F01F077BB89F31188AB8C504696F8D4 -:101240006410194000F05CFA8BF31188EC69BCE77C -:1012500080B2288588F31188EC69BFE727F0400742 -:101260001020FFF771FF2F60D7E700BF4026002056 -:101270007826002013B5104C204600F027FA04F120 -:101280001400009400234FF400720C4900F0E8F8B9 -:1012900004F1380000944FF40072094B094900F042 -:1012A00061F9094B0C215220E365084B236602B01B -:1012B000BDE8104000F05EB840260020AC260020BB -:1012C00039110008AC2800200078004000E1F50545 -:1012D000254B002908BF1946037C012B816630B5D8 -:1012E00011D1224B98420ED1214BD3F8E82042F085 -:1012F0008042C3F8E820D3F8102142F08042C3F8BE -:101300001021D3F810310A68036EC46D03EB520349 -:10131000B3FBF2F34A68150442BF23F0070503F05C -:10132000070343EA4503E3608B6843F040036360CF -:10133000CB68510543F00103A36042F4967343F078 -:10134000010323604FF0FF33236205D512F0102212 -:1013500005D0B2F1805F04D080F8643030BD7F23C7 -:10136000FAE73F23F8E700BFD040000840260020FE -:101370000044025800F1604300F01F0209014009D7 -:1013800003F56143C9B2800083F80013012300F123 -:101390006040934000F56140C0F8803103607047C1 -:1013A000F8B51546826804460B46AA4200D2856805 -:1013B000A1692669761AB54207D218462A46FFF770 -:1013C000C7FDA3692B44A3610DE011D9AF1B3246C1 -:1013D0001846FFF7BDFD3A46E1683044FFF7B8FD17 -:1013E000E2683A44A261A36828465B1BA360F8BD8B -:1013F00018462A46FFF7ACFDE368E4E783689342AA -:101400002DE9F04104460F46154600D28568606913 -:101410002669361AB54207D22A463946FFF798FDA3 -:1014200063692B4463610EE013D9A5EB06083246CD -:101430003946FFF78DFD4246B919E068FFF788FD90 -:10144000E26842446261A36828465B1BA360BDE872 -:10145000F0812A463946FFF77BFDE368E2E70000AA -:1014600010B50A440024C361029B006040608460A0 -:10147000C160816141610261036210BD08B582698A -:101480004369934201D1826882B9826801328260E5 -:101490005A1C42611970426903699A4201D3C368B8 -:1014A0004361002100F0AAFE002008BD4FF0FF308C -:1014B00008BD000070B5202304460E4683F3118852 -:1014C000A568A5B1A368A269013BA360531CA361F1 -:1014D00015782269934224BFE368A361E3690BB1E5 -:1014E00020469847002383F31188284670BD314673 -:1014F000204600F073FE0028E2DA85F3118870BD03 -:101500002DE9F74F05460F4690469A46D0F81C90B5 -:10151000202686F311884FF0000B144664B1224652 -:1015200039462846FFF73CFF034668B9514628462E -:1015300000F054FE0028F1D0002383F31188A8EBBB -:10154000040003B0BDE8F08FB9F1000F03D00190A3 -:101550002846C847019B8BF31188E41A1F4486F381 -:101560001188DBE7C160816141611144C361009B67 -:10157000006040608260016103627047F8B5044614 -:101580000E461746202383F31188A568A5B1A368EA -:10159000013BA36063695A1C62611E702369626922 -:1015A0009A4224BFE3686361E3690BB12046984720 -:1015B000002080F31188F8BD3946204600F00EFE69 -:1015C0000028E2DA85F31188F8BD000083694269DA -:1015D0009A4210B501D182687AB98268013282607C -:1015E0005A1C82611C7803699A4201D3C3688361E3 -:1015F000002100F003FE204610BD4FF0FF3010BD6B -:101600002DE9F74F05460F4690469A46D0F81C90B4 -:10161000202686F311884FF0000B144664B1224651 -:1016200039462846FFF7EAFE034668B95146284680 -:1016300000F0D4FD0028F1D0002383F31188A8EB3B -:10164000040003B0BDE8F08FB9F1000F03D00190A2 -:101650002846C847019B8BF31188E41A1F4486F380 -:101660001188DBE7026843681143016003B1184742 -:10167000704700001430FFF743BF00004FF0FF3306 -:101680001430FFF73DBF00003830FFF7B9BF00004E -:101690004FF0FF333830FFF7B3BF00001430FFF7CF -:1016A00009BF00004FF0FF311430FFF703BF000007 -:1016B0003830FFF763BF00004FF0FF323830FFF7DC -:1016C0005DBF000000207047FFF7D4BD044B0360EE -:1016D000002343608360C36001230374704700BF2D -:1016E000E840000810B52023044683F31188FFF773 -:1016F000EFFD02232374002383F3118810BD000043 -:1017000038B5C36904460D461BB904210844FFF7E8 -:10171000A9FF294604F11400FFF7B0FE002806DAFD -:10172000201D4FF48061BDE83840FFF79BBF38BDF6 -:10173000026843681143016003B118477047000015 -:1017400013B5446BD4F894341A681178042915D170 -:10175000217C022912D11979012312898B4013426D -:101760000CD101A904F14C0001F09AFFD4F8944483 -:101770000246019B2179206800F0EAF902B010BD11 -:10178000143001F01DBF00004FF0FF33143001F0A2 -:1017900017BF00004C3001F0EFBF00004FF0FF33E7 -:1017A0004C3001F0E9BF0000143001F0EBBE000046 -:1017B0004FF0FF31143001F0E5BE00004C3001F075 -:1017C000BBBF00004FF0FF324C3001F0B5BF00004E -:1017D000D0F8942438B5136805461978042901D047 -:1017E000012038BD017C0229FAD1127901205C89DF -:1017F00090400440F4D105F1140001F07DFE024652 -:101800000028EDD0D5F894544FF480732868697996 -:1018100000F08CF9204638BD406BFFF7D9BF0000BF -:1018200000207047704700007FB5124B012502264B -:10183000044603600023057400F1840243602946D6 -:101840008360C3600C4B0290143001934FF480739B -:10185000009601F02DFE094B04F5237229460193F1 -:1018600004F14C004FF480730294009601F0F4FEF2 -:1018700004B070BD10410008191800084117000895 -:101880000A68202383F311880B790B3342F8230075 -:101890004B79133342F823008B7913B10B3342F8A1 -:1018A00023000223C0F894140374002383F31188E7 -:1018B0007047000038B5037F044613B190F85430E8 -:1018C000ABB90125201D0221FFF732FF04F11400FE -:1018D00025776FF0010100F09DFC84F8545004F16D -:1018E0004C006FF00101BDE8384000F093BC38BDFA -:1018F00010B5012104460430FFF71AFF00232377B7 -:1019000084F8543010BD000038B50446002514306A -:1019100001F0E6FD04F14C00257701F0B5FE201D35 -:1019200084F854500121FFF703FF2046BDE83840FA -:10193000FFF74EBF90F8803003F06003202B19D1E1 -:1019400090F88120212A0AD0222A4FF000030ED0DD -:10195000202A0FD1084A42670722826704E0064B1B -:101960004367072383670023C367012070474367EA -:101970008367F9E7002070471C240020D0F89434D6 -:1019800037B51A680446117804291AD1017C022956 -:1019900017D11979012312898B40134211D100F11B -:1019A0004C05284601F030FF58B101A9284601F046 -:1019B00077FED4F894440246019B2179206800F018 -:1019C000C7F803B030BD000001F10B03F7B550F8C4 -:1019D000234005460E46F4B1202383F3118805EB1E -:1019E0008607201D08214C34FFF7A2FEFB685B69C7 -:1019F0001B6813B1204601F061FE01A9204601F0E9 -:101A00004FFE024648B1019B3146284600F0A0F83F -:101A1000002383F3118803B0F0BDFB685A69126894 -:101A2000002AF5D01B8A013B1340F1D105F1800259 -:101A3000EAE70000133138B550F82140DCB120232B -:101A400083F31188D4F894241368527903EB82034A -:101A5000DB689B695D6845B104216018FFF768FE8B -:101A6000294604F1140001F051FD2046FFF7B0FEB5 -:101A7000002383F3118838BD7047000001F04CB893 -:101A8000012300F1300200F1500103700023436094 -:101A900042F8043B8A42D361FAD103814381704703 -:101AA00038B50446202383F31188002500F10C0388 -:101AB00000F13002416043F8045B9342FBD12046C1 -:101AC00001F04CF80223237085F3118838BD000023 -:101AD00070B500EB8103054650690E461446DA6086 -:101AE00018B110220021FFF75BFAA06918B110228B -:101AF0000021FFF755FA31462846BDE8704001F055 -:101B00003FB90000038900F13002002103F0010316 -:101B10000381438903F00103438100F1100343F87B -:101B2000041B9342FBD101F0C3B90000F0B40125BE -:101B300000EB810447898D40E4683D43A4694581F9 -:101B400023600023A2606360F0BC01F0DFB90000F5 -:101B5000F0B4012500EB810407898D40E4683D4322 -:101B60006469058123600023A2606360F0BC01F01A -:101B700057BA0000022300F10C0200F1300110B549 -:101B8000037004460023A0F8883080F88A3080F87B -:101B90008B300381438142F8043B8A42FBD184F8B5 -:101BA0007030204601F080F863681B6823B120463E -:101BB0000021BDE81040184710BD000002784368BE -:101BC00080F88C2005221B6802700BB10421184795 -:101BD00070470000436890F88C201B6802700BB1BE -:101BE000052118477047000090F8703070B5044622 -:101BF00013B1002380F8703004F18002204601F018 -:101C00007BF963689B6863BB94F8805015F06006AD -:101C100015D194F8813005F07F0545EA032540F29F -:101C200002339D4200F00E815BD8022D00F0DC8073 -:101C30003FD8002D00F08780012D00F0CF800021DB -:101C4000204601F011FC0021204601F001FC6368F0 -:101C50001B6813B1062120469847062384F870308C -:101C600070BD204698470028CED094F8872094F87D -:101C7000863043EA0223A26F934238BFA36794F9E8 -:101C80008030A56F002B4FF0200380F2FD80002DE7 -:101C900000F0EC80092284F8702083F31188002181 -:101CA000A36F626F2046FFF753FF002383F3118871 -:101CB00070BDB5F5817F00F0B180B5F5407F49D0AA -:101CC000B5F5807FBBD194F88230012BB7D1B4F841 -:101CD000883023F00203A4F888306667A667E667B9 -:101CE000C3E740F201639D421ED8B5F5C06F3BD2F9 -:101CF000B5F5A06FA3D1B4F88030B3F5A06F0ED1C5 -:101D000094F88230204684F88A3001F02BF863681A -:101D10001B6813B101212046984703232370002339 -:101D20006367A367E367A0E7B5F5106F32D040F6AD -:101D300002439D4252D0B5F5006F80D104F18B0370 -:101D40006367012324E004F18803E56763670223E6 -:101D5000A3678AE794F88230012B7FF470AFB4F860 -:101D6000883043F00203B6E794F885202046616886 -:101D700094F884304D6843EA022394F8831094F871 -:101D80008220A84700283FF45AAF4368636703687E -:101D9000A367A4E72378042B10D1202383F31188B1 -:101DA0002046FFF7AFFE86F311886368032184F8AD -:101DB0008B601B6821700BB12046984794F88230E5 -:101DC000002BACD084F88B300423237063681B682D -:101DD000002BA4D0022120469847A0E7374B636729 -:101DE0000223A36700239DE794F88410204611F096 -:101DF000800F01F00F010ED001F070F8012806D01D -:101E000002287FF41CAF2E4BA067636767E72D4B5A -:101E1000A567636763E701F053F8EFE794F8823052 -:101E2000002B7FF40CAF94F8843013F00F013FF4D3 -:101E300076AF1A06204602D501F02EFB6FE701F0BF -:101E40001FFB6CE794F88230002B7FF4F8AE94F817 -:101E5000843013F00F013FF462AF1B06204602D519 -:101E600001F002FB5BE701F0F3FA58E7142284F873 -:101E7000702083F311882B462A4629462046FFF717 -:101E800055FE85F3118870BD5DB1152284F8702070 -:101E900083F311880021A36F626F2046FFF746FE8F -:101EA00003E70B2284F8702083F311882B462A461F -:101EB00029462046FFF74CFEE3E700BF40410008FB -:101EC000384100083C41000838B590F870300446AD -:101ED000152B29D8DFE803F03E28282828283E289B -:101EE000280B293928282828282828283E3E90F819 -:101EF000871090F88620836F42EA01229A4214D913 -:101F0000C268128AB3FBF2F502FB15356DB92023C6 -:101F100083F311882B462A462946FFF719FE85F3DD -:101F200011880A2384F8703038BD142384F8703087 -:101F3000202383F31188002320461A461946FFF711 -:101F4000F5FD002383F3118838BDC36F03B19847B3 -:101F50000023E7E7002101F087FA0021204601F085 -:101F600077FA63681B6813B1062120469847062359 -:101F7000D8E7000090F87020152A38B5044622D81A -:101F80000123934040F6416213421DD113F48015A2 -:101F90000FD19B0217D50B2380F87030202383F3D9 -:101FA00011882B462A462946FFF7D2FD85F3118872 -:101FB00038BDC3689B695B682BB9C36F03B1984791 -:101FC000002384F8703038BD002101F04DFA002163 -:101FD000204601F03DFA63681B6813B106212046D4 -:101FE00098470623EDE70000024B00221B605B6070 -:101FF0009A607047AC2A0020002382680374054B66 -:102000001B6899689142FBD25A6803604260106075 -:1020100058607047AC2A002008B5202383F311884C -:10202000037C032B05D0042B0DD02BB983F311882F -:1020300008BD436900221A604FF0FF334361FFF788 -:10204000DBFF0023F2E790E80C001A60026853609F -:10205000F2E70000002382680374054B1B6899684F -:102060009142FBD85A680360426010605860704724 -:10207000AC2A0020054B196908741868026853607F -:102080001A60186101230374FEF79EB9AC2A002080 -:102090004B1C30B5054687B00A4C10D0236901A807 -:1020A000094A00F0D3F82846FFF7E4FF049B13B178 -:1020B00001A800F007F92369586907B030BDFFF7A0 -:1020C000D9FFF8E7AC2A00201920000838B50C4DDC -:1020D000044641612B6981689A68914203D8BDE842 -:1020E0003840FFF789BF1846FFF786FF01232C61B0 -:1020F000014623742046BDE83840FEF765B900BFAD -:10210000AC2A0020044B1A681B6990689B689842AF -:1021100094BF002001207047AC2A002010B5084C65 -:10212000236820691A6854602260012223611A74AE -:10213000FFF790FF01462069BDE81040FEF744B963 -:10214000AC2A00208260022202740022427470478E -:102150008368A3F17C0243F80C2C026943F83C2C01 -:10216000426943F8382C074A43F81C2CC268A3F193 -:10217000180043F8102C022203F8082C002203F860 -:10218000072C7047E103000810B5202383F3118862 -:10219000FFF7DEFF00210446FFF798FF002383F3DB -:1021A0001188204610BD0000024B1B6958610F20AA -:1021B000FFF760BFAC2A0020202383F31188FFF7CC -:1021C000F3BF000008B50146202383F311880820DF -:1021D000FFF75EFF002383F3118808BD49B1064B6A -:1021E00042681B6918605A60136043600420FFF75F -:1021F0004FBF4FF0FF307047AC2A00200368984271 -:1022000006D01A680260506018465961FFF7F4BEA4 -:102210007047000038B504460D462068844200D15E -:1022200038BD036823605C604561FFF7E5FEF4E7B5 -:10223000054B03F114025A619A614FF0FF32DA61E3 -:1022400000221A62704700BFAC2A0020F8B5036173 -:1022500002291A4B0646C26038BF02215C6A184B3D -:102260001A461F4652F8145F95420AD15861986188 -:102270001C620560456081600819BDE8F84001F006 -:10228000E5BA186AAB68241A0C1902D3E41A2D684F -:1022900004E09C4202D2204401F0E8FAAB689C4280 -:1022A000F4D86B68356073601E604FF0FF336E606A -:1022B000B460A968091BA960FB61F8BD000C00406F -:1022C000AC2A002010B41A4C234653F8141F814244 -:1022D00010D0416802680A60026851609A424FF06B -:1022E0000001C16003D0936881680B4493605DF87E -:1022F000044B70470A6800209A4262615360C860CC -:1023000003D15DF8044B01F0ABBA936888680344CD -:10231000206A9360074A526A121A9342E7D9991ABF -:102320005DF8044B012998BF931C184401F09EBA34 -:10233000AC2A0020000C004000207047FEE700009F -:10234000704700004FF0FF3070470000022906D0B0 -:10235000032906D00129064818BF00207047054808 -:102360007047032A9ABF044800EBC2000020704760 -:1023700010420008C44100082424002070B59AB01F -:1023800006460846144601AD294600F095F8284651 -:10239000FEF7FEFDC0B2431C5B0086E81800237008 -:1023A0000323023404F8013C00231946DAB2023454 -:1023B000904201D81AB070BDEA5C013304F8011CE8 -:1023C00004F8022CF2E7000008B5202383F31188FB -:1023D0000348FFF7D3FA002383F3118808BD00BF39 -:1023E000EC2A002010B50446052916D8DFE801F0D4 -:1023F00016150316161D202383F311880E4A01219A -:10240000FFF766FB20460D4A0221FFF761FB0C48EF -:10241000FFF77AFA002383F3118810BD202383F39A -:1024200011880748FFF746FAF4E7202383F3118861 -:102430000348FFF75DFAEDE74441000868410008F2 -:10244000EC2A002038B50C4D0C4C2A460C4904F1FE -:102450000800FFF793FF05F1CA0204F110000949D3 -:10246000FFF78CFF05F5CA7204F118000649BDE8B4 -:102470003840FFF783BF00BFB42F00202424002082 -:10248000944100089E410008A941000870B5044627 -:1024900008460D46FEF77CFDC6B22046013403789F -:1024A0000BB9184670BD32462946FEF75BFD002881 -:1024B000F3D1012070BD00002DE9F84F05460C4610 -:1024C000FEF766FD2C49C6B22846FFF7DFFF08B1CC -:1024D0000236F6B229492846FFF7D8FF08B1103670 -:1024E000F6B2632E0DD8DFF89080DFF89090244F7D -:1024F000DFF894A0DFF894B02E7846B92670BDE8D6 -:10250000F88F29462046BDE8F84F01F0BBBD252EC7 -:102510002ED1072241462846FEF724FD70B9DBF88C -:1025200000300735093444F8093CDBF8043044F83E -:10253000053C9BF8083004F8013CDDE708224946D9 -:102540002846FEF70FFD98B9A21C0E4B13F8011F89 -:10255000023209095345C95D02F8041C197801F0DB -:102560000F01C95D02F8031CF0D118340835C3E728 -:10257000267001350134BFE730420008A941000848 -:1025800042420008FFE7F11F0BE8F11F3842000844 -:10259000BFF34F8F044B1A695107FCD1D3F81021B8 -:1025A0005207F8D1704700BF0020005208B50D4B0C -:1025B0001B78ABB9FFF7ECFF0B4BDA68D10704D5FA -:1025C0000A4A5A6002F188325A60D3F80C21D207C5 -:1025D00006D5064AC3F8042102F18832C3F8042163 -:1025E00008BD00BF123200200020005223016745C1 -:1025F00008B5114B1B78F3B9104B1A69510703D575 -:10260000DA6842F04002DA60D3F81021520705D5AB -:10261000D3F80C2142F04002C3F80C21FFF7B8FFB9 -:10262000064BDA6842F00102DA60D3F80C2142F07E -:102630000102C3F80C2108BD123200200020005214 -:102640000F289ABF00F5806040040020704700000A -:102650004FF4003070470000102070470F2808B575 -:102660000BD8FFF7EDFF00F500330268013204D10B -:1026700004308342F9D1012008BD002008BD0000CC -:102680000F2810B504463FD8FFF782FFFFF78EFFF3 -:102690001E484FF0FF33072C4361C0F814311DD89A -:1026A0000361FFF775FF230243F02403C360C3688F -:1026B00043F08003C36003695A07FCD4FFF768FF47 -:1026C0002046FFF7BDFF4FF4003100F0F7F8FFF7A9 -:1026D0008FFF2046BDE81040FFF7C0BFC0F81031A3 -:1026E000FFF756FFA4F108031B0243F02403C0F8D0 -:1026F0000C31D0F80C3143F08003C0F80C31D0F825 -:1027000010315B07FBD4D9E7002010BD0020005238 -:102710002DE9F84F40EA020305460E461746DB0650 -:1027200056D13446DFF8C090DFF8C0A0FFF73EFF77 -:102730003B1B33441F2B04D8FFF75AFF0120BDE891 -:10274000F88F20222146284601F08CFC002837D043 -:1027500005F17843214A22489342224B98BF98467C -:1027600003F5827392BFD346C8469B46A3F1080384 -:1027700088BF1846FFF70CFF4FF0FF3304F11C0130 -:10278000A5EB040ECBF80030036843F002030360AE -:10279000231FD8F8002012F0050FFAD153F8042FA8 -:1027A00099424EF80320F4D1BFF34F8FFFF7F0FEAC -:1027B0004FF0FF33CBF80030036823F002030360CF -:1027C00020222146284601F04DFC20B1FFF710FFE2 -:1027D0000020BDE8F88F20352034A9E7FFFF0F0067 -:1027E0000C200052102000521021005214200052E0 -:1027F00010B5084C237828B153B9FFF7D7FE012351 -:10280000237010BD23B12070BDE81040FFF7F0BE6B -:1028100010BD00BF1232002002440439064BD2B270 -:1028200010B5904200D110BD441C00B253F82000F6 -:1028300041F8040FE0B2F4E7504000580F4B30B5B8 -:102840001C6F240405D41C6F1C671C6F44F40044E7 -:102850001C670B4C024404392368D2B243F48073E2 -:102860002360084B904200D130BD441C51F8045FF6 -:1028700000B243F82050E0B2F4E700BF0044025831 -:10288000004802585040005807B5012201A9002015 -:10289000FFF7C2FF019803B05DF804FB13B50446CF -:1028A000FFF7F2FFA04206D002A90122002041F862 -:1028B000044DFFF7C3FF02B010BD00000144BFF399 -:1028C0004F8F064B884204D3BFF34F8FBFF36F8FF8 -:1028D0007047C3F85C022030F4E700BF00ED00E071 -:1028E000034B1B685B0142BF0122024B1A70704709 -:1028F000D044025813320020014B1878704700BFB3 -:1029000013320020064A536823F001035360EFF3AB -:102910000983683383F30988002383F311887047A0 -:1029200030EF00E010B5202383F31188104B5B6873 -:1029300013F4006318D0F1EE103AEFF309844FF06E -:10294000807344F84C3C0B4BDB6844F8083CA4F122 -:10295000680383F30988FFF7D5FB18B1064B44F8E9 -:10296000503C10BD054BFAE783F3118810BD00BF42 -:1029700000ED00E030EF00E0F1030008F403000890 -:10298000F0B5BFF34F8FBFF36F8F1D4B0021C3F81E -:102990005012BFF34F8FBFF36F8F5A6942F400326A -:1029A0005A61BFF34F8FBFF36F8FC3F88410BFF32B -:1029B0004F8FD3F8802043F6E076C2F3C904C2F308 -:1029C0004E32A507520102EA060E284621464EEA7B -:1029D0000007013900F14040C3F860724F1CF6D186 -:1029E000203A12F1200FEED1BFF34F8F5A6942F413 -:1029F00080325A61BFF34F8FBFF36F8FF0BD00BFBE -:102A000000ED00E0FEE70000084A094B09498B424F -:102A100004D3094A0021934205D3704752F8040FAA -:102A200043F8040BF3E743F8041BF4E730440008D1 -:102A3000603500206035002060350020D0F89430EB -:102A4000002230B51146D0F890409D684FF0FF301D -:102A500004EB421301329542C3F80019C3F8101970 -:102A6000C3F80809C3F8001BC3F8101BC3F8080B10 -:102A7000EED24FF00113C4F81C3830BD00EB8103D7 -:102A80002DE9F04FD3F80CE04F1C4FEA4118DEF867 -:102A900014403F03D4F800C06568D0F89020654525 -:102AA0000AD30120D2F8343800FA01F123EA0101F7 -:102AB000C2F83418BDE8F08FACEB0503BEF8106027 -:102AC000B34228BF334602EB0806D6F81869B6B2FF -:102AD000B3EB860F13D8A6683A449946A6F1040AC8 -:102AE0005AF804BFB9F1040FC2F800B002D9A9F135 -:102AF0000409F5E71E442B44A6606360CCE7002080 -:102B0000BDE8F08F890141F02001016103699B0656 -:102B1000FCD4122000F03ABF10B50A4C2046FEF754 -:102B2000AFFF094BC4F89030084BC4F89430084C00 -:102B30002046FEF7A5FF074BC4F89030064BC4F8BB -:102B4000943010BD14320020000008407842000884 -:102B5000B032002000000440844200080378012BBA -:102B600070B505465DD1494BD0F89040984259D197 -:102B7000474B0E216520D3F8D82042F00062C3F8FD -:102B8000D820D3F8002142F00062C3F80021D3F826 -:102B90000021D3F8802042F00062C3F88020D3F8EF -:102BA000802022F00062C3F88020D3F88030FEF746 -:102BB000E1FB384BE360384BC4F800380023D5F80C -:102BC0009060C4F8003EC02323604FF40413A36355 -:102BD0003369002BFCDA01230C20336100F0D6FEB0 -:102BE0003369DB07FCD4122000F0D0FE3369002BE0 -:102BF000FCDA00262846A660FFF720FF6B68C4F8C1 -:102C00001068DB68C4F81468C4F81C68002B3AD15B -:102C1000224BA3614FF0FF336361A36843F00103CC -:102C2000A36070BD1E4B9842C8D1194B0E214D2098 -:102C3000D3F8D82042F00072C3F8D820D3F800218E -:102C400042F00072C3F80021D3F80021D3F88020AD -:102C500042F00072C3F88020D3F8802022F0007286 -:102C6000C3F88020D3F88020D3F8D82022F08062E7 -:102C7000C3F8D820D3F8002122F08062C3F80021E5 -:102C8000D3F8003193E7074BC3E700BF14320020AD -:102C9000004402584014004003002002003C30C0B1 -:102CA000B0320020083C30C0F8B5D0F8904005465E -:102CB00000214FF000662046FFF724FFD5F894105E -:102CC00000234FF001128F684FF0FF30C4F8343802 -:102CD000C4F81C2804EB431201339F42C2F8006978 -:102CE000C2F8006BC2F80809C2F8080BF2D20B68F0 -:102CF000D5F89020C5F898306362102313611669E7 -:102D000016F01006FBD1122000F040FED4F8003877 -:102D100023F4FE63C4F80038A36943F4402343F06E -:102D20001003A3610923C4F81038C4F814380B4BFE -:102D3000EB604FF0C043C4F8103B094BC4F8003BB4 -:102D4000C4F81069C4F80039D5F8983003F11002BE -:102D500043F48013C5F89820A362F8BD54420008DC -:102D600040800010D0F8902090F88A10D2F80038F7 -:102D700023F4FE6343EA0113C2F8003870470000F1 -:102D80002DE9F0410EB20D4600EB8608D8F80C1084 -:102D90000F6807F00303022B53D0032B53D03F4A95 -:102DA0003F4F012B18BF1746D0F890404FEA451E01 -:102DB000002205F1100C04EB0E03C3F8102B8A69F6 -:102DC000002A42D04A8A05F158033A435B01E25097 -:102DD0000123D4F81C2803FA0CF31343C4F81C385D -:102DE000A64400234A69CEF8103905F13F03002AB2 -:102DF0003BD00A8A04EB8303898B9208012988BFA0 -:102E00004A43D0F89810561841EA02422946C0F8C1 -:102E1000986020465A60FFF775FED8F80C301B8A80 -:102E200043EA85531F4305F148035B01E750012343 -:102E3000D4F81C2803FA05F51543C4F81C58BDE85E -:102E4000F081184FB0E7184FAEE704EB4613D3F804 -:102E5000002B22F40042C3F8002B0123D4F81C28D5 -:102E600003FA0CF322EA0303B8E704EB83030F4AE7 -:102E700004EB461629465A602046FFF743FED6F873 -:102E80000039012223F4004302FA05F5C6F800399F -:102E9000D4F81C3823EA0505CFE700BF00800010F6 -:102EA000008004100080081000800C100004000254 -:102EB000D0F894201268C0F89820FFF7BFBD00003A -:102EC0005831D0F8903049015B5813F4004004D0D9 -:102ED00013F4001F14BF0120022070474831D0F8BE -:102EE000903049015B5813F4004004D013F4001FE4 -:102EF00014BF01200220704700EB8101CB68196AE2 -:102F00000B6813604B6853607047000000EB81034F -:102F100030B5DD68AA691368D36019B9402B84BF46 -:102F2000402313606B8A1468D0F890201C4402EB95 -:102F30004110013C09B2B4FBF3F46343033323F0C3 -:102F4000030343EAC44343F0C043C0F8103B2B687B -:102F500003F00303012B0ED1D2F8083802EB411025 -:102F600013F4807FD0F8003B14BF43F0805343F04C -:102F70000053C0F8003B02EB4112D2F8003B43F093 -:102F80000443C2F8003B30BD2DE9F041D0F8906019 -:102F900005460C4606EB4113D3F8087B3A07C3F805 -:102FA000087B08D5D6F814381B0704D500EB81033D -:102FB000DB685B689847FA072FD5D6F81438DB072B -:102FC0002BD505EB8403D968CCB98B69488A5E6838 -:102FD000B6FBF0F200FB12628AB91868DA68904218 -:102FE0000DD2121A83E81400202383F3118821469E -:102FF0002846FFF78BFF84F31188BDE8F081012399 -:1030000003FA04F26B8923EA02036B81CB6823B1D4 -:1030100021462846BDE8F0411847BDE8F081000090 -:1030200000EB81034A0170B5DD68D0F890306C691F -:103030002668E66056BB1A444FF40020C2F8100917 -:103040002A6802F00302012A0AB20ED1D3F8080856 -:1030500003EB421410F4807FD4F8000914BF40F051 -:10306000805040F00050C4F8000903EB4212D2F83F -:10307000000940F00440C2F800090122D3F83408E6 -:1030800002FA01F10143C3F8341870BD19B9402E9A -:1030900084BF4020206020681A442E8A841940F0A2 -:1030A0000050013CB4FBF6F440EAC440C6E700001F -:1030B0002DE9F041D0F8906004460D4606EB41132F -:1030C000D3F80879C3F80879FB071CD5D6F810386F -:1030D000DA0718D500EB8103D3F80CE0DEF81430E2 -:1030E000D3F800C0DA6894451BD2A2EB0C024FF073 -:1030F00000081A60C3F80480202383F31188FFF7C7 -:103100008FFF88F311883B0618D50123D6F83428A1 -:10311000AB40134212D029462046BDE8F041FFF7EC -:10312000ADBC012303FA01F2038923EA0203038100 -:10313000DEF80830002BE6D09847E4E7BDE8F081E0 -:103140002DE9F047D0F8905004466E69AB691E40F7 -:10315000F1046E6103D5BDE8F047FEF70BBD002E0C -:1031600012DAD5F8003E9A0705D0D5F8003E23F0D4 -:103170000303C5F8003ED5F80438204623F00103C8 -:10318000C5F80438FEF726FD330502D52046FEF7C4 -:1031900015FDB7040CD5D5F8083813F0060FEB6809 -:1031A00023F470530CBF43F4105343F4A053EB606B -:1031B000300704D56368DB680BB120469847F102FD -:1031C00000F1A180B2020BD5D4F8908000274FF017 -:1031D0000109D4F89430F9B29B688B4280F0D28018 -:1031E000F3061AD5D4F890100A6AC2F30A1702F04F -:1031F0000F0302F4F012B2F5802F00F0EB80B2F56D -:10320000402F0AD104EB830301F58051DB68186A73 -:1032100000231A469F4240F0D1803003D5F8185859 -:1032200035D5E90303D500212046FFF7ADFEAA03FB -:1032300003D501212046FFF7A7FE6B0303D502212A -:103240002046FFF7A1FE2F0303D503212046FFF7F9 -:103250009BFEE80203D504212046FFF795FEA90254 -:1032600003D505212046FFF78FFE6A0203D506210C -:103270002046FFF789FE2B0203D507212046FFF7E2 -:1032800083FEEF0103D508212046FFF77DFE700382 -:1032900040F1C780E90703D500212046FFF708FF6A -:1032A000AA0703D501212046FFF702FF6B0703D5CC -:1032B00002212046FFF7FCFE2F0703D503212046FD -:1032C000FFF7F6FEEE0603D504212046FFF7F0FED9 -:1032D000A80603D505212046FFF7EAFE690603D5B7 -:1032E00006212046FFF7E4FE2A0603D507212046E3 -:1032F000FFF7DEFEEB0540F1948020460821BDE893 -:10330000F047FFF7D5BED4F890904FF000084FF08B -:10331000010AD4F894305FFA88F79B68BB42FFF447 -:1033200051AF09EB4713D3F8002902F44022B2F55C -:10333000802F24D1D3F80029002A20DAD3F80029DD -:1033400042F09042C3F80029D3F80029002AFBDBA1 -:103350003946D4F89000FFF7D5FB22890AFA07F323 -:1033600022EA0303238104EB8703DB689B6813B124 -:1033700039462046984739462046FFF77FFB08F13B -:103380000108C6E708EB4112D2F8003B03F44023E2 -:10339000B3F5802F10D1D2F8003B002B0CDA6289F4 -:1033A00009FA01F322EA0303638104EB8103DB687A -:1033B000DB680BB12046984701370AE713F0030F8B -:1033C00000D10A68072B03F101039EBF0270120AA5 -:1033D00001301FE704EB830301F58051DA6890693F -:1033E0000268D0F808C04068A2EB000E0022104628 -:1033F000974208D1DB689B699A683A449A605A6898 -:1034000017445F6009E712F0030F00D10868964582 -:1034100002F1010282BF8CF80000000A0CF1010CDD -:10342000E6E7BDE8F087000008B50348FFF788FE2F -:10343000BDE80840FFF776BA1432002008B503480B -:10344000FFF77EFEBDE80840FFF76CBAB0320020FF -:10345000D0F8903003EB4111D1F8003B43F4001356 -:10346000C1F8003B70470000D0F8903003EB4111E9 -:10347000D1F8003943F40013C1F800397047000057 -:10348000D0F8903003EB4111D1F8003B23F4001346 -:10349000C1F8003B70470000D0F8903003EB4111B9 -:1034A000D1F8003923F40013C1F800397047000047 -:1034B00030B50433039C0172002104FB0325C36172 -:1034C000049B00600363059B4060C1604261026130 -:1034D0008561046242628162C162436330BD000063 -:1034E0000022416AC260416101616FF001018262A4 -:1034F000C262FEF78FBE000003694269934203D1A6 -:10350000C2680AB100207047181D7047036919602E -:103510000021C2680132C260C269134482699342C9 -:10352000036124BF436A0361FEF768BE38B50446F1 -:103530000D46E3683BB162690020131D1268A36267 -:103540001344E36238BD237A33B929462046FEF797 -:1035500045FE0028EDDA38BD6FF00100FBE7000002 -:10356000C368C269013BC3604369134482699342E3 -:10357000436124BF436A436100238362036B03B149 -:103580001847704770B52023044683F31188866A74 -:103590003EB9FFF7CBFF054618B186F311882846E0 -:1035A00070BDA36AE26A13F8015B9342A36202D37F -:1035B0002046FFF7D5FF002383F31188EFE70000D3 -:1035C0002DE9F84F04460E4690469946202787F38A -:1035D00011880025AA46D4F828B0BBF1000F09D104 -:1035E00049462046FFF7A2FF20B18BF311882846F9 -:1035F000BDE8F88FA16AA8EB050BE36A5B1A9B454F -:1036000028BF9B46BBF1400F1BD9334601F1400256 -:1036100051F8040B914243F8040BF9D1A36A4036E8 -:1036200040354033A362A26AE36A9A4202D320463D -:10363000FFF796FF8AF311884545D8D287F31188A2 -:10364000C9E730465A46FDF783FCA36A5E445D44F1 -:103650005B44A362E7E7000010B5029C04330172EB -:10366000C36103FB0421002300608362C362039BE8 -:1036700040600363049BC460426102618161046233 -:103680004262436310BD0000026A6FF00101C26034 -:10369000426A4261026100228262C262FEF7BABDE2 -:1036A000436902699A4203D1C2680AB10020704797 -:1036B000184650F8043B0B6070470000C3680021B7 -:1036C000C2690133C3604369134482699342436111 -:1036D00024BF436A4361FEF791BD000038B504463C -:1036E0000D46E3683BB1236900201A1DA262E2691E -:1036F0001344E36238BD237A33B929462046FEF7E6 -:103700006DFD0028EDDA38BD6FF00100FBE7000029 -:1037100003691960C268013AC260C26913448269D0 -:103720009342036124BF436A036100238362036BF6 -:1037300003B118477047000070B5202304460E46B9 -:1037400083F31188856A35B91146FFF7C7FF10B1B9 -:1037500085F3118870BDA36A1E70A36AE26A013303 -:103760009342A36204D3E16920460439FFF7D0FFF6 -:10377000002080F3118870BD2DE9F84F04460D46F6 -:1037800091469A464FF0200888F311880026B346E8 -:10379000A76A4FB951462046FFF7A0FF20B187F333 -:1037A00011883046BDE8F88FA06AA9EB0603E76AE6 -:1037B0003F1A9F4228BF1F46402F1BD905F14003E7 -:1037C00055F8042B9D4240F8042BF9D1A36A4036EA -:1037D0004033A362A26AE36A9A4204D3E1692046B5 -:1037E0000439FFF795FF8BF311884E45D9D288F342 -:1037F0001188CDE729463A46FDF7AAFBA36A3D4466 -:103800003E443B44A362E5E7026943699A4203D11F -:10381000C3681BB9184670470023FBE7836A002B77 -:10382000F8D0043B9B1AF5D01360C368013BC3601A -:10383000C3691A4483699A42026124BF436A0361DF -:10384000002383620123E5E700F050B9034B002217 -:1038500058631A610222DA60704700BF000C004012 -:103860000022014BDA607047000C0040014B5863A6 -:10387000704700BF000C0040FEE7000010B5194C77 -:10388000FEF7B2FBFEF7D4FC802217492046FEF774 -:1038900059FC012344F8180C0374144B144AD968DA -:1038A00021F4E0610904090C0A431249DA60CA688C -:1038B00042F08072CA60104A1049C2F8B01F116805 -:1038C00041F0010111601022DA77202283F82220D2 -:1038D000002383F3118862B60948BDE81040FEF763 -:1038E00053BC00BFD42A00209042000800ED00E045 -:1038F0000003FA05F0ED00E0001000E055CEACC585 -:10390000984200082DE9F84F1E4C4FF00008DFF8F0 -:103910007890656904F11407D9F82430266AAA68FA -:103920009E1B96421CD34FF0200AAA68236AD5F842 -:103930000CB0B61A134423622B68BB425F6063610C -:10394000C5F80C8001D1FFF78BFF88F31188286937 -:10395000D8478AF311886569AB689E42E5D2DBE7F8 -:103960006269BA420CD0916823628E1B9660A86887 -:1039700002282CBF1818981CBDE8F84FFFF776BF37 -:10398000BDE8F88FAC2A0020000C0040034B5968BA -:103990005A68521A9042FBD8704700BF001000E0EE -:1039A0004B6843608B688360CB68C3600B6943617D -:1039B0004B6903628B6943620B68036070470000C8 -:1039C00008B52C4B40F2FF712B48D3F888200A43EE -:1039D000C3F88820D3F8882022F4FF6222F007027F -:1039E000C3F88820D3F88820D3F8E0200A43C3F82E -:1039F000E020D3F808210A43C3F808211F4AD3F86E -:103A000008311146FFF7CCFF1D4802F11C01FFF7FA -:103A1000C7FF1C4802F13801FFF7C2FF1A4802F144 -:103A20005401FFF7BDFF194802F17001FFF7B8FF1D -:103A3000174802F18C01FFF7B3FF164802F1A80105 -:103A4000FFF7AEFF144802F1C401FFF7A9FF1348C6 -:103A500002F1E001FFF7A4FF114802F1FC01FFF7BA -:103A60009FFF104802F58C71FFF79AFFBDE80840F0 -:103A700000F016B90044025800000258B84200088D -:103A80000004025800080258000C025800100258A6 -:103A90000014025800180258001C02580020025856 -:103AA000002402580028025808B500F0C9FAFFF7B0 -:103AB000E5FEFEF715FFBDE80840FEF7C3BC0000B9 -:103AC00070470000084B1A69920710B508D500240A -:103AD0001C61202383F31188FFF714FF84F31188FE -:103AE000BDE81040FEF71EBF000C0040124B08213D -:103AF0003220D3F8E82042F00802C3F8E820D3F8D7 -:103B0000102142F00802C3F810210C4AD3F81031FA -:103B1000D36B43F00803D363C722094B9A624FF07B -:103B2000FF32DA6200229A615A63DA605A60012237 -:103B30005A611A60FDF71EBC004402580010005C78 -:103B4000000C0040F8B5514B0024D3F880204FF012 -:103B5000FF32C3F88020D3F88010C3F88040D3F838 -:103B60008010D3F88410C3F88420D3F88410C3F8ED -:103B70008440D3F88410D96F41F0FF4141F4FF0134 -:103B800041F4DF4141F07F01D967D96F21F0FF4156 -:103B900021F4FF0121F4DF4121F07F01D967D96FC2 -:103BA000D3F888106FEA41516FEA5151C3F8881079 -:103BB000D3F88810C1F30A01C3F88810D3F888102D -:103BC000D3F89010C3F89020D3F89010C3F8904029 -:103BD000D3F89010D3F89410C3F89420D3F894102D -:103BE000C3F89440D3F89410D3F89810C3F89820F1 -:103BF000D3F89810C3F89840D3F89810D3F88C10E5 -:103C0000C3F88C20D3F88C10C3F88C40D3F88C10F8 -:103C1000D3F89C10C3F89C20D3F89C20C3F89C4098 -:103C2000D3F89C3000F0ECF9194B07229A60194A3E -:103C3000DA60194A1A6105225A60184A536A43F435 -:103C400080335362C2F88440BFF34F8FD2F8803084 -:103C500043F6E076C3F3C904C3F34E33A5075B0113 -:103C600003EA060E284621464EEA0007013900F114 -:103C70004040C2F874724F1CF6D1203B13F1200F64 -:103C8000EED1BFF34F8FBFF36F8FF8BD00440258E2 -:103C900090ED00E0000004301B00080300ED00E0A0 -:103CA00001225B4B5B491A605B4B19609A605B4A6F -:103CB000DA6000221A614FF440429A619A699204D4 -:103CC000FCD51A6842F480721A60554B1A6F12F4D0 -:103CD000407F04D04FF480321A6700221A671A68B6 -:103CE00042F001021A604E4A134611684807FCD59B -:103CF000002111611A6912F03802FBD1012119600B -:103D00004FF0804159605A67464ADA62464A1A6162 -:103D10001A6842F480321A60414A134611688903D6 -:103D2000FCD5116841F0800111601A68D205FCD5FC -:103D30003E4A3F499A6200225A631963A1F58021E5 -:103D4000DA634B3999635A643A4A1A643A4ADA6236 -:103D50001A6842F0A8521A60314B1A6802F02852D1 -:103D6000B2F1285FF9D1482222219A614FF488628A -:103D7000DA6140221A624FF00052DA641A652F4A63 -:103D80005A652F4A9A652F4A11601A6942F0030258 -:103D90001A61234B1A6902F03802182AFAD1D3F8B3 -:103DA000DC2042F00052C3F8DC20D3F8042142F0BA -:103DB0000052C3F80421D3F80421D3F8DC2042F0E8 -:103DC0008042C3F8DC20D3F8042142F08042C3F8DB -:103DD0000421D3F80421D3F8DC2042F00042C3F8D8 -:103DE000DC20D3F8042142F00042C3F80421D3F8C8 -:103DF0000421D3F8F42042F00202C3F8F420D3F8EF -:103E00001C2142F00202C3F81C21D3F81C31704778 -:103E10000881005100C000F0004802580200000173 -:103E2000004402580000FF01008890081210200092 -:103E30006302070147040508FD0BFF010010E000C5 -:103E40000001010000200052084A08B5936811687B -:103E50000B4003F00103936023B1054A13680BB1D3 -:103E600050689847BDE80840FEF75CBD80000058E8 -:103E7000C0250020084A08B5936811680B4003F07C -:103E80000203936023B1054A93680BB1D068984749 -:103E9000BDE80840FEF746BD80000058C025002060 -:103EA000084A08B5936811680B4003F00403936057 -:103EB00023B1054A13690BB150699847BDE8084022 -:103EC000FEF730BD80000058C0250020084A08B524 -:103ED000936811680B4003F00803936023B1054A0F -:103EE00093690BB1D0699847BDE80840FEF71ABD49 -:103EF00080000058C0250020084A08B59368116862 -:103F00000B4003F01003936023B1054A136A0BB111 -:103F1000506A9847BDE80840FEF704BD800000588D -:103F2000C0250020174B10B59C681A68144004F493 -:103F300078729A60A30604D5134A936A0BB1D06ACB -:103F40009847600604D5104A136B0BB1506B984725 -:103F5000210604D50C4A936B0BB1D06B9847E20550 -:103F600004D5094A136C0BB1506C9847A30504D5CE -:103F7000054A936C0BB1D06C9847BDE81040FEF732 -:103F8000D1BC00BF80000058C02500201A4B10B5DE -:103F90009C681A68144004F47C429A60620504D557 -:103FA000164A136D0BB1506D9847230504D5134A7B -:103FB000936D0BB1D06D9847E00404D50F4A136E92 -:103FC0000BB1506E9847A10404D50C4A936E0BB107 -:103FD000D06E9847620404D5084A136F0BB1506F36 -:103FE0009847230404D5054A936F0BB1D06F9847C7 -:103FF000BDE81040FEF796BC80000058C0250020A8 -:10400000062108B50846FDF7B5F906210720FDF79A -:10401000B1F906210820FDF7ADF906210920FDF7C9 -:10402000A9F906210A20FDF7A5F906211720FDF7B9 -:10403000A1F906212820BDE80840FDF79BB9000042 -:1040400008B5FFF77FFDFDF76BF8FDF73DFBFDF7CA -:1040500015FDFDF7E7FBFFF733FDBDE80840FFF76F -:10406000F3BB000010B501390244904201D1002099 -:1040700010BD10F8013B11F8014FA342F5D0181BF9 -:1040800010BD0000034611F8012B03F8012B002A94 -:10409000F9D17047121012131211000001105A00CA -:1040A000031059000120580003205600EC2A00207C -:1040B0004026002053544D333248373F3F3F005392 -:1040C000544D3332483734332F3735330000000036 -:1040D000009600000000000000000000000000004A -:1040E0000000000000000000000000009116000821 -:1040F0007D160008B9160008A5160008B1160008BC -:104100009D1600088916000875160008C5160008D7 -:10411000000000009D17000889170008C517000857 -:10412000B1170008BD170008A91700089517000867 -:10413000811700082118000800000000010000009D -:10414000000000000200000000000000C919000883 -:10415000351A000840004000842F0020942F0020D2 -:10416000020000000000000003000000000000004A -:10417000791A00080000000010000000A42F0020A1 -:1041800000000000010000000000000014320020C8 -:10419000010102004172647550696C6F7400254220 -:1041A0004F415244252D424C002553455249414C24 -:1041B00025000000E52300084D23000835190008FC -:1041C000C923000843000000CC4100080902430055 -:1041D000020100C0320904000001020201000524AE -:1041E0000010010524010001042402020524060038 -:1041F00001070582030800FF09040100020A00000C -:104200000007050102400000070581024000000090 -:1042100012000000184200081201100102000040C4 -:1042200009124157000201020301000004030904BE -:1042300025424F41524425004D6174656B48373427 -:104240003300303132333435363738394142434424 -:104250004546000000000000E91B0008C91E0008D8 -:10426000751F0008400040004C3300204C330020F4 -:10427000010000005C3300208000000040010000CD -:104280000800000000010000000400000800000019 -:104290006D61696E00000000B042000868330020C4 -:1042A000603500200100000079380008000000009F -:1042B00069646C65000000000000802A00000000B6 -:1042C000AAAAAAAA00000000FFFF00000000000048 -:1042D00000A00A000000000100000000AAAAAAAA8B -:1042E00000000001FFFF00000000000000000000CF -:1042F0000000004000000000AAAAAAAA0000004096 -:10430000FFFF0000000000000000000000010000AE -:1043100000000000AAAAAAAA00010000FFFF0000F6 -:10432000000000000000000040804200000000008B -:10433000AAAAAAAA00404100F7FF000000000070EE -:10434000070000000000000000000000AAAAAAAABE -:1043500000000000FFFF000000000000000000005F -:104360000000000000000000AAAAAAAA00000000A5 -:10437000FFFF00000000000000000000000000003F -:1043800000000000AAAAAAAA00000000FFFF000087 -:10439000000000000000000000000000000000001D -:1043A000AAAAAAAA00000000FFFF00000000000067 -:1043B000000000000000000000000000AAAAAAAA55 -:1043C00000000000FFFF00000000000000000000EF -:1043D0000000000000000000AAAAAAAA0000000035 -:1043E000FFFF0000000000000000000000000000CF -:1043F000FF00000000000000B44000083F00000083 -:1044000050040000BF4000083F000000009600007C -:1044100000000800040000002C420008000000001A -:10442000000000000000000000000000000000008C -:044430000000000088 +:100310006F8F02F0CDFB02F06FFB03F009FB4FF093 +:1003200055301F491B4A91423CBF41F8040BFAE784 +:100330001C49194A91423CBF41F8040BFAE71A499B +:100340001A4A1B4B9A423EBF51F8040B42F8040B69 +:10035000F8E700201749184A91423CBF41F8040BC6 +:10036000FAE702F087FB03F067FB144C144DAC4234 +:1003700003DA54F8041B8847F9E700F041F8114C00 +:10038000114DAC4203DA54F8041B8847F9E702F038 +:100390006FBB0000000600200022002000000008C3 +:1003A0000000002000060020A043000800220020DA +:1003B0005C22002060220020FC460020A0020008F1 +:1003C000A0020008A0020008A00200082DE9F04FDA +:1003D0002DED108AC1F80CD0D0F80CD0BDEC108AED +:1003E000BDE8F08F002383F311882846A047002042 +:1003F00001F084FEFEE701F0FFFD00DFFEE70000F4 +:1004000038B500F0E9FC30B1164B00220E211A720B +:100410005A729972DA7202F04DFA054602F080FAC9 +:100420000446D0B9104B9D4219D001339D4241F290 +:10043000883512BF044600250124002002F044FA4A +:100440000CB100F059F800F061FD00F0FFFB284608 +:1004500000F004F900F050F8F9E70025EDE7054653 +:10046000EBE700BF00220020010007B008B500F054 +:10047000B9FBA0F120035842584108BD07B541F22D +:100480001203022101A8ADF8043000F0C9FB03B04B +:100490005DF804FB202310B583F311881248C3686C +:1004A0000BB101F0B1FE0023104A4FF47A710E48EF +:1004B00001F06EFE002383F311880D4C236813B105 +:1004C0002368013B2360636813B16368013B636089 +:1004D000084B1B7833B9636823B9022000F090FC05 +:1004E0003223636010BD00BF602200209504000825 +:1004F0007C23002074220020F8B5514B514A1C4641 +:100500001968013100F09B8004339342F8D162688E +:100510004D4B9A4240F293804C4B9B6803F1006331 +:1005200003F500339A4280F08A80002000F0B4FB8B +:100530000220474B187000F05BFC464B0021D3F8BB +:10054000E820C3F8E810D3F81021C3F81011D3F84D +:100550001021D3F8EC20C3F8EC10D3F81421C3F821 +:100560001411D3F81421D3F8F020C3F8F010D3F805 +:100570001821C3F81811D3F81821D3F8802042F0BD +:100580000062C3F88020D3F8802022F00062C3F814 +:100590008020D3F88020D3F8802042F00072C3F886 +:1005A0008020D3F8802022F00072C3F88020D3F896 +:1005B000803072B64FF0E023C3F8084DD4E9000450 +:1005C000BFF34F8FBFF36F8F234AC2F88410BFF37E +:1005D0004F8F536923F480335361BFF34F8FD2F8A9 +:1005E000803043F6E076C3F3C905C3F34E335B01B5 +:1005F00003EA060C29464CEA81770139C2F8747285 +:10060000F9D2203B13F1200FF2D1BFF34F8FBFF38C +:100610006F8FBFF34F8FBFF36F8F536923F4003396 +:1006200053610023C2F85032BFF34F8FBFF36F8F77 +:10063000202383F31188854680F308882047F8BD7E +:100640000000020820000208FFFF0108002200202D +:10065000742200200044025800ED00E02DE9F04F24 +:1006600093B0A94B2022FF2100900AA89D6800F0BA +:10067000F7FBA64A1378A3B90121A5481170C360FE +:10068000202383F31188C3680BB101F0BDFD002363 +:10069000A04A4FF47A719E4801F07AFD002383F35B +:1006A0001188009B9C4A03B1136000239B49009C66 +:1006B00098469B461E469A460B705360012000F0F8 +:1006C00097FB24B1944B1B68002B00F0168200208E +:1006D00000F088FA0390039B002BF2DB012000F06E +:1006E0007DFB039B213B162BE8D801A252F823F097 +:1006F0004D0700087507000809080008BD06000836 +:10070000BD060008BD0600089D0800086F0A000825 +:1007100089090008EB090008130A0008390A0008D3 +:10072000BD0600084B0A0008BD060008BD0A000807 +:10073000ED070008BD060008010B00085907000876 +:10074000ED070008BD060008EB0900080220FFF7CE +:100750008DFE002840F0FB81009B022105A8B8F126 +:10076000000F08BF1C4641F21233ADF8143000F000 +:1007700057FAA3E74FF47A7000F034FA071EEBDB68 +:100780000220FFF773FE0028E6D0013F052F00F29C +:10079000E081DFE807F0030A0D101336052304217A +:1007A00005A8059300F03CFA17E004215648F9E744 +:1007B00004215B48F6E704215A48F3E74FF01C098F +:1007C000484609F1040900F069FA0421059005A8DA +:1007D00000F026FAB9F12C0FF2D101204FF0000AF7 +:1007E00000FA07F747EA0B0B5FFA8BFB00F084FB7C +:1007F00026B10BF00B030B2B08BF0024FFF73EFEC6 +:100800005CE704214848CDE7002EA5D00BF00B0390 +:100810000B2BA1D10220FFF729FE074600289BD011 +:1008200001203E4E00F038FA4FF0000802203070F0 +:1008300000F0DEFA5FFA88F9484600F03DFA044617 +:1008400090B1484608F1010800F046FA0028F1D1BD +:10085000B846044641F21213022105A83E46ADF8FF +:10086000143000F0DDF929E701232546022033701A +:1008700000F0B4FA244B9B68AB4207D9284600F03D +:100880000DFA013040F068810435F3E70025234B71 +:10089000B8463E461D70204B5D60A7E7002E3FF432 +:1008A0005BAF0BF00B030B2B7FF456AF02201B4BFF +:1008B000187000F09DFA322000F094F9B0F10009B0 +:1008C000FFF64AAF19F003077FF446AF0E4A09EB73 +:1008D0000503926893423FF63FAFB9F5807F3FF73B +:1008E0003BAF124BB945019322DD4FF47A7000F013 +:1008F00079F90390039A002AFFF62EAF039A013785 +:10090000019B03F8012BEDE7002200207823002053 +:1009100060220020950400087C230020742200201F +:1009200004220020082200200C220020782200202F +:10093000C820FFF79BFD074600283FF40DAF1F2D91 +:1009400011D8C5F120020AAB25F0030084494A45BD +:10095000184428BF4A46019200F05CFA019AFF2130 +:100960007F4800F07DFA4FEAA903C9F387027C496A +:100970002846019300F07CFA064600283FF46AAF4F +:10098000019B05EB830531E70220FFF76FFD00288F +:100990003FF4E2AE00F0BCF900283FF4DDAE0027E2 +:1009A000B946704B9B68BB4218D91F2F11D80A9BC0 +:1009B00001330ED027F0030312AA134453F8203C4E +:1009C00005934846042205A9043700F03BFB814605 +:1009D000E7E7384600F062F90590F2E7CDF81490A9 +:1009E000042105A800F01CF900E70023642104A8F5 +:1009F000049300F00BF900287FF4AEAE0220FFF75D +:100A000035FD00283FF4A8AE049800F077F9059072 +:100A1000E6E70023642104A8049300F0F7F8002817 +:100A20007FF49AAE0220FFF721FD00283FF494AE38 +:100A3000049800F065F9EAE70220FFF717FD0028A7 +:100A40003FF48AAE00F074F9E1E70220FFF70EFDF3 +:100A500000283FF481AE05A9142000F06FF9074685 +:100A60000421049004A800F0DBF83946B9E73220ED +:100A700000F0B8F8071EFFF66FAEBB077FF46CAE50 +:100A8000384A07EB0A03926893423FF665AE0220AC +:100A9000FFF7ECFC00283FF45FAE27F00307574454 +:100AA000BA453FF4A3AE50460AF1040A00F0F6F846 +:100AB0000421059005A800F0B3F8F1E74FF47A702F +:100AC000FFF7D4FC00283FF447AE00F021F90028DE +:100AD00044D00A9B01330BD008220AA9002000F061 +:100AE000C7F900283AD02022FF210AA800F0B8F95F +:100AF000FFF7C4FC1C4801F007FB13B0BDE8F08F02 +:100B0000002E3FF429AE0BF00B030B2B7FF424AE29 +:100B10000023642105A8059300F078F80746002813 +:100B20007FF41AAE0220FFF7A1FC814600283FF4B3 +:100B300013AEFFF7A3FC41F2883001F0E5FA059807 +:100B400000F01EFA4E463C4600F0D6F9B6E50646E1 +:100B50004CE64FF0000AFFE5B8467BE6374679E6FB +:100B60007822002000220020A0860100F7B50C4664 +:100B7000184E4FF47A71054602FB01F396F90020F6 +:100B8000501C0BD11448294601930268176A22466B +:100B9000B8478442019B03D1002310E0002AF1D022 +:100BA00096F90020511C01D0012A0DD10B4829468D +:100BB0000268166A2246B047844205D10123084ADA +:100BC0000120137003B0F0BD4FF4FA7001F09CFAED +:100BD0000020F7E710220020F0290020CC2300207D +:100BE000C8230020002307B5024601210DF10700AC +:100BF0008DF80730FFF7BAFF20B19DF8070003B06A +:100C00005DF804FB4FF0FF30F9E700000A460421CD +:100C100008B5FFF7ABFF80F00100C0B2404208BD4D +:100C2000074B0A4630B41978064B53F82140014669 +:100C300023682046DD69044BAC4630BC604700BFEA +:100C4000C823002078400008A086010070B5104C31 +:100C50000025104E01F006FD208030682388834275 +:100C60000CD800252088013801F0F8FC23880544C1 +:100C7000013BB5F5802F2380F4D370BD01F0EEFC6D +:100C8000336805440133B5F5003F3360E5D3E8E749 +:100C9000CA2300208423002001F0C2BD00F10060BF +:100CA00000F500300068704700F10060920000F528 +:100CB000003001F039BD0000054B1A68054B1B8858 +:100CC0009B1A834202D9104401F0C8BC002070472F +:100CD00084230020CA23002038B5074D0446286825 +:100CE000204401F0C1FC28B928682044BDE8384000 +:100CF00001F0CCBC38BD00BF842300200020704729 +:100D000000F1FF5000F58F10D0F800087047000088 +:100D1000064991F8243033B100230822086A81F88B +:100D20002430FFF7C1BF0120704700BF8823002097 +:100D3000014B1868704700BF0010005C244BF0B5F1 +:100D40001A680446234BC2F30B06120C1F8858681E +:100D5000BE4293F9085028D09F89BE4206D1012097 +:100D60000C2505FB0033586893F9085041F2010344 +:100D70009A421CD041F203039A421AD042F2010374 +:100D80009A4218D042F203039A4208BF5625621EC7 +:100D90000B46441E0A4493420FD214F9016F581CAB +:100DA0006EB1034600F8016CF5E70020D8E75A253C +:100DB000EDE75925EBE75825E9E7184605E02C242F +:100DC00082421C7001D9981C5D70401AF0BD00BFB2 +:100DD0000010005C1422002000207047022803D17C +:100DE000024B4FF400229A61704700BF0010025876 +:100DF000022802D1014B08229A6170470010025864 +:100E0000022804D1024A536983F0080353617047F2 +:100E100000100258002310B5934203D0CC5CC45498 +:100E20000133F9E710BD0000013810B510F9013F9A +:100E30003BB191F900409C4203D11AB10131013A12 +:100E4000F4E71AB191F90020981A10BD1046FCE79A +:100E500003460246D01A12F9011B0029FAD1704745 +:100E600002440346934202D003F8011BFAE770479D +:100E70002DE9F8431F4D14460746884695F824206F +:100E800052BBDFF870909CB395F824302BB9202228 +:100E9000FF2148462F62FFF7E3FF95F82400414603 +:100EA000C0F1080205EB8000A24228BF2246D6B25C +:100EB0009200FFF7AFFF95F82430A41B17441E449F +:100EC0009044E4B2F6B2082E85F82460DBD1FFF737 +:100ED0001FFF0028D7D108E02B6A03EB820383426F +:100EE000CFD0FFF715FF0028CBD10020BDE8F88355 +:100EF0000120FBE788230020024B1A78024B1A706E +:100F0000704700BFC82300201022002038B5164CBF +:100F1000164D204600F0FAFB2946204600F022FC40 +:100F20002D681348D5F89020D2F8043843F0020316 +:100F3000C2F8043801F0E8F80E49284600F020FD18 +:100F4000D5F890200C48D2F804380C49A04223F080 +:100F50000203C2F804384FF4E1330B6003D0BDE85C +:100F6000384000F031BB38BDF02900208441000832 +:100F700040420F008C410008CC230020B023002009 +:100F800038B50B4B04461A780A4B53F822500A4BDB +:100F90009D420CD0094B002118221846FFF760FF34 +:100FA000046001462846BDE8384000F00DBB38BD5E +:100FB000C823002078400008F0290020B02300203A +:100FC00000B59BB0EFF3098168226846FFF722FF66 +:100FD000EFF30583044B9A6BDA6A9A6A9A6A9A6A03 +:100FE0009A6A9A6A9B6AFEE700ED00E000B59BB042 +:100FF000EFF3098168226846FFF70CFFEFF30583E2 +:10100000044B9A6B9A6A9A6A9A6A9A6A9A6A9B6A73 +:10101000FEE700BF00ED00E000B59BB0EFF30981F3 +:1010200068226846FFF7F6FEEFF30583034B5A6B21 +:101030009A6A9A6A9A6A9A6A9B6AFEE700ED00E0E9 +:10104000FEE7000030B50A44084D91420DD011F87A +:10105000013B5840082340F30004013B2C4013F0AF +:10106000FF0384EA5000F6D1EFE730BD2083B8EDEE +:10107000026843681143016003B1184770470000DC +:10108000024A136843F0C0031360704700780040C1 +:1010900013B50E4C204600F08BFA04F11400002327 +:1010A0004FF400720A49009400F04CF9094B4FF4D8 +:1010B0000072094904F13800009400F0C5F9074AAC +:1010C000074BC4E9172302B010BD00BFCC2300209A +:1010D00038240020811000083826002000780040C5 +:1010E00000E1F505037C30B5244C002918BF0C46FF +:1010F000012B11D1224B98420ED1224BD3F8E8207C +:1011000042F08042C3F8E820D3F8102142F0804238 +:10111000C3F81021D3F810312268036EC16D03EBC0 +:1011200052038466B3FBF2F36268150442BF23F0F6 +:10113000070503F0070343EA4503CB60A36843F0C8 +:1011400040034B60E36843F001038B6042F4967305 +:1011500043F001030B604FF0FF330B62510505D5DF +:1011600012F0102205D0B2F1805F04D080F8643014 +:1011700030BD7F23FAE73F23F8E700BF8040000837 +:10118000CC230020004402582DE9F047C66D0546E7 +:101190003768F4692107346219D014F0080118BFC8 +:1011A0008021E20748BF41F02001A3074FF0200350 +:1011B00048BF41F04001600748BF41F4807183F3AC +:1011C0001188281DFFF754FF002383F31188E205DF +:1011D0000AD5202383F311884FF40071281DFFF7EF +:1011E00047FF002383F311884FF020094FF0000AD6 +:1011F00014F0200838D13B0616D54FF0200905F130 +:10120000380A200610D589F31188504600F050F9AD +:10121000002836DA0821281DFFF72AFF27F080036F +:101220003360002383F31188790614D5620612D542 +:10123000202383F31188D5E913239A4208D12B6C1C +:1012400033B127F040071021281DFFF711FF376049 +:10125000002383F31188E30618D5AA6E1369ABB196 +:101260005069BDE8F047184789F31188736A28462A +:1012700095F86410194000F0B5F98AF31188F46903 +:10128000B6E7B06288F31188F469BAE7BDE8F08781 +:10129000F8B51546826804460B46AA4200D2856816 +:1012A000A1692669761AB5420BD218462A46FFF77D +:1012B000B1FDA3692B44A3612846A3685B1BA3600F +:1012C000F8BD0CD9AF1B18463246FFF7A3FD3A46CE +:1012D000E1683044FFF79EFDE3683B44EBE71846C6 +:1012E0002A46FFF797FDE368E5E70000836893422D +:1012F000F7B50446154600D28568D4E90460361A6D +:10130000B5420BD22A46FFF785FD63692B44636122 +:101310002846A3685B1BA36003B0F0BD0DD932461D +:10132000AF1B0191FFF776FD01993A46E068314421 +:10133000FFF770FDE3683B44E9E72A46FFF76AFDE3 +:10134000E368E4E710B50A440024C361029B8460AB +:10135000C16002610362C0E90000C0E9051110BD6F +:1013600008B5D0E90532934201D1826882B982681A +:10137000013282605A1C426119700021D0E90432A6 +:101380009A4224BFC368436100F0DAFE002008BD22 +:101390004FF0FF30FBE7000070B5202304460E46F7 +:1013A00083F31188A568A5B1A368A269013BA36076 +:1013B000531CA36115782269934224BFE368A3619B +:1013C000E3690BB120469847002383F31188284630 +:1013D00007E03146204600F0A3FE0028E2DA85F35C +:1013E000118870BD2DE9F74F04460E461746984602 +:1013F000D0F81C904FF0200A8AF311884FF0000BB0 +:10140000154665B12A4631462046FFF741FF03469F +:1014100060B94146204600F083FE0028F1D0002349 +:1014200083F31188781B03B0BDE8F08FB9F1000F8A +:1014300003D001902046C847019B8BF31188ED1A19 +:101440001E448AF31188DCE7C160C361009B82609F +:101450000362C0E905111144C0E900000161704751 +:10146000F8B504460D461646202383F31188A76875 +:10147000A7B1A368013BA36063695A1C62611D7038 +:10148000D4E904329A4224BFE3686361E3690BB193 +:1014900020469847002080F3118807E03146204617 +:1014A00000F03EFE0028E2DA87F31188F8BD000064 +:1014B000D0E9052310B59A4201D182687AB98268D1 +:1014C0000021013282605A1C82611C7803699A42B1 +:1014D00024BFC368836100F033FE204610BD4FF087 +:1014E000FF30FBE72DE9F74F04460E4617469846B6 +:1014F000D0F81C904FF0200A8AF311884FF0000BAF +:10150000154665B12A4631462046FFF7EFFE0346F1 +:1015100060B94146204600F003FE0028F1D00023C8 +:1015200083F31188781B03B0BDE8F08FB9F1000F89 +:1015300003D001902046C847019B8BF31188ED1A18 +:101540001E448AF31188DCE7026843681143016096 +:1015500003B11847704700001430FFF743BF000085 +:101560004FF0FF331430FFF73DBF00003830FFF776 +:10157000B9BF00004FF0FF333830FFF7B3BF0000B2 +:101580001430FFF709BF00004FF0FF311430FFF7B0 +:1015900003BF00003830FFF763BF00004FF0FF3299 +:1015A0003830FFF75DBF000000207047FFF770BDC7 +:1015B000044B036000234360C0E90233012303743A +:1015C000704700BF9840000810B52023044683F3FD +:1015D0001188FFF787FD02232374002383F311880A +:1015E00010BD000038B5C36904460D461BB904217F +:1015F0000844FFF7A9FF294604F11400FFF7B0FEE5 +:10160000002806DA201D4FF48061BDE83840FFF75E +:101610009BBF38BD026843681143016003B118479E +:101620007047000013B5406B00F58054D4F8A4381F +:101630001A681178042914D1017C022911D1197971 +:10164000012312898B4013420BD101A94C3002F0C7 +:101650006FF8D4F8A4480246019B2179206800F075 +:10166000DFF902B010BD0000143001F0F1BF00003E +:101670004FF0FF33143001F0EBBF00004C3002F0AC +:10168000C3B800004FF0FF334C3002F0BDB800008B +:10169000143001F0BFBF00004FF0FF31143001F0F3 +:1016A000B9BF00004C3002F08FB800004FF0FF329D +:1016B0004C3002F089B800000020704710B500F5EA +:1016C0008054D4F8A4381A681178042917D1017C01 +:1016D000022914D15979012352898B4013420ED12A +:1016E000143001F051FF024648B1D4F8A4484FF439 +:1016F000407361792068BDE8104000F07FB910BDEB +:10170000406BFFF7DBBF0000704700007FB5124B56 +:1017100001250426044603600023057400F18402B9 +:1017200043602946C0E902330C4B02901430019308 +:101730004FF44073009601F003FF094B04F6944206 +:10174000294604F14C000294CDE900634FF4407344 +:1017500001F0CAFF04B070BDC040000801170008C6 +:10176000251600080A68202383F311880B790B33B0 +:1017700042F823004B79133342F823008B7913B1DD +:101780000B3342F8230000F58053C3F8A41802235A +:101790000374002383F311887047000038B5037F7A +:1017A000044613B190F85430ABB90125201D022135 +:1017B000FFF730FF04F114006FF00101257700F00E +:1017C000CBFC04F14C0084F854506FF00101BDE8EB +:1017D000384000F0C1BC38BD10B5012104460430CA +:1017E000FFF718FF0023237784F8543010BD000062 +:1017F00038B504460025143001F0BAFE04F14C005F +:10180000257701F089FF201D84F854500121FFF74E +:1018100001FF2046BDE83840FFF750BF90F8803008 +:1018200003F06003202B06D190F881200023212AA9 +:1018300003D81F2A06D800207047222AFBD1C0E90E +:101840001D3303E0034A426707228267C367012012 +:10185000704700BF2C22002037B500F58055D5F821 +:10186000A4381A68117804291AD1017C022917D1E9 +:101870001979012312898B40134211D100F14C04D4 +:10188000204602F009F858B101A9204601F050FFA6 +:10189000D5F8A4480246019B2179206800F0C0F8E1 +:1018A00003B030BD01F10B03F0B550F8236085B0F3 +:1018B00004460D46FEB1202383F3118804EB85070F +:1018C000301D0821FFF7A6FEFB6806F14C005B699E +:1018D0001B681BB1019001F039FF019803A901F0C9 +:1018E00027FF024648B1039B2946204600F098F89E +:1018F000002383F3118805B0F0BDFB685A691268B4 +:10190000002AF5D01B8A013B1340F1D104F180027B +:10191000EAE70000133138B550F82140ECB120233C +:1019200083F3118804F58053D3F8A42813685279FF +:1019300003EB8203DB689B695D6845B10421601895 +:10194000FFF768FE294604F1140001F027FE204647 +:10195000FFF7B4FE002383F3118838BD7047000001 +:1019600001F01AB901234022002110B5044600F805 +:10197000303BFFF775FA0023C4E9013310BD0000C6 +:1019800010B52023044683F31188242241600021EE +:101990000C30FFF765FA204601F020F9022323708E +:1019A000002383F3118810BD70B500EB8103054659 +:1019B00050690E461446DA6018B110220021FFF774 +:1019C0004FFAA06918B110220021FFF749FA3146F9 +:1019D0002846BDE8704001F013BA00008368202259 +:1019E000002103F0011310B5044683601030FFF7A7 +:1019F00037FA2046BDE8104001F08EBAF0B4012558 +:101A000000EB810447898D40E4683D43A46945812A +:101A100023600023A2606360F0BC01F0ABBA000059 +:101A2000F0B4012500EB810407898D40E4683D4353 +:101A30006469058123600023A2606360F0BC01F04B +:101A400021BB000070B50223002504462422037048 +:101A50002946C0F888500C3040F8045CFFF700FAC3 +:101A6000204684F8705001F05FF963681B6823B169 +:101A700029462046BDE87040184770BD037880F8BD +:101A80008C300523037043681B6810B504460BB106 +:101A9000042198470023A36010BD000090F88C201B +:101AA000436802701B680BB105211847704700009E +:101AB00070B590F87030044613B1002380F8703090 +:101AC00004F18002204601F04BFA63689B68B3B9C9 +:101AD00094F8803013F0600535D00021204601F0E5 +:101AE000F5FC0021204601F0E5FC63681B6813B19A +:101AF000062120469847062384F8703070BD2046A2 +:101B000098470028E4D0B4F88630A26F9A4288BF84 +:101B1000A36794F98030A56F002B4FF0200380F26B +:101B20000381002D00F0F280092284F8702083F3F5 +:101B3000118800212046D4E91D23FFF771FF0023FF +:101B400083F31188DAE794F8812003F07F0343EAF6 +:101B5000022340F20232934200F0C58021D8B3F54F +:101B6000807F48D00DD8012B3FD0022B00F093800E +:101B7000002BB2D104F1880262670222A267E367F8 +:101B8000C1E7B3F5817F00F09B80B3F5407FA4D11E +:101B900094F88230012BA0D1B4F8883043F00203CE +:101BA00032E0B3F5006F4DD017D8B3F5A06F31D048 +:101BB000A3F5C063012B90D86368204694F8822077 +:101BC0005E6894F88310B4F88430B047002884D05D +:101BD000436863670368A3671AE0B3F5106F36D0F4 +:101BE00040F6024293427FF478AF5C4B6367022376 +:101BF000A3670023C3E794F88230012B7FF46DAF15 +:101C0000B4F8883023F00203A4F88830C4E91D55E5 +:101C1000E56778E7B4F88030B3F5A06F0ED194F89B +:101C20008230204684F88A3001F0DCF863681B6853 +:101C300013B1012120469847032323700023C4E9F0 +:101C40001D339CE704F18B0363670123C3E723780B +:101C5000042B10D1202383F311882046FFF7BEFE0A +:101C600085F311880321636884F88B5021701B6809 +:101C70000BB12046984794F88230002BDED084F8D0 +:101C80008B300423237063681B68002BD6D002219D +:101C900020469847D2E794F8843020461D0603F08A +:101CA0000F010AD501F04EF9012804D002287FF473 +:101CB00014AF2B4B9AE72B4B98E701F035F9F3E77C +:101CC00094F88230002B7FF408AF94F8843013F03E +:101CD0000F01B3D01A06204602D501F00FFCADE784 +:101CE00001F000FCAAE794F88230002B7FF4F5AEF7 +:101CF00094F8843013F00F01A0D01B06204602D5C3 +:101D000001F0E4FB9AE701F0D5FB97E7142284F891 +:101D1000702083F311882B462A4629462046FFF778 +:101D20006DFE85F31188E9E65DB1152284F8702017 +:101D300083F3118800212046D4E91D23FFF75EFEBE +:101D4000FDE60B2284F8702083F311882B462A4687 +:101D500029462046FFF764FEE3E700BFF040000895 +:101D6000E8400008EC40000838B590F870300446B0 +:101D7000002B3ED0063BDAB20F2A34D80F2B32D8D4 +:101D8000DFE803F03731310822323131313131317E +:101D900031313737856FB0F886309D4214D2C36831 +:101DA0001B8AB5FBF3F203FB12556DB9202383F3B5 +:101DB00011882B462A462946FFF732FE85F3118803 +:101DC0000A2384F870300EE0142384F87030202346 +:101DD00083F31188002320461A461946FFF70EFEAA +:101DE000002383F3118838BDC36F03B198470023E4 +:101DF000E7E70021204601F069FB0021204601F0C1 +:101E000059FB63681B6813B10621204698470623D7 +:101E1000D7E7000010B590F870300446142B29D095 +:101E200017D8062B05D001D81BB110BD093B022BDA +:101E3000FBD80021204601F049FB0021204601F09B +:101E400039FB63681B6813B10621204698470623B7 +:101E500019E0152BE9D10B2380F87030202383F390 +:101E6000118800231A461946FFF7DAFD002383F391 +:101E70001188DAE7C3689B695B68002BD5D1C36F13 +:101E800003B19847002384F87030CEE7024B00225C +:101E9000C3E900339A607047382800200023826825 +:101EA0000374054B1B6899689142FBD25A68036022 +:101EB00042601060586070473828002008B5202321 +:101EC00083F31188037C032B05D0042B0DD02BB991 +:101ED00083F3118808BD436900221A604FF0FF3375 +:101EE0004361FFF7DBFF0023F2E7D0E90032136024 +:101EF0005A60F3E7002382680374054B1B689968F6 +:101F00009142FBD85A680360426010605860704785 +:101F100038280020054B1969087418680268536056 +:101F20001A60186101230374FEF750BA38280020A4 +:101F30004B1C30B5044687B00A4D10D02B6901A860 +:101F4000094A00F025F92046FFF7E4FF049B13B18E +:101F500001A800F059F92B69586907B030BDFFF7A7 +:101F6000D9FFF8E738280020BD1E000838B50C4D11 +:101F7000044641612B6981689A68914203D8BDE8A3 +:101F80003840FFF78BBF1846FFF7B4FF01232C61E1 +:101F9000014623742046BDE83840FEF717BA00BF5B +:101FA00038280020044B1A681B6990689B68984287 +:101FB00094BF0020012070473828002010B5084C3D +:101FC000236820691A6854602260012223611A7410 +:101FD000FFF790FF01462069BDE81040FEF7F6B913 +:101FE0003828002008B5FFF7DDFF18B1BDE808402C +:101FF000FFF7E4BF08BD0000FFF7E0BFFEE7000009 +:1020000010B50C4CFFF742FF00F0B4F880220A49EB +:10201000204600F03BF8012344F8180C037400F04C +:1020200099FC002383F3118862B60448BDE8104090 +:1020300000F04CB860280020F4400008044100087B +:1020400000F01CB9EFF3118020B9EFF305832022D3 +:1020500082F311887047000010B530B9EFF30584A2 +:10206000C4F3080414B180F3118810BDFFF7BAFF60 +:1020700084F31188F9E70000034A516853685B1A3A +:102080009842FBD8704700BF001000E08260022237 +:10209000028270478368A3F17C0243F80C2C02692A +:1020A00043F83C2C426943F8382C074A43F81C2C6F +:1020B000C268A3F1180043F8102C022203F8082C80 +:1020C000002203F8072C7047E503000810B5202311 +:1020D00083F31188FFF7DEFF00210446FFF746FF78 +:1020E000002383F31188204610BD0000024B1B69BA +:1020F00058610F20FFF70EBF38280020202383F3FC +:102100001188FFF7F3BF000008B50146202383F3D1 +:1021100011880820FFF70CFF002383F3118808BD06 +:1021200049B1064B42681B6918605A6013604360EE +:102130000420FFF7FDBE4FF0FF3070473828002025 +:102140000368984206D01A680260506018465961C8 +:10215000FFF7A4BE7047000038B504460D4620685E +:10216000844200D138BD036823605C604561FFF79D +:1021700095FEF4E7054B4FF0FF3103F11402C3E97C +:1021800005220022C3E90712704700BF382800204B +:1021900070B51C4E05460C46C0E9032301F0B2FBA6 +:1021A000334653F8142F9A420DD130620A2C2CBFBB +:1021B00000190A302A60C5E90124C6E90555BDE8C1 +:1021C000704001F089BB316A431AE31838BF1C46DE +:1021D0009368A34202D9081901F08EFB73699A68CB +:1021E00094420CD85A68AC602B606A6015609A689B +:1021F0005D60121B9A604FF0FF33F36170BDA41A4B +:102200001B68ECE73828002038B51B4C63699842FE +:102210000DD08168D0E9003213605A600022C2609C +:102220009A680A449A604FF0FF33E36138BD03684F +:102230002246002142F8143F93425A60C16003D104 +:10224000BDE8384001F052BB9A688168256A0A44AB +:102250009A6001F057FB6369411B9A688A42E5D98D +:10226000AB181D1A206A092D98BF01F10A02BDE8BA +:102270003840104401F040BB382800202DE9F041DF +:10228000184C002704F11406656901F03BFB236A32 +:10229000AA68C11A8A4215D81344D5F80C80236263 +:1022A000D5E9003213605A606369EF60B34201D12F +:1022B00001F01CFB87F311882869C047202383F3B2 +:1022C0001188E1E76169B14209D013441B1ABDE8E6 +:1022D000F0410A2B2CBFC0180A3001F00DBBBDE83D +:1022E000F08100BF3828002000207047FEE7000082 +:1022F000704700004FF0FF307047000002290CD0FB +:10230000032904D00129074818BF00207047032A79 +:1023100005D8054800EBC20070470448704700200C +:10232000704700BFE84100083C2200209C410008A3 +:1023300070B59AB005460846144601A900F0C2F8E7 +:1023400001A8FEF785FD431C0022C6B25B001046C3 +:10235000C5E9003423700323023404F8013C01ABC7 +:10236000D1B202348E4201D81AB070BD13F8011BED +:10237000013204F8010C04F8021CF1E708B520232F +:1023800083F311880348FFF767FA002383F311886A +:1023900008BD00BFF029002090F8803003F01F0234 +:1023A000012A07D190F881200B2A03D10023C0E92C +:1023B0001D3315E003F06003202B08D1B0F8843002 +:1023C0002BB990F88120212A03D81F2A04D8FFF7BF +:1023D00025BA222AEBD0FAE7034A4267072282672E +:1023E000C3670120704700BF3322002007B50529CD +:1023F00017D8DFE801F0191603191920202383F3F9 +:102400001188104A01210190FFF7CEFA01980221AC +:102410000D4AFFF7C9FA0D48FFF7EAF9002383F3E5 +:10242000118803B05DF804FB202383F3118807486B +:10243000FFF7B4F9F2E7202383F311880348FFF78D +:10244000CBF9EBE73C41000860410008F02900208F +:1024500038B50C4D0C4C2A460C4904F10800FFF726 +:1024600067FF05F1CA0204F110000949FFF760FF98 +:1024700005F5CA7204F118000649BDE83840FFF7B7 +:1024800057BF00BFC84200203C2200201C4100086A +:10249000264100083141000870B5044608460D4643 +:1024A000FEF7D6FCC6B22046013403780BB91846B5 +:1024B00070BD32462946FEF7B7FC0028F3D1012053 +:1024C000F6E700002DE9F84F05460C46FEF7C0FC84 +:1024D0002C49C6B22846FFF7DFFF08B10236F6B234 +:1024E00029492846FFF7D8FF08B11036F6B2632E07 +:1024F0000DD8DFF89080DFF89090244FDFF894A09B +:10250000DFF894B02E7846B92670BDE8F88F2946DA +:102510002046BDE8F84F01F099BD252E2ED10722A7 +:1025200041462846FEF780FC70B9DBF800300735DD +:10253000093444F8093CDBF8043044F8053C9BF8C6 +:10254000083004F8013CDDE7082249462846FEF73A +:102550006BFC98B9A21C0E4B197802320909C95DAF +:1025600002F8041C13F8011B01F00F015345C95D6B +:1025700002F8031CF0D118340835C3E7013504F81C +:10258000016BBFE708420008314100081A42000809 +:1025900000E8F11F0CE8F11F10420008BFF34F8F55 +:1025A000044B1A695107FCD1D3F810215207F8D116 +:1025B000704700BF0020005208B50D4B1B78ABB927 +:1025C000FFF7ECFF0B4BDA68D10704D50A4A5A60D3 +:1025D00002F188325A60D3F80C21D20706D5064A98 +:1025E000C3F8042102F18832C3F8042108BD00BFFA +:1025F00026450020002000522301674508B5114BF5 +:102600001B78F3B9104B1A69510703D5DA6842F009 +:102610004002DA60D3F81021520705D5D3F80C2117 +:1026200042F04002C3F80C21FFF7B8FF064BDA680E +:1026300042F00102DA60D3F80C2142F00102C3F843 +:102640000C2108BD26450020002000520F289ABF0B +:1026500000F5806040040020704700004FF4003017 +:1026600070470000102070470F2808B50BD8FFF7FF +:10267000EDFF00F500330268013204D104308342DB +:10268000F9D1012008BD0020FCE700000F2870B53B +:10269000054645D8FFF7D6FC224CFFF77FFF0646DC +:1026A000FFF78AFF4FF0FF33072D6361C4F8143141 +:1026B00020D82361FFF772FF2B0243F02403E3606D +:1026C000E36843F08003E36023695A07FCD428469B +:1026D000FFF764FF4FF40031FFF7B8FF00F002F995 +:1026E0003046FFF78BFFFFF7B7FC2846BDE8704088 +:1026F000FFF7BABFC4F81031FFF750FFA5F1080388 +:102700001B0243F02403C4F80C31D4F80C3143F01D +:102710008003C4F80C31D4F810315B07FBD4D6E742 +:10272000002070BD002000522DE9F84F40EA02035E +:1027300005460C461746D80602D00020BDE8F88FA3 +:1027400027F01F07DFF8D4B0FFF736FF2744BC425D +:1027500003D10120FFF752FFF0E72022294620464F +:1027600001F064FC10B920352034F0E72B4605F168 +:1027700020021E68711CE0D104339A42F9D1FFF7A0 +:1027800061FC05F17843234AB3F5801F224B28BF33 +:102790009A4603F1040338BF9046A2F1080228BF0D +:1027A0009846A3F108033ABF9146DA469946FFF7E7 +:1027B000F5FEC8F80060A5EB040CD9F8002004F180 +:1027C0001C0142F00202C9F80020221FDAF8006062 +:1027D00016F00506FAD152F8043F8A424CF802304E +:1027E000F4D1BFF34F8FFFF7D9FE4FF0FF32C8F897 +:1027F0000020D9F8002022F00202C9F80020FFF7DB +:102800002BFC20222146284601F010FC0028AAD0EB +:1028100030469FE714200052102100521020005231 +:1028200010B5084C237828B11BB9FFF7C5FE01236A +:10283000237010BD002BFCD02070BDE81040FFF7C6 +:10284000DDBE00BF264500200244074BD2B210B5C2 +:10285000904200D110BD441C00B253F8200041F852 +:10286000040BE0B2F4E700BF504000580E4B30B507 +:102870001C6F240405D41C6F1C671C6F44F40044B7 +:102880001C670A4C02442368D2B243F4807323606D +:10289000074B904200D130BD441C51F8045B00B29C +:1028A00043F82050E0B2F4E70044025800480258D0 +:1028B0005040005807B5012201A90020FFF7C4FFCE +:1028C000019803B05DF804FB13B50446FFF7F2FF6F +:1028D000A04205D0012201A900200194FFF7C6FF04 +:1028E00002B010BD0144BFF34F8F064B884204D3A2 +:1028F000BFF34F8FBFF36F8F7047C3F85C02203078 +:10290000F4E700BF00ED00E0034B1A681AB9034A70 +:10291000D2F8D0241A6070472845002000400258A1 +:1029200008B5FFF7F1FF024B1868C0F3806008BDDF +:1029300028450020EFF30983054968334A6B22F0EC +:1029400001024A6383F30988002383F311887047E7 +:1029500000EF00E0202080F3118862B60D4B0E4A94 +:10296000D96821F4E0610904090C0A430B49DA60D3 +:10297000D3F8FC2042F08072C3F8FC20084AC2F869 +:10298000B01F116841F0010111601022DA7783F85D +:102990002200704700ED00E00003FA0555CEACC5FB +:1029A000001000E0202310B583F311880E4B5B6804 +:1029B00013F4006314D0F1EE103AEFF309844FF0F2 +:1029C0008073683CE361094BDB6B236684F3098801 +:1029D000FFF7E8FA10B1064BA36110BD054BFBE70A +:1029E00083F31188F9E700BF00ED00E000EF00E09D +:1029F000F7030008FA03000870B5BFF34F8FBFF369 +:102A00006F8F1A4A0021C2F85012BFF34F8FBFF3E5 +:102A10006F8F536943F400335361BFF34F8FBFF39C +:102A20006F8FC2F88410BFF34F8FD2F8803043F617 +:102A3000E074C3F3C900C3F34E335B0103EA040639 +:102A4000014646EA81750139C2F86052F9D2203B4D +:102A500013F1200FF2D1BFF34F8F536943F480334A +:102A60005361BFF34F8FBFF36F8F70BD00ED00E078 +:102A7000FEE700000A4B0B480B4A90420BD30B4B6E +:102A8000C11EDA1C121A22F003028B4238BF002248 +:102A90000021FEF7E5B953F8041B40F8041BECE7EE +:102AA000FC430008FC460020FC460020FC460020B9 +:102AB0007047000070B5D0E9244300224FF0FF3585 +:102AC0009E6804EB42135101D3F80009002805DA8F +:102AD000D3F8000940F08040C3F80009D3F8000B98 +:102AE000002805DAD3F8000B40F08040C3F8000B53 +:102AF000013263189642C3F80859C3F8085BE0D264 +:102B00004FF00113C4F81C3870BD000000EB8103C6 +:102B1000D3F80CC02DE9F043DCF814204E1CD0F89B +:102B20009050D2F800E005EB063605EB41185068EE +:102B300070450AD30122D5F8343802FA01F123EAAC +:102B40000101C5F83418BDE8F083AEEB0003BCF812 +:102B50001040A34228BF2346D8F81849A4B2B3EBCB +:102B6000840FF0D89468A4F1040959F8047F376001 +:102B7000A4EB09071F44042FF7D81C4403449460B6 +:102B80005360D4E7890141F02001016103699B068C +:102B9000FCD41220FFF770BA10B50A4C2046FEF79D +:102BA000E1FE094BC4F89030084BC4F89430084C4F +:102BB0002046FEF7D7FE074BC4F89030064BC4F80A +:102BC000943010BD2C450020000008405042000801 +:102BD000C8450020000004405C42000870B503783E +:102BE0000546012B5DD1494BD0F89040984259D110 +:102BF000474B0E216520D3F8D82042F00062C3F87D +:102C0000D820D3F8002142F00062C3F80021D3F8A5 +:102C10000021D3F8802042F00062C3F88020D3F86E +:102C2000802022F00062C3F88020D3F8803000F0CA +:102C300071FC384BE360384BC4F800380023D5F8FA +:102C40009060C4F8003EC02323604FF40413A363D4 +:102C50003369002BFCDA01230C203361FFF70CFAF7 +:102C60003369DB07FCD41220FFF706FA3369002B27 +:102C7000FCDA00262846A660FFF71CFF6B68C4F844 +:102C80001068DB68C4F81468C4F81C68002B3AD1DB +:102C9000224BA3614FF0FF336361A36843F001034C +:102CA000A36070BD1E4B9842C8D1194B0E214D2018 +:102CB000D3F8D82042F00072C3F8D820D3F800210E +:102CC00042F00072C3F80021D3F80021D3F880202D +:102CD00042F00072C3F88020D3F8802022F0007206 +:102CE000C3F88020D3F88020D3F8D82022F0806267 +:102CF000C3F8D820D3F8002122F08062C3F8002165 +:102D0000D3F8003193E7074BC3E700BF2C45002001 +:102D1000004402584014004003002002003C30C030 +:102D2000C8450020083C30C0F8B5D0F890400546B2 +:102D300000214FF000662046FFF724FFD5F89410DD +:102D400000234FF001128F684FF0FF30C4F8343881 +:102D5000C4F81C2804EB431201339F42C2F80069F7 +:102D6000C2F8006BC2F80809C2F8080BF2D20B686F +:102D7000D5F89020C5F89830636210231361166966 +:102D800016F01006FBD11220FFF776F9D4F80038C0 +:102D900023F4FE63C4F80038A36943F4402343F0EE +:102DA0001003A3610923C4F81038C4F814380B4B7E +:102DB000EB604FF0C043C4F8103B094BC4F8003B34 +:102DC000C4F81069C4F80039D5F8983003F110023E +:102DD00043F48013C5F89820A362F8BD2C42000884 +:102DE00040800010D0F8902090F88A10D2F8003877 +:102DF00023F4FE6343EA0113C2F800387047000071 +:102E00002DE9F84300EB8103D0F890500C46804642 +:102E1000DA680FFA81F94801166806F00306731E96 +:102E2000022B05EB41134FF0000194BFB604384E5E +:102E3000C3F8101B4FF0010104F1100398BF06F115 +:102E4000805601FA03F3916998BF06F50046002900 +:102E50003AD0578A04F15801374349016F50D5F8E9 +:102E60001C180B430021C5F81C382B180127C3F888 +:102E70001019A7405369611E9BB3138A928B9B085C +:102E8000012A88BF5343D8F89820981842EA034390 +:102E900001F140022146C8F89800284605EB82025D +:102EA0005360FFF76FFE08EB8900C3681B8A43EA93 +:102EB000845348341E4364012E51D5F81C381F43F7 +:102EC000C5F81C78BDE8F88305EB4917D7F8001B57 +:102ED00021F40041C7F8001BD5F81C1821EA0303B0 +:102EE000C0E704F13F030B4A2846214605EB830364 +:102EF0005A60FFF747FE05EB4910D0F8003923F47C +:102F00000043C0F80039D5F81C3823EA0707D7E793 +:102F10000080001000040002D0F894201268C0F86D +:102F20009820FFF7C7BD00005831D0F89030490114 +:102F30005B5813F4004004D013F4001F0CBF0220B0 +:102F4000012070474831D0F8903049015B5813F4A4 +:102F5000004004D013F4001F0CBF02200120704772 +:102F600000EB8101CB68196A0B6813604B685360F2 +:102F70007047000000EB810330B5DD68AA69136873 +:102F8000D36019B9402B84BF402313606B8A146847 +:102F9000D0F890201C4402EB4110013C09B2B4FB74 +:102FA000F3F46343033323F0030343EAC44343F0DE +:102FB000C043C0F8103B2B6803F00303012B0ED174 +:102FC000D2F8083802EB411013F4807FD0F8003BB0 +:102FD00014BF43F0805343F00053C0F8003B02EBB2 +:102FE0004112D2F8003B43F00443C2F8003B30BD2D +:102FF0002DE9F041D0F8906005460C4606EB4113F0 +:10300000D3F8087B3A07C3F8087B08D5D6F81438FC +:103010001B0704D500EB8103DB685B689847FA0760 +:103020001FD5D6F81438DB071BD505EB8403D96808 +:10303000CCB98B69488A5A68B2FBF0F600FB1622BD +:103040008AB91868DA6890420DD2121AC3E90024CE +:10305000202383F3118821462846FFF78BFF84F352 +:103060001188BDE8F081012303FA04F26B8923EA99 +:1030700002036B81CB68002BF3D021462846BDE8C4 +:10308000F041184700EB81034A0170B5DD68D0F8C4 +:1030900090306C692668E66056BB1A444FF40020F5 +:1030A000C2F810092A6802F00302012A0AB20ED1FE +:1030B000D3F8080803EB421410F4807FD4F8000919 +:1030C00014BF40F0805040F00050C4F8000903EBFA +:1030D0004212D2F8000940F00440C2F8000901226F +:1030E000D3F8340802FA01F10143C3F8341870BD73 +:1030F00019B9402E84BF4020206020681A442E8ACF +:103100008419013CB4FBF6F440EAC44040F000509E +:10311000C6E700002DE9F041D0F8906004460D4666 +:1031200006EB4113D3F80879C3F80879FB071CD5DF +:10313000D6F81038DA0718D500EB8103D3F80CC0A5 +:10314000DCF81430D3F800E0DA6896451BD2A2EB25 +:103150000E024FF000081A60C3F80480202383F3A6 +:103160001188FFF78FFF88F311883B0618D50123DC +:10317000D6F83428AB40134212D029462046BDE889 +:10318000F041FFF7C3BC012303FA01F2038923EAEC +:1031900002030381DCF80830002BE6D09847E4E70F +:1031A000BDE8F0812DE9F84FD0F8905004466E69E3 +:1031B000AB691E4016F480586E6103D0BDE8F84F2D +:1031C000FEF740BC002E12DAD5F8003E9F0705D06E +:1031D000D5F8003E23F00303C5F8003ED5F80438C7 +:1031E000204623F00103C5F80438FEF757FC3005EC +:1031F00005D52046FFF75EFC2046FEF73FFCB104F4 +:103200000CD5D5F8083813F0060FEB6823F470538B +:103210000CBF43F4105343F4A053EB60320704D5C2 +:103220006368DB680BB120469847F30200F1BA806F +:10323000B70226D5D4F8909000274FF0010A09EB89 +:103240004712D2F8003B03F44023B3F5802F11D18D +:10325000D2F8003B002B0DDA62890AFA07F322EA62 +:103260000303638104EB8703DB68DB6813B1394632 +:10327000204698470137D4F89430FFB29B689F42AC +:10328000DDD9F00619D5D4F89000026AC2F30A1706 +:1032900002F00F0302F4F012B2F5802F00F0CC80A0 +:1032A000B2F5402F09D104EB8303002200F58050D2 +:1032B000DB681B6A974240F0B2803003D5F818589B +:1032C00035D5E90303D500212046FFF791FEAA0377 +:1032D00003D501212046FFF78BFE6B0303D50221A6 +:1032E0002046FFF785FE2F0303D503212046FFF775 +:1032F0007FFEE80203D504212046FFF779FEA902EC +:1033000003D505212046FFF773FE6A0203D5062187 +:103310002046FFF76DFE2B0203D507212046FFF75D +:1033200067FEEF0103D508212046FFF761FE700319 +:1033300040F1A980E90703D500212046FFF7EAFE06 +:10334000AA0703D501212046FFF7E4FE6B0703D54A +:1033500002212046FFF7DEFE2F0703D5032120467A +:10336000FFF7D8FEEE0603D504212046FFF7D2FE74 +:10337000A80603D505212046FFF7CCFE690603D534 +:1033800006212046FFF7C6FE2A0603D50721204660 +:10339000FFF7C0FEEB0576D520460821BDE8F84FC3 +:1033A000FFF7B8BED4F8909000274FF0010AD4F888 +:1033B00094305FFA87FB9B689B453FF639AF09EB7A +:1033C0004B13D3F8002902F44022B2F5802F24D108 +:1033D000D3F80029002A20DAD3F8002942F09042DD +:1033E000C3F80029D3F80029002AFBDB5946D4F89A +:1033F0009000FFF7C7FB22890AFA0BF322EA0303C6 +:10340000238104EB8B03DB689B6813B1594620468C +:10341000984759462046FFF779FB0137C7E79107E0 +:1034200001D1D0F80080072A02F101029CBF03F805 +:10343000018B4FEA18283DE704EB830300F5805029 +:10344000DA68D2F818C0DCF80820DCE9001CA1EB2F +:103450000C0C00218F4208D1DB689B699A683A44C2 +:103460009A605A683A445A6027E711F0030F01D175 +:10347000D0F800808C4501F1010184BF02F8018B76 +:103480004FEA1828E6E7BDE8F88F000008B50348C2 +:10349000FFF788FEBDE80840FFF784BA2C450020FE +:1034A00008B50348FFF77EFEBDE80840FFF77ABA8B +:1034B000C8450020D0F8903003EB4111D1F8003B13 +:1034C00043F40013C1F8003B70470000D0F890307F +:1034D00003EB4111D1F8003943F40013C1F800396E +:1034E00070470000D0F8903003EB4111D1F8003B59 +:1034F00023F40013C1F8003B70470000D0F890306F +:1035000003EB4111D1F8003923F40013C1F800395D +:1035100070470000090100F16043012203F5614397 +:10352000C9B283F8001300F01F039A4043099B00BF +:1035300003F1604303F56143C3F880211A607047CB +:1035400030B50433039C0172002104FB0325C160E4 +:10355000C0E90653049B0363059BC0E90000C0E972 +:103560000422C0E90842C0E90A11436330BD0000EB +:103570000022416AC260C0E90411C0E90A226FF06A +:103580000101FEF7E9BD0000D0E90432934201D108 +:10359000C2680AB9181D7047002070470369196096 +:1035A0000021C2680132C260C26913448269934239 +:1035B000036124BF436A0361FEF7C2BD38B5044608 +:1035C0000D46E3683BB162690020131D1268A362D7 +:1035D0001344E36207E0237A33B929462046FEF715 +:1035E0009FFD0028EDDA38BD6FF00100FBE7000019 +:1035F000C368C269013BC360436913448269934253 +:10360000436124BF436A436100238362036B03B1B8 +:103610001847704770B52023044683F31188866AE3 +:103620003EB9FFF7CBFF054618B186F3118828464F +:1036300070BDA36AE26A13F8015B9342A36202D3EE +:103640002046FFF7D5FF002383F31188EFE7000042 +:103650002DE9F84F04460E46174698464FF02009CC +:1036600089F311880025AA46D4F828B0BBF1000FD1 +:1036700009D141462046FFF7A1FF20B18BF3118805 +:103680002846BDE8F88FD4E90A12A7EB050B521AB9 +:10369000934528BF9346BBF1400F1BD9334601F138 +:1036A000400251F8040B914243F8040BF9D1A36A8C +:1036B000403640354033A362D4E90A239A4202D30C +:1036C0002046FFF795FF8AF31188BD42D8D289F3CF +:1036D0001188C9E730465A46FDF79CFBA36A5E4451 +:1036E0005D445B44A362E7E710B5029C04330172BA +:1036F00004FB0321C460C0E906130023C0E90A33B8 +:10370000039B0363049BC0E90000C0E90422C0E9F5 +:103710000842436310BD0000026A6FF00101C260FD +:10372000426AC0E904220022C0E90A22FEF714BD61 +:10373000D0E904239A4201D1C26822B9184650F850 +:10374000043B0B607047002070470000C3680021F5 +:10375000C2690133C3604369134482699342436180 +:1037600024BF436A4361FEF7EBBC000038B5044652 +:103770000D46E3683BB1236900201A1DA262E2698D +:103780001344E36207E0237A33B929462046FEF763 +:10379000C7FC0028EDDA38BD6FF00100FBE7000040 +:1037A00003691960C268013AC260C2691344826940 +:1037B0009342036124BF436A036100238362036B66 +:1037C00003B118477047000070B520230D4604462A +:1037D000114683F31188866A2EB9FFF7C7FF10B12F +:1037E00086F3118870BDA36A1D70A36AE26A013373 +:1037F0009342A36204D3E16920460439FFF7D0FF66 +:10380000002080F31188EDE72DE9F84F04460D46BE +:10381000904699464FF0200A8AF311880026B34655 +:10382000A76A4FB949462046FFF7A0FF20B187F3AA +:1038300011883046BDE8F88FD4E90A073A1AA8EB98 +:103840000607974228BF1746402F1BD905F14003B2 +:1038500055F8042B9D4240F8042BF9D1A36A403659 +:103860004033A362D4E90A239A4204D3E169204693 +:103870000439FFF795FF8BF311884645D9D28AF3B7 +:103880001188CDE729463A46FDF7C4FAA36A3D44BC +:103890003E443B44A362E5E7D0E904239A4217D1B2 +:1038A000C3689BB1836A8BB1043B9B1A0ED0136033 +:1038B000C368013BC360C3691A4483699A420261C9 +:1038C00024BF436A036100238362012318467047C3 +:1038D0000023FBE700F0DAB8034B002258631A61BB +:1038E0000222DA60704700BF000C0040014B00224A +:1038F000DA607047000C0040014B5863704700BF0E +:10390000000C0040014B586A704700BF000C00409B +:103910004B6843608B688360CB68C3600B6943610D +:103920004B6903628B6943620B6803607047000058 +:1039300008B53C4B40F2FF713B48D3F888200A435E +:10394000C3F88820D3F8882022F4FF6222F007020F +:10395000C3F88820D3F88820D3F8E0200A43C3F8BE +:10396000E020D3F808210A43C3F808212F4AD3F8EE +:1039700008311146FFF7CCFF00F5806002F11C0111 +:10398000FFF7C6FF00F5806002F13801FFF7C0FFC6 +:1039900000F5806002F15401FFF7BAFF00F5806086 +:1039A00002F17001FFF7B4FF00F5806002F18C01B5 +:1039B000FFF7AEFF00F5806002F1A801FFF7A8FF56 +:1039C00000F5806002F1C401FFF7A2FF00F58060FE +:1039D00002F1E001FFF79CFF00F5806002F1FC01BD +:1039E000FFF796FF02F58C7100F58060FFF790FFFE +:1039F00000F000F90E4BD3F8902242F00102C3F818 +:103A00009022D3F8942242F00102C3F894220522B6 +:103A1000C3F898204FF06052C3F89C20054AC3F8C1 +:103A2000A02008BD00440258000002586842000867 +:103A300000ED00E01F00080308B500F0D7FAFEF71C +:103A4000DFFA0F4BD3F8DC2042F04002C3F8DC2051 +:103A5000D3F8042122F04002C3F80421D3F8043142 +:103A6000084B1A6842F008021A601A6842F0040211 +:103A70001A60FEF749FFBDE80840FEF7E9BC00BF49 +:103A8000004402580018024870470000114BD3F858 +:103A9000E82042F00802C3F8E820D3F8102142F0F1 +:103AA0000802C3F810210C4AD3F81031D36B43F04D +:103AB0000803D363C722094B9A624FF0FF32DA62E0 +:103AC00000229A615A63DA605A6001225A611A60D0 +:103AD000704700BF004402580010005C000C00401A +:103AE000094A08B51169D3680B40D9B29B076FEA40 +:103AF0000101116107D5202383F31188FEF7A0FA95 +:103B0000002383F3118808BD000C0040384B4FF0B0 +:103B1000FF31D3F88020C3F88010D3F88020002232 +:103B2000C3F88020D3F88000D3F88400C3F8841051 +:103B3000D3F88400C3F88420D3F88400D86F40F011 +:103B4000FF4040F4FF0040F43F5040F03F00D86792 +:103B5000D86F20F0FF4020F4FF0020F43F5020F009 +:103B60003F00D867D86FD3F888006FEA40506FEAFB +:103B70005050C3F88800D3F88800C0F30A00C3F897 +:103B80008800D3F88800D3F89000C3F89010D3F8D9 +:103B90009000C3F89020D3F89000D3F89400C3F8B5 +:103BA0009410D3F89400C3F89420D3F89400D3F879 +:103BB0009800C3F89810D3F89800C3F89820D3F869 +:103BC0009800D3F88C00C3F88C10D3F88C00C3F89D +:103BD0008C20D3F88C00D3F89C00C3F89C10D3F849 +:103BE0009C10C3F89C20D3F89C3000F0D3B900BFE0 +:103BF00000440258614B0122C3F80821604BD3F8FE +:103C0000F42042F00202C3F8F420D3F81C2142F061 +:103C10000202C3F81C210222D3F81C31594BDA608E +:103C20005A689104FCD5584A1A6001229A60574A92 +:103C3000DA6000221A614FF440429A61514B9A694E +:103C40009204FCD51A6842F480721A604C4B1A6FC9 +:103C500012F4407F04D04FF480321A6700221A67B2 +:103C60001A6842F001021A60454B1A685007FCD5E9 +:103C700000221A611A6912F03802FBD10121196081 +:103C80004FF0804159605A67414ADA62414A1A61ED +:103C90001A6842F480321A60394B1A689103FCD5D5 +:103CA0001A6842F480521A601A689204FCD53A4AA3 +:103CB0003A499A6200225A6319633949DA6399636F +:103CC0005A64384A1A64384ADA621A6842F0A852CA +:103CD0001A602B4B1A6802F02852B2F1285FF9D112 +:103CE00048229A614FF48862DA6140221A622F4AB0 +:103CF000DA644FF080521A652D4A5A652D4A9A654A +:103D000032232D4A1360136803F00F03022BFAD1FC +:103D10001B4B1A6942F003021A611A6902F0380259 +:103D2000182AFAD1D3F8DC2042F00052C3F8DC2084 +:103D3000D3F8042142F00052C3F80421D3F804213F +:103D4000D3F8DC2042F08042C3F8DC20D3F8042111 +:103D500042F08042C3F80421D3F80421D3F8DC20D8 +:103D600042F00042C3F8DC20D3F8042142F00042C4 +:103D7000C3F80421D3F80431704700BF008000511C +:103D8000004402580048025800C000F00200000140 +:103D90000000FF0100889008121020006302090152 +:103DA0002C02040047040508FD0BFF012000002041 +:103DB0000010E00000010100002000524FF0B0426E +:103DC00008B5D2F8883003F00103C2F8883023B177 +:103DD000044A13680BB150689847BDE80840FEF7E5 +:103DE000E1BD00BF7C4600204FF0B04208B5D2F8DC +:103DF000883003F00203C2F8883023B1044A936884 +:103E00000BB1D0689847BDE80840FEF7CBBD00BFB6 +:103E10007C4600204FF0B04208B5D2F8883003F05D +:103E20000403C2F8883023B1044A13690BB1506906 +:103E30009847BDE80840FEF7B5BD00BF7C460020AE +:103E40004FF0B04208B5D2F8883003F00803C2F84A +:103E5000883023B1044A93690BB1D0699847BDE813 +:103E60000840FEF79FBD00BF7C4600204FF0B042E7 +:103E700008B5D2F8883003F01003C2F8883023B1B7 +:103E8000044A136A0BB1506A9847BDE80840FEF730 +:103E900089BD00BF7C4600204FF0B04310B5D3F879 +:103EA000884004F47872C3F88820A30604D5124A27 +:103EB000936A0BB1D06A9847600604D50E4A136B1B +:103EC0000BB1506B9847210604D50B4A936B0BB18D +:103ED000D06B9847E20504D5074A136C0BB1506CC0 +:103EE0009847A30504D5044A936C0BB1D06C98474E +:103EF000BDE81040FEF756BD7C4600204FF0B043B1 +:103F000010B5D3F8884004F47C42C3F888206205D9 +:103F100004D5164A136D0BB1506D9847230504D58F +:103F2000124A936D0BB1D06D9847E00404D50F4A47 +:103F3000136E0BB1506E9847A10404D50B4A936ED3 +:103F40000BB1D06E9847620404D5084A136F0BB1C9 +:103F5000506F9847230404D5044A936F0BB1D06F78 +:103F60009847BDE81040FEF71DBD00BF7C4600200D +:103F700008B50348FDF708F9BDE80840FEF712BD93 +:103F8000CC23002008B5FFF7ABFDBDE80840FEF7E5 +:103F900009BD0000062108B50846FFF7BBFA062157 +:103FA0000720FFF7B7FA06210820FFF7B3FA06212A +:103FB0000920FFF7AFFA06210A20FFF7ABFA062126 +:103FC0001720FFF7A7FA06212820FFF7A3FA0921F7 +:103FD0007A20FFF79FFA07213220FFF79BFA0C2186 +:103FE0005220BDE80840FFF795BA000008B5FFF77A +:103FF0008DFD00F00DF8FDF7D9FAFDF7B1FCFDF7E6 +:1040000083FBFFF741FDBDE80840FFF763BC0000FC +:104010000023054A19460133102BC2E9001102F1B1 +:104020000802F8D1704700BF7C46002010B5013966 +:104030000244904201D1002005E0037811F8014FBD +:10404000A34201D0181B10BD0130F2E7034611F85E +:10405000012B03F8012B002AF9D1704753544D333B +:104060003248373F3F3F0053544D333248373433A3 +:104070002F37353300000000F0290020CC2300202A +:10408000009600000000000000000000000000009A +:10409000000000000000000000000000751500088E +:1040A000611500089D150008891500089515000880 +:1040B000811500086D15000859150008A91500089C +:1040C000000000008516000871160008AD160008F3 +:1040D00099160008A5160008911600087D1600081C +:1040E00069160008B9160008000000000100000071 +:1040F000000000006D61696E0000000069646C657D +:1041000000000000FC40000878280020F029002072 +:1041100001000000FD1F00080000000041726475EE +:1041200050696C6F740025424F415244252D424C1A +:10413000002553455249414C250000000200000073 +:1041400000000000A51800081519000840004000F4 +:1041500098420020A8420020020000000000000059 +:1041600003000000000000005D19000800000000CE +:1041700010000000B8420020000000000100000014 +:10418000000000002C45002001010200ED23000882 +:10419000FD220008992300087D2300084300000049 +:1041A000A441000809024300020100C032090400D2 +:1041B0000001020201000524001001052401000194 +:1041C000042402020524060001070582030800FFFB +:1041D00009040100020A0000000705010240000076 +:1041E000070581024000000012000000F0410008B5 +:1041F00012011001020000400912415700020102A1 +:10420000030100000403090425424F4152442500E4 +:104210004D6174656B483734330030313233343597 +:10422000363738394142434445460000000000001B +:10423000B11A0008691D0008151E00084000400062 +:1042400064460020644600200100000074460020FF +:104250008000000040010000080000000001000094 +:1042600000040000080000000000802A0000000098 +:10427000AAAAAAAA00000024FFFF00000000000074 +:1042800000A00A000000000100000000AAAAAAAADB +:1042900000000001FFFF000000000000000000001F +:1042A0000000004400000000AAAAAAAA00000044DE +:1042B000FFFF0000000000000000000000011000EF +:1042C00000000000AAAAAAAA00010000FFFB00004B +:1042D00000000000000000005080420000000000CC +:1042E000AAAAAAAA10404100F7FF0000000000702F +:1042F000070000000000000000000000AAAAAAAA0F +:1043000000000000FFFF00000000000000000000AF +:104310000000000000000000AAAAAAAA00000000F5 +:10432000FFFF00000000000000000000000000008F +:1043300000000000AAAAAAAA00000000FFFF0000D7 +:10434000000000000000000000000000000000006D +:10435000AAAAAAAA00000000FFFF000000000000B7 +:10436000000000000000000000000000AAAAAAAAA5 +:1043700000000000FFFF000000000000000000003F +:104380000000000000000000AAAAAAAA0000000085 +:10439000FFFF00000000000000000000000000001F +:1043A000F50300000000000000001A0000000000FB +:1043B000FF000000000000005C4000083F0000001B +:1043C00050040000674000083F0000000096000015 +:1043D0000000080096000000000800000400000033 +:1043E000044200080000000000000000000000007F +:0C43F000000000000000000000000000C1 :00000001FF diff --git a/Tools/bootloaders/MatekL431-Airspeed_bl.bin b/Tools/bootloaders/MatekL431-Airspeed_bl.bin new file mode 100755 index 00000000000..2e150c5ae1f Binary files /dev/null and b/Tools/bootloaders/MatekL431-Airspeed_bl.bin differ diff --git a/Tools/bootloaders/MatekL431-Airspeed_bl.hex b/Tools/bootloaders/MatekL431-Airspeed_bl.hex new file mode 100644 index 00000000000..46fc143ca83 --- /dev/null +++ b/Tools/bootloaders/MatekL431-Airspeed_bl.hex @@ -0,0 +1,1335 @@ +:020000040800F2 +:1000000000090020B5040008E5290008652900085A +:10001000BD2900086529000891290008B7040008D7 +:10002000B7040008B7040008B7040008393800080E +:10003000B7040008B7040008B7040008B7040008B4 +:10004000B7040008B7040008B7040008B7040008A4 +:10005000B7040008B7040008714B0008994B00086A +:10006000C14B0008E94B0008114C0008B704000818 +:10007000B7040008B7040008B7040008B704000874 +:10008000B7040008B7040008B7040008A125000859 +:10009000CD250008DD250008B7040008394C00080C +:1000A000B7040008B7040008B7040008B704000844 +:1000B000494D0008B7040008B7040008B704000859 +:1000C000B7040008B7040008B7040008B704000824 +:1000D000B70400080D4D0008214D0008354D0008FB +:1000E0009D4C0008B7040008B7040008B7040008D6 +:1000F000B7040008B7040008B7040008B7040008F4 +:10010000B7040008B7040008B7040008B7040008E3 +:10011000B7040008B7040008B7040008B7040008D3 +:10012000B7040008B7040008B7040008B7040008C3 +:10013000B7040008B7040008B7040008B7040008B3 +:10014000B7040008B7040008B7040008B7040008A3 +:10015000B7040008B7040008B7040008B704000893 +:10016000B7040008B7040008B7040008B704000883 +:10017000B7040008B7040008B7040008B704000873 +:10018000B7040008B7040008B7040008B704000863 +:10019000B7040008B7040008B7040008B704000853 +:1001A000051800080000000000000000000000002A +:1001B00053B94AB9002908BF00281CBF4FF0FF31CE +:1001C0004FF0FF3000F074B9ADF1080C6DE904CECA +:1001D00000F006F8DDF804E0DDE9022304B0704722 +:1001E0002DE9F047089D04468E46002B4DD18A42EA +:1001F000944669D9B2FA82F252B101FA02F3C2F11D +:10020000200120FA01F10CFA02FC41EA030E9440AD +:100210004FEA1C48210CBEFBF8F61FFA8CF708FBCE +:1002200016E341EA034306FB07F199420AD91CEBA6 +:10023000030306F1FF3080F01F81994240F21C81D8 +:10024000023E63445B1AA4B2B3FBF8F008FB103320 +:1002500044EA034400FB07F7A7420AD91CEB040455 +:1002600000F1FF3380F00A81A74240F20781644425 +:10027000023840EA0640E41B00261DB1D4400023AA +:10028000C5E900433146BDE8F0878B4209D9002D0E +:1002900000F0EF800026C5E9000130463146BDE898 +:1002A000F087B3FA83F6002E4AD18B4202D3824202 +:1002B00000F2F980841A61EB030301209E46002DB1 +:1002C000E0D0C5E9004EDDE702B9FFDEB2FA82F206 +:1002D000002A40F09280A1EB0C014FEA1C471FFA64 +:1002E0008CFE0126200CB1FBF7F307FB131140EA4B +:1002F00001410EFB03F0884208D91CEB010103F118 +:10030000FF3802D2884200F2CB804346091AA4B2D9 +:10031000B1FBF7F007FB101144EA01440EFB00FEAD +:10032000A64508D91CEB040400F1FF3102D2A64512 +:1003300000F2BB800846A4EB0E0440EA03409CE7B1 +:10034000C6F12007B34022FA07FC4CEA030C20FA5E +:1003500007F401FA06F31C43F9404FEA1C4900FA7E +:1003600006F3B1FBF9F8200C1FFA8CFE09FB1811FB +:1003700040EA014108FB0EF0884202FA06F20BD96E +:100380001CEB010108F1FF3A80F08880884240F2BE +:100390008580A8F102086144091AA4B2B1FBF9F002 +:1003A00009FB101144EA014100FB0EFE8E4508D9FD +:1003B0001CEB010100F1FF346CD28E456AD9023882 +:1003C000614440EA0840A0FB0294A1EB0E01A14267 +:1003D000C846A64656D353D05DB1B3EB080261EBD5 +:1003E0000E0101FA07F722FA06F3F1401F43C5E9AF +:1003F000007100263146BDE8F087C2F12003D840E5 +:100400000CFA02FC21FA03F3914001434FEA1C4726 +:100410001FFA8CFEB3FBF7F007FB10360B0C43EA18 +:10042000064300FB0EF69E4204FA02F408D91CEBC8 +:10043000030300F1FF382FD29E422DD902386344C6 +:100440009B1B89B2B3FBF7F607FB163341EA034166 +:1004500006FB0EF38B4208D91CEB010106F1FF38B5 +:1004600016D28B4214D9023E6144C91A46EA0046AC +:1004700038E72E46284605E70646E3E61846F8E63E +:100480004B45A9D2B9EB020864EB0C0E0138A3E787 +:100490004646EAE7204694E74046D1E7D0467BE768 +:1004A000023B614432E7304609E76444023842E7E0 +:1004B000704700BF02E000F000F8FEE772B63A486D +:1004C00080F30888394880F3098839484EF6085186 +:1004D000CEF20001086040F20000CCF200004EF6BF +:1004E0003471CEF200010860BFF34F8FBFF36F8FFE +:1004F00040F20000C0F2F0004EF68851CEF200014A +:100500000860BFF34F8FBFF36F8F4FF00000E1EE35 +:10051000100A4EF63C71CEF200010860062080F30E +:100520001488BFF36F8F04F09DF904F079F904F09B +:10053000B3F94FF055301F491B4A91423CBF41F877 +:10054000040BFAE71C49194A91423CBF41F8040BDD +:10055000FAE71A491A4A1B4B9A423EBF51F8040B5C +:1005600042F8040BF8E700201749184A91423CBFB3 +:1005700041F8040BFAE704F057F904F0E5F9144CDC +:10058000144DAC4203DA54F8041B8847F9E700F035 +:1005900041F8114C114DAC4203DA54F8041B884762 +:1005A000F9E704F03FB90000000900200011002025 +:1005B000000000080001002000090020C0520008CF +:1005C000001100208C110020901100203C390020E7 +:1005D000A0010008A4010008A4010008A40100086B +:1005E0002DE9F04F2DED108AC1F80CD0C3689D465F +:1005F000BDEC108ABDE8F08F002383F311882846F4 +:10060000A047002003F004FEFEE703F07DFD00DFBD +:10061000FEE70000F8B504F0A5F8074604F0F6F888 +:100620000546A0BB1F4B9F4231D001339F4231D0C2 +:100630001D4B27F0FF029A422FD1F8B200F030FD97 +:100640002E4642F2107400F035FF08B10024264611 +:1006500000F02CFD08B90646044635B1134B9F4205 +:1006600003D004F0CBF800242646002004F084F8E0 +:100670000EB100F063F801F051FA00F03FFF01F015 +:100680003DF9204600F0A8F800F058F8F9E72E46AA +:100690000024D8E704460126D5E706464FF47A74CD +:1006A000D1E700BF010007B0000008B0263A09B04A +:1006B00008B501F0EFF8A0F120035842584108BDF9 +:1006C00007B541F21203022101A8ADF8043001F090 +:1006D000FFF803B05DF804FB10B5202383F3118805 +:1006E0001248C3680BB103F00BFE114A0F480023F8 +:1006F0004FF47A7103F0C8FD002383F311880D4C89 +:10070000236813B12368013B2360636813B16368F6 +:10071000013B6360084B1B7833B9636823B902203F +:1007200001F08AF93223636010BD00BF90110020F0 +:10073000D9060008AC120020A4110020214B224A47 +:1007400010B51C46196801313BD004339342F9D1EE +:100750006268A24235D31D4B9B6803F1006303F529 +:1007600020439A422DD204F01BF804F02DF800200B +:1007700001F0DEF8164B0220187001F055F9154B08 +:100780009A6D00229A65996F9A67996FD96DDA65AB +:10079000D96FDA67D96F196E1A66D3F88010C3F86B +:1007A0008020D3F8803072B64FF0E0232021C3F8C8 +:1007B000084DD4E9003281F311889D4683F30888FF +:1007C000104710BD00A0000820A000080011002064 +:1007D000A4110020001002402DE9F04F93B0AC4B63 +:1007E00000902022FF210AA89D6801F041F9A94A42 +:1007F0001378A3B9A8480121C3601170202383F3A3 +:100800001188C3680BB103F07BFDA44AA248002302 +:100810004FF47A7103F038FD002383F31188009BB5 +:100820009F4A03B113609F49009C00230B705360E3 +:1008300098469B461E469A46012001F0F5F824B1E1 +:10084000974B1B68002B00F01C82002001F022F85F +:100850000390039B002B01DA00F094FE039B002B16 +:10086000EDDB012001F0D6F8039B213B162BE3D8EA +:1008700001A252F823F000BFD5080008FD080008C7 +:1008800091090008390800083908000839080008EB +:10089000250A0008F70B0008110B0008730B00086D +:1008A0009B0B0008C10B000839080008D30B000897 +:1008B00039080008450C00087509000839080008C7 +:1008C000890C0008E10800087509000839080008CB +:1008D000730B00080220FFF7EBFE002840F0FB81BD +:1008E000009B0221B8F1000F08BF1C4605A841F289 +:1008F0001233ADF8143000F0EBFF9DE74FF47A703F +:1009000000F0C8FF071EEBDB0220FFF7D1FE002836 +:10091000E6D0013F052F00F2E081DFE807F0030A8F +:100920000D10133605230593042105A800F0D0FF10 +:1009300017E057480421F9E75B480421F6E75B48D4 +:100940000421F3E74FF01C09484600F0F3FF09F1DA +:1009500004090590042105A800F0BAFFB9F12C0F95 +:10096000F2D1012000FA07F747EA0B0B5FFA8BFB85 +:100970004FF0000A01F0C8F826B10BF00B030B2B67 +:1009800008BF0024FFF79CFE56E749480421CDE745 +:10099000002EA5D00BF00B030B2BA1D10220FFF7EB +:1009A00087FE074600289BD001203E4E00F0C0FF86 +:1009B0000220307001F038F84FF000085FFA88F933 +:1009C000484600F0C5FF044690B1484600F0D0FF0D +:1009D00008F101080028F1D1B846044641F212138B +:1009E000022105A8ADF814303E4600F071FF23E760 +:1009F00001230220337001F00DF82546244B9B683B +:100A0000AB4207D9284600F095FF013040F06881DD +:100A10000435F3E7234B00251D70214BB8465D607C +:100A20003E46A7E7002E3FF45BAF0BF00B030B2B0A +:100A30007FF456AF1B4B0220187000F0F5FF3220F8 +:100A400000F028FFB0F10009FFF64AAF19F00307E4 +:100A50007FF446AF0E4A926809EB050393423FF6D6 +:100A60003FAFB9F5807F3FF73BAF124B0193B945DC +:100A700022DD4FF47A7000F00DFF0390039A002AF4 +:100A8000FFF62EAF019B039A03F8012B0137EDE728 +:100A900000110020A812002090110020D9060008A3 +:100AA000AC120020A4110020041100200811002025 +:100AB0000C110020A8110020C820FFF7F9FD0746FF +:100AC00000283FF40DAF1F2D11D8C5F120024A4573 +:100AD0000AAB25F0030028BF4A4683490192184417 +:100AE00000F0B4FF019A8048FF2100F0C1FF4FEAF7 +:100AF000A9037D490193C9F38702284600F0C0FF8E +:100B0000064600283FF46AAF019B05EB830531E7F9 +:100B10000220FFF7CDFD00283FF4E2AE00F044FFD5 +:100B200000283FF4DDAE0027B946704B9B68BB42FE +:100B300018D91F2F11D80A9B01330ED027F00303B9 +:100B400012AA134453F8203C05934846042205A9F1 +:100B500001F056FF04378146E7E7384600F0EAFE29 +:100B60000590F2E7CDF81490042105A800F0B0FE3E +:100B700000E70023642104A8049300F09FFE0028EE +:100B80007FF4AEAE0220FFF793FD00283FF4A8AE3D +:100B9000049800F0FFFE0590E6E70023642104A816 +:100BA000049300F08BFE00287FF49AAE0220FFF73A +:100BB0007FFD00283FF494AE049800F0EDFEEAE7D4 +:100BC0000220FFF775FD00283FF48AAE00F0FCFE1E +:100BD000E1E70220FFF76CFD00283FF481AE05A994 +:100BE000142000F0F7FE04210746049004A800F04A +:100BF0006FFE3946B9E7322000F04CFE071EFFF6C3 +:100C00006FAEBB077FF46CAE384A926807EB0A03FD +:100C100093423FF665AE0220FFF74AFD00283FF4FD +:100C20005FAE27F003075744BA453FF4A3AE5046E2 +:100C300000F080FE0421059005A800F049FE0AF1AD +:100C4000040AF1E74FF47A70FFF732FD00283FF411 +:100C500047AE00F0A9FE002844D00A9B01330BD018 +:100C600008220AA9002000F00BFF00283AD0202219 +:100C7000FF210AA800F0FCFEFFF722FD1C4803F04C +:100C8000CDFA13B0BDE8F08F002E3FF429AE0BF083 +:100C90000B030B2B7FF424AE0023642105A80593DE +:100CA00000F00CFE074600287FF41AAE0220FFF782 +:100CB000FFFC814600283FF413AEFFF701FD41F22F +:100CC000883003F0ABFA059800F042FF4E4600F082 +:100CD0001BFF3C46B0E506464CE64FF0000AFFE538 +:100CE000B8467BE6374679E6A811002000110020BF +:100CF000A0860100094A136849F2690099B21B0CE9 +:100D000000FB01331360064B186844F2506182B255 +:100D1000000C01FB0200186080B270471411002023 +:100D20001011002010B500211022044600F0A0FE92 +:100D3000034B03CB206061601868A06010BD00BF4A +:100D40009075FF1F2DE9F043224DBBB001F052FE1C +:100D5000AB6840F2ED22C31A934232D906AFA860C5 +:100D60002B4628220021384602F022FB05F10E0016 +:100D700000F076FE002604465FFA80F905F10E08C1 +:100D8000F3B2F100994501F1280107D908EB0603F8 +:100D90000822384602F00CFB0136F1E70823012255 +:100DA000CDE9023205340C4B0193A4B230230093F9 +:100DB000CDE9047405A3D3E90023297B074802F099 +:100DC0000FF93BB0BDE8F083AFF3008078F6339FB6 +:100DD00093CACD8DC8330020D5330020CC2200200B +:100DE00070B50D4614461E4602F090F850B9022E1A +:100DF00010D1012C0ED112A3D3E90023C5E90023A1 +:100E0000012007E0282C10D005D8012C09D0052C92 +:100E10000FD0002070BD302CFBD10BA3D3E90023F1 +:100E2000ECE70BA3D3E90023E8E70BA3D3E9002306 +:100E3000E4E70BA3D3E90023E0E700BFAFF30080B2 +:100E4000401DA12026812A0B78F6339F93CACD8DB1 +:100E50009E6AC421818A46EE26417272DF25D7B789 +:100E6000F017304A39059E5613B504462346084606 +:100E700020220021019002F09BFA22790198032A96 +:100E8000234628BF032203F8042F2021022202F068 +:100E90008FFA62790198072A234628BF072203F8B0 +:100EA000052F2221032202F083FAA2790198072A52 +:100EB000234628BF072203F8062F2521032202F02C +:100EC00077FA019804F108031022282102F070FA41 +:100ED000382002B010BD00002DE9F04FADF5037DC4 +:100EE00023AD10AE40F2751280460F4624A80021B3 +:100EF000296000F0BDFD48220021304600F0B8FD19 +:100F000001F078FD564B4FF47A72B0FBF2F01860A6 +:100F100093E80700012386E807000DF162003382A1 +:100F2000FFF700FF42F20463338407AB18464D49D4 +:100F300004F0D2F84FF0200930642946304686F894 +:100F40003C90FFF791FF14AB044601460822284667 +:100F500002F02EFA0822A1180DF15103284602F0E2 +:100F600027FA0DF15203082204F11001284602F07D +:100F70001FFA4A4615AB04F11801284602F018FA88 +:100F800016AB402204F13801284602F011FA18ABE2 +:100F9000082204F17801284602F00AFA0DF16103F3 +:100FA000082204F18001284602F002FA04F1880ABE +:100FB0000DF1620904F5847B4B4651460822284610 +:100FC0000AF1080A02F0F4F9D34509F10109F3D155 +:100FD0001DAB08225946284602F0EAF904F5887448 +:100FE0004FF0000996F834304B450AD9B36B2146CF +:100FF0004B440822284602F0DBF9083409F10109C4 +:10100000F0E74FF0000996F83C304B4504EBC9017E +:1010100008D9336C08224B44284602F0C9F909F17B +:101020000109F0E7CB1DC3F3CF03CDE9045300233F +:101030000393BB7E029307F11903019301230093ED +:10104000F97E05A3D3E90023404601F0C9FF0DF561 +:10105000037DBDE8F08F00BF9E6AC421818A46EE01 +:10106000B41200200851000810B50A4B0A4A1A6051 +:1010700003F5805393F860203AB9DC6D2CB120461B +:1010800001F036FB204603F0B9FEBDE810400348EE +:1010900001F02EBBF8220020085200084033002047 +:1010A000014B1870704700BFC0120020F0B5334BE1 +:1010B0001C7B85B034B1324B0E221A8100242046AD +:1010C00005B0F0BD2F4A1068516802AB03C3082376 +:1010D0002D492E480DEB030203F0E2FE054630B920 +:1010E000274B2B480A221A8101F080FAE6E70169B2 +:1010F000B1F5583F06D9224B26480B221A8101F040 +:1011000075FADCE7438B40F22642934207D01C4934 +:101110000C2008811946204801F068FACFE71F4AE1 +:10112000024402F11003994204D2154B1C481022CC +:101130001A81E4E710398E1A2046144901F060FC48 +:101140003246074605F11801204601F059FCAB680C +:101150009F4202D1EB6898420AD0094B0D221A81B6 +:101160000090D5E902123B460E4801F03FFAA5E790 +:101170000D4801F03BFA0124A1E700BFC83300206D +:10118000B4120020BD510008DC5F030000A000087D +:101190002C510008385100084A5100080860FFF738 +:1011A0006851000885510008AE5100082DE9F04F44 +:1011B000ADB006AF80460C4601F0A8FE05460028FB +:1011C0005AD1237E022B1BD1E38A012B18D101F0C7 +:1011D00011FC0646FFF78EFD03464FF4C870DFF89A +:1011E000D092B3FBF0F206F5167602FB103316FA36 +:1011F00083F3C9F80030E37E33B9A84B00221A709C +:101200009C37BD46BDE8F08FA38AEEB2013BB342E6 +:1012100005F101050BD93B1D1E44E9000096002392 +:10122000082201F0F801204601F086FFECE707F103 +:101230001400FFF777FD324607F11401381D03F063 +:101240001FFE0028D9D10F2E08D8944B1E70D9F854 +:101250000030A3F51673C9F80030D1E7FB1CF87015 +:101260000146009307220346204601F065FFF97806 +:10127000404601F043FEC3E7E38A282B26D010D86E +:10128000012B1ED0052BBBD1BFF34F8F8449854B5B +:10129000CA6802F4E0621343CB60BFF34F8F00BF14 +:1012A000FDE7302BACD1637E7F4D01336A7BDBB22F +:1012B0009342E94603D1E27E2B7B9A4265D0CD462C +:1012C0009EE721464046FFF707FE99E7A38A013BC8 +:1012D0009BB2C92B94D8744D2E7B26BB05F10C0311 +:1012E0000093082233463146204601F025FF731C47 +:1012F000F2B2D9001E46A38A013B9A4205DA0E32A9 +:101300002A44009200230822EEE700230022C5E9C8 +:1013100000230023AB6085F8D730C5F8D8302B7B8D +:101320000BB9E37E2B73002507F114093B1D08223E +:1013300029464846C7E90155FD6002F039F83B7A75 +:1013400005F1010AAB424FEACA0608D9FB68082238 +:101350002B443146484602F02BF85546EFE7C6F3DA +:10136000CF06E17ECDE9049600230393A37E02938A +:10137000193428230093019446A3D3E9002340465F +:1013800001F02EFEFFF7DEFC3AE74FF0000807F110 +:101390001403A7F81480102200934146012320462D +:1013A00001F0CAFEA68A023EB6B2F31C9B109B0057 +:1013B0000733DB08A9EBC3039D460DF1180A1FFA9A +:1013C00088F34FEAC801B34201F110010AD20AEBD7 +:1013D0000803009308220023204601F0ADFE08F127 +:1013E0000108ECE795F8D70000F0B2FAD5F8D8304C +:1013F00004461BB995F8D70000F0BAFAD5F8D830F2 +:1014000033449C4204D295F8D700013000F0B0FA82 +:101410004FEA960B4FF000081FFA88F18B45D5E98B +:10142000003209D90AEB880103EB8800012200F0A1 +:1014300027FB08F10108EFE7F31842F10002C5E9C4 +:101440000032D5F8D83095F8D70006EB0308C5F878 +:10145000D88000F07DFA804509D395F8D730D5F8CB +:10146000D8000133001B85F8D730C5F8D800FF2E0F +:1014700008D800232B7300F097FAFFF717FE08B186 +:10148000FFF75CF92B68094A9B0A0133138100239B +:10149000AB6014E726417272DF25D7B7C522002062 +:1014A00000ED00E00400FA05C8330020B41200206B +:1014B000C822002010B54FF000540C4B22689A420D +:1014C00011D10B4B627D1A700A48237D03730A49C0 +:1014D000C9220E3000F0BAFAE0220021204600F0C6 +:1014E000C7FA012010BD0020FCE700BF9AAD44C53B +:1014F000C0120020C83300201600002037B5184D58 +:1015000018491948022301226B7100F03DFF0023A6 +:101510000193164B164900931648174B4FF480520F +:1015200001F0C6FC154B197811B1124801F0E6FC28 +:1015300001F060FA0446FFF7DDFB4FF4C873B0FB1F +:10154000F3F202FB130304F5167010FA83F00C4B50 +:10155000186003F05BF908B10F232B8103B030BD95 +:10156000B412002040420F00F8220020E10D0008D4 +:10157000C4120020CC220020AD110008C0120020AF +:10158000C82200202DE9F04F2DED028B0FF26429C7 +:10159000D9E900898D4C93B08D4E8E4F204601F0D5 +:1015A00083FD034660B30025CDE90F550E95ADF8D8 +:1015B0004450027B8DF8442099684068DFF83CA2D3 +:1015C0000FAA03C21B6843F000430E9301F014FA04 +:1015D000821941F1000300950EA9384600F002FB84 +:1015E000A84205DD204601F063FD8AF80050D5E7EA +:1015F0009AF80030072B00F2B68001338AF80030E9 +:101600000BAE9FED6E8B0023724FDFF8F4A10A93AF +:10161000ADF834300B9373604FF0000B5B468DEDEB +:10162000008B01250DF11D0207A938468DF81C50CD +:101630008DF81DB000F058FE9DF81C30002B40F0D6 +:101640009680204601F062FC0646002845D1624F94 +:1016500001F0D0F93B6898423FD301F0CBF98246C4 +:10166000FFF748FB4FF4C8730AF5167AB0FBF3F2A4 +:1016700002FB13031AFA83F33B60584F97F800B04C +:10168000CBF1100ABBF1000F14BF33462B465FFAB3 +:101690008AFA0EA88DF82830FFF744FBBAF1060F3E +:1016A00028BF4FF0060A0EAB03EB0B0152460DF1BB +:1016B000290000F0CBF90AAB0393182302930AF137 +:1016C0000102474BD2B2CDE90053049220463DA31C +:1016D000D3E9002301F01CFC3E7001F08BF9414A74 +:1016E000414D1368C31AB3F57A7F2FD3106001F010 +:1016F00083F902460B46204601F0E4FC204601F047 +:1017000005FC18B32B7B394E002B14BF0323022397 +:10171000737101F06FF90EAF4FF47A733946B0FB75 +:10172000F3F030603046FFF79FFB18230730029339 +:101730002F4B0193C0F3CF0040F25513CDE9037056 +:10174000009342464B46204601F0E2FB2B7B2BB137 +:10175000FFF7F8FA2B7B002B7FF41EAF13B0BDEC24 +:10176000028BBDE8F08F204601F0A2FC48E7DAF8D2 +:10177000143083F00803CAF81430594610220EA81A +:1017800000F076F90DF11E0308AA0AA9384600F008 +:1017900027FB96E803000FAB83E803009DF8343085 +:1017A0008DF844300A9B0E930EA9DDE908232046EC +:1017B00001F046FE30E700BFAFF3008000000000FC +:1017C00000000000401DA12026812A0BCC22002011 +:1017D00040420F00F8220020C8220020C52200202D +:1017E000C4220020A8340020C8330020B4120020F6 +:1017F000AC340020F1C6A7C1D068080FAD3400207A +:101800000004004808B5054800F084FBBDE8084026 +:10181000034A0449002003F0EBBA00BFF82200207D +:1018200000350020691000082DE9F84F4FF47A7355 +:10183000DFF85880DFF8589006460D4602FB03F7A4 +:10184000002498F900305A1C5FFA84FA01D0A342B0 +:1018500010D159F8240003682A46D3F820B0314645 +:101860003B46D847854205D1074B012083F800A0AD +:10187000BDE8F88F0134032CE3D14FF4FA7002F085 +:10188000CDFC0020F4E700BFF43400201811002044 +:10189000D451000807B50023024601210DF10700CD +:1018A0008DF80730FFF7C0FF20B19DF8070003B0A7 +:1018B0005DF804FB4FF0FF30F9E700000A4608B579 +:1018C0000421FFF7B1FF80F00100C0B2404208BD23 +:1018D00030B4074B0A461978064B53F82140236869 +:1018E000DD69054B0146AC46204630BC604700BF71 +:1018F000F4340020D4510008A086010070B502F035 +:10190000CBFD094E094D308000242868338883427E +:1019100008D902F0BDFD2B6804440133B4F5204F13 +:101920002B60F2D370BD00BFF6340020B03400202D +:1019300002F072BE00F1006000F5204000687047C0 +:1019400000F10060920000F5204002F0E9BD0000C7 +:10195000054B1A68054B1B889B1A834202D9104419 +:1019600002F096BD00207047B0340020F63400200D +:1019700038B5074D04462868204402F08FFD28B989 +:1019800028682044BDE8384002F09ABD38BD00BF49 +:10199000B03400200020704700F10050A0F5104046 +:1019A000D0F8900570470000064991F8243033B113 +:1019B0000023086A81F824300822FFF7C1BF012004 +:1019C000704700BFB4340020014B1868704700BF57 +:1019D000002004E070B50E4B5C6893F90860421E6D +:1019E0000A44013C0B46934207D214F9015F581C8C +:1019F0002DB100F8015C0346F5E7184605E02C24FC +:101A000082421C7001D9981C5E70401A70BD00BFE4 +:101A10001C110020022802BF024B4FF400229A61E1 +:101A2000704700BF00040048022802BF014B082293 +:101A30009A61704700040048022801BF024A5369B6 +:101A400083F00803536170470004004810B5002379 +:101A5000934203D0CC5CC4540133F9E710BD0000BD +:101A600003460246D01A12F9011B0029FAD1704729 +:101A700002440346934202D003F8011BFAE7704781 +:101A80002DE9F8431F4D144695F824200746884653 +:101A900052BBDFF870909CB395F824302BB920220C +:101AA000FF2148462F62FFF7E3FF95F82400C0F1BD +:101AB0000802A24228BF2246D6B24146920005EB58 +:101AC0008000FFF7C3FF95F82430A41B1E44F6B234 +:101AD000082E17449044E4B285F82460DBD1FFF768 +:101AE00063FF0028D7D108E02B6A03EB820383420F +:101AF000CFD0FFF759FF0028CBD10020BDE8F883F5 +:101B00000120FBE7B4340020024B1A78024B1A7014 +:101B1000704700BFF43400201811002008B50849B0 +:101B200008484FF461430B6002F012FA044906487A +:101B300002F00EFABDE808400149044802F008BA74 +:101B4000DC3400200435002070350020DC35002016 +:101B5000094B10B51822044600211846FFF788FFEC +:101B6000064A074B127804600146BDE8104053F85E +:101B7000220002F0EDB900BFDC340020F434002074 +:101B8000D4510008202383F3118862B67047000007 +:101B9000002383F3118862B67047000010B4026816 +:101BA00054681A4623465DF8044B184701207047D5 +:101BB0000020704700207047704700007047000009 +:101BC000002070470E20704700F5805090F8C80044 +:101BD000C0F340007047000000F5805090F9C90044 +:101BE000704700002DE9F0410C68BDF8187014F042 +:101BF00000541E466FD10B7B082B6CD8FFF7C2FF39 +:101C00004569AB685B010CD4AB681B0108D4AC68B8 +:101C100014F080545DD1FFF7BBFF2046BDE8F08192 +:101C200001240B6804F1180C002BB8BFDB004FEA4D +:101C30000C1CB4BF43F004035B0545F80C300B6883 +:101C40000FFA84FC13F0804F18BF05EB0C1E05EB58 +:101C50000C1C1EBFDEF8803143F00203CEF8803149 +:101C60000B7BCCF8843105EB04158B68C5F88C31FF +:101C70004B68C5F88831DCF8803143F00103CCF8BB +:101C8000803100EB441541F268031D4403EB44131B +:101C90000344C5E9002608330D4601F10C0C55F844 +:101CA00004EB43F804EB6545F9D184342D881D809D +:101CB00000EB441407F00303257925F00B052B43B3 +:101CC0002371FFF765FF06973346BDE8F04100F04A +:101CD000AFBC0224A5E74FF0FF309FE713B500F536 +:101CE00080540191E06D00F039FD1F280AD9019957 +:101CF000E06D202200F0A8FDA0F1200358425841D9 +:101D000002B010BD0020FBE708B500F58050FFF7DA +:101D100039FFC06D00F0F6FCBDE80840FFF738BFA2 +:101D200000220260828142608260704710B500220A +:101D30000023C0E900230023044603810C30FFF791 +:101D4000EFFF204610BD0000F0B5054600F58050BD +:101D50000C4690F8C83013F0040FC3F3800108BF9D +:101D6000114661F3820304F1840680F8C83005EB64 +:101D7000461389B01B79D8072ED57AB319072DD40D +:101D80006846FFF7D3FF05EB441303F5835303F1D4 +:101D9000180703AA103318685968144603C4083397 +:101DA000BB422246F7D1186820609B88A380DDE9FA +:101DB0000E23CDE900230123ADF808302B686946D6 +:101DC0001B6C2846984705EB46152B791A075CBF14 +:101DD00043F008032B7101E0002AF4D109B0F0BDF3 +:101DE0002DE9F047074688B007F5805468469A46C3 +:101DF0008846FFF7C7FE9146FFF798FFE06D00F0B9 +:101E000093FC1F2829D9E06D2022694600F09EFD31 +:101E1000202822D103AD444605AB2E4603CE9E4278 +:101E200020606160354604F10804F6D13068206016 +:101E3000B388A380DDE90023C9E90023BDF8083099 +:101E4000AAF80030FFF7A4FE4A46534641463846FA +:101E500008B0BDE8F04700F0D9BBFFF799FE0020BD +:101E600008B0BDE8F08700002DE9F84F0023C0E975 +:101E70000133254B044640F8183B0F46FFF750FF4F +:101E800004F12800FFF752FF04F1480804F58255D9 +:101E90004646083530462036FFF748FFAE42F9D1B6 +:101EA00004F580554FF480534FF00009C5E913390C +:101EB000C5F848800123EE6504F5875804F584567B +:101EC000C5F8549085F8583085F86030083608F128 +:101ED00008084FF0000A4FF0000B46E908ABA6F1E6 +:101EE0001800FFF71DFF203646F8289C4645F4D120 +:101EF00085F8C97017B1054800F076FD044B6361A1 +:101F00002046BDE8F88F00BF08520008E0510008E5 +:101F10000064004010B5044B197804464A1C1A703E +:101F2000FFF7A2FF204610BDFC3400202DE9F0474A +:101F3000002950D0294B2A4FB7FBF1F599428CBFAD +:101F40000A231123581EB5FBF3FC03FB1C53C4B238 +:101F50002BB102280346F5D80020BDE8F0870CF12C +:101F6000FF36B6F5806FF7D2C4EBC40E0EF1030353 +:101F70004FEAE309C3F3C703A4EB030809F1010A1D +:101F80004FF47A755FFA88F009FB05555AFA88F81C +:101F9000B5FBF8F5B5F5617FC1BF0EF1FF33C3F3B3 +:101FA000C703E01AC0B25C1C50FA84F40CFB04F4C2 +:101FB000B7FBF4F4A142CFD1013BDBB20F2BCBD85E +:101FC0000138C0B20728C7D800211071168091705F +:101FD000D3700120C1E70846BFE700BF3F420F00B2 +:101FE00000B4C40470B505460E464FF47A746B69AC +:101FF0005B6803F00103B34207D04FF47A7002F03C +:102000000DF9013CF3D1204670BD0120FCE7000032 +:1020100030B54269936913F0700F16D000230B4C52 +:10202000936103F1840200EB421211794D0709D547 +:10203000890707D5416954F823508D60117941F023 +:10204000040111710133032BEBD130BDF4510008B1 +:1020500073B51D46436916469A68D207044609D5EA +:102060009A6801219960C2F34002CDE90065002120 +:10207000FFF76AFE63699A68D1050BD59A684FF439 +:1020800080719960C2F34022CDE9006501212046AC +:10209000FFF75AFE63699A68D2030BD59A684FF42A +:1020A00080319960C2F34042CDE9006502212046AB +:1020B000FFF74AFE204602B0BDE87040FFF7A8BF18 +:1020C000F8B50446466900296CD106F10C0738685A +:1020D00080076AD006EB01153868D5F8B00110F01A +:1020E000040FD5F8B0011ABFC00840F00040400D01 +:1020F000A061D5F8B0C11CF0020F1CBF40F08040B9 +:10210000A061D5F8B40106EB011100F00F0084F8CE +:102110002400D1F8B8012077D1F8B801000A60771F +:10212000D1F8B801000CA077D1F8B801000EE07723 +:10213000D1F8BC0184F82000D1F8BC01000A84F871 +:102140002100D1F8BC01000C84F82200D1F8BC11A8 +:10215000090E84F823103821396004F1340004F1A9 +:10216000180104F1240551F8046B40F8046BA942EE +:10217000F9D109880180C4E90A2321460023238676 +:1021800051F8283B20461B6C984704F580522046A6 +:1021900092F8C83043F0040382F8C830BDE8F84034 +:1021A000FFF736BF06F1100791E7F8BD10B50446FA +:1021B00000F022FC02460B4652EA030102D0013A2B +:1021C00063F100030449086820B12146BDE81040CE +:1021D000FFF776BF10BD00BFF8340020F8B500F55A +:1021E00083511E46FFF7CEFCDFF844C008310024BF +:1021F00004F1840500EB45152B795F070ED4DB064F +:102200000CD5D1E900739742B34107D243695CF81A +:1022100024709F602B7943F004032B710134032C4D +:1022200001F12001E4D1BDE8F840FFF7B1BC00BFE7 +:10223000F451000808B5FFF7A5FCFFF7E9FEBDE87B +:102240000840FFF7A5BC0000F8B54369054698684B +:1022500000F0E050B0F1E05F0F461FD0E8B1FFF7AB +:1022600091FC05F583541034002606F1840305EB38 +:1022700043131B791A0706D50136032E04F12004F7 +:10228000F3D1012007E05B07F6D42146384600F081 +:1022900009FA0028F0D1FFF77BFCF8BD0120FCE72C +:1022A00000F5805008B5FFF76DFCC06D00F03CFAFA +:1022B000FFF76EFC43090CBF0120002008BD0000A1 +:1022C000F8B51D46002313700F4606461446FFF767 +:1022D000E7FF80F00100387025B129463046FFF74E +:1022E000B3FF2070F8BD00002DE9B8410C4615463B +:1022F0001F46804600F080FB0B462178024609B954 +:10230000287850B14046FFF769FFFFF793FF3B463F +:102310002A462146FFF7D4FF0120BDE8B88100001E +:1023200010B5FFF72FFC174B9A6D42F000729A65BB +:102330009A6B42F000729A639A6B00F5805422F017 +:1023400000729A63FFF724FC94F8C830DB0718D4B6 +:10235000B9B102211320FFF715FC01F047FC02215F +:10236000142001F043FC0221152001F03FFC94F8F9 +:10237000C83043F0010384F8C830BDE81040FFF7CF +:1023800007BC10BD001002402DE9F04700F5805554 +:1023900088B095F8C930012B04468846164600F2ED +:1023A000FB807E4F57F823200AB947F82300D7F85F +:1023B00000A0C4F80C802674BAF1000F09D141F2D4 +:1023C000D00002F01DFD51468146FFF74DFDC7F8D4 +:1023D000009095F8C930012B5DD001212046FFF710 +:1023E0009FFFFFF7CFFB6269136823F002031360BE +:1023F0006269136843F001031360636900275F613A +:1024000001212046FFF7C4FBFFF7ECFD002800F098 +:102410008480E86D00F076F904F58359BA4609F135 +:102420000809202200216846FFF722FB02A8FFF7D7 +:1024300077FCCDF818A06A4609EB07030DF1180EDA +:102440009446BCE80300F44518605960624603F105 +:102450000803F5D1DCF80000186020379CF8042050 +:102460001A71602FDDD195F8C8306FF38203002711 +:1024700085F8C8306A4641462046ADF80070ADF890 +:1024800002708DF80470FFF751FD6369C0B94FF415 +:1024900000421A6011E0386803685B6B9847014698 +:1024A00000289AD13868FFF73BFF38680368324646 +:1024B0005B684146984700288FD108B0BDE8F08797 +:1024C00061221A609DF802309DF803201B06120459 +:1024D00002F4702203F040731343BDF80020C2F3EE +:1024E000090213439DF804201205022E02F4E002B3 +:1024F0000CBF4FF000410021134362690B43D361CD +:10250000636913225A616269136823F0010313603F +:1025100039462046FFF766FD08B96369B7E795F8C5 +:10252000C93093BB6169D1F8002242F00102C1F8C1 +:1025300000226169D1F8002222F47C5222F00E02BE +:10254000C1F800226169D1F8002242F46062C1F84A +:1025500000226269C2F814326269C2F80432626908 +:1025600041F6FF71C2F80C126269C2F8403262692A +:10257000C2F8443263690122C3F81C226269D2F8AE +:10258000003223F00103C2F8003295F8C83043F05E +:10259000020385F8C83090E700208EE7F834002069 +:1025A00008B500F029FA50EA0103024602D0421EA3 +:1025B00061F10001044B186810B10B46FFF748FDAC +:1025C000BDE8084001F06CB9F834002008B50020DF +:1025D000FFF7ECFDBDE8084001F062B908B5012045 +:1025E000FFF7E4FDBDE8084001F05AB90FB4002040 +:1025F00004B0704713B56C4684E80600031D94E8E8 +:10260000030083E80500012002B010BD73B58568A2 +:10261000019155B11B885B0707D4D0E90036DB6B0D +:102620009847019AC1B23046A847012002B070BD58 +:10263000F0B5866889B005460C465EB1BDF8383005 +:102640005B070AD4D0E90037DB6B98472246C1B25A +:102650003846B047012009B0F0BD00220023CDE983 +:1026600000230023ADF808300A4603AB01F1080649 +:10267000106851681C4603C40832B2422346F7D1A1 +:10268000106820609288A28000F0B8F90423ADF8A9 +:1026900008302B68CDE900011B6C69462846984735 +:1026A000D8E7000030B503680968DD0FB5EBD17FCE +:1026B00023F0604421F060424FEAD1700BD0002B30 +:1026C000B8BFA40C0029B8BF920C944202D034BF0A +:1026D0000120002030BD944205D1C1F38070C3F3C6 +:1026E00080738342F6D194422CBF00200120F1E791 +:1026F00010B5037C044613B9006802F0B9FB20460C +:1027000010BD00000023BFF35B8FC360BFF35B8F7E +:10271000BFF35B8F8360BFF35B8F7047BFF35B8F4B +:102720000068BFF35B8F704770B505460C30FFF74C +:10273000F5FF05F1080604463046FFF7EFFFA0421B +:1027400006D930466D68FFF7E9FF2544281A70BDA9 +:102750003046FFF7E3FF201AF9E7000070B50546A1 +:10276000406898B105F10800FFF7D8FF05F10C06A5 +:1027700004463046FFF7D2FF8442304694BF6D686E +:102780000025FFF7CBFF013C2C44201A70BD000050 +:1027900038B50C460546FFF7C7FFA04210D305F138 +:1027A0000800FFF7BBFF04446868B4FBF0F100FBCE +:1027B0001144BFF35B8F0120AC60BFF35B8F38BD6A +:1027C0000020FCE72DE9F041144607460D46FFF7CF +:1027D000C5FF844228BF0446D4B1B84658F80C6BF4 +:1027E0004046FFF79BFF3044286040467E68FFF775 +:1027F00095FF331A9C4203D86C600120BDE8F0813C +:102800006B60A41B3B68AB602044E8600220F5E7E6 +:102810002046F3E738B50C460546FFF79FFFA04278 +:1028200010D305F10C00FFF779FF04446868B4FB8E +:10283000F0F100FB1144BFF35B8F0120EC60BFF3AC +:102840005B8F38BD0020FCE72DE9FF4188466946D3 +:102850000746FFF7B7FF6C4606B204EBC606002535 +:10286000B44209D06268206808EB0501FFF7EEF872 +:10287000636808341D44F3E729463846FFF7CAFF6A +:10288000284604B0BDE8F081F8B505460C300F4687 +:10289000FFF744FF05F1080604463046FFF73EFF08 +:1028A000A042304688BF6C68FFF738FF201A3860B6 +:1028B00020B130462C68FFF731FF2044F8BD0000FE +:1028C00073B5144606460D46FFF72EFF844228BF17 +:1028D00004460190DCB101A93046FFF7D5FF019B0A +:1028E00033B93268C5E90233C5E9002401200CE0A0 +:1028F0009C4238BF01942860019868608442F5D9F1 +:102900003368AB60241AEC60022002B070BD204630 +:10291000FBE700002DE9FF410F466946FFF7D0FFB6 +:102920006C4600B204EBC0050026AC4209D0D4F8D6 +:10293000048054F8081BB8194246FFF787F846444C +:10294000F3E7304604B0BDE8F081000038B5054635 +:10295000FFF7E0FF044601462846FFF719FF20462F +:1029600038BD000000B59BB0EFF3098168226846CE +:10297000FFF76CF8EFF30583044B9A6BDA6A9A6AF7 +:102980009A6A9A6A9A6A9A6A9B6AFEE700ED00E080 +:1029900000B59BB0EFF3098168226846FFF756F84F +:1029A000EFF30583044B9A6B9A6A9A6A9A6A9A6A59 +:1029B0009A6A9B6AFEE700BF00ED00E000B59BB09D +:1029C000EFF3098168226846FFF740F8EFF30583CB +:1029D000034B5A6B9A6A9A6A9A6A9A6A9B6AFEE7EA +:1029E00000ED00E0FEE700000FB408B5029801F02A +:1029F000AFFBFEE701F050BE01F028BE01F026BE9D +:102A000030B5094D0A4491420DD011F8013B5840B0 +:102A1000082340F30004013B2C4013F0FF0384EA39 +:102A20005000F6D1EFE730BD2083B8ED2DE9F0413D +:102A3000C56915B9C161BDE8F0814B6823F06047F5 +:102A4000C3F38A464FEAD37EC3F3807816EA23069F +:102A500038BF3E46AC462B465A68BEEBD27F22F0CA +:102A600060440AD0002A18DAA40CB44217D19D425F +:102A70000FD10D60DEE71346EEE7A74207D102F063 +:102A80008044C2F3807242450BD054B1EFE708D2C4 +:102A9000EDE7CCF800100B60CDE7B44201D0B442B2 +:102AA000E5D81A689C46002AE5D11960C3E7000002 +:102AB0002DE9F047089D01F007044FEAD5082244AC +:102AC00005F0070500EBD1004FF47F49944201D196 +:102AD000BDE8F08704F0070705F0070A57453E46B2 +:102AE00038BF5646C6F10806111B8E4228BF0E4657 +:102AF000E10808EBD50E415C13F80EC0B94029FA85 +:102B000006F721FA0AF1FFB28CEA010147FA0AF747 +:102B100039408CEA010C03F80EC034443544D5E743 +:102B200080EA0120082341F2210201B2400000297D +:102B300080B203F1FF33B8BF504013F0FF03F4D16C +:102B40007047000038B50C468D18A54200D138BD3D +:102B500014F8011BFFF7E4FFF7E7000002684AB131 +:102B600013680360C388018901339BB29942C38013 +:102B700038BF03811046704770B588B020220446E4 +:102B80000D4668460021FEF773FF20460495FFF7C7 +:102B9000E5FF024658B16B46054608AE1C4603CC1D +:102BA000B44228606960234605F10805F6D1104655 +:102BB00008B070BD082817D909280CD00A280CD0F5 +:102BC0000B280CD00C280CD00D280CD00E2814BFCC +:102BD0004020302070470C20704710207047142090 +:102BE000704718207047202070470000082817D928 +:102BF0000C280CD910280CD914280CD918280CD959 +:102C000020280CD930288CBF0F200E2070470920B7 +:102C100070470A2070470B2070470C2070470D202A +:102C20007047000010B54B6823B9CA8A63F30902E4 +:102C3000CA8210BDC4681A681C60C360438A013B25 +:102C400043824A60EFE700002DE9F84F1D46CB8A2A +:102C50000F46C3F309010629814692460B4630D040 +:102C60000020AAB207F119049EB2052E1FFA80F8BF +:102C70000FD8904503F1010306D3FB8A0A4462F39F +:102C80000903FB8201201AE01AF80060E6540130C3 +:102C9000EAE79045F1D2A1F1060B1C237C68BBFB4F +:102CA000F3F203FB12BB1FFA8BF6002C45D148460A +:102CB000FFF754FF044638B978606FF00200BDE8B2 +:102CC000F88F4FF00008E6E7002606607860ADB2A6 +:102CD0004FF0000B454510D90AEB0803221D13F8ED +:102CE000011B9155B1B208F101081B291FFA88F8A0 +:102CF0002BD0454506F10106F1D8FB8AC3F3090242 +:102D0000154465F30903BCE7013292B21C462368FF +:102D1000002BF9D1AB1F0B441C21B3FBF1F30133A2 +:102D20009BB29A42D3D2BBF1000FD0D14846FFF7F5 +:102D300015FF20B9C4F800B0BFE70122E7E7C0F8EB +:102D400000B05E4620600446C1E74545D5D94846F7 +:102D5000FFF704FF08B92060AFE7C0F800B0002615 +:102D600020600446B6E700002DE9F04F2DED028B00 +:102D700083B0CDE90013BDF83C5007469146002AC8 +:102D800000F092802DB10E9B002B00F08D80072D5E +:102D900032D807F10C00FFF7E1FE044638B96FF0B6 +:102DA0000204204603B0BDEC028BBDE8F08F142274 +:102DB0000021FEF75DFE0E992A4604F10800FEF799 +:102DC00045FE681CC0B2FFF711FFFFF7F3FE207449 +:102DD00099F80030013814FA80F003F01F0363F013 +:102DE0003F030372009B43F0004161603846214677 +:102DF000FFF71CFE0124D4E700F10C034FF000089C +:102E000008EE103A4FF0800A4646444618EE100A83 +:102E1000FFF7A4FE83460028C1D014220021FEF74C +:102E200027FEC6BB019BABF8083002200E9B00F1C9 +:102E3000080299195BFA82F20130C0B2082801D069 +:102E4000AE422AD3FFF7D2FEFFF7B4FE99F8002076 +:102E5000009B411E02F01F0242EA4812AE4208BF28 +:102E60004FF0400A5BFA81F14AEA020A43F000425D +:102E700081F808A08BF81000CBF80420594638469A +:102E8000FFF7D4FD0134AE4224B288F001084FF0C0 +:102E9000000ABBD185E70020C8E711F801CB02F892 +:102EA00001CB0136B6B2C7E76FF0010479E7000045 +:102EB000F8B515460E462822002104461F46FEF7A7 +:102EC000D7FD069B6360B5F5001F079BA76034BF65 +:102ED0006A094FF6FF72236204F10C0097B20023D7 +:102EE0009A4205D80023036027826382A382F8BD3B +:102EF0000660013330462036F2E7000003781BB944 +:102F00004BB2002BC8BF01707047000000787047BB +:102F10002DE9F74FDDF83C90BDF830500D9E9DF83F +:102F20003840BDF84070804692469B46B9F1000F8C +:102F300001D1002F51D11F2C4FD898F80000B0B903 +:102F4000072F47D835F0030347D13A4649464FF695 +:102F5000FF70FFF7F7FD20F001002D02400445EA65 +:102F60000464400C44EA40244FF6FF7321E040EA39 +:102F70000520072F40EA0464F6D900254FF6FF73B9 +:102F8000C5F12000A5F120022AFA05F10BFA00F0A4 +:102F900001432BFA02F211431846C9B2FFF7C0FDF4 +:102FA0000835402D0346EBD13A464946FFF7CAFDA6 +:102FB0000346CDE90097324621464046FFF7D4FE4E +:102FC00033780133DBB21F2B88BF0023337003B08B +:102FD000BDE8F08F6FF00300F9E76FF00100F6E74E +:102FE0002DE9F04F85B09246DDF848800F9D9DF8A1 +:102FF00040209DF84490BDF84C7006469B46B8F1C1 +:10300000000F01D1002F48D11F2A46D83378002B5A +:1030100046D00C0244EA02649DF8381044EAC934F0 +:1030200044EA01441C43072F44F0800432D90023B2 +:103030004FF6FF72C3F1200CA3F120002AFA03F12E +:103040000BFA0CFC41EA0C012BFA00F00143C9B267 +:1030500010460393FFF764FD039B0833402B0246A1 +:10306000E8D13A464146FFF76DFD0346CDE90087BA +:103070002A4621463046FFF777FEB9F1010F06D107 +:103080002B780133DBB21F2B88BF00232B7005B0D8 +:10309000BDE8F08F4FF6FF73E8E76FF00100F6E749 +:1030A0006FF00300F3E70000C06900B1043070471F +:1030B000C3691A68C261C2681A60C360438A013B6F +:1030C000438270472DE9F041D0F81880194E14461C +:1030D0001D464146002709B9BDE8F081D1E9022328 +:1030E000A21A65EB0303964277EB03031ED28369B2 +:1030F0008B420DD1FFF796FD83691B688361C3681E +:103100000B60438AC1608169013B43828846E2E7E4 +:10311000FFF788FD0B68C8F80030C3680B60438A6E +:10312000C160013B4382D8F80010D4E788460968A3 +:10313000D1E700BF80841E002DE9F04F8BB00D4613 +:10314000DDF8509014469B468046002800F0198117 +:10315000B9F1000F00F01581531E3F2B00F21181D1 +:10316000012A03D1BBF1000F40F00B810023CDE910 +:103170000833B8F81430B5EBC30F4FEAC30703D3D5 +:1031800000200BB0BDE8F08F2B199F42D8F80C300F +:103190003ABF7F1BFFB227461BB9D8F81030002B6F +:1031A0007AD02F2D4ED8C5F13006B7424FF000032C +:1031B0002CBFF6B23E4600932946D8F8080008AB6B +:1031C0003246FFF775FCA7EB060A35445FFA8AFA28 +:1031D000B8F8143003F10053063BDB000493D8F831 +:1031E0000C3003933021039B13B1BAF1000F2CD1A3 +:1031F000D8F8100040B1BAF1000F05D0009608AB26 +:103200005246691AFFF754FC38B2002FB8D066074F +:103210000AD00AAB03EBD401624211F8083C02F079 +:103220000702134101F8083C082C3CD9102C40F24D +:10323000B580202C40F2B780BBF1000F00F09C80DD +:10324000082334E0BA460026C2E7049BE02B28BFDF +:10325000E02306930B44AB42059314D95A1B039801 +:103260000096924534BF5246D2B2691A08AB043078 +:103270000792FFF71DFC079A1644AAEB020A1544B1 +:10328000F6B25FFA8AFA049B069A05999B1A049390 +:10329000039B1B680393A6E70093D8F8080008ABCC +:1032A0003A462946AEE7BBF1000F13D00123B4EB39 +:1032B000C30F6CD0082C12D89DF82030621E23FA60 +:1032C00002F2D50706D54FF0FF3202FA04F4234389 +:1032D0008DF820309DF8203089F8003051E7102C0F +:1032E00012D8BDF82030621E23FA02F2D10706D5AB +:1032F0004FF0FF3202FA04F42343ADF82030BDF85A +:103300002030A9F800303CE7202C0FD80899631E24 +:1033100021FA03F3DA0705D54FF0FF3202FA04F47D +:103320000C430894089BC9F800302AE7402C2BD0A6 +:10333000DDE90865611EC4F12102A4F1210326FA2A +:1033400001F105FA02F225FA03F311431943CB0701 +:1033500012D50122A4F12003C4F1200102FA03F3E3 +:1033600022FA01F1A240524243EA010363EB430314 +:1033700032432B43CDE90823DDE90823C9E90023C3 +:10338000FFE66FF00100FCE66FF00800F9E6082C9C +:10339000A0D9102CB3D9202CEED8C3E7BBF1000F75 +:1033A000ADD0022383E7BBF1000FBBD004237EE73F +:1033B00030B5012A144638BF0124402C85B028BFFF +:1033C00040240025012ACDE9025518D81B788DF834 +:1033D000083063070AD004AB03EBD405624215F84A +:1033E000083C02F00702934005F8083C00910346B0 +:1033F0002246002102A8FFF75BFB05B030BD082A7A +:10340000E4D9102A03D81B88ADF80830E1E7202A58 +:103410008DBFD3E900231B680293CDE90223D8E7CF +:1034200010B5CB681BB98B600B618B8210BDC46873 +:103430001A681C60C360438A013B4382CA60F0E79C +:103440002DE9F04FD1F8008093B018F0800FCDE94E +:103450000323C8F3C01219BFC8F3C03BC8F3062644 +:103460004FF0020B1646B8F1000F04460D4680F2ED +:10347000D18118F0C043059340F0CC810B7B002B29 +:1034800000F0C881BBF1020F03D00178B14240F0D7 +:10349000C48108F07F0106916AB3C8F3074A2B4440 +:1034A000069A93F80390760646EA0B4646EA824669 +:1034B0005FEAD91346EA0A06079300F090800022DB +:1034C0000023CDE90A23069B009367685B465246BA +:1034D0000AA92046B84700287ED0A7699FB931467F +:1034E00004F10C00FFF748FB0746E0B96FF002005B +:1034F00013B0BDE8F08FC8F30F2A18F07F0F08BF94 +:103500000AF0030ACBE73B699E420DD03F68002FCB +:10351000F9D1314604F10C00FFF72EFB07460028D5 +:10352000E4D0A3693B60A761DDE90A2300264FF6DA +:10353000FF70C6F1200E22FA06F103FA0EFEA6F184 +:10354000200C23FA0CFC41EA0E0141EA0C01C9B23D +:10355000083609920893FFF7E3FA402EDDE90832B6 +:10356000E7D1B882FB7D09F01F06C3F384039B1BE0 +:10357000D7E9022198B2002BBCBF00F120031BB297 +:1035800052EA0100C8F304680FD00398821A049825 +:1035900060EB0101A74890424FF000028A4104D33A +:1035A000079A002A5BD0012B23DDFA7D4FEA8903BD +:1035B00002F0030203F07C031343FB7539462046F7 +:1035C000FFF730FB079BA3B9FB7DC3F384020132F5 +:1035D00062F38603FB7504E06FF00B0088E7A769D0 +:1035E00017B96FF00C0083E73B699E42BAD03F6881 +:1035F000F6E719F0400F32D0039BBB60049BFB60E1 +:10360000142200210DA8FEF733FA039B0A93049BB2 +:103610000B932B1D0C932B7BADF83EA0013BDBB233 +:10362000ADF83C30069B8DF8433094F824308DF88B +:1036300040B083F001038DF844308DF84160A368F9 +:103640008DF842800AA920469847FB7DC3F3840386 +:10365000013303F01F039B02FB82002048E7FB7D40 +:10366000C9F34012B2EBD31F40F0DA80C3F38403F6 +:10367000B34240F0D88007992B7B4FEA991200297A +:1036800034D0D20741D4032B40F2D080039BBB60DF +:10369000049BFB602B7BAE1D033BDBB232463946FD +:1036A00004F10C00FFF7D0FA00280DDA2046394665 +:1036B000FFF7B8FAFB7DC3F38403013303F01F0364 +:1036C0009B02FB82032013E7AB883B832A7B033AF0 +:1036D000B88AD2B23146FFF735FAFB7DB882DA43B9 +:1036E000C2F3C01262F3C713FB75B6E76AB92E1DA9 +:1036F000013BDBB23246394604F10C00FFF7A4FA75 +:103700000028D3DB2A7B013AE2E7F98AC1F30901F9 +:10371000013B0529DAB259D8281D002307F11A0CFC +:103720009A4208D910F801EB0CF801E0013101339D +:103730000629DBB2F4D103990A9104990B919342C3 +:1037400007F11A010C9138BF043379680D9134BF29 +:1037500055FA83F300230E93FB8AADF83EA0C3F322 +:1037600009031A44069B8DF8433094F82430ADF8D1 +:103770003C2083F001038DF8443000238DF840B0E5 +:103780008DF841608DF842807B602A7BB88A013ACF +:10379000291DFFF7D7F93B8BB882834203D1A36879 +:1037A0000AA92046984720460AA9FFF739FEFB7D63 +:1037B000B88AC3F38403013303F01F039B02FB8227 +:1037C0003B8B984214BF1120002091E67B68002BB0 +:1037D000B1D0062001E01C306346D3F800C0BCF134 +:1037E000000FF8D1091A081D05F1040C00EB0309BC +:1037F00005989DF8143001EB000EBEF11B0F9AD80E +:103800009A4298D91CF8013B09F8013B059B01330A +:103810000593EDE76FF009006AE66FF00A0067E6CE +:103820006FF00D0064E66FF00E0061E66FF00F00C0 +:103830005EE600BF80841E00EFF3098305494A6BF2 +:1038400022F001024A63683383F30988002383F37B +:103850001188704700EF00E0202080F3118862B6E5 +:103860000C4B0D4AD96821F4E0610904090C0A43A4 +:10387000DA60D3F8FC20094942F08072C3F8FC20DA +:103880000A6842F001020A601022DA7783F8220007 +:10389000704700BF00ED00E00003FA05001000E0F3 +:1038A00010B5202383F311880E4B5B6813F400637B +:1038B00014D0F1EE103AEFF30984683C4FF08073B6 +:1038C000E361094BDB6B236684F3098800F0F2FBAC +:1038D00010B1064BA36110BD054BFBE783F31188C4 +:1038E000F9E700BF00ED00E000EF00E00B06000884 +:1038F0000E060008026843681143016003B11847CF +:1039000070470000024A136843F0C0031360704719 +:1039100000380140024A136843F0C0031360704747 +:1039200000440040024A136843F0C003136070472C +:103930000048004037B5244C244D204600F0FCFAE6 +:10394000009404F1140022490023202200F0BEF963 +:1039500020490094202204F138001F4B00F038FA6F +:103960001E4BC4E917351E4C204600F0E5FA0094C2 +:1039700004F114001B490023202200F0A7F91A4982 +:103980000094202204F13800184B00F021FA184B63 +:10399000C4E91735174C204600F0CEFA04F11400A4 +:1039A000154900940023202200F090F9134B14498C +:1039B0000094202204F1380000F00AFA114BC4E907 +:1039C000173503B030BD00BF0435002000B4C40477 +:1039D00048360020A836002005390008003801408C +:1039E0007035002068360020C836002015390008E0 +:1039F00000440040DC3500208836002025390008CE +:103A0000E83600200048004030B5037C304C0029E7 +:103A100018BF0C46012B0FD12E4B984239D12E4B9B +:103A20001A6E42F480421A66D3F8802042F4804233 +:103A3000C3F88020D3F880302268036EC16D84669D +:103A400003EB5203B3FBF2F36268150442BF23F0A9 +:103A5000070503F0070343EA4503CB60A36843F07F +:103A600040034B60E36843F001038B6042F49673BC +:103A700043F001030B604FF0FF330B62510505D596 +:103A800012F010221FD0B2F1805F1ED080F8643097 +:103A900030BD124B98420BD0114B9842CCD10E4BFB +:103AA0009A6D42F480229A659A6F42F4802207E070 +:103AB000094B9A6D42F400329A659A6F42F40032D3 +:103AC0009A679B6FB8E77F23E0E73F23DEE700BFFD +:103AD0004C520008043500200010024070350020D0 +:103AE000DC3500202DE9F047C66D3768F469346293 +:103AF0002107054618D014F0080118BF8021E207FD +:103B000048BF41F02001A30748BF41F040016007D2 +:103B100048BF41F48071202383F31188281DFFF7EB +:103B2000E9FE002383F31188E2050AD5202383F3FD +:103B300011884FF40071281DFFF7DCFE002383F38A +:103B400011884FF020094FF0000A14F0200838D1F6 +:103B50003B0616D54FF0200905F1380A200610D58E +:103B600089F31188504600F067F9002836DA0821F9 +:103B7000281DFFF7BFFE27F080033360002383F387 +:103B80001188790614D5620612D5202383F3118893 +:103B9000D5E913239A4208D12B6C33B11021281D8B +:103BA00027F04007FFF7A6FE3760002383F3118854 +:103BB000E30619D5AA6E1369B3B1BDE8F0475069A1 +:103BC000184789F31188B38C95F86410284619407A +:103BD00000F0CCF98AF31188F469B6E780B2308539 +:103BE00088F31188F469B9E7BDE8F08700F1604314 +:103BF00003F561430901C9B283F80013012200F003 +:103C00001F039A4043099B0003F1604303F561439E +:103C1000C3F880211A607047F8B5154682680669B6 +:103C2000AA420B46816938BF8568761AB5420446B8 +:103C30000BD218462A46FDF709FFA3692B44A3615E +:103C4000A3685B1BA3602846F8BD0CD91846324612 +:103C5000FDF7FCFEAF1BE1683A463044FDF7F6FE87 +:103C6000E3683B44EBE718462A46FDF7EFFEE368BE +:103C7000E5E7000083689342F7B51546044638BF70 +:103C80008568D0E90460361AB5420BD22A46FDF7A2 +:103C9000DDFE63692B446361A36828465B1BA36058 +:103CA00003B0F0BD0DD932460191FDF7CFFE019969 +:103CB000E068AF1B3A463144FDF7C8FEE3683B4479 +:103CC000E9E72A46FDF7C2FEE368E4E710B50A44D7 +:103CD0000024C361029B8460C0E90000C0E90511B3 +:103CE000C1600261036210BD08B5D0E9053293429C +:103CF00001D1826882B98268013282605A1C4261B5 +:103D00001970D0E904329A4224BFC368436100218C +:103D100000F0A0FA002008BD4FF0FF30FBE70000E4 +:103D200070B5202304460E4683F31188A568A5B11B +:103D3000A368A269013BA360531CA36115782269A3 +:103D4000934224BFE368A361E3690BB1204698471F +:103D5000002383F31188284607E03146204600F00F +:103D600069FA0028E2DA85F3118870BD2DE9F74F72 +:103D700004460E4617469846D0F81C904FF0200A8D +:103D80008AF311884FF0000B154665B12A4631467B +:103D90002046FFF741FF034660B94146204600F048 +:103DA00049FA0028F1D0002383F31188781B03B06F +:103DB000BDE8F08FB9F1000F03D001902046C8474D +:103DC000019B8BF31188ED1A1E448AF31188DCE7FE +:103DD000C0E90511C160C3611144009B8260C0E964 +:103DE0000000016103627047F8B504460D461646AF +:103DF000202383F31188A768A7B1A368013BA360C0 +:103E000063695A1C62611D70D4E904329A4224BF6E +:103E1000E3686361E3690BB120469847002080F3B3 +:103E2000118807E03146204600F004FA0028E2DA63 +:103E300087F31188F8BD0000D0E905239A4210B538 +:103E400001D182687AB98268013282605A1C82612B +:103E50001C7803699A4224BFC3688361002100F083 +:103E6000F9F9204610BD4FF0FF30FBE72DE9F74F81 +:103E700004460E4617469846D0F81C904FF0200A8C +:103E80008AF311884FF0000B154665B12A4631467A +:103E90002046FFF7EFFE034660B94146204600F09A +:103EA000C9F90028F1D0002383F31188781B03B0EF +:103EB000BDE8F08FB9F1000F03D001902046C8474C +:103EC000019B8BF31188ED1A1E448AF31188DCE7FD +:103ED000026843681143016003B11847704700004E +:103EE0001430FFF743BF00004FF0FF331430FFF7EB +:103EF0003DBF00003830FFF7B9BF00004FF0FF337F +:103F00003830FFF7B3BF00001430FFF709BF0000DF +:103F10004FF0FF311430FFF703BF00003830FFF7D8 +:103F200063BF00004FF0FF323830FFF75DBF000085 +:103F300000207047FFF7FEBC044B03600023C0E97C +:103F40000233436001230374704700BF64520008CA +:103F500010B52023044683F31188FFF755FD022393 +:103F60002374002383F3118810BD000038B5C369A2 +:103F700004460D461BB904210844FFF7A9FF294652 +:103F800004F11400FFF7B0FE002806DA201D4FF4FC +:103F90008061BDE83840FFF79BBF38BD024B00226F +:103FA000C3E900339A607047083700200023037488 +:103FB0008268054B1B6899689142FBD25A6803607E +:103FC00042601060586070470837002008B5202311 +:103FD00083F31188037C032B05D0042B0DD02BB960 +:103FE00083F3118808BD436900221A604FF0FF3344 +:103FF0004361FFF7DBFF0023F2E7D0E900321360F3 +:104000005A60F3E7002303748268054B1B689968C4 +:104010009142FBD85A680360426010605860704754 +:1040200008370020054B19690874186802681A607F +:104030005360186101230374FCF7D2BA08370020DB +:1040400030B54B1C0B4D87B0044610D02B690A4A83 +:1040500001A800F019F92046FFF7E4FF049B13B113 +:1040600001A800F04DF92B69586907B030BDFFF782 +:10407000D9FFF8E708370020CD3F000838B50C4DD0 +:1040800041612B6981689A689142044603D8BDE872 +:104090003840FFF78BBF1846FFF7B4FF01232C61B0 +:1040A000014623742046BDE83840FCF799BA00BFAA +:1040B00008370020044B1A681B6990689B68984277 +:1040C00094BF0020012070470837002010B5084C2D +:1040D000236820691A6822605460012223611A74DF +:1040E000FFF790FF01462069BDE81040FCF778BA61 +:1040F0000837002008B5FFF7DDFF18B1BDE808401C +:10410000FFF7E4BF08BD0000FFF7E0BFFEE70000D7 +:1041100010B50C4CFFF742FF00F0A8F80A498022C6 +:10412000204600F03DF8012344F8180C0374FFF713 +:1041300093FB002383F3118862B60448BDE8104066 +:1041400000F04EB8303700208C5200089C52000816 +:1041500008B572B6034B586200F072FA00F01EFB0D +:10416000FEE700BF0837002000F004B9EFF311802C +:1041700020B9EFF30583202282F3118870470000F5 +:1041800010B530B9EFF30584C4F3080414B180F31B +:10419000118810BDFFF7AEFF84F31188F9E7000026 +:1041A00082600222028270478368A3F17C0243F896 +:1041B0000C2C026943F83C2C426943F8382C074A1E +:1041C00043F81C2CC26843F8102C022203F8082C78 +:1041D000002203F8072CA3F118007047F905000826 +:1041E00010B5202383F31188FFF7DEFF002104467A +:1041F000FFF744FF002383F31188204610BD000021 +:10420000024B1B6958610F20FFF70CBF08370020D5 +:10421000202383F31188FFF7F3BF000008B50146A0 +:10422000202383F311880820FFF70AFF002383F37C +:10423000118808BD49B1064B42681B6918605A6075 +:10424000136043600420FFF7FBBE4FF0FF30704760 +:10425000083700200368984206D01A680260506050 +:1042600059611846FFF7A2BE70470000054B03F1E5 +:104270001402C3E905224FF0FF310022C3E90712FF +:10428000704700BF0837002070B51C4EC0E90323FB +:1042900005460C4600F0FCFA334653F8142F9A42B8 +:1042A0000DD13062C5E901242A600A2C2CBF001907 +:1042B0000A30C6E90555BDE8704000F0D7BA316A4A +:1042C000431AE31838BF1C469368A34202D9081961 +:1042D00000F0DAFA73699A6894420CD85A68AC60B4 +:1042E0002B606A6015609A685D60121B9A604FF0DF +:1042F000FF33F36170BD1B68A41AECE70837002098 +:1043000038B51B4C636998420DD0D0E90032136078 +:104310005A6000228168C2609A680A449A604FF02D +:10432000FF33E36138BD2246036842F8143F0021A1 +:1043300093425A60C16003D1BDE8384000F09EBA94 +:104340009A688168256A0A449A6000F0A1FA636954 +:104350009A68411B8A42E5D9AB181D1A092D206ABB +:1043600098BF01F10A02BDE83840104400F08CBA51 +:10437000083700202DE9F041184C002704F11406FD +:10438000656900F085FA236AAA68C11A8A4215D8BD +:1043900013442362D5E9003213605A606369D5F88B +:1043A0000C80EF60B34201D100F068FA87F3118806 +:1043B0002869C047202383F31188E1E76169B1428E +:1043C00009D013441B1ABDE8F0410A2B2CBFC018BA +:1043D0000A3000F059BABDE8F08100BF083700206C +:1043E0000C2303604FF0FF3070470000002070473F +:1043F000FEE70000704700004FF0FF3070470000FC +:10440000BFF34F8F024A1369DB03FCD4704700BF30 +:104410000020024008B5094B1B7873B9FFF7F0FF85 +:10442000074B5A69002ABFBF064A9A6002F18832D8 +:104430009A601A6822F480621A6008BD90380020E1 +:10444000002002402301674508B50B4B1B7893B948 +:10445000FFF7D6FF094B5A6942F000425A611A68C9 +:1044600042F480521A601A6822F480521A601A6864 +:1044700042F480621A6008BD90380020002002409B +:104480007F289ABF00F58030C002002070470000EE +:104490004FF4006070470000802070477F2808B507 +:1044A0000BD8FFF7EDFF00F500630268013204D17D +:1044B00004308342F9D1012008BD0020FCE7000050 +:1044C0007F2838B5044626D8FFF750FEFFF798FF3F +:1044D000FFF7A0FF114BF3221A6102225A615A69B9 +:1044E00042EAC4025A615A6942F480325A6105466E +:1044F0002046FFF785FF4FF40061FFF7C1FF00F092 +:1045000049F92846FFF7A0FFFFF73AFE2046BDE82D +:104510003840FFF7C3BF002038BD00BF0020024075 +:1045200040EA020313F007032DE9F04705460C4665 +:10453000164606D0324B40F2FB221A600020BDE83E +:10454000F08781182F4A91420CD92D4A4FF44071BF +:104550001160F3E72B1D1B686268934208D1083E87 +:1045600008350834072E19D92A6823689A42F1D0F1 +:10457000FFF7FCFDFFF74EFFFFF742FF04F10801D4 +:10458000214C4FF001084FF00009012EA1F108075E +:1045900008D8FFF759FFFFF7F3FD01E0002EE7D140 +:1045A0000120CCE7C4F81480AA4651F8083C4AF828 +:1045B000043B51F8043C6B60FFF722FFC4F81490F1 +:1045C0002A6851F8083C9A420ED00D4B40F2263230 +:1045D0001A600E4B1D600E4B1E600E4B1F60FFF7E6 +:1045E00033FFFFF7CDFDA9E7DAF800A051F8043C4E +:1045F0009A4501F10801E8D1083E0835C5E700BF3A +:104600008C38002000000408002002408038002080 +:104610008838002084380020084908B50B7828B174 +:104620001BB9FFF7F7FE01230B7008BD002BFCD070 +:10463000BDE808400870FFF707BF00BF90380020B2 +:104640004FF480314FF0005000F0A6B870B582B042 +:10465000FFF78CFD0E4E054600F01AF932689042C5 +:1046600037BF0C4A0B49516814682EBFD1E900418D +:10467000013151600419034641F1000128460191BE +:104680003360FFF77DFD0199204602B070BD00BF89 +:10469000943800209838002070B582B0FFF766FD8E +:1046A000104E054600F0F4F83268904237BF0E4ACB +:1046B0000D49516814682EBFD1E9004101315160A4 +:1046C000041941F100010346284601913360FFF7C8 +:1046D00057FD01994FF47A7200232046FBF768FDDD +:1046E00002B070BD943800209838002010B5024404 +:1046F000064BD2B2904200D110BD441C00B253F818 +:10470000200041F8040BE0B2F4E700BF502800405D +:10471000114B30B5D3F89040240409D4D3F890401D +:10472000C3F89040D3F8904044F40044C3F890405C +:104730000A4C236843F4807323600244084BD2B2CE +:10474000904200D130BD441C00B251F8045B43F8E4 +:104750002050E0B2F4E700BF0010024000700040BB +:104760005028004007B5012201A90020FFF7BEFF35 +:10477000019803B05DF804FB13B50446FFF7F2FFA0 +:10478000A04205D0012201A900200194FFF7C0FF3B +:1047900002B010BD70470000704700007047000075 +:1047A000074B45F255521A6002225A6040F6FF72DA +:1047B0009A604CF6CC421A60024B01221A70704784 +:1047C00000300040A4380020034B1B781BB1034B82 +:1047D0004AF6AA221A607047A43800200030004030 +:1047E000054B1A6832B902F1804202F50432D2F860 +:1047F00094201A60704700BFA0380020024B4FF48D +:104800000002C3F8942070470010024008B5FFF77B +:10481000E7FF024B1868C0F3407008BDA0380020C5 +:1048200070470000FEE700000A4B0B480B4A90421D +:104830000BD30B4BDA1C121AC11E22F003028B425F +:1048400038BF00220021FDF713B953F8041B40F8CC +:10485000041BECE74C5300083C3900203C39002095 +:104860003C3900207047000000F07AB84FF08043D8 +:10487000002258631A610222DA6070474FF08043C9 +:104880000022DA60704700004FF0804358637047A1 +:104890004FF08043586A7047264B2748DA6A42F047 +:1048A000070210B4DA62DA6A22F00702DA62DA6A20 +:1048B000DA6C42F00702DA64DA6E42F00702DA6676 +:1048C0004FF09042DB6E4FF0AA31002353604FF45B +:1048D000EE449160D0604FF6FF7050611462174C47 +:1048E00053621460164CC2F80434C2F80814C2F8BB +:1048F0000C444FF6F774C2F814444FF0EE44C2F87B +:10490000204447F29974C2F824440E4CC2F8004483 +:10491000C2F80438C2F80818C2F80C38C2F81408F3 +:10492000C2F82038C2F82438C2F800385DF8044BC9 +:1049300000F09CB80010024050010024A0010028A3 +:104940001050500050A0AA0008B500F035FAFFF74B +:10495000DFFBBDE80840FFF743BF000070470000E1 +:104960000F4B9A6D42F001029A659A6F42F0010274 +:104970009A670C4A9B6F936843F0010393604FF072 +:1049800080434F229A624FF0FF32DA6200229A612E +:104990005A63DA605A6001225A611A60704700BF98 +:1049A00000100240002004E04FF0804208B5116979 +:1049B000D3680B40D9B2C9439B07116107D52023A7 +:1049C00083F31188FFF7D0FB002383F3118808BD20 +:1049D00008B5244B4FF0FF319A6A99629A6A002217 +:1049E0009A62986AD86A60F00700D862D86A00F0C4 +:1049F0000700D862D86A186B1963186B1A63186BB2 +:104A0000986B60F080509863986B00F080509863CA +:104A1000986BD86BD963D86BDA63D86B186C196450 +:104A2000196C1A64196C996D41F080519965996FF0 +:104A300041F080519967996FD3F8901011F4407F3D +:104A40001EBF4FF48031C3F89010C3F89020D3F804 +:104A50009020C3F8902000F07FF9034B00225A60A9 +:104A600008BD00BF0010024000700040394B3A4AB8 +:104A70009A6501221A601A689007FCD500229A6094 +:104A80009A6812F00C0FFBD1344A4FF40071116098 +:104A900051694905FCD41A6842F480321A601A68D8 +:104AA0009203FCD52D490A6842F480720A602C4AB0 +:104AB0004FF4E06111601A6842F060021A601A68EF +:104AC00042F008021A601A689007FCD59A6812F042 +:104AD0000C0FFBD1D3F8942042F4C062C3F89420A9 +:104AE000204ADA601A6842F080721A601A689101EE +:104AF000FCD51D4A1A611A6842F080621A601A6871 +:104B00001201FCD500229A601549184AC3F8882082 +:104B10000A6822F0070242F004020A600A6802F002 +:104B20000702042AFAD19A6842F003029A609A684E +:104B300002F00C020C2AFAD11A6E42F001021A6637 +:104B4000D3F8802042F00102C3F88020D3F88030EF +:104B5000704700BF001002400004001000700040C9 +:104B60000020024003140001000C100055550134D0 +:104B7000074A08B5536903F00103536123B1054A9D +:104B800013680BB150689847BDE80840FEF788BE2F +:104B900000040140A8380020074A08B5536903F013 +:104BA0000203536123B1054A93680BB1D06898475B +:104BB000BDE80840FEF774BE00040140A83800209C +:104BC000074A08B5536903F00403536123B1054A4A +:104BD00013690BB150699847BDE80840FEF760BE05 +:104BE00000040140A8380020074A08B5536903F0C3 +:104BF0000803536123B1054A93690BB1D069984703 +:104C0000BDE80840FEF74CBE00040140A838002073 +:104C1000074A08B5536903F01003536123B1054AED +:104C2000136A0BB1506A9847BDE80840FEF738BEDA +:104C300000040140A8380020164B10B55C6904F44C +:104C400078725A61A30604D5134A936A0BB1D06AED +:104C50009847600604D5104A136B0BB1506B984708 +:104C6000210604D50C4A936B0BB1D06B9847E20533 +:104C700004D5094A136C0BB1506C9847A30504D5B1 +:104C8000054A936C0BB1D06C9847BDE81040FEF715 +:104C900007BE00BF00040140A8380020194B10B522 +:104CA0005C6904F47C425A61620504D5164A136DAE +:104CB0000BB1506D9847230504D5134A936D0BB182 +:104CC000D06D9847E00404D50F4A136E0BB1506EB7 +:104CD0009847A10404D50C4A936E0BB1D06E984747 +:104CE000620404D5084A136F0BB1506F9847230430 +:104CF00004D5054A936F0BB1D06F9847BDE81040BB +:104D0000FEF7CEBD00040140A838002008B50348D6 +:104D1000FEF7E8FEBDE80840FEF7C2BD04350020FE +:104D200008B50348FEF7DEFEBDE80840FEF7B8BD53 +:104D30007035002008B50348FEF7D4FEBDE80840F2 +:104D4000FEF7AEBDDC35002008B5FFF72DFEBDE84F +:104D50000840FEF7A5BD0000062108B50846FEF78D +:104D600045FF06210720FEF741FF06210820FEF738 +:104D70003DFF06210920FEF739FF06210A20FEF734 +:104D800035FF06211720FEF731FF06212820FEF708 +:104D90002DFF07211C20FEF729FF0C212520FEF7FF +:104DA00025FF0C212620FEF721FFBDE808400C213D +:104DB0002720FEF71BBF000008B5FFF709FE00F033 +:104DC00009F8FFF7B7F8FFF7C9FDBDE80840FFF79E +:104DD0004BBD00000023054A19460133102BC2E9E0 +:104DE000001102F10802F8D1704700BFA838002076 +:104DF0000B460146184600F025B8000000F038B810 +:104E0000012838BF012010B50446204600F028F8DC +:104E100030B900F007F808B900F00CF88047F4E763 +:104E200010BD0000024B1868BFF35B8F704700BFD6 +:104E30002839002008B5062000F032F90120FFF7DC +:104E4000D7FA000010B5054C13462CB10A460146AE +:104E50000220AFF3008010BD2046FCE700000000F8 +:104E6000024B0146186800F089B800BF28110020E5 +:104E7000024B0146186800F035B800BF2811002029 +:104E800010B501390244904201D1002005E00378B9 +:104E900011F8014FA34201D0181B10BD0130F2E7F9 +:104EA0002DE9F041A3B1C91A17780144044603F172 +:104EB000FF3C8C42204601D9002009E00578BD4224 +:104EC00004F10104F5D10CEB0405D618A54201D17B +:104ED000BDE8F08115F8018D16F801EDF045F5D02B +:104EE000E7E7000037B5002944D051F8043C0190B1 +:104EF000002BA1F10404B8BFE41800F0F5F81E4A35 +:104F00000198136833B96360146003B0BDE83040A2 +:104F100000F0F0B8A34208D9256861198B4201BF9F +:104F200019685B6849192160EDE71A465B680BB1A7 +:104F3000A342FAD911685518A5420BD1246821441F +:104F40005418A3421160E0D11C685B68536021448F +:104F50001160DAE702D90C230360D6E725686119EE +:104F60008B4204BF19685B68636004BF4919216004 +:104F70005460CAE703B030BD2C390020F8B5CD1C11 +:104F800025F0030508350C2D38BF0C25002D0646ED +:104F900001DBA94203D90C2333600020F8BD00F0E7 +:104FA000A3F821490A6814469CB9204F3B6823B9ED +:104FB0002146304600F03CF838602946304600F083 +:104FC00037F8431C23D10C233360304600F092F8AD +:104FD000E3E723685B1B17D40B2B03D923601C4426 +:104FE000256004E06368A2420CBF0B60536030464A +:104FF00000F080F804F10B00231D20F00700C21A16 +:10500000CCD01B1AA350C9E722466468CCE7C41C65 +:1050100024F00304A042E3D0211A304600F008F83F +:105020000130DDD1CFE700BF2C390020303900201E +:1050300038B5064D0023044608462B60FFF7D0F92B +:10504000431C02D12B6803B1236038BD34390020E2 +:105050001F2938B504460D4604D9162303604FF0C6 +:10506000FF3038BD426C12B152F821304BB92046A6 +:1050700000F030F82A4601462046BDE8384000F0EE +:1050800017B8012B0AD0591C03D116230360012045 +:10509000E7E7002442F82540284698470020E0E74B +:1050A000024B01461868FFF7D3BF00BF281100204C +:1050B00038B5074D00230446084611462B60FFF71C +:1050C0009BF9431C02D12B6803B1236038BD00BF9C +:1050D00034390020FFF78AB9034611F8012B03F891 +:1050E000012B002AF9D17047014800F009B800BF30 +:1050F00038390020014800F005B800BF38390020D9 +:1051000070470000704700006F72672E617264750F +:1051100070696C6F742E4D6174656B4C3433312D36 +:105120004169727370656564000000004E6F206114 +:105130007070207369670A00426164206677206C92 +:10514000656E6774682025750A0042616420626F8D +:105150006172645F69642025752073686F756C6483 +:105160002062652025750A0042616420667720640C +:10517000657363726970746F72206C656E677468B2 +:105180002025750A004261642061707020435243FB +:10519000203078253038783A30782530387820300B +:1051A00078253038783A3078253038780A00476FDB +:1051B0006F64206669726D776172650A0040A2E4CF +:1051C000F16468910600000053544D33324C343F73 +:1051D0003F0000000435002070350020DC35002041 +:1051E0004261642043414E496661636520696E6493 +:1051F00065782E0080000000008000000000800024 +:1052000000000000000000009D1B0008892300082A +:10521000E9220008AD1B0008E51B0008E11D00089D +:10522000B11B0008C51B0008B51B0008B91B00080E +:10523000C11B0008BD1B0008091D0008C91B000890 +:10524000F5250008D91B0008DD1C000800960000A9 +:10525000000000000000000000000000000000004E +:105260000000000000000000FD3E0008E93E0008CC +:10527000253F0008113F00081D3F0008093F0008B6 +:10528000F53E0008E13E0008313F00086D61696E9F +:105290000000000069646C65000000009452000882 +:1052A0004837002080380020010000000D41000830 +:1052B000000000002CAFFF7F010000000000000094 +:1052C0002604000000000000006003000000000051 +:1052D000FE2A0100D2040000FF00000000000000D0 +:1052E000C85100083F0000002C1100200000000001 +:1052F00000000000000000000000000000000000AE +:10530000000000000000000000000000000000009D +:10531000000000000000000000000000000000008D +:10532000000000000000000000000000000000007D +:10533000000000000000000000000000000000006D +:0C53400000000000000000000000000061 +:00000001FF diff --git a/Tools/bootloaders/MatekL431-DShot_bl.bin b/Tools/bootloaders/MatekL431-DShot_bl.bin new file mode 100755 index 00000000000..c83b0b8cebf Binary files /dev/null and b/Tools/bootloaders/MatekL431-DShot_bl.bin differ diff --git a/Tools/bootloaders/MatekL431-EFI_bl.bin b/Tools/bootloaders/MatekL431-EFI_bl.bin new file mode 100755 index 00000000000..d57c47b4058 Binary files /dev/null and b/Tools/bootloaders/MatekL431-EFI_bl.bin differ diff --git a/Tools/bootloaders/MatekL431-Periph_bl.bin b/Tools/bootloaders/MatekL431-Periph_bl.bin new file mode 100755 index 00000000000..e8b7eb46b6b Binary files /dev/null and b/Tools/bootloaders/MatekL431-Periph_bl.bin differ diff --git a/Tools/bootloaders/MatekL431-Periph_bl.hex b/Tools/bootloaders/MatekL431-Periph_bl.hex new file mode 100644 index 00000000000..9fc97035105 --- /dev/null +++ b/Tools/bootloaders/MatekL431-Periph_bl.hex @@ -0,0 +1,1335 @@ +:020000040800F2 +:1000000000090020B5040008E5290008652900085A +:10001000BD2900086529000891290008B7040008D7 +:10002000B7040008B7040008B7040008393800080E +:10003000B7040008B7040008B7040008B7040008B4 +:10004000B7040008B7040008B7040008B7040008A4 +:10005000B7040008B7040008714B0008994B00086A +:10006000C14B0008E94B0008114C0008B704000818 +:10007000B7040008B7040008B7040008B704000874 +:10008000B7040008B7040008B7040008A125000859 +:10009000CD250008DD250008B7040008394C00080C +:1000A000B7040008B7040008B7040008B704000844 +:1000B000494D0008B7040008B7040008B704000859 +:1000C000B7040008B7040008B7040008B704000824 +:1000D000B70400080D4D0008214D0008354D0008FB +:1000E0009D4C0008B7040008B7040008B7040008D6 +:1000F000B7040008B7040008B7040008B7040008F4 +:10010000B7040008B7040008B7040008B7040008E3 +:10011000B7040008B7040008B7040008B7040008D3 +:10012000B7040008B7040008B7040008B7040008C3 +:10013000B7040008B7040008B7040008B7040008B3 +:10014000B7040008B7040008B7040008B7040008A3 +:10015000B7040008B7040008B7040008B704000893 +:10016000B7040008B7040008B7040008B704000883 +:10017000B7040008B7040008B7040008B704000873 +:10018000B7040008B7040008B7040008B704000863 +:10019000B7040008B7040008B7040008B704000853 +:1001A000051800080000000000000000000000002A +:1001B00053B94AB9002908BF00281CBF4FF0FF31CE +:1001C0004FF0FF3000F074B9ADF1080C6DE904CECA +:1001D00000F006F8DDF804E0DDE9022304B0704722 +:1001E0002DE9F047089D04468E46002B4DD18A42EA +:1001F000944669D9B2FA82F252B101FA02F3C2F11D +:10020000200120FA01F10CFA02FC41EA030E9440AD +:100210004FEA1C48210CBEFBF8F61FFA8CF708FBCE +:1002200016E341EA034306FB07F199420AD91CEBA6 +:10023000030306F1FF3080F01F81994240F21C81D8 +:10024000023E63445B1AA4B2B3FBF8F008FB103320 +:1002500044EA034400FB07F7A7420AD91CEB040455 +:1002600000F1FF3380F00A81A74240F20781644425 +:10027000023840EA0640E41B00261DB1D4400023AA +:10028000C5E900433146BDE8F0878B4209D9002D0E +:1002900000F0EF800026C5E9000130463146BDE898 +:1002A000F087B3FA83F6002E4AD18B4202D3824202 +:1002B00000F2F980841A61EB030301209E46002DB1 +:1002C000E0D0C5E9004EDDE702B9FFDEB2FA82F206 +:1002D000002A40F09280A1EB0C014FEA1C471FFA64 +:1002E0008CFE0126200CB1FBF7F307FB131140EA4B +:1002F00001410EFB03F0884208D91CEB010103F118 +:10030000FF3802D2884200F2CB804346091AA4B2D9 +:10031000B1FBF7F007FB101144EA01440EFB00FEAD +:10032000A64508D91CEB040400F1FF3102D2A64512 +:1003300000F2BB800846A4EB0E0440EA03409CE7B1 +:10034000C6F12007B34022FA07FC4CEA030C20FA5E +:1003500007F401FA06F31C43F9404FEA1C4900FA7E +:1003600006F3B1FBF9F8200C1FFA8CFE09FB1811FB +:1003700040EA014108FB0EF0884202FA06F20BD96E +:100380001CEB010108F1FF3A80F08880884240F2BE +:100390008580A8F102086144091AA4B2B1FBF9F002 +:1003A00009FB101144EA014100FB0EFE8E4508D9FD +:1003B0001CEB010100F1FF346CD28E456AD9023882 +:1003C000614440EA0840A0FB0294A1EB0E01A14267 +:1003D000C846A64656D353D05DB1B3EB080261EBD5 +:1003E0000E0101FA07F722FA06F3F1401F43C5E9AF +:1003F000007100263146BDE8F087C2F12003D840E5 +:100400000CFA02FC21FA03F3914001434FEA1C4726 +:100410001FFA8CFEB3FBF7F007FB10360B0C43EA18 +:10042000064300FB0EF69E4204FA02F408D91CEBC8 +:10043000030300F1FF382FD29E422DD902386344C6 +:100440009B1B89B2B3FBF7F607FB163341EA034166 +:1004500006FB0EF38B4208D91CEB010106F1FF38B5 +:1004600016D28B4214D9023E6144C91A46EA0046AC +:1004700038E72E46284605E70646E3E61846F8E63E +:100480004B45A9D2B9EB020864EB0C0E0138A3E787 +:100490004646EAE7204694E74046D1E7D0467BE768 +:1004A000023B614432E7304609E76444023842E7E0 +:1004B000704700BF02E000F000F8FEE772B63A486D +:1004C00080F30888394880F3098839484EF6085186 +:1004D000CEF20001086040F20000CCF200004EF6BF +:1004E0003471CEF200010860BFF34F8FBFF36F8FFE +:1004F00040F20000C0F2F0004EF68851CEF200014A +:100500000860BFF34F8FBFF36F8F4FF00000E1EE35 +:10051000100A4EF63C71CEF200010860062080F30E +:100520001488BFF36F8F04F09DF904F079F904F09B +:10053000B3F94FF055301F491B4A91423CBF41F877 +:10054000040BFAE71C49194A91423CBF41F8040BDD +:10055000FAE71A491A4A1B4B9A423EBF51F8040B5C +:1005600042F8040BF8E700201749184A91423CBFB3 +:1005700041F8040BFAE704F057F904F0E5F9144CDC +:10058000144DAC4203DA54F8041B8847F9E700F035 +:1005900041F8114C114DAC4203DA54F8041B884762 +:1005A000F9E704F03FB90000000900200011002025 +:1005B000000000080001002000090020B8520008D7 +:1005C000001100208C110020901100203C390020E7 +:1005D000A0010008A4010008A4010008A40100086B +:1005E0002DE9F04F2DED108AC1F80CD0C3689D465F +:1005F000BDEC108ABDE8F08F002383F311882846F4 +:10060000A047002003F004FEFEE703F07DFD00DFBD +:10061000FEE70000F8B504F0A5F8074604F0F6F888 +:100620000546A0BB1F4B9F4231D001339F4231D0C2 +:100630001D4B27F0FF029A422FD1F8B200F030FD97 +:100640002E4642F2107400F035FF08B10024264611 +:1006500000F02CFD08B90646044635B1134B9F4205 +:1006600003D004F0CBF800242646002004F084F8E0 +:100670000EB100F063F801F051FA00F03FFF01F015 +:100680003DF9204600F0A8F800F058F8F9E72E46AA +:100690000024D8E704460126D5E706464FF47A74CD +:1006A000D1E700BF010007B0000008B0263A09B04A +:1006B00008B501F0EFF8A0F120035842584108BDF9 +:1006C00007B541F21203022101A8ADF8043001F090 +:1006D000FFF803B05DF804FB10B5202383F3118805 +:1006E0001248C3680BB103F00BFE114A0F480023F8 +:1006F0004FF47A7103F0C8FD002383F311880D4C89 +:10070000236813B12368013B2360636813B16368F6 +:10071000013B6360084B1B7833B9636823B902203F +:1007200001F08AF93223636010BD00BF90110020F0 +:10073000D9060008AC120020A4110020214B224A47 +:1007400010B51C46196801313BD004339342F9D1EE +:100750006268A24235D31D4B9B6803F1006303F529 +:1007600020439A422DD204F01BF804F02DF800200B +:1007700001F0DEF8164B0220187001F055F9154B08 +:100780009A6D00229A65996F9A67996FD96DDA65AB +:10079000D96FDA67D96F196E1A66D3F88010C3F86B +:1007A0008020D3F8803072B64FF0E0232021C3F8C8 +:1007B000084DD4E9003281F311889D4683F30888FF +:1007C000104710BD00A0000820A000080011002064 +:1007D000A4110020001002402DE9F04F93B0AC4B63 +:1007E00000902022FF210AA89D6801F041F9A94A42 +:1007F0001378A3B9A8480121C3601170202383F3A3 +:100800001188C3680BB103F07BFDA44AA248002302 +:100810004FF47A7103F038FD002383F31188009BB5 +:100820009F4A03B113609F49009C00230B705360E3 +:1008300098469B461E469A46012001F0F5F824B1E1 +:10084000974B1B68002B00F01C82002001F022F85F +:100850000390039B002B01DA00F094FE039B002B16 +:10086000EDDB012001F0D6F8039B213B162BE3D8EA +:1008700001A252F823F000BFD5080008FD080008C7 +:1008800091090008390800083908000839080008EB +:10089000250A0008F70B0008110B0008730B00086D +:1008A0009B0B0008C10B000839080008D30B000897 +:1008B00039080008450C00087509000839080008C7 +:1008C000890C0008E10800087509000839080008CB +:1008D000730B00080220FFF7EBFE002840F0FB81BD +:1008E000009B0221B8F1000F08BF1C4605A841F289 +:1008F0001233ADF8143000F0EBFF9DE74FF47A703F +:1009000000F0C8FF071EEBDB0220FFF7D1FE002836 +:10091000E6D0013F052F00F2E081DFE807F0030A8F +:100920000D10133605230593042105A800F0D0FF10 +:1009300017E057480421F9E75B480421F6E75B48D4 +:100940000421F3E74FF01C09484600F0F3FF09F1DA +:1009500004090590042105A800F0BAFFB9F12C0F95 +:10096000F2D1012000FA07F747EA0B0B5FFA8BFB85 +:100970004FF0000A01F0C8F826B10BF00B030B2B67 +:1009800008BF0024FFF79CFE56E749480421CDE745 +:10099000002EA5D00BF00B030B2BA1D10220FFF7EB +:1009A00087FE074600289BD001203E4E00F0C0FF86 +:1009B0000220307001F038F84FF000085FFA88F933 +:1009C000484600F0C5FF044690B1484600F0D0FF0D +:1009D00008F101080028F1D1B846044641F212138B +:1009E000022105A8ADF814303E4600F071FF23E760 +:1009F00001230220337001F00DF82546244B9B683B +:100A0000AB4207D9284600F095FF013040F06881DD +:100A10000435F3E7234B00251D70214BB8465D607C +:100A20003E46A7E7002E3FF45BAF0BF00B030B2B0A +:100A30007FF456AF1B4B0220187000F0F5FF3220F8 +:100A400000F028FFB0F10009FFF64AAF19F00307E4 +:100A50007FF446AF0E4A926809EB050393423FF6D6 +:100A60003FAFB9F5807F3FF73BAF124B0193B945DC +:100A700022DD4FF47A7000F00DFF0390039A002AF4 +:100A8000FFF62EAF019B039A03F8012B0137EDE728 +:100A900000110020A812002090110020D9060008A3 +:100AA000AC120020A4110020041100200811002025 +:100AB0000C110020A8110020C820FFF7F9FD0746FF +:100AC00000283FF40DAF1F2D11D8C5F120024A4573 +:100AD0000AAB25F0030028BF4A4683490192184417 +:100AE00000F0B4FF019A8048FF2100F0C1FF4FEAF7 +:100AF000A9037D490193C9F38702284600F0C0FF8E +:100B0000064600283FF46AAF019B05EB830531E7F9 +:100B10000220FFF7CDFD00283FF4E2AE00F044FFD5 +:100B200000283FF4DDAE0027B946704B9B68BB42FE +:100B300018D91F2F11D80A9B01330ED027F00303B9 +:100B400012AA134453F8203C05934846042205A9F1 +:100B500001F056FF04378146E7E7384600F0EAFE29 +:100B60000590F2E7CDF81490042105A800F0B0FE3E +:100B700000E70023642104A8049300F09FFE0028EE +:100B80007FF4AEAE0220FFF793FD00283FF4A8AE3D +:100B9000049800F0FFFE0590E6E70023642104A816 +:100BA000049300F08BFE00287FF49AAE0220FFF73A +:100BB0007FFD00283FF494AE049800F0EDFEEAE7D4 +:100BC0000220FFF775FD00283FF48AAE00F0FCFE1E +:100BD000E1E70220FFF76CFD00283FF481AE05A994 +:100BE000142000F0F7FE04210746049004A800F04A +:100BF0006FFE3946B9E7322000F04CFE071EFFF6C3 +:100C00006FAEBB077FF46CAE384A926807EB0A03FD +:100C100093423FF665AE0220FFF74AFD00283FF4FD +:100C20005FAE27F003075744BA453FF4A3AE5046E2 +:100C300000F080FE0421059005A800F049FE0AF1AD +:100C4000040AF1E74FF47A70FFF732FD00283FF411 +:100C500047AE00F0A9FE002844D00A9B01330BD018 +:100C600008220AA9002000F00BFF00283AD0202219 +:100C7000FF210AA800F0FCFEFFF722FD1C4803F04C +:100C8000CDFA13B0BDE8F08F002E3FF429AE0BF083 +:100C90000B030B2B7FF424AE0023642105A80593DE +:100CA00000F00CFE074600287FF41AAE0220FFF782 +:100CB000FFFC814600283FF413AEFFF701FD41F22F +:100CC000883003F0ABFA059800F042FF4E4600F082 +:100CD0001BFF3C46B0E506464CE64FF0000AFFE538 +:100CE000B8467BE6374679E6A811002000110020BF +:100CF000A0860100094A136849F2690099B21B0CE9 +:100D000000FB01331360064B186844F2506182B255 +:100D1000000C01FB0200186080B270471411002023 +:100D20001011002010B500211022044600F0A0FE92 +:100D3000034B03CB206061601868A06010BD00BF4A +:100D40009075FF1F2DE9F043224DBBB001F052FE1C +:100D5000AB6840F2ED22C31A934232D906AFA860C5 +:100D60002B4628220021384602F022FB05F10E0016 +:100D700000F076FE002604465FFA80F905F10E08C1 +:100D8000F3B2F100994501F1280107D908EB0603F8 +:100D90000822384602F00CFB0136F1E70823012255 +:100DA000CDE9023205340C4B0193A4B230230093F9 +:100DB000CDE9047405A3D3E90023297B074802F099 +:100DC0000FF93BB0BDE8F083AFF3008078F6339FB6 +:100DD00093CACD8DC8330020D5330020CC2200200B +:100DE00070B50D4614461E4602F090F850B9022E1A +:100DF00010D1012C0ED112A3D3E90023C5E90023A1 +:100E0000012007E0282C10D005D8012C09D0052C92 +:100E10000FD0002070BD302CFBD10BA3D3E90023F1 +:100E2000ECE70BA3D3E90023E8E70BA3D3E9002306 +:100E3000E4E70BA3D3E90023E0E700BFAFF30080B2 +:100E4000401DA12026812A0B78F6339F93CACD8DB1 +:100E50009E6AC421818A46EE26417272DF25D7B789 +:100E6000F017304A39059E5613B504462346084606 +:100E700020220021019002F09BFA22790198032A96 +:100E8000234628BF032203F8042F2021022202F068 +:100E90008FFA62790198072A234628BF072203F8B0 +:100EA000052F2221032202F083FAA2790198072A52 +:100EB000234628BF072203F8062F2521032202F02C +:100EC00077FA019804F108031022282102F070FA41 +:100ED000382002B010BD00002DE9F04FADF5017DC6 +:100EE00021AD0EAE40F2751280460F4622A80021B9 +:100EF000296000F0BDFD48220021304600F0B8FD19 +:100F000001F078FD564B4FF47A72B0FBF2F01860A6 +:100F100093E80700012386E807000DF15A003382A9 +:100F2000FFF700FF42F20463338406AB18464D49D5 +:100F300004F0D2F81E2230642946304686F83C2060 +:100F4000FFF792FF12AB044601460822284602F042 +:100F50002FFA0822A1180DF14903284602F028FAB9 +:100F60000DF14A03082204F11001284602F020FA8C +:100F700013AB202204F11801284602F019FA14AB31 +:100F8000402204F13801284602F012FA16AB08227A +:100F900004F17801284602F00BFA0DF159030822FA +:100FA00004F18001284602F003FA04F1880A0DF1E9 +:100FB0005A0904F5847B4B465146082228460AF11B +:100FC000080A02F0F5F9D34509F10109F3D11BAB89 +:100FD00008225946284602F0EBF904F588744FF0D0 +:100FE000000996F834304B450AD9B36B21464B447F +:100FF0000822284602F0DCF9083409F10109F0E77B +:101000004FF0000996F83C304B4504EBC90108D974 +:10101000336C08224B44284602F0CAF909F1010951 +:10102000F0E700230393BB7E0293073107F1190316 +:101030000193C1F3CF010123CDE904510093F97E5F +:1010400005A3D3E90023404601F0CAFF0DF5017D59 +:10105000BDE8F08FAFF300809E6AC421818A46EE1E +:10106000B41200200851000810B50A4B0A4A1A6051 +:1010700003F5805393F860203AB9DC6D2CB120461B +:1010800001F036FB204603F0B9FEBDE810400348EE +:1010900001F02EBBF822002004520008403300204B +:1010A000014B1870704700BFC0120020F0B5334BE1 +:1010B0001C7B85B034B1324B0E221A8100242046AD +:1010C00005B0F0BD2F4A1068516802AB03C3082376 +:1010D0002D492E480DEB030203F0E2FE054630B920 +:1010E000274B2B480A221A8101F080FAE6E70169B2 +:1010F000B1F5583F06D9224B26480B221A8101F040 +:1011000075FADCE7438B40F22642934207D01C4934 +:101110000C2008811946204801F068FACFE71F4AE1 +:10112000024402F11003994204D2154B1C481022CC +:101130001A81E4E710398E1A2046144901F060FC48 +:101140003246074605F11801204601F059FCAB680C +:101150009F4202D1EB6898420AD0094B0D221A81B6 +:101160000090D5E902123B460E4801F03FFAA5E790 +:101170000D4801F03BFA0124A1E700BFC83300206D +:10118000B4120020B9510008DC5F030000A0000881 +:101190002851000834510008465100080860FFF744 +:1011A0006451000881510008AA5100082DE9F04F50 +:1011B000ADB006AF80460C4601F0A8FE05460028FB +:1011C0005AD1237E022B1BD1E38A012B18D101F0C7 +:1011D00011FC0646FFF78EFD03464FF4C870DFF89A +:1011E000D092B3FBF0F206F5167602FB103316FA36 +:1011F00083F3C9F80030E37E33B9A84B00221A709C +:101200009C37BD46BDE8F08FA38AEEB2013BB342E6 +:1012100005F101050BD93B1D1E44E9000096002392 +:10122000082201F0F801204601F086FFECE707F103 +:101230001400FFF777FD324607F11401381D03F063 +:101240001FFE0028D9D10F2E08D8944B1E70D9F854 +:101250000030A3F51673C9F80030D1E7FB1CF87015 +:101260000146009307220346204601F065FFF97806 +:10127000404601F043FEC3E7E38A282B26D010D86E +:10128000012B1ED0052BBBD1BFF34F8F8449854B5B +:10129000CA6802F4E0621343CB60BFF34F8F00BF14 +:1012A000FDE7302BACD1637E7F4D01336A7BDBB22F +:1012B0009342E94603D1E27E2B7B9A4265D0CD462C +:1012C0009EE721464046FFF707FE99E7A38A013BC8 +:1012D0009BB2C92B94D8744D2E7B26BB05F10C0311 +:1012E0000093082233463146204601F025FF731C47 +:1012F000F2B2D9001E46A38A013B9A4205DA0E32A9 +:101300002A44009200230822EEE700230022C5E9C8 +:1013100000230023AB6085F8D730C5F8D8302B7B8D +:101320000BB9E37E2B73002507F114093B1D08223E +:1013300029464846C7E90155FD6002F039F83B7A75 +:1013400005F1010AAB424FEACA0608D9FB68082238 +:101350002B443146484602F02BF85546EFE7C6F3DA +:10136000CF06E17ECDE9049600230393A37E02938A +:10137000193428230093019446A3D3E9002340465F +:1013800001F02EFEFFF7DEFC3AE74FF0000807F110 +:101390001403A7F81480102200934146012320462D +:1013A00001F0CAFEA68A023EB6B2F31C9B109B0057 +:1013B0000733DB08A9EBC3039D460DF1180A1FFA9A +:1013C00088F34FEAC801B34201F110010AD20AEBD7 +:1013D0000803009308220023204601F0ADFE08F127 +:1013E0000108ECE795F8D70000F0B2FAD5F8D8304C +:1013F00004461BB995F8D70000F0BAFAD5F8D830F2 +:1014000033449C4204D295F8D700013000F0B0FA82 +:101410004FEA960B4FF000081FFA88F18B45D5E98B +:10142000003209D90AEB880103EB8800012200F0A1 +:1014300027FB08F10108EFE7F31842F10002C5E9C4 +:101440000032D5F8D83095F8D70006EB0308C5F878 +:10145000D88000F07DFA804509D395F8D730D5F8CB +:10146000D8000133001B85F8D730C5F8D800FF2E0F +:1014700008D800232B7300F097FAFFF717FE08B186 +:10148000FFF75CF92B68094A9B0A0133138100239B +:10149000AB6014E726417272DF25D7B7C522002062 +:1014A00000ED00E00400FA05C8330020B41200206B +:1014B000C822002010B54FF000540C4B22689A420D +:1014C00011D10B4B627D1A700A48237D03730A49C0 +:1014D000C9220E3000F0BAFAE0220021204600F0C6 +:1014E000C7FA012010BD0020FCE700BF9AAD44C53B +:1014F000C0120020C83300201600002037B5184D58 +:1015000018491948022301226B7100F03DFF0023A6 +:101510000193164B164900931648174B4FF480520F +:1015200001F0C6FC154B197811B1124801F0E6FC28 +:1015300001F060FA0446FFF7DDFB4FF4C873B0FB1F +:10154000F3F202FB130304F5167010FA83F00C4B50 +:10155000186003F05BF908B10F232B8103B030BD95 +:10156000B412002040420F00F8220020E10D0008D4 +:10157000C4120020CC220020AD110008C0120020AF +:10158000C82200202DE9F04F2DED028B0FF26429C7 +:10159000D9E900898D4C93B08D4E8E4F204601F0D5 +:1015A00083FD034660B30025CDE90F550E95ADF8D8 +:1015B0004450027B8DF8442099684068DFF83CA2D3 +:1015C0000FAA03C21B6843F000430E9301F014FA04 +:1015D000821941F1000300950EA9384600F002FB84 +:1015E000A84205DD204601F063FD8AF80050D5E7EA +:1015F0009AF80030072B00F2B68001338AF80030E9 +:101600000BAE9FED6E8B0023724FDFF8F4A10A93AF +:10161000ADF834300B9373604FF0000B5B468DEDEB +:10162000008B01250DF11D0207A938468DF81C50CD +:101630008DF81DB000F058FE9DF81C30002B40F0D6 +:101640009680204601F062FC0646002845D1624F94 +:1016500001F0D0F93B6898423FD301F0CBF98246C4 +:10166000FFF748FB4FF4C8730AF5167AB0FBF3F2A4 +:1016700002FB13031AFA83F33B60584F97F800B04C +:10168000CBF1100ABBF1000F14BF33462B465FFAB3 +:101690008AFA0EA88DF82830FFF744FBBAF1060F3E +:1016A00028BF4FF0060A0EAB03EB0B0152460DF1BB +:1016B000290000F0CBF90AAB0393182302930AF137 +:1016C0000102474BD2B2CDE90053049220463DA31C +:1016D000D3E9002301F01CFC3E7001F08BF9414A74 +:1016E000414D1368C31AB3F57A7F2FD3106001F010 +:1016F00083F902460B46204601F0E4FC204601F047 +:1017000005FC18B32B7B394E002B14BF0323022397 +:10171000737101F06FF90EAF4FF47A733946B0FB75 +:10172000F3F030603046FFF79FFB18230730029339 +:101730002F4B0193C0F3CF0040F25513CDE9037056 +:10174000009342464B46204601F0E2FB2B7B2BB137 +:10175000FFF7F8FA2B7B002B7FF41EAF13B0BDEC24 +:10176000028BBDE8F08F204601F0A2FC48E7DAF8D2 +:10177000143083F00803CAF81430594610220EA81A +:1017800000F076F90DF11E0308AA0AA9384600F008 +:1017900027FB96E803000FAB83E803009DF8343085 +:1017A0008DF844300A9B0E930EA9DDE908232046EC +:1017B00001F046FE30E700BFAFF3008000000000FC +:1017C00000000000401DA12026812A0BCC22002011 +:1017D00040420F00F8220020C8220020C52200202D +:1017E000C4220020A8340020C8330020B4120020F6 +:1017F000AC340020F1C6A7C1D068080FAD3400207A +:101800000004004808B5054800F084FBBDE8084026 +:10181000034A0449002003F0EBBA00BFF82200207D +:1018200000350020691000082DE9F84F4FF47A7355 +:10183000DFF85880DFF8589006460D4602FB03F7A4 +:10184000002498F900305A1C5FFA84FA01D0A342B0 +:1018500010D159F8240003682A46D3F820B0314645 +:101860003B46D847854205D1074B012083F800A0AD +:10187000BDE8F88F0134032CE3D14FF4FA7002F085 +:10188000CDFC0020F4E700BFF43400201811002044 +:10189000D051000807B50023024601210DF10700D1 +:1018A0008DF80730FFF7C0FF20B19DF8070003B0A7 +:1018B0005DF804FB4FF0FF30F9E700000A4608B579 +:1018C0000421FFF7B1FF80F00100C0B2404208BD23 +:1018D00030B4074B0A461978064B53F82140236869 +:1018E000DD69054B0146AC46204630BC604700BF71 +:1018F000F4340020D0510008A086010070B502F039 +:10190000CBFD094E094D308000242868338883427E +:1019100008D902F0BDFD2B6804440133B4F5204F13 +:101920002B60F2D370BD00BFF6340020B03400202D +:1019300002F072BE00F1006000F5204000687047C0 +:1019400000F10060920000F5204002F0E9BD0000C7 +:10195000054B1A68054B1B889B1A834202D9104419 +:1019600002F096BD00207047B0340020F63400200D +:1019700038B5074D04462868204402F08FFD28B989 +:1019800028682044BDE8384002F09ABD38BD00BF49 +:10199000B03400200020704700F10050A0F5104046 +:1019A000D0F8900570470000064991F8243033B113 +:1019B0000023086A81F824300822FFF7C1BF012004 +:1019C000704700BFB4340020014B1868704700BF57 +:1019D000002004E070B50E4B5C6893F90860421E6D +:1019E0000A44013C0B46934207D214F9015F581C8C +:1019F0002DB100F8015C0346F5E7184605E02C24FC +:101A000082421C7001D9981C5E70401A70BD00BFE4 +:101A10001C110020022802BF024B4FF400229A61E1 +:101A2000704700BF00040048022802BF014B082293 +:101A30009A61704700040048022801BF024A5369B6 +:101A400083F00803536170470004004810B5002379 +:101A5000934203D0CC5CC4540133F9E710BD0000BD +:101A600003460246D01A12F9011B0029FAD1704729 +:101A700002440346934202D003F8011BFAE7704781 +:101A80002DE9F8431F4D144695F824200746884653 +:101A900052BBDFF870909CB395F824302BB920220C +:101AA000FF2148462F62FFF7E3FF95F82400C0F1BD +:101AB0000802A24228BF2246D6B24146920005EB58 +:101AC0008000FFF7C3FF95F82430A41B1E44F6B234 +:101AD000082E17449044E4B285F82460DBD1FFF768 +:101AE00063FF0028D7D108E02B6A03EB820383420F +:101AF000CFD0FFF759FF0028CBD10020BDE8F883F5 +:101B00000120FBE7B4340020024B1A78024B1A7014 +:101B1000704700BFF43400201811002008B50849B0 +:101B200008484FF461430B6002F012FA044906487A +:101B300002F00EFABDE808400149044802F008BA74 +:101B4000DC3400200435002070350020DC35002016 +:101B5000094B10B51822044600211846FFF788FFEC +:101B6000064A074B127804600146BDE8104053F85E +:101B7000220002F0EDB900BFDC340020F434002074 +:101B8000D0510008202383F3118862B6704700000B +:101B9000002383F3118862B67047000010B4026816 +:101BA00054681A4623465DF8044B184701207047D5 +:101BB0000020704700207047704700007047000009 +:101BC000002070470E20704700F5805090F8C80044 +:101BD000C0F340007047000000F5805090F9C90044 +:101BE000704700002DE9F0410C68BDF8187014F042 +:101BF00000541E466FD10B7B082B6CD8FFF7C2FF39 +:101C00004569AB685B010CD4AB681B0108D4AC68B8 +:101C100014F080545DD1FFF7BBFF2046BDE8F08192 +:101C200001240B6804F1180C002BB8BFDB004FEA4D +:101C30000C1CB4BF43F004035B0545F80C300B6883 +:101C40000FFA84FC13F0804F18BF05EB0C1E05EB58 +:101C50000C1C1EBFDEF8803143F00203CEF8803149 +:101C60000B7BCCF8843105EB04158B68C5F88C31FF +:101C70004B68C5F88831DCF8803143F00103CCF8BB +:101C8000803100EB441541F268031D4403EB44131B +:101C90000344C5E9002608330D4601F10C0C55F844 +:101CA00004EB43F804EB6545F9D184342D881D809D +:101CB00000EB441407F00303257925F00B052B43B3 +:101CC0002371FFF765FF06973346BDE8F04100F04A +:101CD000AFBC0224A5E74FF0FF309FE713B500F536 +:101CE00080540191E06D00F039FD1F280AD9019957 +:101CF000E06D202200F0A8FDA0F1200358425841D9 +:101D000002B010BD0020FBE708B500F58050FFF7DA +:101D100039FFC06D00F0F6FCBDE80840FFF738BFA2 +:101D200000220260828142608260704710B500220A +:101D30000023C0E900230023044603810C30FFF791 +:101D4000EFFF204610BD0000F0B5054600F58050BD +:101D50000C4690F8C83013F0040FC3F3800108BF9D +:101D6000114661F3820304F1840680F8C83005EB64 +:101D7000461389B01B79D8072ED57AB319072DD40D +:101D80006846FFF7D3FF05EB441303F5835303F1D4 +:101D9000180703AA103318685968144603C4083397 +:101DA000BB422246F7D1186820609B88A380DDE9FA +:101DB0000E23CDE900230123ADF808302B686946D6 +:101DC0001B6C2846984705EB46152B791A075CBF14 +:101DD00043F008032B7101E0002AF4D109B0F0BDF3 +:101DE0002DE9F047074688B007F5805468469A46C3 +:101DF0008846FFF7C7FE9146FFF798FFE06D00F0B9 +:101E000093FC1F2829D9E06D2022694600F09EFD31 +:101E1000202822D103AD444605AB2E4603CE9E4278 +:101E200020606160354604F10804F6D13068206016 +:101E3000B388A380DDE90023C9E90023BDF8083099 +:101E4000AAF80030FFF7A4FE4A46534641463846FA +:101E500008B0BDE8F04700F0D9BBFFF799FE0020BD +:101E600008B0BDE8F08700002DE9F84F0023C0E975 +:101E70000133254B044640F8183B0F46FFF750FF4F +:101E800004F12800FFF752FF04F1480804F58255D9 +:101E90004646083530462036FFF748FFAE42F9D1B6 +:101EA00004F580554FF480534FF00009C5E913390C +:101EB000C5F848800123EE6504F5875804F584567B +:101EC000C5F8549085F8583085F86030083608F128 +:101ED00008084FF0000A4FF0000B46E908ABA6F1E6 +:101EE0001800FFF71DFF203646F8289C4645F4D120 +:101EF00085F8C97017B1054800F076FD044B6361A1 +:101F00002046BDE8F88F00BF04520008DC510008ED +:101F10000064004010B5044B197804464A1C1A703E +:101F2000FFF7A2FF204610BDFC3400202DE9F0474A +:101F3000002950D0294B2A4FB7FBF1F599428CBFAD +:101F40000A231123581EB5FBF3FC03FB1C53C4B238 +:101F50002BB102280346F5D80020BDE8F0870CF12C +:101F6000FF36B6F5806FF7D2C4EBC40E0EF1030353 +:101F70004FEAE309C3F3C703A4EB030809F1010A1D +:101F80004FF47A755FFA88F009FB05555AFA88F81C +:101F9000B5FBF8F5B5F5617FC1BF0EF1FF33C3F3B3 +:101FA000C703E01AC0B25C1C50FA84F40CFB04F4C2 +:101FB000B7FBF4F4A142CFD1013BDBB20F2BCBD85E +:101FC0000138C0B20728C7D800211071168091705F +:101FD000D3700120C1E70846BFE700BF3F420F00B2 +:101FE00000B4C40470B505460E464FF47A746B69AC +:101FF0005B6803F00103B34207D04FF47A7002F03C +:102000000DF9013CF3D1204670BD0120FCE7000032 +:1020100030B54269936913F0700F16D000230B4C52 +:10202000936103F1840200EB421211794D0709D547 +:10203000890707D5416954F823508D60117941F023 +:10204000040111710133032BEBD130BDF0510008B5 +:1020500073B51D46436916469A68D207044609D5EA +:102060009A6801219960C2F34002CDE90065002120 +:10207000FFF76AFE63699A68D1050BD59A684FF439 +:1020800080719960C2F34022CDE9006501212046AC +:10209000FFF75AFE63699A68D2030BD59A684FF42A +:1020A00080319960C2F34042CDE9006502212046AB +:1020B000FFF74AFE204602B0BDE87040FFF7A8BF18 +:1020C000F8B50446466900296CD106F10C0738685A +:1020D00080076AD006EB01153868D5F8B00110F01A +:1020E000040FD5F8B0011ABFC00840F00040400D01 +:1020F000A061D5F8B0C11CF0020F1CBF40F08040B9 +:10210000A061D5F8B40106EB011100F00F0084F8CE +:102110002400D1F8B8012077D1F8B801000A60771F +:10212000D1F8B801000CA077D1F8B801000EE07723 +:10213000D1F8BC0184F82000D1F8BC01000A84F871 +:102140002100D1F8BC01000C84F82200D1F8BC11A8 +:10215000090E84F823103821396004F1340004F1A9 +:10216000180104F1240551F8046B40F8046BA942EE +:10217000F9D109880180C4E90A2321460023238676 +:1021800051F8283B20461B6C984704F580522046A6 +:1021900092F8C83043F0040382F8C830BDE8F84034 +:1021A000FFF736BF06F1100791E7F8BD10B50446FA +:1021B00000F022FC02460B4652EA030102D0013A2B +:1021C00063F100030449086820B12146BDE81040CE +:1021D000FFF776BF10BD00BFF8340020F8B500F55A +:1021E00083511E46FFF7CEFCDFF844C008310024BF +:1021F00004F1840500EB45152B795F070ED4DB064F +:102200000CD5D1E900739742B34107D243695CF81A +:1022100024709F602B7943F004032B710134032C4D +:1022200001F12001E4D1BDE8F840FFF7B1BC00BFE7 +:10223000F051000808B5FFF7A5FCFFF7E9FEBDE87F +:102240000840FFF7A5BC0000F8B54369054698684B +:1022500000F0E050B0F1E05F0F461FD0E8B1FFF7AB +:1022600091FC05F583541034002606F1840305EB38 +:1022700043131B791A0706D50136032E04F12004F7 +:10228000F3D1012007E05B07F6D42146384600F081 +:1022900009FA0028F0D1FFF77BFCF8BD0120FCE72C +:1022A00000F5805008B5FFF76DFCC06D00F03CFAFA +:1022B000FFF76EFC43090CBF0120002008BD0000A1 +:1022C000F8B51D46002313700F4606461446FFF767 +:1022D000E7FF80F00100387025B129463046FFF74E +:1022E000B3FF2070F8BD00002DE9B8410C4615463B +:1022F0001F46804600F080FB0B462178024609B954 +:10230000287850B14046FFF769FFFFF793FF3B463F +:102310002A462146FFF7D4FF0120BDE8B88100001E +:1023200010B5FFF72FFC174B9A6D42F000729A65BB +:102330009A6B42F000729A639A6B00F5805422F017 +:1023400000729A63FFF724FC94F8C830DB0718D4B6 +:10235000B9B102211320FFF715FC01F047FC02215F +:10236000142001F043FC0221152001F03FFC94F8F9 +:10237000C83043F0010384F8C830BDE81040FFF7CF +:1023800007BC10BD001002402DE9F04700F5805554 +:1023900088B095F8C930012B04468846164600F2ED +:1023A000FB807E4F57F823200AB947F82300D7F85F +:1023B00000A0C4F80C802674BAF1000F09D141F2D4 +:1023C000D00002F01DFD51468146FFF74DFDC7F8D4 +:1023D000009095F8C930012B5DD001212046FFF710 +:1023E0009FFFFFF7CFFB6269136823F002031360BE +:1023F0006269136843F001031360636900275F613A +:1024000001212046FFF7C4FBFFF7ECFD002800F098 +:102410008480E86D00F076F904F58359BA4609F135 +:102420000809202200216846FFF722FB02A8FFF7D7 +:1024300077FCCDF818A06A4609EB07030DF1180EDA +:102440009446BCE80300F44518605960624603F105 +:102450000803F5D1DCF80000186020379CF8042050 +:102460001A71602FDDD195F8C8306FF38203002711 +:1024700085F8C8306A4641462046ADF80070ADF890 +:1024800002708DF80470FFF751FD6369C0B94FF415 +:1024900000421A6011E0386803685B6B9847014698 +:1024A00000289AD13868FFF73BFF38680368324646 +:1024B0005B684146984700288FD108B0BDE8F08797 +:1024C00061221A609DF802309DF803201B06120459 +:1024D00002F4702203F040731343BDF80020C2F3EE +:1024E000090213439DF804201205022E02F4E002B3 +:1024F0000CBF4FF000410021134362690B43D361CD +:10250000636913225A616269136823F0010313603F +:1025100039462046FFF766FD08B96369B7E795F8C5 +:10252000C93093BB6169D1F8002242F00102C1F8C1 +:1025300000226169D1F8002222F47C5222F00E02BE +:10254000C1F800226169D1F8002242F46062C1F84A +:1025500000226269C2F814326269C2F80432626908 +:1025600041F6FF71C2F80C126269C2F8403262692A +:10257000C2F8443263690122C3F81C226269D2F8AE +:10258000003223F00103C2F8003295F8C83043F05E +:10259000020385F8C83090E700208EE7F834002069 +:1025A00008B500F029FA50EA0103024602D0421EA3 +:1025B00061F10001044B186810B10B46FFF748FDAC +:1025C000BDE8084001F06CB9F834002008B50020DF +:1025D000FFF7ECFDBDE8084001F062B908B5012045 +:1025E000FFF7E4FDBDE8084001F05AB90FB4002040 +:1025F00004B0704713B56C4684E80600031D94E8E8 +:10260000030083E80500012002B010BD73B58568A2 +:10261000019155B11B885B0707D4D0E90036DB6B0D +:102620009847019AC1B23046A847012002B070BD58 +:10263000F0B5866889B005460C465EB1BDF8383005 +:102640005B070AD4D0E90037DB6B98472246C1B25A +:102650003846B047012009B0F0BD00220023CDE983 +:1026600000230023ADF808300A4603AB01F1080649 +:10267000106851681C4603C40832B2422346F7D1A1 +:10268000106820609288A28000F0B8F90423ADF8A9 +:1026900008302B68CDE900011B6C69462846984735 +:1026A000D8E7000030B503680968DD0FB5EBD17FCE +:1026B00023F0604421F060424FEAD1700BD0002B30 +:1026C000B8BFA40C0029B8BF920C944202D034BF0A +:1026D0000120002030BD944205D1C1F38070C3F3C6 +:1026E00080738342F6D194422CBF00200120F1E791 +:1026F00010B5037C044613B9006802F0B9FB20460C +:1027000010BD00000023BFF35B8FC360BFF35B8F7E +:10271000BFF35B8F8360BFF35B8F7047BFF35B8F4B +:102720000068BFF35B8F704770B505460C30FFF74C +:10273000F5FF05F1080604463046FFF7EFFFA0421B +:1027400006D930466D68FFF7E9FF2544281A70BDA9 +:102750003046FFF7E3FF201AF9E7000070B50546A1 +:10276000406898B105F10800FFF7D8FF05F10C06A5 +:1027700004463046FFF7D2FF8442304694BF6D686E +:102780000025FFF7CBFF013C2C44201A70BD000050 +:1027900038B50C460546FFF7C7FFA04210D305F138 +:1027A0000800FFF7BBFF04446868B4FBF0F100FBCE +:1027B0001144BFF35B8F0120AC60BFF35B8F38BD6A +:1027C0000020FCE72DE9F041144607460D46FFF7CF +:1027D000C5FF844228BF0446D4B1B84658F80C6BF4 +:1027E0004046FFF79BFF3044286040467E68FFF775 +:1027F00095FF331A9C4203D86C600120BDE8F0813C +:102800006B60A41B3B68AB602044E8600220F5E7E6 +:102810002046F3E738B50C460546FFF79FFFA04278 +:1028200010D305F10C00FFF779FF04446868B4FB8E +:10283000F0F100FB1144BFF35B8F0120EC60BFF3AC +:102840005B8F38BD0020FCE72DE9FF4188466946D3 +:102850000746FFF7B7FF6C4606B204EBC606002535 +:10286000B44209D06268206808EB0501FFF7EEF872 +:10287000636808341D44F3E729463846FFF7CAFF6A +:10288000284604B0BDE8F081F8B505460C300F4687 +:10289000FFF744FF05F1080604463046FFF73EFF08 +:1028A000A042304688BF6C68FFF738FF201A3860B6 +:1028B00020B130462C68FFF731FF2044F8BD0000FE +:1028C00073B5144606460D46FFF72EFF844228BF17 +:1028D00004460190DCB101A93046FFF7D5FF019B0A +:1028E00033B93268C5E90233C5E9002401200CE0A0 +:1028F0009C4238BF01942860019868608442F5D9F1 +:102900003368AB60241AEC60022002B070BD204630 +:10291000FBE700002DE9FF410F466946FFF7D0FFB6 +:102920006C4600B204EBC0050026AC4209D0D4F8D6 +:10293000048054F8081BB8194246FFF787F846444C +:10294000F3E7304604B0BDE8F081000038B5054635 +:10295000FFF7E0FF044601462846FFF719FF20462F +:1029600038BD000000B59BB0EFF3098168226846CE +:10297000FFF76CF8EFF30583044B9A6BDA6A9A6AF7 +:102980009A6A9A6A9A6A9A6A9B6AFEE700ED00E080 +:1029900000B59BB0EFF3098168226846FFF756F84F +:1029A000EFF30583044B9A6B9A6A9A6A9A6A9A6A59 +:1029B0009A6A9B6AFEE700BF00ED00E000B59BB09D +:1029C000EFF3098168226846FFF740F8EFF30583CB +:1029D000034B5A6B9A6A9A6A9A6A9A6A9B6AFEE7EA +:1029E00000ED00E0FEE700000FB408B5029801F02A +:1029F000AFFBFEE701F050BE01F028BE01F026BE9D +:102A000030B5094D0A4491420DD011F8013B5840B0 +:102A1000082340F30004013B2C4013F0FF0384EA39 +:102A20005000F6D1EFE730BD2083B8ED2DE9F0413D +:102A3000C56915B9C161BDE8F0814B6823F06047F5 +:102A4000C3F38A464FEAD37EC3F3807816EA23069F +:102A500038BF3E46AC462B465A68BEEBD27F22F0CA +:102A600060440AD0002A18DAA40CB44217D19D425F +:102A70000FD10D60DEE71346EEE7A74207D102F063 +:102A80008044C2F3807242450BD054B1EFE708D2C4 +:102A9000EDE7CCF800100B60CDE7B44201D0B442B2 +:102AA000E5D81A689C46002AE5D11960C3E7000002 +:102AB0002DE9F047089D01F007044FEAD5082244AC +:102AC00005F0070500EBD1004FF47F49944201D196 +:102AD000BDE8F08704F0070705F0070A57453E46B2 +:102AE00038BF5646C6F10806111B8E4228BF0E4657 +:102AF000E10808EBD50E415C13F80EC0B94029FA85 +:102B000006F721FA0AF1FFB28CEA010147FA0AF747 +:102B100039408CEA010C03F80EC034443544D5E743 +:102B200080EA0120082341F2210201B2400000297D +:102B300080B203F1FF33B8BF504013F0FF03F4D16C +:102B40007047000038B50C468D18A54200D138BD3D +:102B500014F8011BFFF7E4FFF7E7000002684AB131 +:102B600013680360C388018901339BB29942C38013 +:102B700038BF03811046704770B588B020220446E4 +:102B80000D4668460021FEF773FF20460495FFF7C7 +:102B9000E5FF024658B16B46054608AE1C4603CC1D +:102BA000B44228606960234605F10805F6D1104655 +:102BB00008B070BD082817D909280CD00A280CD0F5 +:102BC0000B280CD00C280CD00D280CD00E2814BFCC +:102BD0004020302070470C20704710207047142090 +:102BE000704718207047202070470000082817D928 +:102BF0000C280CD910280CD914280CD918280CD959 +:102C000020280CD930288CBF0F200E2070470920B7 +:102C100070470A2070470B2070470C2070470D202A +:102C20007047000010B54B6823B9CA8A63F30902E4 +:102C3000CA8210BDC4681A681C60C360438A013B25 +:102C400043824A60EFE700002DE9F84F1D46CB8A2A +:102C50000F46C3F309010629814692460B4630D040 +:102C60000020AAB207F119049EB2052E1FFA80F8BF +:102C70000FD8904503F1010306D3FB8A0A4462F39F +:102C80000903FB8201201AE01AF80060E6540130C3 +:102C9000EAE79045F1D2A1F1060B1C237C68BBFB4F +:102CA000F3F203FB12BB1FFA8BF6002C45D148460A +:102CB000FFF754FF044638B978606FF00200BDE8B2 +:102CC000F88F4FF00008E6E7002606607860ADB2A6 +:102CD0004FF0000B454510D90AEB0803221D13F8ED +:102CE000011B9155B1B208F101081B291FFA88F8A0 +:102CF0002BD0454506F10106F1D8FB8AC3F3090242 +:102D0000154465F30903BCE7013292B21C462368FF +:102D1000002BF9D1AB1F0B441C21B3FBF1F30133A2 +:102D20009BB29A42D3D2BBF1000FD0D14846FFF7F5 +:102D300015FF20B9C4F800B0BFE70122E7E7C0F8EB +:102D400000B05E4620600446C1E74545D5D94846F7 +:102D5000FFF704FF08B92060AFE7C0F800B0002615 +:102D600020600446B6E700002DE9F04F2DED028B00 +:102D700083B0CDE90013BDF83C5007469146002AC8 +:102D800000F092802DB10E9B002B00F08D80072D5E +:102D900032D807F10C00FFF7E1FE044638B96FF0B6 +:102DA0000204204603B0BDEC028BBDE8F08F142274 +:102DB0000021FEF75DFE0E992A4604F10800FEF799 +:102DC00045FE681CC0B2FFF711FFFFF7F3FE207449 +:102DD00099F80030013814FA80F003F01F0363F013 +:102DE0003F030372009B43F0004161603846214677 +:102DF000FFF71CFE0124D4E700F10C034FF000089C +:102E000008EE103A4FF0800A4646444618EE100A83 +:102E1000FFF7A4FE83460028C1D014220021FEF74C +:102E200027FEC6BB019BABF8083002200E9B00F1C9 +:102E3000080299195BFA82F20130C0B2082801D069 +:102E4000AE422AD3FFF7D2FEFFF7B4FE99F8002076 +:102E5000009B411E02F01F0242EA4812AE4208BF28 +:102E60004FF0400A5BFA81F14AEA020A43F000425D +:102E700081F808A08BF81000CBF80420594638469A +:102E8000FFF7D4FD0134AE4224B288F001084FF0C0 +:102E9000000ABBD185E70020C8E711F801CB02F892 +:102EA00001CB0136B6B2C7E76FF0010479E7000045 +:102EB000F8B515460E462822002104461F46FEF7A7 +:102EC000D7FD069B6360B5F5001F079BA76034BF65 +:102ED0006A094FF6FF72236204F10C0097B20023D7 +:102EE0009A4205D80023036027826382A382F8BD3B +:102EF0000660013330462036F2E7000003781BB944 +:102F00004BB2002BC8BF01707047000000787047BB +:102F10002DE9F74FDDF83C90BDF830500D9E9DF83F +:102F20003840BDF84070804692469B46B9F1000F8C +:102F300001D1002F51D11F2C4FD898F80000B0B903 +:102F4000072F47D835F0030347D13A4649464FF695 +:102F5000FF70FFF7F7FD20F001002D02400445EA65 +:102F60000464400C44EA40244FF6FF7321E040EA39 +:102F70000520072F40EA0464F6D900254FF6FF73B9 +:102F8000C5F12000A5F120022AFA05F10BFA00F0A4 +:102F900001432BFA02F211431846C9B2FFF7C0FDF4 +:102FA0000835402D0346EBD13A464946FFF7CAFDA6 +:102FB0000346CDE90097324621464046FFF7D4FE4E +:102FC00033780133DBB21F2B88BF0023337003B08B +:102FD000BDE8F08F6FF00300F9E76FF00100F6E74E +:102FE0002DE9F04F85B09246DDF848800F9D9DF8A1 +:102FF00040209DF84490BDF84C7006469B46B8F1C1 +:10300000000F01D1002F48D11F2A46D83378002B5A +:1030100046D00C0244EA02649DF8381044EAC934F0 +:1030200044EA01441C43072F44F0800432D90023B2 +:103030004FF6FF72C3F1200CA3F120002AFA03F12E +:103040000BFA0CFC41EA0C012BFA00F00143C9B267 +:1030500010460393FFF764FD039B0833402B0246A1 +:10306000E8D13A464146FFF76DFD0346CDE90087BA +:103070002A4621463046FFF777FEB9F1010F06D107 +:103080002B780133DBB21F2B88BF00232B7005B0D8 +:10309000BDE8F08F4FF6FF73E8E76FF00100F6E749 +:1030A0006FF00300F3E70000C06900B1043070471F +:1030B000C3691A68C261C2681A60C360438A013B6F +:1030C000438270472DE9F041D0F81880194E14461C +:1030D0001D464146002709B9BDE8F081D1E9022328 +:1030E000A21A65EB0303964277EB03031ED28369B2 +:1030F0008B420DD1FFF796FD83691B688361C3681E +:103100000B60438AC1608169013B43828846E2E7E4 +:10311000FFF788FD0B68C8F80030C3680B60438A6E +:10312000C160013B4382D8F80010D4E788460968A3 +:10313000D1E700BF80841E002DE9F04F8BB00D4613 +:10314000DDF8509014469B468046002800F0198117 +:10315000B9F1000F00F01581531E3F2B00F21181D1 +:10316000012A03D1BBF1000F40F00B810023CDE910 +:103170000833B8F81430B5EBC30F4FEAC30703D3D5 +:1031800000200BB0BDE8F08F2B199F42D8F80C300F +:103190003ABF7F1BFFB227461BB9D8F81030002B6F +:1031A0007AD02F2D4ED8C5F13006B7424FF000032C +:1031B0002CBFF6B23E4600932946D8F8080008AB6B +:1031C0003246FFF775FCA7EB060A35445FFA8AFA28 +:1031D000B8F8143003F10053063BDB000493D8F831 +:1031E0000C3003933021039B13B1BAF1000F2CD1A3 +:1031F000D8F8100040B1BAF1000F05D0009608AB26 +:103200005246691AFFF754FC38B2002FB8D066074F +:103210000AD00AAB03EBD401624211F8083C02F079 +:103220000702134101F8083C082C3CD9102C40F24D +:10323000B580202C40F2B780BBF1000F00F09C80DD +:10324000082334E0BA460026C2E7049BE02B28BFDF +:10325000E02306930B44AB42059314D95A1B039801 +:103260000096924534BF5246D2B2691A08AB043078 +:103270000792FFF71DFC079A1644AAEB020A1544B1 +:10328000F6B25FFA8AFA049B069A05999B1A049390 +:10329000039B1B680393A6E70093D8F8080008ABCC +:1032A0003A462946AEE7BBF1000F13D00123B4EB39 +:1032B000C30F6CD0082C12D89DF82030621E23FA60 +:1032C00002F2D50706D54FF0FF3202FA04F4234389 +:1032D0008DF820309DF8203089F8003051E7102C0F +:1032E00012D8BDF82030621E23FA02F2D10706D5AB +:1032F0004FF0FF3202FA04F42343ADF82030BDF85A +:103300002030A9F800303CE7202C0FD80899631E24 +:1033100021FA03F3DA0705D54FF0FF3202FA04F47D +:103320000C430894089BC9F800302AE7402C2BD0A6 +:10333000DDE90865611EC4F12102A4F1210326FA2A +:1033400001F105FA02F225FA03F311431943CB0701 +:1033500012D50122A4F12003C4F1200102FA03F3E3 +:1033600022FA01F1A240524243EA010363EB430314 +:1033700032432B43CDE90823DDE90823C9E90023C3 +:10338000FFE66FF00100FCE66FF00800F9E6082C9C +:10339000A0D9102CB3D9202CEED8C3E7BBF1000F75 +:1033A000ADD0022383E7BBF1000FBBD004237EE73F +:1033B00030B5012A144638BF0124402C85B028BFFF +:1033C00040240025012ACDE9025518D81B788DF834 +:1033D000083063070AD004AB03EBD405624215F84A +:1033E000083C02F00702934005F8083C00910346B0 +:1033F0002246002102A8FFF75BFB05B030BD082A7A +:10340000E4D9102A03D81B88ADF80830E1E7202A58 +:103410008DBFD3E900231B680293CDE90223D8E7CF +:1034200010B5CB681BB98B600B618B8210BDC46873 +:103430001A681C60C360438A013B4382CA60F0E79C +:103440002DE9F04FD1F8008093B018F0800FCDE94E +:103450000323C8F3C01219BFC8F3C03BC8F3062644 +:103460004FF0020B1646B8F1000F04460D4680F2ED +:10347000D18118F0C043059340F0CC810B7B002B29 +:1034800000F0C881BBF1020F03D00178B14240F0D7 +:10349000C48108F07F0106916AB3C8F3074A2B4440 +:1034A000069A93F80390760646EA0B4646EA824669 +:1034B0005FEAD91346EA0A06079300F090800022DB +:1034C0000023CDE90A23069B009367685B465246BA +:1034D0000AA92046B84700287ED0A7699FB931467F +:1034E00004F10C00FFF748FB0746E0B96FF002005B +:1034F00013B0BDE8F08FC8F30F2A18F07F0F08BF94 +:103500000AF0030ACBE73B699E420DD03F68002FCB +:10351000F9D1314604F10C00FFF72EFB07460028D5 +:10352000E4D0A3693B60A761DDE90A2300264FF6DA +:10353000FF70C6F1200E22FA06F103FA0EFEA6F184 +:10354000200C23FA0CFC41EA0E0141EA0C01C9B23D +:10355000083609920893FFF7E3FA402EDDE90832B6 +:10356000E7D1B882FB7D09F01F06C3F384039B1BE0 +:10357000D7E9022198B2002BBCBF00F120031BB297 +:1035800052EA0100C8F304680FD00398821A049825 +:1035900060EB0101A74890424FF000028A4104D33A +:1035A000079A002A5BD0012B23DDFA7D4FEA8903BD +:1035B00002F0030203F07C031343FB7539462046F7 +:1035C000FFF730FB079BA3B9FB7DC3F384020132F5 +:1035D00062F38603FB7504E06FF00B0088E7A769D0 +:1035E00017B96FF00C0083E73B699E42BAD03F6881 +:1035F000F6E719F0400F32D0039BBB60049BFB60E1 +:10360000142200210DA8FEF733FA039B0A93049BB2 +:103610000B932B1D0C932B7BADF83EA0013BDBB233 +:10362000ADF83C30069B8DF8433094F824308DF88B +:1036300040B083F001038DF844308DF84160A368F9 +:103640008DF842800AA920469847FB7DC3F3840386 +:10365000013303F01F039B02FB82002048E7FB7D40 +:10366000C9F34012B2EBD31F40F0DA80C3F38403F6 +:10367000B34240F0D88007992B7B4FEA991200297A +:1036800034D0D20741D4032B40F2D080039BBB60DF +:10369000049BFB602B7BAE1D033BDBB232463946FD +:1036A00004F10C00FFF7D0FA00280DDA2046394665 +:1036B000FFF7B8FAFB7DC3F38403013303F01F0364 +:1036C0009B02FB82032013E7AB883B832A7B033AF0 +:1036D000B88AD2B23146FFF735FAFB7DB882DA43B9 +:1036E000C2F3C01262F3C713FB75B6E76AB92E1DA9 +:1036F000013BDBB23246394604F10C00FFF7A4FA75 +:103700000028D3DB2A7B013AE2E7F98AC1F30901F9 +:10371000013B0529DAB259D8281D002307F11A0CFC +:103720009A4208D910F801EB0CF801E0013101339D +:103730000629DBB2F4D103990A9104990B919342C3 +:1037400007F11A010C9138BF043379680D9134BF29 +:1037500055FA83F300230E93FB8AADF83EA0C3F322 +:1037600009031A44069B8DF8433094F82430ADF8D1 +:103770003C2083F001038DF8443000238DF840B0E5 +:103780008DF841608DF842807B602A7BB88A013ACF +:10379000291DFFF7D7F93B8BB882834203D1A36879 +:1037A0000AA92046984720460AA9FFF739FEFB7D63 +:1037B000B88AC3F38403013303F01F039B02FB8227 +:1037C0003B8B984214BF1120002091E67B68002BB0 +:1037D000B1D0062001E01C306346D3F800C0BCF134 +:1037E000000FF8D1091A081D05F1040C00EB0309BC +:1037F00005989DF8143001EB000EBEF11B0F9AD80E +:103800009A4298D91CF8013B09F8013B059B01330A +:103810000593EDE76FF009006AE66FF00A0067E6CE +:103820006FF00D0064E66FF00E0061E66FF00F00C0 +:103830005EE600BF80841E00EFF3098305494A6BF2 +:1038400022F001024A63683383F30988002383F37B +:103850001188704700EF00E0202080F3118862B6E5 +:103860000C4B0D4AD96821F4E0610904090C0A43A4 +:10387000DA60D3F8FC20094942F08072C3F8FC20DA +:103880000A6842F001020A601022DA7783F8220007 +:10389000704700BF00ED00E00003FA05001000E0F3 +:1038A00010B5202383F311880E4B5B6813F400637B +:1038B00014D0F1EE103AEFF30984683C4FF08073B6 +:1038C000E361094BDB6B236684F3098800F0F2FBAC +:1038D00010B1064BA36110BD054BFBE783F31188C4 +:1038E000F9E700BF00ED00E000EF00E00B06000884 +:1038F0000E060008026843681143016003B11847CF +:1039000070470000024A136843F0C0031360704719 +:1039100000380140024A136843F0C0031360704747 +:1039200000440040024A136843F0C003136070472C +:103930000048004037B5244C244D204600F0FCFAE6 +:10394000009404F1140022490023202200F0BEF963 +:1039500020490094202204F138001F4B00F038FA6F +:103960001E4BC4E917351E4C204600F0E5FA0094C2 +:1039700004F114001B490023202200F0A7F91A4982 +:103980000094202204F13800184B00F021FA184B63 +:10399000C4E91735174C204600F0CEFA04F11400A4 +:1039A000154900940023202200F090F9134B14498C +:1039B0000094202204F1380000F00AFA114BC4E907 +:1039C000173503B030BD00BF0435002000B4C40477 +:1039D00048360020A836002005390008003801408C +:1039E0007035002068360020C836002015390008E0 +:1039F00000440040DC3500208836002025390008CE +:103A0000E83600200048004030B5037C304C0029E7 +:103A100018BF0C46012B0FD12E4B984239D12E4B9B +:103A20001A6E42F480421A66D3F8802042F4804233 +:103A3000C3F88020D3F880302268036EC16D84669D +:103A400003EB5203B3FBF2F36268150442BF23F0A9 +:103A5000070503F0070343EA4503CB60A36843F07F +:103A600040034B60E36843F001038B6042F49673BC +:103A700043F001030B604FF0FF330B62510505D596 +:103A800012F010221FD0B2F1805F1ED080F8643097 +:103A900030BD124B98420BD0114B9842CCD10E4BFB +:103AA0009A6D42F480229A659A6F42F4802207E070 +:103AB000094B9A6D42F400329A659A6F42F40032D3 +:103AC0009A679B6FB8E77F23E0E73F23DEE700BFFD +:103AD00048520008043500200010024070350020D4 +:103AE000DC3500202DE9F047C66D3768F469346293 +:103AF0002107054618D014F0080118BF8021E207FD +:103B000048BF41F02001A30748BF41F040016007D2 +:103B100048BF41F48071202383F31188281DFFF7EB +:103B2000E9FE002383F31188E2050AD5202383F3FD +:103B300011884FF40071281DFFF7DCFE002383F38A +:103B400011884FF020094FF0000A14F0200838D1F6 +:103B50003B0616D54FF0200905F1380A200610D58E +:103B600089F31188504600F067F9002836DA0821F9 +:103B7000281DFFF7BFFE27F080033360002383F387 +:103B80001188790614D5620612D5202383F3118893 +:103B9000D5E913239A4208D12B6C33B11021281D8B +:103BA00027F04007FFF7A6FE3760002383F3118854 +:103BB000E30619D5AA6E1369B3B1BDE8F0475069A1 +:103BC000184789F31188B38C95F86410284619407A +:103BD00000F0CCF98AF31188F469B6E780B2308539 +:103BE00088F31188F469B9E7BDE8F08700F1604314 +:103BF00003F561430901C9B283F80013012200F003 +:103C00001F039A4043099B0003F1604303F561439E +:103C1000C3F880211A607047F8B5154682680669B6 +:103C2000AA420B46816938BF8568761AB5420446B8 +:103C30000BD218462A46FDF709FFA3692B44A3615E +:103C4000A3685B1BA3602846F8BD0CD91846324612 +:103C5000FDF7FCFEAF1BE1683A463044FDF7F6FE87 +:103C6000E3683B44EBE718462A46FDF7EFFEE368BE +:103C7000E5E7000083689342F7B51546044638BF70 +:103C80008568D0E90460361AB5420BD22A46FDF7A2 +:103C9000DDFE63692B446361A36828465B1BA36058 +:103CA00003B0F0BD0DD932460191FDF7CFFE019969 +:103CB000E068AF1B3A463144FDF7C8FEE3683B4479 +:103CC000E9E72A46FDF7C2FEE368E4E710B50A44D7 +:103CD0000024C361029B8460C0E90000C0E90511B3 +:103CE000C1600261036210BD08B5D0E9053293429C +:103CF00001D1826882B98268013282605A1C4261B5 +:103D00001970D0E904329A4224BFC368436100218C +:103D100000F0A0FA002008BD4FF0FF30FBE70000E4 +:103D200070B5202304460E4683F31188A568A5B11B +:103D3000A368A269013BA360531CA36115782269A3 +:103D4000934224BFE368A361E3690BB1204698471F +:103D5000002383F31188284607E03146204600F00F +:103D600069FA0028E2DA85F3118870BD2DE9F74F72 +:103D700004460E4617469846D0F81C904FF0200A8D +:103D80008AF311884FF0000B154665B12A4631467B +:103D90002046FFF741FF034660B94146204600F048 +:103DA00049FA0028F1D0002383F31188781B03B06F +:103DB000BDE8F08FB9F1000F03D001902046C8474D +:103DC000019B8BF31188ED1A1E448AF31188DCE7FE +:103DD000C0E90511C160C3611144009B8260C0E964 +:103DE0000000016103627047F8B504460D461646AF +:103DF000202383F31188A768A7B1A368013BA360C0 +:103E000063695A1C62611D70D4E904329A4224BF6E +:103E1000E3686361E3690BB120469847002080F3B3 +:103E2000118807E03146204600F004FA0028E2DA63 +:103E300087F31188F8BD0000D0E905239A4210B538 +:103E400001D182687AB98268013282605A1C82612B +:103E50001C7803699A4224BFC3688361002100F083 +:103E6000F9F9204610BD4FF0FF30FBE72DE9F74F81 +:103E700004460E4617469846D0F81C904FF0200A8C +:103E80008AF311884FF0000B154665B12A4631467A +:103E90002046FFF7EFFE034660B94146204600F09A +:103EA000C9F90028F1D0002383F31188781B03B0EF +:103EB000BDE8F08FB9F1000F03D001902046C8474C +:103EC000019B8BF31188ED1A1E448AF31188DCE7FD +:103ED000026843681143016003B11847704700004E +:103EE0001430FFF743BF00004FF0FF331430FFF7EB +:103EF0003DBF00003830FFF7B9BF00004FF0FF337F +:103F00003830FFF7B3BF00001430FFF709BF0000DF +:103F10004FF0FF311430FFF703BF00003830FFF7D8 +:103F200063BF00004FF0FF323830FFF75DBF000085 +:103F300000207047FFF7FEBC044B03600023C0E97C +:103F40000233436001230374704700BF60520008CE +:103F500010B52023044683F31188FFF755FD022393 +:103F60002374002383F3118810BD000038B5C369A2 +:103F700004460D461BB904210844FFF7A9FF294652 +:103F800004F11400FFF7B0FE002806DA201D4FF4FC +:103F90008061BDE83840FFF79BBF38BD024B00226F +:103FA000C3E900339A607047083700200023037488 +:103FB0008268054B1B6899689142FBD25A6803607E +:103FC00042601060586070470837002008B5202311 +:103FD00083F31188037C032B05D0042B0DD02BB960 +:103FE00083F3118808BD436900221A604FF0FF3344 +:103FF0004361FFF7DBFF0023F2E7D0E900321360F3 +:104000005A60F3E7002303748268054B1B689968C4 +:104010009142FBD85A680360426010605860704754 +:1040200008370020054B19690874186802681A607F +:104030005360186101230374FCF7D2BA08370020DB +:1040400030B54B1C0B4D87B0044610D02B690A4A83 +:1040500001A800F019F92046FFF7E4FF049B13B113 +:1040600001A800F04DF92B69586907B030BDFFF782 +:10407000D9FFF8E708370020CD3F000838B50C4DD0 +:1040800041612B6981689A689142044603D8BDE872 +:104090003840FFF78BBF1846FFF7B4FF01232C61B0 +:1040A000014623742046BDE83840FCF799BA00BFAA +:1040B00008370020044B1A681B6990689B68984277 +:1040C00094BF0020012070470837002010B5084C2D +:1040D000236820691A6822605460012223611A74DF +:1040E000FFF790FF01462069BDE81040FCF778BA61 +:1040F0000837002008B5FFF7DDFF18B1BDE808401C +:10410000FFF7E4BF08BD0000FFF7E0BFFEE70000D7 +:1041100010B50C4CFFF742FF00F0A8F80A498022C6 +:10412000204600F03DF8012344F8180C0374FFF713 +:1041300093FB002383F3118862B60448BDE8104066 +:1041400000F04EB83037002088520008985200081E +:1041500008B572B6034B586200F072FA00F01EFB0D +:10416000FEE700BF0837002000F004B9EFF311802C +:1041700020B9EFF30583202282F3118870470000F5 +:1041800010B530B9EFF30584C4F3080414B180F31B +:10419000118810BDFFF7AEFF84F31188F9E7000026 +:1041A00082600222028270478368A3F17C0243F896 +:1041B0000C2C026943F83C2C426943F8382C074A1E +:1041C00043F81C2CC26843F8102C022203F8082C78 +:1041D000002203F8072CA3F118007047F905000826 +:1041E00010B5202383F31188FFF7DEFF002104467A +:1041F000FFF744FF002383F31188204610BD000021 +:10420000024B1B6958610F20FFF70CBF08370020D5 +:10421000202383F31188FFF7F3BF000008B50146A0 +:10422000202383F311880820FFF70AFF002383F37C +:10423000118808BD49B1064B42681B6918605A6075 +:10424000136043600420FFF7FBBE4FF0FF30704760 +:10425000083700200368984206D01A680260506050 +:1042600059611846FFF7A2BE70470000054B03F1E5 +:104270001402C3E905224FF0FF310022C3E90712FF +:10428000704700BF0837002070B51C4EC0E90323FB +:1042900005460C4600F0FCFA334653F8142F9A42B8 +:1042A0000DD13062C5E901242A600A2C2CBF001907 +:1042B0000A30C6E90555BDE8704000F0D7BA316A4A +:1042C000431AE31838BF1C469368A34202D9081961 +:1042D00000F0DAFA73699A6894420CD85A68AC60B4 +:1042E0002B606A6015609A685D60121B9A604FF0DF +:1042F000FF33F36170BD1B68A41AECE70837002098 +:1043000038B51B4C636998420DD0D0E90032136078 +:104310005A6000228168C2609A680A449A604FF02D +:10432000FF33E36138BD2246036842F8143F0021A1 +:1043300093425A60C16003D1BDE8384000F09EBA94 +:104340009A688168256A0A449A6000F0A1FA636954 +:104350009A68411B8A42E5D9AB181D1A092D206ABB +:1043600098BF01F10A02BDE83840104400F08CBA51 +:10437000083700202DE9F041184C002704F11406FD +:10438000656900F085FA236AAA68C11A8A4215D8BD +:1043900013442362D5E9003213605A606369D5F88B +:1043A0000C80EF60B34201D100F068FA87F3118806 +:1043B0002869C047202383F31188E1E76169B1428E +:1043C00009D013441B1ABDE8F0410A2B2CBFC018BA +:1043D0000A3000F059BABDE8F08100BF083700206C +:1043E0000C2303604FF0FF3070470000002070473F +:1043F000FEE70000704700004FF0FF3070470000FC +:10440000BFF34F8F024A1369DB03FCD4704700BF30 +:104410000020024008B5094B1B7873B9FFF7F0FF85 +:10442000074B5A69002ABFBF064A9A6002F18832D8 +:104430009A601A6822F480621A6008BD90380020E1 +:10444000002002402301674508B50B4B1B7893B948 +:10445000FFF7D6FF094B5A6942F000425A611A68C9 +:1044600042F480521A601A6822F480521A601A6864 +:1044700042F480621A6008BD90380020002002409B +:104480007F289ABF00F58030C002002070470000EE +:104490004FF4006070470000802070477F2808B507 +:1044A0000BD8FFF7EDFF00F500630268013204D17D +:1044B00004308342F9D1012008BD0020FCE7000050 +:1044C0007F2838B5044626D8FFF750FEFFF798FF3F +:1044D000FFF7A0FF114BF3221A6102225A615A69B9 +:1044E00042EAC4025A615A6942F480325A6105466E +:1044F0002046FFF785FF4FF40061FFF7C1FF00F092 +:1045000049F92846FFF7A0FFFFF73AFE2046BDE82D +:104510003840FFF7C3BF002038BD00BF0020024075 +:1045200040EA020313F007032DE9F04705460C4665 +:10453000164606D0324B40F2FB221A600020BDE83E +:10454000F08781182F4A91420CD92D4A4FF44071BF +:104550001160F3E72B1D1B686268934208D1083E87 +:1045600008350834072E19D92A6823689A42F1D0F1 +:10457000FFF7FCFDFFF74EFFFFF742FF04F10801D4 +:10458000214C4FF001084FF00009012EA1F108075E +:1045900008D8FFF759FFFFF7F3FD01E0002EE7D140 +:1045A0000120CCE7C4F81480AA4651F8083C4AF828 +:1045B000043B51F8043C6B60FFF722FFC4F81490F1 +:1045C0002A6851F8083C9A420ED00D4B40F2263230 +:1045D0001A600E4B1D600E4B1E600E4B1F60FFF7E6 +:1045E00033FFFFF7CDFDA9E7DAF800A051F8043C4E +:1045F0009A4501F10801E8D1083E0835C5E700BF3A +:104600008C38002000000408002002408038002080 +:104610008838002084380020084908B50B7828B174 +:104620001BB9FFF7F7FE01230B7008BD002BFCD070 +:10463000BDE808400870FFF707BF00BF90380020B2 +:104640004FF480314FF0005000F0A6B870B582B042 +:10465000FFF78CFD0E4E054600F01AF932689042C5 +:1046600037BF0C4A0B49516814682EBFD1E900418D +:10467000013151600419034641F1000128460191BE +:104680003360FFF77DFD0199204602B070BD00BF89 +:10469000943800209838002070B582B0FFF766FD8E +:1046A000104E054600F0F4F83268904237BF0E4ACB +:1046B0000D49516814682EBFD1E9004101315160A4 +:1046C000041941F100010346284601913360FFF7C8 +:1046D00057FD01994FF47A7200232046FBF768FDDD +:1046E00002B070BD943800209838002010B5024404 +:1046F000064BD2B2904200D110BD441C00B253F818 +:10470000200041F8040BE0B2F4E700BF502800405D +:10471000114B30B5D3F89040240409D4D3F890401D +:10472000C3F89040D3F8904044F40044C3F890405C +:104730000A4C236843F4807323600244084BD2B2CE +:10474000904200D130BD441C00B251F8045B43F8E4 +:104750002050E0B2F4E700BF0010024000700040BB +:104760005028004007B5012201A90020FFF7BEFF35 +:10477000019803B05DF804FB13B50446FFF7F2FFA0 +:10478000A04205D0012201A900200194FFF7C0FF3B +:1047900002B010BD70470000704700007047000075 +:1047A000074B45F255521A6002225A6040F6FF72DA +:1047B0009A604CF6CC421A60024B01221A70704784 +:1047C00000300040A4380020034B1B781BB1034B82 +:1047D0004AF6AA221A607047A43800200030004030 +:1047E000054B1A6832B902F1804202F50432D2F860 +:1047F00094201A60704700BFA0380020024B4FF48D +:104800000002C3F8942070470010024008B5FFF77B +:10481000E7FF024B1868C0F3407008BDA0380020C5 +:1048200070470000FEE700000A4B0B480B4A90421D +:104830000BD30B4BDA1C121AC11E22F003028B425F +:1048400038BF00220021FDF713B953F8041B40F8CC +:10485000041BECE7445300083C3900203C3900209D +:104860003C3900207047000000F07AB84FF08043D8 +:10487000002258631A610222DA6070474FF08043C9 +:104880000022DA60704700004FF0804358637047A1 +:104890004FF08043586A7047264B2748DA6A42F047 +:1048A000070210B4DA62DA6A22F00702DA62DA6A20 +:1048B000DA6C42F00702DA64DA6E42F00702DA6676 +:1048C0004FF09042DB6E4FF0AA31002353604FF45B +:1048D000EE449160D0604FF6FF7050611462174C47 +:1048E00053621460164CC2F80434C2F80814C2F8BB +:1048F0000C444FF6F774C2F814444FF0EE44C2F87B +:10490000204447F29974C2F824440E4CC2F8004483 +:10491000C2F80438C2F80818C2F80C38C2F81408F3 +:10492000C2F82038C2F82438C2F800385DF8044BC9 +:1049300000F09CB80010024050010024A0010028A3 +:104940001050500050A0AA0008B500F035FAFFF74B +:10495000DFFBBDE80840FFF743BF000070470000E1 +:104960000F4B9A6D42F001029A659A6F42F0010274 +:104970009A670C4A9B6F936843F0010393604FF072 +:1049800080434F229A624FF0FF32DA6200229A612E +:104990005A63DA605A6001225A611A60704700BF98 +:1049A00000100240002004E04FF0804208B5116979 +:1049B000D3680B40D9B2C9439B07116107D52023A7 +:1049C00083F31188FFF7D0FB002383F3118808BD20 +:1049D00008B5244B4FF0FF319A6A99629A6A002217 +:1049E0009A62986AD86A60F00700D862D86A00F0C4 +:1049F0000700D862D86A186B1963186B1A63186BB2 +:104A0000986B60F080509863986B00F080509863CA +:104A1000986BD86BD963D86BDA63D86B186C196450 +:104A2000196C1A64196C996D41F080519965996FF0 +:104A300041F080519967996FD3F8901011F4407F3D +:104A40001EBF4FF48031C3F89010C3F89020D3F804 +:104A50009020C3F8902000F07FF9034B00225A60A9 +:104A600008BD00BF0010024000700040394B3A4AB8 +:104A70009A6501221A601A689007FCD500229A6094 +:104A80009A6812F00C0FFBD1344A4FF40071116098 +:104A900051694905FCD41A6842F480321A601A68D8 +:104AA0009203FCD52D490A6842F480720A602C4AB0 +:104AB0004FF4E06111601A6842F060021A601A68EF +:104AC00042F008021A601A689007FCD59A6812F042 +:104AD0000C0FFBD1D3F8942042F4C062C3F89420A9 +:104AE000204ADA601A6842F080721A601A689101EE +:104AF000FCD51D4A1A611A6842F080621A601A6871 +:104B00001201FCD500229A601549184AC3F8882082 +:104B10000A6822F0070242F004020A600A6802F002 +:104B20000702042AFAD19A6842F003029A609A684E +:104B300002F00C020C2AFAD11A6E42F001021A6637 +:104B4000D3F8802042F00102C3F88020D3F88030EF +:104B5000704700BF001002400004001000700040C9 +:104B60000020024003140001000C100055550134D0 +:104B7000074A08B5536903F00103536123B1054A9D +:104B800013680BB150689847BDE80840FEF788BE2F +:104B900000040140A8380020074A08B5536903F013 +:104BA0000203536123B1054A93680BB1D06898475B +:104BB000BDE80840FEF774BE00040140A83800209C +:104BC000074A08B5536903F00403536123B1054A4A +:104BD00013690BB150699847BDE80840FEF760BE05 +:104BE00000040140A8380020074A08B5536903F0C3 +:104BF0000803536123B1054A93690BB1D069984703 +:104C0000BDE80840FEF74CBE00040140A838002073 +:104C1000074A08B5536903F01003536123B1054AED +:104C2000136A0BB1506A9847BDE80840FEF738BEDA +:104C300000040140A8380020164B10B55C6904F44C +:104C400078725A61A30604D5134A936A0BB1D06AED +:104C50009847600604D5104A136B0BB1506B984708 +:104C6000210604D50C4A936B0BB1D06B9847E20533 +:104C700004D5094A136C0BB1506C9847A30504D5B1 +:104C8000054A936C0BB1D06C9847BDE81040FEF715 +:104C900007BE00BF00040140A8380020194B10B522 +:104CA0005C6904F47C425A61620504D5164A136DAE +:104CB0000BB1506D9847230504D5134A936D0BB182 +:104CC000D06D9847E00404D50F4A136E0BB1506EB7 +:104CD0009847A10404D50C4A936E0BB1D06E984747 +:104CE000620404D5084A136F0BB1506F9847230430 +:104CF00004D5054A936F0BB1D06F9847BDE81040BB +:104D0000FEF7CEBD00040140A838002008B50348D6 +:104D1000FEF7E8FEBDE80840FEF7C2BD04350020FE +:104D200008B50348FEF7DEFEBDE80840FEF7B8BD53 +:104D30007035002008B50348FEF7D4FEBDE80840F2 +:104D4000FEF7AEBDDC35002008B5FFF72DFEBDE84F +:104D50000840FEF7A5BD0000062108B50846FEF78D +:104D600045FF06210720FEF741FF06210820FEF738 +:104D70003DFF06210920FEF739FF06210A20FEF734 +:104D800035FF06211720FEF731FF06212820FEF708 +:104D90002DFF07211C20FEF729FF0C212520FEF7FF +:104DA00025FF0C212620FEF721FFBDE808400C213D +:104DB0002720FEF71BBF000008B5FFF709FE00F033 +:104DC00009F8FFF7B7F8FFF7C9FDBDE80840FFF79E +:104DD0004BBD00000023054A19460133102BC2E9E0 +:104DE000001102F10802F8D1704700BFA838002076 +:104DF0000B460146184600F025B8000000F038B810 +:104E0000012838BF012010B50446204600F028F8DC +:104E100030B900F007F808B900F00CF88047F4E763 +:104E200010BD0000024B1868BFF35B8F704700BFD6 +:104E30002839002008B5062000F032F90120FFF7DC +:104E4000D7FA000010B5054C13462CB10A460146AE +:104E50000220AFF3008010BD2046FCE700000000F8 +:104E6000024B0146186800F089B800BF28110020E5 +:104E7000024B0146186800F035B800BF2811002029 +:104E800010B501390244904201D1002005E00378B9 +:104E900011F8014FA34201D0181B10BD0130F2E7F9 +:104EA0002DE9F041A3B1C91A17780144044603F172 +:104EB000FF3C8C42204601D9002009E00578BD4224 +:104EC00004F10104F5D10CEB0405D618A54201D17B +:104ED000BDE8F08115F8018D16F801EDF045F5D02B +:104EE000E7E7000037B5002944D051F8043C0190B1 +:104EF000002BA1F10404B8BFE41800F0F5F81E4A35 +:104F00000198136833B96360146003B0BDE83040A2 +:104F100000F0F0B8A34208D9256861198B4201BF9F +:104F200019685B6849192160EDE71A465B680BB1A7 +:104F3000A342FAD911685518A5420BD1246821441F +:104F40005418A3421160E0D11C685B68536021448F +:104F50001160DAE702D90C230360D6E725686119EE +:104F60008B4204BF19685B68636004BF4919216004 +:104F70005460CAE703B030BD2C390020F8B5CD1C11 +:104F800025F0030508350C2D38BF0C25002D0646ED +:104F900001DBA94203D90C2333600020F8BD00F0E7 +:104FA000A3F821490A6814469CB9204F3B6823B9ED +:104FB0002146304600F03CF838602946304600F083 +:104FC00037F8431C23D10C233360304600F092F8AD +:104FD000E3E723685B1B17D40B2B03D923601C4426 +:104FE000256004E06368A2420CBF0B60536030464A +:104FF00000F080F804F10B00231D20F00700C21A16 +:10500000CCD01B1AA350C9E722466468CCE7C41C65 +:1050100024F00304A042E3D0211A304600F008F83F +:105020000130DDD1CFE700BF2C390020303900201E +:1050300038B5064D0023044608462B60FFF7D0F92B +:10504000431C02D12B6803B1236038BD34390020E2 +:105050001F2938B504460D4604D9162303604FF0C6 +:10506000FF3038BD426C12B152F821304BB92046A6 +:1050700000F030F82A4601462046BDE8384000F0EE +:1050800017B8012B0AD0591C03D116230360012045 +:10509000E7E7002442F82540284698470020E0E74B +:1050A000024B01461868FFF7D3BF00BF281100204C +:1050B00038B5074D00230446084611462B60FFF71C +:1050C0009BF9431C02D12B6803B1236038BD00BF9C +:1050D00034390020FFF78AB9034611F8012B03F891 +:1050E000012B002AF9D17047014800F009B800BF30 +:1050F00038390020014800F005B800BF38390020D9 +:1051000070470000704700006F72672E617264750F +:1051100070696C6F742E4D6174656B4C3433312D36 +:1051200050657269706800004E6F20617070207366 +:1051300069670A00426164206677206C656E677457 +:10514000682025750A0042616420626F6172645FA5 +:1051500069642025752073686F756C642062652012 +:1051600025750A0042616420667720646573637266 +:105170006970746F72206C656E6774682025750A9B +:1051800000426164206170702043524320307825D2 +:105190003038783A307825303878203078253038F3 +:1051A000783A3078253038780A00476F6F64206687 +:1051B00069726D776172650A0040A2E4F1646891DA +:1051C0000600000053544D33324C343F3F00000082 +:1051D0000435002070350020DC3500204261642059 +:1051E00043414E496661636520696E6465782E00AF +:1051F000800000000080000000008000000000002F +:10520000000000009D1B000889230008E922000817 +:10521000AD1B0008E51B0008E11D0008B11B0008DC +:10522000C51B0008B51B0008B91B0008C11B0008FE +:10523000BD1B0008091D0008C91B0008F525000852 +:10524000D91B0008DD1C00080096000000000000CB +:10525000000000000000000000000000000000004E +:1052600000000000FD3E0008E93E0008253F000860 +:10527000113F00081D3F0008093F0008F53E0008E7 +:10528000E13E0008313F00086D61696E00000000DA +:1052900069646C65000000009052000848370020E7 +:1052A00080380020010000000D41000800000000CF +:1052B00030AFFF7F01000000260400000000000066 +:1052C0000060030000000000FE2A0100D20400007C +:1052D000FF00000000000000C45100083F00000073 +:1052E0002C11002000000000000000000000000061 +:1052F00000000000000000000000000000000000AE +:10530000000000000000000000000000000000009D +:10531000000000000000000000000000000000008D +:10532000000000000000000000000000000000007D +:10533000000000000000000000000000000000006D +:045340000000000069 +:00000001FF diff --git a/Tools/bootloaders/MatekL431-Rangefinder_bl.bin b/Tools/bootloaders/MatekL431-Rangefinder_bl.bin new file mode 100755 index 00000000000..dea889eabdb Binary files /dev/null and b/Tools/bootloaders/MatekL431-Rangefinder_bl.bin differ diff --git a/Tools/bootloaders/Nucleo-G491_bl.bin b/Tools/bootloaders/Nucleo-G491_bl.bin index 4ac9842054b..36f66fcbb86 100755 Binary files a/Tools/bootloaders/Nucleo-G491_bl.bin and b/Tools/bootloaders/Nucleo-G491_bl.bin differ diff --git a/Tools/bootloaders/Nucleo-G491_bl.elf b/Tools/bootloaders/Nucleo-G491_bl.elf index 0a68987e3b0..99fb29a55d4 100755 Binary files a/Tools/bootloaders/Nucleo-G491_bl.elf and b/Tools/bootloaders/Nucleo-G491_bl.elf differ diff --git a/Tools/bootloaders/Nucleo-G491_bl.hex b/Tools/bootloaders/Nucleo-G491_bl.hex index 4af89c2b234..fb3f3c42650 100644 --- a/Tools/bootloaders/Nucleo-G491_bl.hex +++ b/Tools/bootloaders/Nucleo-G491_bl.hex @@ -1,19 +1,19 @@ :020000040800F2 -:1000000000060020E1010008FD0C0008010D0008B9 -:10001000590D0008010D00082D0D0008E30100082E -:10002000E3010008E3010008E3010008451A0008A5 +:1000000000060020E1010008490D0008C90C0008A5 +:10001000210D0008C90C0008F50C0008E3010008D8 +:10002000E3010008E3010008E3010008711A000879 :10003000E3010008E3010008E3010008E301000810 :10004000E3010008E3010008E3010008E301000800 -:10005000E3010008E3010008251E00084D1E00080A -:10006000751E00089D1E0008C51E0008E30100085B +:10005000E3010008E30100084D1E0008751E0008BA +:100060009D1E0008C51E0008ED1E0008E3010008E3 :10007000E3010008E3010008E3010008E3010008D0 :10008000E3010008E3010008E3010008E3010008C0 -:10009000E3010008E3010008E3010008ED1E000889 +:10009000E3010008E3010008E3010008151F000860 :1000A000E3010008E3010008E3010008E3010008A0 -:1000B000D51F0008E3010008E3010008E301000880 +:1000B000FD1F0008E3010008E3010008E301000858 :1000C000E3010008E3010008E3010008E301000880 -:1000D000E3010008C11F0008E3010008E301000874 -:1000E000511F0008E3010008E3010008E3010008D4 +:1000D000E3010008E91F0008E3010008E30100084C +:1000E000791F0008E3010008E3010008E3010008AC :1000F000E3010008E3010008E3010008E301000850 :10010000E3010008E3010008E3010008E30100083F :10011000E3010008E3010008E3010008E30100082F @@ -36,509 +36,513 @@ :10022000C0F2F0004EF68851CEF200010860BFF334 :100230004F8FBFF36F8F4FF00000E1EE100A4EF6C4 :100240003C71CEF200010860062080F31488BFF3F1 -:100250006F8F01F073FC01F053FC01F099FC4FF03B +:100250006F8F01F08DFC01F069FC01F0B3FC4FF0F1 :1002600055301F491B4A91423CBF41F8040BFAE745 :100270001C49194A91423CBF41F8040BFAE71A495C :100280001A4A1B4B9A423EBF51F8040B42F8040B2A :10029000F8E700201749184A91423CBF41F8040B87 -:1002A000FAE701F031FC01F0BFFC144C144DAC42F4 +:1002A000FAE701F047FC01F0D3FC144C144DAC42CA :1002B00003DA54F8041B8847F9E700F041F8114CC1 :1002C000114DAC4203DA54F8041B8847F9E701F0FA -:1002D00019BC0000000600200022002000000008D9 -:1002E0000000002000060020C82100080022002095 -:1002F0001022002010220020F4270020E001000836 +:1002D0002FBC0000000600200022002000000008C3 +:1002E0000000002000060020F82100080022002065 +:1002F000202200202022002008280020E001000801 :10030000E0010008E0010008E00100082DE9F04FDD :100310002DED108AC1F80CD0C3689D46BDEC108A43 :10032000BDE8F08F002383F311882846A047002002 -:1003300001F01AF9FEE701F0A5F800DFFEE7000082 -:1003400038B501F051FB054601F076FB0446D0B903 +:1003300001F020F9FEE701F0A5F800DFFEE700007C +:1003400038B501F063FB054601F088FB0446D0B9DF :100350000F4B9D4219D001339D420DBF00254FF434 -:100360007A7504460124002001F048FB0CB100F02E -:1003700059F800F0A3FC00F095FB284600F0A6F821 -:1003800000F050F8F9E70025EDE70546EBE700BF80 -:10039000010007B008B500F057FBA0F12003584258 -:1003A000584108BD07B5054B02211B88ADF8043044 -:1003B00001A800F067FB03B05DF804FB942000087F -:1003C00010B5202383F311881248C3680BB101F0E4 -:1003D00045F90023104A0F484FF47A7101F000F9F3 -:1003E000002383F311880D4C236813B12368013B6C -:1003F0002360636813B16368013B6360084B1B783B -:1004000033B9636823B9022000F0E6FB322363604E -:1004100010BD00BF10220020C10300082C230020C3 -:100420002422002010B5204B204953F8042F01321C -:1004300000D110BD8B42F8D11D4C1E4B22689A4250 -:1004400030D91D4B9B6803F1006303F5F0439A42DA -:1004500028D2002000F040FB184B0220187000F05A -:10046000B3FB174B9A6D00229A65996F9A67996F43 -:10047000D96DDA65D96FDA67D96F196E1A66D3F854 -:100480008010C3F88020D3F8803072B60D4A0E4B2E -:1004900013601B682268202181F311889D4683F335 -:1004A0000888104710BD00BFFC7700081C780008C2 -:1004B00004780008FF770008002200202422002092 -:1004C0000010024008ED00E0007800082DE9F04F30 -:1004D00099B0B94D00902022FF2110A8AC6800F01F -:1004E0008FFBB64A01951378A3B9B5480121C360C3 -:1004F0001170202383F31188C3680BB101F0AEF8AB -:100500000023B04AAE484FF47A7101F069F8002335 -:1005100083F31188009BAC4A03B11360AB4B009D81 -:10052000029300261E705660B2463746B14601203F -:1005300000F04AFB002D00F02582A34B1B68002B26 -:1005400040F0208219B0BDE8F08F0220FFF722FFB3 -:10055000002840F01082009B002E08BF1D469C4BD7 -:1005600002211B88ADF82C300BA800F08BFADEE7D7 -:100570004FF47A7000F068FAB0F10008EBDB02206B -:10058000FFF708FF0028E6D008F1FF38B8F1040FA4 -:1005900000F2F381DFE808F0031E2124270018A8E9 -:1005A000052340F8343D042100F06CFA012303FADE -:1005B00008F848EA0A0A5FFA8AFA4FF0000900F0E0 -:1005C00073FB27B10AF00B030B2B08BF0025FFF7C5 -:1005D000E9FEACE704217848E6E704217D48E3E73B -:1005E00004217D48E0E74FF01C09484600F076FA08 -:1005F00009F104090B9004210BA800F043FAB9F1AA -:100600002C0FF2D1D2E7002FA5D00AF00B030B2B51 -:10061000A1D10220FFF7BEFE804600289BD001201A -:100620006A4E00F059FA0220307000F0CDFA00272F -:100630005FFA87FB584600F05FFA054688B15846D6 -:1006400000F06AFA01370028F2D146460025634BD4 -:1006500002211B88ADF82C300BA800F013FA474696 -:1006600065E701230220337000F0A6FA2C46019BB7 -:100670009B689C4206D2204600F030FA0130E4D15B -:100680000434F4E7029B00241C704F4B46465C6028 -:100690004746254693E7002F3FF45DAF0AF00B0372 -:1006A0000B2B7FF458AF029B0220187000F08CFADD -:1006B000322000F0C9F9B0F1000BFFF64CAF1BF08F -:1006C00003087FF448AF019B996804EB0B028A4250 -:1006D0003FF641AFBBF5807F3FF63DAF404A039206 -:1006E000D8450FDA4FF47A7000F0AEF9049004990F -:1006F0000029FFF630AF039A049908F8021008F1B8 -:100700000108ECE7C820FFF745FE804600283FF4CB -:1007100022AF1F2C11D8C4F120075F4528BF5F46C8 -:1007200010AB24F003003A462D49184400F05EFA5D -:100730003A46FF212A4800F063FA4FEAAB03DAB2E7 -:1007400027490393204600F063FA074600283FF448 -:100750007EAF039B04EB830431E70220FFF71AFE10 -:1007600000283FF4F8AE00F0F1F900283FF4F3AEB2 -:100770004FF000084346019A9268904532D2B8F192 -:100780001F0F12D8109A01320FD028F0030218A9B7 -:100790000A4452F8202C0B92184604220BA900F0B0 -:1007A000EFFA08F104080346E5E74046039300F03A -:1007B00095F9039B0B90EFE70022002028230020EF -:1007C00010220020C10300082C2300202422002036 -:1007D000962000080422002008220020982000080B -:1007E0002822002018A8042140F84C3D00F04AF9C6 -:1007F000E5E618A8002340F8343D642100F038F9FC -:1008000000287FF4A8AE0220FFF7C4FD00283FF4C3 -:10081000A2AE0B9800F092F918AB43F8480D0421F2 -:100820001846E3E718A8002340F8343D642100F09F -:100830001FF900287FF48FAE0220FFF7ABFD0028E0 -:100840003FF489AE0B9800F07BF918AB43F8440DE8 -:10085000E5E70220FFF79EFD00283FF47CAE00F0A4 -:1008600085F918AB43F8400DD9E70220FFF792FD58 -:1008700000283FF470AE0BA9142000F07DF98046EB -:1008800018A8042140F83C8D00F0FCF841460BA864 -:10089000ACE7322000F0D8F8B0F10008FFF65BAE0C -:1008A00018F0030F7FF457AE019A926808EB090322 -:1008B00093423FF650AE0220FFF76CFD00283FF454 -:1008C0004AAE28F00308C844C1453FF478AE484614 -:1008D00000F004F904210A900AA800F0D3F809F105 -:1008E0000409F1E74FF47A70FFF754FD00283FF454 -:1008F00032AE00F02BF9002842D0109B01330BD010 -:10090000082210A9002000F083F9002838D0202206 -:10091000FF2110A800F074F9FFF744FD364800F0FD -:1009200029FE0FE6002F3FF416AE0AF00B030B2B47 -:100930007FF411AE18A8002340F8343D642100F084 -:1009400097F8804600287FF406AE0220FFF722FDCC -:1009500000283FF400AE0390FFF724FD41F28830F9 -:1009600000F008FE0B9800F0B5F900F09DF9039B2C -:1009700045461F46DBE5074621E64FF00009EAE55C -:10098000B84664E6002000F05FF80490049B002B5A -:10099000FFF6D0AD012000F00FF9049B213B122B94 -:1009A0003FF6C5AD01A252F823F000BF4B05000889 -:1009B00071050008070600082F0500082F0500082C -:1009C0002F05000897060008930800085B07000839 -:1009D000F307000825080008530800082F05000841 -:1009E0006B0800082F050008E5080008BF0500088F -:1009F0002F05000825090008A086010070B50F4BDF -:100A00000C4619780131C9B2012906460FD80C48A5 -:100A100003681D6A4FF47A73534331462246A84750 -:100A2000844204D1074B00221A70012070BD4FF49C -:100A3000FA7000F09FFD002070BD00BF0C22002066 -:100A40007C2300207823002007B502AB002203F8A6 -:100A5000012D012102461846FFF7D0FF20B19DF875 -:100A6000070003B05DF804FB4FF0FF30F9E700002A -:100A70000A4608B50421FFF7C1FF80F00100C0B2AB -:100A8000404208BD30B4054C2368DD69044B0A467A -:100A9000AC460146204630BC604700BF7C230020A6 -:100AA000A086010070B500F0A1FE094C094E20801F -:100AB000002530682388834208D900F093FE33680C -:100AC00005440133B5F5F04F3360F2D370BD00BF7C -:100AD0007A2300203423002000F036BF00F10060AC -:100AE00000F5F0400068704700F10060920000F5EA -:100AF000F04000F0B7BE0000054B1A68054B1B889C -:100B00009B1A834202D9104400F06CBE002070474B -:100B1000342300207A23002038B5074D0446286886 -:100B2000204400F065FE28B928682044BDE838401C -:100B300000F070BE38BD00BF342300200020704795 -:100B4000014BC058704700BF9075FF1F064991F8D0 -:100B5000243033B100230822086A81F82430FFF7DB -:100B6000C3BF0120704700BF38230020014B186825 -:100B7000704700BF002004E070B50E4B5C6893F92D -:100B8000086001380A18013C0B4693420FD214F951 -:100B9000015F581C1DB1034600F8015CF5E72C24E9 -:100BA00082421C7001D9981C5E70401A70BD1846B4 -:100BB000FBE700BF7C230020022802BF4FF09043D8 -:100BC00020229A6170470000022802BF4FF0904334 -:100BD0004FF400129A617047022801BF4FF0904213 -:100BE000536983F0200353617047000010B5002360 -:100BF000934203D0CC5CC4540133F9E710BD00002C -:100C000002440346934202D003F8011BFAE77047FF -:100C10002DE9F047234C94F82430054688461746C2 -:100C200083BB2E46DFF87C90C7B394F824302BB9F1 -:100C30002022FF2148462662FFF7E2FF94F82400B5 -:100C4000C0F10805BD4228BF3D465FFA85FAAD00F8 -:100C500041462A4604EB8000FFF7C8FF94F8243091 -:100C6000A7EB0A079A445FFA8AFABAF1080F2E44F2 -:100C7000A844FFB284F824A0D6D1FFF767FF00286C -:100C8000D2D108E0266A06EB8306B042CAD0FFF74D -:100C90005DFF0028C5D10020BDE8F0870120BDE838 -:100CA000F08700BF38230020024B1A78024B1A70DD -:100CB000704700BF782300200C220020034904481D -:100CC0004FF4E1330B6000F01DBB00BF6023002038 -:100CD0007C230020074B10B500210446182218463B -:100CE000FFF78EFF04600146BDE81040024800F0A7 -:100CF00009BB00BF602300207C230020FEE700002A -:100D000000B59BB0EFF3098168226846FFF76EFFDC -:100D1000EFF30583044B9A6BDA6A9A6A9A6A9A6AC5 -:100D20009A6A9A6A9B6AFEE700ED00E000B59BB004 -:100D3000EFF3098168226846FFF758FFEFF3058358 -:100D4000044B9A6B9A6A9A6A9A6A9A6A9A6A9B6A36 -:100D5000FEE700BF00ED00E000B59BB0EFF30981B6 -:100D600068226846FFF742FFEFF30583034B5A6B97 -:100D70009A6A9A6A9A6A9A6A9B6AFEE700ED00E0AC -:100D800030B5084D0A4491420BD011F8013B0924BB -:100D90005840013CF7D040F300032B4083EA500059 -:100DA000F7E730BD2083B8ED026843681143016066 -:100DB00003B1184770470000024A136843F0C003AC -:100DC000136070470038014013B50E4C204600F008 -:100DD0008DFA04F11400009400234FF480720A4944 -:100DE00000F04EF90094094B09494FF4807204F168 -:100DF000380000F0C7F9074BE365074B236602B0E4 -:100E000010BD00BF7C230020E8230020B90D00089E -:100E1000E824002000380140007A030A244B00290E -:100E200008BF1946037C012B30B50FD1214B9842E6 -:100E30000CD1214B1A6E42F480421A66D3F88020FE -:100E400042F48042C3F88020D3F880300A68036EF1 -:100E5000C46D816603EB5203B3FBF2F34A681504D9 -:100E600042BF23F0070503F0070343EA4503E360AD -:100E70008B6843F040036360CB6843F00103A360D9 -:100E800042F4967343F00103236051054FF0FF33A2 -:100E9000236205D512F0102205D0B2F1805F04D094 -:100EA00080F8643030BD7F23FAE73F23F8E700BFC6 -:100EB0009C2000087C230020001002402DE9F04710 -:100EC000C66D3768F46934620546200719D014F0FE -:100ED000080F0CBF00218021E20748BF41F020012C -:100EE000A30748BF41F04001600748BF41F480714B -:100EF000202383F31188281DFFF756FF002383F377 -:100F00001188E2050AD5202383F311884FF400717C -:100F1000281DFFF749FF002383F311884FF02009B4 -:100F20004FF0000A14F0200831D13B0616D54FF0DF -:100F3000200905F1380A200610D589F3118850469A -:100F400000F054F900282FDA0821281DFFF72CFFA4 -:100F500027F080033360002383F3118879060DD5D1 -:100F600062060BD5202383F31188EA6C2B6D9A421D -:100F700001D12B6CEBB9002383F31188E30620D554 -:100F8000AA6E1369EBB15069BDE8F047184789F3C1 -:100F90001188736A95F864102846194000F0C0F96A -:100FA0008AF31188F469BDE7B06288F31188F469A7 -:100FB000C1E71021281D27F04007FFF7F5FE376035 -:100FC000D9E7BDE8F0870000F8B5154682680669E4 -:100FD000AA420B46816938BF8568761AB542044635 -:100FE00007D218462A46FFF701FEA3692B44A361E6 -:100FF0000DE011D932461846FFF7F8FDAF1B3A460F -:10100000E1683044FFF7F2FDE2683A44A261A36868 -:101010005B1BA3602846F8BD18462A46FFF7E6FD8D -:10102000E368E4E783682DE9F041044693421546FE -:10103000266938BF85684069361AB5420F4606D220 -:101040002A46FFF7D3FD63692B4463610DE012D993 -:101050003246A5EB0608FFF7C9FD4246B919E0681C -:10106000FFF7C4FDE26842446261A3685B1BA360B2 -:101070002846BDE8F0812A46FFF7B8FDE368E4E7BB -:1010800010B50A440024C361029B00604060846084 -:10109000C160816141610261036210BD08B582696E -:1010A0004369934201D1826882B9826801328260C9 -:1010B0005A1C42611970426903699A4201D3C3689C -:1010C0004361002100F072FA002008BD4FF0FF30AC -:1010D00008BD000070B5202304460E4683F3118836 -:1010E000A568A5B1A368A269013BA360531CA361D5 -:1010F00015782269934224BFE368A361E3690BB1C9 -:1011000020469847002383F31188284670BD314656 -:10111000204600F03BFA0028E2DA85F3118870BD22 -:101120002DE9F74F05460F4690469A46D0F81C9099 -:10113000202686F311884FF0000B144664B1224636 -:1011400039462846FFF740FF034668B9514628460E -:1011500000F01CFA0028F1D0002383F31188A8EBDB -:10116000040003B0BDE8F08FB9F1000F03D0019087 -:101170002846C847019B8BF31188E41A1F4486F365 -:101180001188DBE7C16081614161C3611144009B4B -:10119000006040608260016103627047F8B50446F8 -:1011A0000E461746202383F31188A568A5B1A368CE -:1011B000013BA36063695A1C62611E702369626906 -:1011C0009A4224BFE3686361E3690BB12046984704 -:1011D000002080F31188F8BD3946204600F0D6F98A -:1011E0000028E2DA85F31188F8BD000083694269BE -:1011F0009A4210B501D182687AB982680132826060 -:101200005A1C82611C7803699A4201D3C3688361C6 -:10121000002100F0CBF9204610BD4FF0FF3010BD8B -:101220002DE9F74F05460F4690469A46D0F81C9098 -:10123000202686F311884FF0000B144664B1224635 -:1012400039462846FFF7EEFE034668B95146284660 -:1012500000F09CF90028F1D0002383F31188A8EB5B -:10126000040003B0BDE8F08FB9F1000F03D0019086 -:101270002846C847019B8BF31188E41A1F4486F364 -:101280001188DBE7026843681143016003B1184726 -:10129000704700001430FFF743BF00004FF0FF33EA -:1012A0001430FFF73DBF00003830FFF7B9BF000032 -:1012B0004FF0FF333830FFF7B3BF00001430FFF7B3 -:1012C00009BF00004FF0FF311430FFF703BF0000EB -:1012D0003830FFF763BF00004FF0FF323830FFF7C0 -:1012E0005DBF000000207047FFF76EBD044B036038 -:1012F000002343608360C36001230374704700BF11 -:10130000B420000810B52023044683F31188FFF7AA -:1013100085FD02232374002383F3118810BD000090 -:1013200038B5C36904460D461BB904210844FFF7CC -:10133000A9FF294604F11400FFF7B0FE002806DAE1 -:10134000201D4FF48061BDE83840FFF79BBF38BDDA -:10135000024B00221B605B609A607047E82500200A -:10136000002303748268054B1B6899689142FBD285 -:101370005A6803604260106058607047E82500209A -:1013800008B5202383F31188037C032B05D0042B9D -:101390000DD02BB983F3118808BD436900221A6070 -:1013A0004FF0FF334361FFF7DBFF0023F2E790E8E4 -:1013B0000C001A6002685360F2E700000023037417 -:1013C0008268054B1B6899689142FBD85A68036094 -:1013D0004260106058607047E8250020054B19698D -:1013E0000874186802681A60536018610123037456 -:1013F000FEF78CBFE825002030B54B1C87B00546B2 -:101400000A4C10D023690A4A01A800F0E9F82846DE -:10141000FFF7E4FF049B13B101A800F01FF9236953 -:10142000586907B030BDFFF7D9FFF8E7E82500207D -:101430008113000838B50C4D41612B6981689A68A9 -:101440009142044603D8BDE83840FFF789BF1846EB -:10145000FFF7B4FF01232C61014623742046BDE849 -:101460003840FEF753BF00BFE8250020044B1A6840 -:101470001B6990689B68984294BF002001207047C8 -:10148000E825002010B5084C236820691A682260FE -:101490005460012223611A74FFF790FF014620690E -:1014A000BDE81040FEF732BFE8250020FEE700004F -:1014B00010B50C4CFFF74CFF00F084F880220A496D -:1014C000204600F017F8012344F8180C037400F0CC -:1014D000C9FA002383F3118862B60448BDE81040BE -:1014E00000F02AB810260020DC200008E4200008C4 -:1014F00000F0F0B882600222027400224274704749 -:101500008368A3F17C0243F80C2C026943F83C2C5D -:10151000426943F8382C074A43F81C2CC26843F848 -:10152000102C022203F8082C002203F8072CA3F148 -:10153000180070472503000810B5202383F3118895 -:10154000FFF7DEFF00210446FFF774FF002383F35B -:101550001188204610BD0000024B1B6958610F2006 -:10156000FFF73CBFE8250020202383F31188FFF715 -:10157000F3BF000008B50146202383F3118808203B -:10158000FFF73AFF002383F3118808BD49B1064BEA -:1015900042681B6918605A60136043600420FFF7BB -:1015A0002BBF4FF0FF307047E825002003689842BA -:1015B00006D01A680260506059611846FFF7D0BE25 -:1015C00070470000054B03F114025A619A614FF015 -:1015D000FF32DA6100221A62704700BFE82500205E -:1015E000F8B50361C2600E46054600F0BDFA1A4B1D -:1015F00019461F4651F8142F8A420DD11862AE6069 -:101600006A602A60022E2CBF801902309D615D61E4 -:10161000BDE8F84000F096BA1B6A9268C41A341903 -:1016200028BF3446A24202D9181900F099FA7B6902 -:101630009A6894420CD8AC6098685A682B60041B76 -:101640006A6015605D609C604FF0FF33FB61F8BD20 -:10165000A41A1B68ECE700BFE825002038B51C4B36 -:1016600001685A6990421D460DD0446821600268A5 -:1016700000215460C16091688068014491604FF01E -:10168000FF32DA6138BD1A4642F8141F4A605B69BE -:1016900000219342C16003D1BDE8384000F05ABA3E -:1016A0009A6881680A449A602C6A00F05DFA6A6957 -:1016B0009268001B824209D9111A012998BF821C25 -:1016C000286ABDE83840104400F04ABA38BD00BF6F -:1016D000E82500202DE9F041184D002705F11406FA -:1016E0006C6900F041FA2A6AA368811A8B4216D805 -:1016F00013442B6294E80C001A602268D4F80C8022 -:1017000053606B69E760B34201D100F023FA87F3BD -:1017100011882069C047202383F31188E0E76A69B4 -:10172000B24208D05B1A022B2CBFC0180230BDE8B1 -:10173000F04100F015BABDE8F08100BFE8250020B7 -:1017400000207047FEE70000704700004FF0FF30B8 -:1017500070470000BFF34F8F024A1369DB03FCD4CC -:10176000704700BF0020024008B5094B1B7873B9D1 -:10177000FFF7F0FF074B5A69002ABFBF064A9A607D -:1017800002F188329A601A6822F480621A6008BDF9 -:1017900070270020002002402301674508B50B4B4D -:1017A0001B7893B9FFF7D6FF094B5A6942F0004204 -:1017B0005A611A6842F480521A601A6822F4805200 -:1017C0001A601A6842F480621A6008BD702700200F -:1017D000002002407F289ABF00F58030C002002020 -:1017E000704700004FF40060704700008020704791 -:1017F0007F2808B50BD8FFF7EDFF00F500630268FE -:10180000013204D104308342F9D1012008BD002007 -:1018100008BD00007F2810B504461FD8FFF79AFFC7 -:10182000FFF7A2FF0E4BF3221A6102225A615A6996 -:1018300042EAC0025A615A6942F480325A61FFF7A3 -:1018400089FFFFF7C7FF4FF4006100F0E7F8FFF7EB -:10185000A5FF2046BDE81040FFF7CABF002010BD1D -:10186000002002402DE9F84340EA020313F0070389 -:10187000144606D02E4B40F2BF221A600020BDE86D -:10188000F88385182B4A95420CD9294A4FF43171B7 -:101890001160F3E7031D1B684A68934208D1083CB6 -:1018A00008300831072C14D903680A689342F1D034 -:1018B000FFF75AFFFFF74EFF1F4E08314FF00108A8 -:1018C0004FF00009012CA1F1080707D8FFF766FFC8 -:1018D00001E0002CECD10120BDE8F883C6F81480AB -:1018E000054651F8083C45F8043B51F8043C436078 -:1018F000FFF730FFC6F81490026851F8083C9A428E -:101900000CD00B4B40F2EA221A600C4B18600C4BC7 -:101910001C600C4B1F60FFF741FFAFE72D680831DB -:1019200051F80C3C9D42ECD1083C0830CAE700BF9E -:101930006C270020FFFF03080020024060270020E2 -:101940006827002064270020084908B50B7828B1D3 -:1019500053B9FFF709FF01230B7008BD23B1BDE8A0 -:1019600008400870FFF71ABF08BD00BF70270020AD -:1019700002440439D2B2904200D17047431C800027 -:1019800000F1804000F51450006841F8040FD8B20F -:10199000F1E70000124B10B5D3F89040240409D4AD -:1019A000D3F89040C3F89040D3F8904044F40044FA -:1019B000C3F890400B4C2368024443F480732360C7 -:1019C0000439D2B2904200D110BD431C800000F116 -:1019D000804000F5145051F8044F0460D8B2F1E78C -:1019E000001002400070004007B5012201A900204C -:1019F000FFF7BEFF019803B05DF804FB13B5044682 -:101A0000FFF7F2FFA04206D002A9012241F8044DDF -:101A10000020FFF7BFFF02B010BD000070470000BC -:101A2000034B1B689B0042BF024B01221A70704798 -:101A30009410024071270020014B1878704700BFB6 -:101A400071270020EFF3098305494A6822F001025B -:101A50004A60683383F30988002383F31188704751 -:101A600030EF00E0202080F3118862B60B4B0C4A67 -:101A7000D96821F4E0610904090C0A430949DA60D4 -:101A8000CA6842F08072CA6007490A6842F00102DF -:101A90000A601022DA7783F82200704700ED00E038 -:101AA0000003FA05F0ED00E0001000E010B520237F -:101AB00083F311880E4B5B6813F4006314D0F1EECE -:101AC000103AEFF30984683C4FF08073E361094BEF -:101AD000DB68236684F30988FFF7C8FC10B1064B66 -:101AE000A36110BD054BFBE783F3118810BD00BF58 -:101AF00000ED00E030EF00E0370300083A03000893 -:101B000070470000FEE70000084A094B09498B4274 -:101B100004D3094A0021934205D3704752F8040FB9 -:101B200043F8040BF3E743F8041BF4E7D42100085F -:101B3000F4270020F4270020F4270020704700003D -:101B400000F07EB84FF08043002258631A610222F1 -:101B5000DA6070474FF080430022DA60704700007F -:101B60004FF08043586370474FF08043586A704786 -:101B70004B6843608B688360CB68C3600B694361CB -:101B80004B6903628B6943620B6803607047000016 -:101B900008B51D4BDA6A42F07F02DA62DA6A22F097 -:101BA0007F02DA62DA6ADA6C42F07F02DA64DA6EB5 -:101BB00042F07F02DA66154ADB6E11464FF0904024 -:101BC000FFF7D6FF124802F11C01FFF7D1FF1148C1 -:101BD00002F13801FFF7CCFF0F4802F15401FFF783 -:101BE000C7FF0E4802F17001FFF7C2FF0C4802F177 -:101BF0008C01FFF7BDFF0B4802F1A801FFF7B8FF0A -:101C0000BDE8084000F070B8001002400421000850 -:101C10000004004800080048000C0048001000487C -:101C2000001400480018004808B500F019FAFFF742 -:101C30003FFCBDE80840FFF7F3BE0000704700001E -:101C40000F4B9A6D42F001029A659A6F42F00102C1 -:101C50009A670C4A9B6F936843F0010393604FF0BF -:101C60008043A7229A624FF0FF32DA6200229A6123 -:101C70005A63DA605A6001225A611A60704700BFE5 -:101C800000100240002004E04FF0804208B51369C4 -:101C9000D1680B40D9B2C9439B07116107D52023F6 -:101CA00083F31188FFF724FC002383F3118808BD18 -:101CB00008B50B4BD3F8902012F4407F1FBF4FF4B0 -:101CC0008032C3F890200022C3F89020D3F89020EF -:101CD000C3F8902000F086F9024B00225A6008BD3C -:101CE0000010024000700040484B4FF0FF319A6AEC -:101CF00099629A6A00229A62986AD86A60F07F00B4 -:101D0000D862D86A00F07F00D862D86A186B19636D -:101D1000186B1A63186B986B9963986B9A63986B3E -:101D2000D86BD963D86BDA63D86B186C1964196CEB -:101D30001A641A6C9A6D42F080529A659A6F22F07A -:101D400080529A679A6F324A4FF40071116051695C -:101D500011F48061FBD14FF40040516090604FF46A -:101D60008070D160C2F88000116251629162D162CC -:101D7000116351639163D163116451649164D164BF -:101D800011655165D3F8982042F00102C3F89820FC -:101D9000D3F898209007FBD51A6842F480321A6075 -:101DA0001A689103FCD51A490A6842F480720A60E5 -:101DB000184ADA601A6842F080721A601A68920152 -:101DC000FCD5002214499A60C3F88810C3F89C20FF -:101DD000124A13491160116801F00F010429FAD168 -:101DE0009A6842F003029A609A6802F00C020C2A88 -:101DF000FAD11A6E42F001021A66D3F8802042F03E -:101E00000102C3F88020D3F88030704700100240F0 -:101E100000700040232A610155010050002002405B -:101E200004070400074A08B5536903F0010353612E -:101E300023B1054A13680BB150689847BDE80840C4 -:101E4000FFF734BE0004014074270020074A08B59C -:101E5000536903F00203536123B1054A93680BB140 -:101E6000D0689847BDE80840FFF720BE0004014055 -:101E700074270020074A08B5536903F0040353612F -:101E800023B1054A13690BB150699847BDE8084072 -:101E9000FFF70CBE0004014074270020074A08B574 -:101EA000536903F00803536123B1054A93690BB1E9 -:101EB000D0699847BDE80840FFF7F8BD000401402D -:101EC00074270020074A08B5536903F010035361D3 -:101ED00023B1054A136A0BB1506A9847BDE8084020 -:101EE000FFF7E4BD0004014074270020164B10B535 -:101EF0005C6904F478725A61A30604D5134A936AA4 -:101F00000BB1D06A9847600604D5104A136B0BB129 -:101F1000506B9847210604D50C4A936B0BB1D06BDC -:101F20009847E20504D5094A136C0BB1506C9847E9 -:101F3000A30504D5054A936C0BB1D06C9847BDE856 -:101F40001040FFF7B3BD00BF00040140742700201C -:101F5000194B10B55C6904F47C425A61620504D5E2 -:101F6000164A136D0BB1506D9847230504D5134ADB -:101F7000936D0BB1D06D9847E00404D50F4A136EF2 -:101F80000BB1506E9847A10404D50C4A936E0BB167 -:101F9000D06E9847620404D5084A136F0BB1506F96 -:101FA0009847230404D5054A936F0BB1D06F984727 -:101FB000BDE81040FFF77ABD0004014074270020FF -:101FC00008B50348FEF77AFFBDE80840FFF76EBD8D -:101FD0007C23002008B5FFF757FEBDE80840FFF757 -:101FE00065BD0000062108B5084600F023F806216B -:101FF000072000F01FF80621082000F01BF806213A -:10200000092000F017F806210A2000F013F8062135 -:10201000172000F00FF80621282000F00BF8072108 -:102020001C2000F007F80C212520BDE8084000F036 -:1020300001B8000000F1604300F01F02400903F501 -:10204000614309018000C9B200F1604083F80013C8 -:1020500000F5614001239340C0F880310360704770 -:1020600008B5FFF725FE00F009F8FFF73DF9FFF787 -:10207000E5FDBDE80840FFF763BD0000002304490B -:102080001A465A50C8180833802B4260F9D170475D -:102090007427002012101213121100000096000085 -:1020A0000000000000000000000000000000000030 -:1020B0000000000000000000B11200089D1200089E -:1020C000D9120008C5120008D1120008BD1200087C -:1020D000A912000895120008E51200086D61696EEA -:1020E00000000000FC2000082826002060270020B7 -:1020F00001000000AD1400080000000069646C6578 -:10210000000000000004282800000000AAAABEAABF -:1021100000001400DFFF0000000000007007000056 -:102120000000000000000000AAAAAAAA0000000007 -:10213000FFFF0000000000000000000000000000A1 -:1021400000000000AAAAAAAA00000000FFFF0000E9 -:10215000000000000000000000000000000000007F -:10216000AAAAAAAA00000000FFFF000000000000C9 -:10217000000000000000000000000000AAAAAAAAB7 -:1021800000000000FFFF0000000000000000000051 -:102190000000000000000000AAAAAAAA0000000097 -:1021A000FFFF000000000000000000000000000031 -:1021B00000000000AAAAAAAA00000000FFFF000079 -:1021C00000000000000000001004000000000000FB -:0821D00000880300FF0000007D +:100360007A7504460124002001F05AFB0CB100F01C +:1003700057F800F089FC00F07FFB284600F0A0F859 +:1003800000F04EF8F9E70025EDE70546EBE700BF82 +:10039000010007B008B500F041FBA0F1200358426E +:1003A000584108BD07B541F21203022101A8ADF87A +:1003B000043000F051FB03B05DF804FB10B52023BE +:1003C00083F311881248C3680BB101F04BF9114A4D +:1003D0000F4800234FF47A7101F008F9002383F3EA +:1003E00011880D4C236813B12368013B23606368B7 +:1003F00013B16368013B6360084B1B7833B96368D2 +:1004000023B9022000F0D6FB3223636010BD00BF89 +:1004100020220020BD0300083C23002034220020BD +:1004200038B5214A214B196801313CD0043393423D +:10043000F9D11F4C1D4DD4F80428AA4233D31D4BCB +:100440009B6803F1006303F5F0439A422BD200202E +:1004500000F02CFB184B0220187000F0A3FB174B88 +:100460009A6D00229A65996F9A67996FD96DDA65CE +:10047000D96FDA67D96F196E1A66D3F88010C3F88E +:100480008020D3F8803072B64FF0E0232021C3F8EB +:10049000085DD4F80038D4F8042881F311889D460B +:1004A00083F30888104738BD2078000800780008DA +:1004B00000700008002200203422002000100240BA +:1004C0002DE9F04F93B0A94B00902022FF210AA8FC +:1004D0009D6800F083FBA64A1378A3B9A5480121C3 +:1004E000C3601170202383F31188C3680BB101F03E +:1004F000B9F8A14A9F4800234FF47A7101F076F8C9 +:10050000002383F31188009B9C4A03B113609C492C +:10051000009C00230B70536098469B461E469A46EB +:10052000012000F03FFB24B1944B1B68002B00F02E +:100530001682002000F072FA0390039B002BF2DB7E +:10054000012000F027FB039B213B162BE8D801A2DA +:1005500052F823F0B1050008D90500086D0600081F +:1005600021050008210500082105000801070008F1 +:10057000D3080008ED0700084F08000877080008B6 +:100580009D08000821050008AF08000821050008A3 +:100590002109000851060008210500086509000826 +:1005A000BD05000851060008210500084F08000895 +:1005B0000220FFF7EFFE002840F0FB81009B0221A4 +:1005C000B8F1000F08BF1C4605A841F21233ADF880 +:1005D000143000F041FAA3E74FF47A7000F01EFAED +:1005E000071EEBDB0220FFF7D5FE0028E6D0013F17 +:1005F000052F00F2E081DFE807F0030A0D10133643 +:1006000005230593042105A800F026FA17E05748B2 +:100610000421F9E75B480421F6E75B480421F3E78E +:100620004FF01C09484600F043FA09F1040905900F +:10063000042105A800F010FAB9F12C0FF2D1012025 +:1006400000FA07F747EA0B0B5FFA8BFB4FF0000A43 +:1006500000F010FB26B10BF00B030B2B08BF00249E +:10066000FFF7A0FE5CE749480421CDE7002EA5D0A6 +:100670000BF00B030B2BA1D10220FFF78BFE0746DB +:1006800000289BD001203E4E00F010FA022030706E +:1006900000F088FA4FF000085FFA88F9484600F049 +:1006A00017FA044690B1484600F022FA08F1010812 +:1006B0000028F1D1B846044641F21213022105A8E0 +:1006C000ADF814303E4600F0C7F929E701230220B7 +:1006D000337000F05FFA2546244B9B68AB4207D984 +:1006E000284600F0E5F9013040F068810435F3E771 +:1006F000234B00251D70214BB8465D603E46A7E7A1 +:10070000002E3FF45BAF0BF00B030B2B7FF456AFC7 +:100710001B4B0220187000F045FA322000F07EF9E1 +:10072000B0F10009FFF64AAF19F003077FF446AFB6 +:100730000E4A926809EB050393423FF63FAFB9F5C5 +:10074000807F3FF73BAF124B0193B94522DD4FF459 +:100750007A7000F063F90390039A002AFFF62EAF37 +:10076000019B039A03F8012B0137EDE700220020DB +:100770003823002020220020BD0300083C23002055 +:100780003422002004220020082200200C22002015 +:1007900038220020C820FFF7FDFD074600283FF45F +:1007A0000DAF1F2D11D8C5F120024A450AAB25F027 +:1007B000030028BF4A4683490192184400F004FA16 +:1007C000019A8048FF2100F009FA4FEAA9037D4908 +:1007D0000193C9F38702284600F008FA064600286C +:1007E0003FF46AAF019B05EB830531E70220FFF779 +:1007F000D1FD00283FF4E2AE00F096F900283FF466 +:10080000DDAE0027B946704B9B68BB4218D91F2F3D +:1008100011D80A9B01330ED027F0030312AA134408 +:1008200053F8203C05934846042205A900F08EFAAF +:1008300004378146E7E7384600F03AF90590F2E7D9 +:10084000CDF81490042105A800F006F900E7002374 +:10085000642104A8049300F0F5F800287FF4AEAEFC +:100860000220FFF797FD00283FF4A8AE049800F09F +:1008700051F90590E6E70023642104A8049300F0F1 +:10088000E1F800287FF49AAE0220FFF783FD0028EC +:100890003FF494AE049800F03FF9EAE70220FFF736 +:1008A00079FD00283FF48AAE00F04EF9E1E702201E +:1008B000FFF770FD00283FF481AE05A9142000F079 +:1008C00049F904210746049004A800F0C5F8394608 +:1008D000B9E7322000F0A2F8071EFFF66FAEBB07A3 +:1008E0007FF46CAE384A926807EB0A0393423FF6F6 +:1008F00065AE0220FFF74EFD00283FF45FAE27F003 +:1009000003075744BA453FF4A3AE504600F0D0F871 +:100910000421059005A800F09FF80AF1040AF1E708 +:100920004FF47A70FFF736FD00283FF447AE00F031 +:10093000FBF8002844D00A9B01330BD008220AA9F7 +:10094000002000F053F900283AD02022FF210AA805 +:1009500000F044F9FFF726FD1C4800F011FE13B02B +:10096000BDE8F08F002E3FF429AE0BF00B030B2BEC +:100970007FF424AE0023642105A8059300F062F8FB +:10098000074600287FF41AAE0220FFF703FD8146D8 +:1009900000283FF413AEFFF705FD41F2883000F068 +:1009A000EFFD059800F07CF94E4600F063F93C46F7 +:1009B000B6E506464CE64FF0000AFFE5B8467BE692 +:1009C000374679E63822002000220020A086010068 +:1009D00070B50F4B1B780133DBB2012B0C4611D8DD +:1009E0000C4D29684FF47A730E6AA2FB033201465C +:1009F00022462846B047844204D1074B00221A7091 +:100A0000012070BD4FF4FA7000F0BAFD0020F8E745 +:100A1000102200208C2300208823002007B500230B +:100A2000024601210DF107008DF80730FFF7D0FFD6 +:100A300020B19DF8070003B05DF804FB4FF0FF30D4 +:100A4000F9E700000A4608B50421FFF7C1FF80F06E +:100A50000100C0B2404208BD30B4054C2368DD69D6 +:100A6000044B0A46AC460146204630BC604700BFF6 +:100A70008C230020A086010070B500F0B9FE094E5D +:100A8000094D3080002428683388834208D900F05B +:100A9000ABFE2B6804440133B4F5F04F2B60F2D366 +:100AA00070BD00BF8A2300204423002000F060BFF7 +:100AB00000F1006000F5E040D0F800087047000049 +:100AC00000F10060920000F5F04000F0D5BE00009B +:100AD000054B1A68054B1B889B1A834202D91044A8 +:100AE00000F082BE00207047442300208A230020AB +:100AF00038B5074D04462868204400F07BFE28B92D +:100B000028682044BDE8384000F086BE38BD00BFEC +:100B1000442300200020704700F10050A0F5104051 +:100B2000D0F8900570470000064991F8243033B1A1 +:100B30000023086A81F824300822FFF7C1BF012092 +:100B4000704700BF48230020014B1868704700BF62 +:100B5000002004E070B50E4B5C6893F90860421EFB +:100B60000A44013C0B46934207D214F9015F581C1A +:100B70002DB100F8015C0346F5E7184605E02C248A +:100B800082421C7001D9981C5E70401A70BD00BF73 +:100B900014220020022802BF4FF0904320229A61C5 +:100BA00070470000022802BF4FF090434FF400123C +:100BB0009A617047022801BF4FF09042536983F059 +:100BC000200353617047000010B50023934203D007 +:100BD000CC5CC4540133F9E710BD00000244034665 +:100BE000934202D003F8011BFAE770472DE9F8435E +:100BF0001F4D144695F824200746884652BBDFF85F +:100C000070909CB395F824302BB92022FF214846E0 +:100C10002F62FFF7E3FF95F82400C0F10802A2421B +:100C200028BF2246D6B24146920005EB8000FFF76E +:100C3000CBFF95F82430A41B1E44F6B2082E1744AF +:100C40009044E4B285F82460DBD1FFF76DFF002803 +:100C5000D7D108E02B6A03EB82038342CFD0FFF7A2 +:100C600063FF0028CBD10020BDE8F8830120FBE71B +:100C700048230020024B1A78024B1A70704700BFBD +:100C80008823002010220020034904484FF4E13358 +:100C90000B6000F01BBB00BF702300208C230020E2 +:100CA000074B10B50021044618221846FFF796FF9F +:100CB00004600146BDE81040024800F007BB00BFD9 +:100CC000702300208C23002000B59BB0EFF3098136 +:100CD00068226846FFF778FFEFF30583044B9A6BB1 +:100CE000DA6A9A6A9A6A9A6A9A6A9A6A9B6AFEE7C2 +:100CF00000ED00E000B59BB0EFF309816822684683 +:100D0000FFF762FFEFF30583044B9A6B9A6A9A6AC6 +:100D10009A6A9A6A9A6A9B6AFEE700BF00ED00E051 +:100D200000B59BB0EFF3098168226846FFF74CFFDE +:100D3000EFF30583034B5A6B9A6A9A6A9A6A9A6A26 +:100D40009B6AFEE700ED00E0FEE7000030B5094DCC +:100D50000A4491420DD011F8013B5840082340F35A +:100D60000004013B2C4013F0FF0384EA5000F6D14D +:100D7000EFE730BD2083B8ED02684368114301609E +:100D800003B1184770470000024A136843F0C003DC +:100D9000136070470038014013B50E4C204600F038 +:100DA00089FA04F114000C49009400234FF4807276 +:100DB00000F04AF9094B0A4900944FF4807204F19B +:100DC000380000F0C3F9074A074BC4E9172302B003 +:100DD00010BD00BF8C230020F8230020890D0008DF +:100DE000F824002000380140007A030A30B5037C63 +:100DF000234C002918BF0C46012B0FD1214B9842E0 +:100E00000CD1214B1A6E42F480421A66D3F880202E +:100E100042F48042C3F88020D3F880302268036E09 +:100E2000C16D846603EB5203B3FBF2F362681504F1 +:100E300042BF23F0070503F0070343EA4503CB60F5 +:100E4000A36843F040034B60E36843F001038B6009 +:100E500042F4967343F001030B604FF0FF330B62D3 +:100E6000510505D512F0102205D0B2F1805F04D0F3 +:100E700080F8643030BD7F23FAE73F23F8E700BFF6 +:100E8000CC2000088C230020001002402DE9F04700 +:100E9000C66D3768F46934622107054618D014F02E +:100EA000080118BF8021E20748BF41F02001A307D5 +:100EB00048BF41F04001600748BF41F480712023E2 +:100EC00083F31188281DFFF757FF002383F3118850 +:100ED000E2050AD5202383F311884FF40071281D01 +:100EE000FFF74AFF002383F311884FF020094FF0EA +:100EF000000A14F0200838D13B0616D54FF020091F +:100F000005F1380A200610D589F31188504600F003 +:100F100051F9002836DA0821281DFFF72DFF27F0A8 +:100F200080033360002383F31188790614D56206A9 +:100F300012D5202383F31188D5E913239A4208D1CF +:100F40002B6C33B11021281D27F04007FFF714FF49 +:100F50003760002383F31188E30618D5AA6E13695E +:100F6000ABB1BDE8F0475069184789F31188736A3F +:100F700095F864102846194000F0B6F98AF31188F4 +:100F8000F469B6E7B06288F31188F469BAE7BDE89E +:100F9000F0870000F8B5154682680669AA420B463C +:100FA000816938BF8568761AB54204460BD2184667 +:100FB0002A46FFF709FEA3692B44A361A3685B1BC4 +:100FC000A3602846F8BD0CD918463246FFF7FCFD51 +:100FD000AF1BE1683A463044FFF7F6FDE3683B4457 +:100FE000EBE718462A46FFF7EFFDE368E5E7000068 +:100FF00083689342F7B51546044638BF8568D0E943 +:101000000460361AB5420BD22A46FFF7DDFD63694C +:101010002B446361A36828465B1BA36003B0F0BD4B +:101020000DD932460191FFF7CFFD0199E068AF1B62 +:101030003A463144FFF7C8FDE3683B44E9E72A46F6 +:10104000FFF7C2FDE368E4E710B50A440024C3617A +:10105000029B8460C0E90000C0E90511C160026123 +:10106000036210BD08B5D0E90532934201D1826810 +:1010700082B98268013282605A1C42611970D0E9DB +:1010800004329A4224BFC3684361002100F094FAFD +:10109000002008BD4FF0FF30FBE7000070B52023B3 +:1010A00004460E4683F31188A568A5B1A368A2691A +:1010B000013BA360531CA36115782269934224BFAE +:1010C000E368A361E3690BB120469847002383F3EB +:1010D0001188284607E03146204600F05DFA0028D6 +:1010E000E2DA85F3118870BD2DE9F74F04460E460C +:1010F00017469846D0F81C904FF0200A8AF31188C2 +:101100004FF0000B154665B12A4631462046FFF7E1 +:1011100041FF034660B94146204600F03DFA0028F1 +:10112000F1D0002383F31188781B03B0BDE8F08F62 +:10113000B9F1000F03D001902046C847019B8BF303 +:101140001188ED1A1E448AF31188DCE7C0E9051105 +:10115000C160C3611144009B8260C0E9000001616D +:1011600003627047F8B504460D461646202383F304 +:101170001188A768A7B1A368013BA36063695A1CE3 +:1011800062611D70D4E904329A4224BFE36863614E +:10119000E3690BB120469847002080F3118807E0EF +:1011A0003146204600F0F8F90028E2DA87F311888A +:1011B000F8BD0000D0E905239A4210B501D182683C +:1011C0007AB98268013282605A1C82611C78036994 +:1011D0009A4224BFC3688361002100F0EDF92046E4 +:1011E00010BD4FF0FF30FBE72DE9F74F04460E46E8 +:1011F00017469846D0F81C904FF0200A8AF31188C1 +:101200004FF0000B154665B12A4631462046FFF7E0 +:10121000EFFE034660B94146204600F0BDF90028C4 +:10122000F1D0002383F31188781B03B0BDE8F08F61 +:10123000B9F1000F03D001902046C847019B8BF302 +:101240001188ED1A1E448AF31188DCE702684368AE +:101250001143016003B11847704700001430FFF7D5 +:1012600043BF00004FF0FF331430FFF73DBF0000D5 +:101270003830FFF7B9BF00004FF0FF333830FFF7C9 +:10128000B3BF00001430FFF709BF00004FF0FF317B +:101290001430FFF703BF00003830FFF763BF0000D2 +:1012A0004FF0FF323830FFF75DBF0000002070477D +:1012B000FFF772BD044B03600023C0E902334360B3 +:1012C00001230374704700BFE420000810B52023F9 +:1012D000044683F31188FFF789FD0223237400235A +:1012E00083F3118810BD000038B5C36904460D466C +:1012F0001BB904210844FFF7A9FF294604F1140093 +:10130000FFF7B0FE002806DA201D4FF48061BDE82B +:101310003840FFF79BBF38BD024B0022C3E90033C2 +:101320009A607047F8250020002303748268054BFB +:101330001B6899689142FBD25A6803604260106052 +:1013400058607047F825002008B5202383F31188E2 +:10135000037C032B05D0042B0DD02BB983F311880C +:1013600008BD436900221A604FF0FF334361FFF765 +:10137000DBFF0023F2E7D0E9003213605A60F3E7A5 +:10138000002303748268054B1B6899689142FBD85F +:101390005A6803604260106058607047F82500206A +:1013A000054B19690874186802681A60536018615F +:1013B00001230374FEF7AABFF825002030B54B1CAB +:1013C0000B4D87B0044610D02B690A4A01A800F0E3 +:1013D0000DF92046FFF7E4FF049B13B101A800F0CC +:1013E00041F92B69586907B030BDFFF7D9FFF8E71D +:1013F000F82500204913000838B50C4D41612B69D0 +:1014000081689A689142044603D8BDE83840FFF7E6 +:101410008BBF1846FFF7B4FF01232C6101462374EC +:101420002046BDE83840FEF771BF00BFF825002018 +:10143000044B1A681B6990689B68984294BF00200F +:1014400001207047F825002010B5084C236820695A +:101450001A6822605460012223611A74FFF790FF1A +:1014600001462069BDE81040FEF750BFF825002076 +:1014700008B5FFF7DDFF18B1BDE80840FFF7E4BF8E +:1014800008BD0000FFF7E0BFFEE7000010B50C4C00 +:10149000FFF742FF00F09CF80A498022204600F046 +:1014A00031F8012344F8180C037400F0F1FA00231A +:1014B00083F3118862B60448BDE8104000F042B8DA +:1014C000202600200C2100081C21000800F004B98F +:1014D000EFF3118020B9EFF30583202282F3118806 +:1014E0007047000010B530B9EFF30584C4F3080469 +:1014F00014B180F3118810BDFFF7BAFF84F311888F +:10150000F9E7000082600222028270478368A3F13B +:101510007C0243F80C2C026943F83C2C426943F8E6 +:10152000382C074A43F81C2CC26843F8102C0222BE +:1015300003F8082C002203F8072CA3F118007047C9 +:101540002503000810B5202383F31188FFF7DEFF81 +:1015500000210446FFF750FF002383F31188204643 +:1015600010BD0000024B1B6958610F20FFF718BF28 +:10157000F8250020202383F31188FFF7F3BF000034 +:1015800008B50146202383F311880820FFF716FFD2 +:10159000002383F3118808BD49B1064B42681B69DB +:1015A00018605A60136043600420FFF707BF4FF0D4 +:1015B000FF307047F82500200368984206D01A686B +:1015C0000260506059611846FFF7AEBE70470000D8 +:1015D000054B03F11402C3E905224FF0FF3100224D +:1015E000C3E90712704700BFF825002070B51C4EF4 +:1015F000C0E9032305460C4600F0D0FA334653F801 +:10160000142F9A420DD13062C5E901242A600A2CB8 +:101610002CBF00190A30C6E90555BDE8704000F03E +:10162000ABBA316A431AE31838BF1C469368A34229 +:1016300002D9081900F0AEFA73699A6894420CD87E +:101640005A68AC602B606A6015609A685D60121B16 +:101650009A604FF0FF33F36170BD1B68A41AECE78A +:10166000F825002038B51B4C636998420DD0D0E9AD +:10167000003213605A6000228168C2609A680A448E +:101680009A604FF0FF33E36138BD2246036842F8A9 +:10169000143F002193425A60C16003D1BDE8384035 +:1016A00000F072BA9A688168256A0A449A6000F06C +:1016B00075FA63699A68411B8A42E5D9AB181D1A0D +:1016C000092D206A98BF01F10A02BDE83840104494 +:1016D00000F060BAF82500202DE9F041184C0027F1 +:1016E00004F11406656900F059FA236AAA68C11A60 +:1016F0008A4215D813442362D5E9003213605A6038 +:101700006369D5F80C80EF60B34201D100F03CFA78 +:1017100087F311882869C047202383F31188E1E704 +:101720006169B14209D013441B1ABDE8F0410A2B8C +:101730002CBFC0180A3000F02DBABDE8F08100BF00 +:10174000F825002000207047FEE7000070470000E9 +:101750004FF0FF3070470000BFF34F8F024A13690C +:10176000DB03FCD4704700BF0020024008B5094BE2 +:101770001B7873B9FFF7F0FF074B5A69002ABFBF08 +:10178000064A9A6002F188329A601A6822F48062EE +:101790001A6008BD80270020002002402301674511 +:1017A00008B50B4B1B7893B9FFF7D6FF094B5A6965 +:1017B00042F000425A611A6842F480521A601A6874 +:1017C00022F480521A601A6842F480621A6008BDDE +:1017D00080270020002002407F289ABF00F580303B +:1017E000C0020020704700004FF400607047000006 +:1017F000802070477F2808B50BD8FFF7EDFF00F574 +:1018000000630268013204D104308342F9D101201F +:1018100008BD0020FCE700007F2838B5044626D824 +:10182000FFF756FEFFF798FFFFF7A0FF114BF322DB +:101830001A6102225A615A6942EAC4025A615A691B +:1018400042F480325A6105462046FFF785FF4FF487 +:101850000061FFF7C1FF00F0F1F82846FFF7A0FF95 +:10186000FFF740FE2046BDE83840FFF7C3BF002029 +:1018700038BD00BF0020024040EA020313F0070316 +:101880002DE9F04705460C46164606D0324B40F28D +:10189000FB221A600020BDE8F08781182F4A914290 +:1018A0000CD92D4A4FF440711160F3E72B1D1B68D2 +:1018B0006268934208D1083E08350834072E19D9CA +:1018C0002A6823689A42F1D0FFF702FEFFF74EFF25 +:1018D000FFF742FF04F10801214C4FF001084FF0DF +:1018E0000009012EA1F1080708D8FFF759FFFFF7FB +:1018F000F9FD01E0002EE7D10120CCE7C4F8148007 +:10190000AA4651F8083C4AF8043B51F8043C6B6085 +:10191000FFF722FFC4F814902A6851F8083C9A4255 +:101920000ED00D4B40F226321A600E4B1D600E4B4E +:101930001E600E4B1F60FFF733FFFFF7D3FDA9E7D3 +:10194000DAF800A051F8043C9A4501F10801E8D109 +:10195000083E0835C5E700BF7C27002000000408CA +:1019600000200240702700207827002074270020E4 +:10197000084908B50B7828B11BB9FFF7F7FE01231A +:101980000B7008BD002BFCD0BDE808400870FFF7C5 +:1019900007BF00BF802700200244D2B2904200D18E +:1019A0007047431C800000F1804000F5145000682F +:1019B00041F8040BD8B2F1E7124B10B5D3F89040C0 +:1019C000240409D4D3F89040C3F89040D3F8904051 +:1019D00044F40044C3F890400B4C2368024443F4A1 +:1019E00080732360D2B2904200D110BD431C8000AE +:1019F00000F1804000F5145051F8044B0460D8B257 +:101A0000F1E700BF001002400070004007B501225E +:101A100001A90020FFF7C0FF019803B05DF804FBA7 +:101A200013B50446FFF7F2FFA04205D0012201A939 +:101A300000200194FFF7C0FF02B010BD7047000006 +:101A4000054B1A6832B902F1804202F50432D2F82D +:101A500094201A60704700BF8427002008B5FFF764 +:101A6000EFFF024B1868C0F3407008BD84270020C8 +:101A7000EFF3098305494A6B22F001024A63683398 +:101A800083F30988002383F31188704700EF00E097 +:101A9000202080F3118862B60C4B0D4AD96821F4DE +:101AA000E0610904090C0A43DA60D3F8FC20094913 +:101AB00042F08072C3F8FC200A6842F001020A601A +:101AC0001022DA7783F82200704700BF00ED00E0B3 +:101AD0000003FA05001000E010B5202383F31188FD +:101AE0000E4B5B6813F4006314D0F1EE103AEFF381 +:101AF0000984683C4FF08073E361094BDB6B23661C +:101B000084F30988FFF794FC10B1064BA36110BD64 +:101B1000054BFBE783F31188F9E700BF00ED00E018 +:101B200000EF00E0370300083A03000870470000A8 +:101B3000FEE700000A4B0B480B4A90420BD30B4BBD +:101B4000DA1C121AC11E22F003028B4238BF002297 +:101B50000021FFF743B853F8041B40F8041BECE7DF +:101B60001822000808280020082800200828002043 +:101B70007047000000F078B84FF0804300225863AF +:101B80001A610222DA6070474FF080430022DA6067 +:101B9000704700004FF08043586370474FF0804318 +:101BA000586A70474B6843608B688360CB68C3603A +:101BB0000B6943614B6903628B6943620B68036085 +:101BC0007047000008B5204BDA6A42F07F02DA6203 +:101BD000DA6A22F07F02DA62DA6ADA6C42F07F02B5 +:101BE000DA64DA6E42F07F02DA66184ADB6E11467A +:101BF0004FF09040FFF7D6FF02F11C0100F5806026 +:101C0000FFF7D0FF02F1380100F58060FFF7CAFF4F +:101C100002F1540100F58060FFF7C4FF02F170018A +:101C200000F58060FFF7BEFF02F18C0100F58060D7 +:101C3000FFF7B8FF02F1A80100F58060FFF7B2FFDF +:101C4000BDE8084000F064B80010024034210008EC +:101C500008B500F019FAFFF719FCBDE80840FFF7D6 +:101C6000EFBE0000704700000F4B9A6D42F001027A +:101C70009A659A6F42F001029A670C4A9B6F9368CB +:101C800043F0010393604FF08043A7229A624FF024 +:101C9000FF32DA6200229A615A63DA605A600122E6 +:101CA0005A611A60704700BF00100240002004E033 +:101CB0004FF0804208B51169D3680B40D9B2C943CF +:101CC0009B07116107D5202383F31188FFF7FEFBE3 +:101CD000002383F3118808BD08B50B4BD3F890207F +:101CE00012F4407F1FBF4FF48032C3F890200022CF +:101CF000C3F89020D3F89020C3F8902000F086F924 +:101D0000024B00225A6008BD0010024000700040E3 +:101D1000484B4FF0FF319A6A99629A6A00229A62A0 +:101D2000986AD86A60F07F00D862D86A00F07F00B5 +:101D3000D862D86A186B1963186B1A63186B986BA2 +:101D40009963986B9A63986BD86BD963D86BDA6395 +:101D5000D86B186C1964196C1A641A6C9A6D42F07D +:101D600080529A659A6F22F080529A679A6F324A2F +:101D70004FF400711160516911F48061FBD14FF48F +:101D80000040516090604FF48070D160C2F88000D4 +:101D9000116251629162D162116351639163D163A7 +:101DA000116451649164D16411655165D3F8982030 +:101DB00042F00102C3F89820D3F898209007FBD591 +:101DC0001A6842F480321A601A689103FCD51A49E5 +:101DD0000A6842F480720A60184ADA601A6842F0AF +:101DE00080721A601A689201FCD5002214499A6028 +:101DF000C3F888101349C3F89C20134A0A600A6884 +:101E000002F00F02042AFAD19A6842F003029A60A3 +:101E10009A6802F00C020C2AFAD11A6E42F0010202 +:101E20001A66D3F8802042F00102C3F88020D3F86C +:101E3000803070470010024000700040232A61018A +:101E4000550100500020024004070400074A08B56D +:101E5000536903F00103536123B1054A13680BB1C1 +:101E600050689847BDE80840FFF736BE00040140BF +:101E700088270020074A08B5536903F0020353611D +:101E800023B1054A93680BB1D0689847BDE8084074 +:101E9000FFF722BE0004014088270020074A08B54A +:101EA000536903F00403536123B1054A13690BB16D +:101EB00050699847BDE80840FFF70EBE0004014096 +:101EC00088270020074A08B5536903F008035361C7 +:101ED00023B1054A93690BB1D0699847BDE8084022 +:101EE000FFF7FABD0004014088270020074A08B523 +:101EF000536903F01003536123B1054A136A0BB110 +:101F0000506A9847BDE80840FFF7E6BD000401406D +:101F100088270020164B10B55C6904F478725A616A +:101F2000A30604D5134A936A0BB1D06A984760069A +:101F300004D5104A136B0BB1506B9847210604D59A +:101F40000C4A936B0BB1D06B9847E20504D5094A54 +:101F5000136C0BB1506C9847A30504D5054A936CDC +:101F60000BB1D06C9847BDE81040FFF7B5BD00BF7E +:101F70000004014088270020194B10B55C6904F467 +:101F80007C425A61620504D5164A136D0BB1506D3F +:101F90009847230504D5134A936D0BB1D06D98472C +:101FA000E00404D50F4A136E0BB1506E9847A1049C +:101FB00004D50C4A936E0BB1D06E9847620404D5D9 +:101FC000084A136F0BB1506F9847230404D5054A94 +:101FD000936F0BB1D06F9847BDE81040FFF77CBD01 +:101FE000000401408827002008B50348FEF74EFF93 +:101FF000BDE80840FFF770BD8C23002008B5FFF74F +:1020000057FEBDE80840FFF767BD0000062108B590 +:10201000084600F023F80621072000F01FF80621EB +:10202000082000F01BF80621092000F017F806210F +:102030000A2000F013F80621172000F00FF80621FF +:10204000282000F00BF807211C2000F007F8BDE85D +:1020500008400C21252000F001B8000000F1604389 +:1020600003F561430901C9B283F80013012200F0AE +:102070001F039A4043099B0003F1604303F561434A +:10208000C3F880211A60704708B5FFF725FE00F0FD +:1020900009F8FFF70DF9FFF7E5FDBDE80840FFF788 +:1020A00069BD00000023054A19460133102BC2E91F +:1020B000001102F10802F8D1704700BF8827002004 +:1020C00053544D333247343F3F0000000096000028 +:1020D0000000000000000000000000000000000000 +:1020E00000000000000000007912000865120008DE +:1020F000A11200088D12000899120008851200082C +:10210000711200085D120008AD1200086D61696E61 +:102110000000000069646C650000000014210008E4 +:1021200038260020702700200100000089140008D4 +:10213000000000000004282800000000AAAABEAA8F +:1021400000001424DFFF0000000000007007000002 +:102150000000000000000000AAAAAAAA00000000D7 +:10216000FFFF000000000000000000000000000071 +:1021700000000000AAAAAAAA00000000FFFF0000B9 +:10218000000000000000000000000000000000004F +:10219000AAAAAAAA00000000FFFF00000000000099 +:1021A000000000000000000000000000AAAAAAAA87 +:1021B00000000000FFFF0000000000000000000021 +:1021C0000000000000000000AAAAAAAA0000000067 +:1021D000FFFF000000000000000000000000000001 +:1021E00000000000AAAAAAAA00000000FFFF000049 +:1021F00000000000000000001004000000000000CB +:102200000088030000000000FF0000000000000044 +:08221000C02000083F0000009F :00000001FF diff --git a/Tools/bootloaders/PixPilot-V6_bl.bin b/Tools/bootloaders/PixPilot-V6_bl.bin new file mode 100644 index 00000000000..f2c6d4c6df2 Binary files /dev/null and b/Tools/bootloaders/PixPilot-V6_bl.bin differ diff --git a/Tools/bootloaders/PixPilot-V6_bl.hex b/Tools/bootloaders/PixPilot-V6_bl.hex new file mode 100644 index 00000000000..bc04e0c55f9 --- /dev/null +++ b/Tools/bootloaders/PixPilot-V6_bl.hex @@ -0,0 +1,1118 @@ +:020000040800F2 +:1000000000060020A1020008C110000841100008ED +:1000100099100008411000086D100008A3020008A4 +:10002000A3020008A3020008A3020008AD2A0008EA +:10003000A3020008A3020008A3020008A30200080C +:10004000A3020008A3020008A3020008A3020008FC +:10005000A3020008A3020008353F0008613F000822 +:100060008D3F0008B93F0008E53F0008A3020008E3 +:10007000A3020008A3020008A3020008A3020008CC +:10008000A3020008A3020008A3020008A3020008BC +:10009000A3020008A3020008A30200081140000800 +:1000A000A3020008A3020008A3020008A30200089C +:1000B000A3020008A3020008A3020008A30200088C +:1000C000A3020008A3020008A3020008A30200087C +:1000D000A3020008A3020008E9400008FD40000850 +:1000E00075400008A3020008A3020008A30200084C +:1000F000A3020008A3020008A3020008A30200084C +:10010000A3020008A302000825410008A30200087A +:10011000A3020008A3020008A3020008A30200082B +:10012000A3020008A3020008A3020008A30200081B +:10013000A3020008A3020008A3020008A30200080B +:10014000A3020008A3020008A3020008A3020008FB +:10015000A3020008A3020008A3020008A3020008EB +:10016000A3020008A3020008A3020008A3020008DB +:10017000A302000819360008A3020008A302000821 +:10018000A3020008A302000811410008A30200080E +:10019000A3020008A3020008A3020008A3020008AB +:1001A000A3020008A3020008A3020008A30200089B +:1001B000A3020008A3020008A3020008A30200088B +:1001C000A3020008A3020008A3020008A30200087B +:1001D000A302000805360008A3020008A3020008D5 +:1001E000A3020008A3020008A3020008A30200085B +:1001F000A3020008A3020008A3020008A30200084B +:10020000A3020008A3020008A3020008A30200083A +:10021000A3020008A3020008A3020008A30200082A +:10022000A3020008A3020008A3020008A30200081A +:10023000A3020008A3020008A3020008A30200080A +:10024000A3020008A3020008A3020008A3020008FA +:10025000A3020008A3020008A3020008A3020008EA +:10026000A3020008A3020008A3020008A3020008DA +:10027000A3020008A3020008A3020008A3020008CA +:10028000A3020008A3020008A3020008A3020008BA +:10029000A3020008A3020008A3020008A3020008AA +:1002A00002E000F000F8FEE772B63A4880F30888F2 +:1002B000394880F3098839484EF60851CEF20001DA +:1002C000086040F20000CCF200004EF63471CEF22D +:1002D00000010860BFF34F8FBFF36F8F40F2000043 +:1002E000C0F2F0004EF68851CEF200010860BFF374 +:1002F0004F8FBFF36F8F4FF00000E1EE100A4EF604 +:100300003C71CEF200010860062080F31488BFF330 +:100310006F8F02F089FC02F02BFC03F0C5FB4FF05D +:1003200055301F491B4A91423CBF41F8040BFAE784 +:100330001C49194A91423CBF41F8040BFAE71A499B +:100340001A4A1B4B9A423EBF51F8040B42F8040B69 +:10035000F8E700201749184A91423CBF41F8040BC6 +:10036000FAE702F043FC03F023FC144C144DAC42BA +:1003700003DA54F8041B8847F9E700F041F8114C00 +:10038000114DAC4203DA54F8041B8847F9E702F038 +:100390002BBC000000060020002200200000000806 +:1003A0000000002000060020584500080022002020 +:1003B0005C22002060220020D44F0020A002000810 +:1003C000A0020008A0020008A00200082DE9F04FDA +:1003D0002DED108AC1F80CD0D0F80CD0BDEC108AED +:1003E000BDE8F08F002383F311882846A047002042 +:1003F00001F03CFFFEE701F0B7FE00DFFEE7000082 +:1004000038B502F03BFB30B1164B00220E211A72B8 +:100410005A729972DA7202F007FB054602F03CFB51 +:100420000446D0B9104B9D4219D001339D4241F290 +:10043000883512BF044600250124002002F0FEFA90 +:100440000CB100F079F800F09BFD00F02BFC284681 +:1004500000F020F900F070F8F9E70025EDE7054617 +:10046000EBE700BF00220020010007B008B500F054 +:10047000E5FBA0F120035842584108BD07B541F201 +:100480001203022101A8ADF8043000F0F5FB03B01F +:100490005DF804FB38B5202383F311881748C3683F +:1004A0000BB101F069FF0023154A4FF47A7113482C +:1004B00001F026FF002383F31188124C236813B147 +:1004C0002368013B2360636813B16368013B636089 +:1004D0000D4D2B7833B963687BB9022000F0C0FC66 +:1004E000322363602B78032B07D163682BB902207A +:1004F00000F0B6FC4FF47A73636038BD60220020D0 +:10050000950400087C23002074220020084B1870FA +:1005100003280CD8DFE800F008050208022000F0EC +:100520008FBC022000F07ABC024B00225A60704758 +:10053000742200207C230020F8B5504B504A1C4602 +:100540001968013100F0998004339342F8D1626850 +:100550004C4B9A4240F291804B4B9B6803F10063F5 +:1005600003F500339A4280F08880002000F0B4FB4D +:100570000220FFF7CBFF454B0021D3F8E820C3F85A +:10058000E810D3F81021C3F81011D3F81021D3F8D4 +:10059000EC20C3F8EC10D3F81421C3F81411D3F8ED +:1005A0001421D3F8F020C3F8F010D3F81821C3F8C1 +:1005B0001811D3F81821D3F8802042F00062C3F854 +:1005C0008020D3F8802022F00062C3F88020D3F886 +:1005D0008020D3F8802042F00072C3F88020D3F846 +:1005E000802022F00072C3F88020D3F8803072B6E9 +:1005F0004FF0E023C3F8084DD4E90004BFF34F8F58 +:10060000BFF36F8F224AC2F88410BFF34F8F536934 +:1006100023F480335361BFF34F8FD2F8803043F619 +:10062000E076C3F3C905C3F34E335B0103EA060C5E +:1006300029464CEA81770139C2F87472F9D2203B1D +:1006400013F1200FF2D1BFF34F8FBFF36F8FBFF3C2 +:100650004F8FBFF36F8F536923F40033536100232F +:10066000C2F85032BFF34F8FBFF36F8F202383F355 +:100670001188854680F308882047F8BD00000208ED +:1006800020000208FFFF0108002200200044025859 +:1006900000ED00E02DE9F04F93B0B44B2022FF2194 +:1006A00000900AA89D6800F015FCB14A1378A3B920 +:1006B0000121B0481170C360202383F31188C368FF +:1006C0000BB101F059FE0023AB4A4FF47A71A948EF +:1006D00001F016FE002383F31188009B13B1A74B92 +:1006E000009A1A60A64A1378032B03D000231370D4 +:1006F000A24A53604FF0000A009CD3465646D146AA +:10070000012000F09DFB24B19C4B1B68002B00F0E6 +:100710002682002000F092FA0390039B002BF2DB6C +:10072000012000F07BFB039B213B1F2BE8D801A29B +:1007300052F823F0B5070008DD070008710800082B +:100740000107000801070008010700080309000865 +:10075000D30A0008ED0900084F0A0008770A0008CC +:100760009D0A000801070008AF0A000801070008F9 +:10077000210B00085508000801070008650B000858 +:10078000C107000855080008010700084F0A0008C3 +:100790000107000801070008010700080107000819 +:1007A0000107000801070008010700080107000809 +:1007B000710800080220FFF759FE002840F0F98177 +:1007C000009B022105A8BAF1000F08BF1C4641F2A8 +:1007D0001233ADF8143000F04FFA91E74FF47A700D +:1007E00000F02CFA071EEBDB0220FFF73FFE00288B +:1007F000E6D0013F052F00F2DE81DFE807F0030AB3 +:100800000D1013360523042105A8059300F034FAD2 +:1008100017E004215548F9E704215A48F6E7042176 +:100820005948F3E74FF01C08404608F1040800F06F +:1008300055FA0421059005A800F01EFAB8F12C0F16 +:10084000F2D101204FF0000900FA07F747EA0B0B3D +:100850005FFA8BFB00F08AFB26B10BF00B030B2B2E +:1008600008BF0024FFF70AFE4AE704214748CDE706 +:10087000002EA5D00BF00B030B2BA1D10220FFF70C +:10088000F5FD074600289BD00120002600F024FA41 +:100890000220FFF73BFE5FFA86F8404600F02CFA94 +:1008A0000446B0B1039940460136A1F140025142DD +:1008B000514100F031FA0028EDD1BA46044641F228 +:1008C0001213022105A83E46ADF8143000F0D4F909 +:1008D00016E725460120FFF719FE244B9B68AB4223 +:1008E00007D9284600F0FAF9013040F06781043555 +:1008F000F3E70025224BBA463E461D701F4B5D6054 +:10090000A8E7002E3FF45CAF0BF00B030B2B7FF43A +:1009100057AF0220FFF7FAFD322000F08FF9B0F157 +:100920000008FFF64DAF18F003077FF449AF0F4AF8 +:1009300008EB0503926893423FF642AFB8F5807F1B +:100940003FF73EAF124BB845019323DD4FF47A7069 +:1009500000F074F90390039A002AFFF631AF039A6E +:100960000137019B03F8012BEDE700BF00220020B7 +:100970007823002060220020950400087C230020BA +:100980007422002004220020082200200C220020D3 +:1009900078220020C820FFF769FD074600283FF4B1 +:1009A0000FAF1F2D11D8C5F120020AAB25F00300AF +:1009B00084494245184428BF4246019200F064FA37 +:1009C000019AFF217F4800F085FA4FEAA803C8F397 +:1009D00087027C492846019300F084FA06460028E5 +:1009E0003FF46DAF019B05EB830533E70220FFF772 +:1009F0003DFD00283FF4E4AE00F0ACF900283FF4E0 +:100A0000DFAE0027B846704B9B68BB4218D91F2F3A +:100A100011D80A9B01330ED027F0030312AA134406 +:100A200053F8203C05934046042205A9043700F002 +:100A300049FB8046E7E7384600F050F90590F2E7B9 +:100A4000CDF81480042105A800F016F902E7002370 +:100A5000642104A8049300F005F900287FF4B0AEE7 +:100A60000220FFF703FD00283FF4AAAE049800F02F +:100A700067F90590E6E70023642104A8049300F0D9 +:100A8000F1F800287FF49CAE0220FFF7EFFC00286D +:100A90003FF496AE049800F055F9EAE70220FFF71C +:100AA000E5FC00283FF48CAE00F064F9E1E7022099 +:100AB000FFF7DCFC00283FF483AE05A9142000F00A +:100AC0005FF907460421049004A800F0D5F83946E0 +:100AD000B9E7322000F0B2F8071EFFF671AEBB078F +:100AE0007FF46EAE384A07EB0903926893423FF6F3 +:100AF00067AE0220FFF7BAFC00283FF461AE27F092 +:100B000003074F44B9453FF4A5AE484609F104092F +:100B100000F0E4F80421059005A800F0ADF8F1E735 +:100B20004FF47A70FFF7A2FC00283FF449AE00F0C2 +:100B300011F9002844D00A9B01330BD008220AA9DE +:100B4000002000F0CFF900283AD02022FF210AA887 +:100B500000F0C0F9FFF792FC1C4801F08DFB13B0C8 +:100B6000BDE8F08F002E3FF42BAE0BF00B030B2BE8 +:100B70007FF426AE0023642105A8059300F072F8E7 +:100B8000074600287FF41CAE0220FFF76FFC80466A +:100B900000283FF415AEFFF771FC41F2883001F0F8 +:100BA0006BFB059800F02CFA46463C4600F0DEF957 +:100BB000A6E506464EE64FF0000901E6BA467EE697 +:100BC00037467CE67822002000220020A086010023 +:100BD0002DE9F84F4FF47A7306460D46002402FBC8 +:100BE00003F7DFF85080DFF8509098F900305FFA93 +:100BF00084FA5A1C01D0A34210D159F824002A4685 +:100C000031460368D3F820B03B46D847854205D12A +:100C1000074B012083F800A0BDE8F88F0134042CB5 +:100C2000E3D14FF4FA7001F027FB0020F4E700BF96 +:100C3000C82300201022002028420008002307B506 +:100C4000024601210DF107008DF80730FFF7C0FFC4 +:100C500020B19DF8070003B05DF804FB4FF0FF30B2 +:100C6000F9E700000A46042108B5FFF7B1FF80F05C +:100C70000100C0B2404208BD074B0A4630B41978A3 +:100C8000064B53F82140014623682046DD69044B9A +:100C9000AC4630BC604700BFC82300202842000893 +:100CA000A086010070B50A4E00240A4D01F094FDA3 +:100CB000308028683388834208D901F089FD2B6889 +:100CC00004440133B4F5003F2B60F2D370BD00BF84 +:100CD000CA2300208423002001F05CBE00F10060E4 +:100CE00000F500300068704700F10060920000F5E8 +:100CF000003001F0D3BD0000054B1A68054B1B887E +:100D00009B1A834202D9104401F062BD0020704753 +:100D100084230020CA23002038B50446074D29B19A +:100D200028682044BDE8384001F06ABD28682044A6 +:100D300001F054FD0028F3D038BD00BF842300200B +:100D40000020704700F1FF5000F58F10D0F8000828 +:100D500070470000064991F8243033B1002308227F +:100D6000086A81F82430FFF7BFBF0120704700BF39 +:100D700088230020014B1868704700BF0010005CFA +:100D8000244BF0B51A680446234BC2F30B06120C31 +:100D90001F885868BE4293F9085028D09F89BE42E8 +:100DA00006D101200C2505FB0033586893F9085043 +:100DB00041F201039A421CD041F203039A421AD035 +:100DC00042F201039A4218D042F203039A4208BF4A +:100DD0005625621E0B46441E0A4493420FD214F954 +:100DE000016F581C6EB1034600F8016CF5E7002056 +:100DF000D8E75A25EDE75925EBE75825E9E71846E6 +:100E000005E02C2482421C7001D9981C5D70401AA8 +:100E1000F0BD00BF0010005C14220020022804D1A5 +:100E2000054B4FF080529A6170470128FCD1034B6B +:100E30004FF40022F7E700BF0010025800040258E8 +:100E4000022804D1044B4FF480529A617047012864 +:100E5000FCD1024B0822F8E70010025800040258A7 +:100E6000022805D1064A536983F4805353617047C1 +:100E70000128FCD1034A536983F00803F6E700BF59 +:100E80000010025800040258002310B5934203D00A +:100E9000CC5CC4540133F9E710BD0000013810B533 +:100EA00010F9013F3BB191F900409C4203D11AB1C6 +:100EB0000131013AF4E71AB191F90020981A10BDF6 +:100EC0001046FCE703460246D01A12F9011B00291E +:100ED000FAD1704702440346934202D003F8011B43 +:100EE000FAE770472DE9F8431F4D14460746884638 +:100EF00095F8242052BBDFF870909CB395F824300D +:100F00002BB92022FF2148462F62FFF7E3FF95F817 +:100F100024004146C0F1080205EB8000A24228BF30 +:100F20002246D6B29200FFF7AFFF95F82430A41BFB +:100F300017441E449044E4B2F6B2082E85F82460AB +:100F4000DBD1FFF707FF0028D7D108E02B6A03EBBE +:100F500082038342CFD0FFF7FDFE0028CBD10020D3 +:100F6000BDE8F8830120FBE788230020024B1A78B4 +:100F7000024B1A70704700BFC823002010220020C7 +:100F8000F8B5194C194800F079FC2146174800F0D3 +:100F9000A1FC24681648D4F89020164ED2F80438E4 +:100FA000154D43F00203114FC2F8043801F064F903 +:100FB0002046124900F09CFDD4F890200424D2F879 +:100FC000043823F00203C2F804384FF4E1333360ED +:100FD00055F8040BB84202D0314600F0ADFB013C9D +:100FE00014F0FF04F4D1F8BD3C430008C8320020DF +:100FF00040420F00B023002028420008444300086C +:1010000038B50B4B04461A780A4B53F822500A4B5A +:101010009D420CD0094B002118221846FFF75AFFB9 +:10102000046001462846BDE8384000F085BB38BD65 +:10103000C823002028420008C8320020B023002026 +:1010400000B59BB0EFF3098168226846FFF71CFFEB +:10105000EFF30583044B9A6BDA6A9A6A9A6A9A6A82 +:101060009A6A9A6A9B6AFEE700ED00E000B59BB0C1 +:10107000EFF3098168226846FFF706FFEFF3058367 +:10108000044B9A6B9A6A9A6A9A6A9A6A9A6A9B6AF3 +:10109000FEE700BF00ED00E000B59BB0EFF3098173 +:1010A00068226846FFF7F0FEEFF30583034B5A6BA7 +:1010B0009A6A9A6A9A6A9A6A9B6AFEE700ED00E069 +:1010C000FEE7000030B50A44084D91420DD011F8FA +:1010D000013B5840082340F30004013B2C4013F02F +:1010E000FF0384EA5000F6D1EFE730BD2083B8ED6E +:1010F000026843681143016003B11847704700005C +:10110000024A136843F0C003136070470044004074 +:10111000024A136843F0C003136070470048004060 +:10112000024A136843F0C003136070470078004020 +:1011300037B5274C274D204600F0F2FA04F1140091 +:10114000009400234FF40072234900F0B3F94FF4E8 +:101150000072224904F138000094214B00F02CFA6F +:10116000204BC4E91735204C204600F0D9FA04F191 +:101170001400009400234FF400721C4900F09AF907 +:101180004FF400721A4904F138000094194B00F032 +:1011900013FA194BC4E91735184C204600F0C0FA71 +:1011A00004F1140000234FF400721549009400F07C +:1011B00081F9144B4FF40072134904F13800009484 +:1011C00000F0FAF9114BC4E9173503B030BD00BF88 +:1011D000CC23002000E1F50510250020102B002075 +:1011E000011100080044004038240020102700208E +:1011F000102D00201111000800480040A4240020F8 +:101200001029002021110008102F00200078004034 +:10121000037C30B5334C002918BF0C46012B18D184 +:10122000314B98420FD1314BD3F8E82042F40032D1 +:10123000C3F8E820D3F8102142F40032C3F810219B +:10124000D3F8103105E02A4B98422FD0294B984211 +:1012500038D02268036EC16D03EB52038466B3FB82 +:10126000F2F36268150442BF23F0070503F0070399 +:1012700043EA4503CB60A36843F040034B60E36857 +:1012800043F001038B6042F4967343F001030B605B +:101290004FF0FF330B62510505D512F010221DD01F +:1012A000B2F1805F1CD080F8643030BD0F4BD3F8B2 +:1012B000E82042F48022C3F8E820D3F8102142F459 +:1012C0008022BBE7094BD3F8E82042F08042C3F804 +:1012D000E820D3F8102142F08042AFE77F23E2E715 +:1012E0003F23E0E738420008CC23002000440258A6 +:1012F00038240020A42400202DE9F047C66D0546BF +:101300003768F4692107346219D014F0080118BF56 +:101310008021E20748BF41F02001A3074FF02003DE +:1013200048BF41F04001600748BF41F4807183F33A +:101330001188281DFFF7DCFE002383F31188E205E6 +:101340000AD5202383F311884FF40071281DFFF77D +:10135000CFFE002383F311884FF020094FF0000ADD +:1013600014F0200838D13B0616D54FF0200905F1BE +:10137000380A200610D589F31188504600F050F93C +:10138000002836DA0821281DFFF7B2FE27F0800377 +:101390003360002383F31188790614D5620612D5D1 +:1013A000202383F31188D5E913239A4208D12B6CAB +:1013B00033B127F040071021281DFFF799FE376051 +:1013C000002383F31188E30618D5AA6E1369ABB125 +:1013D0005069BDE8F047184789F31188736A2846B9 +:1013E00095F86410194000F0B5F98AF31188F46992 +:1013F000B6E7B06288F31188F469BAE7BDE8F08710 +:10140000F8B51546826804460B46AA4200D28568A4 +:10141000A1692669761AB5420BD218462A46FFF70B +:1014200033FDA3692B44A3612846A3685B1BA3601B +:10143000F8BD0CD9AF1B18463246FFF725FD3A46DA +:10144000E1683044FFF720FDE3683B44EBE71846D2 +:101450002A46FFF719FDE368E5E700008368934239 +:10146000F7B50446154600D28568D4E90460361AFB +:10147000B5420BD22A46FFF707FD63692B4463612F +:101480002846A3685B1BA36003B0F0BD0DD93246AC +:10149000AF1B0191FFF7F8FC01993A46E06831442F +:1014A000FFF7F2FCE3683B44E9E72A46FFF7ECFC70 +:1014B000E368E4E710B50A440024C361029B84603A +:1014C000C16002610362C0E90000C0E9051110BDFE +:1014D00008B5D0E90532934201D1826882B98268A9 +:1014E000013282605A1C426119700021D0E9043235 +:1014F0009A4224BFC368436100F0DAFE002008BDB1 +:101500004FF0FF30FBE7000070B5202304460E4685 +:1015100083F31188A568A5B1A368A269013BA36004 +:10152000531CA36115782269934224BFE368A36129 +:10153000E3690BB120469847002383F311882846BE +:1015400007E03146204600F0A3FE0028E2DA85F3EA +:10155000118870BD2DE9F74F04460E461746984690 +:10156000D0F81C904FF0200A8AF311884FF0000B3E +:10157000154665B12A4631462046FFF741FF03462E +:1015800060B94146204600F083FE0028F1D00023D8 +:1015900083F31188781B03B0BDE8F08FB9F1000F19 +:1015A00003D001902046C847019B8BF31188ED1AA8 +:1015B0001E448AF31188DCE7C160C361009B82602E +:1015C0000362C0E905111144C0E9000001617047E0 +:1015D000F8B504460D461646202383F31188A76804 +:1015E000A7B1A368013BA36063695A1C62611D70C7 +:1015F000D4E904329A4224BFE3686361E3690BB122 +:1016000020469847002080F3118807E031462046A5 +:1016100000F03EFE0028E2DA87F31188F8BD0000F2 +:10162000D0E9052310B59A4201D182687AB982685F +:101630000021013282605A1C82611C7803699A423F +:1016400024BFC368836100F033FE204610BD4FF015 +:10165000FF30FBE72DE9F74F04460E461746984644 +:10166000D0F81C904FF0200A8AF311884FF0000B3D +:10167000154665B12A4631462046FFF7EFFE034680 +:1016800060B94146204600F003FE0028F1D0002357 +:1016900083F31188781B03B0BDE8F08FB9F1000F18 +:1016A00003D001902046C847019B8BF31188ED1AA7 +:1016B0001E448AF31188DCE7026843681143016025 +:1016C00003B11847704700001430FFF743BF000014 +:1016D0004FF0FF331430FFF73DBF00003830FFF705 +:1016E000B9BF00004FF0FF333830FFF7B3BF000041 +:1016F0001430FFF709BF00004FF0FF311430FFF73F +:1017000003BF00003830FFF763BF00004FF0FF3227 +:101710003830FFF75DBF000000207047FFF708BDBD +:10172000044B036000234360C0E9023301230374C8 +:10173000704700BF5042000810B52023044683F3D1 +:101740001188FFF765FD02232374002383F31188BA +:1017500010BD000038B5C36904460D461BB904210D +:101760000844FFF7A9FF294604F11400FFF7B0FE73 +:10177000002806DA201D4FF48061BDE83840FFF7ED +:101780009BBF38BD026843681143016003B118472D +:101790007047000013B5406B00F58054D4F8A438AE +:1017A0001A681178042914D1017C022911D1197900 +:1017B000012312898B4013420BD101A94C3002F056 +:1017C00073F8D4F8A4480246019B2179206800F000 +:1017D000DFF902B010BD0000143001F0F5BF0000C9 +:1017E0004FF0FF33143001F0EFBF00004C3002F037 +:1017F000C7B800004FF0FF334C3002F0C1B8000012 +:10180000143001F0C3BF00004FF0FF31143001F07D +:10181000BDBF00004C3002F093B800004FF0FF3223 +:101820004C3002F08DB800000020704710B500F574 +:101830008054D4F8A4381A681178042917D1017C8F +:10184000022914D15979012352898B4013420ED1B8 +:10185000143001F055FF024648B1D4F8A4484FF4C3 +:10186000407361792068BDE8104000F07FB910BD79 +:10187000406BFFF7DBBF0000704700007FB5124BE5 +:1018800001250426044603600023057400F1840248 +:1018900043602946C0E902330C4B02901430019397 +:1018A0004FF44073009601F007FF094B04F6944291 +:1018B000294604F14C000294CDE900634FF44073D3 +:1018C00001F0CEFF04B070BD784200087118000826 +:1018D000951700080A68202383F311880B790B33CE +:1018E00042F823004B79133342F823008B7913B16C +:1018F0000B3342F8230000F58053C3F8A4180223E9 +:101900000374002383F311887047000038B5037F08 +:10191000044613B190F85430ABB90125201D0221C3 +:10192000FFF730FF04F114006FF00101257700F09C +:10193000CBFC04F14C0084F854506FF00101BDE879 +:10194000384000F0C1BC38BD10B501210446043058 +:10195000FFF718FF0023237784F8543010BD0000F0 +:1019600038B504460025143001F0BEFE04F14C00E9 +:10197000257701F08DFF201D84F854500121FFF7D9 +:1019800001FF2046BDE83840FFF750BF90F8803097 +:1019900003F06003202B06D190F881200023212A38 +:1019A00003D81F2A06D800207047222AFBD1C0E99D +:1019B0001D3303E0034A426707228267C3670120A1 +:1019C000704700BF2C22002037B500F58055D5F8B0 +:1019D000A4381A68117804291AD1017C022917D178 +:1019E0001979012312898B40134211D100F14C0463 +:1019F000204602F00DF858B101A9204601F054FF2D +:101A0000D5F8A4480246019B2179206800F0C0F86F +:101A100003B030BD01F10B03F0B550F8236085B081 +:101A200004460D46FEB1202383F3118804EB85079D +:101A3000301D0821FFF7A6FEFB6806F14C005B692C +:101A40001B681BB1019001F03DFF019803A901F053 +:101A50002BFF024648B1039B2946204600F098F828 +:101A6000002383F3118805B0F0BDFB685A69126842 +:101A7000002AF5D01B8A013B1340F1D104F180020A +:101A8000EAE70000133138B550F82140ECB12023CB +:101A900083F3118804F58053D3F8A428136852798E +:101AA00003EB8203DB689B695D6845B10421601824 +:101AB000FFF768FE294604F1140001F02BFE2046D2 +:101AC000FFF7B4FE002383F3118838BD7047000090 +:101AD00001F01EB901234022002110B5044600F890 +:101AE000303BFFF7F7F90023C4E9013310BD0000D4 +:101AF00010B52023044683F311882422416000217D +:101B00000C30FFF7E7F9204601F024F90223237097 +:101B1000002383F3118810BD70B500EB81030546E7 +:101B200050690E461446DA6018B110220021FFF702 +:101B3000D1F9A06918B110220021FFF7CBF9314685 +:101B40002846BDE8704001F017BA000083682022E3 +:101B5000002103F0011310B5044683601030FFF735 +:101B6000B9F92046BDE8104001F092BAF0B4012561 +:101B700000EB810447898D40E4683D43A4694581B9 +:101B800023600023A2606360F0BC01F0AFBA0000E4 +:101B9000F0B4012500EB810407898D40E4683D43E2 +:101BA0006469058123600023A2606360F0BC01F0DA +:101BB00025BB000070B502230025044624220370D3 +:101BC0002946C0F888500C3040F8045CFFF782F9D1 +:101BD000204684F8705001F063F963681B6823B1F4 +:101BE00029462046BDE87040184770BD037880F84C +:101BF0008C300523037043681B6810B504460BB195 +:101C0000042198470023A36010BD000090F88C20A9 +:101C1000436802701B680BB105211847704700002C +:101C200070B590F87030044613B1002380F870301E +:101C300004F18002204601F04FFA63689B68B3B953 +:101C400094F8803013F0600535D00021204601F073 +:101C5000F9FC0021204601F0E9FC63681B6813B120 +:101C6000062120469847062384F8703070BD204630 +:101C700098470028E4D0B4F88630A26F9A4288BF13 +:101C8000A36794F98030A56F002B4FF0200380F2FA +:101C90000381002D00F0F280092284F8702083F384 +:101CA000118800212046D4E91D23FFF771FF00238E +:101CB00083F31188DAE794F8812003F07F0343EA85 +:101CC000022340F20232934200F0C58021D8B3F5DE +:101CD000807F48D00DD8012B3FD0022B00F093809D +:101CE000002BB2D104F1880262670222A267E36787 +:101CF000C1E7B3F5817F00F09B80B3F5407FA4D1AD +:101D000094F88230012BA0D1B4F8883043F002035C +:101D100032E0B3F5006F4DD017D8B3F5A06F31D0D6 +:101D2000A3F5C063012B90D86368204694F8822005 +:101D30005E6894F88310B4F88430B047002884D0EB +:101D4000436863670368A3671AE0B3F5106F36D082 +:101D500040F6024293427FF478AF5C4B6367022304 +:101D6000A3670023C3E794F88230012B7FF46DAFA3 +:101D7000B4F8883023F00203A4F88830C4E91D5574 +:101D8000E56778E7B4F88030B3F5A06F0ED194F82A +:101D90008230204684F88A3001F0E0F863681B68DE +:101DA00013B1012120469847032323700023C4E97F +:101DB0001D339CE704F18B0363670123C3E723789A +:101DC000042B10D1202383F311882046FFF7BEFE99 +:101DD00085F311880321636884F88B5021701B6898 +:101DE0000BB12046984794F88230002BDED084F85F +:101DF0008B300423237063681B68002BD6D002212C +:101E000020469847D2E794F8843020461D0603F018 +:101E10000F010AD501F052F9012804D002287FF4FD +:101E200014AF2B4B9AE72B4B98E701F039F9F3E706 +:101E300094F88230002B7FF408AF94F8843013F0CC +:101E40000F01B3D01A06204602D501F013FCADE70E +:101E500001F004FCAAE794F88230002B7FF4F5AE81 +:101E600094F8843013F00F01A0D01B06204602D551 +:101E700001F0E8FB9AE701F0D9FB97E7142284F818 +:101E8000702083F311882B462A4629462046FFF707 +:101E90006DFE85F31188E9E65DB1152284F87020A6 +:101EA00083F3118800212046D4E91D23FFF75EFE4D +:101EB000FDE60B2284F8702083F311882B462A4616 +:101EC00029462046FFF764FEE3E700BFA84200086A +:101ED000A0420008A442000838B590F870300446CB +:101EE000002B3ED0063BDAB20F2A34D80F2B32D863 +:101EF000DFE803F03731310822323131313131310D +:101F000031313737856FB0F886309D4214D2C368BF +:101F10001B8AB5FBF3F203FB12556DB9202383F343 +:101F200011882B462A462946FFF732FE85F3118891 +:101F30000A2384F870300EE0142384F870302023D4 +:101F400083F31188002320461A461946FFF70EFE38 +:101F5000002383F3118838BDC36F03B19847002372 +:101F6000E7E70021204601F06DFB0021204601F04B +:101F70005DFB63681B6813B1062120469847062362 +:101F8000D7E7000010B590F870300446142B29D024 +:101F900017D8062B05D001D81BB110BD093B022B69 +:101FA000FBD80021204601F04DFB0021204601F026 +:101FB0003DFB63681B6813B1062120469847062342 +:101FC00019E0152BE9D10B2380F87030202383F31F +:101FD000118800231A461946FFF7DAFD002383F320 +:101FE0001188DAE7C3689B695B68002BD5D1C36FA2 +:101FF00003B19847002384F87030CEE7024B0022EB +:10200000C3E900339A6070471031002000238268D2 +:102010000374054B1B6899689142FBD25A680360B0 +:1020200042601060586070471031002008B52023CE +:1020300083F31188037C032B05D0042B0DD02BB91F +:1020400083F3118808BD436900221A604FF0FF3303 +:102050004361FFF7DBFF0023F2E7D0E900321360B2 +:102060005A60F3E7002382680374054B1B68996884 +:102070009142FBD85A680360426010605860704714 +:1020800010310020054B1969087418680268536004 +:102090001A60186101230374FEF798B9103100200B +:1020A0004B1C30B5044687B00A4D10D02B6901A8EF +:1020B000094A00F025F92046FFF7E4FF049B13B11D +:1020C00001A800F059F92B69586907B030BDFFF736 +:1020D000D9FFF8E7103100202D20000838B50C4D4D +:1020E000044641612B6981689A68914203D8BDE832 +:1020F0003840FFF78BBF1846FFF7B4FF01232C6170 +:10210000014623742046BDE83840FEF75FB900BFA2 +:1021100010310020044B1A681B6990689B68984234 +:1021200094BF0020012070471031002010B5084CEA +:10213000236820691A6854602260012223611A749E +:10214000FFF790FF01462069BDE81040FEF73EB959 +:102150001031002008B5FFF7DDFF18B1BDE80840D9 +:10216000FFF7E4BF08BD0000FFF7E0BFFEE7000097 +:1021700010B50C4CFFF742FF00F0B4F880220A497A +:10218000204600F03BF8012344F8180C037400F0DB +:102190009DFC002383F3118862B60448BDE810401B +:1021A00000F04CB838310020AC420008BC420008B6 +:1021B00000F01CB9EFF3118020B9EFF30583202262 +:1021C00082F311887047000010B530B9EFF3058431 +:1021D000C4F3080414B180F3118810BDFFF7BAFFEF +:1021E00084F31188F9E70000034A516853685B1AC9 +:1021F0009842FBD8704700BF001000E082600222C6 +:10220000028270478368A3F17C0243F80C2C0269B8 +:1022100043F83C2C426943F8382C074A43F81C2CFD +:10222000C268A3F1180043F8102C022203F8082C0E +:10223000002203F8072C7047E503000810B520239F +:1022400083F31188FFF7DEFF00210446FFF746FF06 +:10225000002383F31188204610BD0000024B1B6948 +:1022600058610F20FFF70EBF10310020202383F3A9 +:102270001188FFF7F3BF000008B50146202383F360 +:1022800011880820FFF70CFF002383F3118808BD95 +:1022900049B1064B42681B6918605A60136043607D +:1022A0000420FFF7FDBE4FF0FF30704710310020D3 +:1022B0000368984206D01A68026050601846596157 +:1022C000FFF7A4BE7047000038B504460D462068ED +:1022D000844200D138BD036823605C604561FFF72C +:1022E00095FEF4E7054B4FF0FF3103F11402C3E90B +:1022F00005220022C3E90712704700BF10310020F9 +:1023000070B51C4E05460C46C0E9032301F0B6FB30 +:10231000334653F8142F9A420DD130620A2C2CBF49 +:1023200000190A302A60C5E90124C6E90555BDE84F +:10233000704001F08DBB316A431AE31838BF1C4668 +:102340009368A34202D9081901F092FB73699A6855 +:1023500094420CD85A68AC602B606A6015609A6829 +:102360005D60121B9A604FF0FF33F36170BDA41AD9 +:102370001B68ECE71031002038B51B4C63699842AC +:102380000DD08168D0E9003213605A600022C2602B +:102390009A680A449A604FF0FF33E36138BD0368DE +:1023A0002246002142F8143F93425A60C16003D193 +:1023B000BDE8384001F056BB9A688168256A0A4436 +:1023C0009A6001F05BFB6369411B9A688A42E5D918 +:1023D000AB181D1A206A092D98BF01F10A02BDE849 +:1023E0003840104401F044BB103100202DE9F04189 +:1023F000184C002704F11406656901F03FFB236ABD +:10240000AA68C11A8A4215D81344D5F80C802362F1 +:10241000D5E9003213605A606369EF60B34201D1BD +:1024200001F020FB87F311882869C047202383F33C +:102430001188E1E76169B14209D013441B1ABDE874 +:10244000F0410A2B2CBFC0180A3001F011BBBDE8C7 +:10245000F08100BF1031002000207047FEE700002F +:10246000704700004FF0FF307047000002290CD089 +:10247000032904D00129074818BF00207047032A08 +:1024800005D8054800EBC20070470448704700209B +:10249000704700BFA04300083C22002054430008BE +:1024A00070B59AB005460846144601A900F0C2F876 +:1024B00001A8FEF707FD431C0022C6B25B001046D0 +:1024C000C5E9003423700323023404F8013C01AB56 +:1024D000D1B202348E4201D81AB070BD13F8011B7C +:1024E000013204F8010C04F8021CF1E708B52023BE +:1024F00083F311880348FFF767FA002383F31188F9 +:1025000008BD00BFC832002090F8803003F01F02E1 +:10251000012A07D190F881200B2A03D10023C0E9BA +:102520001D3315E003F06003202B08D1B0F8843090 +:102530002BB990F88120212A03D81F2A04D8FFF74D +:1025400025BA222AEBD0FAE7034A426707228267BC +:10255000C3670120704700BF3322002007B505295B +:1025600017D8DFE801F0191603191920202383F387 +:102570001188104A01210190FFF7CEFA019802213B +:102580000D4AFFF7C9FA0D48FFF7EAF9002383F374 +:10259000118803B05DF804FB202383F311880748FA +:1025A000FFF7B4F9F2E7202383F311880348FFF71C +:1025B000CBF9EBE7F442000818430008C8320020CA +:1025C00038B50C4D0C4C2A460C4904F10800FFF7B5 +:1025D00067FF05F1CA0204F110000949FFF760FF27 +:1025E00005F5CA7204F118000649BDE83840FFF746 +:1025F00057BF00BFA04B00203C220020D44200085F +:10260000DE420008E942000870B5044608460D465F +:10261000FEF758FCC6B22046013403780BB91846C1 +:1026200070BD32462946FEF739FC0028F3D101205F +:10263000F6E700002DE9F84F05460C46FEF742FC90 +:102640002D49C6B22846FFF7DFFF08B10436F6B2BF +:102650002A492846FFF7D8FF08B11036F6B2632E94 +:102660000DD8DFF89490DFF894A0DFF89C80DFF8B5 +:102670009CB0234F2E7846B92670BDE8F88F2946C6 +:102680002046BDE8F84F01F0B9BD252E30D1072214 +:1026900049462846FEF702FC70B93B6807350B3403 +:1026A00044F80B3C7B6844F8073C3B8924F8033C26 +:1026B000BB7A04F8013CDDE7082251462846FEF7C4 +:1026C000EDFBA8B9A21C0F4B19780232090911F8C9 +:1026D000081002F8041C13F8011B01F00F015B4500 +:1026E00011F8081002F8031CEED118340835C1E7C0 +:1026F000013504F8016BBDE7C0430008E94200085A +:10270000C843000800E8F11FD44300080CE8F11F9B +:10271000BFF34F8F044B1A695107FCD1D3F8102136 +:102720005207F8D1704700BF0020005208B50D4B8A +:102730001B78ABB9FFF7ECFF0B4BDA68D10704D578 +:102740000A4A5A6002F188325A60D3F80C21D20743 +:1027500006D5064AC3F8042102F18832C3F80421E1 +:1027600008BD00BFFE4D0020002000522301674538 +:1027700008B5114B1B78F3B9104B1A69510703D5F3 +:10278000DA6842F04002DA60D3F81021520705D52A +:10279000D3F80C2142F04002C3F80C21FFF7B8FF38 +:1027A000064BDA6842F00102DA60D3F80C2142F0FD +:1027B0000102C3F80C2108BDFE4D0020002000528C +:1027C0000F289ABF00F58060400400207047000089 +:1027D0004FF4003070470000102070470F2808B5F4 +:1027E0000BD8FFF7EDFF00F500330268013204D18A +:1027F00004308342F9D1012008BD0020FCE700002D +:102800000F2870B5054645D8FFF7D4FC224CFFF7DA +:102810007FFF0646FFF78AFF4FF0FF33072D636106 +:10282000C4F8143120D82361FFF772FF2B0243F064 +:102830002403E360E36843F08003E36023695A07FD +:10284000FCD42846FFF764FF4FF40031FFF7B8FFD0 +:1028500000F002F93046FFF78BFFFFF7B5FC284682 +:10286000BDE87040FFF7BABFC4F81031FFF750FF62 +:10287000A5F108031B0243F02403C4F80C31D4F87B +:102880000C3143F08003C4F80C31D4F810315B07ED +:10289000FBD4D6E7002070BD002000522DE9F84F90 +:1028A00040EA020305460C461746D80602D000202F +:1028B000BDE8F88F27F01F07DFF8D4B0FFF736FF29 +:1028C0002744BC4203D10120FFF752FFF0E720224A +:1028D0002946204601F082FC10B920352034F0E76B +:1028E0002B4605F120021E68711CE0D104339A4288 +:1028F000F9D1FFF75FFC05F17843234AB3F5801F58 +:10290000224B28BF9A4603F1040338BF9046A2F138 +:10291000080228BF9846A3F108033ABF9146DA4659 +:102920009946FFF7F5FEC8F80060A5EB040CD9F84E +:10293000002004F11C0142F00202C9F80020221F0D +:10294000DAF8006016F00506FAD152F8043F8A4220 +:102950004CF80230F4D1BFF34F8FFFF7D9FE4FF0A0 +:10296000FF32C8F80020D9F8002022F00202C9F88E +:102970000020FFF729FC20222146284601F02EFCEA +:102980000028AAD030469FE71420005210210052A0 +:102990001020005210B5084C237828B11BB9FFF75E +:1029A000C5FE0123237010BD002BFCD02070BDE8B4 +:1029B0001040FFF7DDBE00BFFE4D00200244074B74 +:1029C000D2B210B5904200D110BD441C00B253F8F1 +:1029D000200041F8040BE0B2F4E700BF504000587B +:1029E0000E4B30B51C6F240405D41C6F1C671C6F84 +:1029F00044F400441C670A4C02442368D2B243F4F6 +:102A000080732360074B904200D130BD441C51F8C5 +:102A1000045B00B243F82050E0B2F4E700440258EF +:102A2000004802585040005807B5012201A9002073 +:102A3000FFF7C4FF019803B05DF804FB13B504462B +:102A4000FFF7F2FFA04205D0012201A90020019466 +:102A5000FFF7C6FF02B010BD0144BFF34F8F064B16 +:102A6000884204D3BFF34F8FBFF36F8F7047C3F813 +:102A70005C022030F4E700BF00ED00E0002070476A +:102A8000034B1A681AB9034AD2F8D0241A60704767 +:102A9000004E00200040025808B5FFF7F1FF024B3E +:102AA0001868C0F3806008BD004E0020EFF3098372 +:102AB000054968334A6B22F001024A6383F30988AF +:102AC000002383F31188704700EF00E0202080F39B +:102AD000118862B60D4B0E4AD96821F4E0610904F1 +:102AE000090C0A430B49DA60D3F8FC2042F08072EB +:102AF000C3F8FC20084AC2F8B01F116841F0010178 +:102B000011601022DA7783F82200704700ED00E0B0 +:102B10000003FA0555CEACC5001000E0202310B527 +:102B200083F311880E4B5B6813F4006314D0F1EE4D +:102B3000103AEFF309844FF08073683CE361094B6E +:102B4000DB6B236684F30988FFF7E4FA10B1064BC8 +:102B5000A36110BD054BFBE783F31188F9E700BFC4 +:102B600000ED00E000EF00E0F7030008FA030008C2 +:102B700070B5BFF34F8FBFF36F8F1A4A0021C2F8B1 +:102B80005012BFF34F8FBFF36F8F536943F400337D +:102B90005361BFF34F8FBFF36F8FC2F88410BFF341 +:102BA0004F8FD2F8803043F6E074C3F3C900C3F30B +:102BB0004E335B0103EA0406014646EA817501399A +:102BC000C2F86052F9D2203B13F1200FF2D1BFF3CB +:102BD0004F8F536943F480335361BFF34F8FBFF37B +:102BE0006F8F70BD00ED00E0FEE700000A4B0B4860 +:102BF0000B4A90420BD30B4BC11EDA1C121A22F067 +:102C000003028B4238BF00220021FEF763B953F85C +:102C1000041B40F8041BECE7B4450008D44F002027 +:102C2000D44F0020D44F00207047000070B5D0E989 +:102C3000244300224FF0FF359E6804EB42135101FC +:102C4000D3F80009002805DAD3F8000940F08040E5 +:102C5000C3F80009D3F8000B002805DAD3F8000BFD +:102C600040F08040C3F8000B013263189642C3F86D +:102C70000859C3F8085BE0D24FF00113C4F81C38C0 +:102C800070BD000000EB8103D3F80CC02DE9F043C8 +:102C9000DCF814204E1CD0F89050D2F800E005EB80 +:102CA000063605EB4118506870450AD30122D5F865 +:102CB000343802FA01F123EA0101C5F83418BDE8FD +:102CC000F083AEEB0003BCF81040A34228BF2346BC +:102CD000D8F81849A4B2B3EB840FF0D89468A4F1E3 +:102CE000040959F8047F3760A4EB09071F44042F37 +:102CF000F7D81C44034494605360D4E7890141F041 +:102D00002001016103699B06FCD41220FFF76CBA15 +:102D100010B50A4C2046FEF7DDFE094BC4F8903092 +:102D2000084BC4F89430084C2046FEF7D3FE074BFE +:102D3000C4F89030064BC4F8943010BD044E002007 +:102D4000000008400C440008A04E00200000044091 +:102D50001844000870B503780546012B5DD1494B36 +:102D6000D0F89040984259D1474B0E216520D3F8B6 +:102D7000D82042F00062C3F8D820D3F8002142F0F6 +:102D80000062C3F80021D3F80021D3F8802042F07C +:102D90000062C3F88020D3F8802022F00062C3F8DC +:102DA0008020D3F8803000F071FC384BE360384B62 +:102DB000C4F800380023D5F89060C4F8003EC02362 +:102DC00023604FF40413A3633369002BFCDA01235F +:102DD0000C203361FFF708FA3369DB07FCD41220BB +:102DE000FFF702FA3369002BFCDA00262846A660BA +:102DF000FFF71CFF6B68C4F81068DB68C4F8146840 +:102E0000C4F81C68002B3AD1224BA3614FF0FF336A +:102E10006361A36843F00103A36070BD1E4B984239 +:102E2000C8D1194B0E214D20D3F8D82042F00072A2 +:102E3000C3F8D820D3F8002142F00072C3F8002173 +:102E4000D3F80021D3F8802042F00072C3F880202C +:102E5000D3F8802022F00072C3F88020D3F88020BD +:102E6000D3F8D82022F08062C3F8D820D3F800210C +:102E700022F08062C3F80021D3F8003193E7074BBA +:102E8000C3E700BF044E0020004402584014004035 +:102E900003002002003C30C0A04E0020083C30C09F +:102EA000F8B5D0F89040054600214FF00066204666 +:102EB000FFF724FFD5F8941000234FF001128F681C +:102EC0004FF0FF30C4F83438C4F81C2804EB431228 +:102ED00001339F42C2F80069C2F8006BC2F80809CA +:102EE000C2F8080BF2D20B68D5F89020C5F89830DC +:102EF000636210231361166916F01006FBD11220CD +:102F0000FFF772F9D4F8003823F4FE63C4F80038F0 +:102F1000A36943F4402343F01003A3610923C4F8D9 +:102F20001038C4F814380B4BEB604FF0C043C4F8B2 +:102F3000103B094BC4F8003BC4F81069C4F80039D1 +:102F4000D5F8983003F1100243F48013C5F89820A7 +:102F5000A362F8BDE843000840800010D0F890203C +:102F600090F88A10D2F8003823F4FE6343EA011384 +:102F7000C2F80038704700002DE9F84300EB8103E8 +:102F8000D0F890500C468046DA680FFA81F9480173 +:102F9000166806F00306731E022B05EB41134FF073 +:102FA000000194BFB604384EC3F8101B4FF0010166 +:102FB00004F1100398BF06F1805601FA03F39169FA +:102FC00098BF06F5004600293AD0578A04F1580107 +:102FD000374349016F50D5F81C180B430021C5F841 +:102FE0001C382B180127C3F81019A7405369611E1C +:102FF0009BB3138A928B9B08012A88BF5343D8F84E +:103000009820981842EA034301F140022146C8F88B +:103010009800284605EB82025360FFF76FFE08EB2D +:103020008900C3681B8A43EA845348341E43640101 +:103030002E51D5F81C381F43C5F81C78BDE8F8831D +:1030400005EB4917D7F8001B21F40041C7F8001B16 +:10305000D5F81C1821EA0303C0E704F13F030B4A2B +:103060002846214605EB83035A60FFF747FE05EB30 +:103070004910D0F8003923F40043C0F80039D5F8DE +:103080001C3823EA0707D7E700800010000400027D +:10309000D0F894201268C0F89820FFF7C7BD000050 +:1030A0005831D0F8903049015B5813F4004004D0F7 +:1030B00013F4001F0CBF0220012070474831D0F8E4 +:1030C000903049015B5813F4004004D013F4001F02 +:1030D0000CBF02200120704700EB8101CB68196A08 +:1030E0000B6813604B6853607047000000EB81036E +:1030F00030B5DD68AA691368D36019B9402B84BF65 +:10310000402313606B8A1468D0F890201C4402EBB3 +:103110004110013C09B2B4FBF3F46343033323F0E1 +:10312000030343EAC44343F0C043C0F8103B2B6899 +:1031300003F00303012B0ED1D2F8083802EB411043 +:1031400013F4807FD0F8003B14BF43F0805343F06A +:103150000053C0F8003B02EB4112D2F8003B43F0B1 +:103160000443C2F8003B30BD2DE9F041D0F8906037 +:1031700005460C4606EB4113D3F8087B3A07C3F823 +:10318000087B08D5D6F814381B0704D500EB81035B +:10319000DB685B689847FA071FD5D6F81438DB0759 +:1031A0001BD505EB8403D968CCB98B69488A5A686A +:1031B000B2FBF0F600FB16228AB91868DA68904272 +:1031C0000DD2121AC3E90024202383F3118821466B +:1031D0002846FFF78BFF84F31188BDE8F0810123B7 +:1031E00003FA04F26B8923EA02036B81CB68002B9C +:1031F000F3D021462846BDE8F041184700EB810393 +:103200004A0170B5DD68D0F890306C692668E660D8 +:1032100056BB1A444FF40020C2F810092A6802F085 +:103220000302012A0AB20ED1D3F8080803EB4214B4 +:1032300010F4807FD4F8000914BF40F0805040F0B3 +:103240000050C4F8000903EB4212D2F8000940F024 +:103250000440C2F800090122D3F8340802FA01F14F +:103260000143C3F8341870BD19B9402E84BF402003 +:10327000206020681A442E8A8419013CB4FBF6F4BD +:1032800040EAC44040F00050C6E700002DE9F0419C +:10329000D0F8906004460D4606EB4113D3F8087948 +:1032A000C3F80879FB071CD5D6F81038DA0718D50B +:1032B00000EB8103D3F80CC0DCF81430D3F800E045 +:1032C000DA6896451BD2A2EB0E024FF000081A6096 +:1032D000C3F80480202383F31188FFF78FFF88F35E +:1032E00011883B0618D50123D6F83428AB40134289 +:1032F00012D029462046BDE8F041FFF7C3BC0123A8 +:1033000003FA01F2038923EA02030381DCF808309F +:10331000002BE6D09847E4E7BDE8F0812DE9F84FAF +:10332000D0F8905004466E69AB691E4016F4805880 +:103330006E6103D0BDE8F84FFEF73CBC002E12DAF8 +:10334000D5F8003E9F0705D0D5F8003E23F00303D3 +:10335000C5F8003ED5F80438204623F00103C5F82F +:103360000438FEF753FC300505D52046FFF75EFC18 +:103370002046FEF73BFCB1040CD5D5F8083813F015 +:10338000060FEB6823F470530CBF43F4105343F45F +:10339000A053EB60320704D56368DB680BB12046AD +:1033A0009847F30200F1BA80B70226D5D4F890907E +:1033B00000274FF0010A09EB4712D2F8003B03F453 +:1033C0004023B3F5802F11D1D2F8003B002B0DDA4A +:1033D00062890AFA07F322EA0303638104EB870395 +:1033E000DB68DB6813B13946204698470137D4F8CB +:1033F0009430FFB29B689F42DDD9F00619D5D4F80E +:103400009000026AC2F30A1702F00F0302F4F012EE +:10341000B2F5802F00F0CC80B2F5402F09D104EB3B +:103420008303002200F58050DB681B6A974240F05E +:10343000B2803003D5F8185835D5E90303D50021FB +:103440002046FFF791FEAA0303D501212046FFF78E +:103450008BFE6B0303D502212046FFF785FE2F0369 +:1034600003D503212046FFF77FFEE80203D50421A0 +:103470002046FFF779FEA90203D505212046FFF774 +:1034800073FE6A0203D506212046FFF76DFE2B026C +:1034900003D507212046FFF767FEEF0103D508217A +:1034A0002046FFF761FE700340F1A980E90703D5CC +:1034B00000212046FFF7EAFEAA0703D50121204696 +:1034C000FFF7E4FE6B0703D502212046FFF7DEFE7F +:1034D0002F0703D503212046FFF7D8FEEE0603D5BC +:1034E00004212046FFF7D2FEA80603D50521204679 +:1034F000FFF7CCFE690603D506212046FFF7C6FE7E +:103500002A0603D507212046FFF7C0FEEB0576D536 +:1035100020460821BDE8F84FFFF7B8BED4F89090D8 +:1035200000274FF0010AD4F894305FFA87FB9B68BC +:103530009B453FF639AF09EB4B13D3F8002902F452 +:103540004022B2F5802F24D1D3F80029002A20DAB6 +:10355000D3F8002942F09042C3F80029D3F800299B +:10356000002AFBDB5946D4F89000FFF7C7FB2289FD +:103570000AFA0BF322EA0303238104EB8B03DB68D3 +:103580009B6813B159462046984759462046FFF795 +:1035900079FB0137C7E7910701D1D0F80080072AEE +:1035A00002F101029CBF03F8018B4FEA18283DE7A6 +:1035B00004EB830300F58050DA68D2F818C0DCF819 +:1035C0000820DCE9001CA1EB0C0C00218F4208D183 +:1035D000DB689B699A683A449A605A683A445A6030 +:1035E00027E711F0030F01D1D0F800808C4501F1DD +:1035F000010184BF02F8018B4FEA1828E6E7BDE815 +:10360000F88F000008B50348FFF788FEBDE80840C2 +:10361000FFF784BA044E002008B50348FFF77EFE8A +:10362000BDE80840FFF77ABAA04E0020D0F89030ED +:1036300003EB4111D1F8003B43F40013C1F8003B08 +:1036400070470000D0F8903003EB4111D1F80039F9 +:1036500043F40013C1F8003970470000D0F89030EF +:1036600003EB4111D1F8003B23F40013C1F8003BF8 +:1036700070470000D0F8903003EB4111D1F80039C9 +:1036800023F40013C1F8003970470000090100F16C +:103690006043012203F56143C9B283F8001300F0CF +:1036A0001F039A4043099B0003F1604303F5614304 +:1036B000C3F880211A60704730B50433039C01724F +:1036C000002104FB0325C160C0E90653049B03638A +:1036D000059BC0E90000C0E90422C0E90842C0E936 +:1036E0000A11436330BD00000022416AC260C0E994 +:1036F0000411C0E90A226FF00101FEF7E5BD0000E8 +:10370000D0E90432934201D1C2680AB9181D70474A +:1037100000207047036919600021C2680132C2604D +:10372000C269134482699342036124BF436A0361FF +:10373000FEF7BEBD38B504460D46E3683BB162698D +:103740000020131D1268A3621344E36207E0237A8A +:1037500033B929462046FEF79BFD0028EDDA38BD37 +:103760006FF00100FBE70000C368C269013BC36062 +:103770004369134482699342436124BF436A4361AE +:1037800000238362036B03B11847704770B5202391 +:10379000044683F31188866A3EB9FFF7CBFF0546DE +:1037A00018B186F31188284670BDA36AE26A13F83F +:1037B000015B9342A36202D32046FFF7D5FF0023AB +:1037C00083F31188EFE700002DE9F84F04460E4619 +:1037D000174698464FF0200989F311880025AA461C +:1037E000D4F828B0BBF1000F09D141462046FFF7BD +:1037F000A1FF20B18BF311882846BDE8F88FD4E9EA +:103800000A12A7EB050B521A934528BF9346BBF14A +:10381000400F1BD9334601F1400251F8040B91428D +:1038200043F8040BF9D1A36A403640354033A36214 +:10383000D4E90A239A4202D32046FFF795FF8AF380 +:103840001188BD42D8D289F31188C9E730465A465B +:10385000FDF71AFBA36A5E445D445B44A362E7E79D +:1038600010B5029C0433017204FB0321C460C0E95B +:1038700006130023C0E90A33039B0363049BC0E9DA +:103880000000C0E90422C0E90842436310BD000003 +:10389000026A6FF00101C260426AC0E9042200229C +:1038A000C0E90A22FEF710BDD0E904239A4201D1F3 +:1038B000C26822B9184650F8043B0B6070470020DC +:1038C00070470000C3680021C2690133C3604369C7 +:1038D000134482699342436124BF436A4361FEF704 +:1038E000E7BC000038B504460D46E3683BB12369E8 +:1038F00000201A1DA262E2691344E36207E0237A02 +:1039000033B929462046FEF7C3FC0028EDDA38BD5E +:103910006FF00100FBE7000003691960C268013A1B +:10392000C260C269134482699342036124BF436A3F +:10393000036100238362036B03B1184770470000E3 +:1039400070B520230D460446114683F31188866A1C +:103950002EB9FFF7C7FF10B186F3118870BDA36AB7 +:103960001D70A36AE26A01339342A36204D3E16942 +:1039700020460439FFF7D0FF002080F31188EDE7DF +:103980002DE9F84F04460D46904699464FF0200A1F +:103990008AF311880026B346A76A4FB949462046E4 +:1039A000FFF7A0FF20B187F311883046BDE8F88FFC +:1039B000D4E90A073A1AA8EB0607974228BF174628 +:1039C000402F1BD905F1400355F8042B9D4240F8C8 +:1039D000042BF9D1A36A40364033A362D4E90A2309 +:1039E0009A4204D3E16920460439FFF795FF8BF32F +:1039F00011884645D9D28AF31188CDE729463A463F +:103A0000FDF742FAA36A3D443E443B44A362E5E726 +:103A1000D0E904239A4217D1C3689BB1836A8BB162 +:103A2000043B9B1A0ED01360C368013BC360C3699B +:103A30001A4483699A42026124BF436A03610023E6 +:103A400083620123184670470023FBE700F0DAB8D1 +:103A5000034B002258631A610222DA60704700BFEC +:103A6000000C0040014B0022DA607047000C00405F +:103A7000014B5863704700BF000C0040014B586A6F +:103A8000704700BF000C00404B6843608B68836048 +:103A9000CB68C3600B6943614B6903628B69436206 +:103AA0000B6803607047000008B53C4B40F2FF71A3 +:103AB0003B48D3F888200A43C3F88820D3F88820ED +:103AC00022F4FF6222F00702C3F88820D3F888208E +:103AD000D3F8E0200A43C3F8E020D3F808210A43D2 +:103AE000C3F808212F4AD3F808311146FFF7CCFF5D +:103AF00000F5806002F11C01FFF7C6FF00F5806051 +:103B000002F13801FFF7C0FF00F5806002F15401B7 +:103B1000FFF7BAFF00F5806002F17001FFF7B4FF14 +:103B200000F5806002F18C01FFF7AEFF00F58060C8 +:103B300002F1A801FFF7A8FF00F5806002F1C401BF +:103B4000FFF7A2FF00F5806002F1E001FFF79CFFA4 +:103B500000F5806002F1FC01FFF796FF02F58C7121 +:103B600000F58060FFF790FF00F000F90E4BD3F8EE +:103B7000902242F00102C3F89022D3F8942242F03E +:103B80000102C3F894220522C3F898204FF0605236 +:103B9000C3F89C20054AC3F8A02008BD0044025881 +:103BA000000002582444000800ED00E01F00080354 +:103BB00008B500F0F3FAFEF7DBFA0F4BD3F8DC2080 +:103BC00042F04002C3F8DC20D3F8042122F0400286 +:103BD000C3F80421D3F80431084B1A6842F00802F4 +:103BE0001A601A6842F004021A60FEF749FFBDE845 +:103BF0000840FEF7E5BC00BF004402580018024828 +:103C000070470000114BD3F8E82042F00802C3F8D7 +:103C1000E820D3F8102142F00802C3F810210C4A22 +:103C2000D3F81031D36B43F00803D363C722094B99 +:103C30009A624FF0FF32DA6200229A615A63DA60C8 +:103C40005A6001225A611A60704700BF004402584E +:103C50000010005C000C0040094A08B51169D368E7 +:103C60000B40D9B29B076FEA0101116107D52023F0 +:103C700083F31188FEF79CFA002383F3118808BDB3 +:103C8000000C0040384B4FF0FF31D3F88020C3F8D0 +:103C90008010D3F880200022C3F88020D3F8800061 +:103CA000D3F88400C3F88410D3F88400C3F88420C8 +:103CB000D3F88400D86F40F0FF4040F4FF0040F498 +:103CC0003F5040F03F00D867D86F20F0FF4020F40D +:103CD000FF0020F43F5020F03F00D867D86FD3F8A2 +:103CE00088006FEA40506FEA5050C3F88800D3F85C +:103CF0008800C0F30A00C3F88800D3F88800D3F81E +:103D00009000C3F89010D3F89000C3F89020D3F837 +:103D10009000D3F89400C3F89410D3F89400C3F83B +:103D20009420D3F89400D3F89800C3F89810D3F8EF +:103D30009800C3F89820D3F89800D3F88C00C3F803 +:103D40008C10D3F88C00C3F88C20D3F88C00D3F8F7 +:103D50009C00C3F89C10D3F89C10C3F89C20D3F8A7 +:103D60009C3000F0E7B900BF00440258614B0122CB +:103D7000C3F80821604BD3F8F42042F00202C3F8E4 +:103D8000F420D3F81C2142F00202C3F81C210222C5 +:103D9000D3F81C31594BDA605A689104FCD5584A63 +:103DA0001A6001229A60574ADA6000221A614FF4C1 +:103DB00040429A61514B9A699204FCD51A6842F4C8 +:103DC00080721A604C4B1A6F12F4407F04D04FF48B +:103DD00080321A6700221A671A6842F001021A60DC +:103DE000454B1A685007FCD500221A611A6912F077 +:103DF0003802FBD1012119604FF0804159605A67A8 +:103E0000414ADA62414A1A611A6842F480321A6001 +:103E1000394B1A689103FCD51A6842F480521A6033 +:103E20001A689204FCD53A4A3A499A6200225A63C7 +:103E300019633949DA6399635A64384A1A64384A0B +:103E4000DA621A6842F0A8521A602B4B1A6802F024 +:103E50002852B2F1285FF9D148229A614FF4886262 +:103E6000DA6140221A622F4ADA644FF080521A65F2 +:103E70002D4A5A652D4A9A6532232D4A13601368DC +:103E800003F00F03022BFAD11B4B1A6942F0030215 +:103E90001A611A6902F03802182AFAD1D3F8DC2024 +:103EA00042F00052C3F8DC20D3F8042142F0005263 +:103EB000C3F80421D3F80421D3F8DC2042F0804277 +:103EC000C3F8DC20D3F8042142F08042C3F8042177 +:103ED000D3F80421D3F8DC2042F00042C3F8DC2000 +:103EE000D3F8042142F00042C3F80421D3F804318E +:103EF000704700BF0080005100440258004802583B +:103F000000C000F0020000010000FF0100889008DE +:103F100032206000630209011D0204004704050805 +:103F2000FD0BFF01200000200010E0000001010057 +:103F3000002000524FF0B04208B5D2F8883003F0AC +:103F40000103C2F8883023B1044A13680BB15068EA +:103F50009847BDE80840FEF7E1BD00BF544F002080 +:103F60004FF0B04208B5D2F8883003F00203C2F82F +:103F7000883023B1044A93680BB1D0689847BDE8F4 +:103F80000840FEF7CBBD00BF544F00204FF0B042B9 +:103F900008B5D2F8883003F00403C2F8883023B1A2 +:103FA000044A13690BB150699847BDE80840FEF711 +:103FB000B5BD00BF544F00204FF0B04208B5D2F855 +:103FC000883003F00803C2F8883023B1044A9369AB +:103FD0000BB1D0699847BDE80840FEF79FBD00BF10 +:103FE000544F00204FF0B04208B5D2F8883003F0AB +:103FF0001003C2F8883023B1044A136A0BB1506A27 +:104000009847BDE80840FEF789BD00BF544F002027 +:104010004FF0B04310B5D3F8884004F47872C3F879 +:104020008820A30604D5124A936A0BB1D06A984738 +:10403000600604D50E4A136B0BB1506B98472106EE +:1040400004D50B4A936B0BB1D06B9847E20504D5AE +:10405000074A136C0BB1506C9847A30504D5044A6A +:10406000936C0BB1D06C9847BDE81040FEF756BD7D +:10407000544F00204FF0B04310B5D3F8884004F4FB +:104080007C42C3F88820620504D5164A136D0BB133 +:10409000506D9847230504D5124A936D0BB1D06D2E +:1040A0009847E00404D50F4A136E0BB1506E984741 +:1040B000A10404D50B4A936E0BB1D06E98476204ED +:1040C00004D5084A136F0BB1506F9847230404D5E9 +:1040D000044A936F0BB1D06F9847BDE81040FEF7CC +:1040E0001DBD00BF544F002008B50348FDF704F97B +:1040F000BDE80840FEF712BDCC23002008B50348F8 +:10410000FDF7FAF8BDE80840FEF708BD38240020A6 +:1041100008B50348FDF7F0F8BDE80840FEF7FEBC1F +:10412000A424002008B5FFF797FDBDE80840FEF77E +:10413000F5BC0000062108B50846FFF7A7FA0621DE +:104140000720FFF7A3FA06210820FFF79FFA0621B0 +:104150000920FFF79BFA06210A20FFF797FA0621AC +:104160001720FFF793FA06212820FFF78FFA09217D +:104170007A20FFF78BFA07213220FFF787FA0C210C +:104180002620FFF783FA0C212720FFF77FFA0C2166 +:104190005220BDE80840FFF779BA000008B5FFF7E4 +:1041A00071FD00F00DF8FDF7B9FAFDF791FCFDF790 +:1041B00063FBFFF725FDBDE80840FFF747BC0000A3 +:1041C0000023054A19460133102BC2E9001102F100 +:1041D0000802F8D1704700BF544F002010B50139D4 +:1041E0000244904201D1002005E0037811F8014F0C +:1041F000A34201D0181B10BD0130F2E7034611F8AD +:10420000012B03F8012B002AF9D1704753544D3389 +:104210003248373F3F3F0053544D333248373433F1 +:104220002F37353300000000C8320020CC23002097 +:1042300038240020A4240020009600000000000084 +:10424000000000000000000000000000000000006E +:1042500000000000E5160008D11600080D17000840 +:10426000F916000805170008F1160008DD16000809 +:10427000C91600081917000800000000F51700080B +:10428000E11700081D180008091800081518000893 +:1042900001180008ED170008D917000829180008B0 +:1042A0000000000001000000000000006D61696E68 +:1042B0000000000069646C6500000000B442000862 +:1042C00050310020C8320020010000006D2100089C +:1042D000000000004172647550696C6F74002542E3 +:1042E0004F415244252D424C002553455249414CE3 +:1042F000250000000200000000000000151A000860 +:10430000851A000840004000704B0020804B0020C0 +:104310000200000000000000030000000000000098 +:10432000CD1A00080000000010000000904B002093 +:10433000000000000100000000000000044E00200A +:10434000010102005D2500086D2400080925000810 +:10435000ED240008430000005C430008090243000C +:10436000020100C03209040000010202010005241C +:1043700000100105240100010424020205240600A6 +:1043800001070582030800FF09040100020A00007A +:1043900000070501024000000705810240000000FF +:1043A00012000000A84300081201100102000040A2 +:1043B000091241570002010203010000040309042D +:1043C00025424F415244250050697850696C6F7402 +:1043D0002D56360030313233343536373839414294 +:1043E000434445460000000000000000211C000876 +:1043F000D91E0008851F0008400040003C4F0020E7 +:104400003C4F0020010000004C4F002080000000C5 +:10441000400100000800000000010000000400004E +:10442000080000000000802A00000000AAAAAAAA32 +:1044300000000024FFFF00000000000000A00A00B0 +:104440004000000008000000AAAAAAAA000000007C +:10445000FFFF00000000000000000000100000143A +:1044600000000000AAAAAAAA10000014FFFF000082 +:10447000000000000000000010681A0000000000AA +:10448000AAAAAAAA10541500FFFF00000000700796 +:10449000770000000081020100100000AAAAAAAA69 +:1044A00000410100FFFF0000000000700700000055 +:1044B0000000000000000000AAAAAAAA0000000054 +:1044C000FFFF0000000000000000000000000000EE +:1044D00000000000AAAAAAAA00000000FFFF000036 +:1044E00000000000000000000000000000000000CC +:1044F000AAAAAAAA00000000FFFF00000000000016 +:10450000000000000000000000000000AAAAAAAA03 +:1045100000000000FFFF000000000000000000009D +:104520000000000000000000AAAAAAAA00000000E3 +:10453000FFFF00000000000000000000000000007D +:1045400000000000AAAAAAAA00000000FFFF0000C5 +:1045500000000000000000003B040000000000001C +:1045600000001E0000000000FF000000000000002E +:104570000C4200083F0000005004000017420008F1 +:104580003F000000009600000000080096000000B8 +:104590000008000004000000BC4300080000000008 +:1045A000000000000000000000000000000000000B +:0445B0000000000007 +:00000001FF diff --git a/Tools/bootloaders/Pixhawk6C_bl.bin b/Tools/bootloaders/Pixhawk6C_bl.bin new file mode 100755 index 00000000000..f74eefc68d8 Binary files /dev/null and b/Tools/bootloaders/Pixhawk6C_bl.bin differ diff --git a/Tools/bootloaders/Pixhawk6X-ODID_bl.bin b/Tools/bootloaders/Pixhawk6X-ODID_bl.bin new file mode 100755 index 00000000000..916e7b25462 Binary files /dev/null and b/Tools/bootloaders/Pixhawk6X-ODID_bl.bin differ diff --git a/Tools/bootloaders/Pixhawk6X_bl.bin b/Tools/bootloaders/Pixhawk6X_bl.bin new file mode 100755 index 00000000000..e423fa530e8 Binary files /dev/null and b/Tools/bootloaders/Pixhawk6X_bl.bin differ diff --git a/Tools/bootloaders/Pixracer-periph_bl.bin b/Tools/bootloaders/Pixracer-periph_bl.bin old mode 100644 new mode 100755 index b8c2d6e2a6c..8996c42e28f Binary files a/Tools/bootloaders/Pixracer-periph_bl.bin and b/Tools/bootloaders/Pixracer-periph_bl.bin differ diff --git a/Tools/bootloaders/Pixracer-periph_bl.hex b/Tools/bootloaders/Pixracer-periph_bl.hex index 01518690777..3a75e01b2a8 100644 --- a/Tools/bootloaders/Pixracer-periph_bl.hex +++ b/Tools/bootloaders/Pixracer-periph_bl.hex @@ -1,1874 +1,1802 @@ :020000040800F2 -:10000000000700202905000861280008652800086D -:10001000B9280008652800088D2800082B0500086D -:100020002B0500082B0500082B050008653B000880 -:100030002B0500082B0500082B0500082B050008E0 -:100040002B0500082B0500082B0500082B050008D0 -:100050002B0500082B050008A9650008D5650008D8 -:10006000016600082D660008596600082B05000887 -:100070002B0500082B0500082B0500082B050008A0 -:100080002B0500082B0500082B050008FD2700089C -:100090002D2800083D2800082B050008856600086B -:1000A0002B0500082B0500082B0500082B05000870 -:1000B000BD6300082B0500082B0500082B05000870 -:1000C0002B0500082B0500082B0500082B05000850 -:1000D0002B0500082B050008213C00082B05000813 -:1000E000ED6600082B0500082B0500082B0500080D -:1000F0002B0500082B0500082B0500082B05000820 -:100100002B0500082B0500082B0500082B0500080F -:100110002B0500082B0500082B0500082B050008FF -:100120002B0500082B0500082B0500082B050008EF -:100130002B0500082B0500082B0500082B050008DF -:100140002B0500082B0500082B050008595C00084A -:100150002B0500082B0500082B0500082B050008BF -:100160002B0500082B0500082B0500082B050008AF -:100170002B0500082B0500082B0500082B0500089F -:100180002B0500082B0500082B0500082B0500088F -:100190002B0500082B0500082B0500082B0500087F -:1001A0002B0500082B0500082B0500082B0500086F -:1001B0002B0500082B0500082B0500082B0500085F -:1001C0002B0500082B0500082B0500082B0500084F -:1001D0002B0500082B0500082B0500082B0500083F -:1001E000F518000800000000D0400B1CD1409C46D0 -:1001F000203AD34018435242634693401843704715 -:100200009140031C90409C46203A9340194352422F -:100210006346D3401943704753B94AB9002908BF10 -:1002200000281CBF4FF0FF314FF0FF3000F07AB9CB -:10023000ADF1080C6DE904CE00F006F8DDF804E03D -:10024000DDE9022304B070472DE9F0478C460D46E6 -:100250000446089E002B51D18A4217466DD9B2FA46 -:1002600082FEBEF1000F0BD0CEF1200C01FA0EF58C -:1002700020FA0CFC02FA0EF74CEA050C00FA0EF418 -:100280004FEA174A250CBCFBFAF81FFA87F90AFB5C -:1002900018CC45EA0C4508FB09F3AB420AD9ED1925 -:1002A00008F1FF3280F02381AB4240F22081A8F1B7 -:1002B00002083D44ED1AA4B2B5FBFAF00AFB105552 -:1002C00044EA054400FB09F9A14509D9E41900F104 -:1002D000FF3380F00A81A14540F2078102383C4497 -:1002E000A4EB090440EA08400021002E61D024FA62 -:1002F0000EF4002334607360BDE8F0878B4207D9A9 -:10030000002E54D0002186E821000846BDE8F08781 -:10031000B3FA83F1002940F08E80AB4202D38242CF -:1003200000F2FA80841A65EB03050120AC46002E2A -:100330003FD086E81010BDE8F08712B90127B7FB5F -:10034000F2F7B7FA87FEBEF1000F34D1EB1B3A0C7F -:100350001FFA87FC0121B3FBF2F8250C02FB1833CE -:1003600045EA03450CFB08F3AB4207D9ED1908F148 -:10037000FF3002D2AB4200F2D1808046ED1AA3B228 -:10038000B5FBF2F002FB105543EA05440CFB00FC00 -:10039000A44507D9E41900F1FF3302D2A44500F2C5 -:1003A000B8801846A4EB0C0440EA08409DE73146AB -:1003B0003046BDE8F087CEF1200405FA0EF307FAC7 -:1003C0000EF720FA04F83A0C25FA04F448EA030878 -:1003D000B4FBF2F14FEA184502FB11441FFA87FC07 -:1003E00045EA044501FB0CF3AB4200FA0EF409D9CF -:1003F000ED1901F1FF3080F08A80AB4240F2878036 -:1004000002393D44EB1A1FFA88F5B3FBF2F002FB08 -:10041000103345EA034500FB0CF3AB4207D9ED1955 -:1004200000F1FF386FD2AB426DD902383D44EB1A70 -:1004300040EA01418FE7C1F1200722FA07F88B401B -:1004400005FA01F448EA030320FA07FE4FEA134CC9 -:10045000FD404EEA040EB5FBFCF94FEA1E440CFBCE -:1004600019551FFA83F844EA054509FB08F4AC4224 -:1004700002FA01F200FA01FA08D9ED1809F1FF3089 -:1004800043D2AC4241D9A9F102091D442D1B1FFAE8 -:100490008EFEB5FBFCF00CFB10554EEA054400FB4C -:1004A00008F8A04507D9E41800F1FF3529D2A04586 -:1004B00027D902381C4440EA0940A4EB0804A0FBF9 -:1004C00002894C45C6464D4615D312D056B1BAEBFB -:1004D0000E0364EB050404FA07F7CB401F43CC403E -:1004E000376074600021BDE8F0871846F8E6904652 -:1004F000E0E6C245EAD2B8EB020E69EB030501382B -:10050000E4E72846D7E7404691E78146BEE7014643 -:1005100078E702383C4445E7084608E7A8F10208B6 -:100520003D442BE7704700BF02E000F000F8FEE713 -:1005300072B6394880F30888384880F3098838480B -:100540004EF60851CEF20001086040F20000CCF2F5 -:1005500000004EF63471CEF200010860BFF34F8FF9 -:10056000BFF36F8F40F20000C0F2F0004EF68851EA -:10057000CEF200010860BFF34F8FBFF36F8F4FF0D3 -:100580000000E1EE100A4EF63C71CEF20001086068 -:10059000062080F31488BFF36F8F05F025F805F06F -:1005A000A3FE4FF055301F491B4A91423CBF41F812 -:1005B000040BFAE71C49194A91423CBF41F8040B6D -:1005C000FAE71A491A4A1B4B9A423EBF51F8040BEC -:1005D00042F8040BF8E700201749184A91423CBF43 -:1005E00041F8040BFAE705F003F805F0D9FE144CC6 -:1005F000144DAC4203DA54F8041B8847F9E700F0C5 -:100600003FF8114C114DAC4203DA54F8041B8847F3 -:10061000F9E704F0EBBF00000007002000270020EE -:100620000000000800010020000700206874000896 -:10063000002700209427002098270020545A0020EB -:10064000E0010008E4010008E4010008E4010008FA -:100650002DE9F04F2DED108AC1F80CD0C3689D46EE -:10066000BDEC108ABDE8F08F002383F31188284683 -:10067000A047002004F0A6FB04F098FA00DFFEE794 -:10068000F8B5314C7A2323700523002563701F23AE -:10069000A570E57025716571A571E57125726572AA -:1006A000A372E57201F08EFA20B10F2325726572F4 -:1006B000A372E57204F03EFF074604F08FFF064682 -:1006C000B0BB224B9F4233D001339F4233D0204BEB -:1006D00027F0FF029A4231D1F8B200F043FD3546CF -:1006E00042F2107400F06CFF00F042FD08B90546BC -:1006F000044636B1174B9F4203D004F067FF002435 -:100700002546002004F020FF134B1B6913F480736F -:1007100018D00DB100F06AF801F034FB00F072FF60 -:1007200001F07EF9204600F0C3F800F05FF8F9E729 -:1007300035460024D6E704460125D3E7054641F2B5 -:100740008834CFE71C46E7E798270020010007B070 -:10075000000008B0263A09B00004024008B501F0D4 -:10076000DDF8A0F120035842584108BD07B5054BFC -:1007700002211B88ADF8043001A801F03BF903B059 -:100780005DF804FB046B000810B5202383F3118887 -:100790001248C3680BB104F09BFB0023104A0F48BA -:1007A0004FF47A7104F058FB002383F311880D4C49 -:1007B000236813B12368013B2360636813B1636846 -:1007C000013B6360084B1B7833B9636823B902208F -:1007D00001F03EFA3223636010BD00BFA427002061 -:1007E00089070008C0280020B827002010B5274B33 -:1007F000274953F8042F013200D110BD8B42F8D1A4 -:10080000244C254B22689A423ED9244B9B6803F125 -:10081000006303F580339A4236D204F0ABFE04F055 -:10082000BDFE002001F016F91D4B0220187001F0EA -:1008300001FA1C4B1A6C00221A64196E1A66196EA2 -:10084000596C5A64596E5A665A6E5A6942F080025F -:100850005A615A6922F080025A615A691A6942F053 -:1008600000521A611A6922F000521A611B6972B6AD -:100870000D4A0E4B13601B682268202181F31188FA -:100880009D4683F30888104710BD00BFFCFF000899 -:100890001C00010804000108FFFF00089827002041 -:1008A000B82700200038024008ED00E000000108F1 -:1008B0002DE9F04F99B0B34C01902022FF2110A8F0 -:1008C000A66801F001FAB04A1378A346A3B9AF486D -:1008D0000121C3601170202383F31188C3680BB119 -:1008E00004F0F6FA0023AA4AA8484FF47A7104F0FB -:1008F000B3FA002383F31188019B13B1A54B019A2E -:100900001A60A54AA349019F0292002313704B600D -:1009100099461C461D469846012001F08BF9002F90 -:1009200000F012829B4B1B68002B40F00D8219B027 -:10093000BDE8F08F0220FFF711FF002840F0FB8197 -:10094000019BB9F1000F08BF1F46944B1B88ADF8FF -:100950002C3002210BA801F04DF8DDE74FF47A703E -:1009600000F0DCFF031E0393EADB0220FFF7F6FE34 -:1009700082460028E4D0039B581E042800F2DD8143 -:10098000DFE800F0030E1114170018A8052340F843 -:10099000343D042101F02EF854464FF0000856E093 -:1009A00004217848F6E704217D48F3E704217D48D7 -:1009B000F0E71C24204601F04FF804340B9004218A -:1009C0000BA801F017F82C2CF4D1E5E7002DB7D0D7 -:1009D000002CB5D00220FFF7C1FE0546002800F02C -:1009E000AF8101206C4C01F035F80220207001F03D -:1009F00021F94FF000095FFA89FA504601F03AF800 -:100A0000074658B1504601F045F809F101090028A0 -:100A1000F1D12C46A9460027634B97E7012302201A -:100A2000237001F0F9F83E46DBF808309E4206D20A -:100A3000304601F011F80130EBD10436F4E7029BA7 -:100A400000261E70534BA9465E602C46374601F0C7 -:100A50008FF915B1002C18BF0027FFF787FE5BE761 -:100A6000002D3FF46DAF002C3FF46AAF029B0220D3 -:100A7000187001F0DFF8322000F050FFB0F1000AEA -:100A8000C0F25E811AF0030540F05A81DBF80820BD -:100A900006EB0A03934200F25381BAF5807F00F21D -:100AA0004F8155450DDA4FF47A7000F037FF04900E -:100AB000049B002BC0F244813C4A049BAB5401359B -:100AC000EFE7C820FFF74AFE0546002800F038810E -:100AD0001F2E11D8C6F12004544528BF544610AB30 -:100AE00026F0030022463149184401F0C3F822469B -:100AF000FF212E4801F0E8F84FEAAA0A5FFA8AF2CD -:100B00002A49304601F0E8F80446002800F01A812E -:100B100006EB8A0605469AE70220FFF71FFE00282B -:100B20003FF40EAF00F0DCFF00283FF409AF4FF0B8 -:100B3000000A5346DBF8082092451CD2BAF11F0F79 -:100B400012D8109A01320FD02AF0030218A90A44D1 -:100B500052F8202C0B92184604220BA902F030F810 -:100B60000AF1040A0346E5E75046039300F074FFD8 -:100B7000039B0B90EFE718A8042140F84C3D00F0D0 -:100B800039FF64E798270020BC280020A427002014 -:100B900089070008C0280020B8270020066B00083D -:100BA0009C270020A0270020086B0008BC270020FD -:100BB00018A8002340F8343D642100F0E7FE002827 -:100BC0007FF4BEAE0220FFF7C9FD00283FF4B8AEA7 -:100BD0000B9800F071FF18AB43F8480D042118463C -:100BE000CDE718A8002340F8343D642100F0CEFE84 -:100BF00000287FF4A5AE0220FFF7B0FD00283FF4E7 -:100C00009FAE0B9800F066FF18AB43F8440DE5E784 -:100C10000220FFF7A3FD00283FF492AE00F070FF22 -:100C200018AB43F8400DD9E70220FFF797FD0028E5 -:100C30003FF486AE0BA9142000F068FF824618A886 -:100C4000042140F83CAD00F0D5FE51460BA896E7D4 -:100C5000322000F063FEB0F1000AFFF671AE1AF028 -:100C6000030F7FF46DAEDBF808200AEB0803934214 -:100C70003FF666AE0220FFF771FD00283FF460AE3C -:100C80002AF0030AC244D0453FF4E1AE404600F0EA -:100C9000E3FE04210A900AA800F0ACFE08F1040863 -:100CA000F1E74FF47A70FFF759FD00283FF448AEA2 -:100CB00000F016FF00283FF4AFAE109B01330CD0BC -:100CC000082210A9002001F007F800283FF4A4AE84 -:100CD0002022FF2110A800F0F7FFFFF747FD394859 -:100CE00004F076F823E6002D3FF42AAE002C3FF402 -:100CF00027AE18A8002340F8343D642100F046FEDA -:100D0000824600287FF41CAE0220FFF727FD002852 -:100D10003FF416AE0390FFF729FD41F2883004F04E -:100D200057F80B9801F062F801F022F8039B574640 -:100D30001C461D46F0E5054689E64FF00008FFE534 -:100D40002546FDE52C4667E6002000F0E7FD04900F -:100D5000049B002B01DA00F099FC049B002BFFF6AA -:100D6000DEAD012000F058FF049B213B122B3FF623 -:100D7000D3AD01A252F823F0350900085D0900083F -:100D8000CD09000819090008190900081909000807 -:100D9000610A0008510C0008190B0008B10B00088B -:100DA000E30B0008110C000819090008290C0008C1 -:100DB00019090008A30C00084F0A000819090008C7 -:100DC000E70C0008A086010009490B6849F2690098 -:100DD0009AB21B0C00FB0233064A0B60136844F204 -:100DE000506198B21B0C01FB0030106080B270475C -:100DF000042700200027002010B5002110220446FF -:100E000000F062FF034B03CB206061601868A060B4 -:100E100010BD00BF107AFF1FF0B51F4CBBB001F032 -:100E200067FDA368C31AF92B30D906AD2346A0602D -:100E300028220021284602F04DFC04F10E0000F0AB -:100E40003BFF0023C6B2591D5F1CDBB2B3424FEA21 -:100E5000C10107DA0E3323440822284602F03AFC87 -:100E60003B46F0E7012303930823207B02930B4BBF -:100E70000193C1F3CF0130230591009301460495FE -:100E800003A3D3E90023064802F0F4F93BB0F0BD18 -:100E900078F6339F93CACD8DD8490020E5490020CC -:100EA000E038002038B50B4B036041F25403C21800 -:100EB000044612793AB9C5582DB1284601F040FDD3 -:100EC000284605F09FFC04F5825001F039FD2046CC -:100ED00038BD00BF406D000870B50D4614461E4673 -:100EE00002F06EF950B9022E0ED1012C0CD112A3D2 -:100EF000D3E90023C5E90023012070BD052C14D0DF -:100F000003D8012C09D0002070BD282C09D0302C2A -:100F1000F9D10BA3D3E90023ECE70BA3D3E900231A -:100F2000E8E70BA3D3E90023E4E70BA3D3E900230D -:100F3000E0E700BFAFF30080401DA12026812A0B0F -:100F400078F6339F93CACD8D9E6AC421818A46EE7E -:100F500026417272DF25D7B7F017304A39059E5601 -:100F600038B504460D46034620222846002102F0EB -:100F7000B1FB22792346032A28BF032203F8042F5A -:100F800028460222202102F0A5FB62792346072A87 -:100F900028BF072203F8052F28460322222102F04A -:100FA00099FBA2792346072A28BF072203F8062FB8 -:100FB00028460322252102F08DFB284604F1080370 -:100FC0001022282102F086FB382038BD2DE9F04F91 -:100FD000ADF5017D21AE0EAD40F2791280460F468F -:100FE0003046002100F070FE48220021284600F023 -:100FF0006BFE01F07DFC594B4FF47A72B0FBF2F0BE -:10100000186093E80700012385E807002B740DF1B1 -:101010005A0000236B74FFF7EFFE052385F820309C -:101020007A2385F8213006AB18464D4905F05EFD60 -:101030001D2228643146284685F83C20FFF790FFA2 -:1010400012AB044601460822304602F043FB082258 -:10105000A1180DF14903304602F03CFB0DF14A03A3 -:10106000082204F11001304602F034FB13AB2022B9 -:1010700004F11801304602F02DFB14AB402204F1BC -:101080003801304602F026FB16AB082204F1780145 -:10109000304602F01FFB0DF15903082204F18001D4 -:1010A000304602F017FB04F1880A0DF15A0904F5E5 -:1010B000847B4B465146082230460AF1080A02F06A -:1010C00009FBD34509F10109F3D11BAB08225946AD -:1010D000304602F0FFFA04F588744FF0000995F8E5 -:1010E00034304B4510D84FF0000995F83C304B4553 -:1010F00015D92B6C21464B440822304602F0EAFAFF -:10110000083409F10109F0E7AB6B21464B44082292 -:10111000304602F0DFFA083409F10109DFE7E31D88 -:10112000C3F3CF03F97E0593002304960393BB7E9C -:101130000293193701230093019706A3D3E90023F3 -:10114000404602F097F80DF5017DBDE8F08F00BF35 -:10115000AFF300809E6AC421818A46EEC828002031 -:101160003C6C0008014B1870704700BFD428002069 -:10117000F0B5334B1C7B85B034B1324B0E221A8153 -:101180000024204605B0F0BD2F4A1068516802AB1C -:1011900003C308230DEB03022C492D4805F088FBFF -:1011A000054630B9274B2B480A221A8101F04EFB25 -:1011B000E6E70169B1F5F81F06D9224B26480B2254 -:1011C0001A8101F043FBDCE7438B40F27A529342F1 -:1011D00007D01C490C2008811946204801F036FB35 -:1011E000CFE71F4A024402F11003994204D2154B83 -:1011F0001C4810221A81E4E710398E1A204614493F -:1012000001F0DEFC3246074605F11801204601F0E8 -:10121000D7FCAB689F4202D1EB6898420AD0094BD9 -:101220000D221A8100903B46EA68A9680E4801F039 -:101230000DFBA5E70D4801F009FB0124A1E700BF64 -:10124000D8490020C82800200C6B0008DCFF1E00D5 -:1012500000000108146B0008206B0008326B0008C6 -:101260000800FFF7506B00086D6B0008966B0008D4 -:101270002DE9F04FADB006AF80460C4601F0A0FF5F -:10128000054600286AD1237E022B18D1E38A012B60 -:1012900015D101F02DFB8146FFF796FD4FF4C87381 -:1012A000BD4EB0FBF3F209F5167902FB1300E37EA5 -:1012B00019FA80F030608BB9B84B00221A709C3755 -:1012C000BD46BDE8F08F3B1D1D440095002308225C -:1012D0004FEAC901204602F061F84D46A38A013B5E -:1012E000AB425FFA85F90BD905F10109B9F1110F8C -:1012F000E9D1AB4BAB4A40F23911AB4805F08CFA5F -:1013000007F11400FFF778FD2A4607F11401381D94 -:1013100005F0BEFA03460028CED1B9F1100F07D070 -:101320009E4B83F800903368A3F516733360C6E7CD -:1013300007F19802014602F8950D20460092072217 -:1013400002F02CF8F9787F2904DD984B954A4FF488 -:10135000A871D2E7404601F017FFB0E7E38A052BFA -:1013600000F0068106D8012BA9D121464046FFF79F -:101370002DFEA4E7282B3DD0302BA0D1637E8C4DD1 -:1013800001336A7BDBB29342E94640F0EF80E27EB4 -:101390002B7B9A4240F0EA8007F19803002623F85D -:1013A000846D1022009331460123204601F0F6FFA0 -:1013B000B4F81480A8F102081FFA88F808F10303B2 -:1013C00023F003030A3323F00703ADEB030D0DF104 -:1013D000180A33469BB2B11C98454FEAC10106F189 -:1013E00001066CDD5344009308220023204601F0DF -:1013F000D5FFEEE7A38A013B9BB2C92B3FF65FAF57 -:101400006B4E357B4DBB06F10C03009308222B4637 -:101410002946204601F0C2FFA38A05F10109013BDC -:10142000EDB29D424FEAC90109DA0E353544009507 -:1014300000230822204601F0B1FF4D46ECE70023CF -:101440000022C6E900230023B36086F8D730C6F82F -:10145000D830337B0BB9E37E3373002507F11406D4 -:101460003B1D0822294630467D60BD60FD6002F0CC -:1014700031F93B7A05F10109AB424FEAC90107D9BD -:10148000FB6808222B44304602F024F94D46F0E771 -:10149000C1F3CF010023E07E059104960393A37E60 -:1014A00002931934282301460093019438A3D3E909 -:1014B0000023404601F0DEFEFFF7AEFCFFE695F8A4 -:1014C000D70000F0D7FAD5F8D83006461BB995F802 -:1014D000D70000F0DFFAD5F8D83043449E4204D25A -:1014E00095F8D700013000F0D5FA4FEA980B0024A8 -:1014F000A0B2584504F1010408DA2B6880000AEB19 -:1015000000010122184400F0E7FBF1E7D5E90023D0 -:10151000D5F8D84095F8D70012EB080243F1000344 -:101520004444C5E90023C5F8D84000F0A3FA84423A -:1015300009D395F8D730013385F8D730D5F8D830AE -:101540009E1BC5F8D860B8F1FF0F08DC00232B7391 -:1015500000F0C6FAFFF70CFE08B1FFF747F92B6859 -:10156000144A9B0A013313810023AB60CD46A6E6E3 -:10157000BFF34F8F1049114BCA6802F4E062134366 -:10158000CB60BFF34F8F00BFFDE700BFAFF300801C -:1015900026417272DF25D7B7DC380020D938002009 -:1015A000A86B00085C6C0008016C0008236C000844 -:1015B000D8490020C828002000ED00E00400FA050A -:1015C00008B54FF000530B4A196891420AD10A4AF4 -:1015D000597D117009481B7D0373C92208490E30DB -:1015E00000F048FBE02200214FF00050BDE8084029 -:1015F00000F06ABB9AAD44C5D4280020D849002029 -:101600001600002037B5184D184919480223012249 -:101610006B7100F0E9FF00230193164B009316490C -:10162000164B17484FF4805201F078FD154B19788E -:1016300011B1134801F0A8FD01F05AF90446FFF773 -:10164000C3FB4FF4C87304F51674B0FBF3F202FB4E -:1016500013000D4B14FA80F0186003F0BFFF08B1BF -:101660000F232B8103B030BDC828002040420F005B -:1016700008390020D90E0008D8280020711200086F -:10168000E0380020D4280020DC3800202DE9F04F7D -:101690008C4C93B08C4EDFF850820027204601F02E -:1016A00035FE024668B300250E958DF844500F951F -:1016B0001095037B8DF8443001460FAB51F8040FB1 -:1016C000DFF82892496803C3136843F000430E9380 -:1016D00001F010F9821941EB070300950EA940466D -:1016E00000F0C4FBA84205DD204601F013FE89F896 -:1016F0000050D3E799F80030072B46DC013389F816 -:1017000000300BAD0023DFF8E0A1DFF8E4B10A936D -:101710008DF834300B934FF000086B604FF00009E8 -:1017200012AA002602F82B6D33460127CDE9008965 -:1017300007A950468DF81C7000F000FF9DF81C3082 -:101740003BB3DBF8143083F00203CBF8143031469E -:1017500010220EA800F0B8FA0DF11E0308AA0AA97B -:10176000504600F02DFC95E803000FAB83E8030022 -:101770009DF834308DF844300A9B0E930EA9DDE9B4 -:101780000823204602F00CF8CAE7204601F0C2FD0B -:10179000B7E7204601F014FD0546002842D14B4E24 -:1017A00001F0A6F8336898423CD301F0A1F88046D6 -:1017B000FFF70AFB4FF4C87308F51678B0FBF3F295 -:1017C00002FB130018FA80F03060414E8DF828506B -:1017D00096F80080B8F1000F01D18DF82870C8F19B -:1017E0001005EDB20EA8FFF707FB062D28BF062552 -:1017F0000EAB2A4603EB08010DF1290000F03AFA7E -:101800000AAB039318230293324B01930135012352 -:101810000093049527A3D3E90023204601F0D2FCCE -:101820000023337001F064F82B4A2C4D1368C31A5F -:10183000B3F57A7F30D3106001F05CF802460B46B6 -:10184000204601F06DFD204601F0BAFC20B32B7B51 -:10185000234E002B14BF03230223737101F048F8B9 -:101860000EAF4FF47A733946B0FBF3F03060304678 -:10187000FFF776FB1823073002931A4B0193C0F34E -:10188000CF0040F255130490009303970BA3D3E9C4 -:101890000023204601F096FC2B7B0BB1FFF7BCFA2E -:1018A0002B7B002B7FF4F6AE13B0BDE8F08F00BFAA -:1018B000AFF30080401DA12026812A0BF1C6A7C1ED -:1018C000D068080FE038002040420F00DC380020CC -:1018D000D9380020D8380020B84A0020D849002044 -:1018E000C8280020BC4A002008390020BD4A00203A -:1018F0000004024010B5064C0021204600F09AFB7F -:101900002046044A0449BDE8104004F06DBF00BF02 -:1019100008390020084B0020A50E00082DE9F347E8 -:1019200002AE00244FF47A7506F8014D144FDFF82B -:101930005880454397F900305A1C5FFA84F901D06A -:10194000A34212D158F8240003680122D3F820A042 -:1019500031462B46D047012807D10A4B9DF8070096 -:1019600083F8009002B0BDE8F0870134022CE1D189 -:101970004FF4FA7003F02CFA4FF0FF30F2E700BF9B -:1019800008270020004B0020F06C00082DE9F047EC -:101990004FF47A75144FDFF8588006464D43002403 -:1019A00097F900305A1C5FFA84F901D0A34210D194 -:1019B00058F8240003680422D3F820A031462B46AF -:1019C000D047042805D1094B83F800900020BDE8DA -:1019D000F0870134022CE3D14FF4FA7003F0F8F9E8 -:1019E0004FF0FF30BDE8F08708270020004B0020B3 -:1019F000F06C000830B4074B1A78074B53F82240BC -:101A00002368DD69054B0A46AC460146204630BCDA -:101A1000604700BF004B0020F06C0008A08601006A -:101A200070B503F029FC094C094E20700025306880 -:101A30002378834208D903F019FC33680544013345 -:101A4000B5F5803F3360F2D370BD00BF014B00207D -:101A5000C04A002003F0C6BC00F1006000F58030F1 -:101A60000068704700F10060920000F5803003F0DC -:101A700051BC0000054B1A68054B1B789B1A83422A -:101A800002D9104403F0F2BB00207047C04A002086 -:101A9000014B002038B5074D04462868204403F068 -:101AA000EDFB28B928682044BDE8384003F0FEBBB0 -:101AB00038BD00BFC04A002010F0030308D1B0F5C4 -:101AC000007F05D800F10050A0F50840006870477D -:101AD00000207047014BC058704700BF107AFF1FAD -:101AE000064991F8243033B100230822086A81F8AE -:101AF0002430FFF7B7BF0120704700BFC44A002061 -:101B0000014B1868704700BF002004E070B52A4BF5 -:101B10001C68C4F30B03240C63B140F213429342DC -:101B200031D040F2194293422FD040F221429342E9 -:101B30002DD10323214A0C2505FB03235D6893F96E -:101B4000082042F201039C4224D0B4F5805F23D0E8 -:101B500041F201039C4221D041F203039C421FD079 -:101B600041F207039C4208BF3122441E0C44013D50 -:101B70000B46A3421ED215F9016F581C96B10346BD -:101B800000F8016CF5E70123D4E70223D2E73F22F6 -:101B90000B4DD6E73322E3E74122E1E75A22E4E79F -:101BA0005922E2E72C2584421D7001D9981C5A70F5 -:101BB000401A70BD1846FBE7002004E0C06C000826 -:101BC000A06C0008124B5A8842F201018A4293B27B -:101BD00014D0B3F5805F13D041F20102934211D0CB -:101BE00041F2030293420FD041F2070293420DD11A -:101BF0000423084A02EB8303D87870470023F8E7F0 -:101C00000123F6E70223F4E70323F2E700207047FD -:101C1000002004E0AC6C0008022802D1044B98615B -:101C20007047012802BF024B08229A61704700BF2B -:101C300000040240022804D14FF40032034B9A61A1 -:101C400070470128FCD14FF40022F7E7000402405E -:101C5000022805D1064A536983F002035361704795 -:101C60000128FCD1024A536983F00803F6E700BF5C -:101C70000004024010B50023934203D0CC5CC4544E -:101C80000133F9E710BD000030B5441E14F9010F0F -:101C90000B4660B193F90050854201F1010106D174 -:101CA0001AB993F90020801A30BD013AEEE7002AF4 -:101CB000F7D1104630BD000002460346981A13F9CA -:101CC000011B0029FAD1704702440346934202D017 -:101CD00003F8011BFAE770472DE9F047234C94F80D -:101CE000243005468846174683BB2E46DFF87C9095 -:101CF000C7B394F824302BB92022FF21484626622E -:101D0000FFF7E2FF94F82400C0F10805BD4228BFA8 -:101D10003D465FFA85FAAD0041462A4604EB800055 -:101D2000FFF7A8FF94F82430A7EB0A079A445FFA5C -:101D30008AFABAF1080F2E44A844FFB284F824A00E -:101D4000D6D1FFF7CDFE0028D2D108E0266A06EBF7 -:101D50008306B042CAD0FFF7C3FE0028C5D10020D9 -:101D6000BDE8F0870120BDE8F08700BFC44A00202D -:101D7000024B1A78024B1A70704700BF004B0020CC -:101D80000827002038B5134C134D204602F0AAFA5C -:101D90002946204602F0D2FA2D6810486A6D936BEE -:101DA00023F40023936303F013F80D49284602F04F -:101DB000D1FB6A6D0B48936B0B4943F4002393638B -:101DC000A0424FF4E1330B6003D0BDE8384002F08D -:101DD000E7B938BD30520020D871000840420F00EA -:101DE000007200088C4B0020EC4A002038B50B4BE9 -:101DF0001A780B4B53F822400A4B9C4205460CD0F4 -:101E0000094B002118461422FFF75EFF05600146CA -:101E10002046BDE8384002F0C3B938BD004B002071 -:101E2000F06C000830520020EC4A0020202383F39D -:101E3000118862B670470000002383F3118862B6F0 -:101E40007047000001207047002070470020704755 -:101E50000020704770470000002070470E20704738 -:101E600000F586500078C0F340007047F8B51F4673 -:101E70000B68BDF8185013F00054164669D10B7B5F -:101E8000082B66DCFFF7D2FFC26893685B015CD465 -:101E900093681C0157D4936813F0805357D00223E2 -:101EA0000C6803F1180E002CB8BFE4004FEA0E1EB8 -:101EB000B4BF44F00404640542F80E400C680FFA05 -:101EC00083FE14F0804F18BF02EB0E1C02EB0E1EB7 -:101ED0001EBFDCF8804144F00204CCF880410C7B4A -:101EE000CEF8844102EB03128C68C2F88C414C6836 -:101EF000C2F88841DEF8802142F00102CEF880214C -:101F000003F1830200EB4212C2E9006701F10C0405 -:101F1000083251F8046B42F8046BA142F9D100EB8E -:101F200043130978117003F5835301201A7F65F379 -:101F30000002C5F3400565F341026FF3C3021A774F -:101F4000FFF77AFFF8BD0123AAE72346A8E7184662 -:101F5000F6E74FF0FF30F8BD08B5FFF767FF41F235 -:101F60005403C05800F0F6FCBDE80840FFF764BF1A -:101F700038B5044600680D4600F016FD1F2809D943 -:101F800020222946206800F087FDA0F12003584256 -:101F9000584138BD002038BD002202600273426003 -:101FA0008260704710B500220023C0E9002300239F -:101FB000044603810C30FFF7EFFF204610BD000000 -:101FC0002DE9F041064688B041F254050C46904692 -:101FD0001F46FFF72BFF6846FFF7E4FF705900F03C -:101FE000CBFC1F2805D80020FFF726FF08B0BDE86E -:101FF000F08120226946705900F0D6FD2028F2D1E8 -:1020000003AA234605AD144603CCAC4218605960C0 -:10201000224603F10803F6D12068186022791A716C -:10202000DDE90023C8E90023BDF808303B8001202A -:10203000DAE70000264B2DE9F047044640F8103B54 -:102040008946FFF7A9FF04F12000FFF7ABFF04F179 -:102050004006354604F5825728462035FFF7A2FF93 -:10206000BD42F9D14FF4805341F248026B60002326 -:102070002E60A35041F24C0241F25401A35060186B -:1020800001222A7404F5865A655004F583550271BD -:1020900008350AF1080A00260027984645E9026734 -:1020A0002846FFF779FF203545F8108C5545F5D1C6 -:1020B00041F2C80304F80390B9F1000F02D00548BB -:1020C00000F00EFC044BE3602046BDE8F08700BF43 -:1020D000406D0008246D0008006400402DE9F041C7 -:1020E00079B1274B274FB7FBF1F4994294BF1023E6 -:1020F0000923581CB4FBF0FE00FB1E4038B1022B34 -:1021000002DC0020BDE8F081013BDBB2F1E70EF11B -:10211000FF36B6F5806FF4D2C3EBC30C0CF10300AD -:10212000C010C5B25C1B0130E4B24FF47A7808FBF2 -:1021300000F8204498FBF0F080B2B0F5617F08D938 -:102140000CF1FF354FF0080C95FBFCF5EDB25B1B75 -:10215000DCB22B1903FB0EEEB7FBFEFE7145D0D1AE -:10216000691EC9B20F29CCD8631EDBB2072BC8D8B1 -:10217000002090701680D17013710120BDE8F081AD -:102180003F420F0080DE800270B505460E464FF4D8 -:102190007A74EB685B6803F00103B34207D04FF435 -:1021A0007A7002F015FE013CF3D1204670BD01208B -:1021B00070BD0000F0B5032989B005460C4647DC28 -:1021C00000F5865066010378C3F38001002908BF3B -:1021D000114661F382030370AB1903F5835318337F -:1021E0001B79D80732D5002A32D0190723D4684684 -:1021F000FFF7D8FE05EB441303F5835303F11007F3 -:1022000003AA083318685968144603C40833BB424C -:102210002246F7D1186820601B792371DDE90E236F -:1022200005F58250CDE90023694601231430ADF84D -:102230000830FFF79DFE354405F5835518352B7999 -:102240001A075CBF43F008032B7101E0002AF2D1AA -:1022500009B0F0BD70B5C268936913F0700F17D064 -:1022600000230C4D936141F2780400EB43122244A9 -:1022700011794E0709D5890707D5C16855F823603C -:102280008E60117941F0040111710133032BECD1FF -:1022900070BD00BF186D0008D3B51F46C368164651 -:1022A0009A68D207044609D59A6801219960C2F359 -:1022B0004002CDE900670021FFF77CFFE3689A68E0 -:1022C000D1050BD59A684FF480719960C2F3402212 -:1022D000CDE9006701212046FFF76CFFE3689A68AB -:1022E000D2030BD59A684FF480319960C2F3404213 -:1022F000CDE9006702212046FFF75CFF204602B0CF -:10230000BDE8D040FFF7A6BFF8B51F460446164605 -:10231000C368002966D1D86803F10C02800765D034 -:10232000106803EB011003EB0111D0F8B05115F068 -:10233000040FD0F8B05116BFED086D0D45F0004503 -:102340002561D0F8B051AD0742BF256945F0804501 -:102350002561D0F8B40100F00F002077D1F8B83132 -:102360002375D1F8B8311B0A6375D1F8B8311B0C4D -:10237000A375D1F8B8311B0EE375D1F8BC312376C3 -:10238000D1F8BC311B0A6376D1F8BC311B0CA376A3 -:10239000D1F8BC311B0EE3763823136004F11C0125 -:1023A00004F1100304F12C0253F8040B42F8040B5F -:1023B0008B42F9D11B78137004F5825000232385DA -:1023C000C4E9086704F120011430FFF7D1FD04F5DA -:1023D00086522046137843F004031370BDE8F8409A -:1023E000FFF738BF03F11002186997E7F8BD000046 -:1023F00010B5044600F07EFA02460B4652EA03018D -:1024000003D012F1FF3243F1FF330449086820B1D1 -:102410002146BDE81040FFF777BF10BD044B0020F8 -:102420002DE9F84F99469046FFF700FD124C00F554 -:102430008356002341F2780700EB431139440A79AF -:1024400055070FD4D2060DD5D6E900ABCB4508BF52 -:10245000C24507D2C26854F8235095600A7942F009 -:1024600004020A710133032B06F12006E4D1BDE812 -:10247000F84FFFF7E1BC00BF186D000808B5FFF783 -:10248000D5FCFFF7E7FEBDE80840FFF7D5BC00002C -:102490002DE9F041C3680646986800F0E050B0F1BD -:1024A000E05F0F4619D010B3FFF7C0FC06F5835468 -:1024B0000834002541F2780806EB451343441B79A4 -:1024C0001A070DD45B070BD42146384600F014FAE6 -:1024D00030B9FFF7B1FCBDE8F0810120BDE8F08123 -:1024E0000135032D04F12004E6D10120F1E7BDE818 -:1024F000F081000008B5FFF799FC41F25403C05881 -:1025000000F03AFAFFF798FC1F288CBF002001204A -:1025100008BD0000F8B51D46002313700F4606469F -:102520001446FFF7E7FF80F00100387025B1294617 -:102530003046FFF7ADFF2070F8BD0000F8B50D463E -:1025400016461F46044600F0D1F92B7802460BB917 -:10255000307868B100232046FFF762FF2046FFF77E -:102560008DFF20463B4632462946FFF7D3FF012028 -:10257000F8BD000010B5FFF759FC41F2C803C35C79 -:1025800063B9184B1A6C42F000721A641A6A42F06E -:1025900000721A621A6A22F000721A62FFF74CFC8B -:1025A00000F586542378DB071AD4C9B1FFF73EFC47 -:1025B00041F2C803C35C5BB90221132001F026FC81 -:1025C0000221142001F022FC0221152001F01EFC42 -:1025D000237843F001032370BDE81040FFF72CBCC3 -:1025E00010BD00BF003802402DE9F04341F2C8039E -:1025F00089B0C35C012B04468846174600F3FA8075 -:102600007D4D55F823200AB945F823002E68C4F8FB -:10261000048027724EB941F2D00004F0D3F831465D -:102620008146FFF707FDC5F8009041F2C803E35C5F -:10263000012B60D001212046FFF79CFFFFF7F6FB3E -:10264000E268136823F002031360E268136843F042 -:1026500001031360E36800255D61FFF7EDFB0121D5 -:102660002046FFF791FD002800F0868041F25403D8 -:102670002E46E05800F06EF9202200216846FFF750 -:1026800023FB02A8FFF788FC0DF1200C05F583530E -:102690004CF8086D6A4623449646BEE80300E645BA -:1026A00018605960724603F10803F5D1DEF80000A6 -:1026B000186020359EF804201A71602DDCD104F5D5 -:1026C000865600253378ADF800506FF382033370DF -:1026D0006A46414620468DF802508DF803508DF829 -:1026E0000450FFF7FBFCE368C0B94FF400421A60E6 -:1026F00009B0BDE8F083286803681B6B9847014662 -:10270000002897D12868FFF735FF286803683A4604 -:102710001B684146984700288CD1E9E761221A607E -:102720009DF802309DF80310E2681B06090401F4CD -:10273000702103F040730B43BDF80010C1F3090191 -:102740000B439DF80410090501F4E001022F43EA50 -:1027500001030CBF4FF0004100210B43D361E3683C -:1027600013225A61E268136823F0010313602946BB -:102770002046FFF709FD08B9E368B6E741F2C80350 -:10278000E15C91BBE268D2F8003243F00103C2F889 -:102790000032E268D2F8003223F47C5323F00E03B7 -:1027A000C2F80032E268D2F8003243F46063C2F843 -:1027B0000032E368C3F81412E368C3F80412E36854 -:1027C00041F6FF72C3F80C22E368C3F84012E368D5 -:1027D000C3F84412E3680122C3F81C22E268D2F86D -:1027E000003223F00103C2F80032337843F00203D1 -:1027F00033707DE700207BE7044B002008B500F034 -:1028000079F802460B4652EA030103D012F1FF3277 -:1028100043F1FF330449086808B1FFF73DFDBDE807 -:10282000084001F0AFB900BF044B002008B50020FC -:10283000FFF7DEFDBDE8084001F0A4B908B50120AE -:10284000FFF7D6FDBDE8084001F09CB90FB40020A9 -:1028500004B070470FB44FF0FF3004B07047000071 -:10286000FEE7000000B59BB0EFF3098168226846DF -:10287000FFF700FAEFF30583034B9A6B9A6A9A6AA3 -:102880009A6A9A6A9B6AFEE700ED00E000B59BB089 -:10289000EFF3098168226846FFF7ECF9EFF305834F -:1028A000044B9A6B9A6A9A6A9A6A9A6A9A6A9B6ABB -:1028B000FEE700BF00ED00E000B59BB0EFF309813B -:1028C00068226846FFF7D6F9EFF30583034B5A6B8E -:1028D0009A6A9A6A9A6A9A6A9B6AFEE700ED00E031 -:1028E0000FB408B5029802F0BFF9FEE702F0C2BDCE -:1028F00002F0DCBD02F09ABD10B509680468C80F8B -:10290000B0EBD47F24F0604221F060430BD0002C68 -:10291000B8BF920C0029B8BF9B0C9A420FD034BFAD -:102920000120002010BD9A4205D1C1F38070C4F38C -:102930008074844203D19A422CBF0020012010BD34 -:1029400010B5037C044613B9006803F099FF2046D4 -:1029500010BD00000023BFF35B8FC360BFF35B8F2C -:10296000BFF35B8F8360BFF35B8F7047BFF35B8FF9 -:102970000068BFF35B8F704770B506460C30FFF7F9 -:10298000F5FF06F1080504462846FFF7EFFF8442ED -:1029900006D228467668FFF7E9FF3444201A70BD56 -:1029A0002846FFF7E3FFF9E770B50546406898B1A0 -:1029B00005F10800FFF7DAFF05F10C060446304682 -:1029C000FFF7D4FF8442304694BF6D680025FFF7BF -:1029D000CDFF013C2C44201A70BD000038B50C46D8 -:1029E0000546FFF7C9FFA04210D305F10800FFF725 -:1029F000BDFF6B68BFF35B8F2044B0FBF3F403FBB8 -:102A00001400A860BFF35B8F012038BD002038BDE3 -:102A10002DE9F041144680460D46FFF7C5FF84427C -:102A200028BF0446DCB1474657F80C6B3846FFF721 -:102A30009DFF304428603846D8F80460FFF796FFC1 -:102A4000301AA0423BBF6860D8F800306C60241A8E -:102A50003BBFAB60EC6001200220BDE8F081204666 -:102A6000BDE8F08138B50C460546FFF79DFFA04252 -:102A700010D305F10C00FFF779FF6B68BFF35B8F94 -:102A80002044B0FBF3F403FB1400E860BFF35B8F5A -:102A9000012038BD002038BD2DE9F04385B08846BF -:102AA00069460746FFF7B4FF0026814601AD34466C -:102AB0004E4505F108050CDA08EB040155F8082C21 -:102AC00055F80C0CFFF7D6F855F8083C01361C44B5 -:102AD000EEE721463846FFF7C5FF204605B0BDE8C2 -:102AE000F0830000F8B506460C300F46FFF73EFFB6 -:102AF00006F1080504462846FFF738FF84422846B9 -:102B000038BF7468FFF732FF201A386020B12846BA -:102B10003468FFF72BFF2044F8BD000073B514465E -:102B200006460D46FFF728FF844228BF0446019061 -:102B3000DCB101A93046FFF7D5FF019B33B93268FC -:102B4000AB6085E81400EB6001200CE0A34288BF75 -:102B50000194286001986860A042F5D23368AB60A8 -:102B6000241AEC60022002B070BD2046FBE7000092 -:102B70002DE9FF410F466946FFF7D0FF002480464C -:102B8000254644450BDA0DEBC4035DF834105E684E -:102B900078193246FFF76EF835440134F1E72846DC -:102BA00004B0BDE8F081000038B50546FFF7E0FF4E -:102BB000044601462846FFF711FF204638BD0000B5 -:102BC00030B5084D0A4491420BD011F8013B09245D -:102BD0005840013CF7D040F300032B4083EA5000FB -:102BE000F7E730BD2083B8ED0246006848B10368BE -:102BF0001360D388118901339BB29942D38038BFC7 -:102C00001381704770B588B00D460446202200211C -:102C10006846FFF759F820460495FFF7E5FF05469B -:102C200058B16B46044608AE1A4603CAB242206049 -:102C30006160134604F10804F6D1284608B070BD5F -:102C40002DE9F04130B9274B274A40F2C5312748DA -:102C500003F0E2FD0B7C23B9254B234A40F2C63139 -:102C6000F5E7C66986B9C161BDE8F081002B29DAB4 -:102C7000930CAB4229D1B44201D10C60F3E7C8F800 -:102C800000100C60BDE8F0814B6823F06047BD0C7C -:102C90004FEAD37EC3F3807C15EA230538BF3D4657 -:102CA000B04634466368BEEBD37F23F06042DDD18B -:102CB000974203D1C3F380739C450AD1974205E044 -:102CC0001C46EFE7AA4206D013469D422CBF0023C4 -:102CD0000123002BCFD12368A046002BF0D1216027 -:102CE000BDE8F08104700008F86D0008BC700008B1 -:102CF000DD70000808B5034A034B044840F25E311A -:102D000003F08AFDD46D00087C700008BC700008D8 -:102D100008B503680B60C388016033B9044B054AEA -:102D200005484FF4C76103F077FD013BC38008BD40 -:102D30004C700008486E0008BC70000870B50C4666 -:102D400000F10C05616831B9E38A61F30903E3829C -:102D50000020002170BD0E682846FFF7D9FF66608D -:102D6000F0E7000008B5426832B10B4B0B4A0C4843 -:102D700040F22F4103F050FDC37DC3F384010131C4 -:102D800061F38603C375C38A62F30903C3821B0A16 -:102D900062F3C713C37508BD98700008046E00087D -:102DA000BC7000082DE9F047089E32B91F4B204A3D -:102DB000204840F2395103F02FFD01F007054FEA9A -:102DC000D6082A4406F0070600EBD1004FF47F49ED -:102DD000954201D1BDE8F08705F0070E06F0070A1D -:102DE000D645774638BF5746C7F10807511BEC0850 -:102DF0008F4228BF0F46045D08EBD60104FA0EF49B -:102E000013F801C029FA07FE24FA0AF45FFA8EFECD -:102E10008CEA04044EFA0AFE04EA0E048CEA040C5E -:102E200003F801C03D443E44D2E700BF18700008DB -:102E30001C6E0008BC7000082DE9F04106460F46E4 -:102E400000254FF6FF7441F221082A4630463946E4 -:102E5000FDF7CAF9C0B284EA0024082314F4004F35 -:102E60004FEA4404A4B203F1FF3318BF84EA080414 -:102E700013F0FF03F2D10835402DE6D12046BDE81E -:102E8000F081000010B50A4441F22104914200D1C2 -:102E900010BD11F8013B80EA0320082310F4004F15 -:102EA0004FEA400080B203F1FF3318BF604013F0D7 -:102EB000FF03F3D1EAE700002DE9F04F85B08A4621 -:102EC0008DE80C00BDF83C40814630B9494B4A4A78 -:102ED00040F26E31494803F09FFC11F0604F04D07E -:102EE000474B454A40F26F31F4E7009B002B7ED000 -:102EF00024B10E9B002B7AD0072C28D809F10C00A6 -:102F0000FFF772FE054628B96FF00205284605B0A6 -:102F1000BDE8F08F14220021FEF7D6FE22460E995E -:102F200005F10800FEF7A6FE631C2B74009B1B78BE -:102F30002C4403F01F0363F03F0323724AF0004365 -:102F40006B6029464846FFF77BFE0125DEE7019BC3 -:102F50001B0A4FF00008029300F10C034FF0800BA6 -:102F60004646454603930398FFF73EFE0746002872 -:102F7000CAD014220021FEF7A7FEB6BB9DF804308C -:102F80003B729DF808307B7202220E9B711E194421 -:102F9000B4420AD9B8180132D2B211F801EF80F860 -:102FA00008E00136072AB6B2F2D1009B197801F089 -:102FB0001F01B44208BF4FF0400BB81841EA481156 -:102FC0004BEA0103037201324AF000437B603A741A -:102FD00039464846FFF734FE0135B4422DB288F039 -:102FE00001084FF0000BBED190E70022CDE76FF053 -:102FF00001058BE704700008E86D0008BC7000084C -:10300000287000082DE9F0471E46CB8A9146C3F38D -:103010000902062A80460F4619D013460021B0B295 -:103020008DB25A1992B2052A09D9A84210D8FA8A43 -:10303000034463F30902FA820120BDE8F087A84245 -:10304000F3D93A4419F8014094760131E8E70025B4 -:10305000FB8A7C68C3F30900821F1C23B2FBF3FACE -:1030600003FB1A2A1FFA8AF27CB301212368002B82 -:1030700039D1B31F03441C20B3FBF0F301339BB2DF -:1030800099420CD2BAF1000F09D14046FFF7ACFDCE -:1030900008B1C0F800A0206008B304460022B6B210 -:1030A0004FF0000AB54230D2691E49441346E01879 -:1030B00001339BB211F801EF80F804E001351C2BBD -:1030C000ADB214D0AE42F2D8ECE74046FFF78CFD2B -:1030D000044608B1002303607C60002CDED16FF051 -:1030E0000200BDE8F087013189B21C46BEE7AE425E -:1030F000D8D94046FFF778FD08B1C0F800A020609D -:103100000028ECD004460022CCE7FB8AC3F3090276 -:10311000164466F30903FB828EE70000F8B50E46FD -:1031200015461F46044628B9144B154A15484F2129 -:1031300003F072FB24220021FEF7C6FD069B6360AC -:10314000079B23626A094FF6FF739A424FF0000013 -:1031500028BF1A46A7602070A061E06197B204F111 -:103160000C05824205D100232B6027826382A38253 -:10317000F8BD2E60013035462036F2E700700008B9 -:10318000746D0008BC70000808B528B9084B094ADE -:103190007321094803F040FB037823B94BB2002B9D -:1031A00001DD017008BD054B024A7D21F1E700BF3A -:1031B00004700008806D0008BC700008486F0008AB -:1031C000007870472DE9F7430D9EBDF828900B9DC0 -:1031D0009DF83040BDF8388007461946104616B9AC -:1031E000B8F1000F43D11F2C41D83B78D3B9B8F1C7 -:1031F000070F39D839F0030339D1424631464FF62B -:10320000FF70FFF73FFE4FEA092920F0010009F4A3 -:103210004079400449EA0464400C44EA40244FF6F3 -:10322000FF730DE043EA0923B8F1070F43EA046492 -:10323000F5D9FFF701FE42463146FFF723FE03466C -:103240008DE840012A4621463846FFF735FE0DB984 -:10325000FFF750FD2B780133DBB21F2B88BF002313 -:103260002B7003B0BDE8F0836FF00300F9E76FF057 -:103270000100F6E72DE9F7430E9F0B9D9DF8348082 -:10328000BDF83C6081469DF8300007B9C6BB1F28D9 -:1032900036D899F800E0BEF1000F34D00C0244F0AB -:1032A00080049DF8281044EAC83444EA014444EA02 -:1032B0000E04072E44EA006415D919461046FFF79C -:1032C000BBFD32463946FFF7DDFD03460196009708 -:1032D0002A4621464846FFF7EFFDB8F1010F0CD111 -:1032E00025B9FFF707FD4FF6FF73EFE72B780133A2 -:1032F000DBB21F2B88BF00232B7003B0BDE8F08327 -:103300006FF00100F9E76FF00300F6E7C06900B164 -:1033100004307047C1690B68C3610C30FFF7F8BC1B -:103320002DE9F84FD0F818A0DFF86C800546164656 -:103330001F4654464FF0000900F10C0B0CB9BDE8D4 -:10334000F88FD4E90223B21A67EB0303994508BF4B -:1033500090451FD2AB699C42214628460DD1FFF70C -:10336000EDFCAB691B68AB6121465846FFF7D0FC0A -:10337000AC692346A2461C46E0E7FFF7DFFC236862 -:10338000CAF8003021465846FFF7C2FC5446DAF826 -:103390000030EFE72368EDE780841E002DE9F04F51 -:1033A0008BB00D4614460793DDF8509082460028F6 -:1033B00000F06481B9F1000F00F06081531E3F2BD3 -:1033C00000F25C81012A03D1079B002B40F056815B -:1033D000BAF81460F6000023B5420893099380F010 -:1033E00053812B199E420AD2761B16F0FF0607D195 -:1033F000AB4BAC4A40F26751AB4803F00DFA26469E -:10340000DAF80C3023B9DAF81030002B00F0A58080 -:103410002F2D31D8C5F1300846454FF000032CBFA1 -:103420005FFA88F8B0460093294608AB4246DAF8BE -:103430000800FFF7B7FCA6EB08074544FFB2BAF84F -:10344000143003F10053063BDB000293DAF80C3032 -:1034500005934FF0300B059B002B51D087B9DAF85C -:103460001000002861D0002F5FD0AB4550D98F4BA2 -:103470008C4A40F2A651BFE737464FF00008DEE71E -:10348000029B23B98A4B874A4FF4B161B4E7029B90 -:10349000E02B28BFE02306935B44AB4204931DD985 -:1034A0005B1B9F4226BFDBB203930397AB4504D956 -:1034B0007E4B7C4A40F291519EE70598CDF8008002 -:1034C00008ABA5EB0B01039A0430FFF76BFC039BE1 -:1034D0009844FF1A1D445FFA88F8FFB2049B9B458D -:1034E00004D3744B6F4A40F29B5185E7029B069AC6 -:1034F000DDF810B09B1A0293059B1B680593AAE7A1 -:10350000029BBB42ABD26C4B664A40F2A15173E7BF -:10351000CDF800803A46A5EB0B0108ABFFF742FC63 -:10352000B8443D445FFA88F80027BAF81430B5EB88 -:10353000C30F04D9614B5B4A40F2B1515CE7B8F16B -:10354000400F04D95E4B574A40F2B25154E767B17D -:103550005C4B544A40F2B3514EE70093324608ABFD -:103560002946DAF80800FFF71DFC731E3F2B35B221 -:1035700001D8A64204DD544B544A40F235213BE7C2 -:1035800060070AD00AAB03EBD401624211F8083C91 -:1035900002F00702134101F8083C082C21D9102C35 -:1035A00021D9202C8CBF08230423079A002A6DD030 -:1035B000B4EBC30F6CD0082C04F1FF3215D89DF882 -:1035C000203023FA02F2D10706D54FF0FF3202FA7B -:1035D00004F423438DF820309DF8203089F8003022 -:1035E0004EE00123E1E70223DFE7102C11D8BDF8FC -:1035F000203023FA02F2D20706D54FF0FF3202FA4A -:1036000004F42343ADF82030BDF82030A9F8003091 -:1036100036E0202C0ED8089921FA02F2D30705D5FE -:103620004FF0FF3303FA04F40C430894089BC9F8E5 -:10363000003025E0402C1CD0DDE9086730463946D3 -:10364000FCF7D2FD002100F0010050EA01030BD08D -:10365000224601200021FCF7D3FD404261EB4101ED -:1036600006430F43CDE90867DDE90823C9E90023D4 -:1036700006E0174B154A4FF42071BDE66FF00105C7 -:1036800028460BB0BDE8F08F1D46F9E7012CA3D00A -:10369000082CA1D9102CB7D9202CE5D8C6E700BF3B -:1036A000546E00082C6E0008BC700008766E00088E -:1036B000636E00089B6E0008C36E0008EA6E000887 -:1036C000186F0008306F00084A6F0008AC6D0008E2 -:1036D000486F000830B585B030B9244B244A40F219 -:1036E000B121244803F098F823B9234B204A40F233 -:1036F000B221F6E7402A04D9204B1D4A40F2B621F8 -:10370000EFE722B91D4B1A4A4FF42F71E9E7002465 -:10371000012A0294039417D11B788DF808305307BF -:103720000AD004AB03EBD203554213F8084C05F062 -:103730000705AC4003F8084C00910346002102A89D -:10374000FFF730FB05B030BD082AE5D9102A03D8B1 -:103750001B88ADF80830E2E7202A02D81B680293E4 -:10376000DDE7D3E90045CDE90245D8E7846F0008DD -:10377000C06D0008BC7000089F6F0008486F00080B -:1037800070B50C4600F10C05E16819B9A160216122 -:10379000A18270BD0E682846FFF7BAFAE660F3E72B -:1037A0002DE9F04FD1F8009091B0C9F3C01604464E -:1037B0000D46CDE90223002E50D0C9F3C03BC9F31A -:1037C0000626B9F1000F80F29F8119F0C04F40F03A -:1037D0009B812B7B002B00F09781BBF1020F03D064 -:1037E0002278B24240F0938109F07F02BBF1020FD0 -:1037F000059236D119F07F0FC9F30F2A01D10AF0D3 -:10380000030A2B447606059A93F8038046EA0B4692 -:1038100046EA82465FEAD81346EA0A06069300F0B3 -:103820009A800022002310A961E90823059B0093D8 -:1038300067685B4652462046B847002800F08880FB -:10384000A7698FB9314604F10C00FFF7DBF9074691 -:10385000D0B96FF0020011B0BDE8F08F4FF0020B4D -:10386000AFE7C9F3074ACCE73B699E420DD03F68FA -:10387000002FF9D1314604F10C00FFF7C3F90746D8 -:103880000028E6D0A3693B60A761DDE90801FFF7E6 -:10389000D3FAB882F97D08F01F06C1F38401711ACA -:1038A00089B20FFA81FED7E90223BEF1000FB8BF3B -:1038B00001F1200EC9F30461B8BF0FFA8EFE079123 -:1038C00052EA030100F02F81DDE90201801A61EB69 -:1038D000030102460B469F480021994208BF9042CF -:1038E000C0F02181069B002B3FD0BEF1010F00F3F9 -:1038F0001A8118F0400F38D0DDE90223C7E902230E -:10390000202200210DEB0200FEF7DEF9DDE90223A3 -:10391000CDE908232B1D0A932B7BADF836A0013B84 -:10392000DBB2ADF834309DF81C308DF83A309DF89C -:1039300014308DF83B3020468DF838B08DF8396062 -:10394000A36808A998473846FFF70CFA002082E7D9 -:103950006FF00B007FE7A76917B96FF00C007AE7EB -:103960003B699E4296D03F68F6E7FB7DC8F3401264 -:10397000B2EBD31F40F0CE80C3F38403B34240F0D8 -:10398000CC8006992B7B4FEA981279B3D2073CD4AE -:10399000032B40F2C580DDE90223C7E902232B7B1C -:1039A000AE1D033BDBB23246394604F10C00FFF793 -:1039B00029FB002808DA39462046FFF7BFF93846C8 -:1039C000FFF7D0F9032046E7AB883B832A7B033A15 -:1039D000D2B2B88A3146FFF755FAFB7DB882DA4396 -:1039E000C2F3C01262F3C713FB75AFE76AB92E1DAD -:1039F000013BDBB23246394604F10C00FFF702FB13 -:103A00000028D8DB2A7B013AE2E7FA8AC2F30902EE -:103A1000013B052AD9B250D8281D002399420AD962 -:103A200007EB020E013210F801CB8EF81AC00133F9 -:103A3000062ADBB2F2D1DDE902898B4207F11A02D4 -:103A4000CDE908890A9238BF04337A680B9234BFF3 -:103A50005B1900230C93FB8AADF836A0C3F309036E -:103A600019449DF81C308DF83A309DF814308DF8CB -:103A70003B300023ADF834108DF838B08DF8396044 -:103A80007B602A7BB88A013A291DFFF7FBF93B8B43 -:103A9000B882834203D1A36808A92046984708A9A1 -:103AA0002046FFF76DFE3846FFF75CF9B88A3B8B7E -:103AB000984214BF11200020CDE6786810B34FF073 -:103AC000060E03689BB9A2EB0E021B2A13D8033221 -:103AD000024405F1040E1F309942ACD91EF801CB07 -:103AE00002F801CF01339042DBB2F5D1A3E70EF12A -:103AF0001C0E1846E5E7184B184A194840F2B31156 -:103B000002F08AFE034696E76FF00900A3E66FF025 -:103B10000A00A0E66FF00D009DE66FF00E009AE639 -:103B20006FF00F0097E6FB7D68F386036FF3C71312 -:103B3000FB7539462046FFF701F9069B002B7FF401 -:103B4000D8AEFB7DC3F38402013262F38603FB75BA -:103B500003E700BF80841E00B46F0008986D000862 -:103B6000BC700008064A536823F001035360EFF36A -:103B70000983683383F30988002383F3118870472E -:103B800030EF00E010B5202383F31188104B5B6801 -:103B900013F4006318D0F1EE103AEFF309844FF0FC -:103BA000807344F84C3C0B4BDB6844F8083CA4F1B0 -:103BB000680383F3098800F0EDFF18B1064B44F861 -:103BC000503C10BD054BFAE783F3118810BD00BFD0 -:103BD00000ED00E030EF00E0790600087C06000808 -:103BE000002304491A465A50C8180833802B4260F3 -:103BF000F9D170470C4B0020024AD36843F0C00350 -:103C0000D360704700440040044B5A6810439A68E0 -:103C100058600AB1181D1047704700BF8C4B002038 -:103C20002DE9F0413D4ED6F85C54EF682B68DA057B -:103C30009CB20CD5202383F311884FF40070FFF75A -:103C4000E3FF6FF480732B60002383F3118820233C -:103C500083F31188DFF8C48014F02F0331D183F38C -:103C60001188380613D5210611D5202383F3118836 -:103C70002B4800F0F3F9002844DA0820FFF7C4FFCE -:103C80004FF67F733B40EB60002383F311887A0685 -:103C90000DD563060BD5202383F31188F26C336DA9 -:103CA0009A4201D1336C7BBB002383F31188D6F891 -:103CB0006424D3680BB110699847BDE8F041FFF761 -:103CC00061BF230712D014F0080F0CBF0020802022 -:103CD000E10748BF40F02000A20748BF40F0400085 -:103CE000630748BF40F48070FFF78EFFA4066B683F -:103CF00005D596F860144046194000F05FFA2C682C -:103D0000A4B2A9E76860BFE727F040073F0410208E -:103D10003F0CFFF779FFEF60C6E700BF8C4B002038 -:103D2000C44B002010B5054C054A0021204600F088 -:103D300015FA044BC4F85C3410BD00BF8C4B002056 -:103D4000F93B00080044004038B5294C037C0029A9 -:103D500018BF0C46012B0546C0F8644410D1254B12 -:103D600098420DD1244B1A6C42F400321A641A6E38 -:103D700042F400321A660B2126201B6E00F046F832 -:103D80001E4BD5F85C249A42236802D01C498A4213 -:103D90002BD11C4901EB5301B1FBF3F3A1880804BB -:103DA00042BF23F0070003F0070343EA4003936098 -:103DB000E38843F040039BB21361238943F001037E -:103DC0009BB2536141F4045343F02C03D36001F4DC -:103DD000A05100231360B1F5806F136853680CBFC6 -:103DE0007F23FF2385F8603438BD0749D2E700BF41 -:103DF000F87000088C4B0020003802400010014091 -:103E00000014014000BD010580DE800200F1604326 -:103E100000F01F02400903F5614309018000C9B2A7 -:103E200000F1604083F8001300F5614001239340E6 -:103E3000C0F8803103607047F8B51546826806699E -:103E4000AA420B46816938BF8568761AB542044696 -:103E500007D218462A46FDF70DFFA3692B44A3613C -:103E60000DE011D932461846FDF704FFAF1B3A4664 -:103E7000E1683044FDF7FEFEE2683A44A261A368BF -:103E80005B1BA3602846F8BD18462A46FDF7F2FEE4 -:103E9000E368E4E783682DE9F04104469342154660 -:103EA000266938BF85684069361AB5420F4606D282 -:103EB0002A46FDF7DFFE63692B4463610DE012D9EA -:103EC0003246A5EB0608FDF7D5FE4246B919E06873 -:103ED000FDF7D0FEE26842446261A3685B1BA36009 -:103EE0002846BDE8F0812A46FDF7C4FEE368E4E712 -:103EF00010B50A440024C361029B006040608460E6 -:103F0000C160816141610261036210BD08B58269CF -:103F10004369934201D1826882B98268013282602A -:103F20005A1C42611970426903699A4201D3C368FD -:103F30004361002100F068FF002008BD4FF0FF3012 -:103F400008BD000070B5202304460E4683F3118897 -:103F5000A568A5B1A368A269013BA360531CA36136 -:103F600015782269934224BFE368A361E3690BB12A -:103F700020469847002383F31188284670BD3146B8 -:103F8000204600F031FF0028E2DA85F3118870BD89 -:103F90002DE9F74F05460F4690469A46D0F81C90FB -:103FA000202686F311884FF0000B144664B1224698 -:103FB00039462846FFF740FF034668B95146284670 -:103FC00000F012FF0028F1D0002383F31188A8EB42 -:103FD000040003B0BDE8F08FB9F1000F03D00190E9 -:103FE0002846C847019B8BF31188E41A1F4486F3C7 -:103FF0001188DBE7C16081614161C3611144009BAD -:10400000006040608260016103627047F8B5044659 -:104010000E461746202383F31188A568A5B1A3682F -:10402000013BA36063695A1C62611E702369626967 -:104030009A4224BFE3686361E3690BB12046984765 -:10404000002080F31188F8BD3946204600F0CCFEF0 -:104050000028E2DA85F31188F8BD0000836942691F -:104060009A4210B501D182687AB9826801328260C1 -:104070005A1C82611C7803699A4201D3C368836128 -:10408000002100F0C1FE204610BD4FF0FF3010BDF2 -:104090002DE9F74F05460F4690469A46D0F81C90FA -:1040A000202686F311884FF0000B144664B1224697 -:1040B00039462846FFF7EEFE034668B951462846C2 -:1040C00000F092FE0028F1D0002383F31188A8EBC2 -:1040D000040003B0BDE8F08FB9F1000F03D00190E8 -:1040E0002846C847019B8BF31188E41A1F4486F3C6 -:1040F0001188DBE7026843681143016003B1184788 -:10410000704700001430FFF743BF00004FF0FF334B -:104110001430FFF73DBF00003830FFF7B9BF000093 -:104120004FF0FF333830FFF7B3BF00001430FFF714 -:1041300009BF00004FF0FF311430FFF703BF00004C -:104140003830FFF763BF00004FF0FF323830FFF721 -:104150005DBF000000207047FFF7E4BD37B50F4B8F -:104160000360002343608360C3600123044603743B -:10417000154600900B464FF4007200F15C011430BC -:10418000FFF7B6FE00942B464FF4007204F517714A -:1041900004F13800FFF72EFF03B030BD0C710008AA -:1041A00010B52023044683F31188FFF7CDFD0223C9 -:1041B0002374002383F3118810BD000038B5C36950 -:1041C00004460D461BB904210844FFF793FF294616 -:1041D00004F11400FFF79AFE002806DA201D4FF4C0 -:1041E0008061BDE83840FFF785BF38BD026843688D -:1041F0001143016003B118477047000013B5446BC9 -:10420000D4F894341A681178042915D1217C022934 -:1042100012D11979128901238B4013420CD101A9C3 -:1042200004F14C0001F068FFD4F89444019B21791B -:104230000246206800F0DAF902B010BD143001F037 -:10424000EBBE00004FF0FF33143001F0E5BE00007C -:104250004C3001F0BDBF00004FF0FF334C3001F097 -:10426000B7BF0000143001F0B9BE00004FF0FF31BD -:10427000143001F0B3BE00004C3001F089BF0000E3 -:104280004FF0FF324C3001F083BF0000D0F894248F -:1042900038B5136819780429054601D0012038BDC6 -:1042A000017C0229FAD112795C89012090400440F6 -:1042B000F4D105F1140001F04BFE02460028EDD0C8 -:1042C000D5F894544FF480732868697900F07CF92C -:1042D000204638BD406BFFF7D9BF00000020704773 -:1042E000704700007FB5124B03600023436083607A -:1042F000C360012502260F4B05740446029001930A -:1043000000F18402294600964FF48073143001F0C6 -:10431000FBFD094B0193029400964FF4807304F562 -:104320002372294604F14C0001F0C2FE04B070BDB6 -:1043300034710008D5420008FD4100080B682022B6 -:1043400082F311880A7903EB820290614A7909327B -:1043500043F822008A7912B103EB820398610223A9 -:104360000374C0F89414002383F31188704700008D -:1043700038B5037F044613B190F85430ABB9201D13 -:1043800001250221FFF732FF04F1140025776FF0B9 -:10439000010100F045FD84F8545004F14C006FF029 -:1043A0000101BDE8384000F03BBD38BD10B501212A -:1043B00004460430FFF71AFF0023237784F85430B3 -:1043C00010BD000038B504460025143001F0B4FDDE -:1043D00004F14C00257701F083FE201D84F8545031 -:1043E0000121FFF703FF2046BDE83840FFF74EBF2D -:1043F00090F8443003F06003202B19D190F8452049 -:10440000212A0AD0222A4FF000030ED0202A0FD1F1 -:10441000084A82630722C26304E0064B83630723D2 -:10442000C36300230364012070478363C363F9E718 -:104430000020704709270020D0F8943437B51A6857 -:104440001178042904461AD1017C022917D119795F -:10445000128901238B40134211D100F14C052846EB -:1044600001F0FEFE58B101A9284601F045FED4F83E -:104470009444019B21790246206800F0B7F803B00C -:1044800030BD000000EB8103F7B59C6905460E4680 -:10449000F4B1202383F3118805EB8607201D082142 -:1044A000FFF7A4FEFB685B691B684C3413B1204620 -:1044B00001F030FE01A9204601F01EFE024648B17F -:1044C000019B3146284600F091F8002383F31188C0 -:1044D00003B0F0BDFB685A691268002AF5D01B8A48 -:1044E000013B1340F1D105F14402EAE7093138B547 -:1044F00050F82140DCB1202383F31188D4F89424B0 -:104500001368527903EB8203DB689B695D6845B1F0 -:1045100004216018FFF76AFE294604F1140001F037 -:1045200021FD2046FFF7B2FE002383F3118838BD3A -:104530007047000001F0E2B80123037000234360DC -:10454000C36183620362C362436203630381438185 -:104550007047000038B50446202383F311880025F6 -:104560004160C56005614561856101F0D7F80223AE -:10457000237085F3118838BD70B500EB81030546C3 -:104580005069DA600E46144618B110220021FDF77A -:104590009BFBA06918B110220021FDF795FB314665 -:1045A0002846BDE8704001F083B90000028902F09E -:1045B00001020281428902F001024281002202616D -:1045C0004261826101F008BAF0B400EB81044789CE -:1045D000E4680125A4698D403D43458123600023A3 -:1045E000A2606360F0BC01F023BA0000F0B400EBFD -:1045F00081040789E468012564698D403D43058194 -:1046000023600023A2606360F0BC01F09DBA00004B -:1046100070B50223002504460370A0F84C5080F8C2 -:104620004E5080F84F5005814581C5600561456158 -:10463000856180F8345001F0D7F863681B6823B1B6 -:1046400029462046BDE87040184770BD436802788F -:104650001B6880F85020052202700BB10421184716 -:1046600070470000436890F850201B6802700BB13F -:10467000052118477047000090F8343070B50446A3 -:1046800013B1002380F8343004F14402204601F0D5 -:10469000C5F963689B6863BB94F8445015F06006E5 -:1046A00015D194F8453005F07F0545EA032540F221 -:1046B00002339D4200F00E815BD8022D00F0DC80B9 -:1046C0003FD8002D00F08780012D00F0CF80002121 -:1046D000204601F0FBFB0021204601F0EDFB636862 -:1046E0001B6813B1062120469847062384F834300E -:1046F00070BD204698470028CED094F84B2094F8FF -:104700004A3043EA0223E26B934238BFE36394F9F1 -:104710004430E56B002B4FF0200380F2FD80002D2C -:1047200000F0EC80092284F8342083F31188002102 -:10473000E36BA26B2046FFF759FF002383F3118838 -:1047400070BDB5F5817F00F0B180B5F5407F49D0EF -:10475000B5F5807FBBD194F84630012BB7D1B4F8C2 -:104760004C3023F00203A4F84C30A663E6632664C1 -:10477000C3E740F201639D421ED8B5F5C06F3BD23E -:10478000B5F5A06FA3D1B4F84430B3F5A06F0ED146 -:1047900094F8463084F84E30204601F07DF8636886 -:1047A0001B6813B10121204698470323237000237F -:1047B000A363E3632364A0E7B5F5106F32D040F63E -:1047C00002439D4252D0B5F5006F80D104F14F03F2 -:1047D000A363012324E004F14C03A3630223E363F6 -:1047E00025648AE794F84630012B7FF470AFB4F863 -:1047F0004C3043F00203B6E794F84920616894F81E -:1048000048304D6894F8471043EA0223204694F854 -:104810004620A84700283FF45AAF4368A3630368C3 -:10482000E363A4E72378042B10D1202383F31188BA -:104830002046FFF7BBFE86F31188636884F84F605B -:104840001B68032121700BB12046984794F846302D -:10485000002BACD084F84F300423237063681B68AE -:10486000002BA4D0022120469847A0E7374BA36332 -:104870000223E36300239DE794F8481011F0800FB2 -:10488000204601F00F010ED001F0BAF8012806D041 -:1048900002287FF41CAF2E4BA363E06367E72D4B28 -:1048A000A363E56363E701F09DF8EFE794F8463012 -:1048B000002B7FF40CAF94F8483013F00F013FF455 -:1048C00076AF1A06204602D501F014FB6FE701F01F -:1048D00007FB6CE794F84630002B7FF4F8AE94F8B1 -:1048E000483013F00F013FF462AF1B06204602D59B -:1048F00001F0ECFA5BE701F0DFFA58E7142284F8E4 -:10490000342083F311882B462A4629462046FFF798 -:104910005BFE85F3118870BD5DB1152284F83420EB -:1049200083F311880021E36BA26B2046FFF74CFE56 -:1049300003E70B2284F8342083F311882B462A46A0 -:1049400029462046FFF752FEE3E700BF64710008E6 -:104950005C7100086071000838B590F83430044686 -:10496000152B29D8DFE803F03E28282828283E28E0 -:10497000280B293928282828282828283E3E90F85E -:104980004B1090F84A20C36B42EA01229A4214D994 -:10499000C268128AB3FBF2F502FB15356DB920230C -:1049A00083F311882B462A462946FFF71FFE85F31D -:1049B00011880A2384F8343038BD142384F8343045 -:1049C000202383F3118800231A4619462046FFF757 -:1049D000FBFD002383F3118838BD036C03B19847B6 -:1049E0000023E7E7002101F071FA0021204601F0E1 -:1049F00063FA63681B6813B10621204698470623B3 -:104A0000D8E7000090F83420152A38B5044622D89B -:104A10000123934040F6416213421DD113F48015E7 -:104A20000FD19B0217D50B2380F83430202383F35A -:104A300011882B462A462946FFF7D8FD85F31188B1 -:104A400038BDC3689B695B682BB9036C03B1984799 -:104A5000002384F8343038BD002101F037FA0021FA -:104A6000204601F029FA63681B6813B1062120462D -:104A700098470623EDE70000024B00221B605B60B5 -:104A80009A607047F44F0020002303748268054B3E -:104A90001B6899689142FBD25A68036042601060BB -:104AA00058607047F44F002008B5202383F3118825 -:104AB000037C032B05D0042B0DD02BB983F3118875 -:104AC00008BD436900221A604FF0FF334361FFF7CE -:104AD000DBFF0023F2E790E80C001A6002685360E5 -:104AE000F2E70000002303748268054B1B68996895 -:104AF0009142FBD85A68036042601060586070476A -:104B0000F44F0020054B19690874186802681A6090 -:104B10005360186101230374FBF79ABDF44F002022 -:104B200030B54B1C87B005460A4C10D023690A4AA1 -:104B300001A800F091F92846FFF7E4FF049B13B1A8 -:104B400001A800F0C5F92369586907B030BDFFF727 -:104B5000D9FFF8E7F44F0020A94A000838B50C4DFA -:104B600041612B6981689A689142044603D8BDE887 -:104B70003840FFF789BF1846FFF786FF01232C61F5 -:104B8000014623742046BDE83840FBF761BD00BFF5 -:104B9000F44F0020044B1A681B6990689B68984288 -:104BA00094BF002001207047F44F002010B5084C3E -:104BB000236820691A6822605460012223611A74F4 -:104BC000FFF790FF01462069BDE81040FBF740BDAC -:104BD000F44F002008B5FFF7DDFF18B1BDE808402D -:104BE000FFF7E4BF08BD0000FEE7000010B5174C5A -:104BF000FFF742FF00F022F980221549204600F01D -:104C0000A7F8012344F8180C0374124B124AD96810 -:104C100021F4E0610904090C0A431049DA60CA680A -:104C200042F08072CA600E490A6842F001020A60CE -:104C30001022DA77202283F82220002383F31188C0 -:104C400062B60848BDE8104000F0A4B81C5000202F -:104C50006871000800ED00E00003FA05F0ED00E0E7 -:104C6000001000E07071000808B572B6034B58627E -:104C700000F0CCFB00F07CFCFEE700BFF44F00200E -:104C80002DE9F84F1F4C4FF00008656904F1140737 -:104C9000C1464FF08043266A5B6AAA689E1B964213 -:104CA0001DD34FF0200AAA68236AD5F80CB013442C -:104CB00023622B68BB425F60A6EB02066361C5F806 -:104CC0000C8001D101F0F6FA89F311882869D847E0 -:104CD0008AF311886569AB689E42E4D2D9E76269BC -:104CE000BA420CD0916823628E1B9660A868022895 -:104CF0002CBF1818981CBDE8F84F01F0E1BABDE8C8 -:104D0000F88F00BFF44F0020EFF3118020B9EFF3CC -:104D10000583202282F311887047000010B558B92E -:104D2000EFF30584C4F3080414B180F3118810BDB7 -:104D3000FFF750FF84F3118810BD0000034B596842 -:104D40005A68521A9042FBD8704700BF001000E02A -:104D50008260022202740022427470478368A3F1C9 -:104D60007C0243F80C2C026943F83C2C426943F85E -:104D7000382C074A43F81C2CC26843F8102C022236 -:104D800003F8082C002203F8072CA3F11800704741 -:104D90006906000810B5202383F31188FFF7DEFFB2 -:104DA00000210446FFF7DAFE002383F31188204632 -:104DB00010BD0000024B1B6958610F20FFF7A2BE17 -:104DC000F44F0020202383F31188FFF7F3BF000086 -:104DD00008B50146202383F311880820FFF7A0FEC1 -:104DE000002383F3118808BD49B1064B42681B6953 -:104DF00018605A60136043600420FFF791BE4FF0C3 -:104E0000FF307047F44F00200368984206D01A68BC -:104E10000260506059611846FFF736BE70470000C7 -:104E200038B504460D462068844200D138BD036879 -:104E300023605C604561FFF727FEF4E7054B03F153 -:104E400014025A619A614FF0FF32DA6100221A624D -:104E5000704700BFF44F0020F8B503614FF0804366 -:104E6000C2605C6A194B1A46022952F8145F38BFB7 -:104E70000221954206461F460AD1586198611C627C -:104E80000560456081600819BDE8F84001F00ABA84 -:104E9000186AAB68241A0C1902D3E41A2D6804E0CE -:104EA0009C4202D2204401F00BFAAB689C42F4D839 -:104EB0006B68736035601E606E60B460A9684FF007 -:104EC000FF33091BA960FB61F8BD00BFF44F002050 -:104ED00010B41B4C234653F8141F814210D0416874 -:104EE00002680A60026851609A424FF00001C16096 -:104EF00003D0936881680B4493605DF8044B70475E -:104F00000A68626100209A425360C86003D15DF86C -:104F1000044B01F0CFB993688868034493604FF065 -:104F20008042206A526A121A9342E6D9991A0129DC -:104F300098BF931C18445DF8044B01F0C1B900BF41 -:104F4000F44F00200C2303604FF0FF307047000047 -:104F500000207047FEE70000704700004FF0FF3070 -:104F600070470000022906D0032906D0012906480F -:104F700018BF0020704705487047032A9ABF0448AD -:104F800000EBC200002070475C720008107200083D -:104F90001027002070B59AB001AD06460846294694 -:104FA000144600F095F82846FCF786FEC0B2431C74 -:104FB0005B0086E81800237003236370002302342B -:104FC0001946DAB2904204F1020401D81AB070BD59 -:104FD000EA5C04F8022C04F8011C0133F1E700003C -:104FE00008B5202383F311880348FFF725FA00232F -:104FF00083F3118808BD00BF3052002010B504466D -:10500000052916D8DFE801F016150316161D202312 -:1050100083F311880E4A0121FFF7AEFA20460D4AAC -:105020000221FFF7A9FA0C48FFF7CCF9002383F31C -:10503000118810BD202383F311880748FFF798F9E2 -:10504000F4E7202383F311880348FFF7AFF9EDE776 -:1050500090710008B47100083052002038B50C4D32 -:105060000C4C0D492A4604F10800FFF793FF05F1A7 -:10507000CA0204F110000949FFF78CFF05F5CA7256 -:1050800004F118000649BDE83840FFF783BF00BFB0 -:10509000F856002010270020E0710008EA7100088F -:1050A000F571000870B5044608460D46FCF704FE8D -:1050B000C6B22046013403780BB9184670BD32469B -:1050C0002946FCF7E1FD0028F3D1012070BD000066 -:1050D0002DE9F04704460D46FCF7EEFD2D49C6B21A -:1050E0002046FFF7DFFF08B10836F6B22A4920460E -:1050F000FFF7D8FF08B11036F6B2632E0BD8DFF8F1 -:105100009480DFF89490254FDFF89CA0267846B96C -:105110002E70BDE8F08721462846BDE8F04701F033 -:10512000E5BC252E31D1072241462046FCF7ACFDD7 -:1051300080B91B4B2A4603F10C0153F8040B42F8CB -:10514000040B8B42F9D119889B7811809370073436 -:105150000F35DBE7082249462046FCF795FDA0B94C -:10516000104BAA1C13F8011F09095345C95D02F829 -:10517000021C197801F00F0102F10202C95D02F868 -:10518000031CEFD118350834C0E72E700134013507 -:10519000BCE700BF7C720008F5710008847200084B -:1051A0004A6C00080F7AFF1F1B7AFF1FBFF34F8F57 -:1051B000024AD368DB03FCD4704700BF003C0240C6 -:1051C00008B5094B1B7873B9FFF7F0FF074B1A6955 -:1051D000002ABFBF064A5A6002F188325A601A6834 -:1051E00022F480621A6008BD56590020003C02403B -:1051F0002301674508B50B4B1B7893B9FFF7D6FF22 -:10520000094B1A6942F000421A611A6842F480524E -:105210001A601A6822F480521A601A6842F4806296 -:105220001A6008BD56590020003C0240172870B58E -:1052300013D80B4A0B4C137863B90B4E4FF0006137 -:1052400044F8231056F823500133182B2944F7D182 -:105250000123137054F8200070BD002070BD00BF02 -:10526000B85900205859002098720008014B53F893 -:10527000200070479872000818207047172810B552 -:10528000044601D9002010BDFFF7D0FF064B53F8AC -:1052900024301844C21A0BB9012010BD1268013223 -:1052A000F0D1043BF6E700BF98720008172810B54C -:1052B000044629D8FFF77AFFFFF782FF1349F3234B -:1052C000CB600C23B0FBF3F203FB1200D30143EAE3 -:1052D000C003DBB243F4007343F002030B610B69BC -:1052E00043F480330B61FFF761FF2046FFF79EFF19 -:1052F000074B53F8241000F037F9FFF77BFF2046E7 -:10530000BDE81040FFF7BABF002010BD003C0240CE -:10531000987200082DE9F84312F00103154640D1B8 -:105320008218B2F1026F3CD22C4B1B6813F00103C0 -:1053300037D02B4CFFF744FFF323E360FFF736FF32 -:1053400040F20127032D01D9830713D0244C0F46C7 -:10535000401A40F20118EB1B0B44012B00EB07062F -:10536000236924D823F001032361FFF743FF0120C1 -:10537000BDE8F883236923F44073236123693B4329 -:10538000236151F8046B0660BFF34F8FFFF70EFFE8 -:1053900003689E4208D0236923F001032361FFF7CD -:1053A00029FF0020BDE8F883043D0430CAE723F458 -:1053B00040732361236943EA08032361B94637F840 -:1053C000023B3380BFF34F8FFFF7F0FE3688B9F80A -:1053D0000030B6B2B342BED0DDE700BF00380240B5 -:1053E000003C0240084908B50B7828B153B9FFF7D3 -:1053F000E7FE01230B7008BD23B1BDE8084008702B -:10540000FFF7F8BE08BD00BF5659002008B54FF49D -:1054100040314FF0005000F0A9F84FF480314FF0C8 -:105420008050BDE8084000F0A1B8000070B5FFF75B -:105430006BFC0E4E4FF08043596A3368994210D28C -:105440000B4CD4E90023003243F10103C4E90023EB -:10545000541843F100053160FFF760FC20462946EF -:1054600070BD034BD3E90023F2E700BFBC59002015 -:10547000C0590020D0B5FFF747FC4FF08042094BE0 -:10548000546A1A68944207D2074AD2E90067003684 -:1054900047F10107C2E900671C60FFF73FFC2046A7 -:1054A000D0BD00BFBC590020C059002008B5FFF78F -:1054B000BDFF4FF47A720023FAF7AEFE08BD00BFBD -:1054C00010B50244064B0439D2B2904200D110BD4F -:1054D000441C00B253F8200041F8040FE0B2F4E796 -:1054E00050280040104B30B51C6F240407D41C6FAB -:1054F00044F400741C671C6F44F400441C670B4C9C -:10550000236843F4807323600244094B0439D2B208 -:10551000904200D130BD441C00B251F8045F43F802 -:105520002050E0B2F4E700BF0038024000700040B5 -:105530005028004007B5012201A90020FFF7C0FF55 -:10554000019803B05DF804FB13B50446FFF7F2FFC2 -:10555000A04206D002A9012241F8044D0020FFF725 -:10556000C1FF02B010BD000070470000704700008E -:1055700070470000074B45F255521A6002225A60EC -:1055800040F6FF729A604CF6CC421A60024B012240 -:105590001A70704700300040C9590020034B1B7837 -:1055A0001BB1034B4AF6AA221A607047C959002062 -:1055B00000300040034B1B689B0042BF024B01229E -:1055C0001A70704774380240C8590020024B4FF0DF -:1055D00080721A60704700BF74380240014B18781F -:1055E000704700BFC859002070470000FEE7000068 -:1055F000084A094B09498B4204D3094A00219342C6 -:1056000005D3704752F8040F43F8040BF3E743F84F -:10561000041BF4E7F8740008545A0020545A002080 -:10562000545A0020836D30B500229D68446D1146A8 -:105630004FF0FF3004EB421301329542C3F80019DA -:10564000C3F81019C3F80809C3F8001BC3F8101BEE -:10565000C3F8080BEED24FF00113C4F81C3830BD6C -:10566000890141F02001016103699B06FCD41220ED -:10567000FFF764BB204B03EB80022DE9F047D2F823 -:105680000CE05D6DDEF81420461CD2F800C005EB7E -:10569000063605EB4018516861450BD3D5F8342820 -:1056A000012303FA00F022EA0000C5F83408184686 -:1056B000BDE8F087BEF81040ACEB0103A34228BF61 -:1056C0002346D8F81849A4B2B3EB840F10D89468D5 -:1056D0001F46A4F1040959F804AFC6F800A0042F2E -:1056E00001D9043FF7E71C440B4494605360D2E7B0 -:1056F0000020BDE8F08700BFCC59002010B5054C54 -:105700002046FEF719FF4FF0A0436365024BA365E7 -:1057100010BD00BFCC5900201C7300080378012B7A -:1057200070B5054650D12A4B446D98421BD1294B88 -:105730005A6B42F080025A635A6D42F080025A65F9 -:105740005A6D5A6942F080025A615A6922F0800209 -:105750005A610E2143205B69FEF758FB1E4BE36044 -:105760001E4BC4F800380023C4F8003EC023236059 -:105770006E6D4FF45023A3633369002BFCDA0123D1 -:1057800033610C20FFF7DAFA3369DB07FCD412200F -:10579000FFF7D4FA3369002BFCDA0026A66028460E -:1057A000FFF740FF6B68C4F81068DB68C4F8146842 -:1057B000C4F81C684BB90A4BA3614FF0FF33636117 -:1057C000A36843F00103A36070BD064BF4E700BF7C -:1057D000CC59002000380240401400400300200251 -:1057E000003C30C0083C30C0F8B5446D054600218F -:1057F0002046FFF735FFA96D00234FF001128F6897 -:10580000C4F834384FF00066C4F81C284FF0FF305D -:1058100004EB431201339F42C2F80069C2F8006BE7 -:10582000C2F80809C2F8080BF2D20B686A6DEB6582 -:10583000636210231361166916F01006FBD1122063 -:10584000FFF77CFAD4F8003823F4FE63C4F800387C -:10585000A36943F4402343F01003A3610923C4F870 -:105860001038C4F814380A4BEB604FF0C043C4F84A -:10587000103B084BC4F8003BC4F81069C4F8003969 -:10588000EB6D03F1100243F48013EA65A362F8BDE7 -:10589000F872000840800010426D90F84E10D2F867 -:1058A000003823F4FE6343EA0113C2F8003870475E -:1058B0002DE9F0410EB200EB86080D46D8F80C1029 -:1058C0000F6807F00303022B50D0032B50D03D4A42 -:1058D0003D4F012B18BF1746446D4FEA451E04EBA0 -:1058E0000E030022C3F8102B8A6905F1100C002A60 -:1058F00040D04A8A05F158035B013A43E250012344 -:10590000D4F81C2803FA0CF31343A6444A69C4F8DC -:105910001C380023CEF8103905F13F03002A39D096 -:105920000A8A898B9208012988BF4A43C16D04EB1A -:105930008303561841EA0242C66529465A6020464A -:10594000FFF78EFED8F80C301B8A43EA85531F43BD -:1059500005F148035B01E7500123D4F81C2803FA42 -:1059600005F51543C4F81C58BDE8F081174FB3E79F -:10597000174FB1E704EB4613D3F8002B22F4004293 -:10598000C3F8002BD4F81C28012303FA0CF322EAF5 -:105990000303BAE704EB83030E4A5A6004EB46168E -:1059A00029462046FFF75CFED6F8003923F4004371 -:1059B000C6F80039D4F81C38012202FA05F523EAAA -:1059C0000505CFE70080001000800410008008105B -:1059D00000800C1000040002826D1268C265FFF79F -:1059E00021BE00005831436D49015B5813F400405B -:1059F00004D013F4001F14BF0120022070470000E0 -:105A00004831436D49015B5813F4004004D013F44E -:105A1000001F14BF012002207047000000EB81012D -:105A2000CB68196A0B6813604B68536070470000BD -:105A300000EB810330B5DD68AA691368D36019B93A -:105A4000402B84BF402313606B8A1468426D1C4452 -:105A5000013CB4FBF3F46343033323F0030302EB91 -:105A6000411043EAC44343F0C043C0F8103B2B68E5 -:105A700003F00303012B09B20ED1D2F8083802EB70 -:105A8000411013F4807FD0F8003B14BF43F08053E3 -:105A900043F00053C0F8003B02EB4112D2F8003B48 -:105AA00043F00443C2F8003B30BD00002DE9F04153 -:105AB000244D6E6D06EB40130446D3F8087BC3F803 -:105AC000087B38070AD5D6F81438190706D505EB30 -:105AD00084032146DB6828465B689847FA072FD580 -:105AE000D6F81438DB072BD505EB8403D968CCB97D -:105AF0008B69488A5E68B6FBF0F200FB12628AB9D5 -:105B00001868DA6890420DD2121A83E81400202334 -:105B100083F311880B482146FFF78AFF84F311882D -:105B2000BDE8F081012303FA04F26B8923EA020342 -:105B30006B81CB6823B121460248BDE8F04118478C -:105B4000BDE8F081CC59002000EB810370B5DD6821 -:105B5000436D6C692668E6604A0156BB1A444FF4EF -:105B60000020C2F810092A6802F00302012A0AB2D2 -:105B70000ED1D3F8080803EB421410F4807FD4F858 -:105B8000000914BF40F0805040F00050C4F80009F4 -:105B900003EB4212D2F8000940F00440C2F80009B9 -:105BA000D3F83408012202FA01F10143C3F8341892 -:105BB00070BD19B9402E84BF4020206020682E8A15 -:105BC000841940F00050013C1A44B4FBF6F440EA5A -:105BD000C440C6E7F8B504461E48456D05EB4413BE -:105BE000D3F80869C3F80869F10717D5D5F8103854 -:105BF000DA0713D500EB8403D9684B691F68DA68AC -:105C0000974218D2D21B00271A605F60202383F3CB -:105C100011882146FFF798FF87F31188330617D5BF -:105C2000D5F834280123A340134211D02046BDE803 -:105C3000F840FFF71FBD012303FA04F2038923EAAA -:105C4000020303818B68002BE8D021469847E5E7E3 -:105C5000F8BD00BFCC59002096482DE9F84F456D9E -:105C60006E69AB691E4016F4805F6E61044605D014 -:105C7000FEF7CEFCBDE8F84FFDF784BF002E12DA28 -:105C8000D5F8003E8B489B071EBFD5F8003E23F099 -:105C90000303C5F8003ED5F8043823F00103C5F826 -:105CA0000438FEF7DFFC370502D58248FEF7CEFC4C -:105CB000B0040CD5D5F8083813F0060FEB6823F4C0 -:105CC00070530CBF43F4105343F4A053EB603107FF -:105CD00004D56368DB680BB176489847F2025AD462 -:105CE000B3020CD5D4F85480DFF8C8A100274FF0D8 -:105CF0000109A36D9B68F9B28B4280F08780F7069B -:105D000019D5616D0A6AC2F30A1702F00F0302F493 -:105D1000F012B2F5802F00F0A180B2F5402F0AD129 -:105D200004EB830301F58051DB68186A00231A46EF -:105D30009F4240F087803003D5F8184813D5E1031F -:105D400002D50020FFF7B2FEA20302D50120FFF723 -:105D5000ADFE630302D50220FFF7A8FE270302D59C -:105D60000320FFF7A3FE750384D5E00702D50020CA -:105D7000FFF730FFA10702D50120FFF72BFF6207D5 -:105D800002D50220FFF726FF23077FF573AF03201C -:105D9000FFF720FF6EE7D4F85480DFF818A1002742 -:105DA0004FF00109A36D9B685FFA87FB5B4597D3B2 -:105DB00008EB4B13D3F8002902F44022B2F5802FF0 -:105DC00022D1D3F80029002A1EDAD3F8002942F0A4 -:105DD0009042C3F80029D3F80029002AFBDB59467A -:105DE000606DFFF73DFC228909FA0BF322EA0303F9 -:105DF000238104EB8B03DB689B6813B15946504643 -:105E000098475846FFF736FC0137CBE708EB4112BD -:105E1000D2F8003B03F44023B3F5802F10D1D2F821 -:105E2000003B002B0CDA628909FA01F322EA030332 -:105E3000638104EB8103DB68DB680BB15046984754 -:105E4000013756E79C0708BF0A68072B98BF027006 -:105E500003F101039CBF120A013069E7023304EB2E -:105E6000830201F58051526890690268D0F808C039 -:105E70004068A2EB000E0022104697420AD104EBC4 -:105E8000830463689B699A683A449A605A68174425 -:105E90005F6050E712F0030F08BF0868964588BF9F -:105EA0008CF8000002F1010284BF000A0CF1010C21 -:105EB000E3E700BFCC590020436D03EB4111D1F85B -:105EC000003B43F40013C1F8003B7047436D03EB04 -:105ED0004111D1F8003943F40013C1F8003970477B -:105EE000436D03EB4111D1F8003B23F40013C1F8DB -:105EF000003B7047436D03EB4111D1F8003923F4A7 -:105F00000013C1F80039704730B5039C01720433A7 -:105F100004FB0325C361049B03630021059B006010 -:105F20004060C160426102618561046242628162D7 -:105F3000C162436330BD00000022416A41610161DA -:105F4000C2608262C2626FF00101FEF769BF0000A9 -:105F500003694269934203D1C2680AB100207047C5 -:105F6000181D704703691960C2680132C260C269B6 -:105F7000134482690361934224BF436A0361002191 -:105F8000FEF742BF38B504460D46E3683BB162698F -:105F9000131D1268A3621344E362002038BD237A04 -:105FA00033B929462046FEF71FFF0028EDDA38BD39 -:105FB0006FF00100FBE70000C368C269013BC360EA -:105FC0004369134482694361934224BF436A436136 -:105FD00000238362036B03B11847704770B5202319 -:105FE000044683F31188866A3EB9FFF7CBFF054666 -:105FF00018B186F31188284670BDA36AE26A13F8C7 -:10600000015BA362934202D32046FFF7D5FF002332 -:1060100083F31188EFE700002DE9F84F04460E46A0 -:1060200090469946202787F311880025AA46D4F880 -:1060300028B0BBF1000F09D149462046FFF7A2FF67 -:1060400020B18BF311882846BDE8F88FA16AE36A76 -:10605000A8EB050B5B1A9B4528BF9B46BBF1400F85 -:106060001BD9334601F1400251F8040B43F8040BED -:106070009142F9D1A36A40334036A3624035A26A07 -:10608000E36A9A4202D32046FFF796FF8AF311880B -:106090004545D8D287F31188C9E730465A46FBF701 -:1060A000E9FDA36A5B445E44A3625D44E7E7000048 -:1060B00010B5029C0172043303FB0421C361002369 -:1060C0008362C362039B0363049B00604060C460FF -:1060D00042610261816104624262436310BD00005B -:1060E000026AC260426A4261026100228262C26246 -:1060F0006FF00101FEF794BE436902699A4203D131 -:10610000C2680AB100207047184650F8043B0B6083 -:1061100070470000C368C2690133C3604369134418 -:1061200082694361934224BF436A43610021FEF7C1 -:106130006BBE000038B504460D46E3683BB12369E9 -:106140001A1DA262E2691344E362002038BD237A7B -:1061500033B929462046FEF747FE0028EDDA38BD60 -:106160006FF00100FBE7000003691960C268013AA3 -:10617000C260C269134482690361934224BF436AC7 -:10618000036100238362036B03B11847704700006B -:1061900070B5202304460E4683F31188856A35B90D -:1061A0001146FFF7C7FF10B185F3118870BDA36AD0 -:1061B0001E70A36AE26A01339342A36204D3E169C9 -:1061C00020460439FFF7D0FF002080F3118870BD0E -:1061D0002DE9F84F04460D4691469A464FF02008A7 -:1061E00088F311880026B346A76A4FB95146204666 -:1061F000FFF7A0FF20B187F311883046BDE8F88F84 -:10620000A06AE76AA9EB06033F1A9F4228BF1F4610 -:10621000402F1BD905F1400355F8042B40F8042BFF -:106220009D42F9D1A36A4033A3624036A26AE36A71 -:106230009A4204D3E16920460439FFF795FF8BF3B6 -:1062400011884E45D9D288F31188CDE729463A46C0 -:10625000FBF710FDA36A3B443D44A3623E44E5E7DF -:10626000026943699A4203D1C3681BB91846704753 -:106270000023FBE7836A002BF8D0043B9B1AF5D080 -:106280001360C368013BC360C3691A448369026138 -:106290009A4224BF436A0361002383620123E5E736 -:1062A00000F0A0B84FF08043002258631A61022228 -:1062B000DA6070474FF080430022DA6070470000D8 -:1062C0004FF08043586370474B6843608B6883602E -:1062D000CB68C3600B6943614B6903628B6943629E -:1062E0000B6803607047000008B5224B22481A690A -:1062F00040F2FF110A431A611A6922F4FF7222F078 -:1063000001021A611A691A6B0A431A631A6D0A4369 -:106310001A651A4A1B6D1146FFF7D6FF184802F19D -:106320001C01FFF7D1FF174802F13801FFF7CCFF3E -:10633000154802F15401FFF7C7FF144802F170013C -:10634000FFF7C2FF124802F18C01FFF7BDFF1148B1 -:1063500002F1A801FFF7B8FF0F4802F1C401FFF7EF -:10636000B3FF0E4802F1E001FFF7AEFFBDE80840C1 -:1063700000F0A2B800380240000002402873000874 -:106380000004024000080240000C024000100240DD -:106390000014024000180240001C0240002002408D -:1063A00008B500F0FDF9FEF721FCFFF703F9BDE8A1 -:1063B0000840FEF753BE0000704700004FF08043D6 -:1063C00010B51A69920708D500241C61202383F3B5 -:1063D0001188FEF755FC84F31188BDE81040FDF7E5 -:1063E000D1BB0000104B1A6C42F001021A641A6E05 -:1063F00042F001021A660D4A1B6E936843F00103D6 -:1064000093604FF0804353229A624FF0FF32DA627A -:1064100000229A615A63DA605A6001225A610821A7 -:106420001A601C20FDF7F2BC00380240002004E096 -:106430001F4B1A696FEAC2526FEAD2521A611A6987 -:10644000C2F308021A614FF0FF301A695A695861A5 -:1064500000215A6959615A691A6A62F080521A62B7 -:106460001A6A02F080521A621A6A5A6A58625A6AA2 -:1064700059625A6A1A6C42F080521A641A6E42F0DB -:1064800080521A661A6E0B4A106840F480701060D1 -:10649000186F00F44070B0F5007F1EBF4FF48030DD -:1064A00018671967536823F40073536000F058B9F4 -:1064B0000038024000700040324B4FF080521A64A6 -:1064C000314A4FF4404111601A6842F001021A60EB -:1064D0001A689207FCD59A6822F003029A60294B49 -:1064E00019469A6812F00C02FBD1186800F0F90006 -:1064F00018609A601A6842F480321A600B689B0335 -:10650000FCD54B6F43F001034B671E4B5A6F90074E -:10651000FCD51E4A5A601A6842F080721A601A4A04 -:1065200053685904FCD5174B1A689201FCD5184AD8 -:106530009A600322C3F88C20164B1A68164B9A42B5 -:10654000164B1BD1164A1168164A914216D140F2D9 -:1065500005121A600B4B9A6842F002029A609A6820 -:1065600002F00C02082AFAD15A6C42F480425A64B2 -:106570005A6E42F480425A665B6E704740F2057272 -:10658000E7E700BF003802400070004018544007A1 -:1065900000948838002004E011640020003C024090 -:1065A00000ED00E041C20F41084A08B55369116887 -:1065B0000B4003F00103536123B1054A13680BB18B -:1065C00050689847BDE80840FDF7DCBA003C014040 -:1065D0000C4B0020084A08B5536911680B4003F0C2 -:1065E0000203536123B1054A93680BB1D068984701 -:1065F000BDE80840FDF7C6BA003C01400C4B002046 -:10660000084A08B5536911680B4003F0040353614D -:1066100023B1054A13690BB150699847BDE808409A -:10662000FDF7B0BA003C01400C4B0020084A08B509 -:10663000536911680B4003F00803536123B1054A05 -:1066400093690BB1D0699847BDE80840FDF79ABA45 -:10665000003C01400C4B0020084A08B55369116802 -:106660000B4003F01003536123B1054A136A0BB1C9 -:10667000506A9847BDE80840FDF784BA003C0140E5 -:106680000C4B0020174B10B55C691A68144004F4D9 -:1066900078725A61A30604D5134A936A0BB1D06A83 -:1066A0009847600604D5104A136B0BB1506B98479E -:1066B000210604D50C4A936B0BB1D06B9847E205C9 -:1066C00004D5094A136C0BB1506C9847A30504D547 -:1066D000054A936C0BB1D06C9847BDE81040FDF7AC -:1066E00051BA00BF003C01400C4B00201A4B10B5C2 -:1066F0005C691A68144004F47C425A61620504D54E -:10670000164A136D0BB1506D9847230504D5134AF3 -:10671000936D0BB1D06D9847E00404D50F4A136E0A -:106720000BB1506E9847A10404D50C4A936E0BB17F -:10673000D06E9847620404D5084A136F0BB1506FAE -:106740009847230404D5054A936F0BB1D06F98473F -:10675000BDE81040FDF716BA003C01400C4B00208C -:10676000062108B50846FDF751FB06210720FDF775 -:106770004DFB06210820FDF749FB06210920FDF706 -:1067800045FB06210A20FDF741FB06211720FDF7F6 -:106790003DFB06212820BDE80840FDF737BB00007F -:1067A00008B5FFF745FEFDF71BFAFDF7D5FCFDF731 -:1067B000C1FEFDF795FDFFF7FFFDBDE80840FFF7BF -:1067C0006FBD000010B5002814BF04460124204608 -:1067D00000F04EF830B900F00DF808B900F014F8E8 -:1067E0008047F4E710BD00000B460146184600F054 -:1067F00031B80000024B1868BFF35B8F704700BFD1 -:10680000445A002000F03CB808B5062000F052F9C8 -:106810000120FEF79FFB00001FB51C46094B1B68BB -:106820000546D86852B1084B02928DE80A0022460C -:106830002B460649FCF70EF8FFF7E6FF044B1A4615 -:10684000F2E700BF302700202474000831740008EC -:10685000A46B000810B5054C13462CB10A4601463E -:106860000220AFF3008010BD204610BD00000000E4 -:10687000024B0146186800F087B800BF302700209F -:10688000024B0146186800F031B800BF30270020E5 -:1068900010B501390244904201D1002010BD10F81A -:1068A000013B11F8014FA342F5D0181B10BD0000A9 -:1068B0002DE9F8430746884691461E468BB10D46A2 -:1068C000A8EB0500B54207EB000402D20020BDE8AA -:1068D000F883324649462046FFF7DAFF18B1013DFA -:1068E000EEE7BDE8F8832046BDE8F88338B50546F5 -:1068F000002945D051F8043C0C1F002BB8BFE41808 -:1069000000F0FCF81F4A1368104633B96360146046 -:106910002846BDE8384000F0F3B8A3420CD92168FE -:106920006218934204BF1A685B68636004BF521820 -:1069300022600460ECE713465A680AB1A242FAD911 -:1069400019685818A0420BD1206801445818824297 -:106950001960DDD1106852685A6001441960D7E7A8 -:1069600002D90C232B60D3E7206821188A4204BF88 -:1069700011685268626004BF091821605C60C7E753 -:1069800038BD00BF485A002070B5CD1C25F0030566 -:1069900008350C2D38BF0C25002D064601DBA94219 -:1069A00003D90C233360002070BD00F0A7F8234A00 -:1069B0001468214691B9224C23681BB9304600F077 -:1069C00041F820602946304600F03CF8431C26D1AF -:1069D0000C233360304600F093F8E4E70B685B1B50 -:1069E0001AD40B2B0FD90B60CD50CC18304600F0C9 -:1069F00087F804F10B00231D20F00700C31A1BD0F9 -:106A00005A42E25070BD8C420DBF63684B686360B0 -:106A1000136018BF0C46E9E70C464968CAE7C41C76 -:106A200024F00304A04205D0211A304600F00AF8F1 -:106A30000130CDD02560D9E770BD00BF485A002095 -:106A40004C5A002038B5064C002305460846236002 -:106A5000FEF778FA431C02D1236803B12B6038BDDE -:106A6000505A00201F2938B504460D4604D9162374 -:106A700003604FF0FF3038BD426C12B152F8213044 -:106A80004BB9204600F030F82A4601462046BDE8C2 -:106A9000384000F017B8012B0AD0591C03D1162337 -:106AA0000360012038BD002442F82540284698475D -:106AB000002038BD024B01461868FFF7D3BF00BF66 -:106AC0003027002038B5074C0023054608461146FC -:106AD0002360FEF743FA431C02D1236803B12B6005 -:106AE00038BD00BF505A0020FEF732BA034611F8F5 -:106AF000012B03F8012B002AF9D1704770470000E1 -:106B000070470000121012131211000040A2E4F1AD -:106B1000646891064E6F20617070207369670A0087 -:106B2000426164206677206C656E67746820257505 -:106B30000A0042616420626F6172645F69642025AB -:106B4000752073686F756C642062652025750A0076 -:106B50004261642066772064657363726970746F44 -:106B600072206C656E6774682025750A0042616446 -:106B70002061707020435243203078253038783AB5 -:106B8000307825303878203078253038783A3078A9 -:106B9000253038780A00476F6F64206669726D7718 -:106BA0006172650A0000000072656365697665645C -:106BB0005F756E697175655F69645F6C656E203CB9 -:106BC0002055415643414E5F50524F544F434F4C16 -:106BD0005F44594E414D49435F4E4F44455F4944E0 -:106BE0005F414C4C4F434154494F4E5F554E4951C4 -:106BF00055455F49445F4D41585F4C454E475448A9 -:106C0000002E2E2F2E2E2F546F6F6C732F41505F3E -:106C1000426F6F746C6F616465722F63616E2E6377 -:106C2000707000616C6C6F63617465645F6E6F643B -:106C3000655F6964203C3D20313237006F72672EFA -:106C40006172647570696C6F742E506978726163DB -:106C500065722D706572697068000000766F6964F6 -:106C60002068616E646C655F616C6C6F63617469F0 -:106C70006F6E5F726573706F6E73652843616E61CE -:106C80007264496E7374616E63652A2C2043616E71 -:106C900061726452785472616E736665722A29005B -:106CA00053544D3332463F3F3F0000000120330034 -:106CB0000010410101105A01031059010710310160 -:106CC00000000000A06C00083F000000130400005A -:106CD000F86C00083F00000019040000026D000875 -:106CE0003F000000210400000C6D00083F00000080 -:106CF000305200208C4B002053544D3332463430F8 -:106D0000780053544D3332463432780053544D3367 -:106D100032463434365858008000000000800000AD -:106D2000000080004261642043414E496661636512 -:106D300020696E6465782E000000000000000000ED -:106D4000E92500083D250008451E00086D1E0008C5 -:106D5000C11F0008491E00085D1E00084D1E0008E6 -:106D6000511E0008591E0008551E0008591F000832 -:106D7000611E000863616E617264496E697400008F -:106D800063616E6172645365744C6F63616C4E6FC6 -:106D9000646549440000000063616E61726448618B -:106DA0006E646C6552784672616D650063616E61F8 -:106DB00072644465636F64655363616C6172000063 -:106DC00063616E617264456E636F64655363616C89 -:106DD00061720000696E6372656D656E74547261F4 -:106DE0006E73666572494400656E717565756554AC -:106DF000784672616D65730070757368547851756B -:106E00006575650070726570617265466F724E657A -:106E100078745472616E736665720000636F707986 -:106E200042697441727261790000000064657363A5 -:106E300061747465725472616E73666572506179C3 -:106E40006C6F61640000000066726565426C6F6380 -:106E50006B0000006269745F6C656E677468203E49 -:106E600020300072656D61696E696E675F6269747A -:106E700073203E203000696E7075745F6269745FC4 -:106E80006F6666736574203E3D20626C6F636B5F56 -:106E90006269745F6F666673657400626C6F636BC2 -:106EA0005F656E645F6269745F6F666673657420A8 -:106EB0003E20626C6F636B5F6269745F6F666673BE -:106EC00065740072656D61696E696E675F62697491 -:106ED0005F6C656E677468203C3D2072656D61690A -:106EE0006E696E675F6269747300696E7075745F56 -:106EF0006269745F6F6666736574203C3D207472CE -:106F0000616E736665722D3E7061796C6F61645F4E -:106F10006C656E202A2038006F75747075745F621E -:106F200069745F6F6666736574203C3D203634007B -:106F300072656D61696E696E675F6269745F6C65C9 -:106F40006E677468203D3D20300028726573756C53 -:106F500074203E2030292026262028726573756C07 -:106F600074203C3D20363429202626202872657363 -:106F7000756C74203C3D206269745F6C656E67744B -:106F80006829000064657374696E6174696F6E20AE -:106F9000213D202828766F6964202A29302900762F -:106FA000616C756520213D202828766F6964202A50 -:106FB000293029006F66667365745F776974686944 -:106FC0006E5F626C6F636B203C2028333255202D3E -:106FD000205F5F6275696C74696E5F6F666673656A -:106FE000746F66202843616E6172644275666665DF -:106FF00072426C6F636B2C206461746129290000FC -:107000006F75745F696E7320213D202828766F6943 -:1070100064202A29302900007372635F6C656E203A -:107020003E203055000000002863616E5F696420D7 -:107030002620307831464646464646465529203D6C -:107040003D2063616E5F696400000000616C6C6FDD -:107050006361746F722D3E737461746973746963D4 -:10706000732E63757272656E745F75736167655FA9 -:10707000626C6F636B73203E203000007472616E2F -:10708000736665725F696420213D202828766F69E8 -:1070900064202A293029000073746174652D3E62D2 -:1070A00075666665725F626C6F636B73203D3D2031 -:1070B0002828766F6964202A293029002E2E2F2E49 -:1070C0002E2F6D6F64756C65732F6C696263616ED2 -:1070D0006172642F63616E6172642E63006974650E -:1070E0006D2D3E6672616D652E646174615F6C65C5 -:1070F0006E203E20300000000096000000000000DE -:10710000000000000000000000000000000000007F -:10711000214100080D41000849410008354100089F -:10712000414100082D4100081941000805410008AF -:10713000554100080000000059420008454200087F -:10714000814200086D42000879420008654200084B -:10715000514200083D420008DD42000800000000E6 -:1071600001000000000000006D61696E0000000079 -:1071700088710008385000203052002001000000C3 -:10718000E94B00080000000069646C650000000025 -:10719000020000000000000085440008ED440008E3 -:1071A00040004000C8560020D856002002000000D1 -:1071B000000000000300000000000000314500084E -:1071C0000000000010000000E85600200000000051 -:1071D0000100000000000000CC5900200101020065 -:1071E0004172647550696C6F740025424F4152447E -:1071F000252D424C002553455249414C25000000A5 -:10720000FD4F0008654F0008F1430008E14F0008FA -:10721000430000001872000809024300020100C088 -:1072200032090400000102020100052400100105DA -:10723000240100010424020205240600010705823E -:10724000030800FF09040100020A0000000705010D -:10725000024000000705810240000000120000000B -:107260006472000812011001020000400912415727 -:1072700000020102030100000403090425424F41FA -:1072800052442500303132333435363738394142B3 -:10729000434445460000000000400000004000005C -:1072A000004000000040000000000100000002005B -:1072B00000000200000002000000020000000200C6 -:1072C000000002000000020000400000004000003A -:1072D000004000000040000000000100000002002B -:1072E0000000020000000200000002000000020096 -:1072F00000000200000002000000000079460008C3 -:1073000059490008054A0008400040002C5A002056 -:107310002C5A0020010000003C5A00208000000090 -:1073200040010000030000000000802A000000006F -:10733000AAAAAAAA00000000FFFF000000000000A7 -:1073400000A00A004400000000000000AAAAAAAAA7 -:1073500000000000FFFF000000000000000000002F -:107360001000004000000000AAAAAAAA10000040D5 -:10737000FFFF000000000000000000000A6810008D -:1073800000000000AAAAAAAA00541000FFFF0000F3 -:10739000990070070000000000000040000000009D -:1073A000AAAAAAAA00000040FFFF000000000000F7 -:1073B000000000000000000000000000AAAAAAAA25 -:1073C00000000000FFFF00000000000000000000BF -:1073D0000000000000000000AAAAAAAA0000000005 -:1073E000FFFF00000000000000000000000000009F -:1073F000000000000A000000000000000300000080 -:10740000000000000000000000000000000000007C -:10741000000000000000000000000000000000006C -:10742000000000002C2066756E6374696F6E3A2050 -:1074300000617373657274696F6E20222573222058 -:107440006661696C65643A2066696C652022257303 -:10745000222C206C696E65202564257325730A0033 -:10746000E88DFF7F01000000FE2A0100D204000029 -:10747000FF00960000000008040000007872000879 -:1074800000000000000000000000000000000000FC -:107490000000000000000000342700200000000071 -:1074A00000000000000000000000000000000000DC -:1074B00000000000000000000000000000000000CC -:1074C00000000000000000000000000000000000BC -:1074D00000000000000000000000000000000000AC -:1074E000000000000000000000000000000000009C -:0C74F00000000000000000000000000090 +:1000000000070020F5040008652C0008E52B000817 +:100010003D2C0008E52B0008112C0008F70400080F +:10002000F7040008F7040008F70400081D3B000867 +:10003000F7040008F7040008F7040008F7040008B4 +:10004000F7040008F7040008F7040008F7040008A4 +:10005000F7040008F7040008AD650008D96500083A +:1000600005660008316600085D660008F7040008B0 +:10007000F7040008F7040008F7040008F704000874 +:10008000F7040008F7040008F70400082128000816 +:100090004D2800085D280008F7040008896600085C +:1000A000F7040008F7040008F7040008F704000844 +:1000B0001D640008F7040008F7040008F7040008AE +:1000C000F7040008F7040008F7040008F704000824 +:1000D000F7040008F7040008013C0008F7040008D2 +:1000E000F1660008F7040008F7040008F7040008A8 +:1000F000F7040008F7040008F7040008F7040008F4 +:10010000F7040008F7040008F7040008F7040008E3 +:10011000F7040008F7040008F7040008F7040008D3 +:10012000F7040008F7040008F7040008F7040008C3 +:10013000F7040008F7040008F7040008F7040008B3 +:10014000F7040008F7040008F7040008455C0008FD +:10015000F7040008F7040008F7040008F704000893 +:10016000F7040008F7040008F7040008F704000883 +:10017000F7040008F7040008F7040008F704000873 +:10018000F7040008F7040008F7040008F704000863 +:10019000F7040008F7040008F7040008F704000853 +:1001A000F7040008F7040008F7040008F704000843 +:1001B000F7040008F7040008F7040008F704000833 +:1001C000F7040008F7040008F7040008F704000823 +:1001D000F7040008F7040008F7040008F704000813 +:1001E00001190008000000000000000000000000ED +:1001F00053B94AB9002908BF00281CBF4FF0FF318E +:100200004FF0FF3000F074B9ADF1080C6DE904CE89 +:1002100000F006F8DDF804E0DDE9022304B07047E1 +:100220002DE9F047089D04468E46002B4DD18A42A9 +:10023000944669D9B2FA82F252B101FA02F3C2F1DC +:10024000200120FA01F10CFA02FC41EA030E94406D +:100250004FEA1C48210CBEFBF8F61FFA8CF708FB8E +:1002600016E341EA034306FB07F199420AD91CEB66 +:10027000030306F1FF3080F01F81994240F21C8198 +:10028000023E63445B1AA4B2B3FBF8F008FB1033E0 +:1002900044EA034400FB07F7A7420AD91CEB040415 +:1002A00000F1FF3380F00A81A74240F207816444E5 +:1002B000023840EA0640E41B00261DB1D44000236A +:1002C000C5E900433146BDE8F0878B4209D9002DCE +:1002D00000F0EF800026C5E9000130463146BDE858 +:1002E000F087B3FA83F6002E4AD18B4202D38242C2 +:1002F00000F2F980841A61EB030301209E46002D71 +:10030000E0D0C5E9004EDDE702B9FFDEB2FA82F2C5 +:10031000002A40F09280A1EB0C014FEA1C471FFA23 +:100320008CFE0126200CB1FBF7F307FB131140EA0A +:1003300001410EFB03F0884208D91CEB010103F1D7 +:10034000FF3802D2884200F2CB804346091AA4B299 +:10035000B1FBF7F007FB101144EA01440EFB00FE6D +:10036000A64508D91CEB040400F1FF3102D2A645D2 +:1003700000F2BB800846A4EB0E0440EA03409CE771 +:10038000C6F12007B34022FA07FC4CEA030C20FA1E +:1003900007F401FA06F31C43F9404FEA1C4900FA3E +:1003A00006F3B1FBF9F8200C1FFA8CFE09FB1811BB +:1003B00040EA014108FB0EF0884202FA06F20BD92E +:1003C0001CEB010108F1FF3A80F08880884240F27E +:1003D0008580A8F102086144091AA4B2B1FBF9F0C2 +:1003E00009FB101144EA014100FB0EFE8E4508D9BD +:1003F0001CEB010100F1FF346CD28E456AD9023842 +:10040000614440EA0840A0FB0294A1EB0E01A14226 +:10041000C846A64656D353D05DB1B3EB080261EB94 +:100420000E0101FA07F722FA06F3F1401F43C5E96E +:10043000007100263146BDE8F087C2F12003D840A4 +:100440000CFA02FC21FA03F3914001434FEA1C47E6 +:100450001FFA8CFEB3FBF7F007FB10360B0C43EAD8 +:10046000064300FB0EF69E4204FA02F408D91CEB88 +:10047000030300F1FF382FD29E422DD90238634486 +:100480009B1B89B2B3FBF7F607FB163341EA034126 +:1004900006FB0EF38B4208D91CEB010106F1FF3875 +:1004A00016D28B4214D9023E6144C91A46EA00466C +:1004B00038E72E46284605E70646E3E61846F8E6FE +:1004C0004B45A9D2B9EB020864EB0C0E0138A3E747 +:1004D0004646EAE7204694E74046D1E7D0467BE728 +:1004E000023B614432E7304609E76444023842E7A0 +:1004F000704700BF02E000F000F8FEE772B63A482D +:1005000080F30888394880F3098839484EF6085145 +:10051000CEF20001086040F20000CCF200004EF67E +:100520003471CEF200010860BFF34F8FBFF36F8FBD +:1005300040F20000C0F2F0004EF68851CEF2000109 +:100540000860BFF34F8FBFF36F8F4FF00000E1EEF5 +:10055000100A4EF63C71CEF200010860062080F3CE +:100560001488BFF36F8F05F051F805F02DF805F0F2 +:10057000B9FE4FF055301F491B4A91423CBF41F82C +:10058000040BFAE71C49194A91423CBF41F8040B9D +:10059000FAE71A491A4A1B4B9A423EBF51F8040B1C +:1005A00042F8040BF8E700201749184A91423CBF73 +:1005B00041F8040BFAE705F00BF805F0E7FE144CE0 +:1005C000144DAC4203DA54F8041B8847F9E700F0F5 +:1005D00041F8114C114DAC4203DA54F8041B884722 +:1005E000F9E704F0F3BF000000070020002300201B +:1005F000000000080001002000070020D06F000864 +:1006000000230020B0230020B0230020EC53002062 +:10061000E0010008E4010008E4010008E40100082A +:100620002DE9F04F2DED108AC1F80CD0C3689D461E +:10063000BDEC108ABDE8F08F002383F311882846B3 +:10064000A047002004F028FBFEE704F097FA00DF43 +:10065000FEE70000F8B501F0ABFA30B1294B0022FB +:100660000F211A725A729972DA7204F047FF074624 +:1006700004F096FF0546C8BB234B9F4236D001339A +:100680009F4236D0214B27F0FF029A4234D1F8B274 +:1006900000F048FD2E4642F2107400F04DFF08B104 +:1006A0000024264600F044FD08B90646044635B14C +:1006B000174B9F4203D004F06BFF00242646002016 +:1006C00004F026FF134B1B6913F4807318D00EB18E +:1006D00000F068F801F042FB00F08CFF01F092F9A5 +:1006E000204600F0BBF800F05DF8F9E72E46002444 +:1006F000D3E704460126D0E7064641F28834CCE72A +:100700001C46E7E700230020010007B0000008B006 +:10071000263A09B00004024008B501F03FF9A0F103 +:1007200020035842584108BD07B541F21203022187 +:1007300001A8ADF8043001F04FF903B05DF804FBF7 +:1007400010B5202383F311881248C3680BB104F05D +:1007500029FB114A0F4800234FF47A7104F0E6FA9E +:10076000002383F311880D4C236813B12368013BE8 +:100770002360636813B16368013B6360084B1B78B7 +:1007800033B9636823B9022001F05AFA3223636057 +:1007900010BD00BFB023002041070008CC2400207A +:1007A000C4230020274B284A10B51C461968013184 +:1007B00046D004339342F9D16268244B9A423FD920 +:1007C000234B9B6803F1006303F580339A4237D2D1 +:1007D00004F0B2FE04F0C4FE002001F02DF91D4B20 +:1007E0000220187001F01CFA1B4B1A6C00221A64CC +:1007F000196E1A66196E596C5A64596E5A665A6E99 +:100800005A6942F080025A615A6922F080025A61A4 +:100810005A691A6942F000521A611A6922F00052AC +:100820001A611B6972B64FF0E0232021C3F8084D0E +:10083000D4E9003281F311889D4683F3088810477C +:1008400010BD00BF0000010820000108FFFF0008E4 +:1008500000230020C4230020003802402DE9F04F7F +:1008600093B0AC4B00902022FF210AA89D6801F0B4 +:100870001FFAA94A1378A3B9A8480121C3601170CF +:10088000202383F31188C3680BB104F08BFAA44AC8 +:10089000A24800234FF47A7104F048FA002383F34E +:1008A0001188009B9F4A03B113609F49009C00235D +:1008B0000B70536098469B461E469A46012001F0F5 +:1008C000AFF924B1974B1B68002B00F01C8200206D +:1008D00001F064F80390039B002B01DA00F0D0FED6 +:1008E000039B002BEDDB012001F08CF9039B213BE6 +:1008F000162BE3D801A252F823F000BF59090008D3 +:1009000081090008150A0008BD080008BD08000894 +:10091000BD080008A90A00087B0C0008950B000818 +:10092000F70B00081F0C0008450C0008BD08000864 +:10093000570C0008BD080008C90C0008F909000898 +:10094000BD0800080D0D000865090008F909000838 +:10095000BD080008F70B00080220FFF7DDFE0028A5 +:1009600040F0FB81009B0221B8F1000F08BF1C463C +:1009700005A841F21233ADF8143001F02DF89DE7CF +:100980004FF47A7001F00AF8071EEBDB0220FFF744 +:10099000C3FE0028E6D0013F052F00F2E081DFE82A +:1009A00007F0030A0D10133605230593042105A84B +:1009B00001F012F817E057480421F9E75B480421D9 +:1009C000F6E75B480421F3E74FF01C09484601F0C5 +:1009D00035F809F104090590042105A800F0FCFF91 +:1009E000B9F12C0FF2D1012000FA07F747EA0B0BFF +:1009F0005FFA8BFB4FF0000A01F0A6F926B10BF06D +:100A00000B030B2B08BF0024FFF78EFE56E7494867 +:100A10000421CDE7002EA5D00BF00B030B2BA1D1A9 +:100A20000220FFF779FE074600289BD001203E4EAA +:100A300001F002F80220307001F0F2F84FF00008E7 +:100A40005FFA88F9484601F007F8044690B1484635 +:100A500001F012F808F101080028F1D1B846044667 +:100A600041F21213022105A8ADF814303E4600F001 +:100A7000B3FF23E701230220337001F0C3F82546BA +:100A8000244B9B68AB4207D9284600F0D7FF0130C2 +:100A900040F068810435F3E7234B00251D70214B9E +:100AA000B8465D603E46A7E7002E3FF45BAF0BF013 +:100AB0000B030B2B7FF456AF1B4B0220187001F079 +:100AC000AFF8322000F06AFFB0F10009FFF64AAF3C +:100AD00019F003077FF446AF0E4A926809EB05034D +:100AE00093423FF63FAFB9F5807F3FF73BAF124BE4 +:100AF0000193B94522DD4FF47A7000F04FFF039067 +:100B0000039A002AFFF62EAF019B039A03F8012BEC +:100B10000137EDE700230020C8240020B023002087 +:100B200041070008CC240020C42300200423002017 +:100B3000082300200C230020C8230020C820FFF732 +:100B4000EBFD074600283FF40DAF1F2D11D8C5F16E +:100B500020024A450AAB25F0030028BF4A468349D4 +:100B60000192184401F07EF8019A8048FF2101F0BB +:100B70009FF84FEAA9037D490193C9F387022846EC +:100B800001F09EF8064600283FF46AAF019B05EB92 +:100B9000830531E70220FFF7BFFD00283FF4E2AEF6 +:100BA00000F094FF00283FF4DDAE0027B946704BFB +:100BB0009B68BB4218D91F2F11D80A9B01330ED056 +:100BC00027F0030312AA134453F8203C0593484628 +:100BD000042205A902F054F804378146E7E73846B5 +:100BE00000F02CFF0590F2E7CDF81490042105A841 +:100BF00000F0F2FE00E70023642104A8049300F053 +:100C0000E1FE00287FF4AEAE0220FFF785FD00284C +:100C10003FF4A8AE049800F041FF0590E6E70023FA +:100C2000642104A8049300F0CDFE00287FF49AAE5E +:100C30000220FFF771FD00283FF494AE049800F005 +:100C40003DFFEAE70220FFF767FD00283FF48AAE88 +:100C500000F04CFFE1E70220FFF75EFD00283FF4C3 +:100C600081AE05A9142000F047FF04210746049037 +:100C700004A800F0B1FE3946B9E7322000F08EFE3C +:100C8000071EFFF66FAEBB077FF46CAE384A926862 +:100C900007EB0A0393423FF665AE0220FFF73CFDE7 +:100CA00000283FF45FAE27F003075744BA453FF4EE +:100CB000A3AE504600F0C2FE0421059005A800F046 +:100CC0008BFE0AF1040AF1E74FF47A70FFF724FD76 +:100CD00000283FF447AE00F0F9FE002844D00A9BFC +:100CE00001330BD008220AA9002000F0E9FF0028F8 +:100CF0003AD02022FF210AA800F0DAFFFFF714FD06 +:100D00001C4803F0CFFF13B0BDE8F08F002E3FF476 +:100D100029AE0BF00B030B2B7FF424AE00236421D0 +:100D200005A8059300F04EFE074600287FF41AAE92 +:100D30000220FFF7F1FC814600283FF413AEFFF7D5 +:100D4000F3FC41F2883003F0ADFF059801F03AF86A +:100D50004E4600F0F9FF3C46B0E506464CE64FF043 +:100D6000000AFFE5B8467BE6374679E6C82300204F +:100D700000230020A0860100094A136849F2690097 +:100D800099B21B0C00FB01331360064B186844F248 +:100D9000506182B2000C01FB0200186080B2704703 +:100DA000182300201423002010B50021102204462F +:100DB00000F07EFF034B03CB206061601868A060E9 +:100DC00010BD00BF107AFF1F2DE9F043224DBBB0CC +:100DD00001F050FFAB6840F2ED22C31A934232D9C2 +:100DE00006AFA8602B4628220021384602F052FCAC +:100DF00005F10E0000F054FF002604465FFA80F96A +:100E000005F10E08F3B2F100994501F1280107D967 +:100E100008EB06030822384602F03CFC0136F1E7F5 +:100E200008230122CDE9023205340C4B0193A4B210 +:100E300030230093CDE9047405A3D3E90023297B73 +:100E4000074802F03FFA3BB0BDE8F083AFF3008003 +:100E500078F6339F93CACD8DE8450020F5450020F4 +:100E6000EC34002070B50D4614461E4602F0C0F961 +:100E700050B9022E10D1012C0ED112A3D3E90023B8 +:100E8000C5E90023012007E0282C10D005D8012C4B +:100E900009D0052C0FD0002070BD302CFBD10BA346 +:100EA000D3E90023ECE70BA3D3E90023E8E70BA386 +:100EB000D3E90023E4E70BA3D3E90023E0E700BF75 +:100EC000AFF30080401DA12026812A0B78F6339FC6 +:100ED00093CACD8D9E6AC421818A46EE26417272E4 +:100EE000DF25D7B7F017304A39059E5613B50446AB +:100EF0002346084620220021019002F0CBFB2279F4 +:100F00000198032A234628BF032203F8042F202137 +:100F1000022202F0BFFB62790198072A234628BF0C +:100F2000072203F8052F2221032202F0B3FBA27946 +:100F30000198072A234628BF072203F8062F2521F8 +:100F4000032202F0A7FB019804F1080310222821D4 +:100F500002F0A0FB382002B010BD00002DE9F04FD8 +:100F6000ADF5017D21AD0EAE40F2751280460F4603 +:100F700022A80021296000F09BFE48220021304673 +:100F800000F096FE01F076FE564B4FF47A72B0FBFD +:100F9000F2F0186093E80700012386E807000DF1DE +:100FA0005A003382FFF700FF47F60523338406AB70 +:100FB00018464D4905F08AFD1D2230642946304609 +:100FC00086F83C20FFF792FF12AB04460146082248 +:100FD000284602F05FFB0822A1180DF149032846BC +:100FE00002F058FB0DF14A03082204F110012846D3 +:100FF00002F050FB13AB202204F11801284602F046 +:1010000049FB14AB402204F13801284602F042FBB0 +:1010100016AB082204F17801284602F03BFB0DF1E3 +:101020005903082204F18001284602F033FB04F141 +:10103000880A0DF15A0904F5847B4B465146082273 +:1010400028460AF1080A02F025FBD34509F10109F7 +:10105000F3D11BAB08225946284602F01BFB04F5CE +:1010600088744FF0000996F834304B450AD9B36BB9 +:1010700021464B440822284602F00CFB083409F1B3 +:101080000109F0E74FF0000996F83C304B4504EBBE +:10109000C90108D9336C08224B44284602F0FAFAF9 +:1010A00009F10109F0E700230393BB7E02930731A6 +:1010B00007F119030193C1F3CF010123CDE90451D5 +:1010C0000093F97E05A3D3E90023404602F0FAF825 +:1010D0000DF5017DBDE8F08FAFF300809E6AC4215D +:1010E000818A46EED4240020FC6A000810B50A4B21 +:1010F0000A4A1A6003F5805393F860203AB9DC6D10 +:101100002CB1204601F034FC204605F071FBBDE80F +:101110001040034801F02CBC18350020586C000822 +:1011200060450020014B1870704700BFE02400208C +:10113000F0B5334B1C7B85B034B1324B0E221A8193 +:101140000024204605B0F0BD2F4A1068516802AB5C +:1011500003C308232D492E480DEB030205F09AFB2B +:10116000054630B9274B2B480A221A8101F07EFB35 +:10117000E6E70169B1F5F81F06D9224B26480B2294 +:101180001A8101F073FBDCE7438B40F27A52934201 +:1011900007D01C490C2008811946204801F066FB45 +:1011A000CFE71F4A024402F11003994204D2154BC3 +:1011B0001C4810221A81E4E710398E1A204614497F +:1011C00001F05EFD3246074605F11801204601F0A8 +:1011D00057FDAB689F4202D1EB6898420AD0094B99 +:1011E0000D221A810090D5E902123B460E4801F00B +:1011F0003DFBA5E70D4801F039FB0124A1E700BF45 +:10120000E8450020D4240020AD6B0008DCFF1E0060 +:10121000000001081C6B0008286B00083A6B0008EE +:101220000800FFF7586B0008756B00089E6B0008FC +:101230002DE9F04FADB006AF80460C4601F0D8FF67 +:10124000054600285AD1237E022B1BD1E38A012BAD +:1012500018D101F00FFD0646FFF78EFD03464FF44F +:10126000C870DFF8D092B3FBF0F206F5167602FBF9 +:10127000103316FA83F3C9F80030E37E33B9A84B74 +:1012800000221A709C37BD46BDE8F08FA38AEEB2EB +:10129000013BB34205F101050BD93B1D1E44E9009A +:1012A00000960023082201F0F801204602F0B6F86B +:1012B000ECE707F11400FFF777FD324607F1140160 +:1012C000381D05F0D7FA0028D9D10F2E08D8944B35 +:1012D0001E70D9F80030A3F51673C9F80030D1E7B5 +:1012E000FB1CF8700146009307220346204602F0DB +:1012F00095F8F978404601F073FFC3E7E38A282B9D +:1013000026D010D8012B1ED0052BBBD1BFF34F8F99 +:101310008449854BCA6802F4E0621343CB60BFF393 +:101320004F8F00BFFDE7302BACD1637E7F4D013383 +:101330006A7BDBB29342E94603D1E27E2B7B9A4281 +:1013400065D0CD469EE721464046FFF707FE99E768 +:10135000A38A013B9BB2C92B94D8744D2E7B26BB2C +:1013600005F10C030093082233463146204602F073 +:1013700055F8731CF2B2D9001E46A38A013B9A426B +:1013800005DA0E322A44009200230822EEE70023F9 +:101390000022C5E900230023AB6085F8D730C5F8EB +:1013A000D8302B7B0BB9E37E2B73002507F1140992 +:1013B0003B1D082229464846C7E90155FD6002F059 +:1013C00069F93B7A05F1010AAB424FEACA0608D92E +:1013D000FB6808222B443146484602F05BF955462B +:1013E000EFE7C6F3CF06E17ECDE904960023039331 +:1013F000A37E0293193428230093019446A3D3E9D2 +:101400000023404601F05EFFFFF7DEFC3AE74FF0B5 +:10141000000807F11403A7F8148010220093414636 +:101420000123204601F0FAFFA68A023EB6B2F31C61 +:101430009B109B000733DB08A9EBC3039D460DF10E +:10144000180A1FFA88F34FEAC801B34201F11001EC +:101450000AD20AEB0803009308220023204601F079 +:10146000DDFF08F10108ECE795F8D70000F0F4FA89 +:10147000D5F8D83004461BB995F8D70000F0FCFA2F +:10148000D5F8D83033449C4204D295F8D7000130C7 +:1014900000F0F2FA4FEA960B4FF000081FFA88F1BD +:1014A0008B45D5E9003209D90AEB880103EB8800A6 +:1014B000012200F005FC08F10108EFE7F31842F102 +:1014C0000002C5E90032D5F8D83095F8D70006EB10 +:1014D0000308C5F8D88000F0BFFA804509D395F815 +:1014E000D730D5F8D8000133001B85F8D730C5F8C0 +:1014F000D800FF2E08D800232B7300F0E7FAFFF77F +:1015000017FE08B1FFF74EF92B68094A9B0A013311 +:1015100013810023AB6014E726417272DF25D7B731 +:10152000E534002000ED00E00400FA05E845002065 +:10153000D4240020E834002030B54FF00054244B70 +:1015400022689A4285B007D004F034F80446A8B95E +:101550000024204605B030BD1E4B627D1A701E4827 +:10156000237D03731D49C9220E3000F07BFB20460A +:10157000E022002100F09CFB0124EAE7184A194D03 +:10158000136C43F000731364AA6D174B9A42DFD1BA +:101590002B6E013B7E2BDBD8144A07CA01AB83E8D4 +:1015A00007001846032101F081FB6B6D83424FF069 +:1015B0000003CDD12A6D8A4201BFAB65054B2A6E6F +:1015C0001A7003BF0A4BEA6D1A601C46C1E700BFE0 +:1015D0009AAD44C5E0240020E84500201600002014 +:1015E00000380240006600405041A0B058660040FC +:1015F0001023002037B5194D194802236B71194B80 +:101600000122196801F000F800230193164B1749D5 +:1016100000931748174B4FF4805201F0BBFD164B57 +:10162000197811B1124801F0DBFD01F023FB0446EB +:10163000FFF7A2FB4FF4C873B0FBF3F202FB1303F6 +:1016400004F5167010FA83F00C4B186003F0A8FF35 +:1016500008B10F232B8103B030BD00BFD42400207C +:101660001835002010230020650E0008E424002017 +:10167000EC34002031120008E0240020E83400207F +:101680002DE9F04F2DED028B0FF26429D9E9008985 +:101690008D4C93B08D4E8E4F204601F077FE034661 +:1016A00060B30025CDE90F550E95ADF84450027B8F +:1016B0008DF8442099684068DFF83CA20FAA03C265 +:1016C0001B6843F000430E9301F0D6FA821941F1F2 +:1016D000000300950EA9384600F0C4FBA84205DDC2 +:1016E000204601F057FE8AF80050D5E79AF80030FE +:1016F000072B00F2B68001338AF800300BAE9FED65 +:101700006E8B0023724FDFF8F4A10A93ADF83430EA +:101710000B9373604FF0000B5B468DED008B012542 +:101720000DF11D0207A938468DF81C508DF81DB02B +:1017300000F01AFF9DF81C30002B40F096802046E8 +:1017400001F056FD0646002845D1624F01F092FA9D +:101750003B6898423FD301F08DFA8246FFF70CFBBD +:101760004FF4C8730AF5167AB0FBF3F202FB1303C9 +:101770001AFA83F33B60584F97F800B0CBF1100A88 +:10178000BBF1000F14BF33462B465FFA8AFA0EA84E +:101790008DF82830FFF708FBBAF1060F28BF4FF08D +:1017A000060A0EAB03EB0B0152460DF1290000F0C7 +:1017B00059FA0AAB0393182302930AF10102474B2B +:1017C000D2B2CDE90053049220463DA3D3E90023D1 +:1017D00001F010FD3E7001F04DFA414A414D136891 +:1017E000C31AB3F57A7F2FD3106001F045FA024691 +:1017F0000B46204601F0D8FD204601F0F9FC18B355 +:101800002B7B394E002B14BF03230223737101F08D +:1018100031FA0EAF4FF47A733946B0FBF3F0306013 +:101820003046FFF763FB1823073002932F4B0193D9 +:10183000C0F3CF0040F25513CDE903700093424648 +:101840004B46204601F0D6FC2B7B2BB1FFF7BCFAB0 +:101850002B7B002B7FF41EAF13B0BDEC028BBDE8D9 +:10186000F08F204601F096FD48E7DAF8143083F057 +:101870000203CAF81430594610220EA800F018FAD4 +:101880000DF11E0308AA0AA9384600F0E9FB96E804 +:1018900003000FAB83E803009DF834308DF844302B +:1018A0000A9B0E930EA9DDE90823204601F03AFFBA +:1018B00030E700BFAFF30080000000000000000030 +:1018C000401DA12026812A0BEC34002040420F004D +:1018D00018350020E8340020E5340020E4340020EE +:1018E000C8460020E8450020D4240020CC46002033 +:1018F000F1C6A7C1D068080FCD4600200004024001 +:1019000008B5054800F046FCBDE80840034A044914 +:10191000002004F067BF00BF183500201C470020DE +:10192000ED100008F7B5194E0C464FF47A7102FB22 +:1019300001F396F900200546501C0BD11448019381 +:1019400002682946176A2246B8478442019B03D1A0 +:10195000002310E0002AF1D096F90020511C01D09C +:10196000012A0DD10B4802682946166A2246B04763 +:10197000844205D10123084A0120137003B0F0BD51 +:101980004FF4FA7003F08EF90020F7E71C230020D3 +:10199000404B0020204700201047002007B50023BF +:1019A000024601210DF107008DF80730FFF7BAFF5D +:1019B00020B19DF8070003B05DF804FB4FF0FF3045 +:1019C000F9E700000A4608B50421FFF7ABFF80F0F5 +:1019D0000100C0B2404208BD30B4074B0A46197836 +:1019E000064B53F821402368DD69054B0146AC46A0 +:1019F000204630BC604700BF10470020286C00081C +:101A0000A086010070B503F005FC094E094D308039 +:101A1000002428683388834208D903F0F5FB2B683B +:101A200004440133B4F5803F2B60F2D370BD00BF96 +:101A300012470020D046002003F0B4BC00F1006043 +:101A400000F580300068704700F10060920000F5FA +:101A5000803003F033BC0000054B1A68054B1B882F +:101A60009B1A834202D9104403F0CEBB002070477A +:101A7000D04600201247002038B5074D044628689C +:101A8000204403F0C9FB28B928682044BDE8384049 +:101A900003F0DABB38BD00BFD046002010F00303CE +:101AA0000AD1B0F5047F05D200F10050A0F5104036 +:101AB000D0F80038184670470023FBE700F10050CB +:101AC000A0F51040D0F8100A70470000064991F8C0 +:101AD000243033B10023086A81F824300822FFF74C +:101AE000B3BF0120704700BFD4460020014B1868E7 +:101AF000704700BF002004E070B52A4B1B68C3F399 +:101B00000B0204461B0C62B140F21340824230D0FB +:101B100040F2194082422ED040F2214082422CD124 +:101B20000322214D0C2000FB0252556842F20102B3 +:101B3000934224D0B3F5805F23D041F20102934257 +:101B400021D041F2030293421FD041F20702934297 +:101B500014BF3F233123013C0C44013D0A46A242FD +:101B600015D215F9016F501C9EB100F8016C0246A8 +:101B7000F5E70122D5E70222D3E70C4DD6E7332360 +:101B8000E9E74123E7E75A23E5E75923E3E710466E +:101B900005E02C258442157001D9901C5370401A21 +:101BA00070BD00BF002004E0F86B0008B86B0008AF +:101BB000124B5A8842F201018A42134614D0B2F500 +:101BC000805F13D041F20102934211D041F203022F +:101BD00093420FD041F2070293420DD10423084AE9 +:101BE00002EB8303D87870470023F8E70123F6E778 +:101BF0000223F4E70323F2E700207047002004E00B +:101C0000E46B0008022802D1044B98617047012858 +:101C100002BF024B08229A61704700BF00040240D5 +:101C2000022804D1054B4FF400329A617047012815 +:101C3000FCD1024B4FF40022F7E700BF0004024042 +:101C4000022805D1064A536983F0020353617047A5 +:101C50000128FCD1024A536983F00803F6E700BF6C +:101C60000004024010B50023934203D0CC5CC4545E +:101C70000133F9E710BD000010B5013810F9013F3C +:101C80003BB191F900409C4203D11AB10131013AB4 +:101C9000F4E71AB191F90020981A10BD1046FCE73C +:101CA00003460246D01A12F9011B0029FAD17047E7 +:101CB00002440346934202D003F8011BFAE770473F +:101CC0002DE9F8431F4D144695F824200746884611 +:101CD00052BBDFF870909CB395F824302BB92022CA +:101CE000FF2148462F62FFF7E3FF95F82400C0F17B +:101CF0000802A24228BF2246D6B24146920005EB16 +:101D00008000FFF7AFFF95F82430A41B1E44F6B205 +:101D1000082E17449044E4B285F82460DBD1FFF725 +:101D2000D5FE0028D7D108E02B6A03EB820383425B +:101D3000CFD0FFF7CBFE0028CBD10020BDE8F88341 +:101D40000120FBE7D4460020024B1A78024B1A70A0 +:101D5000704700BF104700201C23002038B5134CEB +:101D6000134D204602F0A8FA2946204602F0D0FA88 +:101D70002D6810486A6D936B23F40023936302F07F +:101D800091FF0D49284602F0C9FB6A6D0B48936B21 +:101D90000B4943F400239363A0424FF4E1330B60FB +:101DA00003D0BDE8384002F0E7B938BD404B002011 +:101DB0009C6D000840420F00A46D000820470020E1 +:101DC000FC46002038B50B4B1A780B4B53F82250C9 +:101DD0000A4B9D4204460CD0094B002118461422A0 +:101DE000FFF766FF046001462846BDE8384002F070 +:101DF000C3B938BD10470020286C0008404B0020B4 +:101E0000FC460020202383F3118862B6704700004F +:101E1000002383F3118862B67047000010B4026893 +:101E200054681A4623465DF8044B18470120704752 +:101E30000020704700207047704700007047000086 +:101E4000002070470E20704700F5805090F8C800C1 +:101E5000C0F340007047000000F5805090F9C900C1 +:101E6000704700002DE9F0410C68BDF8187014F0BF +:101E700000541E466FD10B7B082B6CD8FFF7C2FFB6 +:101E80004569AB685B010CD4AB681B0108D4AC6836 +:101E900014F080545DD1FFF7BBFF2046BDE8F08110 +:101EA00001240B6804F1180C002BB8BFDB004FEACB +:101EB0000C1CB4BF43F004035B0545F80C300B6801 +:101EC0000FFA84FC13F0804F18BF05EB0C1E05EBD6 +:101ED0000C1C1EBFDEF8803143F00203CEF88031C7 +:101EE0000B7BCCF8843105EB04158B68C5F88C317D +:101EF0004B68C5F88831DCF8803143F00103CCF839 +:101F0000803100EB441541F268031D4403EB441398 +:101F10000344C5E9002608330D4601F10C0C55F8C1 +:101F200004EB43F804EB6545F9D184342D881D801A +:101F300000EB441407F00303257925F00B052B4330 +:101F40002371FFF765FF06973346BDE8F04100F0C7 +:101F5000AFBC0224A5E74FF0FF309FE713B500F5B3 +:101F600080540191E06D00F039FD1F280AD90199D4 +:101F7000E06D202200F0A8FDA0F120035842584156 +:101F800002B010BD0020FBE708B500F58050FFF758 +:101F900039FFC06D00F0F6FCBDE80840FFF738BF20 +:101FA00000220260828142608260704710B5002288 +:101FB0000023C0E900230023044603810C30FFF70F +:101FC000EFFF204610BD0000F0B5054600F580503B +:101FD0000C4690F8C83013F0040FC3F3800108BF1B +:101FE000114661F3820304F1840680F8C83005EBE2 +:101FF000461389B01B79D8072ED57AB319072DD48B +:102000006846FFF7D3FF05EB441303F5835303F151 +:10201000180703AA103318685968144603C4083314 +:10202000BB422246F7D1186820609B88A380DDE977 +:102030000E23CDE900230123ADF808302B68694653 +:102040001B6C2846984705EB46152B791A075CBF91 +:1020500043F008032B7101E0002AF4D109B0F0BD70 +:102060002DE9F047074688B007F5805468469A4640 +:102070008846FFF7C7FE9146FFF798FFE06D00F036 +:1020800093FC1F2829D9E06D2022694600F09EFDAF +:10209000202822D103AD444605AB2E4603CE9E42F6 +:1020A00020606160354604F10804F6D13068206094 +:1020B000B388A380DDE90023C9E90023BDF8083017 +:1020C000AAF80030FFF7A4FE4A4653464146384678 +:1020D00008B0BDE8F04700F0D9BBFFF799FE00203B +:1020E00008B0BDE8F08700002DE9F84F0023C0E9F3 +:1020F0000133254B044640F8183B0F46FFF750FFCD +:1021000004F12800FFF752FF04F1480804F5825556 +:102110004646083530462036FFF748FFAE42F9D133 +:1021200004F580554FF480534FF00009C5E9133989 +:10213000C5F848800123EE6504F5875804F58456F8 +:10214000C5F8549085F8583085F86030083608F1A5 +:1021500008084FF0000A4FF0000B46E908ABA6F163 +:102160001800FFF71DFF203646F8289C4645F4D19D +:1021700085F8C97017B1054800F076FD044B63611E +:102180002046BDE8F88F00BF586C0008306C00088E +:102190000064004010B5044B197804464A1C1A70BC +:1021A000FFF7A2FF204610BD184700202DE9F04799 +:1021B000002950D0294B2A4FB7FBF1F599428CBF2B +:1021C0000A231123581EB5FBF3FC03FB1C53C4B2B6 +:1021D0002BB102280346F5D80020BDE8F0870CF1AA +:1021E000FF36B6F5806FF7D2C4EBC40E0EF10303D1 +:1021F0004FEAE309C3F3C703A4EB030809F1010A9B +:102200004FF47A755FFA88F009FB05555AFA88F899 +:10221000B5FBF8F5B5F5617FC1BF0EF1FF33C3F330 +:10222000C703E01AC0B25C1C50FA84F40CFB04F43F +:10223000B7FBF4F4A142CFD1013BDBB20F2BCBD8DB +:102240000138C0B20728C7D80021107116809170DC +:10225000D3700120C1E70846BFE700BF3F420F002F +:1022600080DE800270B505460E464FF47A746B69C5 +:102270005B6803F00103B34207D04FF47A7002F0B9 +:1022800011FD013CF3D1204670BD0120FCE70000A8 +:1022900030B54269936913F0700F16D000230B4CD0 +:1022A000936103F1840200EB421211794D0709D5C5 +:1022B000890707D5416954F823508D60117941F0A1 +:1022C000040111710133032BEBD130BD446C0008C4 +:1022D00073B51D46436916469A68D207044609D568 +:1022E0009A6801219960C2F34002CDE9006500219E +:1022F000FFF76AFE63699A68D1050BD59A684FF4B7 +:1023000080719960C2F34022CDE900650121204629 +:10231000FFF75AFE63699A68D2030BD59A684FF4A7 +:1023200080319960C2F34042CDE900650221204628 +:10233000FFF74AFE204602B0BDE87040FFF7A8BF95 +:10234000F8B50446466900296CD106F10C073868D7 +:1023500080076AD006EB01153868D5F8B00110F097 +:10236000040FD5F8B0011ABFC00840F00040400D7E +:10237000A061D5F8B0C11CF0020F1CBF40F0804036 +:10238000A061D5F8B40106EB011100F00F0084F84C +:102390002400D1F8B8012077D1F8B801000A60779D +:1023A000D1F8B801000CA077D1F8B801000EE077A1 +:1023B000D1F8BC0184F82000D1F8BC01000A84F8EF +:1023C0002100D1F8BC01000C84F82200D1F8BC1126 +:1023D000090E84F823103821396004F1340004F127 +:1023E000180104F1240551F8046B40F8046BA9426C +:1023F000F9D109880180C4E90A23214600232386F4 +:1024000051F8283B20461B6C984704F58052204623 +:1024100092F8C83043F0040382F8C830BDE8F840B1 +:10242000FFF736BF06F1100791E7F8BD10B5044677 +:1024300000F022FC02460B4652EA030102D0013AA8 +:1024400063F100030449086820B12146BDE810404B +:10245000FFF776BF10BD00BF14470020F8B500F5A8 +:1024600083511E46FFF7CEFCDFF844C0083100243C +:1024700004F1840500EB45152B795F070ED4DB06CC +:102480000CD5D1E900739742B34107D243695CF898 +:1024900024709F602B7943F004032B710134032CCB +:1024A00001F12001E4D1BDE8F840FFF7B1BC00BF65 +:1024B000446C000808B5FFF7A5FCFFF7E9FEBDE88E +:1024C0000840FFF7A5BC0000F8B5436905469868C9 +:1024D00000F0E050B0F1E05F0F461FD0E8B1FFF729 +:1024E00091FC05F583541034002606F1840305EBB6 +:1024F00043131B791A0706D50136032E04F1200475 +:10250000F3D1012007E05B07F6D42146384600F0FE +:1025100009FA0028F0D1FFF77BFCF8BD0120FCE7A9 +:1025200000F5805008B5FFF76DFCC06D00F03CFA77 +:10253000FFF76EFC43090CBF0120002008BD00001E +:10254000F8B51D46002313700F4606461446FFF7E4 +:10255000E7FF80F00100387025B129463046FFF7CB +:10256000B3FF2070F8BD00002DE9B8410C461546B8 +:102570001F46804600F080FB0B462178024609B9D1 +:10258000287850B14046FFF769FFFFF793FF3B46BD +:102590002A462146FFF7D4FF0120BDE8B88100009C +:1025A00010B5FFF72FFC174B1A6C42F000721A643B +:1025B0001A6A42F000721A621A6A00F5805422F018 +:1025C00000721A62FFF724FC94F8C830DB0718D4B5 +:1025D000B9B102211320FFF715FC01F005FC02211F +:1025E000142001F001FC0221152001F0FDFB94F8FC +:1025F000C83043F0010384F8C830BDE81040FFF74D +:1026000007BC10BD003802402DE9F04700F58055A9 +:1026100088B095F8C930012B04468846164600F26A +:10262000FB807E4F57F823200AB947F82300D7F8DC +:1026300000A0C4F80C802674BAF1000F09D141F251 +:10264000D00004F0D7F851468146FFF74DFDC7F89A +:10265000009095F8C930012B5DD001212046FFF78D +:102660009FFFFFF7CFFB6269136823F0020313603B +:102670006269136843F001031360636900275F61B7 +:1026800001212046FFF7C4FBFFF7ECFD002800F016 +:102690008480E86D00F076F904F58359BA4609F1B3 +:1026A0000809202200216846FFF702FB02A8FFF775 +:1026B00077FCCDF818A06A4609EB07030DF1180E58 +:1026C0009446BCE80300F44518605960624603F183 +:1026D0000803F5D1DCF80000186020379CF80420CE +:1026E0001A71602FDDD195F8C8306FF3820300278F +:1026F00085F8C8306A4641462046ADF80070ADF80E +:1027000002708DF80470FFF751FD6369C0B94FF492 +:1027100000421A6011E0386803685B6B9847014615 +:1027200000289AD13868FFF73BFF386803683246C3 +:102730005B684146984700288FD108B0BDE8F08714 +:1027400061221A609DF802309DF803201B061204D6 +:1027500002F4702203F040731343BDF80020C2F36B +:10276000090213439DF804201205022E02F4E00230 +:102770000CBF4FF000410021134362690B43D3614A +:10278000636913225A616269136823F001031360BD +:1027900039462046FFF766FD08B96369B7E795F843 +:1027A000C93093BB6169D1F8002242F00102C1F83F +:1027B00000226169D1F8002222F47C5222F00E023C +:1027C000C1F800226169D1F8002242F46062C1F8C8 +:1027D00000226269C2F814326269C2F80432626986 +:1027E00041F6FF71C2F80C126269C2F840326269A8 +:1027F000C2F8443263690122C3F81C226269D2F82C +:10280000003223F00103C2F8003295F8C83043F0DB +:10281000020385F8C83090E700208EE714470020B7 +:1028200008B500F029FA50EA0103024602D0421E20 +:1028300061F10001044B186810B10B46FFF748FD29 +:10284000BDE8084001F09EB91447002008B50020FB +:10285000FFF7ECFDBDE8084001F094B908B5012090 +:10286000FFF7E4FDBDE8084001F08CB90FB400208B +:1028700004B0704713B56C4684E80600031D94E865 +:10288000030083E80500012002B010BD73B5856820 +:10289000019155B11B885B0707D4D0E90036DB6B8B +:1028A0009847019AC1B23046A847012002B070BDD6 +:1028B000F0B5866889B005460C465EB1BDF8383083 +:1028C0005B070AD4D0E90037DB6B98472246C1B2D8 +:1028D0003846B047012009B0F0BD00220023CDE901 +:1028E00000230023ADF808300A4603AB01F10806C7 +:1028F000106851681C4603C40832B2422346F7D11F +:10290000106820609288A28000F0B8F90423ADF826 +:1029100008302B68CDE900011B6C694628469847B2 +:10292000D8E7000030B503680968DD0FB5EBD17F4B +:1029300023F0604421F060424FEAD1700BD0002BAD +:10294000B8BFA40C0029B8BF920C944202D034BF87 +:102950000120002030BD944205D1C1F38070C3F343 +:1029600080738342F6D194422CBF00200120F1E70E +:1029700010B5037C044613B9006803F073FF2046CA +:1029800010BD00000023BFF35B8FC360BFF35B8FFC +:10299000BFF35B8F8360BFF35B8F7047BFF35B8FC9 +:1029A0000068BFF35B8F704770B505460C30FFF7CA +:1029B000F5FF05F1080604463046FFF7EFFFA04299 +:1029C00006D930466D68FFF7E9FF2544281A70BD27 +:1029D0003046FFF7E3FF201AF9E7000070B505461F +:1029E000406898B105F10800FFF7D8FF05F10C0623 +:1029F00004463046FFF7D2FF8442304694BF6D68EC +:102A00000025FFF7CBFF013C2C44201A70BD0000CD +:102A100038B50C460546FFF7C7FFA04210D305F1B5 +:102A20000800FFF7BBFF04446868B4FBF0F100FB4B +:102A30001144BFF35B8F0120AC60BFF35B8F38BDE7 +:102A40000020FCE72DE9F041144607460D46FFF74C +:102A5000C5FF844228BF0446D4B1B84658F80C6B71 +:102A60004046FFF79BFF3044286040467E68FFF7F2 +:102A700095FF331A9C4203D86C600120BDE8F081B9 +:102A80006B60A41B3B68AB602044E8600220F5E764 +:102A90002046F3E738B50C460546FFF79FFFA042F6 +:102AA00010D305F10C00FFF779FF04446868B4FB0C +:102AB000F0F100FB1144BFF35B8F0120EC60BFF32A +:102AC0005B8F38BD0020FCE72DE9FF418846694651 +:102AD0000746FFF7B7FF6C4606B204EBC6060025B3 +:102AE000B44209D06268206808EB0501FFF7BAF824 +:102AF000636808341D44F3E729463846FFF7CAFFE8 +:102B0000284604B0BDE8F081F8B505460C300F4604 +:102B1000FFF744FF05F1080604463046FFF73EFF85 +:102B2000A042304688BF6C68FFF738FF201A386033 +:102B300020B130462C68FFF731FF2044F8BD00007B +:102B400073B5144606460D46FFF72EFF844228BF94 +:102B500004460190DCB101A93046FFF7D5FF019B87 +:102B600033B93268C5E90233C5E9002401200CE01D +:102B70009C4238BF01942860019868608442F5D96E +:102B80003368AB60241AEC60022002B070BD2046AE +:102B9000FBE700002DE9FF410F466946FFF7D0FF34 +:102BA0006C4600B204EBC0050026AC4209D0D4F854 +:102BB000048054F8081BB8194246FFF753F84644FE +:102BC000F3E7304604B0BDE8F081000038B50546B3 +:102BD000FFF7E0FF044601462846FFF719FF2046AD +:102BE00038BD000000B59BB0EFF30981682268464C +:102BF000FFF738F8EFF30583044B9A6BDA6A9A6AA9 +:102C00009A6A9A6A9A6A9A6A9B6AFEE700ED00E0FD +:102C100000B59BB0EFF3098168226846FFF722F800 +:102C2000EFF30583044B9A6B9A6A9A6A9A6A9A6AD6 +:102C30009A6A9B6AFEE700BF00ED00E000B59BB01A +:102C4000EFF3098168226846FFF70CF8EFF305837C +:102C5000034B5A6B9A6A9A6A9A6A9A6A9B6AFEE767 +:102C600000ED00E0FEE700000FB408B5029801F0A7 +:102C7000A9FFFEE702F0E0BB02F0B8BB02F0B6BB72 +:102C800030B5094D0A4491420DD011F8013B58402E +:102C9000082340F30004013B2C4013F0FF0384EAB7 +:102CA0005000F6D1EFE730BD2083B8EDF7B54FF017 +:102CB000FF33DFF854C0DFF854E000EB81011A461F +:102CC00088421CD050F8044B019401AF042417F83B +:102CD000015B82EA05620825DB18164605F1FF351F +:102CE0005241002EBCBF83EA0C0382EA0E0215F0AB +:102CF000FF05F1D1013C14F0FF04E8D1E0E7D8432F +:102D0000D14303B0F0BD00BF9336EAA9EBE1F04236 +:102D10002DE9F041C56915B9C161BDE8F0814B6885 +:102D200023F06047C3F38A464FEAD37EC3F380782B +:102D300016EA230638BF3E46AC462B465A68BEEB21 +:102D4000D27F22F060440AD0002A18DAA40CB442E0 +:102D500017D19D420FD10D60DEE71346EEE7A74283 +:102D600007D102F08044C2F3807242450BD054B1C7 +:102D7000EFE708D2EDE7CCF800100B60CDE7B442E6 +:102D800001D0B442E5D81A689C46002AE5D1196002 +:102D9000C3E700002DE9F047089D01F007044FEA62 +:102DA000D508224405F0070500EBD1004FF47F4918 +:102DB000944201D1BDE8F08704F0070705F0070A47 +:102DC00057453E4638BF5646C6F10806111B8E428F +:102DD00028BF0E46E10808EBD50E415C13F80EC083 +:102DE000B94029FA06F721FA0AF1FFB28CEA01018B +:102DF00047FA0AF739408CEA010C03F80EC0344454 +:102E00003544D5E780EA0120082341F2210201B2CE +:102E10004000002980B203F1FF33B8BF504013F0E7 +:102E2000FF03F4D17047000038B50C468D18A54259 +:102E300000D138BD14F8011BFFF7E4FFF7E70000ED +:102E400002684AB113680360C388018901339BB2E9 +:102E50009942C38038BF03811046704770B588B06F +:102E6000202204460D4668460021FEF721FF204639 +:102E70000495FFF7E5FF024658B16B46054608AEDC +:102E80001C4603CCB44228606960234605F108055E +:102E9000F6D1104608B070BD082817D909280CD003 +:102EA0000A280CD00B280CD00C280CD00D280CD0E4 +:102EB0000E2814BF4020302070470C20704710208F +:102EC000704714207047182070472020704700007A +:102ED000082817D90C280CD910280CD914280CD97B +:102EE00018280CD920280CD930288CBF0F200E2090 +:102EF0007047092070470A2070470B2070470C204C +:102F000070470D207047000010B54B6823B9CA8A7E +:102F100063F30902CA8210BDC4681A681C60C360EA +:102F2000438A013B43824A60EFE700002DE9F84FF6 +:102F30001D46CB8A0F46C3F30901062981469246F6 +:102F40000B4630D00020AAB207F119049EB2052E1C +:102F50001FFA80F80FD8904503F1010306D3FB8ACE +:102F60000A4462F30903FB8201201AE01AF80060A8 +:102F7000E6540130EAE79045F1D2A1F1060B1C239B +:102F80007C68BBFBF3F203FB12BB1FFA8BF6002C31 +:102F900045D14846FFF754FF044638B978606FF0D2 +:102FA0000200BDE8F88F4FF00008E6E70026066053 +:102FB0007860ADB24FF0000B454510D90AEB08031D +:102FC000221D13F8011B9155B1B208F101081B290C +:102FD0001FFA88F82BD0454506F10106F1D8FB8A87 +:102FE000C3F30902154465F30903BCE7013292B249 +:102FF0001C462368002BF9D1AB1F0B441C21B3FBEB +:10300000F1F301339BB29A42D3D2BBF1000FD0D17E +:103010004846FFF715FF20B9C4F800B0BFE701220A +:10302000E7E7C0F800B05E4620600446C1E74545CA +:10303000D5D94846FFF704FF08B92060AFE7C0F8CC +:1030400000B0002620600446B6E700002DE9F04FEE +:103050002DED028B83B0CDE90013BDF83C5007463F +:103060009146002A00F092802DB10E9B002B00F0BB +:103070008D80072D32D807F10C00FFF7E1FE0446E2 +:1030800038B96FF00204204603B0BDEC028BBDE8F6 +:10309000F08F14220021FEF70BFE0E992A4604F150 +:1030A0000800FEF7DFFD681CC0B2FFF711FFFFF755 +:1030B000F3FE207499F80030013814FA80F003F020 +:1030C0001F0363F03F030372009B43F00041616004 +:1030D00038462146FFF71CFE0124D4E700F10C031B +:1030E0004FF0000808EE103A4FF0800A464644467A +:1030F00018EE100AFFF7A4FE83460028C1D0142260 +:103100000021FEF7D5FDC6BB019BABF808300220BD +:103110000E9B00F1080299195BFA82F20130C0B2ED +:10312000082801D0AE422AD3FFF7D2FEFFF7B4FE43 +:1031300099F80020009B411E02F01F0242EA48124B +:10314000AE4208BF4FF0400A5BFA81F14AEA020A38 +:1031500043F0004281F808A08BF81000CBF804205F +:1031600059463846FFF7D4FD0134AE4224B288F008 +:1031700001084FF0000ABBD185E70020C8E711F82D +:1031800001CB02F801CB0136B6B2C7E76FF00104FC +:1031900079E70000F8B515460E46282200210446BE +:1031A0001F46FEF785FD069B6360B5F5001F079B74 +:1031B000A76034BF6A094FF6FF72236204F10C0066 +:1031C00097B200239A4205D80023036027826382C6 +:1031D000A382F8BD0660013330462036F2E70000D6 +:1031E00003781BB94BB2002BC8BF017070470000B9 +:1031F000007870472DE9F74FDDF83C90BDF830506E +:103200000D9E9DF83840BDF84070804692469B4622 +:10321000B9F1000F01D1002F51D11F2C4FD898F8D0 +:103220000000B0B9072F47D835F0030347D13A461D +:1032300049464FF6FF70FFF7F7FD20F001002D0221 +:10324000400445EA0464400C44EA40244FF6FF730E +:1032500021E040EA0520072F40EA0464F6D9002562 +:103260004FF6FF73C5F12000A5F120022AFA05F1FF +:103270000BFA00F001432BFA02F211431846C9B2CF +:10328000FFF7C0FD0835402D0346EBD13A464946CD +:10329000FFF7CAFD0346CDE9009732462146404676 +:1032A000FFF7D4FE33780133DBB21F2B88BF002336 +:1032B000337003B0BDE8F08F6FF00300F9E76FF0F3 +:1032C0000100F6E72DE9F04F85B09246DDF8488021 +:1032D0000F9D9DF840209DF84490BDF84C70064627 +:1032E0009B46B8F1000F01D1002F48D11F2A46D8C4 +:1032F0003378002B46D00C0244EA02649DF8381063 +:1033000044EAC93444EA01441C43072F44F08004D2 +:1033100032D900234FF6FF72C3F1200CA3F1200035 +:103320002AFA03F10BFA0CFC41EA0C012BFA00F02B +:103330000143C9B210460393FFF764FD039B0833B2 +:10334000402B0246E8D13A464146FFF76DFD034661 +:10335000CDE900872A4621463046FFF777FEB9F1CE +:10336000010F06D12B780133DBB21F2B88BF00235E +:103370002B7005B0BDE8F08F4FF6FF73E8E76FF0F4 +:103380000100F6E76FF00300F3E70000C06900B149 +:1033900004307047C3691A68C261C2681A60C360AA +:1033A000438A013B438270472DE9F041D0F81880F1 +:1033B000194E14461D464146002709B9BDE8F08163 +:1033C000D1E90223A21A65EB0303964277EB0303CC +:1033D0001ED283698B420DD1FFF796FD83691B686E +:1033E0008361C3680B60438AC1608169013B43828A +:1033F0008846E2E7FFF788FD0B68C8F80030C3682D +:103400000B60438AC160013B4382D8F80010D4E7C7 +:1034100088460968D1E700BF80841E002DE9F04F7F +:103420008BB00D46DDF8509014469B468046002830 +:1034300000F01981B9F1000F00F01581531E3F2BE8 +:1034400000F21181012A03D1BBF1000F40F00B8182 +:103450000023CDE90833B8F81430B5EBC30F4FEAB9 +:10346000C30703D300200BB0BDE8F08F2B199F4298 +:10347000D8F80C303ABF7F1BFFB227461BB9D8F8EB +:103480001030002B7AD02F2D4ED8C5F13006B74220 +:103490004FF000032CBFF6B23E4600932946D8F801 +:1034A000080008AB3246FFF775FCA7EB060A354467 +:1034B0005FFA8AFAB8F8143003F10053063BDB00D8 +:1034C0000493D8F80C3003933021039B13B1BAF165 +:1034D000000F2CD1D8F8100040B1BAF1000F05D080 +:1034E000009608AB5246691AFFF754FC38B2002F19 +:1034F000B8D066070AD00AAB03EBD401624211F8D8 +:10350000083C02F00702134101F8083C082C3CD9A2 +:10351000102C40F2B580202C40F2B780BBF1000F98 +:1035200000F09C80082334E0BA460026C2E7049BE2 +:10353000E02B28BFE02306930B44AB42059314D93C +:103540005A1B03980096924534BF5246D2B2691A6C +:1035500008AB04300792FFF71DFC079A1644AAEB4C +:10356000020A1544F6B25FFA8AFA049B069A059994 +:103570009B1A0493039B1B680393A6E70093D8F858 +:10358000080008AB3A462946AEE7BBF1000F13D05E +:103590000123B4EBC30F6CD0082C12D89DF8203057 +:1035A000621E23FA02F2D50706D54FF0FF3202FA67 +:1035B00004F423438DF820309DF8203089F8003042 +:1035C00051E7102C12D8BDF82030621E23FA02F207 +:1035D000D10706D54FF0FF3202FA04F42343ADF8C9 +:1035E0002030BDF82030A9F800303CE7202C0FD85F +:1035F0000899631E21FA03F3DA0705D54FF0FF326D +:1036000002FA04F40C430894089BC9F800302AE736 +:10361000402C2BD0DDE90865611EC4F12102A4F124 +:10362000210326FA01F105FA02F225FA03F3114308 +:103630001943CB0712D50122A4F12003C4F12001C4 +:1036400002FA03F322FA01F1A240524243EA0103D3 +:1036500063EB430332432B43CDE90823DDE9082321 +:10366000C9E90023FFE66FF00100FCE66FF00800F7 +:10367000F9E6082CA0D9102CB3D9202CEED8C3E73A +:10368000BBF1000FADD0022383E7BBF1000FBBD02D +:1036900004237EE730B5012A144638BF0124402CAC +:1036A00085B028BF40240025012ACDE9025518D84D +:1036B0001B788DF8083063070AD004AB03EBD40500 +:1036C000624215F8083C02F00702934005F8083CF6 +:1036D000009103462246002102A8FFF75BFB05B0DC +:1036E00030BD082AE4D9102A03D81B88ADF8083069 +:1036F000E1E7202A8DBFD3E900231B680293CDE9BF +:103700000223D8E710B5CB681BB98B600B618B82A5 +:1037100010BDC4681A681C60C360438A013B4382C1 +:10372000CA60F0E72DE9F04FD1F8008093B018F0AF +:10373000800FCDE90323C8F3C01219BFC8F3C03B03 +:10374000C8F306264FF0020B1646B8F1000F0446E8 +:103750000D4680F2D18118F0C043059340F0CC8132 +:103760000B7B002B00F0C881BBF1020F03D0017866 +:10377000B14240F0C48108F07F0106916AB3C8F3FA +:10378000074A2B44069A93F80390760646EA0B46BE +:1037900046EA82465FEAD91346EA0A06079300F032 +:1037A000908000220023CDE90A23069B00936768DE +:1037B0005B4652460AA92046B84700287ED0A76932 +:1037C0009FB9314604F10C00FFF748FB0746E0B90A +:1037D0006FF0020013B0BDE8F08FC8F30F2A18F0A5 +:1037E0007F0F08BF0AF0030ACBE73B699E420DD06A +:1037F0003F68002FF9D1314604F10C00FFF72EFB92 +:1038000007460028E4D0A3693B60A761DDE90A23ED +:1038100000264FF6FF70C6F1200E22FA06F103FAD9 +:103820000EFEA6F1200C23FA0CFC41EA0E0141EA3F +:103830000C01C9B2083609920893FFF7E3FA402E4B +:10384000DDE90832E7D1B882FB7D09F01F06C3F33A +:1038500084039B1BD7E9022198B2002BBCBF00F167 +:1038600020031BB252EA0100C8F304680FD003988A +:10387000821A049860EB0101A74890424FF00002C1 +:103880008A4104D3079A002A5BD0012B23DDFA7DFD +:103890004FEA890302F0030203F07C031343FB7534 +:1038A00039462046FFF730FB079BA3B9FB7DC3F3E6 +:1038B0008402013262F38603FB7504E06FF00B00B3 +:1038C00088E7A76917B96FF00C0083E73B699E4250 +:1038D000BAD03F68F6E719F0400F32D0039BBB60C7 +:1038E000049BFB60142200210DA8FEF7E1F9039B65 +:1038F0000A93049B0B932B1D0C932B7BADF83EA0DE +:10390000013BDBB2ADF83C30069B8DF8433094F8B8 +:1039100024308DF840B083F001038DF844308DF8E9 +:103920004160A3688DF842800AA920469847FB7D34 +:10393000C3F38403013303F01F039B02FB820020C7 +:1039400048E7FB7DC9F34012B2EBD31F40F0DA80A9 +:10395000C3F38403B34240F0D88007992B7B4FEA2E +:103960009912002934D0D20741D4032B40F2D080E1 +:10397000039BBB60049BFB602B7BAE1D033BDBB258 +:103980003246394604F10C00FFF7D0FA00280DDA70 +:1039900020463946FFF7B8FAFB7DC3F384030133B1 +:1039A00003F01F039B02FB82032013E7AB883B83DA +:1039B0002A7B033AB88AD2B23146FFF735FAFB7D4B +:1039C000B882DA43C2F3C01262F3C713FB75B6E7DD +:1039D0006AB92E1D013BDBB23246394604F10C00B8 +:1039E000FFF7A4FA0028D3DB2A7B013AE2E7F98A41 +:1039F000C1F30901013B0529DAB259D8281D00237A +:103A000007F11A0C9A4208D910F801EB0CF801E002 +:103A1000013101330629DBB2F4D103990A910499EB +:103A20000B91934207F11A010C9138BF0433796866 +:103A30000D9134BF55FA83F300230E93FB8AADF842 +:103A40003EA0C3F309031A44069B8DF8433094F853 +:103A50002430ADF83C2083F001038DF8443000237E +:103A60008DF840B08DF841608DF842807B602A7BF4 +:103A7000B88A013A291DFFF7D7F93B8BB8828342F8 +:103A800003D1A3680AA92046984720460AA9FFF750 +:103A900039FEFB7DB88AC3F38403013303F01F03AF +:103AA0009B02FB823B8B984214BF1120002091E6C1 +:103AB0007B68002BB1D0062001E01C306346D3F8B0 +:103AC00000C0BCF1000FF8D1091A081D05F1040C63 +:103AD00000EB030905989DF8143001EB000EBEF1D0 +:103AE0001B0F9AD89A4298D91CF8013B09F8013B60 +:103AF000059B01330593EDE76FF009006AE66FF06F +:103B00000A0067E66FF00D0064E66FF00E0061E6F4 +:103B10006FF00F005EE600BF80841E00EFF30983A4 +:103B200005494A6B22F001024A63683383F309882E +:103B3000002383F31188704700EF00E0202080F31A +:103B4000118862B60C4B0D4AD96821F4E061090472 +:103B5000090C0A43DA60D3F8FC20094942F080726C +:103B6000C3F8FC200A6842F001020A601022DA77EA +:103B700083F82200704700BF00ED00E00003FA0563 +:103B8000001000E010B5202383F311880E4B5B6812 +:103B900013F4006314D0F1EE103AEFF30984683C9B +:103BA0004FF08073E361094BDB6B236684F3098874 +:103BB00000F0BAFF10B1064BA36110BD054BFBE747 +:103BC00083F31188F9E700BF00ED00E000EF00E0AB +:103BD0004B0600084E060008024AD36843F0C003B3 +:103BE000D360704700440040044B5A6810439A6801 +:103BF00058600AB1181D1047704700BF20470020C9 +:103C00002DE9F0413C4ED6F85C52EF682B68DA059E +:103C10009CB20CD5202383F311884FF40070FFF77A +:103C2000E3FF6FF480732B60002383F3118820235C +:103C300083F31188DFF8C08014F02F0339D183F3A8 +:103C40001188380613D5210611D5202383F3118856 +:103C50002A4800F0EFF900284CDA0820FFF7C4FFEB +:103C60004FF67F733B40EB60002383F311887A06A5 +:103C700015D5630613D5202383F31188D6E91323C2 +:103C80009A4209D1336C3BB127F040073F04102022 +:103C90003F0CFFF7A9FFEF60002383F31188D6F8EC +:103CA0006422D3680BB110699847BDE8F041FFF773 +:103CB00069BF230712D014F0080F0CBF002080202A +:103CC000E10748BF40F02000A20748BF40F0400095 +:103CD000630748BF40F48070FFF786FFA4066B6857 +:103CE00005D596F860124046194000F053FA2C684A +:103CF000A4B2A1E76860B7E720470020584700203A +:103D000010B5054C054A0021204600F013FA044B7B +:103D1000C4F85C3210BD00BF20470020D93B00082A +:103D20000044004038B52A4C037C002918BF0C46DB +:103D3000012B0546C0F8644210D1264B98420DD1A4 +:103D4000254B1A6C42F400321A641A6E42F40032A7 +:103D50001A660B2126201B6E00F046F8D5F85C226F +:103D60001E4923688A424FEA530003D001F580615F +:103D70008A422AD11A490144B4F90400B1FBF3F391 +:103D80000028BEBF23F0070003F0070343EA400307 +:103D9000A1889360E38843F040031361238943F0D3 +:103DA0000103536141F4045343F02C03D36001F445 +:103DB000A05100231360B1F5806F136853680CBFE6 +:103DC0007F23FF2385F8603238BD0649D3E700BF63 +:103DD0009C6C000820470020003802400010014081 +:103DE00000BD010580DE800200F1604303F5614300 +:103DF0000901C9B283F80013012200F01F039A40A1 +:103E000043099B0003F1604303F56143C3F880213C +:103E10001A607047F8B5154682680669AA420B46D3 +:103E2000816938BF8568761AB54204460BD21846B8 +:103E30002A46FDF717FFA3692B44A361A3685B1B08 +:103E4000A3602846F8BD0CD918463246FDF70AFF94 +:103E5000AF1BE1683A463044FDF704FFE3683B449A +:103E6000EBE718462A46FDF7FDFEE368E5E70000AC +:103E700083689342F7B51546044638BF8568D0E994 +:103E80000460361AB5420BD22A46FDF7EBFE636991 +:103E90002B446361A36828465B1BA36003B0F0BD9D +:103EA0000DD932460191FDF7DDFE0199E068AF1BA7 +:103EB0003A463144FDF7D6FEE3683B44E9E72A463B +:103EC000FDF7D0FEE368E4E710B50A440024C361BF +:103ED000029B8460C0E90000C0E90511C160026175 +:103EE000036210BD08B5D0E90532934201D1826862 +:103EF00082B98268013282605A1C42611970D0E92D +:103F000004329A4224BFC3684361002100F0E6FEF8 +:103F1000002008BD4FF0FF30FBE7000070B5202304 +:103F200004460E4683F31188A568A5B1A368A2696B +:103F3000013BA360531CA36115782269934224BFFF +:103F4000E368A361E3690BB120469847002383F33C +:103F50001188284607E03146204600F0AFFE0028D1 +:103F6000E2DA85F3118870BD2DE9F74F04460E465D +:103F700017469846D0F81C904FF0200A8AF3118813 +:103F80004FF0000B154665B12A4631462046FFF733 +:103F900041FF034660B94146204600F08FFE0028ED +:103FA000F1D0002383F31188781B03B0BDE8F08FB4 +:103FB000B9F1000F03D001902046C847019B8BF355 +:103FC0001188ED1A1E448AF31188DCE7C0E9051157 +:103FD000C160C3611144009B8260C0E900000161BF +:103FE00003627047F8B504460D461646202383F356 +:103FF0001188A768A7B1A368013BA36063695A1C35 +:1040000062611D70D4E904329A4224BFE36863619F +:10401000E3690BB120469847002080F3118807E040 +:104020003146204600F04AFE0028E2DA87F3118884 +:10403000F8BD0000D0E905239A4210B501D182688D +:104040007AB98268013282605A1C82611C780369E5 +:104050009A4224BFC3688361002100F03FFE2046DE +:1040600010BD4FF0FF30FBE72DE9F74F04460E4639 +:1040700017469846D0F81C904FF0200A8AF3118812 +:104080004FF0000B154665B12A4631462046FFF732 +:10409000EFFE034660B94146204600F00FFE0028BF +:1040A000F1D0002383F31188781B03B0BDE8F08FB3 +:1040B000B9F1000F03D001902046C847019B8BF354 +:1040C0001188ED1A1E448AF31188DCE70268436800 +:1040D0001143016003B11847704700001430FFF727 +:1040E00043BF00004FF0FF331430FFF73DBF000027 +:1040F0003830FFF7B9BF00004FF0FF333830FFF71B +:10410000B3BF00001430FFF709BF00004FF0FF31CC +:104110001430FFF703BF00003830FFF763BF000023 +:104120004FF0FF323830FFF75DBF000000207047CE +:10413000FFF7E6BD37B515460E4A02600022426021 +:10414000C0E902220122044602740B46009000F1ED +:104150005C014FF480721430FFF7B6FE00942B46DA +:104160004FF4807204F5AE7104F13800FFF72EFFB2 +:1041700003B030BDB06C000810B52023044683F3B3 +:104180001188FFF7CFFD02232374002383F31188E6 +:1041900010BD000038B5C36904460D461BB90421A3 +:1041A0000844FFF793FF294604F11400FFF79AFE35 +:1041B000002806DA201D4FF48061BDE83840FFF783 +:1041C00085BF38BD026843681143016003B11847D9 +:1041D0007047000013B5446BD4F894341A68117812 +:1041E000042915D1217C022912D1197912890123C0 +:1041F0008B4013420CD101A904F14C0001F078FF6F +:10420000D4F89444019B21790246206800F0CEF94D +:1042100002B010BD143001F0FBBE00004FF0FF33C0 +:10422000143001F0F5BE00004C3001F0CDBF0000AD +:104230004FF0FF334C3001F0C7BF0000143001F0E5 +:10424000C9BE00004FF0FF31143001F0C3BE0000C2 +:104250004C3001F099BF00004FF0FF324C3001F0BC +:1042600093BF00000020704710B5D0F894341A684E +:1042700011780429044617D1017C022914D15979F7 +:10428000528901238B4013420ED1143001F05CFEA1 +:10429000024648B1D4F894444FF4807361792068A1 +:1042A000BDE8104000F070B910BD0000406BFFF792 +:1042B000DBBF0000704700007FB5124B0360002396 +:1042C0004360C0E90233012502260F4B0574044602 +:1042D0000290019300F18402294600964FF4807306 +:1042E000143001F00DFE094B0294CDE9006304F592 +:1042F00023724FF48073294604F14C0001F0D4FE80 +:1043000004B070BDD86C0008AD420008D54100086B +:104310000B68202282F311880A7903EB82029061F4 +:104320004A79093243F822008A7912B103EB8203F9 +:10433000986102230374C0F89414002383F3118856 +:104340007047000038B5037F044613B190F854302D +:10435000ABB9201D01250221FFF734FF04F1140041 +:1043600025776FF0010100F0C5FC84F8545004F18A +:104370004C006FF00101BDE8384000F0BBBC38BD17 +:1043800010B5012104460430FFF71CFF00232377FA +:1043900084F8543010BD000038B5044600251430B0 +:1043A00001F0C6FD04F14C00257701F095FE201DBB +:1043B00084F854500121FFF705FF2046BDE838403E +:1043C000FFF752BF90F8443003F06003202B07D171 +:1043D00090F84520212A4FF0000303D81F2A06D861 +:1043E00000207047222AFBD1C0E90E3303E0034AC4 +:1043F00082630722C2630364012070471D230020EB +:1044000037B5D0F894341A681178042904461AD1C3 +:10441000017C022917D11979128901238B4013429B +:1044200011D100F14C05284601F016FF58B101A941 +:10443000284601F05DFED4F89444019B21790246A0 +:10444000206800F0B3F803B030BD0000F0B500EB19 +:10445000810385B09E6904460D46FEB1202383F397 +:10446000118804EB8507301D0821FFF7ABFEFB68C0 +:104470005B691B6806F14C001BB1019001F046FE20 +:10448000019803A901F034FE024648B1039B294676 +:10449000204600F08BF8002383F3118805B0F0BDAF +:1044A000FB685A691268002AF5D01B8A013B134049 +:1044B000F1D104F14402EAE7093138B550F821405E +:1044C000DCB1202383F31188D4F894241368527943 +:1044D00003EB8203DB689B695D6845B104216018CA +:1044E000FFF770FE294604F1140001F037FD204665 +:1044F000FFF7BAFE002383F3118838BD7047000030 +:1045000001F0FAB8012303700023C0E90133C3614D +:1045100083620362C36243620363704738B5044633 +:10452000202383F311880025C0E90355C0E9055510 +:10453000416001F0F1F80223237085F3118838BD42 +:1045400070B500EB810305465069DA600E461446EB +:1045500018B110220021FDF7ABFBA06918B11022A1 +:104560000021FDF7A5FB31462846BDE8704001F06B +:104570009DB90000826802F0011282600022C0E949 +:104580000422826101F01EBAF0B400EB8104478975 +:10459000E4680125A4698D403D43458123600023E3 +:1045A000A2606360F0BC01F039BA0000F0B400EB27 +:1045B00081040789E468012564698D403D430581D4 +:1045C00023600023A2606360F0BC01F0B3BA000076 +:1045D00070B50223002504460370C0E90255C0E906 +:1045E0000455C564856180F8345001F0FBF86368B8 +:1045F0001B6823B129462046BDE87040184770BDAE +:10460000037880F850300523037043681B6810B5A9 +:1046100004460BB1042198470023A36010BD00009D +:1046200090F85020436802701B680BB105211847B1 +:104630007047000070B590F83430044613B1002381 +:1046400080F8343004F14402204601F0DDF963685B +:104650009B68B3B994F8443013F0600535D000215D +:10466000204601F02FFC0021204601F021FC636868 +:104670001B6813B1062120469847062384F834307E +:1046800070BD204698470028E4D0B4F84A30E26B69 +:104690009A4288BFE36394F94430E56B002B4FF0F6 +:1046A000200380F20381002D00F0F280092284F8BB +:1046B000342083F311880021D4E90E232046FFF72C +:1046C00075FF002383F31188DAE794F8452003F09F +:1046D0007F0343EA022340F20232934200F0C58096 +:1046E00021D8B3F5807F48D00DD8012B3FD0022BC5 +:1046F00000F09380002BB2D104F14C02A26302229D +:10470000E2632364C1E7B3F5817F00F09B80B3F5DA +:10471000407FA4D194F84630012BA0D1B4F84C309E +:1047200043F0020332E0B3F5006F4DD017D8B3F574 +:10473000A06F31D0A3F5C063012B90D8636894F8C3 +:1047400046205E6894F84710B4F848302046B047D9 +:10475000002884D04368A3630368E3631AE0B3F5D9 +:10476000106F36D040F6024293427FF478AF5C4B34 +:10477000A3630223E3630023C3E794F84630012BCD +:104780007FF46DAFB4F84C3023F00203C4E90E554A +:10479000A4F84C30256478E7B4F84430B3F5A06F42 +:1047A0000ED194F8463084F84E30204601F072F86D +:1047B00063681B6813B101212046984703232370C7 +:1047C0000023C4E90E339CE704F14F03A3630123E4 +:1047D000C3E72378042B10D1202383F311882046CC +:1047E000FFF7C8FE85F311880321636884F84F50F2 +:1047F00021701B680BB12046984794F84630002B77 +:10480000DED084F84F300423237063681B68002BCC +:10481000D6D0022120469847D2E794F848301D06AA +:1048200003F00F0120460AD501F0E0F8012804D07A +:1048300002287FF414AF2B4B9AE72B4B98E701F03B +:10484000C7F8F3E794F84630002B7FF408AF94F8EC +:10485000483013F00F01B3D01A06204602D501F0FC +:1048600045FBADE701F038FBAAE794F84630002B92 +:104870007FF4F5AE94F8483013F00F01A0D01B067A +:10488000204602D501F01EFB9AE701F011FB97E7E5 +:10489000142284F8342083F311882B462A462946B3 +:1048A0002046FFF771FE85F31188E9E65DB1152218 +:1048B00084F8342083F311880021D4E90E232046A4 +:1048C000FFF762FEFDE60B2284F8342083F31188A3 +:1048D0002B462A4629462046FFF768FEE3E700BF3D +:1048E000086D0008006D0008046D000838B590F8E8 +:1048F00034300446002B3ED0063BDAB20F2A34D8BF +:104900000F2B32D8DFE803F0373131082232313152 +:104910003131313131313737C56BB0F84A309D42D2 +:1049200014D2C3681B8AB5FBF3F203FB12556DB9B1 +:10493000202383F311882B462A462946FFF736FEAB +:1049400085F311880A2384F834300EE0142384F8A8 +:104950003430202383F3118800231A461946204659 +:10496000FFF712FE002383F3118838BD036C03B1F7 +:1049700098470023E7E70021204601F0A3FA002131 +:10498000204601F095FA63681B6813B106212046A2 +:1049900098470623D7E7000010B590F83430142B61 +:1049A000044629D017D8062B05D001D81BB110BD5D +:1049B000093B022BFBD80021204601F083FA00219D +:1049C000204601F075FA63681B6813B10621204682 +:1049D0009847062319E0152BE9D10B2380F83430D2 +:1049E000202383F3118800231A461946FFF7DEFDC2 +:1049F000002383F31188DAE7C3689B695B68002BA7 +:104A0000D5D1036C03B19847002384F83430CEE746 +:104A1000024B0022C3E900339A60704788490020A6 +:104A2000002303748268054B1B6899689142FBD28E +:104A30005A680360426010605860704788490020DF +:104A400008B5202383F31188037C032B05D0042BA6 +:104A50000DD02BB983F3118808BD436900221A6079 +:104A60004FF0FF334361FFF7DBFF0023F2E7D0E9AC +:104A7000003213605A60F3E7002303748268054B29 +:104A80001B6899689142FBD85A68036042601060C5 +:104A90005860704788490020054B196908741868E8 +:104AA00002681A605360186101230374FBF7B8BDF4 +:104AB0008849002030B54B1C0B4D87B0044610D000 +:104AC0002B690A4A01A800F031F92046FFF7E4FFFC +:104AD000049B13B101A800F065F92B69586907B070 +:104AE00030BDFFF7D9FFF8E788490020414A0008A8 +:104AF00038B50C4D41612B6981689A689142044632 +:104B000003D8BDE83840FFF78BBF1846FFF7B4FF66 +:104B100001232C61014623742046BDE83840FBF791 +:104B20007FBD00BF88490020044B1A681B6990684C +:104B30009B68984294BF002001207047884900205C +:104B400010B5084C236820691A682260546001225D +:104B500023611A74FFF790FF01462069BDE81040F9 +:104B6000FBF75EBD8849002008B5FFF7DDFF18B1EF +:104B7000BDE80840FFF7E4BF08BD0000FFF7E0BF55 +:104B8000FEE7000010B50C4CFFF742FF00F0C0F844 +:104B90000A498022204600F047F8012344F8180C07 +:104BA0000374FEF7CBFF002383F3118862B6044839 +:104BB000BDE8104000F058B8B04900200C6D000866 +:104BC0001C6D000808B572B6034B586200F0FEFB7E +:104BD00000F0B0FCFEE700BF8849002000F01CB9DF +:104BE000EFF3118020B9EFF30583202282F31188BF +:104BF0007047000010B530B9EFF30584C4F3080422 +:104C000014B180F3118810BDFFF7AEFF84F3118853 +:104C1000F9E70000034A516853685B1A9842FBD8D1 +:104C2000704700BF001000E08260022202827047DD +:104C30008368A3F17C0243F80C2C026943F83C2CF6 +:104C4000426943F8382C074A43F81C2CC26843F8E1 +:104C5000102C022203F8082C002203F8072CA3F1E1 +:104C6000180070473906000810B5202383F3118817 +:104C7000FFF7DEFF00210446FFF73AFF002383F32E +:104C80001188204610BD0000024B1B6958610F209F +:104C9000FFF702BF88490020202383F31188FFF724 +:104CA000F3BF000008B50146202383F311880820D4 +:104CB000FFF700FF002383F3118808BD49B1064BBD +:104CC00042681B6918605A60136043600420FFF754 +:104CD000F1BE4FF0FF3070478849002003689842CA +:104CE00006D01A680260506059611846FFF798BEF6 +:104CF0007047000038B504460D462068844200D154 +:104D000038BD036823605C604561FFF789FEF4E706 +:104D1000054B03F11402C3E905224FF0FF310022D5 +:104D2000C3E90712704700BF8849002070B51C4EC8 +:104D3000C0E9032305460C4601F0C0FA334653F898 +:104D4000142F9A420DD13062C5E901242A600A2C41 +:104D50002CBF00190A30C6E90555BDE8704001F0C6 +:104D60009BBA316A431AE31838BF1C469368A342C2 +:104D700002D9081901F09EFA73699A6894420CD816 +:104D80005A68AC602B606A6015609A685D60121B9F +:104D90009A604FF0FF33F36170BD1B68A41AECE713 +:104DA0008849002038B51B4C636998420DD0D0E982 +:104DB000003213605A6000228168C2609A680A4417 +:104DC0009A604FF0FF33E36138BD2246036842F832 +:104DD000143F002193425A60C16003D1BDE83840BE +:104DE00001F062BA9A688168256A0A449A6001F003 +:104DF00065FA63699A68411B8A42E5D9AB181D1AA6 +:104E0000092D206A98BF01F10A02BDE8384010441C +:104E100001F050BA884900202DE9F041184C0027D4 +:104E200004F11406656901F049FA236AAA68C11AF7 +:104E30008A4215D813442362D5E9003213605A60C0 +:104E40006369D5F80C80EF60B34201D101F02CFA10 +:104E500087F311882869C047202383F31188E1E78D +:104E60006169B14209D013441B1ABDE8F0410A2B15 +:104E70002CBFC0180A3001F01DBABDE8F08100BF98 +:104E8000884900200C2303604FF0FF30704700007A +:104E900000207047FEE70000704700004FF0FF3031 +:104EA0007047000002290CD0032904D001290748CB +:104EB00018BF00207047032A05D8054800EBC20040 +:104EC0007047044870470020704700BF006E00081C +:104ED0002C230020B46D000870B59AB00546084632 +:104EE00001A9144600F0C2F801A8FCF7D9FE431C42 +:104EF0005B00C5E900340022237003236370C6B24F +:104F000001AB02341046D1B28E4204F1020401D842 +:104F10001AB070BD13F8011B04F8021C04F8010C50 +:104F20000132F0E708B5202383F311880348FFF727 +:104F300067FA002383F3118808BD00BF404B0020AF +:104F400090F8443003F01F02012A07D190F8452061 +:104F50000B2A03D10023C0E90E3315E003F06003F0 +:104F6000202B08D1B0F848302BB990F84520212AE1 +:104F700003D81F2A04D8FFF725BA222AEBD0FAE774 +:104F8000034A82630722C26303640120704700BFA3 +:104F90002423002007B5052917D8DFE801F01916EA +:104FA00003191920202383F31188104A019001214D +:104FB000FFF7C6FA01980E4A0221FFF7C1FA0D4821 +:104FC000FFF7EAF9002383F3118803B05DF804FBCF +:104FD000202383F311880748FFF7B4F9F2E7202371 +:104FE00083F311880348FFF7CBF9EBE7546D000812 +:104FF000786D0008404B002038B50C4D0C4C0D4925 +:105000002A4604F10800FFF767FF05F1CA0204F120 +:1050100010000949FFF760FF05F5CA7204F1180096 +:105020000649BDE83840FFF757BF00BF08500020D1 +:105030002C230020346D00083E6D0008496D0008E7 +:1050400070B5044608460D46FCF72AFEC6B2204657 +:10505000013403780BB9184670BD32462946FCF777 +:105060000BFE0028F3D10120F6E700002DE9F04700 +:1050700005460C46FCF714FE2C49C6B22846FFF73D +:10508000DFFF08B10836F6B229492846FFF7D8FFF6 +:1050900008B11036F6B2632E0BD8DFF89080DFF837 +:1050A0009090244FDFF898A02E7846B92670BDE87E +:1050B000F08729462046BDE8F04701F007BD252EC0 +:1050C00030D1072241462846FCF7D6FD80B91A4B5D +:1050D000224603F10C0153F8040B42F8040B8B42F7 +:1050E000F9D119889B781180937007350F34DBE76D +:1050F000082249462846FCF7BFFD98B90F4BA21C71 +:10510000197809090232C95D02F8041C13F8011B61 +:1051100001F00F015345C95D02F8031CF0D11834AA +:105120000835C1E704F8016B0135BDE7206E0008C2 +:10513000496D0008286E00080A6B0008107AFF1FEE +:105140001C7AFF1FBFF34F8F024AD368DB03FCD4E6 +:10515000704700BF003C024008B5094B1B7873B98B +:10516000FFF7F0FF074B1A69002ABFBF064A5A60D3 +:1051700002F188325A601A6822F480621A6008BD0F +:1051800066520020003C02402301674508B50B4BE6 +:105190001B7893B9FFF7D6FF094B1A6942F000421A +:1051A0001A611A6842F480521A601A6822F4805216 +:1051B0001A601A6842F480621A6008BD66520020C4 +:1051C000003C02401728F0B516D80C4C0C49237847 +:1051D0007BB90C4D0E4618234FF0006255F8047B46 +:1051E00046F8042B013B13F0FF033A44F6D10123A8 +:1051F000237051F82000F0BD0020FCE7C8520020C9 +:10520000685200203C6E0008014B53F820007047A4 +:105210003C6E000818207047172810B5044601D9C5 +:10522000002010BDFFF7CEFF064B53F82430184482 +:10523000C21A0BB90120F4E712680132F0D1043B25 +:10524000F6E700BF3C6E0008172870B504462FD85B +:10525000FFF7C6FC1749FFF775FFFFF77DFFF32344 +:10526000CB600C23B4FBF3F203FB1245D30143EAFA +:10527000C503DBB243F4007343F002030B610B6917 +:1052800043F480330B6106462046FFF75BFFFFF7D0 +:1052900099FF094B53F8241000F048F93046FFF706 +:1052A00075FFFFF7A7FC2046BDE87040FFF7B4BFCD +:1052B000002070BD003C02403C6E000812F001036B +:1052C0002DE9F04105460E4614464BD18218B2F145 +:1052D000026F61D8314B1B6813F001035CD0304F73 +:1052E000FFF77EFCFFF738FFF323FB60FFF72AFF91 +:1052F000314640F20128032C18D824F00104284E2E +:105300000C446D1A40F20118A142336905EB010704 +:105310002AD123F001033361FFF738FFFFF76AFC5E +:105320000120BDE8F081043C0435E4E7AB07E4D19B +:105330003B6923F440733B613B6943EA08033B61EB +:1053400051F8046B2E60BFF34F8FFFF7FBFE2B6805 +:105350009E42E8D03B6923F001033B61FFF716FF53 +:10536000FFF748FC0020DCE723F440733361336926 +:1053700043EA080333610B883B80BFF34F8FFFF78D +:10538000E1FE3F8831F8023BBFB2BB42BCD033697B +:1053900023F001033361E1E71846C2E70038024019 +:1053A000003C0240084908B50B7828B11BB9FFF74B +:1053B000D3FE01230B7008BD002BFCD0BDE80840D4 +:1053C0000870FFF7E3BE00BF6652002008B54FF437 +:1053D00040314FF0005000F0ABF8BDE808404FF40A +:1053E00080314FF0805000F0A3B8000070B582B05B +:1053F000FFF7F6FB0E4E054600F060FF3268904264 +:1054000037BF0C4A0B49516814682EBFD1E90041DF +:10541000013151600419034641F100012846019110 +:105420003360FFF7E7FB0199204602B070BD00BF73 +:10543000CC520020D052002070B582B0FFF7D0FBD4 +:10544000104E054600F03AFF3268904237BF0E4AD0 +:105450000D49516814682EBFD1E9004101315160F6 +:10546000041941F100010346284601913360FFF71A +:10547000C1FB01994FF47A7200232046FAF7B8FE77 +:1054800002B070BDCC520020D052002010B50244B2 +:10549000064BD2B2904200D110BD441C00B253F86A +:1054A000200041F8040BE0B2F4E700BF50280040B0 +:1054B0000F4B30B51C6F240407D41C6F44F40074E8 +:1054C0001C671C6F44F400441C670A4C236843F4B7 +:1054D000807323600244084BD2B2904200D130BDA9 +:1054E000441C00B251F8045B43F82050E0B2F4E7EA +:1054F00000380240007000405028004007B50122EB +:1055000001A90020FFF7C2FF019803B05DF804FB7A +:1055100013B50446FFF7F2FFA04205D0012201A90E +:1055200000200194FFF7C4FF02B010BD70470000D7 +:105530007047000070470000074B45F255521A6053 +:1055400002225A6040F6FF729A604CF6CC421A6012 +:10555000024B01221A70704700300040DC520020DC +:10556000034B1B781BB1034B4AF6AA221A60704703 +:10557000DC52002000300040034B1A681AB9034A7D +:10558000D2F874281A607047D852002000300240C8 +:10559000024B4FF08072C3F874287047003002400D +:1055A00008B5FFF7E9FF024B1868C0F3407008BD6B +:1055B000D852002008B5FFF7DFFF024B1868C0F390 +:1055C000007008BDD852002070470000FEE70000C0 +:1055D0000A4B0B480B4A90420BD30B4BDA1C121AA6 +:1055E000C11E22F003028B4238BF00220021FCF7CB +:1055F0005FBB53F8041B40F8041BECE78070000805 +:10560000EC530020EC530020EC53002070470000C6 +:1056100070B5D0E915439E6800224FF0FF3504EBCA +:1056200042135101D3F800090028BEBFD3F8000986 +:1056300040F08040C3F80009D3F8000B0028BEBF3B +:10564000D3F8000B40F08040C3F8000B0132631820 +:105650009642C3F80859C3F8085BE0D24FF0011333 +:10566000C4F81C3870BD00001D4B03EB80022DE90F +:10567000F043D2F80CC05D6DDCF81420461CD2F863 +:1056800000E005EB063605EB4018516871450AD37A +:10569000D5F83438012202FA00F023EA0000C5F8F8 +:1056A0003408BDE8F083BCF81040AEEB0103A34220 +:1056B00028BF2346D8F81849A4B2B3EB840FF0D81A +:1056C0009468A4F1040959F8047F3760A4EB090732 +:1056D0001F44042FF7D81C440B4494605360D4E754 +:1056E000E0520020890141F02001016103699B061D +:1056F000FCD41220FFF78EBA10B5054C2046FEF7F9 +:1057000001FF4FF0A0436365024BA36510BD00BFCE +:10571000E0520020C06E000870B50378012B0546EA +:1057200050D12A4B446D98421BD1294B5A6B42F001 +:1057300080025A635A6D42F080025A655A6D5A6966 +:1057400042F080025A615A6922F080025A610E21A9 +:1057500043205B69FEF748FB1E4BE3601E4BC4F819 +:1057600000380023C4F8003EC02323606E6D4FF460 +:105770005023A3633369002BFCDA012333610C202F +:10578000FFF748FA3369DB07FCD41220FFF742FA2F +:105790003369002BFCDA0026A6602846FFF738FFA5 +:1057A0006B68C4F81068DB68C4F81468C4F81C6837 +:1057B0004BB90A4BA3614FF0FF336361A36843F019 +:1057C0000103A36070BD064BF4E700BFE052002068 +:1057D000003802404014004003002002003C30C06A +:1057E000083C30C0F8B5446D054600212046FFF75F +:1057F00079FFA96D00234FF001128F68C4F8343887 +:105800004FF00066C4F81C284FF0FF3004EB431241 +:1058100001339F42C2F80069C2F8006BC2F8080960 +:10582000C2F8080BF2D20B686A6DEB656362102355 +:105830001361166916F01006FBD11220FFF7EAF982 +:10584000D4F8003823F4FE63C4F80038A36943F4A5 +:10585000402343F01003A3610923C4F81038C4F8AF +:1058600014380A4BEB604FF0C043C4F8103B084BB0 +:10587000C4F8003BC4F81069C4F80039EB6D03F1BB +:10588000100243F48013EA65A362F8BD9C6E000821 +:1058900040800010426D90F84E10D2F8003823F48A +:1058A000FE6343EA0113C2F8003870472DE9F8435C +:1058B00000EB8103456DDA68166806F00306731E77 +:1058C000022B05EB41130C4680460FFA81F94FEA93 +:1058D00041104FF00001C3F8101B4FF0010104F11B +:1058E000100398BFB60401FA03F391698EBF334EDB +:1058F00006F1805606F5004600293AD0578A04F191 +:105900005801490137436F50D5F81C180B43C5F8AF +:105910001C382B180021C3F8101953690127611E88 +:10592000A7409BB3138A928B9B08012A88BF5343DD +:10593000D8F85C20981842EA034301F1400205EBD5 +:105940008202C8F85C00214653602846FFF7CAFE71 +:1059500008EB8900C3681B8A43EA84534834640116 +:105960001E432E51D5F81C381F43C5F81C78BDE8DE +:10597000F88305EB4917D7F8001B21F40041C7F85D +:10598000001BD5F81C1821EA0303C0E704F13F030C +:1059900005EB83030A4A5A6028462146FFF7A2FE18 +:1059A00005EB4910D0F8003923F40043C0F8003962 +:1059B000D5F81C3823EA0707D7E700BF008000109E +:1059C00000040002826D1268C265FFF721BE00006C +:1059D0005831436D49015B5813F4004004D013F46F +:1059E000001F0CBF02200120704700004831436DAA +:1059F00049015B5813F4004004D013F4001F0CBF9E +:105A0000022001207047000000EB8101CB68196A79 +:105A10000B6813604B6853607047000000EB810314 +:105A200030B5DD68AA691368D36019B9402B84BF0B +:105A3000402313606B8A1468426D1C44013CB4FB24 +:105A4000F3F46343033323F0030302EB411043EA0F +:105A5000C44343F0C043C0F8103B2B6803F003037A +:105A6000012B09B20ED1D2F8083802EB411013F421 +:105A7000807FD0F8003B14BF43F0805343F00053C5 +:105A8000C0F8003B02EB4112D2F8003B43F0044364 +:105A9000C2F8003B30BD00002DE9F041244D6E6D91 +:105AA00006EB40130446D3F8087BC3F8087B38079D +:105AB0000AD5D6F81438190706D505EB8403214614 +:105AC000DB6828465B689847FA071FD5D6F8143874 +:105AD000DB071BD505EB8403D968CCB98B69488AF1 +:105AE0005A68B2FBF0F600FB16228AB91868DA6829 +:105AF00090420DD2121AC3E90024202383F31188A7 +:105B00000B482146FFF78AFF84F31188BDE8F08136 +:105B1000012303FA04F26B8923EA02036B81CB6849 +:105B2000002BF3D021460248BDE8F041184700BFE2 +:105B3000E052002000EB810370B5DD68436D6C69B5 +:105B40002668E6604A0156BB1A444FF40020C2F8AA +:105B500010092A6802F00302012A0AB20ED1D3F812 +:105B6000080803EB421410F4807FD4F8000914BF36 +:105B700040F0805040F00050C4F8000903EB42129E +:105B8000D2F8000940F00440C2F80009D3F8340804 +:105B9000012202FA01F10143C3F8341870BD19B9AA +:105BA000402E84BF4020206020682E8A8419013C4A +:105BB000B4FBF6F440EAC44040F000501A44C6E793 +:105BC000F8B504461E48456D05EB4413D3F8086943 +:105BD000C3F80869F10717D5D5F81038DA0713D5D7 +:105BE00000EB8403D9684B691F68DA68974218D2C2 +:105BF000D21B00271A605F60202383F3118821469F +:105C0000FFF798FF87F31188330617D5D5F83428A6 +:105C10000123A340134211D02046BDE8F840FFF70E +:105C200023BD012303FA04F2038923EA020303815B +:105C30008B68002BE8D021469847E5E7F8BD00BF08 +:105C4000E05200202DE9F74F984C666D7569B369F5 +:105C50001D4015F48058756107D02046FEF7B8FC4A +:105C600003B0BDE8F04FFDF78DBF002D12DAD6F876 +:105C7000003E8E489F071EBFD6F8003E23F0030368 +:105C8000C6F8003ED6F8043823F00103C6F80438FD +:105C9000FEF7C6FC280505D58448FFF7B9FC834804 +:105CA000FEF7AEFCA9040CD5D6F8083813F0060FA1 +:105CB000F36823F470530CBF43F4105343F4A05320 +:105CC000F3602A0704D56368DB680BB1774898470F +:105CD000EB0274D4AF0227D5D4F85490DFF8CCB1DE +:105CE00000274FF0010A09EB4712D2F8003B03F4FA +:105CF0004023B3F5802F11D1D2F8003B002B0DDAF1 +:105D000062890AFA07F322EA0303638104EB87033B +:105D1000DB68DB6813B1394658469847A36D0137F5 +:105D20009B68FFB29F42DED9E80617D5676D3A6AD5 +:105D3000C2F30A1002F00F0302F4F012B2F5802F42 +:105D400000F08880B2F5402F08D104EB83030022D5 +:105D5000DB681B6A07F5805790426DD12903D6F89E +:105D6000184813D5E20302D50020FFF795FEA303E0 +:105D700002D50120FFF790FE670302D50220FFF74E +:105D80008BFE260302D50320FFF786FE6D037FF509 +:105D900067AFE00702D50020FFF712FFA10702D589 +:105DA0000120FFF70DFF620702D50220FFF708FF71 +:105DB00023077FF555AF0320FFF702FF50E7636D20 +:105DC000DFF8E8B0019300274FF0010AA36D9B684C +:105DD0005FFA87F999453FF67DAF019B03EB4913C5 +:105DE000D3F8002902F44022B2F5802F22D1D3F853 +:105DF0000029002A1EDAD3F8002942F09042C3F8A5 +:105E00000029D3F80029002AFBDB606D4946FFF723 +:105E100069FC22890AFA09F322EA0303238104EBCD +:105E20008903DB689B6813B1494658469847484642 +:105E3000FFF71AFC0137C9E7910708BFD7F80080C0 +:105E4000072A98BF03F8018B02F1010298BF4FEABD +:105E5000182881E7023304EB830207F58057526864 +:105E6000D2F818C0DCF80820DCE9001CA1EB0C0C0F +:105E7000002188420AD104EB830463689B699A6815 +:105E800002449A605A6802445A6067E711F0030FAF +:105E900008BFD7F800808C4588BF02F8018B01F15C +:105EA000010188BF4FEA1828E3E700BFE052002055 +:105EB000436D03EB4111D1F8003B43F40013C1F8EB +:105EC000003B7047436D03EB4111D1F8003943F4B7 +:105ED0000013C1F800397047436D03EB4111D1F84D +:105EE000003B23F40013C1F8003B7047436D03EB04 +:105EF0004111D1F8003923F40013C1F8003970477B +:105F000030B5039C0172043304FB0325C0E906533A +:105F1000049B03630021059BC160C0E90000C0E948 +:105F20000422C0E90842C0E90A11436330BD000001 +:105F3000416A0022C0E90411C0E90A22C2606FF080 +:105F40000101FEF7D7BE0000D0E90432934201D12F +:105F5000C2680AB9181D70470020704703691960AC +:105F6000C2680132C260C26913448269036193420C +:105F700024BF436A03610021FEF7B0BE38B5044672 +:105F80000D46E3683BB16269131D1268A3621344B6 +:105F9000E362002007E0237A33B929462046FEF762 +:105FA0008DFE0028EDDA38BD6FF00100FBE7000040 +:105FB000C368C269013BC36043691344826943619A +:105FC000934224BF436A436100238362036B03B19E +:105FD0001847704770B52023044683F31188866AFA +:105FE0003EB9FFF7CBFF054618B186F31188284666 +:105FF00070BDA36AE26A13F8015BA362934202D305 +:106000002046FFF7D5FF002383F31188EFE7000058 +:106010002DE9F84F04460E46174698464FF02009E2 +:1060200089F311880025AA46D4F828B0BBF1000FE7 +:1060300009D141462046FFF7A1FF20B18BF311881B +:106040002846BDE8F88FD4E90A12A7EB050B521ACF +:10605000934528BF9346BBF1400F1BD9334601F14E +:10606000400251F8040B43F8040B9142F9D1A36AA2 +:1060700040334036A3624035D4E90A239A4202D322 +:106080002046FFF795FF8AF31188BD42D8D289F3E5 +:106090001188C9E730465A46FBF7E4FDA36A5B4422 +:1060A0005E44A3625D44E7E710B5029C01720433CD +:1060B00004FB0321C0E906130023C0E90A33039B54 +:1060C0000363049BC460C0E90000C0E90422C0E986 +:1060D0000842436310BD0000026AC260426AC0E920 +:1060E00004220022C0E90A226FF00101FEF702BE7D +:1060F000D0E904239A4201D1C26822B9184650F867 +:10610000043B0B607047002070470000C368C26901 +:106110000133C3604369134482694361934224BFDE +:10612000436A43610021FEF7D9BD000038B504463B +:106130000D46E3683BB123691A1DA262E26913446C +:10614000E362002007E0237A33B929462046FEF7B0 +:10615000B5FD0028EDDA38BD6FF00100FBE7000067 +:1061600003691960C268013AC260C2691344826956 +:106170000361934224BF436A036100238362036B7C +:1061800003B118477047000070B520230D46044640 +:10619000114683F31188866A2EB9FFF7C7FF10B145 +:1061A00086F3118870BDA36A1D70A36AE26A013389 +:1061B0009342A36204D3E16920460439FFF7D0FF7C +:1061C000002080F31188EDE72DE9F84F04460D46D5 +:1061D000904699464FF0200A8AF311880026B3466C +:1061E000A76A4FB949462046FFF7A0FF20B187F3C1 +:1061F00011883046BDE8F88FD4E90A073A1AA8EBAF +:106200000607974228BF1746402F1BD905F14003C8 +:1062100055F8042B40F8042B9D42F9D1A36A403372 +:10622000A3624036D4E90A239A4204D3E1692046A6 +:106230000439FFF795FF8BF311884645D9D28AF3CD +:106240001188CDE729463A46FBF70CFDA36A3B448B +:106250003D44A3623E44E5E7D0E904239A4217D1C6 +:10626000C3689BB1836A8BB1043B9B1A0ED0136049 +:10627000C368013BC360C3691A44836902619A42DF +:1062800024BF436A036100238362012318467047D9 +:106290000023FBE700F088B84FF0804300225863EA +:1062A0001A610222DA6070474FF080430022DA6000 +:1062B000704700004FF08043586370474FF08043B1 +:1062C000586A70474B6843608B688360CB68C360D3 +:1062D0000B6943614B6903628B6943620B6803601E +:1062E0007047000008B5264B26481A6940F2FF1196 +:1062F0000A431A611A6922F4FF7222F001021A613C +:106300001A691A6B0A431A631A6D0A431A651E4A00 +:106310001B6D1146FFF7D6FF02F11C0100F58060EE +:10632000FFF7D0FF02F1380100F58060FFF7CAFFE8 +:1063300002F1540100F58060FFF7C4FF02F1700123 +:1063400000F58060FFF7BEFF02F18C0100F5806070 +:10635000FFF7B8FF02F1A80100F58060FFF7B2FF78 +:1063600002F1C40100F58060FFF7ACFF02F1E0012B +:1063700000F58060FFF7A6FFBDE8084000F09AB87E +:106380000038024000000240CC6E000808B500F062 +:1063900009FAFEF7F7FBFFF7EFF8BDE80840FEF754 +:1063A0002BBE000070470000104B1A6C42F0010237 +:1063B0001A641A6E42F001021A660D4A1B6E936847 +:1063C00043F0010393604FF0804353229A624FF0F1 +:1063D000FF32DA6200229A615A63DA605A6001225F +:1063E0005A6108211A601C20FDF7FEBC00380240EB +:1063F000002004E04FF0804208B51169D3680B40DB +:10640000D9B2C9439B07116107D5202383F31188B3 +:10641000FEF7E4FB002383F3118808BD08B5FFF7FE +:10642000E9FFBDE80840FDF7ADBB00001F4B1A694E +:106430006FEAC2526FEAD2521A611A69C2F30802B5 +:106440001A614FF0FF301A695A69586100215A6980 +:1064500059615A691A6A62F080521A621A6A02F025 +:1064600080521A621A6A5A6A58625A6A59625A6A99 +:106470001A6C42F080521A641A6E42F080521A6608 +:106480001A6E0B4A106840F480701060186F00F4A8 +:106490004070B0F5007F1EBF4FF480301867196759 +:1064A000536823F40073536000F05CB90038024075 +:1064B00000700040344B4FF080521A64334A4FF45E +:1064C000404111601A6842F001021A601A6891078F +:1064D000FCD59A6822F003029A602B4B9A6812F05E +:1064E0000C02FBD1196801F0F90119609A601A6871 +:1064F00042F480321A601A689203FCD55A6F42F057 +:1065000001025A67204B5A6F9007FCD5204A5A6007 +:106510001A6842F080721A601C4A53685904FCD50C +:10652000194B1A689201FCD51A4A9A600322C3F8E3 +:106530008C20194B1A68194B9A42194B21D1194AD0 +:106540001168194A91421CD140F205121A60144A8E +:10655000136803F00F03052BFAD10B4B9A6842F036 +:1065600002029A609A6802F00C02082AFAD15A6C68 +:1065700042F480425A645A6E42F480425A665B6E1C +:10658000704740F20572E1E70038024000700040B9 +:106590001854400700948838002004E0116400205B +:1065A000003C024000ED00E041C20F41084A08B53E +:1065B000516913680B4003F00103536123B1054A8D +:1065C00013680BB150689847BDE80840FDF7DABA88 +:1065D000003C014058530020084A08B5516913682F +:1065E0000B4003F00203536123B1054A93680BB1DA +:1065F000D0689847BDE80840FDF7C4BA003C0140A8 +:1066000058530020084A08B5516913680B4003F03D +:106610000403536123B1054A13690BB150699847CC +:10662000BDE80840FDF7AEBA003C014058530020D9 +:10663000084A08B5516913680B4003F00803536119 +:1066400023B1054A93690BB1D0699847BDE808406A +:10665000FDF798BA003C014058530020084A08B59D +:10666000516913680B4003F01003536123B1054ACD +:10667000136A0BB1506A9847BDE80840FDF782BA2B +:10668000003C014058530020174B10B55A691C6854 +:10669000144004F478725A61A30604D5134A936A2D +:1066A0000BB1D06A9847600604D5104A136B0BB142 +:1066B000506B9847210604D50C4A936B0BB1D06BF5 +:1066C0009847E20504D5094A136C0BB1506C984702 +:1066D000A30504D5054A936C0BB1D06C9847BDE86F +:1066E0001040FDF74FBA00BF003C01405853002056 +:1066F0001A4B10B55A691C68144004F47C425A6164 +:10670000620504D5164A136D0BB1506D98472305E9 +:1067100004D5134A936D0BB1D06D9847E00404D5AE +:106720000F4A136E0BB1506E9847A10404D50C4A62 +:10673000936E0BB1D06E9847620404D5084A136F6C +:106740000BB1506F9847230404D5054A936F0BB1E2 +:10675000D06F9847BDE81040FDF714BA003C0140E7 +:1067600058530020062108B50846FDF73DFB0621D9 +:106770000720FDF739FB06210820FDF735FB062130 +:106780000920FDF731FB06210A20FDF72DFB06212C +:106790001720FDF729FBBDE8084006212820FDF75A +:1067A00023BB000008B5FFF741FE00F00DF8FDF730 +:1067B000BFFCFDF7A5FEFDF77DFDFFF7F3FDBDE88E +:1067C0000840FFF767BD00000023054A1946013362 +:1067D000102BC2E9001102F10802F8D1704700BF86 +:1067E000585300200B460146184600F025B800001B +:1067F00000F038B8012838BF012010B50446204603 +:1068000000F028F830B900F007F808B900F00CF8EB +:106810008047F4E710BD0000024B1868BFF35B8FA0 +:10682000704700BFD853002008B5062000F032F9A9 +:106830000120FEF72FFB000010B5054C13462CB1CC +:106840000A4601460220AFF3008010BD2046FCE757 +:1068500000000000024B0146186800F089B800BF34 +:106860004C230020024B0146186800F035B800BFE9 +:106870004C23002010B501390244904201D1002080 +:1068800005E0037811F8014FA34201D0181B10BD99 +:106890000130F2E72DE9F041A3B1C91A177801449C +:1068A000044603F1FF3C8C42204601D9002009E058 +:1068B0000578BD4204F10104F5D10CEB0405D618AE +:1068C000A54201D1BDE8F08115F8018D16F801ED62 +:1068D000F045F5D0E7E7000037B5002944D051F87E +:1068E000043C0190002BA1F10404B8BFE41800F0AF +:1068F000F5F81E4A0198136833B96360146003B059 +:10690000BDE8304000F0F0B8A34208D9256861190D +:106910008B4201BF19685B6849192160EDE71A468F +:106920005B680BB1A342FAD911685518A5420BD187 +:10693000246821445418A3421160E0D11C685B68AC +:10694000536021441160DAE702D90C230360D6E7D3 +:10695000256861198B4204BF19685B68636004BFD6 +:10696000491921605460CAE703B030BDDC530020F0 +:10697000F8B5CD1C25F0030508350C2D38BF0C25C6 +:10698000002D064601DBA94203D90C233360002009 +:10699000F8BD00F0A3F821490A6814469CB9204FBD +:1069A0003B6823B92146304600F03CF83860294660 +:1069B000304600F037F8431C23D10C2333603046B7 +:1069C00000F092F8E3E723685B1B17D40B2B03D985 +:1069D00023601C44256004E06368A2420CBF0B6086 +:1069E0005360304600F080F804F10B00231D20F0C6 +:1069F0000700C21ACCD01B1AA350C9E7224664680C +:106A0000CCE7C41C24F00304A042E3D0211A304692 +:106A100000F008F80130DDD1CFE700BFDC530020E3 +:106A2000E053002038B5064D0023044608462B608D +:106A3000FEF728FA431C02D12B6803B1236038BD4E +:106A4000E45300201F2938B504460D4604D9162307 +:106A500003604FF0FF3038BD426C12B152F8213064 +:106A60004BB9204600F030F82A4601462046BDE8E2 +:106A7000384000F017B8012B0AD0591C03D1162357 +:106A800003600120E7E7002442F8254028469847A4 +:106A90000020E0E7024B01461868FFF7D3BF00BFB4 +:106AA0004C23002038B5074D002304460846114604 +:106AB0002B60FEF7F3F9431C02D12B6803B123606E +:106AC00038BD00BFE4530020FEF7E2B9034611F8D9 +:106AD000012B03F8012B002AF9D17047014800F07F +:106AE00009B800BFE8530020014800F005B800BF16 +:106AF000E853002070470000704700006F72672E57 +:106B00006172647570696C6F742E5069787261631C +:106B100065722D7065726970680000004E6F2061AB +:106B20007070207369670A00426164206677206C88 +:106B3000656E6774682025750A0042616420626F83 +:106B40006172645F69642025752073686F756C6479 +:106B50002062652025750A00426164206677206402 +:106B6000657363726970746F72206C656E677468A8 +:106B70002025750A004261642061707020435243F1 +:106B8000203078253038783A307825303878203001 +:106B900078253038783A3078253038780A00476FD1 +:106BA0006F64206669726D776172650A0040A2E4C5 +:106BB000F16468910600000053544D3332463F3F64 +:106BC0003F00000053544D33324634307800535464 +:106BD0004D3332463432780053544D3332463434D8 +:106BE00036585800012033000010410101105A01AD +:106BF000031059010710310100000000B86B0008B4 +:106C00003F00000013040000C46B00083F000000B8 +:106C100019040000CE6B00083F00000021040000B2 +:106C2000D86B00083F000000404B002020470020A8 +:106C30004261642043414E496661636520696E6428 +:106C400065782E00800000000080000000008000B9 +:106C500000000000000000001D1E000809260008BA +:106C6000692500082D1E0008651E00086120000827 +:106C7000311E0008451E0008351E0008391E000898 +:106C8000411E00083D1E0008891F0008491E00081B +:106C900075280008591E00085D1F000800960000B6 +:106CA00000000000000000000000000000000000E4 +:106CB00000000000F9400008E540000821410008FC +:106CC0000D4100081941000805410008F140000885 +:106CD000DD4000082D41000800000000314200089E +:106CE0001D42000859420008454200085142000870 +:106CF0003D4200082942000815420008654200088C +:106D00000000000001000000000000006D61696EDD +:106D10000000000069646C6500000000146D00084C +:106D2000C8490020404B002001000000814B0008B2 +:106D3000000000004172647550696C6F7400254258 +:106D40004F415244252D424C002553455249414C58 +:106D50002500000002000000000000004D44000873 +:106D6000B944000840004000D84F0020E84F002000 +:106D7000020000000000000003000000000000000E +:106D8000FD4400080000000010000000F84F002043 +:106D9000000000000100000000000000E0520020A0 +:106DA00001010200954F0008A54E0008414F000860 +:106DB000254F000843000000BC6D00080902430095 +:106DC000020100C032090400000102020100052492 +:106DD000001001052401000104240202052406001C +:106DE00001070582030800FF09040100020A0000F0 +:106DF0000007050102400000070581024000000075 +:106E000012000000086E000812011001020000408C +:106E100009124157000201020301000004030904A2 +:106E200025424F4152442500303132333435363714 +:106E3000383941424344454600000000004000000C +:106E40000040000000400000004000000000010081 +:106E5000000002000000020000000200000002002A +:106E600000000200000002000000020000400000DC +:106E70000040000000400000004000000000010051 +:106E800000000200000002000000020000000200FA +:106E900000000200000002000000020000000000EC +:106EA00035460008ED4800089949000840004000B8 +:106EB00040530020405300200100000050530020A8 +:106EC0008000000040010000030000000000802A54 +:106ED00000000000AAAAAAAA00000024FFFF0000E8 +:106EE0000000000000A00A004400000000000000B4 +:106EF000AAAAAAAA00000000FFFF000000000000EC +:106F0000000000001000004000000000AAAAAAAA89 +:106F100010000040FFFF0000000000000000000023 +:106F20000A68100000000000AAAAAAAA00541000D3 +:106F3000FFFF000099007007000000000000004003 +:106F400000000000AAAAAAAA00000040FFFF00005B +:106F50000000000000000000000000000000000031 +:106F6000AAAAAAAA00000000FFFF0000000000007B +:106F7000000000000000000000000000AAAAAAAA69 +:106F800000000000FFFF0000000000000000000003 +:106F900000000000000000000A00000000000000E7 +:106FA00003000000000000000000000000000000DE +:106FB00000000000000000000000000000000000D1 +:106FC00000000000000000005892FF7F0100000058 +:106FD0007A0500000000000000001F000000000013 +:106FE00040420F00FE2A0100D2040000FF0096007C +:106FF00000000008009600000000080004000000E7 +:107000001C6E0008000000000000000000000000EE +:1070100000000000000000000000000050230020DD +:107020000000000000000000000000000000000060 +:107030000000000000000000000000000000000050 +:107040000000000000000000000000000000000040 +:107050000000000000000000000000000000000030 +:107060000000000000000000000000000000000020 +:107070000000000000000000000000000000000010 :00000001FF diff --git a/Tools/bootloaders/ReaperF745v2_bl.bin b/Tools/bootloaders/ReaperF745v2_bl.bin new file mode 100644 index 00000000000..a48f7010435 Binary files /dev/null and b/Tools/bootloaders/ReaperF745v2_bl.bin differ diff --git a/Tools/bootloaders/ReaperF745v2_bl.hex b/Tools/bootloaders/ReaperF745v2_bl.hex new file mode 100644 index 00000000000..312b0724ded --- /dev/null +++ b/Tools/bootloaders/ReaperF745v2_bl.hex @@ -0,0 +1,1018 @@ +:020000040800F2 +:1000000000060120010200083D0F0008BD0E000897 +:10001000150F0008BD0E0008E90E000803020008D5 +:10002000030200080302000803020008DD2700089D +:10003000030200080302000803020008030200088C +:10004000030200080302000803020008030200087C +:10005000030200080302000851390008793900083A +:10006000A1390008C9390008F13900080302000865 +:10007000030200080302000803020008030200084C +:10008000030200080302000803020008030200083C +:10009000030200080302000803020008193A0008DE +:1000A000030200080302000803020008030200081C +:1000B000013B0008030200080302000803020008D5 +:1000C00003020008030200080302000803020008FC +:1000D00003020008ED3A00080302000803020008CA +:1000E0007D3A00080302000803020008030200082A +:1000F00003020008030200080302000803020008CC +:1001000003020008030200080302000803020008BB +:1001100003020008030200080302000803020008AB +:10012000030200080302000803020008030200089B +:10013000030200080302000803020008030200088B +:100140000302000803020008030200089D2F0008B4 +:10015000030200080302000803020008030200086B +:10016000030200080302000803020008030200085B +:10017000030200080302000803020008030200084B +:10018000030200080302000803020008030200083B +:10019000030200080302000803020008030200082B +:1001A000030200080302000803020008030200081B +:1001B000030200080302000803020008030200080B +:1001C00003020008030200080302000803020008FB +:1001D00003020008030200080302000803020008EB +:1001E00003020008030200080302000803020008DB +:1001F00003020008030200080302000803020008CB +:1002000002E000F000F8FEE772B63A4880F3088892 +:10021000394880F3098839484EF60851CEF200017A +:10022000086040F20000CCF200004EF63471CEF2CD +:1002300000010860BFF34F8FBFF36F8F40F20000E3 +:10024000C0F2F0004EF68851CEF200010860BFF314 +:100250004F8FBFF36F8F4FF00000E1EE100A4EF6A4 +:100260003C71CEF200010860062080F31488BFF3D1 +:100270006F8F02F073FB02F015FB03F00BFA4FF0E7 +:1002800055301F491B4A91423CBF41F8040BFAE725 +:100290001C49194A91423CBF41F8040BFAE71A493C +:1002A0001A4A1B4B9A423EBF51F8040B42F8040B0A +:1002B000F8E700201749184A91423CBF41F8040B67 +:1002C000FAE702F02DFB03F045FA144C144DAC4252 +:1002D00003DA54F8041B8847F9E700F041F8114CA1 +:1002E000114DAC4203DA54F8041B8847F9E702F0D9 +:1002F00015BB0000000601200022012000000008BC +:100300000000012000060120183F00080022012003 +:1003100068220120682201205830012000020008D4 +:100320000002000800020008000200082DE9F04F5A +:100330002DED108AC1F80CD0D0F80CD0BDEC108A8D +:10034000BDE8F08F002383F311882846A0470020E2 +:1003500001F04AFEFEE701F0BFFD00DFFEE700000E +:1003600038B502F0FBF9054602F02EFA0446D8B97A +:100370000F4B9D421AD001339D4218BF044641F2F3 +:10038000883504BF01240025002002F0F1F90CB1EA +:1003900000F058F800F03AFD00F0DEFB284600F0CF +:1003A000E1F800F04FF8F9E70025EDE70546EBE747 +:1003B000010007B008B500F09BFBA0F120035842F4 +:1003C000584108BD07B541F21203022101A8ADF85A +:1003D000043000F0ABFB03B05DF804FB10B572B65F +:1003E000202383F3118862B61248C3680BB101F071 +:1003F00083FE114A0F4800234FF47A7101F040FE4A +:10040000002383F311880D4C236813B12368013B4B +:100410002360636813B16368013B6360084B1B781A +:1004200033B9636823B9022000F06AFC32236360A9 +:1004300010BD00BF68220120DD03000884230120D5 +:100440007C220120F8B5414B414A1C461968013114 +:100450007BD004339342F9D16268A24275D33D4BFD +:100460009B6803F1006303F5C0339A426DD200200C +:1004700000F08CFB384B0220187000F037FC374B33 +:1004800000211A6C19641A6E19661A6E5A6C596436 +:100490005A6E59665A6E5A6942F080025A615A6918 +:1004A00022F080025A615A691A6942F000521A61B8 +:1004B0001A6922F000521A611B6972B64FF0E023EC +:1004C000C3F8084DD4E90004BFF34F8FBFF36F8F1B +:1004D000234AC2F88410BFF34F8F536923F480334B +:1004E0005361BFF34F8FD2F88030C3F3C905C3F314 +:1004F0004E335B0143F6E07603EA060C29464CEAEC +:1005000081770139C2F87472F9D2203B13F1200FC0 +:10051000F2D1BFF34F8FBFF36F8FBFF34F8FBFF396 +:100520006F8F536923F4003353610023C2F85032B4 +:10053000BFF34F8FBFF36F8F72B6202383F3118801 +:1005400062B6854680F308882047F8BD0080010820 +:1005500020800108002201207C2201200038024076 +:1005600000ED00E02DE9F04F93B0AA4B009020225F +:10057000FF210AA89D6800F0F3FBA74A1378B3B9DE +:10058000A64801211170C36072B6202383F311883D +:1005900062B6C3680BB101F0AFFDA14A9F480023CA +:1005A0004FF47A7101F06CFD002383F31188009BF6 +:1005B0009C4A03B113609C49009C00230B7053605C +:1005C00098469B461E469A46012000F08FFB24B1B8 +:1005D000944B1B68002B00F01682002000F088FA74 +:1005E0000390039B002BF2DB012000F075FB039BC3 +:1005F000213B162BE8D801A252F823F05906000837 +:100600008106000815070008C9050008C90500088B +:10061000C9050008A90700087B090008950800081B +:10062000F70800081F09000845090008C905000867 +:1006300057090008C9050008C9090008F90600089B +:10064000C90500080D0A000865060008F90600083B +:10065000C9050008F70800080220FFF7ABFE0028D4 +:1006600040F0FB81009B0221B8F1000F08BF1C463F +:1006700005A841F21233ADF8143000F057FAA3E7A1 +:100680004FF47A7000F034FA071EEBDB0220FFF71C +:1006900091FE0028E6D0013F052F00F2E081DFE85F +:1006A00007F0030A0D10133605230593042105A84E +:1006B00000F03CFA17E057480421F9E75B480421B1 +:1006C000F6E75B480421F3E74FF01C09484600F0C9 +:1006D0005FFA09F104090590042105A800F026FA43 +:1006E000B9F12C0FF2D1012000FA07F747EA0B0B02 +:1006F0005FFA8BFB4FF0000A00F07EFB26B10BF097 +:100700000B030B2B08BF0024FFF75CFE5CE7494896 +:100710000421CDE7002EA5D00BF00B030B2BA1D1AC +:100720000220FFF747FE074600289BD001203E4EDF +:1007300000F02CFA0220307000F0D8FA4FF00008D8 +:100740005FFA88F9484600F031FA044690B148460D +:1007500000F03CFA08F101080028F1D1B84604463F +:1007600041F21213022105A8ADF814303E4600F004 +:10077000DDF929E701230220337000F0ADFA2546A8 +:10078000244B9B68AB4207D9284600F001FA0130A0 +:1007900040F068810435F3E7234B00251D70214BA1 +:1007A000B8465D603E46A7E7002E3FF45BAF0BF016 +:1007B0000B030B2B7FF456AF1B4B0220187000F07D +:1007C00095FA322000F094F9B0F10009FFF64AAF33 +:1007D00019F003077FF446AF0E4A926809EB050350 +:1007E00093423FF63FAFB9F5807F3FF73BAF124BE7 +:1007F0000193B94522DD4FF47A7000F079F9039046 +:10080000039A002AFFF62EAF019B039A03F8012BEF +:100810000137EDE70022012080230120682201201A +:10082000DD030008842301207C2201200422012012 +:10083000082201200C22012080220120C820FFF77D +:10084000B9FD074600283FF40DAF1F2D11D8C5F1A3 +:1008500020024A450AAB25F0030028BF4A468349D7 +:100860000192184400F056FA019A8048FF2100F0E6 +:1008700077FA4FEAA9037D490193C9F38702284615 +:1008800000F076FA064600283FF46AAF019B05EBBC +:10089000830531E70220FFF78DFD00283FF4E2AE2B +:1008A00000F0BEF900283FF4DDAE0027B946704BDA +:1008B0009B68BB4218D91F2F11D80A9B01330ED059 +:1008C00027F0030312AA134453F8203C059348462B +:1008D000042205A900F034FB04378146E7E73846D7 +:1008E00000F056F90590F2E7CDF81490042105A820 +:1008F00000F01CF900E70023642104A8049300F031 +:100900000BF900287FF4AEAE0220FFF753FD00285C +:100910003FF4A8AE049800F06BF90590E6E70023D9 +:10092000642104A8049300F0F7F800287FF49AAE3D +:100930000220FFF73FFD00283FF494AE049800F03A +:1009400067F9EAE70220FFF735FD00283FF48AAE99 +:1009500000F076F9E1E70220FFF72CFD00283FF4D4 +:1009600081AE05A9142000F071F904210746049016 +:1009700004A800F0DBF83946B9E7322000F0B8F8F7 +:10098000071EFFF66FAEBB077FF46CAE384A926865 +:1009900007EB0A0393423FF665AE0220FFF70AFD1C +:1009A00000283FF45FAE27F003075744BA453FF4F1 +:1009B000A3AE504600F0ECF80421059005A800F025 +:1009C000B5F80AF1040AF1E74FF47A70FFF7F2FC88 +:1009D00000283FF447AE00F023F9002844D00A9BDA +:1009E00001330BD008220AA9002000F0C1F9002829 +:1009F0003AD02022FF210AA800F0B2F9FFF7E2FC6A +:100A00001C4801F0F9FA13B0BDE8F08F002E3FF456 +:100A100029AE0BF00B030B2B7FF424AE00236421D3 +:100A200005A8059300F078F8074600287FF41AAE71 +:100A30000220FFF7BFFC814600283FF413AEFFF70A +:100A4000C1FC41F2883001F0D7FA059800F016FA9F +:100A50004E4600F0D1F93C46B6E506464CE64FF06E +:100A6000000AFFE5B8467BE6374679E6802201209A +:100A700000220120A0860100F7B5194E0C464FF464 +:100A80007A7102FB01F396F900200546501C0BD148 +:100A90001448019302682946176A2246B8478442DF +:100AA000019B03D1002310E0002AF1D096F9002029 +:100AB000511C01D0012A0DD10B4802682946166A43 +:100AC0002246B047844205D10123084A0120137011 +:100AD00003B0F0BD4FF4FA7001F08EFA0020F7E792 +:100AE00010220120F8270120D4230120D023012047 +:100AF00007B50023024601210DF107008DF80730EC +:100B0000FFF7BAFF20B19DF8070003B05DF804FBC2 +:100B10004FF0FF30F9E700000A4608B50421FFF75F +:100B2000ABFF80F00100C0B2404208BD30B4074BBB +:100B30000A461978064B53F821402368DD69054BB6 +:100B40000146AC46204630BC604700BFD0230120A0 +:100B5000DC3B0008A086010070B501F0F1FC094EF5 +:100B6000094D3080002428683388834208D901F079 +:100B7000E1FC2B6804440133B4F5C03F2B60F2D391 +:100B800070BD00BFD22301208C23012001F09ABD4B +:100B900000F1006000F5C0300068704700F10060AF +:100BA000920000F5C03001F019BD0000054B1A6835 +:100BB000054B1B889B1A834202D9104401F0BABC32 +:100BC000002070478C230120D223012038B5074D27 +:100BD00004462868204401F0B5FC28B92868204460 +:100BE000BDE8384001F0C6BC38BD00BF8C230120F1 +:100BF00010F0030309D1B0F5846F04D200F1005066 +:100C0000A0F571200368184670470023FBE7000039 +:100C100000F10050A0F57120D0F8200470470000CA +:100C2000064991F8243033B10023086A81F8243052 +:100C30000822FFF7B3BF0120704700BF90230120B7 +:100C4000014B1868704700BF002004E0F0B5204B4E +:100C5000024618681F4B1F885D6893F90840C0F36F +:100C60000B06BE424FEA104022D09F89BE4221D0DF +:100C70001F8BBE4206D102240C2505FB04335D68A0 +:100C800093F90840B0F5805F16D041F20103984215 +:100C900008BF5A24013A0A44013D0B4693420DD243 +:100CA00015F9016F581C5EB100F8016C0346F5E7B9 +:100CB0000024E1E70124DFE74124EBE7184605E0E3 +:100CC0002C2590421D7001D2981C5C70401AF0BD1A +:100CD000002004E014220120022802BF024B4FF042 +:100CE00000529A61704700BF00080240022802BF0C +:100CF000024B4FF400529A61704700BF0008024057 +:100D0000022801BF024A536983F4005353617047BC +:100D10000008024010B50023934203D0CC5CC454B9 +:100D20000133F9E710BD000010B5013810F9013F9B +:100D30003BB191F900409C4203D11AB10131013A13 +:100D4000F4E71AB191F90020981A10BD1046FCE79B +:100D500003460246D01A12F9011B0029FAD1704746 +:100D600002440346934202D003F8011BFAE770479E +:100D70002DE9F8431F4D144695F824200746884670 +:100D800052BBDFF870909CB395F824302BB9202229 +:100D9000FF2148462F62FFF7E3FF95F82400C0F1DA +:100DA0000802A24228BF2246D6B24146920005EB75 +:100DB0008000FFF7AFFF95F82430A41B1E44F6B265 +:100DC000082E17449044E4B285F82460DBD1FFF785 +:100DD00027FF0028D7D108E02B6A03EB8203834268 +:100DE000CFD0FFF71DFF0028CBD10020BDE8F8834E +:100DF0000120FBE790230120024B1A78024B1A7066 +:100E0000704700BFD02301201022012038B5154CB7 +:100E1000154D204600F0F4FB2946204600F01CFC4E +:100E20002D681248EA6ED2F8043843F00203C2F883 +:100E3000043801F0E1F80E49284600F01BFDEA6E87 +:100E40000C48D2F804380C4923F00203C2F80438E5 +:100E5000A0424FF4E1330B6003D0BDE8384000F00E +:100E60002BBB38BDF8270120E83C000840420F00AA +:100E7000F03C0008D4230120B823012038B50B4BE7 +:100E80001A780B4B53F822500A4B9D4204460CD063 +:100E9000094B002118461822FFF762FF0460014643 +:100EA0002846BDE8384000F007BB38BDD0230120FC +:100EB000DC3B0008F8270120B823012000B59BB0D7 +:100EC000EFF3098168226846FFF724FFEFF30583FB +:100ED000044B9A6BDA6A9A6A9A6A9A6A9A6A9A6A66 +:100EE0009B6AFEE700ED00E000B59BB0EFF30981DF +:100EF00068226846FFF70EFFEFF30583044B9A6BF9 +:100F00009A6A9A6A9A6A9A6A9A6A9B6AFEE700BF24 +:100F100000ED00E000B59BB0EFF309816822684660 +:100F2000FFF7F8FEEFF30583034B5A6B9A6A9A6A50 +:100F30009A6A9A6A9B6AFEE700ED00E0FEE700000D +:100F400030B5094D0A4491420DD011F8013B58408B +:100F5000082340F30004013B2C4013F0FF0384EA14 +:100F60005000F6D1EFE730BD2083B8ED72B62023F4 +:100F700083F3118862B670470268436811430160C9 +:100F800003B1184770470000024A136843F0C003DA +:100F9000136070470010014013B50E4C204600F05E +:100FA0007FFA04F114000C49009400234FF480727E +:100FB00000F044F9094B0A4900944FF4807204F19F +:100FC000380000F0B9F9074A074BC4E9172302B00B +:100FD00010BD00BFD423012040240120890F000848 +:100FE000402501200010014000F36F0630B5037C5E +:100FF000214C002918BF0C46012B0CD11F4B9842E5 +:1010000009D11F4B5A6C42F010025A645A6E42F0DA +:1010100010025A665B6E2268036EC16D846603EB34 +:101020005203B3FBF2F36268150442BF23F00705D5 +:1010300003F0070343EA4503CB60A36843F0400392 +:101040004B60E36843F001038B6042F4967343F016 +:1010500001030B604FF0FF330B62510505D512F011 +:10106000102205D0B2F1805F04D080F8643030BD2A +:101070007F23FAE73F23F8E7E43B0008D42301206D +:10108000003802402DE9F047C66D3768F4693462D4 +:101090002107054617D014F0080118BF8021E20788 +:1010A00048BF41F02001A30748BF41F0400160075D +:1010B00048BF41F48071281DFFF758FFFFF75CFF20 +:1010C000002383F31188E20509D54FF40071281D30 +:1010D000FFF74CFFFFF750FF002383F311884FF019 +:1010E000000914F0200835D13B0614D505F1380964 +:1010F000200610D54846FFF739FF00F04FF90028C9 +:1011000035DA0821281DFFF737FF27F08003336009 +:10111000002383F31188790613D5620611D5FFF7F2 +:1011200025FFD5E913239A4208D12B6C33B1102146 +:10113000281D27F04007FFF71FFF3760002383F3C8 +:101140001188E30618D5AA6E1369ABB1BDE8F04764 +:1011500050691847FFF70AFF736A95F8641028462C +:10116000194000F0B5F989F31188F469B9E7B06264 +:1011700088F31188F469BBE7BDE8F08772B62023D5 +:1011800083F3118862B67047F8B515468268066920 +:10119000AA420B46816938BF8568761AB542044673 +:1011A0000BD218462A46FFF7B5FDA3692B44A3616D +:1011B000A3685B1BA3602846F8BD0CD918463246CD +:1011C000FFF7A8FDAF1BE1683A463044FFF7A2FDE8 +:1011D000E3683B44EBE718462A46FFF79BFDE368CC +:1011E000E5E7000083689342F7B51546044638BF2B +:1011F0008568D0E90460361AB5420BD22A46FFF75B +:1012000089FD63692B446361A36828465B1BA36067 +:1012100003B0F0BD0DD932460191FFF77BFD019976 +:10122000E068AF1B3A463144FFF774FDE3683B4486 +:10123000E9E72A46FFF76EFDE368E4E710B50A44E4 +:101240000024C361029B8460C0E90000C0E905116D +:10125000C1600261036210BD08B5D0E90532934256 +:1012600001D1826882B98268013282605A1C42616F +:101270001970D0E904329A4224BFC3684361002147 +:1012800000F0D6FE002008BD4FF0FF30FBE7000065 +:1012900070B504460D46FFF771FFA668A6B1A368B6 +:1012A000A269013BA360531CA36115782269934294 +:1012B00024BFE368A361E3690BB12046984700238C +:1012C00083F31188284607E02946204600F0A0FE57 +:1012D0000028E2DA86F3118870BD00002DE9F84F8E +:1012E000D0F81CA09946FFF749FF04460E469046E9 +:1012F00015464FF0000B65B12A4631462046FFF7F0 +:1013000043FF074660B94946204600F081FE0028A9 +:10131000F1D0002383F31188A8EB0500BDE8F88F16 +:10132000BAF1000F01D02046D0478BF31188ED1B96 +:101330003E44FFF723FFDEE7C0E90511C160C3614A +:101340001144009B8260C0E90000016103627047A4 +:10135000F8B504460D461646FFF710FFA768A7B17B +:10136000A368013BA36063695A1C62611D70D4E9E4 +:1013700004329A4224BFE3686361E3690BB12046FB +:101380009847002080F3118807E03146204600F09E +:101390003FFE0028E2DA87F31188F8BDD0E9052383 +:1013A0009A4210B501D182687AB9826801328260AE +:1013B0005A1C82611C7803699A4224BFC368836106 +:1013C000002100F035FE204610BD4FF0FF30FBE756 +:1013D0002DE9F84FD0F81CA09946FFF7CFFE044640 +:1013E0000E46904615464FF0000B65B12A46314631 +:1013F0002046FFF7F7FE074660B94946204600F051 +:1014000007FE0028F1D0002383F31188A8EB050024 +:10141000BDE8F88FBAF1000F01D02046D0478BF31A +:101420001188ED1B3E44FFF7A9FEDEE772B62023CC +:1014300083F3118862B67047026843681143016004 +:1014400003B11847704700001430FFF747BF000092 +:101450004FF0FF331430FFF741BF00003830FFF783 +:10146000B7BF00004FF0FF333830FFF7B1BF0000C7 +:101470001430FFF70DBF00004FF0FF311430FFF7BD +:1014800007BF00003830FFF763BF00004FF0FF32A6 +:101490003830FFF75DBF000000207047FFF77CBDCC +:1014A000044B03600023C0E902334360012303744B +:1014B000704700BFFC3B000810B50446FFF7B6FFBD +:1014C000FFF794FD02232374002383F3118810BDDA +:1014D00038B5C36904460D461BB904210844FFF71B +:1014E000ABFF294604F11400FFF7B6FE002806DA28 +:1014F000201D4FF48061BDE83840FFF79DBF38BD27 +:1015000072B6202383F3118862B67047026843687D +:101510001143016003B118477047000013B5446BD5 +:10152000D4F894341A681178042915D1217C022941 +:1015300012D11979128901238B4013420CD101A9D0 +:1015400004F14C0001F0AEFFD4F89444019B2179E2 +:101550000246206800F0DAF902B010BD143001F044 +:1015600033BF00004FF0FF33143001F02DBF0000F7 +:101570004C3002F003B800004FF0FF334C3001F064 +:10158000FDBF0000143001F003BF00004FF0FF3139 +:10159000143001F0FDBE00004C3001F0CFBF000060 +:1015A0004FF0FF324C3001F0C9BF000000207047FF +:1015B00010B5D0F894341A6811780429044617D16C +:1015C000017C022914D15979528901238B4013429D +:1015D0000ED1143001F096FE024648B1D4F894447E +:1015E0004FF4807361792068BDE8104000F07CB949 +:1015F00010BD0000406BFFF7DBBF0000704700002C +:101600007FB5124B036000234360C0E9023301251C +:1016100002260F4B057404460290019300F18402E8 +:10162000294600964FF48073143001F047FE094BB1 +:101630000294CDE9006304F523724FF480732946C8 +:1016400004F14C0001F00AFF04B070BD243C000816 +:10165000F51500081D15000808B50A68FFF750FFCA +:101660000B7902EB830318624B790D3342F82300A8 +:101670008B7913B102EB8302106202230374C0F86A +:101680009414002383F3118808BD000038B5037F4C +:10169000044613B190F85430ABB9201D0125022146 +:1016A000FFF734FF04F1140025776FF0010100F01B +:1016B000CBFC84F8545004F14C006FF00101BDE8FC +:1016C000384000F0C1BC38BD10B5012104460430DB +:1016D000FFF71CFF0023237784F8543010BD00006F +:1016E00038B504460025143001F000FE04F14C002A +:1016F000257701F0CBFE201D84F854500121FFF71F +:1017000005FF2046BDE83840FFF752BF90F85C3037 +:1017100003F06003202B07D190F85D20212A4FF0C1 +:10172000000303D81F2A06D800207047222AFBD1C5 +:10173000C0E9143303E0034A02650722426583656A +:10174000012070473822012037B5D0F894341A6848 +:101750001178042904461AD1017C022917D119797C +:10176000128901238B40134211D100F14C05284608 +:1017700001F04AFF58B101A9284601F093FED4F8C0 +:101780009444019B21790246206800F0BFF803B021 +:1017900030BD0000F0B500EB810385B01E6A044641 +:1017A0000D46F6B104EB8507301D0821FFF7A8FEB2 +:1017B000FFF7ACFEFB685B691B6806F14C001BB1D0 +:1017C000019001F07DFE019803A901F06BFE024635 +:1017D00048B1039B2946204600F098F8002383F384 +:1017E000118805B0F0BDFB685A691268002AF5D06F +:1017F0001B8A013B1340F1D104F15C02EAE70000CF +:101800000D3138B550F82140D4B1FFF779FED4F846 +:1018100094241368527903EB8203DB689B695D684B +:1018200045B104216018FFF771FE294604F1140048 +:1018300001F072FD2046FFF7BBFE002383F3118801 +:1018400038BD00007047000072B6202383F3118872 +:1018500062B6704701F0F8B810B50123044628229B +:1018600000F8243B0021FFF77BFA0023C4E9013391 +:1018700010BD000038B50025FFF7E6FF0446C0E9BB +:101880000355C0E90555C0E90755416001F0ECF882 +:101890000223237085F3118838BD000070B500EB7A +:1018A000810305465069DA600E46144618B11022CD +:1018B0000021FFF755FAA06918B110220021FFF7A7 +:1018C0004FFA31462846BDE8704001F097B9000054 +:1018D000826802F0011282600022C0E90422C0E99D +:1018E0000622026201F016BAF0B400EB81044789C7 +:1018F000E4680125A4698D403D43458123600023B0 +:10190000A2606360F0BC01F031BA0000F0B400EBFB +:1019100081040789E468012564698D403D430581A0 +:1019200023600023A2606360F0BC01F0ADBA000048 +:1019300070B50223002504460370C0E90255C0E9D2 +:101940000455C0E906554566056280F84C5001F023 +:10195000F1F863681B6823B129462046BDE8704052 +:10196000184770BD037880F868300523037043681A +:101970001B6810B504460BB1042198470023A360EF +:1019800010BD000090F86820436802701B680BB11E +:10199000052118477047000070B590F84C30044698 +:1019A00013B1002380F84C3004F15C02204601F0B2 +:1019B000D3F963689B68B3B994F85C3013F06005A1 +:1019C00033D00021204601F03FFC0021204601F0E9 +:1019D00031FC63681B6813B1062120469847062333 +:1019E00084F84C3070BD204698470028E4D0B4F805 +:1019F0006230626D9A4288BF636594F95C30656DB0 +:101A0000002B80F20281002D00F0F180092384F880 +:101A10004C30FFF719FF0021D4E914232046FFF7CB +:101A200075FF002383F31188DCE794F85D2003F051 +:101A30007F0343EA022340F20232934200F0C48063 +:101A400021D8B3F5807F48D00DD8012B3FD0022B91 +:101A500000F09280002BB4D104F1640222650222CE +:101A60006265A365C3E7B3F5817F00F09A80B3F5A3 +:101A7000407FA6D194F85E30012BA2D1B4F8643037 +:101A800043F0020332E0B3F5006F4DD017D8B3F541 +:101A9000A06F31D0A3F5C063012B92D8636894F88E +:101AA0005E205E6894F85F10B4F860302046B0475E +:101AB000002886D043682365036863651AE0B3F5A0 +:101AC000106F36D040F6024293427FF47AAF5B4B00 +:101AD0002365022363650023C3E794F85E30012B7E +:101AE0007FF46FAFB4F8643023F00203C4E91455F7 +:101AF000A4F86430A5657AE7B4F85C30B3F5A06F5C +:101B00000ED194F85E3084F86630204601F06AF811 +:101B100063681B6813B10121204698470323237093 +:101B20000023C4E914339CE704F167032365012310 +:101B3000C3E72378042B0FD12046FFF785FEFFF77C +:101B4000C7FE85F311880321636884F8675021700C +:101B50001B680BB12046984794F85E30002BDFD00D +:101B600084F867300423237063681B68002BD7D088 +:101B7000022120469847D3E794F860301D0603F011 +:101B80000F0120460AD501F0D9F8012804D0022817 +:101B90007FF417AF2A4B9BE72A4B99E701F0C0F877 +:101BA000F3E794F85E30002B7FF40BAF94F86030CD +:101BB00013F00F01B4D01A06204602D501F058FBED +:101BC000AEE701F04BFBABE794F85E30002B7FF4FF +:101BD000F8AE94F8603013F00F01A1D01B06204638 +:101BE00002D501F031FB9BE701F024FB98E71423B9 +:101BF00084F84C30FFF728FE2A462B46294620461B +:101C0000FFF772FE85F31188ECE65DB1152384F8C9 +:101C10004C30FFF719FE0021D4E914232046FFF7CA +:101C200063FEFEE60B2384F84C30FFF70DFE2A46D8 +:101C30002B4629462046FFF769FEE3E7543C00089F +:101C40004C3C0008503C000838B590F84C30044635 +:101C5000002B3CD0063BDAB20F2A32D80F2B30D8FB +:101C6000DFE803F0352F2F0821302F2F2F2F2F2FB4 +:101C70002F2F3535456DB0F862309D4213D2C368C1 +:101C80001B8AB5FBF3F203FB125565B9FFF7DCFDC8 +:101C90002A462B462946FFF739FE85F311880A2389 +:101CA00084F84C300DE0142384F84C30FFF7CCFD61 +:101CB00000231A4619462046FFF716FE002383F339 +:101CC000118838BD836D03B198470023E8E70021F0 +:101CD000204601F0B9FA0021204601F0ABFA636812 +:101CE0001B6813B10621204698470623D8E7000059 +:101CF00010B590F84C30142B044628D017D8062B7A +:101D000005D001D81BB110BD093B022BFBD8002127 +:101D1000204601F099FA0021204601F08BFA636811 +:101D20001B6813B1062120469847062318E0152B9F +:101D3000E9D10B2380F84C30FFF786FD00231A46CB +:101D40001946FFF7E3FD002383F31188DBE7C3683F +:101D50009B695B68002BD6D1836D03B19847002344 +:101D600084F84C30CFE70000024B0022C3E9003377 +:101D70009A60704740260120002303748268054B57 +:101D80001B6899689142FBD25A68036042601060F8 +:101D9000586070474026012008B572B6202383F3AF +:101DA000118862B6037C032B05D0042B0DD02BB910 +:101DB00083F3118808BD436900221A604FF0FF3396 +:101DC0004361FFF7D9FF0023F2E7D0E90032136047 +:101DD0005A60F3E7002303748268054B1B68996817 +:101DE0009142FBD85A6803604260106058607047A7 +:101DF00040260120054B19690874186802681A60AA +:101E00005360186101230374FEF790BA4026012045 +:101E100030B54B1C0B4D87B0044610D02B690A4AD5 +:101E200001A800F02DF92046FFF7E4FF049B13B151 +:101E300001A800F061F92B69586907B030BDFFF7C0 +:101E4000D9FFF8E740260120991D000838B50C4D50 +:101E500041612B6981689A689142044603D8BDE8C4 +:101E60003840FFF789BF1846FFF7B4FF01232C6104 +:101E7000014623742046BDE83840FEF757BA00BF3C +:101E800040260120044B1A681B6990689B689842A1 +:101E900094BF0020012070474026012010B5084C57 +:101EA000236820691A6822605460012223611A7431 +:101EB000FFF790FF01462069BDE81040FEF736BAF3 +:101EC0004026012008B5FFF7DDFF18B1BDE8084046 +:101ED000FFF7E4BF08BD0000FFF7E0BFFEE700002A +:101EE00010B50C4CFFF740FF00F0BCF80A49802207 +:101EF000204600F043F8012344F8180C037400F066 +:101F00007DFC002383F3118862B60448BDE81040CD +:101F100000F054B868260120583C0008683C0008CE +:101F200000F024B9EFF3118030B9EFF305832022DC +:101F300072B682F3118862B67047000010B530B9EE +:101F4000EFF30584C4F3080414B180F3118810BDC5 +:101F5000FFF7B8FF84F31188F9E70000034A5168DE +:101F600053685B1A9842FBD8704700BF001000E02E +:101F700072B6202383F3118862B670478260022212 +:101F8000028270478368A3F17C0243F80C2C02693B +:101F900043F83C2C426943F8382C074A43F81C2C80 +:101FA000C26843F8102C022203F8082C002203F820 +:101FB000072CA3F1180070474503000810B5FFF780 +:101FC000D7FFFFF7DFFF00210446FFF73FFF0023A5 +:101FD00083F31188204610BD024B1B6958610F2006 +:101FE000FFF708BF4026012008B5FFF7C1FFBDE895 +:101FF0000840FFF7F1BF000008B501460820FFF7D1 +:10200000B7FFFFF705FF002383F3118808BD000029 +:1020100049B1064B42681B6918605A6013604360FF +:102020000420FFF7F5BE4FF0FF3070474026012037 +:102030000368984206D01A680260506059611846D9 +:10204000FFF79ABE7047000038B504460D46206879 +:10205000844200D138BD036823605C604561FFF7AE +:102060008BFEF4E7054B03F11402C3E905224FF0A0 +:10207000FF310022C3E90712704700BF402601204C +:1020800070B51C4EC0E9032305460C4601F0EEFA7C +:10209000334653F8142F9A420DD13062C5E901241A +:1020A0002A600A2C2CBF00190A30C6E90555BDE884 +:1020B000704001F0C9BA316A431AE31838BF1C46B0 +:1020C0009368A34202D9081901F0CCFA73699A689F +:1020D00094420CD85A68AC602B606A6015609A68AC +:1020E0005D60121B9A604FF0FF33F36170BD1B6897 +:1020F000A41AECE74026012038B51B4C63699842CE +:102100000DD0D0E9003213605A6000228168C260AD +:102110009A680A449A604FF0FF33E36138BD224663 +:10212000036842F8143F002193425A60C16003D112 +:10213000BDE8384001F090BA9A688168256A0A447F +:102140009A6001F093FA63699A68411B8A42E5D963 +:10215000AB181D1A092D206A98BF01F10A02BDE8CB +:102160003840104401F07EBA402601202DE9F041AC +:10217000194C002704F11406656901F077FA236A07 +:10218000AA68C11A8A4217D813442362D5E90032DB +:1021900013605A606369D5F80C80EF60B34201D1D7 +:1021A00001F05AFA87F311882869C04772B62023D4 +:1021B00083F3118862B6DFE76169B14209D0134445 +:1021C0001B1ABDE8F0410A2B2CBFC0180A3001F0E1 +:1021D00049BABDE8F08100BF4026012000207047C9 +:1021E000FEE70000704700004FF0FF30704700002E +:1021F00072B6202383F3118862B6704702290CD08F +:10220000032904D00129074818BF00207047032A7A +:1022100005D8054800EBC20070470448704700200D +:10222000704700BF4C3D000848220120003D0008D7 +:1022300070B59AB00546084601A9144600F0BEF8EC +:1022400001A8FEF785FD431C5B00C5E900340022B0 +:10225000237003236370C6B201AB02341046D1B2BF +:102260008E4204F1020401D81AB070BD13F8011BAC +:1022700004F8021C04F8010C0132F0E708B5044828 +:10228000FFF7B6FFFFF760FA002383F3118808BD5C +:10229000F827012090F85C3003F01F02012A07D1D3 +:1022A00090F85D200B2A03D10023C0E9143315E018 +:1022B00003F06003202B08D1B0F860302BB990F800 +:1022C0005D20212A03D81F2A04D8FFF71FBA222A2B +:1022D000EBD0FAE7034A02650722426583650120D5 +:1022E000704700BF3F22012007B5052916D8DFE857 +:1022F00001F018150318181E104A0121FFF778FF86 +:102300000190FFF7CBFA01980D4A0221FFF7C6FAB8 +:102310000C48FFF7E5F9002383F3118803B05DF85B +:1023200004FB0848FFF764FFFFF7B0F9F3E705483F +:10233000FFF75EFFFFF7C8F9EDE700BFA03C00081C +:10234000C43C0008F827012038B50C4D0C4C0D4951 +:102350002A4604F10800FFF76BFF05F1CA0204F1F9 +:1023600010000949FFF764FF05F5CA7204F118006F +:102370000649BDE83840FFF75BBF00BFC02C012015 +:1023800048220120803C00088A3C0008953C000857 +:1023900070B5044608460D46FEF7DAFCC6B2204684 +:1023A000013403780BB9184670BD32462946FEF752 +:1023B000BBFC0028F3D10120F6E700002DE9F84F1F +:1023C00005460C46FEF7C4FC2B49C6B22846FFF76B +:1023D000DFFF08B10536F6B228492846FFF7D8FFD7 +:1023E00008B11036F6B2632E0DD8DFF88C80DFF816 +:1023F0008C90234FDFF890A0DFF890B02E7846B98C +:102400002670BDE8F88F29462046BDE8F84F01F058 +:10241000C7BB252E2BD1072241462846FEF784FC58 +:1024200058B9DBF800302360DBF804306360DBF878 +:102430000830A36007350C34E0E7082249462846F7 +:10244000FEF772FC98B90F4BA21C197809090232E9 +:10245000C95D02F8041C13F8011B01F00F0153457C +:10246000C95D02F8031CF0D118340835C6E704F83A +:10247000016B0135C2E700BF6C3D0008953C0008C8 +:10248000813D000820F4F01F2CF4F01F743D00087B +:10249000BFF34F8F024AD368DB03FCD4704700BF01 +:1024A000003C024008B5074B1B7853B9FFF7F0FF1B +:1024B000054B1A69002ABFBF044A5A6002F18832EC +:1024C0005A6008BD1E2F0120003C024023016745D1 +:1024D00008B5054B1B7833B9FFF7DAFF034A1369D8 +:1024E00043F00043136108BD1E2F0120003C024051 +:1024F0000728F0B516D80C4C0C4923787BB90C4D45 +:102500000E4608234FF0006255F8047B46F8042B72 +:10251000013B13F0FF033A44F6D10123237051F835 +:102520002000F0BD0020FCE7402F0120202F0120DB +:10253000943D0008014B53F820007047943D00087B +:1025400008207047072810B5044601D9002010BDA7 +:10255000FFF7CEFF064B53F824301844C21A0BB9CC +:102560000120F4E712680132F0D1043BF6E700BF26 +:10257000943D0008072838B5044628D8FFF7D2FC58 +:10258000FFF786FFFFF78EFF124AF323D360E300C5 +:10259000DBB243F4007343F002031361136943F4A5 +:1025A0008033136105462046FFF772FFFFF7A0FF57 +:1025B000094B53F8241000F0E9F82846FFF788FF8C +:1025C000FFF7BCFC2046BDE83840FFF7BBBF00204A +:1025D00038BD00BF003C0240943D000812F00103EA +:1025E0002DE9F04105460E4614464BD18218B2F152 +:1025F000016F61D8314B1B6813F001035CD0304F81 +:10260000FFF790FCFFF74EFFF323FB60FFF740FF5F +:10261000314640F20128032C18D824F00104284E3A +:102620000C446D1A40F20118A142336905EB010711 +:102630002AD123F001033361FFF74AFFFFF77EFC45 +:102640000120BDE8F081043C0435E4E7AB07E4D1A8 +:102650003B6923F440733B613B6943EA08033B61F8 +:1026600051F8046B2E60BFF34F8FFFF711FF2B68FB +:102670009E42E8D03B6923F001033B61FFF728FF4E +:10268000FFF75CFC0020DCE723F44073336133691F +:1026900043EA080333610B883B80BFF34F8FFFF79A +:1026A000F7FE3F8831F8023BBFB2BB42BCD0336972 +:1026B00023F001033361E1E71846C2E70038024026 +:1026C000003C0240084908B50B7828B11BB9FFF758 +:1026D000E9FE01230B7008BD002BFCD0BDE80840CB +:1026E0000870FFF7F5BE00BF1E2F012010B5024491 +:1026F000064BD2B2904200D110BD441C00B253F838 +:10270000200041F8040BE0B2F4E700BF502800407D +:102710000F4B30B51C6F240407D41C6F44F40074B5 +:102720001C671C6F44F400441C670A4C236843F484 +:10273000807323600244084BD2B2904200D130BD76 +:10274000441C00B251F8045B43F82050E0B2F4E7B7 +:1027500000380240007000405028004007B50122B8 +:1027600001A90020FFF7C2FF019803B05DF804FB48 +:1027700013B50446FFF7F2FFA04205D0012201A9DC +:1027800000200194FFF7C4FF02B010BD0144BFF365 +:102790004F8F064B884204D3BFF34F8FBFF36F8F29 +:1027A0007047C3F85C022030F4E700BF00ED00E0A2 +:1027B000034B1A681AB9034AD2F874281A60704792 +:1027C000442F01200030024008B5FFF7F1FF024B13 +:1027D0001868C0F3407008BD442F0120EFF309834F +:1027E00005494A6B22F001024A63683383F3098882 +:1027F000002383F31188704700EF00E0202080F36E +:10280000118862B60D4B0E4AD96821F4E0610904C3 +:10281000090C0A43DA60D3F8FC200A4942F08072BE +:10282000C3F8FC20084AC2F8B01F116841F001014A +:1028300011601022DA7783F82200704700ED00E083 +:102840000003FA0555CEACC5001000E010B572B615 +:10285000202383F3118862B60E4B5B6813F4006388 +:1028600014D0F1EE103AEFF30984683C4FF0807316 +:10287000E361094BDB6B236684F30988FFF702FBF6 +:1028800010B1064BA36110BD054BFBE783F3118824 +:10289000F9E700BF00ED00E000EF00E0570300089B +:1028A0005A03000870B5BFF34F8FBFF36F8F1A4AFA +:1028B0000021C2F85012BFF34F8FBFF36F8F5369DF +:1028C00043F400335361BFF34F8FBFF36F8FC2F8F0 +:1028D0008410BFF34F8FD2F88030C3F3C900C3F325 +:1028E0004E335B0143F6E07403EA0406014646EA10 +:1028F00081750139C2F86052F9D2203B13F1200FE3 +:10290000F2D1BFF34F8F536943F480335361BFF368 +:102910004F8FBFF36F8F70BD00ED00E0FEE700004A +:102920000A4B0B480B4A90420BD30B4BDA1C121A82 +:10293000C11E22F003028B4238BF00220021FEF7A5 +:102940000FBA53F8041B40F8041BECE7803F000863 +:1029500058300120583001205830012070470000C5 +:1029600070B5D0E91B439E6800224FF0FF3504EBA1 +:1029700042135101D3F800090028BEBFD3F8000963 +:1029800040F08040C3F80009D3F8000B0028BEBF18 +:10299000D3F8000B40F08040C3F8000B01326318FD +:1029A0009642C3F80859C3F8085BE0D24FF0011310 +:1029B000C4F81C3870BD00001D4B03EB80022DE9EC +:1029C000F043D2F80CC0DD6EDCF81420461CD2F8BF +:1029D00000E005EB063605EB4018516871450AD357 +:1029E000D5F83438012202FA00F023EA0000C5F8D5 +:1029F0003408BDE8F083BCF81040AEEB0103A342FD +:102A000028BF2346D8F81849A4B2B3EB840FF0D8F6 +:102A10009468A4F1040959F8047F3760A4EB09070E +:102A20001F44042FF7D81C440B4494605360D4E730 +:102A3000482F0120890141F02001016103699B06B3 +:102A4000FCD41220FFF78ABA10B5054C2046FEF7D9 +:102A500003FF4FF0A043E366024B236710BD00BFA6 +:102A6000482F0120D83D000870B50378012B05469A +:102A700050D12A4BC46E98421BD1294B5A6B42F05D +:102A800080025A635A6D42F080025A655A6D5A6943 +:102A900042F080025A615A6922F080025A610E2186 +:102AA00043205B6900F0EEFB1E4BE3601E4BC4F855 +:102AB00000380023C4F8003EC0232360EE6E4FF4BC +:102AC0000413A3633369002BFCDA012333610C2068 +:102AD000FFF744FA3369DB07FCD41220FFF73EFA14 +:102AE0003369002BFCDA0026A6602846FFF738FF82 +:102AF0006B68C4F81068DB68C4F81468C4F81C6814 +:102B00004BB90A4BA3614FF0FF336361A36843F0F5 +:102B10000103A36070BD064BF4E700BF482F0120FE +:102B2000003802404014004003002002003C30C046 +:102B3000083C30C0F8B5C46E054600212046FFF7BA +:102B400079FF296F00234FF001128F68C4F83438E1 +:102B50004FF00066C4F81C284FF0FF3004EB43121E +:102B600001339F42C2F80069C2F8006BC2F808093D +:102B7000C2F8080BF2D20B68EA6E6B67636210232F +:102B80001361166916F01006FBD11220FFF7E6F963 +:102B9000D4F8003823F4FE63C4F80038A36943F482 +:102BA000402343F01003A3610923C4F81038C4F88C +:102BB00014380A4BEB604FF0C043C4F8103B084B8D +:102BC000C4F8003BC4F81069C4F800396B6F03F116 +:102BD000100243F480136A67A362F8BDB43D000895 +:102BE00040800010C26E90F86610D2F8003823F4CE +:102BF000FE6343EA0113C2F8003870472DE9F84339 +:102C000000EB8103C56EDA68166806F00306731ED2 +:102C1000022B05EB41130C4680460FFA81F94FEA6F +:102C200041104FF00001C3F8101B4FF0010104F1F7 +:102C3000100398BFB60401FA03F391698EBF334EB7 +:102C400006F1805606F5004600293AD0578A04F16D +:102C50005801490137436F50D5F81C180B43C5F88C +:102C60001C382B180021C3F8101953690127611E65 +:102C7000A7409BB3138A928B9B08012A88BF5343BA +:102C8000D8F87420981842EA034301F1400205EB9A +:102C90008202C8F87400214653602846FFF7CAFE36 +:102CA00008EB8900C3681B8A43EA845348346401F3 +:102CB0001E432E51D5F81C381F43C5F81C78BDE8BB +:102CC000F88305EB4917D7F8001B21F40041C7F83A +:102CD000001BD5F81C1821EA0303C0E704F13F03E9 +:102CE00005EB83030A4A5A6028462146FFF7A2FEF5 +:102CF00005EB4910D0F8003923F40043C0F800393F +:102D0000D5F81C3823EA0707D7E700BF008000107A +:102D100000040002026F12684267FFF721BE000044 +:102D20005831C36E49015B5813F4004004D013F4CA +:102D3000001F0CBF02200120704700004831C36E05 +:102D400049015B5813F4004004D013F4001F0CBF7A +:102D5000022001207047000000EB8101CB68196A56 +:102D60000B6813604B6853607047000000EB8103F1 +:102D700030B5DD68AA691368D36019B9402B84BFE8 +:102D8000402313606B8A1468C26E1C44013CB4FB80 +:102D9000F3F46343033323F0030302EB411043EAEC +:102DA000C44343F0C043C0F8103B2B6803F0030357 +:102DB000012B09B20ED1D2F8083802EB411013F4FE +:102DC000807FD0F8003B14BF43F0805343F00053A2 +:102DD000C0F8003B02EB4112D2F8003B43F0044341 +:102DE000C2F8003B30BD00002DE9F041254DEE6EEC +:102DF00006EB40130446D3F8087BC3F8087B38077A +:102E00000AD5D6F81438190706D505EB84032146F0 +:102E1000DB6828465B689847FA0721D5D6F814384E +:102E2000DB071DD505EB8403D968DCB98B69488ABB +:102E30005A68B2FBF0F600FB16229AB91868DA68F5 +:102E400090420FD2121AC3E9002472B6202383F3F2 +:102E5000118862B60B482146FFF788FF84F311887A +:102E6000BDE8F081012303FA04F26B8923EA02032F +:102E70006B81CB68002BF3D021460248BDE8F041BE +:102E8000184700BF482F012000EB810370B5DD68B3 +:102E9000C36E6C692668E6604A0156BB1A444FF45B +:102EA0000020C2F810092A6802F00302012A0AB2BF +:102EB0000ED1D3F8080803EB421410F4807FD4F845 +:102EC000000914BF40F0805040F00050C4F80009E1 +:102ED00003EB4212D2F8000940F00440C2F80009A6 +:102EE000D3F83408012202FA01F10143C3F834187F +:102EF00070BD19B9402E84BF4020206020682E8A02 +:102F00008419013CB4FBF6F440EAC44040F00050A0 +:102F10001A44C6E7F8B504461F48C56E05EB4413CE +:102F2000D3F80869C3F80869F10719D5D5F810383E +:102F3000DA0715D500EB8403D9684B691F68DA6896 +:102F400097421AD2D21B00271A605F6072B6202304 +:102F500083F3118862B62146FFF796FF87F3118845 +:102F6000330617D5D5F834280123A340134211D0D6 +:102F70002046BDE8F840FFF71FBD012303FA04F225 +:102F8000038923EA020303818B68002BE8D02146E2 +:102F90009847E5E7F8BD00BF482F01202DE9F74F1E +:102FA000A34CE66E7569B3691D4015F480587561D0 +:102FB00007D02046FEF7BCFC03B0BDE8F04FFFF79A +:102FC00045BC002D12DAD6F8003E99489F071EBF77 +:102FD000D6F8003E23F00303C6F8003ED6F80438C6 +:102FE00023F00103C6F80438FEF7CCFC280505D50C +:102FF0008F48FFF7B5FC8E48FEF7B4FCA9040CD54A +:10300000D6F8083813F0060FF36823F470530CBF9A +:1030100043F4105343F4A053F3602A0704D56368C4 +:10302000DB680BB182489847EB0200F18A80AF025F +:1030300027D5D4F86C90DFF8F8B100274FF0010ADB +:1030400009EB4712D2F8003B03F44023B3F5802F7D +:1030500011D1D2F8003B002B0DDA62890AFA07F38E +:1030600022EA0303638104EB8703DB68DB6813B1A7 +:10307000394658469847236F01379B68FFB29F42F5 +:10308000DED9E80618D5E76E3A6AC2F30A1002F0F4 +:103090000F0302F4F012B2F5802F00F09D80B2F51C +:1030A000402F09D104EB83030022DB681B6A07F57C +:1030B0008057904240F082802B03D6F818481DD5E7 +:1030C000E70302D50020FFF78FFEA60302D50120FB +:1030D000FFF78AFE600302D50220FFF785FE210379 +:1030E00002D50320FFF780FEE20202D50420FFF79D +:1030F0007BFEA30202D50520FFF776FE6F037FF566 +:103100005BAFE60702D50020FFF704FFA50702D555 +:103110000120FFF7FFFE600702D50220FFF7FAFE4D +:10312000210702D50320FFF7F5FEE20602D50420B1 +:10313000FFF7F0FEA3067FF53FAF0520FFF7EAFE9D +:103140003AE7E36EDFF8E8B0019300274FF0010A99 +:10315000236F9B685FFA87F999453FF668AF019B3B +:1031600003EB4913D3F8002902F44022B2F5802F73 +:1031700022D1D3F80029002A1EDAD3F8002942F020 +:103180009042C3F80029D3F80029002AFBDBE06E47 +:103190004946FFF74FFC22890AFA09F322EA0303A2 +:1031A000238104EB8903DB689B6813B149465846C9 +:1031B00098474846FFF700FC0137C9E7910708BF69 +:1031C000D7F80080072A98BF03F8018B02F10102AB +:1031D00098BF4FEA18286CE7023304EB830207F527 +:1031E00080575268D2F818C0DCF80820DCE9001CCF +:1031F000A1EB0C0C002188420AD104EB8304636824 +:103200009B699A6802449A605A6802445A6053E77C +:1032100011F0030F08BFD7F800808C4588BF02F873 +:10322000018B01F1010188BF4FEA1828E3E700BFD5 +:10323000482F0120C36E03EB4111D1F8003B43F44A +:103240000013C1F8003B7047C36E03EB4111D1F886 +:10325000003943F40013C1F800397047C36E03EB23 +:103260004111D1F8003B23F40013C1F8003B704733 +:10327000C36E03EB4111D1F8003923F40013C1F8F8 +:103280000039704700F1604303F561430901C9B299 +:1032900083F80013012200F01F039A4043099B00AA +:1032A00003F1604303F56143C3F880211A6070475E +:1032B00072B6202383F3118862B6704730B5039C41 +:1032C0000172043304FB0325C0E90653049B036326 +:1032D0000021059BC160C0E90000C0E90422C0E9EB +:1032E0000842C0E90A11436330BD0000416A002270 +:1032F000C0E90411C0E90A22C2606FF00101FEF7C3 +:10330000A3BE0000D0E90432934201D1C2680AB9D9 +:10331000181D70470020704703691960C2680132A8 +:10332000C260C269134482690361934224BF436A45 +:1033300003610021FEF77CBE38B504460D46E36804 +:103340003BB16269131D1268A3621344E36200205B +:1033500007E0237A33B929462046FEF759FE0028B4 +:10336000EDDA38BD6FF00100FBE70000C368C26909 +:10337000013BC3604369134482694361934224BFA4 +:10338000436A436100238362036B03B118477047AC +:1033900070B5FFF78DFF866A04463EB9FFF7CCFF94 +:1033A000054618B186F31188284670BDA36AE26A03 +:1033B00013F8015BA362934202D32046FFF7D6FFC6 +:1033C000002383F31188EFE72DE9F0479846FFF7D4 +:1033D0006FFF002504460E461746A946D4F828A0DC +:1033E000BAF1000F09D141462046FFF7A5FF20B1F1 +:1033F0008AF311882846BDE8F087D4E90A12A7EBC2 +:10340000050A521A924528BF9246BAF1400F1BD9BD +:10341000334601F1400251F8040B43F8040B91428A +:10342000F9D1A36A40334036A3624035D4E90A2378 +:103430009A4202D32046FFF799FF89F31188BD42D3 +:10344000D8D2FFF735FFC9E730465246FDF762FC98 +:10345000A36A53445644A3625544E7E710B5029C5F +:103460000172043304FB0321C0E906130023C0E901 +:103470000A33039B0363049BC460C0E90000C0E9F6 +:103480000422C0E90842436310BD0000026AC26022 +:10349000426AC0E904220022C0E90A226FF0010159 +:1034A000FEF7D2BDD0E904239A4201D1C26822B905 +:1034B000184650F8043B0B6070470020704700002E +:1034C000C368C2690133C3604369134482694361BD +:1034D000934224BF436A43610021FEF7A9BD000067 +:1034E00038B504460D46E3683BB123691A1DA26254 +:1034F000E2691344E362002007E0237A33B92946E6 +:103500002046FEF785FD0028EDDA38BD6FF001009A +:10351000FBE7000003691960C268013AC260C26932 +:10352000134482690361934224BF436A0361002309 +:103530008362036B03B118477047000070B5FFF753 +:10354000B7FE866A0D46044611462EB9FFF7C8FF3E +:1035500010B186F3118870BDA36A1D70A36AE26A78 +:1035600001339342A36204D3E16920460439FFF793 +:10357000D1FF002080F31188EDE700002DE9F0472E +:103580009946FFF795FE002604460D469046B24642 +:10359000A76A4FB949462046FFF7A2FF20B187F33B +:1035A00011883046BDE8F087D4E90A073A1AA8EB3B +:1035B0000607974228BF1746402F1BD905F1400345 +:1035C00055F8042B40F8042B9D42F9D1A36A4033EF +:1035D000A3624036D4E90A239A4204D3E169204623 +:1035E0000439FFF797FF8AF311884645D9D2FFF7D0 +:1035F0005FFECDE729463A46FDF78CFBA36A3B44C4 +:103600003D44A3623E44E5E7D0E904239A4217D142 +:10361000C3689BB1836A8BB1043B9B1A0ED01360C5 +:10362000C368013BC360C3691A44836902619A425B +:1036300024BF436A03610023836201231846704755 +:103640000023FBE700F094B84FF08043002258635A +:103650001A610222DA6070474FF080430022DA607C +:10366000704700004FF08043586370474FF080432D +:10367000586A70474B6843608B688360CB68C3604F +:103680000B6943614B6903628B6943620B6803609A +:103690007047000008B52C4B2C481A6940F2FF71A6 +:1036A0000A431A611A6922F4FF6222F007021A61C2 +:1036B0001A691A6B0A431A631A6D0A431A65244A77 +:1036C0001B6D1146FFF7D6FF02F11C0100F580606B +:1036D000FFF7D0FF02F1380100F58060FFF7CAFF65 +:1036E00002F1540100F58060FFF7C4FF02F17001A0 +:1036F00000F58060FFF7BEFF02F18C0100F58060ED +:10370000FFF7B8FF02F1A80100F58060FFF7B2FFF4 +:1037100002F1C40100F58060FFF7ACFF02F1E001A7 +:1037200000F58060FFF7A6FF02F1FC0100F5806064 +:10373000FFF7A0FF02F58C7100F58060FFF79AFF9C +:10374000BDE8084000F08AB800380240000002409E +:10375000E43D000808B500F003FAFEF7C1FBFFF7EF +:1037600027F8BDE80840FEF7EFBD000070470000F5 +:103770000F4B1A6C42F001021A641A6E42F00102F9 +:103780001A660C4A1B6E936843F0010393604FF076 +:1037900080436B229A624FF0FF32DA6200229A6114 +:1037A0005A63DA605A6001225A611A60704700BF9A +:1037B00000380240002004E04FF0804208B5116953 +:1037C000D3680B40D9B2C9439B07116109D572B6C2 +:1037D000202383F3118862B6FEF7A2FB002383F354 +:1037E000118808BD1B4B1A696FEA42526FEA5252A8 +:1037F0001A611A69C2F30A021A614FF0FF301A699E +:103800005A69586100215A6959615A691A6A62F005 +:1038100080521A621A6A02F080521A621A6A5A6A4E +:1038200058625A6A59625A6A0B4A106840F48070AA +:103830001060186F00F44070B0F5007F1EBF4FF4A9 +:10384000803018671967536823F40073536000F0E1 +:103850005FB900BF0038024000700040374B4FF0A6 +:1038600080521A64364A4FF4404111601A6842F09F +:1038700001021A601A689207FCD59A6822F00302C6 +:103880009A602E4B9A6812F00C02FBD1196801F075 +:10389000F90119609A601A6842F480321A601A6855 +:1038A0009003FCD55A6F42F001025A67234B5A6FBE +:1038B0009107FCD5234A5A601A6842F080721A6058 +:1038C0001F4B5A685204FCD51A6842F480321A60C1 +:1038D0005A68D003FCD51A6842F400321A60184ABC +:1038E00053689903FCD5154B1A689201FCD5164A0A +:1038F0009A6040F20112C3F88C200022C3F8902095 +:10390000124A40F207331360136803F00F03072BCA +:10391000FAD10A4B9A6842F002029A609A6802F061 +:103920000C02082AFAD15A6C42F480425A645A6E48 +:1039300042F480425A665B6E704700BF0038024016 +:1039400000700040086C400900948838003C024038 +:10395000074A08B5536903F00103536123B1054ACF +:1039600013680BB150689847BDE80840FEF76EBF7A +:10397000003C0140D82F0120074A08B5536903F0E5 +:103980000203536123B1054A93680BB1D06898478D +:10399000BDE80840FEF75ABF003C0140D82F012087 +:1039A000074A08B5536903F00403536123B1054A7C +:1039B00013690BB150699847BDE80840FEF746BF50 +:1039C000003C0140D82F0120074A08B5536903F095 +:1039D0000803536123B1054A93690BB1D069984735 +:1039E000BDE80840FEF732BF003C0140D82F01205F +:1039F000074A08B5536903F01003536123B1054A20 +:103A0000136A0BB1506A9847BDE80840FEF71EBF25 +:103A1000003C0140D82F0120164B10B55C6904F41E +:103A200078725A61A30604D5134A936A0BB1D06A1F +:103A30009847600604D5104A136B0BB1506B98473A +:103A4000210604D50C4A936B0BB1D06B9847E20565 +:103A500004D5094A136C0BB1506C9847A30504D5E3 +:103A6000054A936C0BB1D06C9847BDE81040FEF747 +:103A7000EDBE00BF003C0140D82F0120194B10B50E +:103A80005C6904F47C425A61620504D5164A136DE0 +:103A90000BB1506D9847230504D5134A936D0BB1B4 +:103AA000D06D9847E00404D50F4A136E0BB1506EE9 +:103AB0009847A10404D50C4A936E0BB1D06E984779 +:103AC000620404D5084A136F0BB1506F9847230462 +:103AD00004D5054A936F0BB1D06F9847BDE81040ED +:103AE000FEF7B4BE003C0140D82F012008B50348C2 +:103AF000FDF7C8FABDE80840FEF7A8BED4230120B0 +:103B000008B5FFF759FEBDE80840FEF79FBE00006C +:103B1000062108B50846FFF7B5FB06210720FFF789 +:103B2000B1FB06210820FFF7ADFB06210920FFF7B6 +:103B3000A9FB06210A20FFF7A5FB06211720FFF7A6 +:103B4000A1FB06212820FFF79DFB07211C20FFF782 +:103B500099FBBDE808400C212520FFF793BB00002E +:103B600008B5FFF73FFE00F00DF8FDF797FCFDF7F5 +:103B700071FEFDF743FDFFF7F9FDBDE80840FFF7D3 +:103B800061BD00000023054A19460133102BC2E92C +:103B9000001102F10802F8D1704700BFD82F0120B0 +:103BA000034611F8012B03F8012B002AF9D17047C5 +:103BB00053544D3332463F3F3F3F3F3F0053544DF8 +:103BC000333246375B347C355D780053544D3332A5 +:103BD00046375B367C375D7800000000F82701200F +:103BE000D423012000960000000000000000000027 +:103BF00000000000000000000000000000000000C5 +:103C000065140008511400088D1400087914000888 +:103C100085140008711400085D1400084914000898 +:103C200099140008000000007915000865150008C7 +:103C3000A11500088D1500089915000885150008C4 +:103C4000711500085D150008AD15000800000000A2 +:103C500001000000000000006D61696E00000000BE +:103C600069646C6500000000603C0008802601204B +:103C7000F827012001000000DD1E00080000000000 +:103C80004172647550696C6F740025424F41524413 +:103C9000252D424C002553455249414C250000003A +:103CA000020000000000000095170008011800083D +:103CB00040004000902C0120A02C012002000000B8 +:103CC000000000000300000000000000451800088C +:103CD0000000000010000000B02C012000000000D7 +:103CE0000100000000000000482F01200101020037 +:103CF000E9220008FD210008952200087D22000825 +:103D000043000000083D000809024300020100C012 +:103D1000320904000001020201000524001001051F +:103D20002401000104240202052406000107058283 +:103D3000030800FF09040100020A00000007050152 +:103D40000240000007058102400000001200000050 +:103D5000543D0008120110010200004009124157B1 +:103D600000020102030100000403090425424F413F +:103D7000524425005265617065724637343576329B +:103D800000303132333435363738394142434445D7 +:103D9000460000000080000000800000008000005D +:103DA0000080000000000200000004000000040089 +:103DB000000004000000000099190008491C0008D8 +:103DC000F11C000840004000C02F0120C02F01203E +:103DD00001000000D02F0120800000004001000001 +:103DE000050000000001A86A00000000AAAAAAAA13 +:103DF00000011464FFFF00000000000070A70A002B +:103E00000000000000000000AAAAAAAA000000000A +:103E1000FFFF0000000000000000000000000004A0 +:103E200000000000AAAAAAAA00000000FFDF00000C +:103E30000000000000000000000000000000000082 +:103E4000AAAAAAAA00000000FFFF000000000000CC +:103E5000000000000001000000000000AAAAAAAAB9 +:103E600000010000FFFF0000000000000000000053 +:103E70000000000000000000AAAAAAAA000000009A +:103E8000FFFF000000000000000000000000000034 +:103E900000000000AAAAAAAA00000000FFFF00007C +:103EA0000000000000000000000000000000000012 +:103EB0000A000000000000000300000000000000F5 +:103EC00000000000000000000000000000000000F2 +:103ED00000000000000000000000000000000000E2 +:103EE00000000000000000000000000000000000D2 +:103EF00000000000000000000000000000000000C2 +:103F000000000000000000000000000000000000B1 +:103F1000000000000000000032040000000000006B +:103F200000800E0000000000FF0000000000000004 +:103F3000B03B00083F00000049040000BD3B000802 +:103F40003F00000051040000CB3B00083F00000090 +:103F50000096000000000800960000000008000025 +:103F600004000000683D00080000000000000000A0 +:103F70000000000000000000000000000000000041 +:00000001FF diff --git a/Tools/bootloaders/SPRacingH7_bl.bin b/Tools/bootloaders/SPRacingH7_bl.bin index 9e6d4c5f0c2..07d60385181 100644 Binary files a/Tools/bootloaders/SPRacingH7_bl.bin and b/Tools/bootloaders/SPRacingH7_bl.bin differ diff --git a/Tools/bootloaders/SPRacingH7_bl.hex b/Tools/bootloaders/SPRacingH7_bl.hex index 09cbab86b09..e7a1420986b 100644 --- a/Tools/bootloaders/SPRacingH7_bl.hex +++ b/Tools/bootloaders/SPRacingH7_bl.hex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diff --git a/Tools/bootloaders/Sierra-L431_bl.bin b/Tools/bootloaders/Sierra-L431_bl.bin index 829be46ba3c..de216ad05d4 100755 Binary files a/Tools/bootloaders/Sierra-L431_bl.bin and b/Tools/bootloaders/Sierra-L431_bl.bin differ diff --git a/Tools/bootloaders/SkystarsH7HD-bdshot_bl.bin b/Tools/bootloaders/SkystarsH7HD-bdshot_bl.bin new file mode 100644 index 00000000000..46b2908ad58 Binary files /dev/null and b/Tools/bootloaders/SkystarsH7HD-bdshot_bl.bin differ diff --git a/Tools/bootloaders/SkystarsH7HD-bdshot_bl.hex b/Tools/bootloaders/SkystarsH7HD-bdshot_bl.hex new file mode 100644 index 00000000000..89d6324f13e --- /dev/null +++ b/Tools/bootloaders/SkystarsH7HD-bdshot_bl.hex @@ -0,0 +1,1110 @@ +:020000040800F2 +:1000000000060020A10200082D110008AD10000814 +:1000100005110008AD100008D9100008A30200085F +:10002000A3020008A3020008A3020008D5270008C5 +:10003000A3020008A3020008A3020008A30200080C +:10004000A3020008A3020008A3020008A3020008FC +:10005000A3020008A3020008213F00084D3F00084A +:10006000793F0008A53F0008D13F0008A30200081F +:10007000A3020008A3020008A3020008A3020008CC +:10008000A3020008A3020008A3020008A3020008BC +:10009000A3020008A3020008A3020008FD3F000815 +:1000A000A3020008A3020008A3020008A30200089C +:1000B000A3020008A3020008A3020008A30200088C +:1000C000A3020008A3020008A3020008A30200087C +:1000D000A3020008A3020008A3020008A30200086C +:1000E00075400008A3020008A3020008A30200084C +:1000F000A3020008A3020008A3020008A30200084C +:10010000A3020008A3020008FD400008A3020008A3 +:10011000A3020008A3020008A3020008A30200082B +:10012000A3020008A3020008A3020008A30200081B +:10013000A3020008A3020008A3020008A30200080B +:10014000A3020008A3020008A3020008A3020008FB +:10015000A3020008A3020008A3020008A3020008EB +:10016000A3020008A3020008A3020008A3020008DB +:10017000A302000831350008A3020008A30200080A +:10018000A3020008A3020008A3020008A3020008BB +:10019000A3020008A3020008A3020008A3020008AB +:1001A000A3020008A3020008A3020008A30200089B +:1001B000A3020008A3020008A3020008A30200088B +:1001C000A3020008A3020008A3020008A30200087B +:1001D000A30200081D350008A3020008A3020008BE +:1001E000A3020008A3020008A3020008A30200085B +:1001F000A3020008A3020008A3020008A30200084B +:10020000A3020008A3020008A3020008A30200083A +:10021000A3020008A3020008A3020008A30200082A +:10022000A3020008A3020008A3020008A30200081A +:10023000A3020008A3020008A3020008A30200080A +:10024000A3020008A3020008A3020008A3020008FA +:10025000A3020008A3020008A3020008A3020008EA +:10026000A3020008A3020008A3020008A3020008DA +:10027000A3020008A3020008A3020008A3020008CA +:10028000A3020008A3020008A3020008A3020008BA +:10029000A3020008A3020008A3020008A3020008AA +:1002A00002E000F000F8FEE772B63A4880F30888F2 +:1002B000394880F3098839484EF60851CEF20001DA +:1002C000086040F20000CCF200004EF63471CEF22D +:1002D00000010860BFF34F8FBFF36F8F40F2000043 +:1002E000C0F2F0004EF68851CEF200010860BFF374 +:1002F0004F8FBFF36F8F4FF00000E1EE100A4EF604 +:100300003C71CEF200010860062080F31488BFF330 +:100310006F8F02F01FFB02F0C1FA03F007FC4FF0F1 +:1003200055301F491B4A91423CBF41F8040BFAE784 +:100330001C49194A91423CBF41F8040BFAE71A499B +:100340001A4A1B4B9A423EBF51F8040B42F8040B69 +:10035000F8E700201749184A91423CBF41F8040BC6 +:10036000FAE702F0DDFA03F003FC144C144DAC4242 +:1003700003DA54F8041B8847F9E700F041F8114C00 +:10038000114DAC4203DA54F8041B8847F9E702F038 +:10039000C5BA00000006002000220020000000086E +:1003A0000000002000060020D844000800220020A1 +:1003B0005C220020602200207C420020A002000875 +:1003C000A0020008A0020008A00200082DE9F04FDA +:1003D0002DED108AC1F80CD0D0F80CD0BDEC108AED +:1003E000BDE8F08F002383F311882846A047002042 +:1003F00001F062FDFEE701F0B3FC00DFFEE7000064 +:1004000038B500F063FD18B1154B4FF460229A60C7 +:1004100002F09AF9044602F0D3F9054640B9114BAF +:100420009C4214D001339C4213D041F2883400E046 +:100430000024002002F094F975B900F009FE00F0E4 +:1004400065FC204600F070F900F000F9F9E700249F +:10045000EFE700240125ECE700F0F8F8EDE700BF36 +:1004600000220020010007B010B584468E46BFF37D +:100470004F8FBFF36F8F1F4B0022C3F88420BFF351 +:100480004F8F5A6922F480325A61BFF34F8FD3F8ED +:100490008040C4F34E3000E01846C4F3C90243F66E +:1004A000E07303EA401343EA82731249C1F87432DD +:1004B0001346013A002BF2D1431E0028ECD1BFF3C2 +:1004C0004F8FBFF36F8FBFF34F8FBFF36F8F4A69AB +:1004D00022F400324A610022C1F85022BFF34F8F4C +:1004E000BFF36F8F202383F31188E5468CF30888D0 +:1004F000704710BD00ED00E000B583B0019004210D +:100500000DEB010000F0F4FB03B05DF804FB00BF4D +:1005100000B583B041F21203ADF80430022101A806 +:1005200000F0E6FB03B05DF804FB00BF00B583B04C +:1005300041F21233ADF80430022101A800F0D8FBDB +:1005400003B05DF804FB00BF00B583B041F21213A5 +:10055000ADF80430022101A800F0CAFB03B05DF839 +:1005600004FB00BF08B5C0EB401300EB8300C000E4 +:1005700001F0AAFC08BD00BF08B5202383F3118851 +:100580001F4BDB6813B11E4801F02AFD00231D4AF2 +:100590004FF47A711A4801F013FD002383F3118898 +:1005A00001E00133DBB2012B0BD8174A52F82320AC +:1005B000002AF6D0144951F82320013A41F82320AB +:1005C000EFE7124B1B7813B90F4B5B6823B10F4B4E +:1005D0001B78032B07D008BD022000F09BFC0A4BC0 +:1005E00032225A60F3E7084B5B68002BF3D10220FC +:1005F00000F090FC044B4FF47A725A60EBE700BFB6 +:1006000060220020790500087C230020742200204D +:1006100008B50C4B1870032806D8DFE800F00A066E +:10062000020E022000F066FC08BD022000F050FC23 +:10063000FAE7054B00225A60F6E7034B00225A60A6 +:10064000F2E700BF742200207C23002008B50023BD +:10065000072B08D8304A52F82320B2F1FF3F0DD0C3 +:100660000133DBB2F4E72C4B5B682C4A934205D98B +:100670002B4A9168284A0A44934200D308BD0020BF +:1006800000F070FB0220FFF7C3FF264BD3F8E820F1 +:100690000022C3F8E820D3F81011C3F81021D3F8D2 +:1006A0001011D3F8EC10C3F8EC20D3F81411C3F8F0 +:1006B0001421D3F81411D3F8F010C3F8F020D3F8B4 +:1006C0001811C3F81821D3F81821D3F8802042F06C +:1006D0000062C3F88020D3F8802022F00062C3F8C3 +:1006E0008020D3F88020D3F8802042F00072C3F835 +:1006F0008020D3F8802022F00072C3F88020D3F845 +:10070000803072B6044B4FF0E022C2F8083D5968C1 +:100710001868FFF7A9FEB1E700000208FFFF010813 +:1007200000220020004402582DE9F04F91B0054608 +:10073000A94BD3F808A02022FF210DEB020000F006 +:1007400029FCA64B1B787BB10DB1A54B1D60A54BB9 +:100750001B78032B21D12C460026B0463746B146E4 +:10076000012000F0C7FB23E09C4B01221A709E4B36 +:100770000022DA60202282F31188DB6813B19A48E4 +:1007800001F02EFC0023994A4FF47A71964801F04B +:1007900017FC002383F31188D6E70020FFF738FF0A +:1007A000D9E7002000F084FA0290029B002B08DABF +:1007B000002CF6D08A4B1B68002BF2D111B0BDE89B +:1007C000F08F012000F084FB029B213B162BC7D841 +:1007D00001A252F823F000BF3508000859080008AC +:1007E000F7080008610700086107000861070008B2 +:1007F0006D090008570B00086B0A0008CF0A0008B3 +:10080000F30A0008170B000861070008350B000801 +:1008100061070008AB0B00084308000861070008E7 +:10082000EB0B0008210B00084308000861070008D3 +:10083000CF0A0008022000F03BFA202840F0708127 +:10084000012700F0FBFB27B108F00B030B2B00F096 +:10085000EB81FFF75DFE83E74FF47A7000F028FA32 +:10086000B0F1000BC0F25C81022000F021FA2028D8 +:1008700040F056810BF1FF33052B00F2D781DFE802 +:1008800003F003151A1F243505230393042103A83D +:1008900000F02EFA0BF1FF30012303FA00F040EADA +:1008A00008085FFA88F84FF00009CAE704214A48AF +:1008B00000F01EFAEEE704214D4800F019FAE9E7CE +:1008C00004214C4800F014FAE4E74FF00709B9F1AD +:1008D0000A0FDFD84FEA890000F048FA039004219C +:1008E00003A800F005FA09F10109F0E704214248E4 +:1008F00000F0FEF9CEE7002F00F0128108F00B03A4 +:100900000B2B40F00D81022000F0D2F9202840F09E +:100910000781012000F026FA0220FFF779FE002669 +:10092000304600F033FA044640B1304600F040FA59 +:10093000002800F080810136F6B2F1E70120FFF7D0 +:1009400067FEA246244B9B68534509D9504600F0E8 +:100950000DFAB0F1FF3F40F073810AF1040AF1E7AC +:100960000020FFF755FE3E46A2466AE7002F00F042 +:10097000D78008F00B030B2B40F0D2800220FFF74A +:1009800047FE322000F094F9B0F1000BC0F2C880AD +:10099000CDF800B01BF0030F40F0C2800BEB0A0350 +:1009A0000D4A9268934200F2BB80BBF5807F00F253 +:1009B000B780002301941C46A34521DD4FF47A70D3 +:1009C00000F076F90290029B002BC0F23281029A6D +:1009D0000A4B1A550134EFE700220020782300204B +:1009E0007C2300207422002060220020790500086A +:1009F00004220020082200200C220020782200205F +:100A0000019CC82000F054F9202840F08980BAF1F8 +:100A10001F0F15D8CAF120039B4500D900932AF077 +:100A200003009DF8003000931A4686490DF1200C12 +:100A3000604400F083FA009AFF21824800F0AAFA8D +:100A40005A46BBF1000F0DDB4FEAA20BC2F387023F +:100A50007C49504600F0A8FA002800F0EE800AEB2E +:100A60008B0AEEE60BF10302EEE7022000F020F91C +:100A7000202855D100F0B6F9002851D04FF0000BD6 +:100A800000945C460BE0584600F070F90390042295 +:100A900003A9204600F04CFB04460BF1040B6A4B03 +:100AA0009B685B450ED9BBF11F0FECD8089BB3F1D7 +:100AB000FF3FE8D02BF0030310AA134453F8203C67 +:100AC0000393E4E72046009CFFF716FDB9E60023F8 +:100AD0000393642103A800F0FFF808BB022000F094 +:100AE000E7F820281CD1039800F074F9FFF704FD03 +:100AF000A7E600230393642103A800F0EDF878B97A +:100B0000022000F0D5F820280AD1039800F064F9FB +:100B1000FFF7F2FC95E6022000F0CAF8202804D086 +:100B200006B92C46FFF702FD1AE600F06DF9FFF753 +:100B3000E3FC86E6022000F0BBF82028F0D103A9F0 +:100B4000142000F067F98346FFF7D6FC594603A846 +:100B500000F0CEF875E6322000F0AAF8B0F1000BF4 +:100B6000DEDB1BF0030FDBD10BEB0903364A926887 +:100B70009342D5D8022000F09BF82028D0D15B46C4 +:100B8000BBF1000F0EDB9B1003F1FF3B002B7FF747 +:100B900058AE484600F0EAF8FFF7AEFC09F1040948 +:100BA0005B46F1E70BF10303EDE74FF47A7000F0D9 +:100BB0007FF82028B4D100F015F900283DD0089B1B +:100BC000B3F1FF3F0BD0082208A9002000F0ECF998 +:100BD00098B32022FF210DEB020000F0DBF9FFF7B4 +:100BE00097FC6420FFF7BEFCE8E5002F98D008F0E2 +:100BF0000B030B2B94D100230393642103A800F073 +:100C00006BF800288CD1022000F052F8202887D100 +:100C1000FFF77EFC0520FFF7A5FC039800F044FADF +:100C200000F00CFA00249BE5002412E64FF00009C6 +:100C300076E7019C74E73E460024FFF785FC8FE5CC +:100C40003E46FAE778220020002200202DE9F041FC +:100C500007460E4615460024E4B9124B93F90030BE +:100C6000B3F1FF3F01D0A3420DD10F480368D3F881 +:100C70002080C5EB451305EB8303DB003246394684 +:100C8000C047864202D00134E4B2E5E7074B1C704E +:100C9000012004E04FF4FA7001F016F90020BDE8DD +:100CA000F08100BF1022002070250020B02300201A +:100CB00000B583B0024600238DF8073001210DF105 +:100CC0000700FFF7C3FF20B19DF8070003B05DF8F0 +:100CD00004FB4FF0FF30F9E708B50A460421FFF79F +:100CE000B5FF08B1002008BD4FF0FF30FBE700BFA3 +:100CF00010B584460A4603480368DC69024B614626 +:100D0000A04710BD70250020A086010038B501F075 +:100D10004FFC124B1880002406E001F045FC04440F +:100D20000F4A136801331360B4F5003F07D20B4B31 +:100D30001B880B4A10688342EFD8002500E000258D +:100D4000B5F5802F09D2054C2088013801F02CFC24 +:100D500005442388013B2380F2E738BDB2230020FD +:100D60008423002008B501F099FC08BD014BC05850 +:100D7000704700BF0000020808B503469200024811 +:100D8000184401F087FC08BD0000020808B5064BB6 +:100D90001B88064A12689B1A834201D8002008BDAE +:100DA000104401F001FCFAE7B22300208423002064 +:100DB00010B50446064B1868204401F0FBFB00B157 +:100DC00010BD034B1868204401F00CFCF8E700BF8D +:100DD0008423002000207047014BC058704700BF9B +:100DE00000E8F11F08B5074B93F824300BB9012038 +:100DF00008BD0449002381F824300822086AFFF75F +:100E0000BBFFF5E788230020014B1868704700BF3F +:100E10000010005C30B585B084468E46284B1C68B7 +:100E2000C4F30B05240C274B93E8070004AB03E93C +:100E300007000023012B11D803EB4302214931F8AD +:100E40002220AA4201D00133F4E703EB430301EB74 +:100E5000830393E8070004AB03E90700002300E0E5 +:100E60000133032B0CD8184A32F82320A242F7D1C1 +:100E7000154A02EB830292F902208DF80C20EFE76D +:100E80000CF1FF3CF444704603E00133029300F898 +:100E9000012B604504D2029B93F90020002AF4D173 +:100EA000604502D22C2300F8013B604503D29DF837 +:100EB0000C3000F8013BA0EB0E0005B030BD00BFC8 +:100EC0000010005C14220020DC4100080020704764 +:100ED000022802D0012805D07047054B4FF40022AC +:100EE0009A61F7E7024B4FF480129A61F4E700BF72 +:100EF00000100258022802D0012804D07047044B89 +:100F000008229A61F8E7024B10229A61F6E700BFC7 +:100F100000100258022802D0012806D07047064A65 +:100F2000536983F008035361F6E7034A536983F07A +:100F300010035361F2E700BF00100258002304E0E1 +:100F400011F803C000F803C001339342F8D370478F +:100F500002E001300131624690F9003043B191F96D +:100F600000C0634504D102F1FF3C002AF1D1624682 +:100F70001AB191F90000181A70470020704700BF9D +:100F80000346002000E0013013F9012B002AFAD1BA +:100F9000704700BF034602E003F8011B624602F1FE +:100FA000FF3C002AF8D170472DE9F8438146884676 +:100FB0001546214B93F8243033B31F4A126A02EBD3 +:100FC0008303834220D0FFF70DFF0346E0B930E0F2 +:100FD000194E96F82400C0F10804AC4228BF2C46F4 +:100FE000E4B2A7003A46414606EB8000FFF7A6FFB1 +:100FF000B944B8442D1BEDB296F824301C44E4B239 +:1010000086F82440082C0DD095B10B4B93F8243072 +:10101000002BDDD10848C0F820902022FF21FFF7E7 +:10102000B9FFD5E7FFF7DEFE03460028ECD100E06C +:1010300001231846BDE8F88388230020024B93F96A +:101040000020024B1A707047B023002010220020AD +:1010500038B5114D284600F019F9104C21462846A4 +:1010600000F042F92468D4F89020D2F8043843F014 +:101070000203C2F804380A4800F026FF0949204656 +:1010800000F094FAD4F89020D2F8043823F0020348 +:10109000C2F8043838BD00BF70250020B4420008F3 +:1010A00040420F00BC420008704700BF00B59BB033 +:1010B000EFF3098168226846FFF740FFEFF30583ED +:1010C000044B9A6BDA6A9A6A9A6A9A6A9A6A9A6A74 +:1010D0009B6AFEE700ED00E000B59BB0EFF30981ED +:1010E00068226846FFF72AFFEFF30583044B9A6BEB +:1010F0009A6A9A6A9A6A9A6A9A6A9B6AFEE700BF33 +:1011000000ED00E000B59BB0EFF30981682268466E +:10111000FFF714FFEFF30583034B5A6B9A6A9A6A41 +:101120009A6A9A6A9B6AFEE700ED00E0FEE700BF5C +:1011300000B58E460AE040F3000C09490CEA0101B3 +:1011400081EA50000133DBB2072BF4D91346013A90 +:1011500023B11EF8013B58400023F5E75DF804FB7E +:101160002083B8ED0020704710B582B0446B04F5C1 +:101170008053D3F8A4381A681178042908D1217C47 +:10118000022905D11289197901238B40134201D01C +:1011900002B010BD01A904F14C0002F02BFB024685 +:1011A00004F58054D4F8A448019B2179206800F00C +:1011B000A5FBEDE700F58053D3F8A4381A68117841 +:1011C00004291DD110B50446017C02291AD1528987 +:1011D000597901238B40134201D0012013E01430D0 +:1011E00002F012FA024678B104F58054D4F8A4084B +:1011F0004FF440734179006800F066FB002002E084 +:1012000001207047012010BD0120FCE708B5406BAC +:10121000FFF7D0FF08BD00BF08B5143002F066FA32 +:1012200008BD00BF08B54FF0FF33143002F05EFA7E +:1012300008BD00BF08B54C3002F054FB08BD00BF2C +:1012400008B54FF0FF334C3002F04CFB08BD00BF37 +:1012500008B5143002F02AFA08BD00BF08B54FF0F7 +:10126000FF31143002F022FA08BD00BF08B54C303F +:1012700002F014FB08BD00BF08B54FF0FF324C3040 +:1012800002F00CFB08BD00BF704700BF70B584B012 +:101290000446124B0360002343608360C360012552 +:1012A000057402900E4B0193042600964FF4407390 +:1012B00000F184022946143002F080F90294094BAF +:1012C000019300964FF4407304F69442294604F1CA +:1012D0004C0002F067FA04B070BD00BFEC4100089A +:1012E0000D120008691100080A68202383F3118891 +:1012F0000B790B3342F823004B79133342F8230068 +:101300008B7913B10B3342F8230000F58053C3F8F7 +:10131000A41802230374002383F31188704700BFCD +:1013200038B50446037F13B190F85430BBB9201D83 +:10133000636843F002036360A36803B19847012523 +:1013400025776FF0010104F1140000F0E7FD84F847 +:1013500054506FF0010104F14C0000F0DFFD38BD86 +:1013600010B50446436843F00103436083680BB142 +:10137000043098470023237784F8543010BD00BF11 +:1013800038B50446143002F031F90025257704F110 +:101390004C0002F021FA84F85450636843F00103D2 +:1013A0006360A3680BB1201D98472046FFF702FF3A +:1013B00038BD00BF90F8803003F06003202B01D0CF +:1013C0000020704790F88130212B05D0222B13D0BC +:1013D000202B09D0002070470A4B436707238367FF +:1013E0000023C36701207047064B436707238367C9 +:1013F0000023C36701207047002343678367C367E7 +:10140000012070472C22002000F58053D3F8A43827 +:101410001A681178042923D130B583B00446017CC1 +:10142000022905D11289197901238B40134201D079 +:1014300003B030BD00F14C05284602F0AFFA002899 +:10144000F6D001A9284602F0D5F9024604F58054E9 +:10145000D4F8A448019B2179206800F04FFAE7E70F +:10146000704700BF70B582B001F10B0350F8234004 +:1014700014B305460E46202383F31188201D6368AC +:1014800043F008036360A36803B19847B31C05EBFE +:1014900083035B685B691B6883B901A904F14C0095 +:1014A00002F0A8F9024670B1019B3146284600F0CF +:1014B00025FA002383F3118802B070BD04F14C00BB +:1014C00002F0AAF9E9E7B31C05EB83035A685369F4 +:1014D0001B68002BEDD0128A013A1342E9D1002398 +:1014E00005F180023146284600F008FAE1E700BF26 +:1014F00038B5133150F8214014B3202383F31188F9 +:1015000004F58053D3F8A42813685279023203EB10 +:1015100082035B689B695D6865B1201D636843F069 +:1015200004036360A36803B19847294604F11400DB +:1015300002F07AF82046FFF73DFE002383F311887E +:1015400038BD00BF704700BF0378407843EA0020F1 +:10155000704700BF10B5044690F8823080F88A309A +:1015600001F0A2FC63681B6813B101212046984773 +:101570000323237010BD00BF08B501F079FB08BD3F +:10158000012303700023436009E003F10C010022F2 +:1015900040F8212003F1140140F821200133072BEA +:1015A000F3D9002303814381704700BF10B504467F +:1015B000202383F311884160002305E09A1C04EB8B +:1015C0008202002151600133082BF7D9204601F037 +:1015D00071FB02232370002383F3118810BD00BF29 +:1015E00008B58B1C00EB83035A6053694BB14FF075 +:1015F000000CC3F800C0C3F804C0C3F808C0C3F8A7 +:101600000CC0936923B100221A605A609A60DA60B4 +:1016100001F058FC08BD00BF08B5038903F00103C1 +:101620000381438903F001034381012305E09A1CF0 +:1016300000EB8202002151600133082BF7D901F041 +:10164000E7FC08BD38B5044690F8803003F07F030E +:1016500090F8812043EA022340F20232934200F0E4 +:101660000F8137D8B3F5807F00F081800DD9B3F5B5 +:10167000817F00F0EF80B3F5407F29D190F8823070 +:10168000012B00F08680002046E0012B65D0022B64 +:1016900012D190F8841090F98430002BC0F2B08001 +:1016A00001F00F0101F0BCFC012800F0C38002280A +:1016B00000F0C88000202FE043B900F188034367A1 +:1016C000022383670023C367012025E0002023E075 +:1016D000002021E0B3F5006F75D018D9B3F5106F75 +:1016E00037D10378042B76D094F882304BB184F84C +:1016F0008B300423237063681B6813B102212046DA +:10170000984700236367A367E367012004E0B3F50C +:10171000A06F4AD001D2002038BDA3F5C063012BD1 +:1017200000F2C48043685D688430FFF70DFF034614 +:1017300094F8822094F883102046A847002800F0EF +:10174000B780426862670368A3670023E3670120EC +:10175000E2E740F60242934207D1584B6367022307 +:10176000A3670023E3670120D6E70020D4E790F8C1 +:101770008230012B01D00020CEE7B0F8883023F072 +:101780000203A0F88830002343678367C367012002 +:10179000C2E7B0F8883043F00203A0F88830002395 +:1017A00043678367C3670120B6E7B0F88030B3F5BD +:1017B000A06F05D000236367A367E3670120ABE751 +:1017C000FFF7C8FEF6E700F18B0343670120A0672F +:1017D0000023E367A0E7202383F31188FFF71CFFB2 +:1017E000002383F3118884F88B300323237063680C +:1017F0001B68002B3FF478AF03212046984773E71E +:1018000001F00F0101F01EFC012803D0022809D0CD +:10181000002081E72A4B63670223A3670023E36765 +:10182000012079E7274B63670223A3670023E3675F +:10183000012071E7224B63670223A3670023E3675C +:10184000012069E71F4B63670223A3670023E36757 +:10185000012061E790F8823063BB90F8843013F088 +:101860000F0104D013F0800F07D101F07FFE002399 +:101870006367A367E36701204EE701F081FEF6E7A7 +:1018800090F88230C3B990F8843013F00F0104D07F +:1018900013F0800F07D101F055FE00236367A367A3 +:1018A000E367012038E701F057FEF6E7002033E751 +:1018B000002031E700202FE700202DE71C42000820 +:1018C000184200081442000838B50C464FF0010ECB +:1018D0000EFA01FE1FFA8EFE45894EEA050EA0F8AB +:1018E0000AE0023400EB84046468A469A260236007 +:1018F0000023636001F0C2FB38BD00BF38B50C4661 +:101900004FF0010E0EFA01FE1FFA8EFE05894EEA17 +:10191000050EA0F808E0023400EB840464686469F2 +:10192000A26023600023636001F048FC38BD00BF63 +:1019300010B50446022303700023A0F8883080F815 +:101940008A3080F88B300381438105E09A1C04EBD8 +:101950008202002151600133082BF7D9002384F85B +:101960007030204601F044FA63681B6813B100210F +:101970002046984710BD00BF10B50446037880F894 +:101980008C300523037043681B680BB10421984712 +:1019900000232381638110BD08B590F88C3003705B +:1019A00043681B680BB10521984708BD10B5044674 +:1019B00090F8703013B1002380F8703004F1800289 +:1019C000204601F051FB63689B6813B1204698479D +:1019D00040B994F8803013F0600F22D12046FFF711 +:1019E00031FEF0B104F18600FFF7AEFDA36F834234 +:1019F00000D9A06794F98030002B24DBA36F002B63 +:101A000043D0152384F87030202383F31188A36F0B +:101A1000626F00212046FFF757FF002383F31188F0 +:101A200010E00021204601F097FD0021204601F042 +:101A300089FD63681B6813B1062120469847062379 +:101A400084F8703010BDA36F7BB1092384F8703027 +:101A5000202383F31188A36F626F00212046FFF7D4 +:101A60004DFF002383F31188ECE7142384F87030D2 +:101A7000202383F3118800231A4619462046FFF7D6 +:101A800023FF002383F31188DCE70B2384F87030F5 +:101A9000202383F3118800231A4619462046FFF7B6 +:101AA0002DFF002383F31188CCE700BF10B5044657 +:101AB00090F87030152B28D8DFE803F03F27272750 +:101AC00027273F27270B18382727272727272727A8 +:101AD0003F3F8630FFF738FDA36F834206D2E268AE +:101AE000128AB3FBF2F102FB11337BB1142384F8A9 +:101AF0007030202383F3118800231A4619462046AC +:101B0000FFF7E2FE002383F3118810BD202383F347 +:101B1000118800231A4619462046FFF7EFFE0023DE +:101B200083F311880A2384F87030EEE7C36F03B1A2 +:101B30009847002384F87030E7E7002101F00CFD9E +:101B40000021204601F0FEFC63681B6813B10621EA +:101B500020469847062384F87030D6E710B504462F +:101B600090F87030152B1AD8DFE803F026191919F0 +:101B700019192619192626261919191919191919A1 +:101B80001A0B0B2380F87030202383F31188002375 +:101B90001A461946FFF7B2FE002383F3118810BDE1 +:101BA000C3689B695B68002BF9D1C36F03B1984789 +:101BB000002384F87030F2E7002101F0CDFC002111 +:101BC000204601F0BFFC63681B6813B10621204664 +:101BD0009847062384F87030E1E700BF024B1B6092 +:101BE0005B6000229A607047B423002000230374D6 +:101BF000054B1B68996882689142FAD203605A6863 +:101C00004260106058607047B423002008B520235C +:101C100083F31188037C032B0ED0042B10D043B127 +:101C20004FF0FF334361FFF7E1FF002383F3118897 +:101C300008BD83F31188FBE7436900221A60EFE7D0 +:101C400042680368136042685A60E9E7002303743E +:101C5000054B1B68996882689142FAD803605A68FC +:101C60004260106058607047B423002008B5074BED +:101C7000196908741A681068186043601A610120B5 +:101C800010741869FEF7A2FB08BD00BFB423002042 +:101C900010B586B00446B1F1FF3F12D00A4B1B6964 +:101CA0000A4A01A800F08CF92046FFF7DFFF049BE9 +:101CB00013B101A800F094F9034B1B69586906B0F1 +:101CC00010BDFFF7D3FFF7E7B42300200D1C000879 +:101CD00010B504460A4B18696161A26883689A428C +:101CE00003D82046FFF782FF10BDFFF7AFFF014684 +:101CF000034B1C61012323742046FEF767FBF3E7C7 +:101D0000B4230020044B1A6890681B699B689842B2 +:101D100094BF002001207047B423002010B5084C68 +:101D2000206923681A6822605460236101221A74B2 +:101D3000FFF78CFF01462069FEF748FB10BD00BF8E +:101D4000B423002008B5054B1A6892681B699B688C +:101D50009A4200D808BDFFF7E1FFFBE7B42300205B +:101D600010B5084C206923681A682260546023610A +:101D700001221A74FFF76AFF01462069FEF726FB6D +:101D800010BD00BFB4230020FEE700BF10B5FFF771 +:101D900025FF00F007F90A4C80220A49204600F08E +:101DA00053F844F8180C0123037400F023FD0023BA +:101DB00083F3118862B6044800F064F810BD00BFD8 +:101DC000DC230020204200083042000808B500F063 +:101DD00047F908BDEFF3118058B9EFF30583C3F35A +:101DE00008031BB1202383F311887047202383F35A +:101DF0001188704778B908B5EFF30583C3F308037A +:101E00001BB1002383F3118808BDFFF79BFF00235C +:101E100083F31188F8E77047401A511A88422CBFA3 +:101E200000200120704700BF38B5064B5D6844199B +:101E3000044B586822462946FFF7EEFF0028F7D1E9 +:101E400038BD00BF001000E0826002220274002250 +:101E50004274704710B58468A4F17C0344F80C3CCC +:101E6000026944F83C2C426944F8382C044A44F88E +:101E70001C2CC2680168A4F11800FFF7E5FF10BD33 +:101E8000E503000810B5202383F31188FFF7E2FF74 +:101E900004460021FFF71CFF002383F3118820462E +:101EA00010BD00BF08B5034B1B6958610F20FFF739 +:101EB000DDFE08BDB423002008B5202383F311887C +:101EC000FFF7F0FF08BD00BF08B50146202383F3EC +:101ED00011880820FFF7DCFE002383F3118808BD7A +:101EE00059B108B5064B1B69186042685A60136007 +:101EF00043600420FFF7CCFE08BD4FF0FF30704771 +:101F0000B423002008B503460068834205D0026868 +:101F10001A6053604161FFF769FE08BD38B5044699 +:101F20000D4605E0036823605C604561FFF75EFED7 +:101F300020688442F6D138BD70B505460E461C4671 +:101F40000368984209D0C068121AA21800D2144639 +:101F50009B68A34210D82A6814E0C2608C6070604D +:101F600003680B6059602960092C00D80A24E868CE +:101F7000204401F03DFD14E0204401F049FDEAE772 +:101F8000E41A126893689C42FAD8B46032605368CD +:101F900073601E60566093681B1B93604FF0FF33A5 +:101FA000AB6070BD054B03F114025A619A614FF0AA +:101FB000FF32DA6100221A62704700BFB4230020AA +:101FC00038B504460D460361C26001F027FD0246A4 +:101FD0002B4621460148FFF7AFFF38BDC82300203C +:101FE00038B51E4B5B69984210D042680368136095 +:101FF00042685A600023C3600268816893680B449A +:102000009360164B4FF0FF32DA6138BD1968134AFE +:10201000134643F8141F4B600021C16052699A4275 +:1020200018D0816893680B4493600C4D2C6A01F0C2 +:10203000F5FC021B6B699B689342E6D9241A1C4489 +:10204000092C01D802F10A03044A106A184401F06D +:10205000DFFCDAE701F0D6FCD7E700BFB4230020AD +:1020600038B507E0002383F311882069A8472023AF +:1020700083F31188144D6C6901F0D0FC2B6AC21AED +:10208000A168914211D819442B46296261682268DF +:102090000A6061685160E5680022E26053F8142F1D +:1020A0009A42DFD101F0AEFCDCE7074A52F8144F48 +:1020B000944207D01A1A0A44092A00D80A22104466 +:1020C00001F0A6FC38BD00BFB423002000207047FB +:1020D000FEE700BF704700BF4FF0FF30704700BF02 +:1020E00002290DD0032905D0012901D00020704715 +:1020F00005487047032A05D8044800EBC200704722 +:102100000348704700207047184300083C22002015 +:10211000CC42000830B59BB005460846144601A9DC +:1021200000F0D6F801A8FEF72BFF5FFA80FC431CF5 +:102130005B002B606C6023700323637000230BE053 +:10214000591C1AAA1A4412F8642C04F811205B00D6 +:1021500003330022E254CBB26345F1D31BB030BD50 +:1021600008B5202383F311880348FFF74DF90023B6 +:1021700083F3118808BD00BF7025002008B590F8D2 +:10218000803003F01F02012A11D003F06003202BDE +:102190000AD1B0F884303BB990F88130212B10D0AF +:1021A000222B1ED0202B14D0FFF704F908BD90F885 +:1021B00081200B2AE9D1002343678367C36701208D +:1021C000F4E70B4B4367072383670023C3670120B2 +:1021D000ECE7074B4367072383670023C3670120AE +:1021E000E4E7002343678367C3670120DEE700BF9E +:1021F0003422002010B5052917D8DFE801F01716A2 +:10220000031717210446202383F31188114A012163 +:10221000FFF7E6F9104A02212046FFF7E1F90F48DF +:10222000FFF7AEF8002383F3118810BD202383F35A +:1022300011880A48FFF774F8002383F31188F4E744 +:10224000202383F311880548FFF78AF8002383F3DE +:102250001188EAE76C4200089042000870250020CF +:1022600038B50B4D0B4C2A460B4904F10800FFF71B +:1022700051FF05F1CA02094904F11000FFF74AFFB6 +:1022800005F5CA72064904F11800FFF743FF38BD8F +:10229000483E00203C2200204842000854420008EA +:1022A0006042000870B504460D460846FEF768FE19 +:1022B000064600E00134237843B1F2B229462046B5 +:1022C000FEF746FE0028F5D1012000E0002070BD99 +:1022D00070B506460C46FEF753FEC5B22749304698 +:1022E000FFF7E0FF08B10C35EDB225493046FFF7A6 +:1022F000D9FF08B11035EDB2632D28D931462046FB +:1023000001F056FF39E01F4D0FCD20606160A260E3 +:10231000E3602A88AB782282A3740736133416E070 +:1023200019495A5C12091948155C224602F8025BE9 +:10233000595C01F00F01095C61700133DBB2144696 +:102340000B2BEDD9083602E0013604F8015B357835 +:102350008DB1252DF8D1072208493046FEF7F8FD4A +:102360000028D0D0082206493046FEF7F1FD0028AB +:10237000EAD10023E4E70023237070BD384300084E +:10238000604200084043000800E8F11F5443000881 +:10239000BFF34F8F054B1B6913F0070FFAD1034BA7 +:1023A000D3F8103113F0070FF4D17047002000521A +:1023B000034B4FF0FF325A61C3F81421704700BF3E +:1023C0000020005208B5104B1B7803B108BDFFF781 +:1023D000DFFF0E4BDB6813F0010F05D00B4B0C4AEF +:1023E0005A6002F188325A60084BD3F80C3113F06E +:1023F000010FEBD0054B064AC3F8042102F18832E5 +:10240000C3F80421E2E700BFA640002000200052EC +:1024100023016745002301E0043001338B4205D2DC +:102420000268B2F1FF3FF7D00020704701207047EB +:102430002DE9F04105460E4600F17843B3F5801FC3 +:102440000FD2184CDFF86C80174FFFF7A1FF4FF049 +:10245000FF33C8F800303B6843F002033B600022C2 +:102460000EE0124CDFF85080114FEEE7236813F0B6 +:10247000050FFBD156F8043B45F8043B0132D2B2BC +:10248000072AF3D9BFF34F8FFFF782FF4FF0FF33D7 +:10249000C8F800303B6823F002033B600120BDE830 +:1024A000F08100BF102000520C2000521021005279 +:1024B0000C210052142000521421005208B5144B74 +:1024C0001B781BBB134B1B6913F0040F04D0114A7C +:1024D000D36843F04003D3600E4BD3F8103113F0B0 +:1024E000040F06D00B4AD2F80C3143F04003C2F877 +:1024F0000C31FFF74DFF074BDA6842F00102DA605A +:10250000D3F80C2142F00102C3F80C2108BD00BF32 +:10251000A6400020002000522DE9F84312F01F0FC2 +:1025200035D104460D46164610F01F0F01D0002786 +:102530002EE0FFF747FF02E02034203E20351F2E1B +:1025400021D920222146284601F022FE0028F3D07E +:1025500008212046FFF75EFF0746C8B1FFF73AFCA7 +:10256000814629462046FFF763FF07464846FFF7A6 +:1025700041FC4FB120222946204601F009FE0028E7 +:10258000DAD0002700E00127FFF798FF00E00027DE +:102590003846BDE8F88300BF0F2803D800F58060F7 +:1025A00040047047002070474FF40030704700BF70 +:1025B000102070470F2811D838B50546FFF7ECFFFB +:1025C00004462846FFF7F0FF30B12368B3F1FF3F20 +:1025D00006D104380434F7E7012038BD00207047E5 +:1025E0000020FAE70F2801D90020704770B5044693 +:1025F000FFF7F0FB0546FFF7CBFEFFF7E3FEFFF723 +:10260000D7FE072C28D8224E4FF0FF333361FFF757 +:10261000BFFE230243F02403F360F36843F080031A +:10262000F3601B4B1B6913F0040FFAD1FFF7B0FEE8 +:102630002046FFF7B1FF06462046FFF7B5FF0146EB +:10264000304600F09DF8FFF739FF2846FFF7D2FB30 +:102650002046FFF7AFFF70BD0D4E4FF0FF33C6F8B9 +:102660001031FFF795FEA4F108031B0243F0240389 +:10267000C6F80C31D6F80C3143F08003C6F80C31A3 +:10268000034BD3F8103113F0040FF9D1CEE700BF9C +:102690000020005208B5FFF73FFF08BD08B503460C +:1026A00010B10A4A127822B113B9084B1B7833B91A +:1026B00008BDFFF787FE054B01221A70F8E7034BB0 +:1026C00000221A70FFF7FAFEF2E700BFA6400020D2 +:1026D00009E000F1010C064A52F8202041F8042BD1 +:1026E0001A465FFA8CF0531EDBB2002AF1D1704714 +:1026F0005040005810B4114B1B6F13F4004F06D11B +:102700000E4B1C6F1C671C6F44F400441C670C4C80 +:10271000236843F48073236009E000F1010C51F851 +:10272000044B084A42F820401A465FFA8CF0531EC8 +:10273000DBB2002AF1D15DF8044B70470044025827 +:10274000004802585040005800B583B0012201A94A +:102750000020FFF7BDFF019803B05DF804FB00BF48 +:1027600010B582B00446FFF7EFFFA04201D102B0DE +:1027700010BD0194012201A90020FFF7BBFFF6E77D +:102780000144BFF34F8F03E0054BC3F85C022030D8 +:102790008842F9D3BFF34F8FBFF36F8F704700BFED +:1027A00000ED00E0044B1B6823B9044BD3F8D024A0 +:1027B000014B1A60704700BFA8400020004002583B +:1027C00008B5FFF7EFFF024B1868C0F3806008BD43 +:1027D000A8400020EFF30983683305494A6B22F0D3 +:1027E00001024A6383F30988002383F31188704749 +:1027F00000EF00E0202080F3118862B60D4BD9680D +:1028000021F4E0610904090C0B4A0A43DA60D3F8A9 +:10281000FC2042F08072C3F8FC20084A0849C2F844 +:10282000B01F116841F0010111601022DA7783F8BE +:102830002200704700ED00E00003FA05001000E000 +:1028400055CEACC5202383F31188104B5B6813F47D +:10285000006F03D1002383F31188704710B5F1EEA8 +:10286000103AEFF30984683C4FF08073E361084B42 +:10287000DB6B236684F30988FFF744FA10B1054B3C +:10288000A36110BD044BA361FBE700BF00ED00E0B6 +:1028900000EF00E0F7030008FA03000810B4BFF3EC +:1028A0004F8FBFF36F8F1C4B0021C3F85012BFF343 +:1028B0004F8FBFF36F8F5A6942F400325A61BFF3F2 +:1028C0004F8FBFF36F8FC3F88410BFF34F8FD3F8D0 +:1028D0008040C4F34E3000E01846C4F3C90243F60A +:1028E000E07303EA401343EA82730B49C1F8603294 +:1028F0001346013A002BF2D1431E0028ECD1BFF35E +:102900004F8F4B6943F480334B61BFF34F8FBFF35D +:102910006F8F5DF8044B704700ED00E0FEE700BFED +:10292000084B094903E051F8042B43F8042B074AEC +:102930009342F8D302E0002243F8042B044A934266 +:10294000F9D370477C420020344500087C420020C7 +:102950007C420020704700BFD0F890200023D0F8C0 +:1029600094108968994232D310B415E003F14801FC +:102970004901545844F08044545013E002EB431191 +:102980004FF0FF34C1F80849C1F8084B0133D0F8C3 +:1029900094108968994213D303F1480149015158B1 +:1029A0000029E3DB03F15801490151580029E5DA18 +:1029B00003F158014901545844F080445450DDE774 +:1029C0004FF00113C2F81C385DF8044B70474FF00C +:1029D0000113C2F81C387047D0F894301B68C0F857 +:1029E000983070470346D0F898000144C3F8981017 +:1029F000704700BF01E0043A04310B680360042A09 +:102A0000F9D8704710B44FF0000C644601E00CF1A7 +:102A1000010C944509D21CF0030F00D104689C45B9 +:102A2000F5D201F8014B240AF1E75DF8044B704739 +:102A300070B5D0F89060336AC3F30A1503F00F0441 +:102A400003F4F013B3F5802F0ED0B3F5402F0AD165 +:102A5000023400EB8404616808232A46096A06F5FB +:102A60008050FFF7CFFF70BD023400EB8404636831 +:102A700099690A684B68D31A2A46896806F5805016 +:102A8000FFF7C0FF63689A6993682B44936063689B +:102A90009A6953682B445360E5E700BF70B506465A +:102AA0000D4629E0D6F89020D2F83438012000FAFB +:102AB00005F523EA0505C2F8345870BDD6F8900034 +:102AC00000EB4513D3F818399BB2B4EB830F22D82F +:102AD0006B1C2246896800EB0330FFF78BFFAB1CB1 +:102AE00006EB83035A6851698A6822448A605B68EE +:102AF0005A69536823445360AB1C06EB83035A683E +:102B0000516948680B689842CCD21B1A148A9C42BF +:102B1000D4D31C46D2E70020CFE700BF70B50546EE +:102B2000D0F89060002404E02146284698470134FC +:102B3000E4B2D5F894309B689C421ED8224604F13A +:102B400058035B01F35803F44023B3F5802FEED113 +:102B500004F158035B01F358002BE8DA012303FA70 +:102B600004F16B8923EA01036B81023205EB8202D7 +:102B70005368DB68002BD7D1D9E770BD08B5D0F812 +:102B80009020890141F020011161136913F0200F99 +:102B9000FBD11220FFF748F908BD00BFF8B5074682 +:102BA000D0F89050002408E0214638469847214646 +:102BB0003846FFF773FF0134E4B22146D7F894306A +:102BC0009B689C422ED8264604F148035B01EB58D3 +:102BD00003F44023B3F5802FEDD104F148035B01EA +:102BE000EB58002BE7DA04F148035B01EA5842F0A6 +:102BF0009042EA5006F148035B01EB58002BF9DBE9 +:102C00003846FFF7BBFF012303FA06F23B8923EAAC +:102C100002033B81023607EB860673689B68002B34 +:102C2000C2D1C4E7F8BD00BF10B5D0F89040236909 +:102C3000002BFCDA012323610C20FFF7F5F8236950 +:102C400013F0010FFBD11220FFF7EEF82369002BE0 +:102C5000FCDA10BD08B5D0F8902010231361136979 +:102C600013F0100FFBD11220FFF7DEF808BD00BFF4 +:102C700010B50A4C2046FEF783FC094BC4F890308F +:102C8000084BC4F89430084C2046FEF779FC074BFB +:102C9000C4F89030064BC4F8943010BDAC4000200E +:102CA000000008408C430008484100200000044018 +:102CB0009843000870B5D0F890600378012B00D0DD +:102CC00070BD0446434B984225D0434B9C4249D0AB +:102CD0000025C6F8005EC02333604FF40413B363CD +:102CE0002046FFF7A1FFB5602046FFF735FEC6F886 +:102CF0001058C6F81458C6F81C586368DB68002BD7 +:102D000065D0364BB3614FF0FF337361B36843F066 +:102D10000103B360D4E7324BD3F8D82042F000620D +:102D2000C3F8D820D3F8002142F00062C3F8002194 +:102D3000D3F80021D3F8802042F00062C3F880204D +:102D4000D3F8802022F00062C3F88020D3F88030CE +:102D50000E21652000F01EFC224BF360224BC6F8CA +:102D60000038B2E71E4BD3F8D82042F00072C3F807 +:102D7000D820D3F8002142F00072C3F80021D3F824 +:102D80000021D3F8802042F00072C3F88020D3F8ED +:102D9000802022F00072C3F88020D3F88020D3F87E +:102DA000D82022F08062C3F8D820D3F8002122F086 +:102DB0008062C3F80021D3F800310E214D2000F0CD +:102DC000E9FB084BF360084BC6F8003880E7074B77 +:102DD000B36198E7AC40002048410020083C30C077 +:102DE000004402584014004003002002003C30C060 +:102DF00038B50546D0F890400021FFF7BFFE00230C +:102E0000C4F834384FF00112C4F81C2812E003F162 +:102E1000480252014FF00061A15003F158025201E3 +:102E2000A15004EB43124FF0FF31C2F80819C2F869 +:102E3000081B0133D5F8942092689A42E7D22846BD +:102E4000FFF7CAFDD5F894301B6863622846FFF788 +:102E500001FFD4F8003823F4FE63C4F80038A269F7 +:102E60000E4B1343A3610923C4F81038C4F8143877 +:102E70000B4BEB604FF0C043C4F8103B094BC4F858 +:102E8000003B0022C4F81029C4F80039102128465C +:102E9000FFF7A8FD40F48010A06238BD10000C00C0 +:102EA0006843000840800010D0F89020D2F8003825 +:102EB00023F4FE6390F88A1043EA0113C2F8003845 +:102EC000704700BF2DE9F04105460C46D0F89060F0 +:102ED0008B1C00EB83035B681B6803F00303032B6D +:102EE00056D8DFE803F0025B5759444F06EB441312 +:102EF0000022C3F8102BA31C05EB83035B689A69BF +:102F0000002A4DD05A8A3A4304F158035B01F2502B +:102F1000D6F81C3804F1100101228A401343C6F888 +:102F20001C3806EB44130022C3F81029A31C05EB40 +:102F300083035B685A69002A44D0198A89089B8BED +:102F4000012B01D903FB01F14FEA01482846FFF7A5 +:102F500049FD48EA000004F13F0306EB8303586093 +:102F600021462846FFF70AFE47EA8457A01C05EBD6 +:102F700080056B681B8A1F4304F148035B01F7500F +:102F8000D6F81C38012101FA04F41C43C6F81C4889 +:102F9000BDE8F0811A4FA9E71A4FA7E71A4FA5E736 +:102FA00004F158035B01F25822F40042F250D6F8C3 +:102FB0001C3804F1100101228A4023EA0203C6F8FA +:102FC0001C38AEE704F13F0306EB83030F4A5A6057 +:102FD00021462846FFF7D2FD04F148035B01F25871 +:102FE00022F40042F250D6F81C38012101FA04F410 +:102FF00023EA0404C6F81C48CAE700BF008000109A +:103000000080081000800C100080041000040002F2 +:1030100010B50446FFF7E0FC2046FFF79DFC10BD0D +:10302000D0F89030583149015B5813F4004F04D068 +:1030300013F4001F03D102207047002070470120C5 +:10304000704700BFD0F89030483149015B5813F405 +:10305000004F04D013F4001F03D10220704700205A +:1030600070470120704700BF023100EB81004368C8 +:103070001B6A19685B6811605360704710B48B1C41 +:1030800000EB83035B689B691A68DA6019B9402A10 +:1030900001D940221A601A6801F1020C00EB8C0C75 +:1030A000DCF804305B8A1A44013AB2FBF3F202FB0B +:1030B00003F3033323F0030343EAC24343F0C04363 +:1030C000D0F8902002EB4112C2F8103BDCF804303B +:1030D0001B6803F00303012B0AD0D0F8902058316D +:1030E0004901535843F0044353505DF8044B704773 +:1030F000D0F89030D3F8082812F4807F07D001F17F +:10310000580252019C5844F080549C50E5E701F16C +:10311000580252019C5844F000549C50DDE700BF17 +:10312000F8B507460C46D0F8906006EB4113D3F88B +:10313000085BC3F8085B15F0080F0AD0D6F81438FE +:1031400013F0080F05D08B1C00EB83035B685B68F2 +:10315000984715F0010F21D0D6F8143813F0010F5D +:103160001CD0A31C07EB830359688A6954B95368C0 +:10317000488AB3FBF0F500FB15331BB91068D36820 +:1031800098420CD3012303FA04F27B8923EA020359 +:103190007B81CB6813B1214638469847F8BD1B1A8E +:1031A000136000255560202383F31188214638469B +:1031B000FFF764FF85F31188F0E700BF10B48B1CA4 +:1031C00000EB83035B685B691A68DA6032BBD0F896 +:1031D000903003EB41134FF40022C3F810298B1CED +:1031E00000EB83035B681B6803F00303012B2FD004 +:1031F000D0F8904001F148035B01E25842F00442EC +:10320000E250D0F89000D0F83438012202FA01F1EF +:103210001943C0F834185DF8044B704719B9402AB7 +:1032200001D940221A601B688A1C00EB8202526896 +:10323000148A1A19013AB2FBF4F2D0F8904043EA2A +:10324000C24343F0005304EB4114C4F81039C6E7FD +:10325000D0F89030D3F8082812F4807F07D001F11D +:10326000480252019C5844F080549C50C0E701F140 +:10327000480252019C5844F000549C50B8E700BFEB +:103280002DE9F04107460C46D0F8906006EB41135B +:10329000D3F80859C3F8085915F0010F19D0D6F81A +:1032A000103813F0010F14D08B1C00EB8303596806 +:1032B0004B691868DA68904216D3012303FA04F2C6 +:1032C0003B8923EA02033B818B6813B121463846D0 +:1032D000984715F0800F05D0D6F834280123A34075 +:1032E0001A4211D1BDE8F081121A1A604FF000089D +:1032F000C3F80480202383F3118821463846FFF762 +:103300005DFF88F31188E4E721463846FFF7C6FBE6 +:10331000E8E700BF70B50646D0F890506C69AB691D +:103320001C406C6114F4805F6BD1002C6CDB14F4D6 +:10333000006F7ED114F4005F0AD0D5F8083813F07E +:10334000060F7DD1EB6823F4705343F41053EB6008 +:1033500014F0080F04D07368DB680BB1304698474F +:1033600014F4801F73D114F4001F74D114F0100FE3 +:1033700075D1D5F8185814F4002F1BD015F4803FE0 +:1033800071D115F4003F73D115F4802F75D115F468 +:10339000002F77D115F4801F79D115F4001F7BD150 +:1033A00015F4800F7DD115F4000F7FD115F0807FCB +:1033B00040F0818014F4802F22D015F0010F7FD1CE +:1033C00015F0020F40F0818015F0040F40F082806C +:1033D00015F0080F40F0838015F0100F40F0848046 +:1033E00015F0200F40F0858015F0400F40F08680EA +:1033F00015F0800F40F0878015F4807F40F08880C2 +:1034000070BDFEF795FAFBE7D5F8003E13F0030F09 +:1034100005D0D5F8003E23F00303C5F8003ED5F8EB +:10342000043823F00103C5F804383046FEF7B4FA37 +:103430007DE73046FFF790FA3046FEF79DFA79E7D0 +:10344000EB6823F4705343F4A053EB6080E73046FD +:10345000FFF7A4FB87E73046FFF760FB86E73046BF +:10346000FFF7E6FA85E700213046FFF759FE88E7C7 +:1034700001213046FFF754FE86E702213046FFF770 +:103480004FFE84E703213046FFF74AFE82E704211E +:103490003046FFF745FE80E705213046FFF740FE46 +:1034A0007EE706213046FFF73BFE7CE707213046EA +:1034B000FFF736FE7AE708213046FFF731FE79E75D +:1034C00000213046FFF7DCFE7AE701213046FFF7A6 +:1034D000D7FE79E702213046FFF7D2FE78E70321D5 +:1034E0003046FFF7CDFE77E704213046FFF7C8FEF0 +:1034F00076E705213046FFF7C3FE75E70621304623 +:10350000FFF7BEFE74E707213046FFF7B9FE73E709 +:1035100008213046FFF7B4FE72E700BF08B5034844 +:10352000FFF7F8FEFFF78EF908BD00BFAC400020A2 +:1035300008B50348FFF7EEFEFFF784F908BD00BFAA +:1035400048410020D0F8902058314901535843F4A5 +:1035500000135350704700BFD0F890204831490104 +:10356000535843F400135350704700BFD0F89020D5 +:1035700058314901535823F400135350704700BF8A +:10358000D0F8902048314901535823F40013535088 +:10359000704700BF0901C9B2074A131883F8001326 +:1035A00000F01F01400901238B4000F1600142F847 +:1035B000213042F82030704700E100E030B4029C36 +:1035C0000060406001720021C16042610261043309 +:1035D00004FB03258561C361046242628162C162AA +:1035E000039B0363049B436330BC704708B5002210 +:1035F000C260416A416101618262C2626FF0010191 +:10360000FEF78CFC08BD00BF03694269934203D0FA +:10361000002232B9181D7047C268002AF9D0012271 +:10362000F7E70020704700BF08B503691960C36859 +:103630000133C360C2690369134403618269934221 +:1036400001D3436A03610021FEF75CFC08BD00BFA3 +:1036500038B504460D46E36843B9237A73B9294661 +:103660002046FEF73DFC0028F5DA06E06269131DEE +:10367000A36212681344E362002038BD6FF00100BA +:10368000FBE700BF08B5C368013BC360C26943697B +:10369000134443618269934201D3436A4361002327 +:1036A0008362036B03B1984708BD00BF38B5044679 +:1036B000202383F31188836A5BB1A36A13F8015B4B +:1036C000A362E26A93420DD2002383F31188284655 +:1036D00038BDFFF7BDFF05460028EED0002383F379 +:1036E0001188F4E72046FFF7CDFFEDE72DE9F84319 +:1036F00004460F4690469946202383F311880026FE +:1037000031E049462046FFF7A3FF78B3002383F357 +:1037100011883046BDE8F883DCF80050DCF804007E +:10372000DCF80820DCF80C30CEF80050CEF80400AD +:10373000CEF80820CEF80C300CF1100C0EF1100E63 +:103740008C45E9D14037A36A4033A3624036A26A70 +:10375000E36A9A4222D2002383F311884645D8D2E5 +:10376000202383F31188A36A002BCAD0E36AA16ADD +:103770005B1AA8EB06059D4200D31D46402D03D9D8 +:103780008C46BE464031C7E72A463846FDF7D6FB91 +:103790002F44A36A2B44A3622E44D8E72046FFF7A8 +:1037A00071FFD8E710B4019C006040600172C460F2 +:1037B00042610261043304FB03218161C36104623D +:1037C000426200238362C362029B0363039B4363E1 +:1037D0005DF8044B704700BF08B5026AC260426AD8 +:1037E0004261026100228262C2626FF00101FEF753 +:1037F00095FB08BD026943699A4206D000224AB986 +:103800001B680B60406904307047C268002AF6D01C +:103810000122F4E70020704708B5C3680133C36094 +:10382000C2694369134443618269934201D3436A85 +:1038300043610021FEF766FB08BD00BF38B50446B2 +:103840000D46E36843B9237A73B929462046FEF74B +:1038500047FB0028F5DA06E023691A1DA262E26937 +:103860001344E362002038BD6FF00100FBE700BFA6 +:1038700008B503691960C368013BC360C269036985 +:10388000134403618269934201D3436A03610023B5 +:103890008362036B03B1984708BD00BF38B5044687 +:1038A0000D46202383F31188836A5BB1A36A1D70E0 +:1038B000A36A0133A362E26A93420CD2002080F330 +:1038C000118838BD1146FFF7B9FF0028EED000235C +:1038D00083F31188F5E7E16904392046FFF7C8FF53 +:1038E000ECE700BF2DE9F84304460E46174698461C +:1038F000202383F3118800252DE041462046FFF761 +:103900009DFF58B3002383F311882846BDE8F88350 +:10391000DCF800E0DCF80410DCF80820DCF80C30FF +:10392000C0F800E041608260C3600CF1100C103000 +:10393000CC45EDD14036A36A4033A3624035A26A3C +:10394000E36A9A4223D2002383F31188BD42DCD27A +:10395000202383F31188A36A002BCED0E36AA06AE8 +:103960001B1AA7EB0509994500D39946B9F1400FF9 +:1039700003D9B44606F14009CAE74A463146FDF785 +:10398000DDFA4E44A36A4B44A3624D44D7E7E16994 +:1039900004392046FFF76CFFD5E700BF03460169F5 +:1039A0004269914209D0002210462AB19A6ACAB1EE +:1039B000521A043A06D100207047C268002AF3D098 +:1039C0000122F1E70A60DA68013ADA60D9691A6916 +:1039D0000A441A6199698A4201D35A6A1A6100221B +:1039E0009A6270470020704708B500F0E9F808BDFA +:1039F000034B586300221A610222DA60704700BF4D +:103A0000000C0040014B0022DA607047000C0040BF +:103A1000014B5863704700BF000C0040014B586ACF +:103A2000704700BF000C00404B6843608B688360A8 +:103A3000CB68C3600B6943614B6903628B69436266 +:103A40000B680360704700BF10B52A4BD3F888207D +:103A500040F2FF710A43C3F88820D3F88800264A51 +:103A60000240C3F88820D3F88820D3F8E0200A4326 +:103A7000C3F8E020D3F808210A43C3F80821D3F89B +:103A800008311E4C21461E48FFF7CEFF04F11C01F1 +:103A90001C48FFF7C9FF04F138011B48FFF7C4FFBA +:103AA00004F154011948FFF7BFFF04F170011848F1 +:103AB000FFF7BAFF04F18C011648FFF7B5FF04F1D8 +:103AC000A8011548FFF7B0FF04F1C4011348FFF740 +:103AD000ABFF04F1E0011248FFF7A6FF04F1FC017F +:103AE0001048FFF7A1FF04F58C710F48FFF79CFF0A +:103AF00010BD00BF0044025800F8FFFFA4430008B7 +:103B0000000002580004025800080258000C025835 +:103B1000001002580014025800180258001C0258E5 +:103B200000200258002402580028025808B5FFF768 +:103B30008BFF00F0FDF80C4BD3F8902242F001020D +:103B4000C3F89022D3F8942242F00102C3F89422E1 +:103B50000522C3F898204FF06052C3F89C20034A16 +:103B6000C3F8A02008BD00BF00ED00E01F0008035F +:103B700008B500F0EFFAFEF709F90E4BD3F8DC2098 +:103B800042F04002C3F8DC20D3F8042122F04002C6 +:103B9000C3F80421D3F80431074B1A6842F0080235 +:103BA0001A601A6842F004021A60FEF7FBFDFEF785 +:103BB00057FB08BD0044025800180248704700BF78 +:103BC000114BD3F8E82042F00802C3F8E820D3F8FC +:103BD000102142F00802C3F81021D3F810310B4A2B +:103BE000D36B43F00803D363094BC7229A624FF0AB +:103BF000FF32DA6200229A615A63DA605A60012267 +:103C00005A611A60704700BF004402580010005CFF +:103C1000000C004008B50A4A1369D168C9B20B40CC +:103C2000D943116113F0020F00D108BD202383F3A3 +:103C30001188FEF7CBF8002383F31188F5E700BF66 +:103C4000000C004010B5384BD3F880204FF0FF3106 +:103C5000C3F88010D3F880200022C3F88020D3F866 +:103C60008000D3F88400C3F88410D3F88400C3F82C +:103C70008420D3F88400D86F40F0FF4040F4FF0068 +:103C800040F43F5040F03F00D867D86F20F0FF402D +:103C900020F4FF0020F43F5020F03F00D867D86F99 +:103CA000D3F8884021482043C3F88800D3F888001F +:103CB000C0F30A00C3F88800D3F88800D3F8900056 +:103CC000C3F89010D3F89000C3F89020D3F8900078 +:103CD000D3F89400C3F89410D3F89400C3F8942058 +:103CE000D3F89400D3F89800C3F89810D3F898004C +:103CF000C3F89820D3F89800D3F88C00C3F88C1040 +:103D0000D3F88C00C3F88C20D3F88C00D3F89C0037 +:103D1000C3F89C10D3F89C10C3F89C20D3F89C30B7 +:103D200000F0F2F910BD00BF0044025800F8FFFF98 +:103D30006B4B0122C3F808216A4BD3F8F42042F000 +:103D40000202C3F8F420D3F81C2142F00202C3F8A7 +:103D50001C21D3F81C31644B0222DA60624B5B6891 +:103D600013F4005FFAD0604B604A1A6001229A6037 +:103D70005F4ADA6000221A614FF440429A615A4B5E +:103D80009B6913F4005FFAD0574A136843F48073B9 +:103D90001360544B1B6F13F4407F05D0514B4FF40D +:103DA00080321A6700221A674E4A136843F00103F3 +:103DB00013604C4B1B6813F0040FFAD0494B0022E0 +:103DC0001A61484B1B6913F0380FFAD1454B012299 +:103DD0001A604FF080425A6000225A67454ADA6200 +:103DE000454A1A611A6842F480321A603D4B1B68DA +:103DF00013F4003FFAD03B4A136843F48053136036 +:103E0000384B1B6813F4005FFAD0364B3B4A9A627A +:103E100000225A633A491963DA633A4999635A644A +:103E2000394A1A64394ADA621A6842F0A8521A60AA +:103E30002C4B1B6803F02853B3F1285FF8D1294BB2 +:103E400048229A614FF48862DA6140221A62304A4D +:103E5000DA644FF080521A652E4A5A652E4A9A65E6 +:103E60002E4B32221A602D4B1B6803F00F03022BDE +:103E7000F9D11C4A136943F003031361194B1B6901 +:103E800003F03803182BF9D1164BD3F8DC2042F09D +:103E90000052C3F8DC20D3F8042142F00052C3F8EA +:103EA0000421D3F80421D3F8DC2042F08042C3F887 +:103EB000DC20D3F8042142F08042C3F80421D3F877 +:103EC0000421D3F8DC2042F00042C3F8DC20D3F810 +:103ED000042142F00042C3F80421D3F804317047B2 +:103EE00000800051004402580048025800C000F011 +:103EF000020000010000FF0100889008121020005D +:103F0000630209012C02040047040508FD0BFF01B0 +:103F1000200000200010E0000001010000200052FD +:103F200008B54FF0B042D2F8883003F00103C2F870 +:103F300088302BB1044B1B6813B1034A5068984773 +:103F4000FEF780FC08BD00BFFC41002008B54FF023 +:103F5000B042D2F8883003F00203C2F888302BB1A7 +:103F6000044B9B6813B1034AD0689847FEF76AFC7C +:103F700008BD00BFFC41002008B54FF0B042D2F8A8 +:103F8000883003F00403C2F888302BB1044B1B695E +:103F900013B1034A50699847FEF754FC08BD00BFAF +:103FA000FC41002008B54FF0B042D2F8883003F051 +:103FB0000803C2F888302BB1044B9B6913B1034A44 +:103FC000D0699847FEF73EFC08BD00BFFC410020C9 +:103FD00008B54FF0B042D2F8883003F01003C2F8B1 +:103FE00088302BB1044B1B6A13B1034A506A9847BF +:103FF000FEF728FC08BD00BFFC41002010B54FF0C3 +:10400000B043D3F8884004F47872C3F8882014F0E1 +:10401000200F05D0164B9B6A13B1154AD06A9847FA +:1040200014F0400F05D0124B1B6B13B1104A506BAC +:10403000984714F0800F05D00D4B9B6B13B10C4AC1 +:10404000D06B984714F4807F05D0094B1B6C13B1DB +:10405000074A506C984714F4007F05D0044B9B6CC2 +:1040600013B1034AD06C9847FEF7ECFB10BD00BFBC +:10407000FC41002010B54FF0B043D3F8884004F461 +:104080007C42C3F8882014F4806F05D01A4B1B6D56 +:1040900013B1194A506D984714F4006F05D0164BB0 +:1040A0009B6D13B1144AD06D984714F4805F05D00E +:1040B000114B1B6E13B1104A506E984714F4005FF9 +:1040C00005D00D4B9B6E13B10B4AD06E984714F47C +:1040D000804F05D0084B1B6F13B1074A506F9847AC +:1040E00014F4004F05D0044B9B6F13B1024AD06FFC +:1040F0009847FEF7A7FB10BDFC41002008B5FFF76D +:1041000089FDFEF79FFB08BD08B506210846FFF7AD +:1041100041FA06210720FFF73DFA06210820FFF7A4 +:1041200039FA06210920FFF735FA06210A20FFF7A0 +:1041300031FA06211720FFF72DFA06212820FFF774 +:1041400029FA09217A20FFF725FA07213220FFF703 +:1041500021FA08BD08B5FFF775FD00F009F8FDF775 +:104160000BFAFDF791F8FFF729FDFFF73DFC08BDBD +:10417000002307E0054A002142F8331002EBC30296 +:10418000516001330F2BF5D9704700BFFC4100206F +:1041900010B501390244904201D1002005E00378B6 +:1041A00011F8014FA34201D0181B10BD0130F2E7F6 +:1041B000034611F8012B03F8012B002AF9D17047AF +:1041C00053544D333248373F3F3F000053544D3333 +:1041D00032483734332F37353300000001105A008E +:1041E0000310590001205800032056000000000071 +:1041F0004112000825120008791200085D1200081B +:104200006D1200085112000835120008191200083A +:10421000651100080000000001000000000000001F +:104220006D61696E0000000069646C65000000004B +:1042300028420008F823002070250020010000001B +:10424000891D0008000000004172647550696C6FA0 +:104250007400000025424F415244252D424C00007D +:104260002553455249414C25000000000200000042 +:104270000000000065140008F11400084000400030 +:10428000183E0020283E0020020000000000000030 +:1042900003000000000000004515000800000000B9 +:1042A00010000000383E0020000000000100000067 +:1042B00000000000AC40002001010200F5210008D0 +:1042C000E12000087D210008612100084300000072 +:1042D000D442000809024300020100C03209040070 +:1042E0000001020201000524001001052401000163 +:1042F000042402020524060001070582030800FFCA +:1043000009040100020A0000000705010240000044 +:104310000705810240000000120000002043000851 +:10432000120110010200004009124157000201026F +:10433000030100000403090425424F4152442500B3 +:10434000536B797374617273483748442D62647398 +:10435000686F740030313233343536373839414282 +:10436000434445460000000000000000AD1900086D +:10437000AD1A00085D1B000840004000E441002029 +:10438000E441002001000000F44100208000000012 +:1043900040010000080000000001000000040000CF +:1043A000080000000000806A00000000AAAAAAAA73 +:1043B00000000064FFFF00000000000000A00A00F1 +:1043C0004000000100000000AAAAAAAA0000000103 +:1043D000F7FF000000000000000000001004004093 +:1043E00000000000AAAAAAAA00000040FFFF0000E7 +:1043F00000000000000000001000000000000000AD +:10440000AAAAAAAA00000000FBFF0000000000000A +:10441000000000004001400000000000AAAAAAAA73 +:1044200000004000FFFF000000000000000000004E +:104430000000000000000000AAAAAAAA00000000D4 +:10444000FFFF00000000000000000000000000006E +:1044500000000000AAAAAAAA00000000FFFF0000B6 +:10446000000000000000000000000000000000004C +:10447000AAAAAAAA00000000FFFF00000000000096 +:10448000000000000000000000000000AAAAAAAA84 +:1044900000000000FFFF000000000000000000001E +:1044A0000000000000000000AAAAAAAA0000000064 +:1044B000FFFF0000000000000000000000000000FE +:1044C00000000000AAAAAAAA00000000FFFF000046 +:1044D00000000000000000003304000000000000A5 +:1044E00000001A0000000000FF00000000000000B3 +:1044F000C04100083F00000050040000CC4100080B +:104500003F00000000960000000008000096000038 +:104510000000080004000000344300080000000010 +:10452000000000000000000000000000000000008B +:044530000000000087 +:00000001FF diff --git a/Tools/bootloaders/SkystarsH7HD_bl.bin b/Tools/bootloaders/SkystarsH7HD_bl.bin new file mode 100755 index 00000000000..0d72a6fe9ec Binary files /dev/null and b/Tools/bootloaders/SkystarsH7HD_bl.bin differ diff --git a/Tools/bootloaders/SkystarsH7HD_bl.hex b/Tools/bootloaders/SkystarsH7HD_bl.hex new file mode 100644 index 00000000000..cf629a8c8d4 --- /dev/null +++ b/Tools/bootloaders/SkystarsH7HD_bl.hex @@ -0,0 +1,1109 @@ +:020000040800F2 +:1000000000060020A10200082D110008AD10000814 +:1000100005110008AD100008D9100008A30200085F +:10002000A3020008A3020008A3020008CD270008CD +:10003000A3020008A3020008A3020008A30200080C +:10004000A3020008A3020008A3020008A3020008FC +:10005000A3020008A3020008193F0008453F00085A +:10006000713F00089D3F0008C93F0008A302000837 +:10007000A3020008A3020008A3020008A3020008CC +:10008000A3020008A3020008A3020008A3020008BC +:10009000A3020008A3020008A3020008F53F00081D +:1000A000A3020008A3020008A3020008A30200089C +:1000B000A3020008A3020008A3020008A30200088C +:1000C000A3020008A3020008A3020008A30200087C +:1000D000A3020008A3020008A3020008A30200086C +:1000E0006D400008A3020008A3020008A302000854 +:1000F000A3020008A3020008A3020008A30200084C +:10010000A3020008A3020008F5400008A3020008AB +:10011000A3020008A3020008A3020008A30200082B +:10012000A3020008A3020008A3020008A30200081B +:10013000A3020008A3020008A3020008A30200080B +:10014000A3020008A3020008A3020008A3020008FB +:10015000A3020008A3020008A3020008A3020008EB +:10016000A3020008A3020008A3020008A3020008DB +:10017000A302000829350008A3020008A302000812 +:10018000A3020008A3020008A3020008A3020008BB +:10019000A3020008A3020008A3020008A3020008AB +:1001A000A3020008A3020008A3020008A30200089B +:1001B000A3020008A3020008A3020008A30200088B +:1001C000A3020008A3020008A3020008A30200087B +:1001D000A302000815350008A3020008A3020008C6 +:1001E000A3020008A3020008A3020008A30200085B +:1001F000A3020008A3020008A3020008A30200084B +:10020000A3020008A3020008A3020008A30200083A +:10021000A3020008A3020008A3020008A30200082A +:10022000A3020008A3020008A3020008A30200081A +:10023000A3020008A3020008A3020008A30200080A +:10024000A3020008A3020008A3020008A3020008FA +:10025000A3020008A3020008A3020008A3020008EA +:10026000A3020008A3020008A3020008A3020008DA +:10027000A3020008A3020008A3020008A3020008CA +:10028000A3020008A3020008A3020008A3020008BA +:10029000A3020008A3020008A3020008A3020008AA +:1002A00002E000F000F8FEE772B63A4880F30888F2 +:1002B000394880F3098839484EF60851CEF20001DA +:1002C000086040F20000CCF200004EF63471CEF22D +:1002D00000010860BFF34F8FBFF36F8F40F2000043 +:1002E000C0F2F0004EF68851CEF200010860BFF374 +:1002F0004F8FBFF36F8F4FF00000E1EE100A4EF604 +:100300003C71CEF200010860062080F31488BFF330 +:100310006F8F02F01BFB02F0BDFA03F003FC4FF0FD +:1003200055301F491B4A91423CBF41F8040BFAE784 +:100330001C49194A91423CBF41F8040BFAE71A499B +:100340001A4A1B4B9A423EBF51F8040B42F8040B69 +:10035000F8E700201749184A91423CBF41F8040BC6 +:10036000FAE702F0D9FA03F0FFFB144C144DAC424B +:1003700003DA54F8041B8847F9E700F041F8114C00 +:10038000114DAC4203DA54F8041B8847F9E702F038 +:10039000C1BA000000060020002200200000000872 +:1003A0000000002000060020D044000800220020A9 +:1003B0005C220020602200207C420020A002000875 +:1003C000A0020008A0020008A00200082DE9F04FDA +:1003D0002DED108AC1F80CD0D0F80CD0BDEC108AED +:1003E000BDE8F08F002383F311882846A047002042 +:1003F00001F062FDFEE701F0B3FC00DFFEE7000064 +:1004000038B500F063FD18B1154B4FF460229A60C7 +:1004100002F096F9044602F0CFF9054640B9114BB7 +:100420009C4214D001339C4213D041F2883400E046 +:100430000024002002F090F975B900F009FE00F0E8 +:1004400065FC204600F070F900F000F9F9E700249F +:10045000EFE700240125ECE700F0F8F8EDE700BF36 +:1004600000220020010007B010B584468E46BFF37D +:100470004F8FBFF36F8F1F4B0022C3F88420BFF351 +:100480004F8F5A6922F480325A61BFF34F8FD3F8ED +:100490008040C4F34E3000E01846C4F3C90243F66E +:1004A000E07303EA401343EA82731249C1F87432DD +:1004B0001346013A002BF2D1431E0028ECD1BFF3C2 +:1004C0004F8FBFF36F8FBFF34F8FBFF36F8F4A69AB +:1004D00022F400324A610022C1F85022BFF34F8F4C +:1004E000BFF36F8F202383F31188E5468CF30888D0 +:1004F000704710BD00ED00E000B583B0019004210D +:100500000DEB010000F0F4FB03B05DF804FB00BF4D +:1005100000B583B041F21203ADF80430022101A806 +:1005200000F0E6FB03B05DF804FB00BF00B583B04C +:1005300041F21233ADF80430022101A800F0D8FBDB +:1005400003B05DF804FB00BF00B583B041F21213A5 +:10055000ADF80430022101A800F0CAFB03B05DF839 +:1005600004FB00BF08B5C0EB401300EB8300C000E4 +:1005700001F0AAFC08BD00BF08B5202383F3118851 +:100580001F4BDB6813B11E4801F02AFD00231D4AF2 +:100590004FF47A711A4801F013FD002383F3118898 +:1005A00001E00133DBB2012B0BD8174A52F82320AC +:1005B000002AF6D0144951F82320013A41F82320AB +:1005C000EFE7124B1B7813B90F4B5B6823B10F4B4E +:1005D0001B78032B07D008BD022000F09BFC0A4BC0 +:1005E00032225A60F3E7084B5B68002BF3D10220FC +:1005F00000F090FC044B4FF47A725A60EBE700BFB6 +:1006000060220020790500087C230020742200204D +:1006100008B50C4B1870032806D8DFE800F00A066E +:10062000020E022000F066FC08BD022000F050FC23 +:10063000FAE7054B00225A60F6E7034B00225A60A6 +:10064000F2E700BF742200207C23002008B50023BD +:10065000072B08D8304A52F82320B2F1FF3F0DD0C3 +:100660000133DBB2F4E72C4B5B682C4A934205D98B +:100670002B4A9168284A0A44934200D308BD0020BF +:1006800000F070FB0220FFF7C3FF264BD3F8E820F1 +:100690000022C3F8E820D3F81011C3F81021D3F8D2 +:1006A0001011D3F8EC10C3F8EC20D3F81411C3F8F0 +:1006B0001421D3F81411D3F8F010C3F8F020D3F8B4 +:1006C0001811C3F81821D3F81821D3F8802042F06C +:1006D0000062C3F88020D3F8802022F00062C3F8C3 +:1006E0008020D3F88020D3F8802042F00072C3F835 +:1006F0008020D3F8802022F00072C3F88020D3F845 +:10070000803072B6044B4FF0E022C2F8083D5968C1 +:100710001868FFF7A9FEB1E700000208FFFF010813 +:1007200000220020004402582DE9F04F91B0054608 +:10073000A94BD3F808A02022FF210DEB020000F006 +:1007400029FCA64B1B787BB10DB1A54B1D60A54BB9 +:100750001B78032B21D12C460026B0463746B146E4 +:10076000012000F0C7FB23E09C4B01221A709E4B36 +:100770000022DA60202282F31188DB6813B19A48E4 +:1007800001F02EFC0023994A4FF47A71964801F04B +:1007900017FC002383F31188D6E70020FFF738FF0A +:1007A000D9E7002000F084FA0290029B002B08DABF +:1007B000002CF6D08A4B1B68002BF2D111B0BDE89B +:1007C000F08F012000F084FB029B213B162BC7D841 +:1007D00001A252F823F000BF3508000859080008AC +:1007E000F7080008610700086107000861070008B2 +:1007F0006D090008570B00086B0A0008CF0A0008B3 +:10080000F30A0008170B000861070008350B000801 +:1008100061070008AB0B00084308000861070008E7 +:10082000EB0B0008210B00084308000861070008D3 +:10083000CF0A0008022000F03BFA202840F0708127 +:10084000012700F0FBFB27B108F00B030B2B00F096 +:10085000EB81FFF75DFE83E74FF47A7000F028FA32 +:10086000B0F1000BC0F25C81022000F021FA2028D8 +:1008700040F056810BF1FF33052B00F2D781DFE802 +:1008800003F003151A1F243505230393042103A83D +:1008900000F02EFA0BF1FF30012303FA00F040EADA +:1008A00008085FFA88F84FF00009CAE704214A48AF +:1008B00000F01EFAEEE704214D4800F019FAE9E7CE +:1008C00004214C4800F014FAE4E74FF00709B9F1AD +:1008D0000A0FDFD84FEA890000F048FA039004219C +:1008E00003A800F005FA09F10109F0E704214248E4 +:1008F00000F0FEF9CEE7002F00F0128108F00B03A4 +:100900000B2B40F00D81022000F0D2F9202840F09E +:100910000781012000F026FA0220FFF779FE002669 +:10092000304600F033FA044640B1304600F040FA59 +:10093000002800F080810136F6B2F1E70120FFF7D0 +:1009400067FEA246244B9B68534509D9504600F0E8 +:100950000DFAB0F1FF3F40F073810AF1040AF1E7AC +:100960000020FFF755FE3E46A2466AE7002F00F042 +:10097000D78008F00B030B2B40F0D2800220FFF74A +:1009800047FE322000F094F9B0F1000BC0F2C880AD +:10099000CDF800B01BF0030F40F0C2800BEB0A0350 +:1009A0000D4A9268934200F2BB80BBF5807F00F253 +:1009B000B780002301941C46A34521DD4FF47A70D3 +:1009C00000F076F90290029B002BC0F23281029A6D +:1009D0000A4B1A550134EFE700220020782300204B +:1009E0007C2300207422002060220020790500086A +:1009F00004220020082200200C220020782200205F +:100A0000019CC82000F054F9202840F08980BAF1F8 +:100A10001F0F15D8CAF120039B4500D900932AF077 +:100A200003009DF8003000931A4686490DF1200C12 +:100A3000604400F083FA009AFF21824800F0AAFA8D +:100A40005A46BBF1000F0DDB4FEAA20BC2F387023F +:100A50007C49504600F0A8FA002800F0EE800AEB2E +:100A60008B0AEEE60BF10302EEE7022000F020F91C +:100A7000202855D100F0B6F9002851D04FF0000BD6 +:100A800000945C460BE0584600F070F90390042295 +:100A900003A9204600F04CFB04460BF1040B6A4B03 +:100AA0009B685B450ED9BBF11F0FECD8089BB3F1D7 +:100AB000FF3FE8D02BF0030310AA134453F8203C67 +:100AC0000393E4E72046009CFFF716FDB9E60023F8 +:100AD0000393642103A800F0FFF808BB022000F094 +:100AE000E7F820281CD1039800F074F9FFF704FD03 +:100AF000A7E600230393642103A800F0EDF878B97A +:100B0000022000F0D5F820280AD1039800F064F9FB +:100B1000FFF7F2FC95E6022000F0CAF8202804D086 +:100B200006B92C46FFF702FD1AE600F06DF9FFF753 +:100B3000E3FC86E6022000F0BBF82028F0D103A9F0 +:100B4000142000F067F98346FFF7D6FC594603A846 +:100B500000F0CEF875E6322000F0AAF8B0F1000BF4 +:100B6000DEDB1BF0030FDBD10BEB0903364A926887 +:100B70009342D5D8022000F09BF82028D0D15B46C4 +:100B8000BBF1000F0EDB9B1003F1FF3B002B7FF747 +:100B900058AE484600F0EAF8FFF7AEFC09F1040948 +:100BA0005B46F1E70BF10303EDE74FF47A7000F0D9 +:100BB0007FF82028B4D100F015F900283DD0089B1B +:100BC000B3F1FF3F0BD0082208A9002000F0ECF998 +:100BD00098B32022FF210DEB020000F0DBF9FFF7B4 +:100BE00097FC6420FFF7BEFCE8E5002F98D008F0E2 +:100BF0000B030B2B94D100230393642103A800F073 +:100C00006BF800288CD1022000F052F8202887D100 +:100C1000FFF77EFC0520FFF7A5FC039800F044FADF +:100C200000F00CFA00249BE5002412E64FF00009C6 +:100C300076E7019C74E73E460024FFF785FC8FE5CC +:100C40003E46FAE778220020002200202DE9F041FC +:100C500007460E4615460024E4B9124B93F90030BE +:100C6000B3F1FF3F01D0A3420DD10F480368D3F881 +:100C70002080C5EB451305EB8303DB003246394684 +:100C8000C047864202D00134E4B2E5E7074B1C704E +:100C9000012004E04FF4FA7001F016F90020BDE8DD +:100CA000F08100BF1022002070250020B02300201A +:100CB00000B583B0024600238DF8073001210DF105 +:100CC0000700FFF7C3FF20B19DF8070003B05DF8F0 +:100CD00004FB4FF0FF30F9E708B50A460421FFF79F +:100CE000B5FF08B1002008BD4FF0FF30FBE700BFA3 +:100CF00010B584460A4603480368DC69024B614626 +:100D0000A04710BD70250020A086010038B501F075 +:100D10004BFC124B1880002406E001F041FC044417 +:100D20000F4A136801331360B4F5003F07D20B4B31 +:100D30001B880B4A10688342EFD8002500E000258D +:100D4000B5F5802F09D2054C2088013801F028FC28 +:100D500005442388013B2380F2E738BDB2230020FD +:100D60008423002008B501F095FC08BD014BC05854 +:100D7000704700BF0000020808B503469200024811 +:100D8000184401F083FC08BD0000020808B5064BBA +:100D90001B88064A12689B1A834201D8002008BDAE +:100DA000104401F0FDFBFAE7B22300208423002069 +:100DB00010B50446064B1868204401F0F7FB00B15B +:100DC00010BD034B1868204401F008FCF8E700BF91 +:100DD0008423002000207047014BC058704700BF9B +:100DE00000E8F11F08B5074B93F824300BB9012038 +:100DF00008BD0449002381F824300822086AFFF75F +:100E0000BBFFF5E788230020014B1868704700BF3F +:100E10000010005C30B585B084468E46284B1C68B7 +:100E2000C4F30B05240C274B93E8070004AB03E93C +:100E300007000023012B11D803EB4302214931F8AD +:100E40002220AA4201D00133F4E703EB430301EB74 +:100E5000830393E8070004AB03E90700002300E0E5 +:100E60000133032B0CD8184A32F82320A242F7D1C1 +:100E7000154A02EB830292F902208DF80C20EFE76D +:100E80000CF1FF3CF444704603E00133029300F898 +:100E9000012B604504D2029B93F90020002AF4D173 +:100EA000604502D22C2300F8013B604503D29DF837 +:100EB0000C3000F8013BA0EB0E0005B030BD00BFC8 +:100EC0000010005C14220020D4410008002070476C +:100ED000022802D0012805D07047054B4FF40022AC +:100EE0009A61F7E7024B4FF480129A61F4E700BF72 +:100EF00000100258022802D0012804D07047044B89 +:100F000008229A61F8E7024B10229A61F6E700BFC7 +:100F100000100258022802D0012806D07047064A65 +:100F2000536983F008035361F6E7034A536983F07A +:100F300010035361F2E700BF00100258002304E0E1 +:100F400011F803C000F803C001339342F8D370478F +:100F500002E001300131624690F9003043B191F96D +:100F600000C0634504D102F1FF3C002AF1D1624682 +:100F70001AB191F90000181A70470020704700BF9D +:100F80000346002000E0013013F9012B002AFAD1BA +:100F9000704700BF034602E003F8011B624602F1FE +:100FA000FF3C002AF8D170472DE9F8438146884676 +:100FB0001546214B93F8243033B31F4A126A02EBD3 +:100FC0008303834220D0FFF70DFF0346E0B930E0F2 +:100FD000194E96F82400C0F10804AC4228BF2C46F4 +:100FE000E4B2A7003A46414606EB8000FFF7A6FFB1 +:100FF000B944B8442D1BEDB296F824301C44E4B239 +:1010000086F82440082C0DD095B10B4B93F8243072 +:10101000002BDDD10848C0F820902022FF21FFF7E7 +:10102000B9FFD5E7FFF7DEFE03460028ECD100E06C +:1010300001231846BDE8F88388230020024B93F96A +:101040000020024B1A707047B023002010220020AD +:1010500038B5114D284600F019F9104C21462846A4 +:1010600000F042F92468D4F89020D2F8043843F014 +:101070000203C2F804380A4800F026FF0949204656 +:1010800000F094FAD4F89020D2F8043823F0020348 +:10109000C2F8043838BD00BF70250020AC420008FB +:1010A00040420F00B4420008704700BF00B59BB03B +:1010B000EFF3098168226846FFF740FFEFF30583ED +:1010C000044B9A6BDA6A9A6A9A6A9A6A9A6A9A6A74 +:1010D0009B6AFEE700ED00E000B59BB0EFF30981ED +:1010E00068226846FFF72AFFEFF30583044B9A6BEB +:1010F0009A6A9A6A9A6A9A6A9A6A9B6AFEE700BF33 +:1011000000ED00E000B59BB0EFF30981682268466E +:10111000FFF714FFEFF30583034B5A6B9A6A9A6A41 +:101120009A6A9A6A9B6AFEE700ED00E0FEE700BF5C +:1011300000B58E460AE040F3000C09490CEA0101B3 +:1011400081EA50000133DBB2072BF4D91346013A90 +:1011500023B11EF8013B58400023F5E75DF804FB7E +:101160002083B8ED0020704710B582B0446B04F5C1 +:101170008053D3F8A4381A681178042908D1217C47 +:10118000022905D11289197901238B40134201D01C +:1011900002B010BD01A904F14C0002F027FB024689 +:1011A00004F58054D4F8A448019B2179206800F00C +:1011B000A5FBEDE700F58053D3F8A4381A68117841 +:1011C00004291DD110B50446017C02291AD1528987 +:1011D000597901238B40134201D0012013E01430D0 +:1011E00002F00EFA024678B104F58054D4F8A4084F +:1011F0004FF440734179006800F066FB002002E084 +:1012000001207047012010BD0120FCE708B5406BAC +:10121000FFF7D0FF08BD00BF08B5143002F062FA36 +:1012200008BD00BF08B54FF0FF33143002F05AFA82 +:1012300008BD00BF08B54C3002F050FB08BD00BF30 +:1012400008B54FF0FF334C3002F048FB08BD00BF3B +:1012500008B5143002F026FA08BD00BF08B54FF0FB +:10126000FF31143002F01EFA08BD00BF08B54C3043 +:1012700002F010FB08BD00BF08B54FF0FF324C3044 +:1012800002F008FB08BD00BF704700BF70B584B016 +:101290000446124B0360002343608360C360012552 +:1012A000057402900E4B0193042600964FF4407390 +:1012B00000F184022946143002F07CF90294094BB3 +:1012C000019300964FF4407304F69442294604F1CA +:1012D0004C0002F063FA04B070BD00BFE4410008A6 +:1012E0000D120008691100080A68202383F3118891 +:1012F0000B790B3342F823004B79133342F8230068 +:101300008B7913B10B3342F8230000F58053C3F8F7 +:10131000A41802230374002383F31188704700BFCD +:1013200038B50446037F13B190F85430BBB9201D83 +:10133000636843F002036360A36803B19847012523 +:1013400025776FF0010104F1140000F0E7FD84F847 +:1013500054506FF0010104F14C0000F0DFFD38BD86 +:1013600010B50446436843F00103436083680BB142 +:10137000043098470023237784F8543010BD00BF11 +:1013800038B50446143002F02DF90025257704F114 +:101390004C0002F01DFA84F85450636843F00103D6 +:1013A0006360A3680BB1201D98472046FFF702FF3A +:1013B00038BD00BF90F8803003F06003202B01D0CF +:1013C0000020704790F88130212B05D0222B13D0BC +:1013D000202B09D0002070470A4B436707238367FF +:1013E0000023C36701207047064B436707238367C9 +:1013F0000023C36701207047002343678367C367E7 +:10140000012070472C22002000F58053D3F8A43827 +:101410001A681178042923D130B583B00446017CC1 +:10142000022905D11289197901238B40134201D079 +:1014300003B030BD00F14C05284602F0ABFA00289D +:10144000F6D001A9284602F0D1F9024604F58054ED +:10145000D4F8A448019B2179206800F04FFAE7E70F +:10146000704700BF70B582B001F10B0350F8234004 +:1014700014B305460E46202383F31188201D6368AC +:1014800043F008036360A36803B19847B31C05EBFE +:1014900083035B685B691B6883B901A904F14C0095 +:1014A00002F0A4F9024670B1019B3146284600F0D3 +:1014B00025FA002383F3118802B070BD04F14C00BB +:1014C00002F0A6F9E9E7B31C05EB83035A685369F8 +:1014D0001B68002BEDD0128A013A1342E9D1002398 +:1014E00005F180023146284600F008FAE1E700BF26 +:1014F00038B5133150F8214014B3202383F31188F9 +:1015000004F58053D3F8A42813685279023203EB10 +:1015100082035B689B695D6865B1201D636843F069 +:1015200004036360A36803B19847294604F11400DB +:1015300002F076F82046FFF73DFE002383F3118882 +:1015400038BD00BF704700BF0378407843EA0020F1 +:10155000704700BF10B5044690F8823080F88A309A +:1015600001F09EFC63681B6813B101212046984777 +:101570000323237010BD00BF08B501F075FB08BD43 +:10158000012303700023436009E003F10C010022F2 +:1015900040F8212003F1140140F821200133072BEA +:1015A000F3D9002303814381704700BF10B504467F +:1015B000202383F311884160002305E09A1C04EB8B +:1015C0008202002151600133082BF7D9204601F037 +:1015D0006DFB02232370002383F3118810BD00BF2D +:1015E00008B58B1C00EB83035A6053694BB14FF075 +:1015F000000CC3F800C0C3F804C0C3F808C0C3F8A7 +:101600000CC0936923B100221A605A609A60DA60B4 +:1016100001F054FC08BD00BF08B5038903F00103C5 +:101620000381438903F001034381012305E09A1CF0 +:1016300000EB8202002151600133082BF7D901F041 +:10164000E3FC08BD38B5044690F8803003F07F0312 +:1016500090F8812043EA022340F20232934200F0E4 +:101660000F8137D8B3F5807F00F081800DD9B3F5B5 +:10167000817F00F0EF80B3F5407F29D190F8823070 +:10168000012B00F08680002046E0012B65D0022B64 +:1016900012D190F8841090F98430002BC0F2B08001 +:1016A00001F00F0101F0B8FC012800F0C38002280E +:1016B00000F0C88000202FE043B900F188034367A1 +:1016C000022383670023C367012025E0002023E075 +:1016D000002021E0B3F5006F75D018D9B3F5106F75 +:1016E00037D10378042B76D094F882304BB184F84C +:1016F0008B300423237063681B6813B102212046DA +:10170000984700236367A367E367012004E0B3F50C +:10171000A06F4AD001D2002038BDA3F5C063012BD1 +:1017200000F2C48043685D688430FFF70DFF034614 +:1017300094F8822094F883102046A847002800F0EF +:10174000B780426862670368A3670023E3670120EC +:10175000E2E740F60242934207D1584B6367022307 +:10176000A3670023E3670120D6E70020D4E790F8C1 +:101770008230012B01D00020CEE7B0F8883023F072 +:101780000203A0F88830002343678367C367012002 +:10179000C2E7B0F8883043F00203A0F88830002395 +:1017A00043678367C3670120B6E7B0F88030B3F5BD +:1017B000A06F05D000236367A367E3670120ABE751 +:1017C000FFF7C8FEF6E700F18B0343670120A0672F +:1017D0000023E367A0E7202383F31188FFF71CFFB2 +:1017E000002383F3118884F88B300323237063680C +:1017F0001B68002B3FF478AF03212046984773E71E +:1018000001F00F0101F01AFC012803D0022809D0D1 +:10181000002081E72A4B63670223A3670023E36765 +:10182000012079E7274B63670223A3670023E3675F +:10183000012071E7224B63670223A3670023E3675C +:10184000012069E71F4B63670223A3670023E36757 +:10185000012061E790F8823063BB90F8843013F088 +:101860000F0104D013F0800F07D101F07BFE00239D +:101870006367A367E36701204EE701F07DFEF6E7AB +:1018800090F88230C3B990F8843013F00F0104D07F +:1018900013F0800F07D101F051FE00236367A367A7 +:1018A000E367012038E701F053FEF6E7002033E755 +:1018B000002031E700202FE700202DE71442000828 +:1018C000104200080C42000838B50C464FF0010EDB +:1018D0000EFA01FE1FFA8EFE45894EEA050EA0F8AB +:1018E0000AE0023400EB84046468A469A260236007 +:1018F0000023636001F0BEFB38BD00BF38B50C4665 +:101900004FF0010E0EFA01FE1FFA8EFE05894EEA17 +:10191000050EA0F808E0023400EB840464686469F2 +:10192000A26023600023636001F044FC38BD00BF67 +:1019300010B50446022303700023A0F8883080F815 +:101940008A3080F88B300381438105E09A1C04EBD8 +:101950008202002151600133082BF7D9002384F85B +:101960007030204601F040FA63681B6813B1002113 +:101970002046984710BD00BF10B50446037880F894 +:101980008C300523037043681B680BB10421984712 +:1019900000232381638110BD08B590F88C3003705B +:1019A00043681B680BB10521984708BD10B5044674 +:1019B00090F8703013B1002380F8703004F1800289 +:1019C000204601F04DFB63689B6813B120469847A1 +:1019D00040B994F8803013F0600F22D12046FFF711 +:1019E00031FEF0B104F18600FFF7AEFDA36F834234 +:1019F00000D9A06794F98030002B24DBA36F002B63 +:101A000043D0152384F87030202383F31188A36F0B +:101A1000626F00212046FFF757FF002383F31188F0 +:101A200010E00021204601F093FD0021204601F046 +:101A300085FD63681B6813B106212046984706237D +:101A400084F8703010BDA36F7BB1092384F8703027 +:101A5000202383F31188A36F626F00212046FFF7D4 +:101A60004DFF002383F31188ECE7142384F87030D2 +:101A7000202383F3118800231A4619462046FFF7D6 +:101A800023FF002383F31188DCE70B2384F87030F5 +:101A9000202383F3118800231A4619462046FFF7B6 +:101AA0002DFF002383F31188CCE700BF10B5044657 +:101AB00090F87030152B28D8DFE803F03F27272750 +:101AC00027273F27270B18382727272727272727A8 +:101AD0003F3F8630FFF738FDA36F834206D2E268AE +:101AE000128AB3FBF2F102FB11337BB1142384F8A9 +:101AF0007030202383F3118800231A4619462046AC +:101B0000FFF7E2FE002383F3118810BD202383F347 +:101B1000118800231A4619462046FFF7EFFE0023DE +:101B200083F311880A2384F87030EEE7C36F03B1A2 +:101B30009847002384F87030E7E7002101F008FDA2 +:101B40000021204601F0FAFC63681B6813B10621EE +:101B500020469847062384F87030D6E710B504462F +:101B600090F87030152B1AD8DFE803F026191919F0 +:101B700019192619192626261919191919191919A1 +:101B80001A0B0B2380F87030202383F31188002375 +:101B90001A461946FFF7B2FE002383F3118810BDE1 +:101BA000C3689B695B68002BF9D1C36F03B1984789 +:101BB000002384F87030F2E7002101F0C9FC002115 +:101BC000204601F0BBFC63681B6813B10621204668 +:101BD0009847062384F87030E1E700BF024B1B6092 +:101BE0005B6000229A607047B423002000230374D6 +:101BF000054B1B68996882689142FAD203605A6863 +:101C00004260106058607047B423002008B520235C +:101C100083F31188037C032B0ED0042B10D043B127 +:101C20004FF0FF334361FFF7E1FF002383F3118897 +:101C300008BD83F31188FBE7436900221A60EFE7D0 +:101C400042680368136042685A60E9E7002303743E +:101C5000054B1B68996882689142FAD803605A68FC +:101C60004260106058607047B423002008B5074BED +:101C7000196908741A681068186043601A610120B5 +:101C800010741869FEF7A2FB08BD00BFB423002042 +:101C900010B586B00446B1F1FF3F12D00A4B1B6964 +:101CA0000A4A01A800F08CF92046FFF7DFFF049BE9 +:101CB00013B101A800F094F9034B1B69586906B0F1 +:101CC00010BDFFF7D3FFF7E7B42300200D1C000879 +:101CD00010B504460A4B18696161A26883689A428C +:101CE00003D82046FFF782FF10BDFFF7AFFF014684 +:101CF000034B1C61012323742046FEF767FBF3E7C7 +:101D0000B4230020044B1A6890681B699B689842B2 +:101D100094BF002001207047B423002010B5084C68 +:101D2000206923681A6822605460236101221A74B2 +:101D3000FFF78CFF01462069FEF748FB10BD00BF8E +:101D4000B423002008B5054B1A6892681B699B688C +:101D50009A4200D808BDFFF7E1FFFBE7B42300205B +:101D600010B5084C206923681A682260546023610A +:101D700001221A74FFF76AFF01462069FEF726FB6D +:101D800010BD00BFB4230020FEE700BF10B5FFF771 +:101D900025FF00F007F90A4C80220A49204600F08E +:101DA00053F844F8180C0123037400F01FFD0023BE +:101DB00083F3118862B6044800F064F810BD00BFD8 +:101DC000DC230020184200082842000808B500F073 +:101DD00047F908BDEFF3118058B9EFF30583C3F35A +:101DE00008031BB1202383F311887047202383F35A +:101DF0001188704778B908B5EFF30583C3F308037A +:101E00001BB1002383F3118808BDFFF79BFF00235C +:101E100083F31188F8E77047401A511A88422CBFA3 +:101E200000200120704700BF38B5064B5D6844199B +:101E3000044B586822462946FFF7EEFF0028F7D1E9 +:101E400038BD00BF001000E0826002220274002250 +:101E50004274704710B58468A4F17C0344F80C3CCC +:101E6000026944F83C2C426944F8382C044A44F88E +:101E70001C2CC2680168A4F11800FFF7E5FF10BD33 +:101E8000E503000810B5202383F31188FFF7E2FF74 +:101E900004460021FFF71CFF002383F3118820462E +:101EA00010BD00BF08B5034B1B6958610F20FFF739 +:101EB000DDFE08BDB423002008B5202383F311887C +:101EC000FFF7F0FF08BD00BF08B50146202383F3EC +:101ED00011880820FFF7DCFE002383F3118808BD7A +:101EE00059B108B5064B1B69186042685A60136007 +:101EF00043600420FFF7CCFE08BD4FF0FF30704771 +:101F0000B423002008B503460068834205D0026868 +:101F10001A6053604161FFF769FE08BD38B5044699 +:101F20000D4605E0036823605C604561FFF75EFED7 +:101F300020688442F6D138BD70B505460E461C4671 +:101F40000368984209D0C068121AA21800D2144639 +:101F50009B68A34210D82A6814E0C2608C6070604D +:101F600003680B6059602960092C00D80A24E868CE +:101F7000204401F039FD14E0204401F045FDEAE77A +:101F8000E41A126893689C42FAD8B46032605368CD +:101F900073601E60566093681B1B93604FF0FF33A5 +:101FA000AB6070BD054B03F114025A619A614FF0AA +:101FB000FF32DA6100221A62704700BFB4230020AA +:101FC00038B504460D460361C26001F023FD0246A8 +:101FD0002B4621460148FFF7AFFF38BDC82300203C +:101FE00038B51E4B5B69984210D042680368136095 +:101FF00042685A600023C3600268816893680B449A +:102000009360164B4FF0FF32DA6138BD1968134AFE +:10201000134643F8141F4B600021C16052699A4275 +:1020200018D0816893680B4493600C4D2C6A01F0C2 +:10203000F1FC021B6B699B689342E6D9241A1C448D +:10204000092C01D802F10A03044A106A184401F06D +:10205000DBFCDAE701F0D2FCD7E700BFB4230020B5 +:1020600038B507E0002383F311882069A8472023AF +:1020700083F31188144D6C6901F0CCFC2B6AC21AF1 +:10208000A168914211D819442B46296261682268DF +:102090000A6061685160E5680022E26053F8142F1D +:1020A0009A42DFD101F0AAFCDCE7074A52F8144F4C +:1020B000944207D01A1A0A44092A00D80A22104466 +:1020C00001F0A2FC38BD00BFB423002000207047FF +:1020D000FEE700BF704700BF4FF0FF30704700BF02 +:1020E00002290DD0032905D0012901D00020704715 +:1020F00005487047032A05D8044800EBC200704722 +:102100000348704700207047104300083C2200201D +:10211000C442000830B59BB005460846144601A9E4 +:1021200000F0D6F801A8FEF72BFF5FFA80FC431CF5 +:102130005B002B606C6023700323637000230BE053 +:10214000591C1AAA1A4412F8642C04F811205B00D6 +:1021500003330022E254CBB26345F1D31BB030BD50 +:1021600008B5202383F311880348FFF74DF90023B6 +:1021700083F3118808BD00BF7025002008B590F8D2 +:10218000803003F01F02012A11D003F06003202BDE +:102190000AD1B0F884303BB990F88130212B10D0AF +:1021A000222B1ED0202B14D0FFF704F908BD90F885 +:1021B00081200B2AE9D1002343678367C36701208D +:1021C000F4E70B4B4367072383670023C3670120B2 +:1021D000ECE7074B4367072383670023C3670120AE +:1021E000E4E7002343678367C3670120DEE700BF9E +:1021F0003422002010B5052917D8DFE801F01716A2 +:10220000031717210446202383F31188114A012163 +:10221000FFF7E6F9104A02212046FFF7E1F90F48DF +:10222000FFF7AEF8002383F3118810BD202383F35A +:1022300011880A48FFF774F8002383F31188F4E744 +:10224000202383F311880548FFF78AF8002383F3DE +:102250001188EAE7644200088842000870250020DF +:1022600038B50B4D0B4C2A460B4904F10800FFF71B +:1022700051FF05F1CA02094904F11000FFF74AFFB6 +:1022800005F5CA72064904F11800FFF743FF38BD8F +:10229000483E00203C220020404200084C420008FA +:1022A0005842000870B504460D460846FEF768FE21 +:1022B000064600E00134237843B1F2B229462046B5 +:1022C000FEF746FE0028F5D1012000E0002070BD99 +:1022D00070B506460C46FEF753FEC5B2254930469A +:1022E000FFF7E0FF08B10535EDB223493046FFF7AF +:1022F000D9FF08B11035EDB2632D23D93146204600 +:1023000001F052FF34E01D4B07CB20606160A260FA +:1023100007360C3416E01A495A5C12091948155C44 +:10232000224602F8025B595C01F00F01095C617002 +:102330000133DBB214460B2BEDD9083602E001362F +:1023400004F8015B35788DB1252DF8D107220949B4 +:102350003046FEF7FDFD0028D5D00822064930465C +:10236000FEF7F6FD0028EAD10023E4E700232370FE +:1023700070BD00BF304300085842000838430008D1 +:1023800000E8F11F48430008BFF34F8F054B1B695E +:1023900013F0070FFAD1034BD3F8103113F0070FE6 +:1023A000F4D1704700200052034B4FF0FF325A61C6 +:1023B000C3F81421704700BF0020005208B5104B2D +:1023C0001B7803B108BDFFF7DFFF0E4BDB6813F08E +:1023D000010F05D00B4B0C4A5A6002F188325A604B +:1023E000084BD3F80C3113F0010FEBD0054B064A24 +:1023F000C3F8042102F18832C3F80421E2E700BFE8 +:10240000A64000200020005223016745002301E080 +:10241000043001338B4205D20268B2F1FF3FF7D09E +:1024200000207047012070472DE9F04105460E4617 +:1024300000F17843B3F5801F0FD2184CDFF86C80A1 +:10244000174FFFF7A1FF4FF0FF33C8F800303B688C +:1024500043F002033B6000220EE0124CDFF8508094 +:10246000114FEEE7236813F0050FFBD156F8043B3C +:1024700045F8043B0132D2B2072AF3D9BFF34F8F9C +:10248000FFF782FF4FF0FF33C8F800303B6823F0BE +:1024900002033B600120BDE8F08100BF1020005224 +:1024A0000C200052102100520C2100521420005226 +:1024B0001421005208B5144B1B781BBB134B1B692E +:1024C00013F0040F04D0114AD36843F04003D360E3 +:1024D0000E4BD3F8103113F0040F06D00B4AD2F88C +:1024E0000C3143F04003C2F80C31FFF74DFF074BAE +:1024F000DA6842F00102DA60D3F80C2142F00102FE +:10250000C3F80C2108BD00BFA640002000200052E7 +:102510002DE9F84312F01F0F35D104460D4616463B +:1025200010F01F0F01D000272EE0FFF747FF02E059 +:102530002034203E20351F2E21D920222146284636 +:1025400001F022FE0028F3D008212046FFF75EFFAD +:102550000746C8B1FFF73EFC814629462046FFF7F3 +:1025600063FF07464846FFF745FC4FB12022294646 +:10257000204601F009FE0028DAD0002700E00127FC +:10258000FFF798FF00E000273846BDE8F88300BF5A +:102590000F2803D800F58060400470470020704782 +:1025A0004FF40030704700BF102070470F2811D83B +:1025B00038B50546FFF7ECFF04462846FFF7F0FF65 +:1025C00030B12368B3F1FF3F06D104380434F7E794 +:1025D000012038BD002070470020FAE70F2801D9FC +:1025E0000020704770B50446FFF7F4FB0546FFF77F +:1025F000CBFEFFF7E3FEFFF7D7FE072C28D8224ECD +:102600004FF0FF333361FFF7BFFE230243F0240393 +:10261000F360F36843F08003F3601B4B1B6913F016 +:10262000040FFAD1FFF7B0FE2046FFF7B1FF0646D0 +:102630002046FFF7B5FF0146304600F09DF8FFF752 +:1026400039FF2846FFF7D6FB2046FFF7AFFF70BDE6 +:102650000D4E4FF0FF33C6F81031FFF795FEA4F191 +:1026600008031B0243F02403C6F80C31D6F80C31E2 +:1026700043F08003C6F80C31034BD3F8103113F04C +:10268000040FF9D1CEE700BF0020005208B5FFF7D4 +:102690003FFF08BD08B5034610B10A4A127822B1BF +:1026A00013B9084B1B7833B908BDFFF787FE054BFC +:1026B00001221A70F8E7034B00221A70FFF7FAFEA6 +:1026C000F2E700BFA640002009E000F1010C064A35 +:1026D00052F8202041F8042B1A465FFA8CF0531E62 +:1026E000DBB2002AF1D170475040005810B4114BB2 +:1026F0001B6F13F4004F06D10E4B1C6F1C671C6F31 +:1027000044F400441C670C4C236843F4807323603A +:1027100009E000F1010C51F8044B084A42F820404E +:102720001A465FFA8CF0531EDBB2002AF1D15DF835 +:10273000044B70470044025800480258504000586B +:1027400000B583B0012201A90020FFF7BDFF019869 +:1027500003B05DF804FB00BF10B582B00446FFF77C +:10276000EFFFA04201D102B010BD0194012201A9E6 +:102770000020FFF7BBFFF6E70144BFF34F8F03E0F4 +:10278000054BC3F85C0220308842F9D3BFF34F8F6A +:10279000BFF36F8F704700BF00ED00E0044B1B6874 +:1027A00023B9044BD3F8D024014B1A60704700BF03 +:1027B000A84000200040025808B5FFF7EFFF024B89 +:1027C0001868C0F3806008BDA8400020EFF30983BB +:1027D000683305494A6B22F001024A6383F3098892 +:1027E000002383F31188704700EF00E0202080F37E +:1027F000118862B60D4BD96821F4E0610904090C17 +:102800000B4A0A43DA60D3F8FC2042F08072C3F826 +:10281000FC20084A0849C2F8B01F116841F00101C4 +:1028200011601022DA7783F82200704700ED00E093 +:102830000003FA05001000E055CEACC5202383F359 +:102840001188104B5B6813F4006F03D1002383F3EE +:102850001188704710B5F1EE103AEFF30984683C27 +:102860004FF08073E361084BDB6B236684F30988C8 +:10287000FFF748FA10B1054BA36110BD044BA361EB +:10288000FBE700BF00ED00E000EF00E0F703000809 +:10289000FA03000810B4BFF34F8FBFF36F8F1C4BC8 +:1028A0000021C3F85012BFF34F8FBFF36F8F5A69E7 +:1028B00042F400325A61BFF34F8FBFF36F8FC3F8FA +:1028C0008410BFF34F8FD3F88040C4F34E3000E044 +:1028D0001846C4F3C90243F6E07303EA401343EA1F +:1028E00082730B49C1F860321346013A002BF2D1D2 +:1028F000431E0028ECD1BFF34F8F4B6943F4803364 +:102900004B61BFF34F8FBFF36F8F5DF8044B704780 +:1029100000ED00E0FEE700BF084B094903E051F875 +:10292000042B43F8042B074A9342F8D302E0002219 +:1029300043F8042B044A9342F9D370477C420020A9 +:102940002C4500087C4200207C420020704700BFDC +:10295000D0F890200023D0F894108968994232D39F +:1029600010B415E003F148014901545844F0804483 +:10297000545013E002EB43114FF0FF34C1F8084903 +:10298000C1F8084B0133D0F894108968994213D3E9 +:1029900003F14801490151580029E3DB03F15801D3 +:1029A000490151580029E5DA03F158014901545809 +:1029B00044F080445450DDE74FF00113C2F81C3856 +:1029C0005DF8044B70474FF00113C2F81C38704794 +:1029D000D0F894301B68C0F8983070470346D0F8A0 +:1029E00098000144C3F89810704700BF01E0043A12 +:1029F00004310B680360042AF9D8704710B44FF013 +:102A0000000C644601E00CF1010C944509D21CF065 +:102A1000030F00D104689C45F5D201F8014B240A4C +:102A2000F1E75DF8044B704770B5D0F89060336AF9 +:102A3000C3F30A1503F00F0403F4F013B3F5802F6A +:102A40000ED0B3F5402F0AD1023400EB8404616844 +:102A500008232A46096A06F58050FFF7CFFF70BDAC +:102A6000023400EB8404636899690A684B68D31ADE +:102A70002A46896806F58050FFF7C0FF63689A69A7 +:102A800093682B44936063689A6953682B4453603E +:102A9000E5E700BF70B506460D4629E0D6F8902060 +:102AA000D2F83438012000FA05F523EA0505C2F80A +:102AB000345870BDD6F8900000EB4513D3F81839A0 +:102AC0009BB2B4EB830F22D86B1C2246896800EBC3 +:102AD0000330FFF78BFFAB1C06EB83035A68516989 +:102AE0008A6822448A605B685A6953682344536049 +:102AF000AB1C06EB83035A68516948680B6898421F +:102B0000CCD21B1A148A9C42D4D31C46D2E7002094 +:102B1000CFE700BF70B50546D0F89060002404E010 +:102B20002146284698470134E4B2D5F894309B6892 +:102B30009C421ED8224604F158035B01F35803F46B +:102B40004023B3F5802FEED104F158035B01F35815 +:102B5000002BE8DA012303FA04F16B8923EA01036D +:102B60006B81023205EB82025368DB68002BD7D100 +:102B7000D9E770BD08B5D0F89020890141F0200157 +:102B80001161136913F0200FFBD11220FFF74CF9EC +:102B900008BD00BFF8B50746D0F89050002408E003 +:102BA00021463846984721463846FFF773FF0134DF +:102BB000E4B22146D7F894309B689C422ED8264632 +:102BC00004F148035B01EB5803F44023B3F5802F75 +:102BD000EDD104F148035B01EB58002BE7DA04F177 +:102BE00048035B01EA5842F09042EA5006F148037C +:102BF0005B01EB58002BF9DB3846FFF7BBFF0123E5 +:102C000003FA06F23B8923EA02033B81023607EB13 +:102C1000860673689B68002BC2D1C4E7F8BD00BF6D +:102C200010B5D0F890402369002BFCDA0123236112 +:102C30000C20FFF7F9F8236913F0010FFBD11220E4 +:102C4000FFF7F2F82369002BFCDA10BD08B5D0F8C5 +:102C5000902010231361136913F0100FFBD1122081 +:102C6000FFF7E2F808BD00BF10B50A4C2046FEF79A +:102C700087FC094BC4F89030084BC4F89430084CDA +:102C80002046FEF77DFC074BC4F89030064BC4F895 +:102C9000943010BDAC400020000008408043000884 +:102CA00048410020000004408C43000870B5D0F873 +:102CB00090600378012B00D070BD0446434B9842CE +:102CC00025D0434B9C4249D00025C6F8005EC02366 +:102CD00033604FF40413B3632046FFF7A1FFB560E0 +:102CE0002046FFF735FEC6F81058C6F81458C6F847 +:102CF0001C586368DB68002B65D0364BB3614FF01E +:102D0000FF337361B36843F00103B360D4E7324B20 +:102D1000D3F8D82042F00062C3F8D820D3F80021BD +:102D200042F00062C3F80021D3F80021D3F88020DC +:102D300042F00062C3F88020D3F8802022F00062C5 +:102D4000C3F88020D3F880300E21652000F01EFCEF +:102D5000224BF360224BC6F80038B2E71E4BD3F883 +:102D6000D82042F00072C3F8D820D3F8002142F0F6 +:102D70000072C3F80021D3F80021D3F8802042F07C +:102D80000072C3F88020D3F8802022F00072C3F8CC +:102D90008020D3F88020D3F8D82022F08062C3F8B6 +:102DA000D820D3F8002122F08062C3F80021D3F8A4 +:102DB00000310E214D2000F0E9FB084BF360084B79 +:102DC000C6F8003880E7074BB36198E7AC400020B5 +:102DD00048410020083C30C00044025840140040E4 +:102DE00003002002003C30C038B50546D0F89040C2 +:102DF0000021FFF7BFFE0023C4F834384FF0011262 +:102E0000C4F81C2812E003F1480252014FF000619F +:102E1000A15003F158025201A15004EB43124FF0AC +:102E2000FF31C2F80819C2F8081B0133D5F8942005 +:102E300092689A42E7D22846FFF7CAFDD5F8943047 +:102E40001B6863622846FFF701FFD4F8003823F4BB +:102E5000FE63C4F80038A2690E4B1343A361092333 +:102E6000C4F81038C4F814380B4BEB604FF0C04373 +:102E7000C4F8103B094BC4F8003B0022C4F81029E9 +:102E8000C4F8003910212846FFF7A8FD40F480104F +:102E9000A06238BD10000C005C43000840800010A8 +:102EA000D0F89020D2F8003823F4FE6390F88A100E +:102EB00043EA0113C2F80038704700BF2DE9F04122 +:102EC00005460C46D0F890608B1C00EB83035B68D2 +:102ED0001B6803F00303032B56D8DFE803F0025B03 +:102EE0005759444F06EB44130022C3F8102BA31C80 +:102EF00005EB83035B689A69002A4DD05A8A3A43EE +:102F000004F158035B01F250D6F81C3804F11001AB +:102F100001228A401343C6F81C3806EB44130022F2 +:102F2000C3F81029A31C05EB83035B685A69002AC8 +:102F300044D0198A89089B8B012B01D903FB01F12D +:102F40004FEA01482846FFF749FD48EA000004F12E +:102F50003F0306EB8303586021462846FFF70AFE2D +:102F600047EA8457A01C05EB80056B681B8A1F434A +:102F700004F148035B01F750D6F81C38012101FA2F +:102F800004F41C43C6F81C48BDE8F0811A4FA9E7B9 +:102F90001A4FA7E71A4FA5E704F158035B01F2584F +:102FA00022F40042F250D6F81C3804F1100101223C +:102FB0008A4023EA0203C6F81C38AEE704F13F0357 +:102FC00006EB83030F4A5A6021462846FFF7D2FDDD +:102FD00004F148035B01F25822F40042F250D6F8A3 +:102FE0001C38012101FA04F423EA0404C6F81C4841 +:102FF000CAE700BF008000100080081000800C109D +:10300000008004100004000210B50446FFF7E0FC45 +:103010002046FFF79DFC10BDD0F890305831490193 +:103020005B5813F4004F04D013F4001F03D10220A7 +:103030007047002070470120704700BFD0F89030E3 +:10304000483149015B5813F4004F04D013F4001FBA +:1030500003D102207047002070470120704700BF55 +:10306000023100EB810043681B6A19685B681160DC +:103070005360704710B48B1C00EB83035B689B6943 +:103080001A68DA6019B9402A01D940221A601A6810 +:1030900001F1020C00EB8C0CDCF804305B8A1A4462 +:1030A000013AB2FBF3F202FB03F3033323F0030311 +:1030B00043EAC24343F0C043D0F8902002EB4112F0 +:1030C000C2F8103BDCF804301B6803F00303012B4B +:1030D0000AD0D0F8902058314901535843F00443A6 +:1030E00053505DF8044B7047D0F89030D3F808285F +:1030F00012F4807F07D001F1580252019C5844F02D +:1031000080549C50E5E701F1580252019C5844F06C +:1031100000549C50DDE700BFF8B507460C46D0F8D8 +:10312000906006EB4113D3F8085BC3F8085B15F019 +:10313000080F0AD0D6F8143813F0080F05D08B1CEE +:1031400000EB83035B685B68984715F0010F21D0A3 +:10315000D6F8143813F0010F1CD0A31C07EB83031F +:1031600059688A6954B95368488AB3FBF0F500FB83 +:1031700015331BB91068D36898420CD3012303FAA6 +:1031800004F27B8923EA02037B81CB6813B12146D9 +:1031900038469847F8BD1B1A136000255560202358 +:1031A00083F3118821463846FFF764FF85F31188C1 +:1031B000F0E700BF10B48B1C00EB83035B685B6916 +:1031C0001A68DA6032BBD0F8903003EB41134FF449 +:1031D0000022C3F810298B1C00EB83035B681B687B +:1031E00003F00303012B2FD0D0F8904001F14803E6 +:1031F0005B01E25842F00442E250D0F89000D0F86F +:103200003438012202FA01F11943C0F834185DF88C +:10321000044B704719B9402A01D940221A601B6833 +:103220008A1C00EB82025268148A1A19013AB2FB16 +:10323000F4F2D0F8904043EAC24343F0005304EB69 +:103240004114C4F81039C6E7D0F89030D3F80828F4 +:1032500012F4807F07D001F1480252019C5844F0DB +:1032600080549C50C0E701F1480252019C5844F040 +:1032700000549C50B8E700BF2DE9F04107460C46CA +:10328000D0F8906006EB4113D3F80859C3F80859F9 +:1032900015F0010F19D0D6F8103813F0010F14D023 +:1032A0008B1C00EB830359684B691868DA689042FD +:1032B00016D3012303FA04F23B8923EA02033B817C +:1032C0008B6813B121463846984715F0800F05D01A +:1032D000D6F834280123A3401A4211D1BDE8F08169 +:1032E000121A1A604FF00008C3F80480202383F3F9 +:1032F000118821463846FFF75DFF88F31188E4E71F +:1033000021463846FFF7C6FBE8E700BF70B5064622 +:10331000D0F890506C69AB691C406C6114F4805F0C +:103320006BD1002C6CDB14F4006F7ED114F4005FC1 +:103330000AD0D5F8083813F0060F7DD1EB6823F4D6 +:10334000705343F41053EB6014F0080F04D073680B +:10335000DB680BB13046984714F4801F73D114F426 +:10336000001F74D114F0100F75D1D5F8185814F44B +:10337000002F1BD015F4803F71D115F4003F73D19D +:1033800015F4802F75D115F4002F77D115F4801F17 +:1033900079D115F4001F7BD115F4800F7DD115F480 +:1033A000000F7FD115F0807F40F0818014F4802FD2 +:1033B00022D015F0010F7FD115F0020F40F081806F +:1033C00015F0040F40F0828015F0080F40F0838064 +:1033D00015F0100F40F0848015F0200F40F085802C +:1033E00015F0400F40F0868015F0800F40F0878088 +:1033F00015F4807F40F0888070BDFEF799FAFBE7F6 +:10340000D5F8003E13F0030F05D0D5F8003E23F0A9 +:103410000303C5F8003ED5F8043823F00103C5F8CE +:1034200004383046FEF7B8FA7DE73046FFF790FAE9 +:103430003046FEF7A1FA79E7EB6823F4705343F4C2 +:10344000A053EB6080E73046FFF7A4FB87E73046E8 +:10345000FFF760FB86E73046FFF7E6FA85E70021D5 +:103460003046FFF759FE88E701213046FFF754FE4A +:1034700086E702213046FFF74FFE84E703213046FE +:10348000FFF74AFE82E704213046FFF745FE80E75A +:1034900005213046FFF740FE7EE706213046FFF764 +:1034A0003BFE7CE707213046FFF736FE7AE708212E +:1034B0003046FFF731FE79E700213046FFF7DCFEAA +:1034C0007AE701213046FFF7D7FE79E7022130463F +:1034D000FFF7D2FE78E703213046FFF7CDFE77E70E +:1034E00004213046FFF7C8FE76E705213046FFF796 +:1034F000C3FE75E706213046FFF7BEFE74E70721DD +:103500003046FFF7B9FE73E708213046FFF7B4FEF7 +:1035100072E700BF08B50348FFF7F8FEFFF78EF922 +:1035200008BD00BFAC40002008B50348FFF7EEFE21 +:10353000FFF784F908BD00BF48410020D0F8902073 +:1035400058314901535843F400135350704700BF9A +:10355000D0F8902048314901535843F40013535098 +:10356000704700BFD0F8902058314901535823F4D8 +:1035700000135350704700BFD0F8902048314901E4 +:10358000535823F400135350704700BF0901C9B2C8 +:10359000074A131883F8001300F01F0140090123A4 +:1035A0008B4000F1600142F8213042F82030704732 +:1035B00000E100E030B4029C006040600172002134 +:1035C000C16042610261043304FB03258561C3616C +:1035D000046242628162C162039B0363049B436392 +:1035E00030BC704708B50022C260416A4161016188 +:1035F0008262C2626FF00101FEF790FC08BD00BF5D +:1036000003694269934203D0002232B9181D704702 +:10361000C268002AF9D00122F7E70020704700BFF6 +:1036200008B503691960C3680133C360C2690369DF +:10363000134403618269934201D3436A0361002109 +:10364000FEF760FC08BD00BF38B504460D46E368D0 +:1036500043B9237A73B929462046FEF741FC002876 +:10366000F5DA06E06269131DA36212681344E3628F +:10367000002038BD6FF00100FBE700BF08B5C3684C +:10368000013BC360C2694369134443618269934249 +:1036900001D3436A436100238362036B03B19847FC +:1036A00008BD00BF38B50446202383F31188836A20 +:1036B0005BB1A36A13F8015BA362E26A93420DD285 +:1036C000002383F31188284638BDFFF7BDFF054668 +:1036D0000028EED0002383F31188F4E72046FFF79B +:1036E000CDFFEDE72DE9F84304460F469046994695 +:1036F000202383F31188002631E049462046FFF756 +:10370000A3FF78B3002383F311883046BDE8F88324 +:10371000DCF80050DCF80400DCF80820DCF80C30A1 +:10372000CEF80050CEF80400CEF80820CEF80C30C9 +:103730000CF1100C0EF1100E8C45E9D14037A36A44 +:103740004033A3624036A26AE36A9A4222D200233F +:1037500083F311884645D8D2202383F31188A36AC6 +:10376000002BCAD0E36AA16A5B1AA8EB06059D424A +:1037700000D31D46402D03D98C46BE464031C7E7D5 +:103780002A463846FDF7DAFB2F44A36A2B44A3628E +:103790002E44D8E72046FFF771FFD8E710B4019C0C +:1037A000006040600172C46042610261043304FB46 +:1037B00003218161C3610462426200238362C362A8 +:1037C000029B0363039B43635DF8044B704700BF98 +:1037D00008B5026AC260426A4261026100228262E6 +:1037E000C2626FF00101FEF799FB08BD02694369EF +:1037F0009A4206D000224AB91B680B604069043027 +:103800007047C268002AF6D00122F4E70020704712 +:1038100008B5C3680133C360C26943691344436197 +:103820008269934201D3436A43610021FEF76AFB38 +:1038300008BD00BF38B504460D46E36843B9237A96 +:1038400073B929462046FEF74BFB0028F5DA06E05F +:1038500023691A1DA262E2691344E362002038BDA5 +:103860006FF00100FBE700BF08B503691960C3688A +:10387000013BC360C26903691344036182699342D7 +:1038800001D3436A036100238362036B03B198474A +:1038900008BD00BF38B504460D46202383F31188C8 +:1038A000836A5BB1A36A1D70A36A0133A362E26AF3 +:1038B00093420CD2002080F3118838BD1146FFF7E7 +:1038C000B9FF0028EED0002383F31188F5E7E16902 +:1038D00004392046FFF7C8FFECE700BF2DE9F843A5 +:1038E00004460E4617469846202383F31188002588 +:1038F0002DE041462046FFF79DFF58B3002383F398 +:1039000011882846BDE8F883DCF800E0DCF80410F4 +:10391000DCF80820DCF80C30C0F800E04160826080 +:10392000C3600CF1100C1030CC45EDD14036A36AC9 +:103930004033A3624035A26AE36A9A4223D200234D +:1039400083F31188BD42DCD2202383F31188A36A5C +:10395000002BCED0E36AA06A1B1AA7EB0509994594 +:1039600000D39946B9F1400F03D9B44606F1400996 +:10397000CAE74A463146FDF7E1FA4E44A36A4B4492 +:10398000A3624D44D7E7E16904392046FFF76CFF95 +:10399000D5E700BF034601694269914209D0002280 +:1039A00010462AB19A6ACAB1521A043A06D10020C6 +:1039B0007047C268002AF3D00122F1E70A60DA6892 +:1039C000013ADA60D9691A690A441A6199698A4226 +:1039D00001D35A6A1A6100229A6270470020704728 +:1039E00008B500F0E9F808BD034B586300221A61DE +:1039F0000222DA60704700BF000C0040014B002239 +:103A0000DA607047000C0040014B5863704700BFFC +:103A1000000C0040014B586A704700BF000C00408A +:103A20004B6843608B688360CB68C3600B694361FC +:103A30004B6903628B6943620B680360704700BF88 +:103A400010B52A4BD3F8882040F2FF710A43C3F81F +:103A50008820D3F88800264A0240C3F88820D3F88B +:103A60008820D3F8E0200A43C3F8E020D3F80821E7 +:103A70000A43C3F80821D3F808311E4C21461E48DA +:103A8000FFF7CEFF04F11C011C48FFF7C9FF04F14A +:103A900038011B48FFF7C4FF04F154011948FFF730 +:103AA000BFFF04F170011848FFF7BAFF04F18C0161 +:103AB0001648FFF7B5FF04F1A8011548FFF7B0FF5E +:103AC00004F1C4011348FFF7ABFF04F1E001124811 +:103AD000FFF7A6FF04F1FC011048FFF7A1FF04F572 +:103AE0008C710F48FFF79CFF10BD00BF00440258C7 +:103AF00000F8FFFF98430008000002580004025835 +:103B000000080258000C0258001002580014025815 +:103B100000180258001C02580020025800240258C5 +:103B20000028025808B5FFF78BFF00F0FDF80C4B9A +:103B3000D3F8902242F00102C3F89022D3F89422E5 +:103B400042F00102C3F894220522C3F898204FF0F6 +:103B50006052C3F89C20034AC3F8A02008BD00BFF0 +:103B600000ED00E01F00080308B500F0EFFAFEF7D3 +:103B70000DF90E4BD3F8DC2042F04002C3F8DC20F4 +:103B8000D3F8042122F04002C3F80421D3F8043111 +:103B9000074B1A6842F008021A601A6842F00402E1 +:103BA0001A60FEF7FBFDFEF75BFB08BD0044025800 +:103BB00000180248704700BF114BD3F8E82042F0CC +:103BC0000802C3F8E820D3F8102142F00802C3F835 +:103BD0001021D3F810310B4AD36B43F00803D363A1 +:103BE000094BC7229A624FF0FF32DA6200229A61D3 +:103BF0005A63DA605A6001225A611A60704700BF46 +:103C0000004402580010005C000C004008B50A4A4D +:103C10001369D168C9B20B40D943116113F0020F87 +:103C200000D108BD202383F31188FEF7CFF80023CD +:103C300083F31188F5E700BF000C004010B5384B46 +:103C4000D3F880204FF0FF31C3F88010D3F88020E4 +:103C50000022C3F88020D3F88000D3F88400C3F892 +:103C60008410D3F88400C3F88420D3F88400D86F7C +:103C700040F0FF4040F4FF0040F43F5040F03F0070 +:103C8000D867D86F20F0FF4020F4FF0020F43F50A9 +:103C900020F03F00D867D86FD3F8884021482043F0 +:103CA000C3F88800D3F88800C0F30A00C3F888007E +:103CB000D3F88800D3F89000C3F89010D3F89000A0 +:103CC000C3F89020D3F89000D3F89400C3F8941070 +:103CD000D3F89400C3F89420D3F89400D3F8980054 +:103CE000C3F89810D3F89800C3F89820D3F8980038 +:103CF000D3F88C00C3F88C10D3F88C00C3F88C2058 +:103D0000D3F88C00D3F89C00C3F89C10D3F89C1017 +:103D1000C3F89C20D3F89C3000F0F2F910BD00BF2E +:103D20000044025800F8FFFF6B4B0122C3F8082142 +:103D30006A4BD3F8F42042F00202C3F8F420D3F81F +:103D40001C2142F00202C3F81C21D3F81C31644B41 +:103D50000222DA60624B5B6813F4005FFAD0604BBA +:103D6000604A1A6001229A605F4ADA6000221A6192 +:103D70004FF440429A615A4B9B6913F4005FFAD0AA +:103D8000574A136843F480731360544B1B6F13F44A +:103D9000407F05D0514B4FF480321A6700221A67DA +:103DA0004E4A136843F0010313604C4B1B6813F039 +:103DB000040FFAD0494B00221A61484B1B6913F0DB +:103DC000380FFAD1454B01221A604FF080425A60F9 +:103DD00000225A67454ADA62454A1A611A6842F473 +:103DE00080321A603D4B1B6813F4003FFAD03B4A07 +:103DF000136843F480531360384B1B6813F4005F5F +:103E0000FAD0364B3B4A9A6200225A633A49196308 +:103E1000DA633A4999635A64394A1A64394ADA6268 +:103E20001A6842F0A8521A602C4B1B6803F0285302 +:103E3000B3F1285FF8D1294B48229A614FF4886288 +:103E4000DA6140221A62304ADA644FF080521A6511 +:103E50002E4A5A652E4A9A652E4B32221A602D4BF5 +:103E60001B6803F00F03022BF9D11C4A136943F0BE +:103E700003031361194B1B6903F03803182BF9D1A5 +:103E8000164BD3F8DC2042F00052C3F8DC20D3F804 +:103E9000042142F00052C3F80421D3F80421D3F8DE +:103EA000DC2042F08042C3F8DC20D3F8042142F049 +:103EB0008042C3F80421D3F80421D3F8DC2042F077 +:103EC0000042C3F8DC20D3F8042142F00042C3F8DA +:103ED0000421D3F804317047008000510044025897 +:103EE0000048025800C000F0020000010000FF017D +:103EF0000088900812102000630209012C020400BF +:103F000047040508FD0BFF01200000200010E00021 +:103F1000000101000020005208B54FF0B042D2F875 +:103F2000883003F00103C2F888302BB1044B1B68C2 +:103F300013B1034A50689847FEF780FC08BD00BFE4 +:103F4000FC41002008B54FF0B042D2F8883003F0B1 +:103F50000203C2F888302BB1044B9B6813B1034AAB +:103F6000D0689847FEF76AFC08BD00BFFC410020FE +:103F700008B54FF0B042D2F8883003F00403C2F81D +:103F800088302BB1044B1B6913B1034A5069984721 +:103F9000FEF754FC08BD00BFFC41002008B54FF0FF +:103FA000B042D2F8883003F00803C2F888302BB151 +:103FB000044B9B6913B1034AD0699847FEF73EFC56 +:103FC00008BD00BFFC41002008B54FF0B042D2F858 +:103FD000883003F01003C2F888302BB1044B1B6A01 +:103FE00013B1034A506A9847FEF728FC08BD00BF8A +:103FF000FC41002010B54FF0B043D3F8884004F4E2 +:104000007872C3F8882014F0200F05D0164B9B6AF5 +:1040100013B1154AD06A984714F0400F05D0124BDF +:104020001B6B13B1104A506B984714F0800F05D0EA +:104030000D4B9B6B13B10C4AD06B984714F4807FE7 +:1040400005D0094B1B6C13B1074A506C984714F408 +:10405000007F05D0044B9B6C13B1034AD06C98478A +:10406000FEF7ECFB10BD00BFFC41002010B54FF087 +:10407000B043D3F8884004F47C42C3F8882014F499 +:10408000806F05D01A4B1B6D13B1194A506D9847BC +:1040900014F4006F05D0164B9B6D13B1144AD06D0C +:1040A000984714F4805F05D0114B1B6E13B1104A72 +:1040B000506E984714F4005F05D00D4B9B6E13B102 +:1040C0000B4AD06E984714F4804F05D0084B1B6FF5 +:1040D00013B1074A506F984714F4004F05D0044BB2 +:1040E0009B6F13B1024AD06F9847FEF7A7FB10BD34 +:1040F000FC41002008B5FFF789FDFEF79FFB08BDD6 +:1041000008B506210846FFF741FA06210720FFF708 +:104110003DFA06210820FFF739FA06210920FFF7AA +:1041200035FA06210A20FFF731FA06211720FFF79A +:104130002DFA06212820FFF729FA09217A20FFF716 +:1041400025FA07213220FFF721FA08BD08B5FFF74D +:1041500075FD00F009F8FDF70FFAFDF795F8FFF788 +:1041600029FDFFF73DFC08BD002307E0054A0021BB +:1041700042F8331002EBC302516001330F2BF5D923 +:10418000704700BFFC41002010B501390244904245 +:1041900001D1002005E0037811F8014FA34201D0BE +:1041A000181B10BD0130F2E7034611F8012B03F88C +:1041B000012B002AF9D1704753544D333248373F11 +:1041C0003F3F000053544D3332483734332F373597 +:1041D0003300000001105A0003105900012058005C +:1041E00003205600000000004112000825120008BC +:1041F000791200085D1200086D12000851120008C3 +:1042000035120008191200086511000800000000AE +:1042100001000000000000006D61696E00000000F8 +:1042200069646C650000000020420008F82300204B +:104230007025002001000000891D0008000000001A +:104240004172647550696C6F7400000025424F41E3 +:104250005244252D424C00002553455249414C25DE +:1042600000000000020000000000000065140008CB +:10427000F114000840004000183E0020283E0020B5 +:104280000200000000000000030000000000000029 +:10429000451500080000000010000000383E002016 +:1042A000000000000100000000000000AC40002001 +:1042B00001010200F5210008E12000087D2100082D +:1042C0006121000843000000CC42000809024300BD +:1042D000020100C0320904000001020201000524AD +:1042E0000010010524010001042402020524060037 +:1042F00001070582030800FF09040100020A00000B +:10430000000705010240000007058102400000008F +:1043100012000000184300081201100102000040C2 +:1043200009124157000201020301000004030904BD +:1043300025424F4152442500536B79737461727367 +:1043400048374844000000003031323334353637C6 +:104350003839414243444546000000000000000057 +:10436000AD190008AD1A00085D1B000840004000B0 +:10437000E4410020E441002001000000F44100205D +:104380008000000040010000080000000001000063 +:1043900000040000080000000000806A0000000027 +:1043A000AAAAAAAA00000064FFFF00000000000003 +:1043B00000A00A004000000100000000AAAAAAAA6A +:1043C00000000001F7FF00000000000000000000F6 +:1043D0001004004000000000AAAAAAAA00000040A1 +:1043E000FFFF0000000000000000000010000000BF +:1043F00000000000AAAAAAAA00000000FBFF00001B +:10440000000000000000000040014000000000002B +:10441000AAAAAAAA00004000FFFF000000000000B6 +:10442000000000000000000000000000AAAAAAAAE4 +:1044300000000000FFFF000000000000000000007E +:104440000000000000000000AAAAAAAA00000000C4 +:10445000FFFF00000000000000000000000000005E +:1044600000000000AAAAAAAA00000000FFFF0000A6 +:10447000000000000000000000000000000000003C +:10448000AAAAAAAA00000000FFFF00000000000086 +:10449000000000000000000000000000AAAAAAAA74 +:1044A00000000000FFFF000000000000000000000E +:1044B0000000000000000000AAAAAAAA0000000054 +:1044C000FFFF0000000000000000000000000000EE +:1044D000330400000000000000001A00000000008B +:1044E000FF00000000000000B84100083F0000008D +:1044F00050040000C44100083F0000000096000086 +:104500000000080000960000000008000400000001 +:104510002C43000800000000000000000000000024 +:0C4520000000000000000000000000008F +:00000001FF diff --git a/Tools/bootloaders/ZubaxGNSS_bl.bin b/Tools/bootloaders/ZubaxGNSS_bl.bin index 053fcc5431a..d391822244c 100755 Binary files a/Tools/bootloaders/ZubaxGNSS_bl.bin and b/Tools/bootloaders/ZubaxGNSS_bl.bin differ diff --git a/Tools/bootloaders/ZubaxGNSS_bl.elf b/Tools/bootloaders/ZubaxGNSS_bl.elf index 67c2cec687d..9cdd2287d2a 100755 Binary files a/Tools/bootloaders/ZubaxGNSS_bl.elf and b/Tools/bootloaders/ZubaxGNSS_bl.elf differ diff --git a/Tools/bootloaders/ZubaxGNSS_bl.hex b/Tools/bootloaders/ZubaxGNSS_bl.hex index 3339e3f928b..7f9eb818e3b 100644 --- a/Tools/bootloaders/ZubaxGNSS_bl.hex +++ b/Tools/bootloaders/ZubaxGNSS_bl.hex @@ -1,1053 +1,1057 @@ :020000040800F2 -:1000000000020020A1040008B1130008B513000885 -:10001000F1130008B5130008D1130008A304000869 -:10002000A3040008A3040008A3040008213000086A -:10003000A3040008A3040008A304000895350008E1 -:10004000A3040008A3040008A3040008A3040008F4 -:10005000A3040008A304000899320008C532000870 -:10006000F13200081D33000849330008A3040008DA -:10007000A3040008A3040008A3040008A3040008C4 -:10008000A3040008A3040008A30400080525000831 -:1000900071250008C52500081926000875330008D9 -:1000A000A3040008A3040008A3040008A304000894 -:1000B000A3040008A3040008A3040008A304000884 -:1000C000A3040008A3040008A3040008A304000874 -:1000D000A3040008A3040008093700081D3700081E -:1000E000DD330008A3040008A3040008A3040008EB -:1000F000A3040008A3040008A3040008A304000844 -:10010000A3040008A3040008A3040008A304000833 -:10011000A3040008A3040008A3040008A304000823 -:10012000A3040008A3040008A3040008A304000813 -:10013000A3040008A3040008A3040008A304000803 -:10014000A3040008A3040008A3040008A3040008F3 -:10015000A3040008A3040008A3040008A3040008E3 -:10016000D0400B1CD1409C46203AD3401843524209 -:1001700063469340184370479140031C90409C464F -:10018000203A9340194352426346D3401943704783 -:1001900053B94AB9002908BF00281CBF4FF0FF31EE -:1001A0004FF0FF3000F07AB9ADF1080C6DE904CEE4 -:1001B00000F006F8DDF804E0DDE9022304B0704742 -:1001C0002DE9F0478C460E460446089D002B50D181 -:1001D0008A4217466CD9B2FA82FEBEF1000F0BD0EC -:1001E000CEF1200C01FA0EF620FA0CFC02FA0EF702 -:1001F0004CEA060C00FA0EF43A0CBCFBF2F9BBB266 -:1002000002FB19CC09FB03FA4FEA144848EA0C46F2 -:10021000B2450AD9F61909F1FF3180F02581B245BE -:1002200040F22281A9F102093E44A6EB0A06B6FB80 -:10023000F2F002FB106600FB03F3A4B244EA0644AA -:10024000A34209D9E41900F1FF3280F00B81A342E7 -:1002500040F2088102383C440021E41A40EA094097 -:10026000002D62D0002324FA0EF42C606B60BDE8F0 -:10027000F0878B4207D9002D55D0002185E8410039 -:100280000846BDE8F087B3FA83F1002940F08F807B -:10029000B34202D3824200F2FC80841A66EB03066A -:1002A0000120B446002D40D085E81010BDE8F0874D -:1002B00012B90127B7FBF2F7B7FA87FEBEF1000FBC -:1002C00035D10121F61B4FEA174C1FFA87F8B6FB10 -:1002D000FCF20CFB126608FB02F0230C43EA064614 -:1002E000B04207D9F61902F1FF3302D2B04200F250 -:1002F000D2801A46361AB6FBFCF00CFB106608FBDF -:1003000000F8A3B243EA0644A04507D9E41900F176 -:10031000FF3302D2A04500F2B9801846A4EB0804CE -:1003200040EA02409CE729462846BDE8F08707FAE4 -:100330000EF7CEF1200326FA03F24FEA174CB2FB78 -:10034000FCF11FFA87F80CFB112206FA0EF620FAD0 -:1003500003F301FB08F933431E0C46EA0246B1459C -:1003600000FA0EF409D9F61901F1FF3280F08C8001 -:10037000B14540F2898002393E44A6EB0906B6FB3E -:10038000FCF00CFB106200FB08F99EB246EA024644 -:10039000B14507D9F61900F1FF3371D2B1456FD9D4 -:1003A00002383E44A6EB090640EA01418FE7C1F15D -:1003B000200722FA07F88B4048EA030326FA07F4DD -:1003C0004FEA134EB4FBFEF91FFA83FC0EFB1944EF -:1003D0008E4020FA07F809FB0CFA48EA06084FEAB3 -:1003E000184646EA0444A24502FA01F200FA01F670 -:1003F00008D9E41809F1FF3044D2A24542D9A9F145 -:1004000002091C44A4EB0A04B4FBFEF00EFB1044EA -:1004100000FB0CFC1FFA88F848EA0444A44507D9FD -:10042000E41800F1FF3E29D2A44527D902381C4424 -:1004300040EA0940A0FB0289A4EB0C0CCC45C24663 -:10044000CE4615D312D055B1B6EB0A036CEB0E06AF -:1004500006FA07F7CB401F43CE402F606E600021A5 -:10046000BDE8F0871046F7E68946DEE64645EAD263 -:10047000B8EB020A69EB030E0138E4E77046D7E7F0 -:1004800018468FE78146BDE7114676E702383C44BF -:1004900044E7084606E7023A3E442BE7704700BFB0 -:1004A00002E000F000F8FEE772B6274880F3088803 -:1004B000264880F3098826484EF60851CEF20001FE -:1004C0000860022080F31488BFF36F8F02F0D8FD1C -:1004D00002F070FE4FF055301E491B4A91423CBF5E -:1004E00041F8040BFAE71C49184A91423CBF41F815 -:1004F000040BFAE719491A4A1A4B9A423EBF51F8BF -:10050000040B42F8040BF8E700201749174A914200 -:100510003CBF41F8040BFAE702F0B6FD02F04CFED6 -:10052000134C144DAC4203DA54F8041B8847F9E726 -:1005300000F03AF8104C114DAC4203DA54F8041BA9 -:100540008847F9E702F09EBD000200200008002065 -:1005500000000008000100200002002038410008CF -:10056000000800207808002078080020542400208B -:1005700060010008600100086001000860010008D7 -:100580002DE9F04FC1F80CD0C3689D46BDE8F08F4F -:10059000002383F311882846A047002002F036FB91 -:1005A00002F0DCFA00DFFEE76FF01202F8B53E4B16 -:1005B00000241A70032270215A709A723B4A5972B1 -:1005C0009C70DC701C715C719C71DC711C72DC7243 -:1005D000536823F0E06343F0905343F48043536047 -:1005E00002F0C8FC074602F015FD0646A0BB304BE2 -:1005F0009F4233D001339F4233D02E4B27F0FF026E -:100600009A4231D1F8B200F059FA354642F21074EC -:1006100000F08AFC00F058FA88B34CBB2EB1264B90 -:100620009F4202D002F0EEFC0025002002F0ACFC5C -:1006300015B1002500F042F800F098FC00F032FE01 -:1006400000F0E4FE044605B300F0E0FE001BA84203 -:100650001BD900F033F8F3E70546D9E70546044611 -:10066000D6E704460125D3E7054641F28834CFE7B3 -:10067000AEB9002002F088FC4FF47A75DAE756B97B -:10068000002002F081FC0025D6E700F0C5FC012027 -:1006900002F0C2FAD7E7084B9F42C3D1F0E7064BFE -:1006A0009F42BFD1E5E700BF78080020000001406D -:1006B000010007B0000008B0263A09B010B51C4B85 -:1006C0001C4953F8042F013200D110BD8B42F8D1E0 -:1006D000194C1A4B22689A4228D9194B9B6803F18E -:1006E000006303F508439A4220D202F05FFC02F057 -:1006F00071FC002000F0FCFD0220124B187000F08D -:100700002BFE114BDA690022DA61D96999699A6185 -:100710009B6972B60D4B0E4A202113601B6822683C -:1007200081F311889D4683F30888104710BD00BFF0 -:10073000FC8700081C88000804880008FF87000860 -:10074000780800208408002000100240008800087B -:1007500008ED00E049F2690008490B689AB21B0CE9 -:1007600000FB02330B6044F25061054A136898B2F3 -:100770001B0C01FB0030106080B270471008002095 -:100780000C08002010B504460021102200F000FEE5 -:10079000034B03CB206061601868A06010BD00BFF0 -:1007A000E8F7FF1FF0B5BBB000F030FE1D4CA368AA -:1007B000C31AF92B30D906AD2346A06028220021A8 -:1007C000284601F0B1FB04F10E0000F0D9FD002332 -:1007D000C6B2591D5F1CDBB2B3424FEAC10107DA52 -:1007E0000E3323440822284601F09EFB3B46F0E7E7 -:1007F00001230393082302930B4B207B01933023A7 -:10080000C1F3CF0105910093014604A3D3E900236E -:100810000495064801F058F93BB0F0BD78F6339FD7 -:1008200093CACD8DC8180020D5180020A01800202C -:1008300070B50D4614461E4601F0ECF850B9022E74 -:100840000ED1012C0CD112A3D3E90023C5E900235A -:10085000012070BD052C14D003D8012C09D0002034 -:1008600070BD282C09D0302CF9D10BA3D3E900237B -:10087000ECE70BA3D3E90023E8E70BA3D3E90023BC -:10088000E4E70BA3D3E90023E0E700BFAFF3008068 -:10089000401DA12026812A0B78F6339F93CACD8D67 -:1008A0009E6AC421818A46EE26417272DF25D7B73F -:1008B000F017304A39059E5638B50D4604460346B2 -:1008C00020222846002101F02FFB22792346032A0B -:1008D00028BF0322284603F8042F2021022201F01A -:1008E00023FB62792346072A28BF0722284603F8FC -:1008F000052F2221032201F017FBA2792346072AA4 -:1009000028BF0722284603F8062F2521032201F0DD -:100910000BFB284604F108031022282101F004FBF8 -:10092000382038BD2DE9F04FADF5037D23AE10AD75 -:1009300040F2791280460F463046002100F028FD33 -:1009400048220021284600F023FD00F05FFD4FF40F -:100950007A72B0FBF2F0574B0DF16209186093E820 -:10096000070001232B74002385E807000DF16200C6 -:100970006B74FFF707FF032385F82030ED2385F81C -:10098000213007AB18464C4903F09CF8212228641B -:100990003146284685F83C20FFF78EFF14AB04460D -:1009A00001460822304601F0BFFA08220DF151033A -:1009B000A118304601F0B8FA0DF15203082204F1F3 -:1009C0001001304601F0B0FA15AB202204F11801F5 -:1009D000304601F0A9FA16AB402204F13801304646 -:1009E00001F0A2FA18AB082204F17801304601F0B8 -:1009F0009BFA0DF16103082204F18001304601F0F9 -:100A000093FA04F1880A04F5847B4B465146082288 -:100A100030460AF1080A01F087FAD34509F10109C5 -:100A2000F3D11DAB08225946304601F07DFA4FF054 -:100A3000000904F5887495F834304B4510D84FF010 -:100A4000000995F83C304B4515D92B6C21464B4499 -:100A50000822304601F068FA083409F10109F0E78C -:100A6000AB6B21464B440822304601F05DFA083456 -:100A700009F10109DFE7E31DC3F3CF03F97E059315 -:100A8000002304960393BB7E193702930123019739 -:100A90000093404605A3D3E9002301F015F80DF5B6 -:100AA000037DBDE8F08F00BFAFF300809E6AC421D4 -:100AB000818A46EE880800207C3C0008014B1870B3 -:100AC000704700BF94080020F0B52E4B85B01C7B0A -:100AD0002CB10E222C4B1A81002005B0F0BD2B4A00 -:100AE00002AB1068516803C3082329490DEB0302C8 -:100AF000284802F0C9FF054630B90A22224B264891 -:100B00001A8100F04DFCE7E70369B3F55E3F07D9B2 -:100B10000B211D4A21481181194600F041FCDBE7F9 -:100B200040F2ED32418B914206D00C20164B1881D9 -:100B30001B4800F035FCCFE71A4A103B0244154928 -:100B400020469E1A00F066FC0746324605F1180161 -:100B5000204600F05FFCAB689F4202D1EB689842F0 -:100B60000AD00D22084B1A8100903B46EA68A9681A -:100B70000D4800F015FCAFE70C4800F011FC012017 -:100B8000ABE700BFC8180020880800206C3B0008B5 -:100B9000DC77030000880008743B0008803B0008F5 -:100BA000923B00080878FFF7B03B0008D93B0008EB -:100BB0002DE9F04FAFB006AF80460D4600F02AFF9A -:100BC000044600286CD12B7E022B18D1EB8A012B16 -:100BD00015D100F01BFC8146FFF7BCFD4FF4C87334 -:100BE000B0FBF3F202FB1300BD4E80B209F516799B -:100BF000EB7E4844306093B90022BA4B1A70A43798 -:100C0000BD46BDE8F08F07F10C031C44009400239F -:100C100008224FEAC901284600F0EAFF4C46AB8A99 -:100C20005FFA84F9013BA3420BD904F10109B9F140 -:100C3000110FE8D140F23911AB4BAC4AAC4802F08D -:100C4000F5FE07F11C00FFF79DFD224607F11C0190 -:100C500007F10C0002F008FF03460028CCD1B9F1DF -:100C6000100F07D09F4B83F800903368A3F51673DD -:100C70003360C4E707F1A00202F8950D0146009227 -:100C80002846072200F0B4FFF97A7F2904DD994B4A -:100C9000964A4FF4A871D1E7404600F09FFEAEE7B8 -:100CA000EB8A052B00F02E8106D8012BA7D129460F -:100CB0004046FFF737FEA2E7282B3DD0302B9ED1D0 -:100CC0006B7E8D4C0133627BDBB29342EA4640F08F -:100CD0000081EA7E237B9A4240F0FB80002607F1E8 -:100CE000A00323F8846D0093102201233146284687 -:100CF00000F07EFFB5F81480A8F102081FFA88F80A -:100D000008F1030323F003030A3323F00703ADEBD9 -:100D1000030D0DF1180933469BB2B11C98454FEAFB -:100D2000C10106F101066DDD4B440093082200234A -:100D3000284600F05DFFEEE7AB8A013B9BB2C92B72 -:100D40003FF65DAF6C4E347B4CBB06F10C03009359 -:100D5000082223462146284600F04AFFAB8A04F1C8 -:100D60000109013BE4B29C424FEAC90109DA0E34A1 -:100D70003444009400230822284600F039FF4C46F2 -:100D8000ECE700230022C6E900230023B36086F8C5 -:100D9000D730C6F8D830337B0BB9EB7E33730024E1 -:100DA00007F11C0607F10C03082221463046FC60BF -:100DB0003C617C6101F0B8F83B7C04F10109A3427D -:100DC0004FEAC90107D97B6908222344304601F064 -:100DD000ABF84C46F0E70023C1F3CF01E87E059164 -:100DE00004960393AB7E19350293282301460093A2 -:100DF000019539A3D3E90023404600F065FEFFF7D3 -:100E0000D1FCFCE694F8D70000F084FAD4F8D8308E -:100E100006461BB994F8D70000F08CFAD4F8D83005 -:100E200043449E4204D294F8D700013000F082FA85 -:100E30000025324B4FEA980BAAB25A45104616DAF3 -:100E40005AB994F8D72042B9D4E900120A4304D120 -:100E5000D9F800201A600135EEE7226859F8201011 -:100E600002EB80007B6000F045FA7B68F3E7D4E991 -:100E70000023D4F8D85012EB080043F10001C4E974 -:100E80000001454494F8D700C4F8D85000F042FA65 -:100E9000854209D394F8D730013384F8D730D4F899 -:100EA000D8309E1BC4F8D860B8F1FF0F0ADC0020D0 -:100EB000124B2073196800F01DFAFFF705FE08B108 -:100EC000FFF7FCFB23680E4A9B0A013313810023C2 -:100ED000A360D54693E600BF26417272DF25D7B7DF -:100EE0009C18002099180020E83B0008A03C00084E -:100EF000413C0008633C0008C8180020000800209E -:100F000088080020BFF34F8F0549064BCA6802F4DA -:100F1000E0621343CB60BFF34F8F00BFFDE700BF1C -:100F200000ED00E00400FA0508B54FF000530B4A4D -:100F3000196891420AD1597D094A0A4811701B7DEE -:100F4000C922037308490E3000F010FABDE80840CA -:100F5000E02200214FF0005000F01ABA9AAD44C5CB -:100F600094080020C818002016000020022330B585 -:100F70001F4C85B0637104230025ADF808300123B0 -:100F80000722ADF80C501B498DF80C308DF80B3052 -:100F9000194B1A484B608DF80A2001F0E5FC184BFC -:100FA000019500931749184B4FF48052174800F0F1 -:100FB000DFFC174B2546197811B1144800F00EFDDF -:100FC00000F024FA0446FFF7C5FB4FF4C873B0FBEA -:100FD000F3F202FB130304F516749BB21C440D4B91 -:100FE0001C6002F017F808B10F232B8105B030BD4B -:100FF000880800200408002003000600B81900201B -:101000003108000898080020B10B0008A018002043 -:10101000940800209C1800202DE9F04F96A7D7E9EE -:1010200000670FF25C29D9E900898F4C93B0DFF893 -:1010300058B2DFF858A2204600F092FD0CAD0790A0 -:1010400098B310220021284600F0A2F94FF00002C8 -:10105000079B197B61F3030219468DF8302051F884 -:10106000040F0EAA496803C21B680D9A584663F321 -:101070001C029DF830300D9243F020038DF8303083 -:1010800000232A46194601F07FFC079030B920461C -:1010900000F06AFD079B8AF80030CCE79AF8003030 -:1010A000072B40DC01338AF8003018220021284643 -:1010B00000F06EF9DFF8D0B1DFF8D4A100232A46A2 -:1010C0001946584601F088FC014680BB102208A84A -:1010D00000F05EF9DAF80C3083F00803CAF80C303F -:1010E00000F096F90DF1240E0B4612A9024611E903 -:1010F00003008EE803009DF83410C1F30300890655 -:1011000049BF0E99BDF83810C1F31C0141F00041F0 -:1011100058BFC1F30A018DF82C000891204608A998 -:1011200000F068FFCAE7204600F01EFDBDE720463C -:1011300000F070FC824600284AD100F067F9DFF821 -:1011400054B1DBF80030984242D300F05FF90790C9 -:10115000FFF700FB4FF4C873B0FBF3F101FB130082 -:10116000079A80B202F516721044CBF80000DFF83F -:1011700028B18DF820A09BF8001011B901238DF83B -:10118000203028460791FFF7FDFA07990DF121005D -:10119000C1F1100A5FFA8AFABAF1060F28BF4FF0C0 -:1011A000060A2944524600F0E1F80AF101030493CB -:1011B00008AB0393182302932C4B3246019301236F -:1011C000204600933B4600F027FC00238BF80030BC -:1011D00000F01CF9264ADFF8C4A01368C31AB3F55F -:1011E0007A7F32D3106000F013F902460B46204696 -:1011F00000F0C0FC204600F00DFC30B39AF80C3033 -:10120000DFF89CB0002B14BF032302238BF80530BA -:1012100000F0FCF84FF47A73B0FBF3F02946CBF8FA -:1012200000005846FFF748FB18230293114B073084 -:10123000019340F25513C0F3CF000490009303953F -:1012400042464B46204600F0E7FB9AF80C300BB1C3 -:10125000FFF7A8FA9AF80C30002B7FF4E8AE13B031 -:10126000BDE8F08FAFF30080A01800209818002090 -:10127000A8190020AC190020401DA12026812A0BAE -:10128000F1C6A7C1D068080FB8190020AD19002019 -:10129000000C01409C18002099180020C81800205C -:1012A0008808002070B501F06DFD00250E4C0F4E32 -:1012B00020703068237883420CD8002520780138CC -:1012C00001F05CFD23780544013BB5F5006F237008 -:1012D000F4D370BD01F052FD336805440133B5F518 -:1012E000084F3360E5D3E8E7B4190020B0190020B7 -:1012F00001F0D6BD07B502AB43F8041D00F1006054 -:101300000422194600F5084001F076FD03B05DF8AF -:1013100004FB0000054B1A68054B1B789B1A83429F -:1013200002D9104401F02ABD00207047B0190020F6 -:10133000B419002038B50446064D2868204401F051 -:1013400023FD28B928682044BDE8384001F02EBDAF -:1013500038BD00BFB0190020022802BF4FF40022A0 -:10136000014B1A61704700BF000C0140002310B50B -:10137000934203D0CC5CC4540133F9E710BD0000A4 -:1013800002460346981A13F9011B0029FAD1704747 -:1013900003460244934202D003F8011BFAE7704768 -:1013A0000FB4002004B070470EB4002003B07047A3 -:1013B000FEE70000EFF30983EFF30583034B9A6B1D -:1013C0009A6A9A6A9A6A9A6A9B6AFEE700ED00E056 -:1013D000EFF30983EFF30583044B9A6B9A6A9A6AD9 -:1013E0009A6A9A6A9A6A9B6AFEE700BF00ED00E07B -:1013F000EFF30983EFF30583034B5A6B9A6A9A6AFA -:101400009A6A9A6A9B6AFEE700ED00E001F080BDEF -:1014100001F05ABD30B5084D0A4491420BD0092461 -:1014200011F8013B5840013CF7D040F300032B403A -:1014300083EA5000F7E730BD2083B8ED024600682C -:1014400048B1036811891360D38801339BB2994274 -:10145000D38038BF1381704770B504460D4688B0FD -:10146000202200216846FFF793FF20460495FFF7EE -:10147000E5FF054658B16B46044608AE1A4603CA56 -:10148000B24220606160134604F10804F6D1284698 -:1014900008B070BD2DE9F04130B940F2C531264B9E -:1014A000264A274802F0C2FA0B7C23B9254B234A6F -:1014B00040F2C631F5E7C66986B9C161BDE8F08181 -:1014C000002B29DA930CAB4229D1B44201D10C6034 -:1014D000F3E7C8F800100C60BDE8F0814B68B04637 -:1014E00023F06047BD0C15EA230538BF3D4634465E -:1014F0004FEAD37EC3F3807C6368BEEBD37F23F0D7 -:101500006042DDD1974203D1C3F380739C450AD179 -:10151000974205E01C46EFE7AA4206D013469D42DB -:101520002CBF00230123002BCFD12368A046002B22 -:10153000F0D12160BDE8F081743F0008683D0008EB -:101540002C4000084D40000808B5034A034B40F208 -:101550005E31034802F06AFA443D0008EC3F00089F -:101560002C40000808B503680B60C388016033B9DC -:10157000044B054A4FF4C761044802F057FA013B97 -:10158000C38008BDBC3F0008B83D00082C400008DF -:1015900070B50C4600F10C05616831B9E38A002092 -:1015A00061F30903E382002170BD0E682846FFF74E -:1015B000D9FF6660F0E7000008B5426832B10B4B16 -:1015C0000B4A40F22F410B4802F030FAC37DC3F3BF -:1015D0008401013161F38603C375C38A62F3090391 -:1015E000C3821B0A62F3C713C37508BD0840000815 -:1015F000743D00082C4000082DE9F047089E32B9E0 -:101600001F4B204A40F239511F4802F00FFA4FF4A5 -:101610007F4901F007054FEAD6082A4406F007067D -:1016200000EBD100954201D1BDE8F08705F0070E2F -:1016300006F0070AD645774638BF5746511BC7F113 -:1016400008078F4228BF0F46EC08045D08EBD6015F -:1016500013F801C004FA0EF429FA07FE24FA0AF47A -:101660005FFA8EFE8CEA04044EFA0AFE04EA0E04C7 -:101670008CEA040C03F801C03D443E44D2E700BFAD -:10168000883F00088C3D00082C4000082DE9F041FF -:1016900006460F4600254FF6FF7441F221082A4600 -:1016A00030463946FEF75CFD0823C0B284EA0024C8 -:1016B00014F4004F4FEA4404A4B203F1FF3318BFFF -:1016C00084EA080413F0FF03F2D10835402DE6D177 -:1016D0002046BDE8F081000010B541F221040A4423 -:1016E000914200D110BD11F8013B80EA032008238C -:1016F00010F4004F4FEA400080B203F1FF3318BFEF -:10170000604013F0FF03F3D1EAE700002DE9F04F4A -:1017100085B08A468DE80C00BDF83C40814630B962 -:1017200040F26E31484B494A494802F07FF911F0C6 -:10173000604F04D0474B454A40F26F31F4E7009BBD -:10174000002B7ED024B10E9B002B7AD0072C28D8FA -:1017500009F10C00FFF772FE054628B96FF002058B -:10176000284605B0BDE8F08F14220021FFF710FED7 -:1017700022460E9905F10800FFF7F8FD631C2B7453 -:10178000009B2C441B78294603F01F0363F03F03A2 -:1017900023724AF000436B604846FFF77BFE012549 -:1017A000DEE74FF000084FF0800B46464546019BB0 -:1017B0001B0A029300F10C0303930398FFF73EFE0C -:1017C00007460028CAD014220021FFF7E1FDB6BB6E -:1017D00002229DF804303B729DF808307B720E9B0C -:1017E000711E1944B4420AD9B818013211F801EF38 -:1017F000D2B20136072A80F808E0B6B2F2D1B4427C -:1018000008BF4FF0400B009BB8181978013201F067 -:101810001F0141EA48114BEA010303724AF00043F9 -:101820007B603A7439464846FFF734FE0135B442CE -:101830002DB288F001084FF0000BBED190E70022D6 -:10184000CDE76FF001058BE7743F0008583D0008B5 -:101850002C400008983F00082DE9F0471E46CB8A2F -:101860009146C3F30902062A80460F4619D0134653 -:101870000021B0B28DB25A1992B2052A09D9A842F4 -:1018800010D8FA8A034463F30902FA820120BDE802 -:10189000F087A842F3D919F801403A44947601310F -:1018A000E8E70025FB8A7C68C3F309001C23821F3C -:1018B000B2FBF3FA03FB1A2A1FFA8AF27CB3012166 -:1018C0002368002B39D1B31F03441C20B3FBF0F372 -:1018D00001339BB299420CD2BAF1000F09D14046B4 -:1018E000FFF7ACFD08B1C0F800A0206008B30446C3 -:1018F00000224FF0000AB6B2B54230D21346691E3C -:101900004944E018013311F801EF9BB201351C2B5B -:1019100080F804E0ADB214D0AE42F2D8ECE7404615 -:10192000FFF78CFD044608B1002303607C60002CA7 -:10193000DED16FF00200BDE8F087013189B21C46AC -:10194000BEE7AE42D8D94046FFF778FD08B1C0F8EF -:1019500000A020600028ECD004460022CCE7FB8ADF -:10196000C3F30902164466F30903FB828EE7000005 -:10197000F8B50E4615461F46044628B9144B154ABD -:101980004F21154802F052F824220021FFF700FDF4 -:10199000069B6A096360079B002023624FF6FF7372 -:1019A0009A4228BF1A46A7602070A061E06197B2F2 -:1019B00004F10C05824205D100232B60278263824B -:1019C000A382F8BD2E60013035462036F2E700BF15 -:1019D000703F0008E43C00082C40000808B528B916 -:1019E0007321084B084A094802F020F8037823B90C -:1019F0004BB2002B01DD017008BD054B024A7D2171 -:101A0000F1E700BF743F0008F03C00082C400008DC -:101A1000B83E0008007870472DE9F7430D9E074651 -:101A200019461046BDF828900B9D9DF83040BDF832 -:101A3000388016B9B8F1000F43D11F2C41D83B783C -:101A4000D3B9B8F1070F39D839F0030339D1424679 -:101A500031464FF6FF70FFF73FFE4FEA092920F0AD -:101A6000010009F44079400449EA0464400C44EA66 -:101A700040244FF6FF730DE043EA0923B8F1070F46 -:101A800043EA0464F5D9FFF701FE42463146FFF709 -:101A900023FE03468DE840012A4621463846FFF7DB -:101AA00035FE0DB9FFF750FD2B780133DBB21F2B4C -:101AB00088BF00232B7003B0BDE8F0836FF00300F4 -:101AC000F9E76FF00100F6E72DE9F7430E9F814635 -:101AD0000B9D9DF830009DF83480BDF83C6007B93F -:101AE000C6BB1F2836D899F800E0BEF1000F34D0ED -:101AF0000C0244F080049DF8281044EAC83444EAFB -:101B0000014444EA0E04072E44EA006415D919463C -:101B10001046FFF7BBFD32463946FFF7DDFD0346B1 -:101B2000019600972A4621464846FFF7EFFDB8F197 -:101B3000010F0CD125B9FFF707FD4FF6FF73EFE753 -:101B40002B780133DBB21F2B88BF00232B7003B02F -:101B5000BDE8F0836FF00100F9E76FF00300F6E7EE -:101B6000C06900B104307047C1690C300B68036173 -:101B7000FFF7F8BC2DE9F84FD0F818A00546164637 -:101B80001F4654464FF00009DFF8608000F10C0B4F -:101B90000CB9BDE8F88FD4E90223B21A67EB03034E -:101BA000994508BF90451FD2AB6921469C42284603 -:101BB0000DD1FFF7EDFCAB6921461B685846AB61C0 -:101BC000FFF7D0FCAC692346A2461C46E0E7FFF7CE -:101BD000DFFC23682146CAF800305846FFF7C2FCF4 -:101BE0005446DAF80030EFE72368EDE780841E0002 -:101BF0002DE9F04F8BB00D4614460793DDF8509059 -:101C00008246002800F06481B9F1000F00F0608185 -:101C1000531E3F2B00F25C81012A03D1079B002B4E -:101C200040F056810023BAF814600893F600B542DC -:101C3000099380F053812B199E420AD2761B16F02D -:101C4000FF0607D140F26751AA4BAB4AAB4801F0FF -:101C5000EDFE2646DAF80C3023B9DAF81030002B06 -:101C600000F0A5802F2D31D8C5F1300846454FF042 -:101C7000000334BFB0465FFA88F80093294608ABEA -:101C80004246DAF80800FFF7B7FCA6EB0807454420 -:101C9000FFB24FF0300BBAF8143003F10053063B9B -:101CA000DB000293DAF80C300593059B002B51D032 -:101CB00087B9DAF81000002861D0002F5FD0AB455B -:101CC00050D98F4B8C4A40F2A651BFE737464FF0B0 -:101CD0000008DEE7029B23B98A4B874A4FF4B161C3 -:101CE000B4E7029BE02B28BFE02306935B44AB42A2 -:101CF00004931DD95B1B9F4226BFDBB2039303975E -:101D0000AB4504D97E4B7C4A40F291519EE7059841 -:101D1000CDF8008008ABA5EB0B01039A0430FFF768 -:101D20006BFC039B9844FF1A1D445FFA88F8FFB2CE -:101D3000049B9B4504D3744B6F4A40F29B5185E74B -:101D4000029B069ADDF810B09B1A0293059B1B6854 -:101D50000593AAE7029BBB42ABD26C4B664A40F2AA -:101D6000A15173E7CDF800803A46A5EB0B0108AB13 -:101D7000B8443D44FFF740FC00275FFA88F8BAF802 -:101D80001430B5EBC30F04D9614B5B4A40F2B1513B -:101D90005CE7B8F1400F04D95E4B574A40F2B251AC -:101DA00054E767B15C4B544A40F2B3514EE700939D -:101DB000324608AB2946DAF80800FFF71DFC731E0F -:101DC0003F2B35B201D8A64204DD544B544A40F2B1 -:101DD00035213BE760070AD00AAB03EBD40111F8C9 -:101DE000083C624202F00702134101F8083C082C4B -:101DF00021D9102C21D9202C8CBF08230423079A29 -:101E0000002A6DD0B4EBC30F6CD0082C04F1FF3264 -:101E100015D89DF8203023FA02F2D10706D54FF0ED -:101E2000FF3202FA04F423438DF820309DF820306D -:101E300089F800304EE00123E1E70223DFE7102CB0 -:101E400011D8BDF8203023FA02F2D20706D54FF0A0 -:101E5000FF3202FA04F42343ADF82030BDF82030FD -:101E6000A9F8003036E0202C0ED8089921FA02F2A9 -:101E7000D30705D54FF0FF3303FA04F40C4308945D -:101E8000089BC9F8003025E0402C1CD0DDE908672C -:101E900030463946FEF764F9002100F0010050EAAF -:101EA00001030BD0224601200021FEF765F94042D4 -:101EB00061EB410106430F43CDE90867DDE90823E3 -:101EC000C9E9002306E0174B154A4FF42071BDE61F -:101ED0006FF0010528460BB0BDE8F08F1D46F9E70D -:101EE000012CA3D0082CA1D9102CB7D9202CE5D8CF -:101EF000C6E700BFC43D00089C3D00082C40000818 -:101F0000E63D0008D33D00080B3E0008333E0008C4 -:101F10005A3E0008883E0008A03E0008BA3E00086D -:101F20001C3D0008B83E000830B585B030B940F21D -:101F3000B121234B234A244801F078FD23B9234BD8 -:101F4000204A40F2B221F6E7402A04D9204B1D4A2C -:101F500040F2B621EFE722B91D4B1A4A4FF42F7118 -:101F6000E9E70024012A0294039417D11B788DF825 -:101F7000083053070AD004AB03EBD20313F8084C24 -:101F8000554205F00705AC4003F8084C00910346A4 -:101F9000002102A8FFF730FB05B030BD082AE5D9C3 -:101FA000102A03D81B88ADF80830E2E7202A02D8AF -:101FB0001B680293DDE7D3E90045CDE90245D8E788 -:101FC000F43E0008303D00082C4000080F3F000898 -:101FD000B83E000870B50C4600F10C05E16819B96F -:101FE000A1602161A18270BD0E682846FFF7BAFA90 -:101FF000E660F3E72DE9F04FD1F8009091B0C9F316 -:10200000C01604460D46CDE90223002E50D0C9F378 -:10201000C03BC9F30626B9F1000F80F29F8119F089 -:10202000C04F40F09B812B7B002B00F09781BBF1D0 -:10203000020F03D02278B24240F0938109F07F0270 -:10204000BBF1020F059236D119F07F0FC9F30F2AA9 -:1020500001D10AF0030A2B447606059A93F803800F -:1020600046EA0B4646EA82465FEAD81346EA0A0683 -:10207000069300F09A800022002310A961E908234A -:10208000059B6768009352465B462046B847002888 -:1020900000F08880A7698FB9314604F10C00FFF782 -:1020A000DBF90746D0B96FF0020011B0BDE8F08F40 -:1020B0004FF0020BAFE7C9F3074ACCE73B699E42FA -:1020C0000DD03F68002FF9D1314604F10C00FFF725 -:1020D000C3F907460028E6D0A3693B60A761DDE9A4 -:1020E0000801FFF7D3FAB882F97D08F01F06C1F3A3 -:1020F0008401711A89B20FFA81FEBEF1000FB8BFD8 -:1021000001F1200EC9F30461D7E90223B8BF0FFA29 -:102110008EFE079152EA030100F02F81DDE90201F2 -:10212000801A61EB03010B46002102469E4899424A -:1021300008BF9042C0F02181069B002B3FD0BEF12A -:10214000010F00F31A8118F0400F38D0DDE90223A7 -:10215000C7E90223202200210DEB0200FFF718F946 -:10216000DDE90223CDE908232B1D0A932B7B2046B2 -:10217000013BDBB2ADF834309DF81C30ADF836A031 -:102180008DF83A309DF814308DF838B08DF83B302A -:102190008DF83960A36808A998473846FFF70CFA0C -:1021A000002082E76FF00B007FE7A76917B96FF097 -:1021B0000C007AE73B699E4296D03F68F6E7FB7DCC -:1021C000C8F34012B2EBD31F40F0CE80C3F38403B8 -:1021D000B34240F0CC8006992B7B4FEA981279B33A -:1021E000D2073CD4032B40F2C580DDE90223C7E9C6 -:1021F00002232B7BAE1D033BDBB23246394604F192 -:102200000C00FFF729FB002808DA39462046FFF7C3 -:10221000BFF93846FFF7D0F9032046E7AB883B8388 -:102220002A7B033AD2B2B88A3146FFF755FAFB7DD2 -:10223000B882DA43C2F3C01262F3C713FB75AFE78B -:102240006AB92E1D013BDBB23246394604F10C005F -:10225000FFF702FB0028D8DB2A7B013AE2E7FA8A83 -:10226000013BC2F30902052AD9B250D80023281D28 -:1022700099420AD907EB020E10F801CB0132013363 -:10228000062A8EF81AC0DBB2F2D18B4228BF002397 -:10229000DDE9028907F11A02CDE908890A927A6814 -:1022A0003CBF04335B190B920C93FB8AADF836A04C -:1022B000C3F3090319449DF81C30ADF834108DF8B0 -:1022C0003A309DF814308DF838B08DF83B3000234B -:1022D0008DF839607B602A7BB88A013A291DFFF7A7 -:1022E000FBF93B8BB882834203D1A36808A920463F -:1022F000984708A92046FFF76DFE3846FFF75CF9BE -:10230000B88A3B8B984214BF11200020CDE6786834 -:1023100010B34FF0060E03689BB9A2EB0E021B2A06 -:1023200013D80332024405F1040E1F309942ACD990 -:102330001EF801CB013302F801CF9042DBB2F5D198 -:10234000A3E70EF11C0E1846E5E7184B184A40F2B9 -:10235000B311184801F06AFB034696E76FF00900D5 -:10236000A3E66FF00A00A0E66FF00D009DE66FF0A7 -:102370000E009AE66FF00F0097E6FB7D394668F392 -:1023800086036FF3C713FB752046FFF701F9069B21 -:10239000002B7FF4D8AEFB7DC3F38402013262F3DD -:1023A0008603FB7503E700BF80841E00243F0008FE -:1023B000083D00082C4000082DE9F0414E4EB04287 -:1023C00040F086804D4CDFF838E1E56945F0007556 -:1023D000E561E469846AD4F8007207EA0E0747F001 -:1023E0000107C4F80072D4F8005205EA0E0545F062 -:1023F000010545EA0121C4F80012002A6AD0002133 -:102400000F46C4F81C12C4F80412C4F80C12C4F825 -:10241000141204EBC10501311C29C5F84072C5F83E -:102420004472F6D14FF0000E4FF0010C964510D1DA -:10243000826AB042D2F8003223F00103C2F80032BF -:1024400058D12E4BDA6922F00072DA61DB69BDE8FF -:10245000F0819F781D8817F0010F18BFD4F804820F -:102460000CFA05F11CBF41EA0808C4F8048217F011 -:10247000020F18BFD4F80C8204EBC5051CBF41EA5B -:102480000808C4F80C827F0748BFD4F8147203F11F -:102490000C0344BF0F43C4F8147253F8087C0EF1C8 -:1024A000010EC5F8407253F8047CC5F84472D4F8A4 -:1024B0001C522943C4F81C12B8E70021846AC4F8EE -:1024C0001C12C4F80412C4F80C12C4F81412A9E7C0 -:1024D000002AF2D10022836AC3F84022C3F84422C2 -:1024E000C3F80422C3F814220122C3F80C22C3F853 -:1024F0001C229DE7BDE8F081B819002000100240C1 -:102500000000FFFF184A08B5916A8B688B6013F0D2 -:10251000010105D013F00C0F14BF4FF480310121DD -:10252000D80506D513F4406F14BF41F4003141F0D3 -:102530000201D80306D513F4402F14BF41F48021C3 -:1025400041F00401D3690BB107489847202383F376 -:1025500011880021054800F087FB002383F31188D0 -:10256000BDE8084000F066BDB8190020C019002081 -:1025700038B5124CA36ADD68AA0712D05A6922F056 -:1025800002025A61A36913B1012120469847202312 -:1025900083F3118800210A4800F066FB002383F3CF -:1025A0001188EB0606D51021A36AD960236A0BB106 -:1025B00002489847BDE8384000F03CBDB8190020FB -:1025C000C819002038B5124CA36A1D69AA0712D099 -:1025D0005A6922F010025A61A36913B10221204600 -:1025E0009847202383F3118800210A4800F03CFB20 -:1025F000002383F31188EB0606D51021A36A196125 -:10260000236A0BB102489847BDE8384000F012BD7C -:10261000B8190020C819002038B50F4CA36A5D68AE -:102620002A075D600AD5032222701A6822F002028E -:102630001A60636A13B10021204698476B0706D5DC -:10264000A36A9969236A13B1090403489847BDE84E -:10265000384000F0EFBC00BFB819002010B50F4C97 -:10266000204600F06FF90E4B0B211320A36200F0FF -:1026700049F90B21142000F045F90B21152000F039 -:1026800041F90B21162000F03DF900232046BDE85A -:1026900010401A460E21FFF78FBE00BFB819002068 -:1026A000006400400F4B10B59842044605D10E4B14 -:1026B000DA6942F00072DA61DB690122A36A1A600A -:1026C000A36A5A68D20707D5626851681268D9614F -:1026D0001A60064A5A6110BD0121082000F0F8F97D -:1026E000EEE700BFB8190020001002405B87010030 -:1026F00003291AD8DFE801F0020A0F14836A9B68E5 -:1027000013F0E05F14BF012000207047836A9868CF -:10271000C0F380607047836A9868C0F3C0607047F8 -:10272000836A9868C0F3007070470020704700000B -:1027300010B503291FD8DFE801F0021F2327816AA3 -:102740008B68C3F30163183301EB03131078810620 -:102750001ED55468C0F30011490041EAC40141F09C -:10276000040100F00F005860906841F0010198608A -:10277000D268DA60196010BD836A03F5C073E5E7BB -:10278000836A03F5C873E1E7836A03F5D073DDE775 -:102790009488C0F30011490041EA4451E1E7000088 -:1027A00001290CD003D3022910D000207047836A7E -:1027B000DA68920701D1186903E001207047836A43 -:1027C000D86810F0030018BF01207047836AF2E751 -:1027D00010B539B9836AD96889071BD11B699B0772 -:1027E00004D110BD012915D0022948D1816AD1F840 -:1027F000C031D1F8C401D1F8C8411461D1F8CC413D -:10280000546120240C610C69A40717D14C6944F071 -:10281000100412E0816AD1F8B031D1F8B401D1F8D6 -:10282000B8411461D1F8BC4154612024CC60CC681B -:10283000A40703D14C6944F002044C6111795C088F -:1028400064F304119C0864F34511117189064BBFB0 -:1028500091681189DB085B0D4CBF63F31C0163F3C6 -:102860000A01137948BF916060F3030313714FEAC3 -:1028700010234FEA104058BF11811370508010BDD3 -:1028800000231A4610B51C495A50CC180833802B27 -:102890006260F9D1194B9A6942F07D029A619B6995 -:1028A0000268174BDA6082685A6042681A60C26830 -:1028B00003F58063DA6042695A6002691A608269CE -:1028C000C3F80C24026AC3F80424C269C3F80024C4 -:1028D000426AC3F80C28C26AC3F80428826AC3F8A3 -:1028E0000028026BC3F80C2C826BC3F8042C426BDB -:1028F000C3F8002C10BD00BFE419002000100240F6 -:102900000008014000F16043090103F56143C9B2C9 -:1029100083F80013012300F01F024009800000F13A -:102920006040934000F56140C0F88031036070471B -:10293000090100F16040C9B200F56D4001767047B1 -:10294000FFF78CBE01230370002300F108028260B0 -:10295000C26000F110024360026142618361C361A1 -:10296000036243627047000010B52023044683F3DE -:102970001188022341600370FFF794FE0323237044 -:10298000002383F3118810BD2DE9F0411F46044652 -:102990000D461646202383F3118800F1080823789A -:1029A000042B0ED029462046FFF7A2FE48B1204650 -:1029B00032462946FFF7BCFE002080F31188BDE8AF -:1029C000F0813946404600F033F90028E7D0002373 -:1029D00083F31188BDE8F0812DE9F0411F460446DC -:1029E0000D461646202383F3118800F11008237842 -:1029F000042B0ED029462046FFF7D2FE48B12046D0 -:102A000032462946FFF7E4FE002080F31188BDE836 -:102A1000F0813946404600F00BF90028E7D000234A -:102A200083F31188BDE8F0810022024B1B605B60DC -:102A30009A607047641A0020002382680374054B73 -:102A40001B6899689142FBD25A680360426010602B -:102A500058607047641A002008B5202383F311885A -:102A6000037C032B05D0042B0DD02BB983F31188E5 -:102A700008BD002243691A604FF0FF334361FFF73E -:102A8000DBFF0023F2E790E80C001A600268536055 -:102A9000F2E70000002382680374054B1B68996805 -:102AA0009142FBD85A6803604260106058607047DA -:102AB000641A0020054B196908741868026853608D -:102AC0001A60186101230374FDF75ABD641A0020CF -:102AD00030B54B1C87B005460A4C10D023690A4A12 -:102AE00001A800F0DDF82846FFF7E4FF049B13B1CE -:102AF00001A800F0EFF82369586907B030BDFFF76F -:102B0000D9FFF8E7641A0020592A000838B50C4D9F -:102B100041612B6981689A680446914203D8BDE8F7 -:102B20003840FFF789BF1846FFF786FF01232C6165 -:102B3000014623742046BDE83840FDF721BD00BFA3 -:102B4000641A0020044B1A681B6990689B689842BD -:102B500094BF002001207047641A002010B5084C73 -:102B6000236820691A6854602260012223611A7464 -:102B7000FFF790FF01462069BDE81040FDF700BD5A -:102B8000641A002008B5FFF7DDFF18B1BDE8084062 -:102B9000FFF7E4BF08BD0000826002220274002239 -:102BA000427470478368A3F13C0243F80C2C02691D -:102BB00043F83C2C426943F8382C074A43F81C2C54 -:102BC000C268A3F1180043F8102C022203F8082C65 -:102BD000002203F8072C70479105000810B5202348 -:102BE00083F31188FFF7DEFF00210446FFF78EFF15 -:102BF000002383F31188204610BD0000024B1B699F -:102C000058610F20FFF756BF641A0020202383F37A -:102C10001188FFF7F3BF000008B50146202383F3B6 -:102C200011880820FFF754FF002383F3118808BDA3 -:102C300049B1064B42681B6918605A6013604360D3 -:102C40000420FFF745BF4FF0FF307047641A0020A3 -:102C50000368984206D01A680260506059611846AD -:102C6000FFF7EABE7047000038B504460D462068FD -:102C7000844200D138BD036823605C604561FFF782 -:102C8000DBFEF4E7054B03F114025A619A614FF041 -:102C9000FF32DA6100221A62704700BF641A002016 -:102CA00010B5C2600A4A036153699C68A1420CD8FE -:102CB0005C68036044602060586081609868411AD5 -:102CC00099604FF0FF33D36110BD091B1B68ECE71F -:102CD000641A0020036881689A680A449A6042680E -:102CE000136003685A6000234FF0FF32C360014B4A -:102CF000DA617047641A002000207047FEE7000088 -:102D0000704700004FF0FF3070470000BFF34F8F57 -:102D1000024AD368DB07FCD4704700BF00200240A2 -:102D200008B5074B1B7853B9FFF7F0FF054B1A693D -:102D3000120641BF044A5A6002F188325A6008BD47 -:102D4000B41A0020002002402301674508B5054B56 -:102D50001B7833B9FFF7DAFF034A136943F08003A6 -:102D6000136108BDB41A0020002002407F289ABFDA -:102D700000F58030C0020020704700004FF4006072 -:102D800070470000802070477F2808B50BD8FFF7F8 -:102D9000EDFF00F500630268013204D10430834284 -:102DA000F9D1012008BD002008BD00007F2810B522 -:102DB00004461CD8FFF7AAFFFFF7B2FFF3220D4B22 -:102DC000DA6002221A61FFF7D1FF58611A6942F0F6 -:102DD00040021A61FFF79AFF4FF4006100F0E4F837 -:102DE000FFF7B4FF2046BDE81040FFF7CDBF00203D -:102DF00010BD00BF002002402DE9F84312F001038E -:102E0000144606D040F241221F4B1A600020BDE854 -:102E1000F88385181D4A954204D940F246211A4A82 -:102E20001160F3E7FFF77CFFFFF770FF4FF0010938 -:102E3000DFF86880451A012C05EB01060F4604D81F -:102E4000FFF784FF0120BDE8F883C8F8109031F83F -:102E5000023B3380FFF75AFF0020C8F81000338888 -:102E60003A889BB29A420DD040F25D22064B1A601E -:102E7000074B1E60074B1C60074B1F60FFF766FF88 -:102E8000BDE8F883023CD6E7B01A0020FFFF030834 -:102E9000A41A0020AC1A0020A81A0020002002402A -:102EA000084908B50B7828B153B9FFF739FF01235A -:102EB0000B7008BD23B1BDE808400870FFF746BF9E -:102EC00008BD00BFB41A002038B500F059F94FF41E -:102ED0007A730C490C4A0C6A116803FB04F38B42A9 -:102EE0000A49D1E9004504D2003445F10105C1E9A0 -:102EF0000045E41845F10005136000F04BF9204649 -:102F0000294638BD641A0020B81A0020C01A0020D3 -:102F100008B5FFF7D9FF4FF47A720023FDF738F9AF -:102F200008BD00BF10B5094C0439013AD2B2FF2ADE -:102F300000D110BD53089800043054F823300059D4 -:102F40009BB243EA004341F8043FEEE7046C0040C3 -:102F500030B50748013AD2B2FF2A00D130BD0D8802 -:102F6000540840F82450A3004C8804331C50F1E767 -:102F7000046C004007B5012201A90020FFF7D2FF31 -:102F8000019803B05DF804FB13B50446FFF7F2FFA8 -:102F9000A04206D002A941F8044D01220020FFF70B -:102FA000D7FF02B010BD00007047000045F2555237 -:102FB000064B1A6002225A6040F6FF729A604CF685 -:102FC000CC421A600122024B1A7070470030004058 -:102FD000C91A0020034B1B781BB14AF6AA22024BE8 -:102FE0001A607047C91A002000300040034B1B686C -:102FF0009B0042BF0122024B1A707047241002400E -:10300000C81A00204FF08072014B1A60704700BF51 -:1030100024100240014B1878704700BFC81A0020E6 -:10302000EFF30983203383F30988002383F31188A6 -:103030007047000010B5202383F311880D4B5B68A7 -:1030400013F4006312D0EFF309844FF0807344F857 -:10305000043CA4F1200383F30988FFF773FD18B142 -:10306000054B44F8083C10BD044BFAE783F3118884 -:1030700010BD00BF00ED00E0A1050008A405000898 -:1030800070470000FEE70000084A094B09498B42DF -:1030900004D30021084A934205D3704752F8040F25 -:1030A00043F8040BF3E743F8041BF4E7AC410008D2 -:1030B000542400205424002054240020FEE7000063 -:1030C00010B5174CFFF7B0FCFFF7DCFD8022154967 -:1030D0002046FFF761FD012344F8180C0374124BDE -:1030E000124AD96821F4E0610904090C0A43104925 -:1030F000DA60CA6842F08072CA600E490A6842F01B -:1031000001020A601022DA77202283F822200023AD -:1031100083F3118862B6BDE810400748FFF75EBD33 -:103120008C1A00206840000800ED00E00003FA055A -:10313000F0ED00E0001000E070400008F8B50F4C22 -:10314000226A01322262224652F8141F9142154629 -:1031500006D020268B68013B8B6063699A6802B1B8 -:10316000F8BD1968DF68DA604D60616182F311882B -:103170001869B84786F31188EFE700BF641A00208A -:10318000EFF3118020B9EFF30583202282F3118839 -:103190007047000010B558B9EFF30584C4F3080474 -:1031A00014B180F3118810BDFFF7ECFC84F3118893 -:1031B00010BD000000F030B808B500F069F9FFF765 -:1031C0007FFFBDE80840FFF711BF00007047000017 -:1031D0004FF0FF310E4B1A6919611A6900221A610A -:1031E0001869D868D960D968DA60DA68DA6942F0B3 -:1031F0008052DA61DA69DA6942F00062DA61054A1E -:10320000DB69136843F48073136000F021B900BFD9 -:1032100000100240007000401C4B1A6842F001028E -:103220001A601A689007FCD55A6822F003025A60A7 -:103230005A6812F00C02FBD1196801F0F90119600B -:103240005A601A6842F480321A601A689103FCD5F9 -:103250004EF63162DA625A6842F4E8125A601A682D -:1032600042F080721A601A689201FCD51221084A55 -:103270005A60084A11605A6842F002025A605A685D -:1032800002F00C02082AFAD1704700BF0010024079 -:1032900000641D0000200240084A08B55369116807 -:1032A0000B4003F00103536123B1054A13680BB1CE -:1032B00050689847BDE80840FFF7BCBE00040140D5 -:1032C000E4190020084A08B5536911680B4003F05F -:1032D0000203536123B1054A93680BB1D068984744 -:1032E000BDE80840FFF7A6BE00040140E419002035 -:1032F000084A08B5536911680B4003F00403536191 -:1033000023B1054A13690BB150699847BDE80840DD -:10331000FFF790BE00040140E4190020084A08B5F8 -:10332000536911680B4003F00803536123B1054A48 -:1033300093690BB1D0699847BDE80840FFF77ABEA2 -:1033400000040140E4190020084A08B553691168D7 -:103350000B4003F01003536123B1054A136A0BB10C -:10336000506A9847BDE80840FFF764BE000401407A -:10337000E4190020174B10B55C691A68144004F476 -:1033800078725A61A30604D5134A936A0BB1D06AC6 -:103390009847600604D5104A136B0BB1506B9847E1 -:1033A000210604D50C4A936B0BB1D06B9847E2050C -:1033B00004D5094A136C0BB1506C9847A30504D58A -:1033C000054A936C0BB1D06C9847BDE81040FFF7ED -:1033D00031BE00BF00040140E41900201A4B10B5B3 -:1033E0005C691A68144004F47C425A61620504D591 -:1033F000164A136D0BB1506D9847230504D5134A37 -:10340000936D0BB1D06D9847E00404D50F4A136E4D -:103410000BB1506E9847A10404D50C4A936E0BB1C2 -:10342000D06E9847620404D5084A136F0BB1506FF1 -:103430009847230404D5054A936F0BB1D06F984782 -:10344000BDE81040FFF7F6BD00040140E41900207C -:10345000062108B50846FFF755FA06210720FFF7B1 -:1034600051FA06210820FFF74DFA06210920FFF73F -:1034700049FA06210A20FFF745FA06211720FFF72F -:1034800041FABDE8084006212820FFF73BBA0000BA -:1034900008B5FFF79DFE0648FFF7F2F9FFF750FA6F -:1034A00000F03AF8FFF792FEBDE8084000F070B86F -:1034B00090400008026843681143016003B1184757 -:1034C00070470000143000F0FFB900004FF0FF33E8 -:1034D000143000F0F9B90000383000F075BA00007F -:1034E0004FF0FF33383000F06FBA0000143000F0B6 -:1034F000C5B900004FF0FF31143000F0BFB9000033 -:10350000383000F01FBA00004FF0FF32383000F0C2 -:1035100019BA00000020704700F00AB90F4B37B508 -:103520000360002343608360C360012304461546A3 -:1035300003744FF4007200900B4600F15C011430EC -:1035400000F072F900942B464FF4007204F51771E5 -:1035500004F1380000F0EAF903B030BDCC400008B7 -:1035600038B5C36904460D461BB904210844FFF76A -:10357000A1FF294604F1140000F064F9002806DADE -:10358000201D4FF48061BDE83840FFF793BF38BD80 -:1035900000F00EB808B5202383F31188FFF7CEFDA5 -:1035A000002383F31188BDE80840FFF743BD000006 -:1035B000054B064A08215A6000229A6007220B2018 -:1035C0001A60FFF7B5B900BF10E000E03F19010035 -:1035D000026843681143016003B118477047000057 -:1035E000024AD36843F0C003D360704700440040F0 -:1035F000024AD36843F0C003D360704700480040DC -:103600002DE9F041D0F85C640546F7683368DA05C7 -:103610009CB20DD5202383F311884FF40071043040 -:10362000FFF7D6FF6FF480733360002383F31188B4 -:10363000202383F3118805F1040814F02F0333D1FC -:1036400083F31188380615D5210613D5202383F37B -:10365000118805F1380000F09DF9002846DA0821AC -:10366000281DFFF7B5FF4FF67F733B40F360002343 -:1036700083F311887A060ED563060CD5202383F3D5 -:103680001188EA6C2B6D9A4202D12B6C002B2FD142 -:10369000002383F31188D5F86424D368002B31D03C -:1036A000BDE8F04110691847230713D014F0080F44 -:1036B0000CBF00218021E00748BF41F02001A20794 -:1036C00048BF41F04001630748BF41F48071404664 -:1036D000FFF77EFFA406736805D595F860142846A9 -:1036E0001940FFF73DFF3468A4B2A6E77060BEE75B -:1036F00027F040073F041021281D3F0CFFF768FF0B -:10370000F760C5E7BDE8F08108B50348FFF778FF2B -:10371000BDE80840FFF78EBC801B002008B50348B9 -:10372000FFF76EFFBDE80840FFF784BCE81F0020EC -:1037300010B5094C094A20460021FFF7EFFE084B5F -:10374000084AC4F85C34084C00212046FFF7E6FE26 -:10375000064BC4F85C3410BD801B0020E135000826 -:1037600000440040F1350008E81F002000480040F8 -:10377000F8B5154682680B46AA428169066938BFCA -:103780008568761AB542044607D218462A46FDF7E0 -:10379000EDFDA3692B44A3610DE011D93246184613 -:1037A000FDF7E4FDAF1B3A46E1683044FDF7DEFD6E -:1037B000E2683A44A261A36828465B1BA360F8BD97 -:1037C00018462A46FDF7D2FDE368E4E72DE9F0410B -:1037D0000446154683682669934238BF8568406968 -:1037E0000F46361AB54206D22A46FDF7BFFD636979 -:1037F0002B4463610DE012D93246A5EB0608FDF7B4 -:10380000B5FD4246B919E068FDF7B0FDE2684244F3 -:103810006261A36828465B1BA360BDE8F0812A466D -:10382000FDF7A4FDE368E4E710B50024C361029B43 -:103830000A44006040608460C1608161416102614E -:10384000036210BD08B582694369934201D1826861 -:1038500082B98268013282605A1C426119704269E1 -:1038600003699A4201D3C36843610021FFF7F0F96D -:10387000002008BD4FF0FF3008BD000070B52023C8 -:1038800004460E4683F31188A568A5B1A368A26912 -:10389000013BA360531CA36115782269934224BFA6 -:1038A000E368A361E3690BB120469847002383F3E3 -:1038B0001188284670BD31462046FFF7B9F9002827 -:1038C000E2DA85F3118870BD2DE9F74F05460F4602 -:1038D00090469A46D0F81C90202686F311884FF027 -:1038E000000B144664B1224639462846FFF740FFD4 -:1038F000034668B951462846FFF79AF90028F1D0E7 -:10390000002383F31188A8EB040003B0BDE8F08F17 -:10391000B9F1000F03D001902846C847019B8BF3F3 -:103920001188E41A1F4486F31188DBE7C361009B0A -:10393000C160816141611144006040608260016149 -:1039400003627047F8B504460E461746202383F3FA -:103950001188A568A5B1A368013BA36063695A1CDF -:1039600062611E70236962699A4224BFE3686361E1 -:10397000E3690BB120469847002080F31188F8BD19 -:1039800039462046FFF754F90028E2DA85F311881A -:10399000F8BD00008369426910B59A4201D182687E -:1039A0007AB98268013282605A1C82611C7803698C -:1039B0009A4201D3C36883610021FFF749F9204689 -:1039C00010BD4FF0FF3010BD2DE9F74F05460F46F3 -:1039D00090469A46D0F81C90202686F311884FF026 -:1039E000000B144664B1224639462846FFF7EEFE26 -:1039F000034668B951462846FFF71AF90028F1D066 -:103A0000002383F31188A8EB040003B0BDE8F08F16 -:103A1000B9F1000F03D001902846C847019B8BF3F2 -:103A20001188E41A1F4486F31188DBE71FB51C4692 -:103A3000094B05461B68D86852B1084B8DE80A004F -:103A400002922B4622460649FDF7AEFC00F042F8F2 -:103A5000044B1A46F2E700BF14080020F4400008A7 -:103A600001410008E73B000810B5013902449042CB -:103A700001D1002010BD10F8013B11F8014FA34205 -:103A8000F5D0181B10BD00002DE9F8430746884605 -:103A900091461E468BB10D46A8EB0500B54207EBDB -:103AA000000402D20020BDE8F88332464946204691 -:103AB000FFF7DAFF18B1013DEEE7BDE8F8832046D5 -:103AC000BDE8F883034611F8012B03F8012B002A07 -:103AD000F9D1704708B5062000F02CF80120FFF757 -:103AE0000DF900001F2938B504460D4604D91623E8 -:103AF00003604FF0FF3038BD426C12B152F82130F4 -:103B00004BB9204600F030F82A4601462046BDE871 -:103B1000384000F017B8012B0AD0591C03D11623E6 -:103B20000360012038BD0024284642F8254098470C -:103B3000002038BD024B01461868FFF7D3BF00BF15 -:103B40001408002038B50023064C054608461146E7 -:103B50002360FFF7D7F8431C02D1236803B12B6021 -:103B600038BD00BF50240020FFF7C6B840A2E4F1E2 -:103B7000646891064E6F20617070207369670A0057 -:103B8000426164206677206C656E677468202575D5 -:103B90000A0042616420626F6172645F696420257B -:103BA000752073686F756C642062652025750A0046 -:103BB0004261642061707020435243203078253088 -:103BC00038783A3078253038782030782530387891 -:103BD0003A3078253038780A00476F6F642066697C -:103BE000726D776172650A007265636569766564F6 -:103BF0005F756E697175655F69645F6C656E203CA9 -:103C00002055415643414E5F50524F544F434F4C05 -:103C10005F44594E414D49435F4E4F44455F4944CF -:103C20005F414C4C4F434154494F4E5F554E4951B3 -:103C300055455F49445F4D41585F4C454E47544898 -:103C4000002E2E2F2E2E2F546F6F6C732F41505F2E -:103C5000426F6F746C6F616465722F63616E2E6367 -:103C6000707000616C6C6F63617465645F6E6F642B -:103C7000655F6964203C3D20313237006F72672EEA -:103C80006172647570696C6F742E61705F706572BB -:103C90006970685F5A75626178474E53530000003F -:103CA000766F69642068616E646C655F616C6C6FCF -:103CB000636174696F6E5F726573706F6E73652890 -:103CC00043616E617264496E7374616E63652A2C20 -:103CD0002043616E61726452785472616E736665DE -:103CE000722A290063616E617264496E6974000012 -:103CF00063616E6172645365744C6F63616C4E6F87 -:103D0000646549440000000063616E61726448614B -:103D10006E646C6552784672616D650063616E61B8 -:103D200072644465636F64655363616C6172000023 -:103D300063616E617264456E636F64655363616C49 -:103D400061720000696E6372656D656E74547261B4 -:103D50006E73666572494400656E7175657565546C -:103D6000784672616D65730070757368547851752B -:103D70006575650070726570617265466F724E653B -:103D800078745472616E736665720000636F707947 -:103D90004269744172726179000000006465736366 -:103DA00061747465725472616E7366657250617984 -:103DB0006C6F61640000000066726565426C6F6341 -:103DC0006B0000006269745F6C656E677468203E0A -:103DD00020300072656D61696E696E675F6269743B -:103DE00073203E203000696E7075745F6269745F85 -:103DF0006F6666736574203E3D20626C6F636B5F17 -:103E00006269745F6F666673657400626C6F636B82 -:103E10005F656E645F6269745F6F66667365742068 -:103E20003E20626C6F636B5F6269745F6F6666737E -:103E300065740072656D61696E696E675F62697451 -:103E40005F6C656E677468203C3D2072656D6169CA -:103E50006E696E675F6269747300696E7075745F16 -:103E60006269745F6F6666736574203C3D2074728E -:103E7000616E736665722D3E7061796C6F61645F0F -:103E80006C656E202A2038006F75747075745F62DF -:103E900069745F6F6666736574203C3D203634003C -:103EA00072656D61696E696E675F6269745F6C658A -:103EB0006E677468203D3D20300028726573756C14 -:103EC00074203E2030292026262028726573756CC8 -:103ED00074203C3D20363429202626202872657324 -:103EE000756C74203C3D206269745F6C656E67740C -:103EF0006829000064657374696E6174696F6E206F -:103F0000213D202828766F6964202A2930290076EF -:103F1000616C756520213D202828766F6964202A10 -:103F2000293029006F66667365745F776974686904 -:103F30006E5F626C6F636B203C2028333255202DFE -:103F4000205F5F6275696C74696E5F6F666673652A -:103F5000746F66202843616E61726442756666659F -:103F600072426C6F636B2C206461746129290000BC -:103F70006F75745F696E7320213D202828766F6904 -:103F800064202A29302900007372635F6C656E20FB -:103F90003E203055000000002863616E5F69642098 -:103FA0002620307831464646464646465529203D2D -:103FB0003D2063616E5F696400000000616C6C6F9E -:103FC0006361746F722D3E73746174697374696395 -:103FD000732E63757272656E745F75736167655F6A -:103FE000626C6F636B73203E203000007472616EF0 -:103FF000736665725F696420213D202828766F69A9 -:1040000064202A293029000073746174652D3E6292 -:1040100075666665725F626C6F636B73203D3D20F1 -:104020002828766F6964202A293029002E2E2F2E09 -:104030002E2F6D6F64756C65732F6C696263616E92 -:104040006172642F63616E6172642E6300697465CE -:104050006D2D3E6672616D652E646174615F6C6585 -:104060006E203E20300000006D61696E000000008F -:1040700088400008D01A0020801B002001000000AA -:10408000BD3000080000000069646C65000000009D -:104090000C880000887B888888588828800E00005B -:1040A00088181118987B8888000000008888888804 -:1040B00088888888040000008882888888888888A2 -:1040C00000000000888888888888888800000000B0 -:1040D000E1340008CD34000809350008F534000843 -:1040E00001350008ED340008D9340008C534000853 -:1040F000153500082C2066756E6374696F6E3A2062 -:1041000000617373657274696F6E202225732220BB -:104110006661696C65643A2066696C652022257366 -:10412000222C206C696E65202564257325730A0096 -:1041300090C0FF7F01000000FFFFFFFF6400000050 -:1041400000000000FE2A0100D20400001808002030 -:10415000000000000000000000000000000000005F -:10416000000000000000000000000000000000004F -:10417000000000000000000000000000000000003F -:10418000000000000000000000000000000000002F +:10000000000200207904000809220008AD21000840 +:10001000ED210008AD210008CD2100087B04000877 +:100020007B0400087B0400087B040008BD30000846 +:100030007B0400087B0400087B040008B13C000836 +:100040007B0400087B0400087B0400087B04000894 +:100050007B0400087B040008E5390008113A000819 +:100060003D3A0008693A0008953A00087B04000808 +:100070007B0400087B0400087B0400087B04000864 +:100080007B0400087B0400087B040008F51D0008C1 +:10009000211E0008311E00087B040008C13A000838 +:1000A0007B0400087B0400087B0400087B04000834 +:1000B0007B0400087B0400087B0400087B04000824 +:1000C0007B0400087B0400087B0400087B04000814 +:1000D0007B0400087B0400087B0400087B04000804 +:1000E000293B00087B0400087B0400087B0400080F +:1000F0007B0400087B0400087B0400087B040008E4 +:100100007B0400087B0400087B0400087B040008D3 +:100110007B0400087B0400087B0400087B040008C3 +:100120007B0400087B0400087B0400087B040008B3 +:100130007B0400087B0400087B0400087B040008A3 +:100140007B0400087B0400087B0400087B04000893 +:100150007B0400087B0400087B0400087B04000883 +:100160006112000800000000000000000000000014 +:1001700053B94AB9002908BF00281CBF4FF0FF310E +:100180004FF0FF3000F076B9ADF1080C6DE904CE08 +:1001900000F006F8DDF804E0DDE9022304B0704762 +:1001A0002DE9F047089E0D4604468846002B4DD1A8 +:1001B0008A42944668D9B2FA82F252B101FA02F345 +:1001C000C2F1200120FA01F10CFA02FC41EA030815 +:1001D00094404FEA1C41B8FBF1F71FFA8CFE01FB7B +:1001E000178807FB0EF0230C43EA084398420AD90C +:1001F0001CEB030307F1FF3580F01E81984240F2AB +:100200001B81023F63441B1AB3FBF1F001FB103367 +:1002100000FB0EFEA4B244EA0344A6450AD91CEB37 +:10022000040400F1FF3380F00981A64540F2068105 +:10023000644402380021A4EB0E0440EA07401EB1DA +:100240000023D440C6E90043BDE8F0878B4208D9BB +:10025000002E00F0EE800021C6E900050846BDE84A +:10026000F087B3FA83F100294AD1AB4202D382422C +:1002700000F2FC80841A65EB030301209846002EEF +:10028000E2D0C6E90048DFE702B9FFDEB2FA82F247 +:10029000002A40F09180A1EB0C0001214FEA1C479D +:1002A0001FFA8CFEB0FBF7F307FB1300250C45EAA1 +:1002B00000450EFB03F0A84208D91CEB050503F12D +:1002C000FF3802D2A84200F2CE8043462D1AB5FB79 +:1002D000F7F007FB10550EFB00FEA4B244EA0544FC +:1002E000A64508D91CEB040400F1FF3502D2A6454F +:1002F00000F2B6802846A4EB0E0440EA03409EE7D5 +:10030000C1F120078B4022FA07FC4CEA030C25FAC6 +:1003100007FA4FEA1C49BAFBF9F820FA07F309FB80 +:1003200018AA8D401FFA8CFE1D4300FA01F308FB4A +:100330000EF02C0C44EA0A44A04202FA01F20BD956 +:100340001CEB040408F1FF3A80F08880A04240F2E0 +:100350008580A8F102086444241AB4FBF9F009FB73 +:10036000104400FB0EFEADB245EA0444A64508D990 +:100370001CEB040400F1FF356CD2A6456AD90238A3 +:10038000644440EA0840A0FB0295A4EB0E04AC4292 +:10039000C846AE4656D353D0002E69D0B3EB080200 +:1003A00064EB0E0422FA01F304FA07F71F43CC4072 +:1003B000C6E90074002147E70CFA02FCC2F12001F3 +:1003C00025FA01F34FEA1C4720FA01F195400D434D +:1003D000B3FBF7F107FB11331FFA8CFE280C40EA40 +:1003E000034001FB0EF3834204FA02F408D91CEB2C +:1003F000000001F1FF382FD283422DD90239604429 +:10040000C01AB0FBF7F307FB1300ADB245EA004595 +:1004100003FB0EF0A84208D91CEB050503F1FF38D9 +:1004200016D2A84214D9023B6544281A43EA014176 +:1004300038E73146304607E72F46E4E61846F9E646 +:100440004B45A9D2B9EB020865EB0C0E0138A3E7C6 +:100450004346EAE7284694E74146D1E7D0467BE7A2 +:100460006444023847E7023B65442FE7084606E745 +:100470003146E9E6704700BF02E000F000F8FEE711 +:1004800072B6284880F30888274880F309882748EF +:100490004EF60851CEF200010860022080F3148865 +:1004A000BFF36F8F03F026FA03F002FA03F024FA89 +:1004B0004FF055301E491B4A91423CBF41F8040B96 +:1004C000FAE71C49184A91423CBF41F8040BFAE78D +:1004D00019491A4A1A4B9A423EBF51F8040B42F886 +:1004E000040BF8E700201749174A91423CBF41F836 +:1004F000040BFAE703F0E0F903F000FA134C144D93 +:10050000AC4203DA54F8041B8847F9E700F03CF8E2 +:10051000104C114DAC4203DA54F8041B8847F9E73C +:1005200003F0C8B900020020000800200000000805 +:10053000000100200002002068410008000800209F +:1005400080080020800800206C2000206001000846 +:100550006401000864010008640100082DE9F04FFF +:10056000C1F80CD0C3689D46BDE8F08F002383F32B +:1005700011882846A047002002F048FFFEE702F05D +:10058000C1FE00DFFEE700002DE9F0412F4A53686D +:1005900023F0E06343F0905343F48043536003F04F +:1005A00021F9074603F070F90546B8BB284B9F4276 +:1005B00034D001339F4234D0264B27F0FF029A42B9 +:1005C00033D1F8B200F066FAA84642F2107400F097 +:1005D0006BFC08B10024A04600F062FA064640B366 +:1005E0004CBB464635B11C4B9F4203D0002403F060 +:1005F00043F92646002003F0FFF80EB100F02EF874 +:1006000000F0B0FC00F03EFE01F006FE0546ACB97D +:1006100000F0EEFC012002F0FFFEF8E7A8460024FF +:10062000D5E704464FF00108D1E7804641F288340F +:10063000CDE70446D6E74FF47A74D3E701F0ECFD3A +:10064000431BA342E4D900F009F8DDE700000140B4 +:10065000010007B0000008B0263A09B038B51D4ABD +:100660001D4B1968013134D004339342F9D11B4C2E +:10067000194DD4F80428AA422BD3194B9B6803F1D7 +:10068000006303F508439A4223D203F0C9F803F04C +:10069000DBF8002000F01CFE0220124B187000F066 +:1006A00053FE114BDA690022DA61D96999699A61BE +:1006B0009B6972B64FF0E023C3F8085DD4F80038A8 +:1006C000D4F80428202181F311889D4683F30888FB +:1006D000104738BD20880008008800080080000806 +:1006E00000080020800800200010024049F2690044 +:1006F000084A136899B21B0C00FB013344F25061A5 +:100700001360054B186882B2000C01FB02001860F0 +:1007100080B27047180800201408002010B5044665 +:100720000021102200F02CFE034B03CB20606160FF +:100730001868A06010BD00BFE8F7FF1F2DE9F04367 +:10074000BBB001F069FD40F2ED22204DAB68C31A49 +:10075000934232D906AF2B4628220021A8603846A2 +:1007600002F066FA05F10E0000F002FE00260446D3 +:100770005FFA80F905F10E08F3B2F100994501F135 +:10078000280107D908EB06030822384602F050FA80 +:100790000136F1E708230122CDE902320C4B053482 +:1007A00001933023A4B20093CDE9047405A3D3E9E7 +:1007B0000023297B074802F051F83BB0BDE8F083E5 +:1007C000AFF3008078F6339F93CACD8D981D00203B +:1007D000A51D00209C18002070B50D4614461E462D +:1007E00001F0D2FF50B9022E10D1012C0ED112A36C +:1007F000D3E900230120C5E9002307E0282C10D00D +:1008000005D8012C09D0052C0FD0002070BD302C4C +:10081000FBD10BA3D3E90023ECE70BA3D3E900231F +:10082000E8E70BA3D3E90023E4E70BA3D3E9002314 +:10083000E0E700BFAFF30080401DA12026812A0B16 +:1008400078F6339F93CACD8D9E6AC421818A46EE85 +:1008500026417272DF25D7B7F017304A39059E5608 +:1008600038B50D460446034620222846002102F0F2 +:10087000DFF922792346032A28BF0322284603F8FA +:10088000042F2021022202F0D3F962792346072A9D +:1008900028BF0722284603F8052F2221032202F051 +:1008A000C7F9A2792346072A28BF0722284603F85A +:1008B000062F2521032202F0BBF928461022282109 +:1008C00004F1080302F0B4F9382038BD2DE9F04FE7 +:1008D0000024ADF5037D10AE40F2751280460F4640 +:1008E00024A82146239400F04BFD2146482230469F +:1008F00000F046FD01F090FC4FF47A72B0FBF2F08C +:10090000544B23AD186093E80700012386E80700E5 +:100910000DF162003382FFF701FF4EF6035333847B +:1009200007AB18464C4903F039FB212229463064B5 +:10093000304686F83C20FFF793FF08220446014624 +:1009400014AB284602F074F908222846A1180DF1CC +:10095000510302F06DF9082228460DF1520304F10B +:10096000100102F065F92022284615AB04F11801A8 +:1009700002F05EF94022284616AB04F1380102F07D +:1009800057F90822284618AB04F1780102F050F913 +:10099000082228460DF1610304F1800102F048F9B4 +:1009A00004F1880A0DF1620904F5847B4B46514637 +:1009B000082228460AF1080A02F03AF9D34509F15B +:1009C0000109F3D10822594628461DAB02F030F93F +:1009D0004FF0000904F5887496F834304B450AD975 +:1009E000B36B21464B440822284602F021F9083413 +:1009F00009F10109F0E74FF0000996F83C3004EBEB +:100A0000C9014B4508D9336C08224B44284602F0F3 +:100A10000FF909F10109F0E700230393BB7E0731C9 +:100A2000029307F1190301930123C1F3CF01CDE92B +:100A300004510093404605A3D3E90023F97E01F059 +:100A40000DFF0DF5037DBDE8F08F00BF9E6AC42148 +:100A5000818A46EE84080020CC3F000810B50A4B7E +:100A60000A4A1A6093F8602442B9D3F85C442CB166 +:100A7000204601F067FA204603F028F9BDE810404F +:100A8000034801F05FBA00BFC8180020B440000856 +:100A9000101D0020014B1870704700BF9008002007 +:100AA000F0B5334B85B01C7B34B10E22314B1A812B +:100AB0000024204605B0F0BD2F4A02AB10685168F3 +:100AC00003C308232D492E480DEB030203F050F910 +:100AD000054630B90A22274B2A481A8101F0B0F99D +:100AE000E6E70169B1F55E3F06D90B22214B2648A6 +:100AF0001A8101F0A5F9DCE740F2ED32438B934215 +:100B000007D00C201B4908811946204801F098F9AC +:100B1000CFE71F4A024402F11003994204D2102287 +:100B2000144B1C481A81E4E710398E1A20461449E8 +:100B300001F078FB07463246204605F1180101F026 +:100B400071FBAB689F4202D1EB6898420AD00D223C +:100B5000084B1A8100903B46D5E902120E4801F07D +:100B60006FF9A5E70D4801F06BF90124A1E700BF7B +:100B7000981D00208408002081400008DC770300D5 +:100B800000880008F03F0008FC3F00080E40000805 +:100B90000878FFF72C400008494000087240000820 +:100BA0002DE9F04FADB006AF80460C4601F0ECFDEC +:100BB0000546002859D1237E022B1AD1E38A012B46 +:100BC00017D101F029FB0646FFF790FD4FF4C873DB +:100BD000B0FBF3F202FB1300DFF8B49206F51676D1 +:100BE00080B2E37E0644C9F8006033B90022A94B05 +:100BF0001A709C37BD46BDE8F08FA38AEEB2013B68 +:100C0000B34205F101050BD93B1D1E44E900002349 +:100C100008222046009601F0F80101F0CBFEECE737 +:100C200007F11400FFF77AFD324607F11401381D71 +:100C300003F08EF803460028D8D10F2E08D8954B24 +:100C40001E70D9F80030A3F51673C9F80030D0E74C +:100C5000FA1CF870014600922046072201F0AAFE15 +:100C60004046F97801F088FDC3E7E38A282B26D0B7 +:100C700010D8012B1ED0052BBBD1BFF34F8F864957 +:100C8000864BCA6802F4E0621343CB60BFF34F8F18 +:100C900000BFFDE7302BACD1637E814D01336A7B11 +:100CA000DBB29342E94603D1E27E2B7B9A4265D0C8 +:100CB000CD469EE721464046FFF708FE99E7A38A06 +:100CC000013B9BB2C92B94D8754D2E7B26BB05F1F9 +:100CD0000C030093082233463146204601F06AFE99 +:100CE000731CF2B2D9001E46A38A013B9A4205DA70 +:100CF0000E322A44009200230822EEE7002300224D +:100D0000C5E900230023AB6085F8D730C5F8D8309B +:100D10002B7B0BB9E37E2B73002507F11406082209 +:100D2000294630463B1DC7E90155FD6001F080FFB3 +:100D30003B7A05F10109AB424FEAC90107D9FB68CB +:100D400008222B44304601F073FF4D46F0E70023A4 +:100D5000C1F3CF01E07ECDE904610393A37E193492 +:100D60000293282301460093404647A3D3E900237A +:100D7000019401F073FDFFF7E1FC3AE74FF0000842 +:100D800007F11403A7F814801022009341460123B1 +:100D9000204601F00FFEA68A023EB6B2F31C9B105D +:100DA0009B000733DB08A9EBC3039D460DF1180A2E +:100DB0001FFA88F34FEAC801B34201F110010AD2C9 +:100DC0000AEB0803009308220023204601F0F2FDFD +:100DD00008F10108ECE795F8D70000F083FAD5F8A0 +:100DE000D83004461BB995F8D70000F08BFAD5F837 +:100DF000D83033449C4204D295F8D700013000F03B +:100E000081FA4FF000084FEA960B1FFA88F18B45E4 +:100E1000D5E9003209D90AEB880103EB88000122E9 +:100E200000F0B6FA08F10108EFE7F31842F100020A +:100E3000C5E90032D5F8D83095F8D70006EB03089D +:100E4000C5F8D88000F04EFA804509D395F8D73020 +:100E5000D5F8D8000133001B85F8D730C5F8D80085 +:100E6000FF2E08D800232B7300F05EFAFFF718FE60 +:100E700008B1FFF7F3FB2B680A4A9B0A0133138181 +:100E80000023AB6014E700BF26417272DF25D7B79D +:100E9000981800209518002000ED00E00400FA05E5 +:100EA000981D00208408002030B54FF00054244BDA +:100EB000226885B09A4207D002F0F0FC0446A8B937 +:100EC0000024204605B030BD627D1E4B1E481A70BE +:100ED000237DC92203731D490E3000F03FFA2046DE +:100EE000E022002100F04CFA0124EAE7184A194DEB +:100EF000D36943F00073D361AA6D174B9A42DFD1D7 +:100F00002B6E013B7E2BDBD8144A01AB07CA83E86A +:100F100007001846032101F09BF96B6D83424FF0E7 +:100F20000003CDD12A6D8A4203BFAB652A6E054B03 +:100F30001C4601BF1A70EA6D094B1A60C1E700BF79 +:100F40009AAD44C590080020981D0020160000208E +:100F500000100240006600405041A0B058660040BA +:100F600010080020022337B5184D01226B71184B71 +:100F70001848196800F036FE00230193164B1749F4 +:100F800000934FF48052164B164801F0CDFB164BE0 +:100F9000197811B1134801F0EFFB01F03DF9044657 +:100FA000FFF7A4FB4FF4C873B0FBF3F202FB13038B +:100FB00004F516709BB218440C4B186002F064FCE8 +:100FC00008B10F232B8103B030BD00BF840800207F +:100FD00010080020C8180020D90700089408002035 +:100FE000A10B00089C1800209008002098180020F1 +:100FF0002DE9F04F0FF26029D9E900898A4C93B0AE +:101000008A4E8B4F204601F08DFC034660B30025CD +:10101000CDE90F550E95ADF84450027BDFF814A2D0 +:101020008DF84420996840680FAA03C21B6843F0FA +:1010300000430E9301F0F2F8821941F100033846A3 +:1010400000950EA900F014FAA84205DD204601F033 +:101050006DFC8AF80050D5E79AF80030072B00F2B3 +:10106000B78001338AF8003000230BAE704FDFF8F1 +:10107000C8A10A93ADF834300B9373604FF0000BA6 +:10108000002200230125CDE9002338465B460DF1FF +:101090001D0207A98DF81C508DF81DB000F054FDFD +:1010A0009DF81C30002B40F09780204601F06CFB2F +:1010B0000646002848D101F0AFF8DFF880A1DAF841 +:1010C0000030984240D301F0A7F80746FFF70EFB27 +:1010D0004FF4C873B0FBF3F202FB130007F5167769 +:1010E00080B20744CAF80070554F0EA897F800B0B8 +:1010F000BBF1000F14BF33462B46CBF1100A5FFA49 +:101100008AFA8DF82830FFF709FBBAF1060F28BFDD +:101110004FF0060A0EAB03EB0B0152460DF129000E +:1011200000F01CF90AAB039318230AF101020293A1 +:10113000444BD2B2CDE900530492204638A3D3E900 +:10114000002301F023FB3E7001F066F83E4A3F4D5C +:101150001368C31AB3F57A7F2FD3106001F05EF8DD +:1011600002460B46204601F0EBFB204601F00CFB4B +:1011700018B32B7B364E002B14BF0323022373714D +:1011800001F04AF84FF47A73B0FBF3F00EAF306021 +:1011900039463046FFF764FB182302932D4B073086 +:1011A000019340F25513C0F3CF00CDE903700093D3 +:1011B00042464B46204601F0E9FA2B7B2BB1FFF764 +:1011C000BDFA2B7B002B7FF41BAF13B0BDE8F08F73 +:1011D000204601F0ABFB47E7DAF80C30594683F0C4 +:1011E0000803CAF80C3010220EA800F0C9F80DF15F +:1011F0001E0308AA0AA9384600F032FA96E803004E +:101200000FAB83E803009DF8343020468DF844305E +:101210000A9B0EA90E93DDE9082301F051FD2DE78D +:10122000401DA12026812A0B9C18002040420F005F +:10123000C81800207D1E0020000C014098180020D6 +:101240009518002094180020781E0020981D00207A +:10125000840800207C1E0020F1C6A7C1D068080FBA +:1012600008B5054800F092FABDE808400020034A9E +:10127000034902F025BD00BFC8180020B81E002099 +:101280005D0A000870B502F07DF900250E4C0F4E86 +:1012900020803068238883420CD8002520880138BC +:1012A00002F06CF923880544013BB5F5805F23808B +:1012B000F4D370BD02F062F9336805440133B5F52B +:1012C000084F3360E5D3E8E7AC1E0020801E002005 +:1012D00002F0F6B900F10060920000F5084002F05B +:1012E00091B90000054B1A68054B1B889B1A834275 +:1012F00002D9104402F042B900207047801E00203D +:10130000AC1E002038B50446064D2868204402F083 +:101310003BF928B928682044BDE8384002F046B9B6 +:1013200038BD00BF801E0020064991F8243033B13B +:1013300000230822086A81F82430FFF7CBBF012080 +:10134000704700BF841E0020022802BF4FF4002215 +:10135000014B1A61704700BF000C0140002310B51B +:10136000934203D0CC5CC4540133F9E710BD0000B4 +:1013700003460246D01A12F9011B0029FAD1704720 +:1013800003460244934202D003F8011BFAE7704778 +:101390002DE9F8431F4D144695F82420074688464A +:1013A00052BBDFF870909CB395F824302BB9202203 +:1013B000FF2148462F62FFF7E3FF95F824004146DE +:1013C000C0F10802A24228BF224605EB8000D6B237 +:1013D0009200FFF7C3FF95F82430A41B1E44F6B219 +:1013E000082E17449044E4B285F82460DBD1FFF75F +:1013F0009BFF0028D7D108E02B6A03EB82038342CE +:10140000CFD0FFF791FF0028CBD10020BDE8F883B3 +:101410000120FBE7841E0020202383F3118862B69D +:1014200070470000002383F3118862B67047000004 +:1014300010B4026854681A46234610BC18470000CE +:10144000012070470020704700207047704700005F +:1014500070470000002070470E20704790F8C804C5 +:10146000C0F340007047000090F9C90470470000C5 +:101470002DE9F0410C681E4614F00054BDF81870B8 +:101480006AD10B7B082B67D8FFF7C6FF4569AB68AD +:101490005B010CD4AB681B0108D4AC6814F0805419 +:1014A00058D1FFF7BFFF2046BDE8F08101240B684B +:1014B00004F1180C002BBABFDB0043F004035B05FA +:1014C0004FEA0C1C45F80C300B684FEA041C13F073 +:1014D000804F1CBF05EB0C0EDEF88031AC441CBF06 +:1014E00043F00203CEF880310B7B05EB0415CCF8FA +:1014F00084318B68C5F88C314B68C5F888310D464E +:10150000DCF8803143F00103CCF8803100EB441368 +:10151000C3F86824C3F86C6401F10C0C03F58E6306 +:1015200055F804EB654543F804EBF9D12D882434D4 +:101530001D8000EB4414257907F0030325F00B050B +:101540002B432371FFF76EFF33460697BDE8F0414A +:1015500000F098BC0224AAE74FF0FF30A4E7000097 +:1015600038B50446D0F85C040D4600F01FFD1F2876 +:101570000AD920222946D4F85C0400F08DFDA0F1A0 +:1015800020035842584138BD0020FCE708B5FFF75A +:1015900043FFD0F85C0400F0DFFCBDE80840FFF733 +:1015A00041BF000000220260828142608260704779 +:1015B0000022002310B5C0E9002300230446038164 +:1015C0000C30FFF7EFFF204610BD0000F0B590F89B +:1015D000C8340D4613F0040FC3F3800108BF114651 +:1015E00005F1240661F3820380F8C83400EB46134A +:1015F0001B790446D80789B02DD572B319072CD4AE +:1016000004EB45156846FFF7D3FF05F58E6303AA83 +:1016100005F58F65174618685968083303C7AB424C +:101620003A46F7D11868694638609B882046BB80E7 +:10163000DDE90E23CDE900230123ADF8083023684E +:101640001B6C984704EB461423791A075CBF43F0E0 +:101650000803237101E0002AF4D109B0F0BD0000B5 +:101660002DE9F047054688B068469A468846914677 +:10167000FFF7D2FEFFF79CFFD5F85C0400F07EFC7C +:101680001F282AD920226946D5F85C0400F082FD83 +:10169000202822D1444603AE05AB374603CF9F42F4 +:1016A000206061603E4604F10804F6D13868414686 +:1016B0002060BB882846A380DDE90023C9E9002318 +:1016C000BDF808304A46AAF80030FFF7ABFE534693 +:1016D00008B0BDE8F04700F0C3BB0020FFF7A2FE52 +:1016E00008B0BDE8F087000000232DE9F04704466C +:1016F000C0E90133224B0E4640F8183BFFF752FF7A +:1017000004F1480704F12800FFF752FF3D4604F5B5 +:10171000896828462035FFF74BFF4545F9D14FF43E +:101720008063C4F84874C4F84C34002701234FF098 +:1017300000084FF00009C4F85C54C4F85074C4F8B1 +:10174000547484F8583484F8603404F5916504F5D1 +:101750009D6A45E90889A5F11800FFF723FF2035A8 +:1017600045F8287C5545F4D184F8C96416B105487C +:1017700000F04CFD044B20466361BDE8F08700BFDC +:10178000B44000088C4000080064004010B50446D6 +:10179000034B19784A1C1A70FFF7A6FF204610BDAC +:1017A000B41E00202DE9F04300294FD0284F294BCB +:1017B000B7FBF1F499428CBF0A231123B4FBF3FC6D +:1017C000581E03FB1C43C5B22BB102280346F5D8B3 +:1017D0000020BDE8F0830CF1FF36B6F5806FF7D23C +:1017E0004FF47A74C5EBC50E0EF103034FEAE3091B +:1017F00009FB0444C3F3C703E81AC0B209F10108A6 +:101800008044B4FBF8F4B4F5617FC2BF0EF1FF333E +:10181000C3F3C703E81A03F10104C8BFC0B2E4B2BE +:1018200004440CFB04F4B7FBF4F4A142D0D1013B17 +:10183000DBB20F2BCCD80138C0B20728C8D80021A2 +:101840001071168001209170D370C2E70846C0E77E +:10185000005125023F420F0070B505460E464FF479 +:101860007A746B6901205B6803F00103B34204D012 +:1018700001F0D2FD013CF4D1204670BD30B5426983 +:10188000936913F0700F16D000230B4C936103F192 +:10189000240200EB421211794D0709D5890707D5BB +:1018A000416954F823508D60117941F004011171A0 +:1018B0000133032BEBD130BDA040000873B51D46AA +:1018C000436916469A680446D20709D501219A68E9 +:1018D0009960C2F340020021CDE90065FFF776FE72 +:1018E00063699A68D1050BD54FF480719A682046D8 +:1018F0009960C2F340220121CDE90065FFF766FE41 +:1019000063699A68D2030BD54FF480319A682046F8 +:101910009960C2F340420221CDE90065FFF756FE0F +:10192000204602B0BDE87040FFF7A8BFF8B50446F6 +:10193000466900296AD106F10C073868800768D02B +:10194000386806EB01104FEA011CD0F8B011D0F84E +:10195000B051490746BFED0845F000456D0DA56142 +:10196000D0F8B011890744BF45F08045A561D0F893 +:10197000B40106EB0C0100F00F0084F82400D1F84C +:10198000B80104F124052077D1F8B801000A607786 +:10199000D1F8B801000CA077D1F8B801000EE077BB +:1019A000D1F8BC0184F82000D1F8BC01000A84F809 +:1019B0002100D1F8BC01000C84F82200D1F8BC1140 +:1019C00004F13400090E84F823103821396004F141 +:1019D000180151F8046BA94240F8046BF9D1098849 +:1019E0000180C4E90A2300232146238651F8283BBD +:1019F00020461B6C984794F8C834204643F00403F3 +:101A000084F8C834BDE8F840FFF738BF06F1100786 +:101A100093E7F8BD10B5044600F000FC02460B4603 +:101A200052EA030102D0013A63F100030449086855 +:101A300020B12146BDE81040FFF778BF10BD00BFC0 +:101A4000B01E0020F8B500211E46FFF7E5FC124F3E +:101A500000F58D6501F1240400EB4414237913F0A3 +:101A6000040F0FD1DB060DD5D5E900C39445B34172 +:101A700008D2436957F821C0C3F808C0237943F05E +:101A8000040323710131032905F12005E2D1BDE8EA +:101A9000F840FFF7C7BC00BFA040000808B5FFF73B +:101AA000BBFCFFF7EBFEBDE80840FFF7BBBC000046 +:101AB000F8B54369044698680E4600F0E050B0F16E +:101AC000E05F1DD0D8B1FFF7A7FC002504F58E67B5 +:101AD00004EB451393F884341A0706D50135032D1A +:101AE00007F12007F4D1012007E05B07F6D439465F +:101AF000304600F001FA0028F0D1FFF793FCF8BD62 +:101B00000120FCE708B5FFF787FCD0F85C0400F083 +:101B100035FAFFF787FC43090CBF0120002008BD00 +:101B2000F8B51D46002313700F4606461446FFF70E +:101B3000E9FF80F00100387025B129463046FFF7F3 +:101B4000B7FF2070F8BD0000F8B50C4615461E46DC +:101B5000074600F063FB0B462178024609B9287856 +:101B600050B13846FFF76EFFFFF798FF33462A461D +:101B70002146FFF7D5FF0120F8BD000010B5FFF7A3 +:101B80004BFC174B0446DA6942F00072DA611A69BD +:101B900042F000721A611A6922F000721A61FFF7AE +:101BA00041FC90F8C834DB0718D4B9B102211320E6 +:101BB000FFF732FC01F0D2FA0221142001F0CEFA34 +:101BC0000221152001F0CAFA94F8C83443F0010349 +:101BD00084F8C834BDE81040FFF724BC10BD00BF36 +:101BE000001002402DE9F04790F8C9340446012B5B +:101BF0000F46154688B000F2F9807D4E56F8232036 +:101C00000AB946F82300D6F80090E7602574B9F1C8 +:101C1000000F09D14FF49A6002F05AF88046494605 +:101C2000FFF762FDC6F8008094F8C934012B5CD040 +:101C30004FF0000801212046FFF7A0FFFFF7ECFB63 +:101C4000626901211368204623F002031360626970 +:101C5000136843F0010313606369C3F81480FFF74E +:101C6000E1FBFFF7F9FD002800F08180D4F85C0467 +:101C700000F072F9A14604F1600A202200216846B2 +:101C8000FFF77EFB02A8FFF78DFC6A46CDF81880AF +:101C900009F58D630DF1180C164603CE66451860E4 +:101CA0005960324603F10803F6D1306809F1200982 +:101CB00018603279CA451A71DFD1002694F8C83409 +:101CC0006A466FF3820384F8C83439462046ADF87B +:101CD0000060ADF802608DF80460FFF763FD636992 +:101CE000C0B94FF400421A6011E0306803685B6BC2 +:101CF0009847014600289BD13068FFF73FFF3068C6 +:101D00002A46036839465B689847002890D108B096 +:101D1000BDE8F0876122022D0CBF4FF00041002189 +:101D20001A609DF802309DF803201B06120402F48D +:101D3000702203F040731343BDF800202046C2F325 +:101D4000090213439DF80420120502F4E002134334 +:101D500062690B43D3611322636931465A61626938 +:101D6000136823F001031360FFF776FD08B9636978 +:101D7000B7E794F8C93493BB6169D1F8002242F007 +:101D80000102C1F800226169D1F8002222F47C52DC +:101D900022F00E02C1F800226169D1F8002242F45B +:101DA0006062C1F8002241F6FF716269C2F8143224 +:101DB0006269C2F804326269C2F80C126269C2F840 +:101DC00040326269C2F8443201226369C3F81C22BE +:101DD0006269D2F8003223F00103C2F8003294F8AD +:101DE000C83443F0020384F8C83490E700208EE73B +:101DF000B01E002008B500F011FA02460B4652EA68 +:101E0000030102D0013A63F100030449086808B1F4 +:101E1000FFF754FDBDE8084001F07EB9B01E002078 +:101E200008B50020FFF7F6FDBDE8084001F074B9E1 +:101E300008B50120FFF7EEFDBDE8084001F06CB9E0 +:101E40000FB4002004B0704713B56C4684E8060058 +:101E5000031D94E8030083E80500012002B010BDD3 +:101E6000F8B586680D4656B11B885B0707D4D0E9E4 +:101E70000037DB6B98472A46C1B23846B04701208D +:101E8000F8BD0000F0B5866805460C4689B05EB125 +:101E9000BDF838305B070AD4D0E90037DB6B9847D0 +:101EA0002246C1B23846B047012009B0F0BD002239 +:101EB0000023CDE9002300230A46ADF8083001F1E4 +:101EC000080603AB1C4610685168083203C4B242CE +:101ED0002346F7D1106820609288A28000F0A0F914 +:101EE0000423ADF808302B68CDE900011B6C69466E +:101EF00028469847D8E7000030B503680968DD0F29 +:101F0000B5EBD17F23F0604421F060424FEAD170FD +:101F10000BD0002BB8BFA40C0029B8BF920C944280 +:101F200002D034BF0120002030BD944205D1C1F35E +:101F30008070C3F380738342F6D194422CBF00209B +:101F40000120F1E710B5037C044613B9006801F0E5 +:101F5000F7FE204610BD00000023BFF35B8FC36077 +:101F6000BFF35B8FBFF35B8F8360BFF35B8F704703 +:101F7000BFF35B8F0068BFF35B8F704770B505469A +:101F80000C30FFF7F5FF05F1080604463046FFF771 +:101F9000EFFFA04206D930466D68FFF7E9FF2C44F9 +:101FA000201A70BD3046FFF7E3FFF9E770B505462C +:101FB0004068A0B105F10800FFF7DAFF05F10C0653 +:101FC00004463046FFF7D4FF844288BF00253046E0 +:101FD00098BF6D68FFF7CCFF013C2C44201A70BD00 +:101FE00038B50C460546FFF7C9FFA04210D305F1EE +:101FF0000800FFF7BDFF04446868BFF35B8FB4FBC4 +:10200000F0F100FB1144AC60BFF35B8F012038BDE1 +:102010000020FCE72DE9F041144607460D46FFF786 +:10202000C5FF844228BF0446D4B1B84658F80C6BAB +:102030004046FFF79DFF06442E6040467E68FFF74E +:1020400097FF331A9C4203D801206C60BDE8F081F1 +:102050006B603B68A61B0644AB600220EE60F5E7B0 +:102060002046F3E738B50C460546FFF79FFFA04230 +:1020700010D305F10C00FFF77BFF04446868BFF341 +:102080005B8FB4FBF0F100FB1144EC60BFF35B8F9E +:10209000012038BD0020FCE72DE9FF410F466946CD +:1020A00006466C46FFF7B6FF002504EBC008444522 +:1020B00008D0626820687919FFF750F9636808341E +:1020C0001D44F4E729463046FFF7CCFF284604B00C +:1020D000BDE8F081F8B505460C300F46FFF748FF24 +:1020E00005F1080604463046FFF742FFA04230469D +:1020F00088BF6C68FFF73CFF201A386020B130467B +:102100002C68FFF735FF2044F8BD0000F7B51746EF +:1021100006460D46FFF732FFB842044628BF3C464C +:102120000190DCB1304601A9FFF7D4FF019B33B920 +:102130003268C5E90233C5E9002401200CE09C4265 +:1021400038BF01942860019884426860F5D9241A48 +:1021500002203368EC60AB6003B0F0BD2046FBE7C3 +:102160002DE9FF410E466946FFF7D0FF6C4600257A +:1021700004EBC007BC4209D0D4F804807019424671 +:1021800054F8081BFFF7EAF84544F3E7284604B083 +:10219000BDE8F08138B50546FFF7E2FF0446014689 +:1021A0002846FFF71DFF204638BD0000EFF30983E6 +:1021B000EFF30583044B9A6BDA6A9A6A9A6A9A6A11 +:1021C0009A6A9A6A9B6AFEE700ED00E0EFF30983E2 +:1021D000EFF30583044B9A6B9A6A9A6A9A6A9A6A31 +:1021E0009A6A9B6AFEE700BF00ED00E0EFF3098307 +:1021F000EFF30583034B5A6B9A6A9A6A9A6A9A6A52 +:102200009B6AFEE700ED00E0FEE700000FB408B5B2 +:10221000029801F09BF8FEE701F092BA01F06ABA69 +:1022200001F068BA30B5094D0A4491420DD011F859 +:10223000013B5840082340F30004013B2C4013F0BD +:10224000FF0384EA5000F6D1EFE730BD2083B8EDFC +:102250004FF0FF33F7B500EB81061946DFF848C0B1 +:10226000DFF848E0B0421BD050F8042B01AF0192D8 +:10227000042217F8014B81EA046108240D46DB189B +:102280004941013C002DBCBF83EA0C0381EA0E01E9 +:1022900014F0FF04F2D1013A12F0FF02E9D1E1E7B4 +:1022A000D843C94303B0F0BD9336EAA9EBE1F0424D +:1022B0002DE9F041C56915B9C161BDE8F0814B68F0 +:1022C000AC4623F06047C3F38A4616EA230638BFBC +:1022D0003E464FEAD37EC3F380782B465A68BEEB66 +:1022E000D27F22F060440AD0002A18DAA40CB4424B +:1022F00017D19D420FD10D60DEE71346EEE7A742EE +:1023000007D102F08044C2F3807242450BD054B131 +:10231000EFE708D2EDE7CCF800100B60CDE7B44250 +:1023200001D0B442E5D81A689C46002AE5D119606C +:10233000C3E700002DE9F0474FF47F49089D01F005 +:1023400007044FEAD508224405F0070500EBD10049 +:10235000944201D1BDE8F08704F0070705F0070AB1 +:1023600057453E4638BF5646111BC6F108068E42F9 +:1023700028BF0E46E108415C08EBD50E13F80EC0ED +:10238000B94029FA06F721FA0AF1FFB28CEA0101F5 +:1023900047FA0AF739408CEA010C03F80EC03444BE +:1023A0003544D5E7082341F2210280EA012001B239 +:1023B0004000002980B203F1FF33B8BF504013F052 +:1023C000FF03F4D17047000038B50C468D18A542C4 +:1023D00000D138BD14F8011BFFF7E4FFF7E7000058 +:1023E0000346006848B1026819891A60DA88013228 +:1023F00092B29142DA8038BF1A81704770B50446B4 +:102400000D4688B0202200216846FEF7B9FF20461D +:102410000495FFF7E5FF024658B16B46054608AE46 +:102420001C4603CCB44228606960234605F10805C8 +:10243000F6D1104608B070BD082817D909280CD06D +:102440000A280CD00B280CD00C280CD00D280CD04E +:102450000E2814BF4020302070470C2070471020F9 +:1024600070471420704718207047202070470000E4 +:10247000082817D90C280CD910280CD914280CD9E5 +:1024800018280CD920280CD930288CBF0F200E20FA +:102490007047092070470A2070470B2070470C20B6 +:1024A00070470D207047000010B54B6823B9CA8AE9 +:1024B00063F30902CA8210BDC4681A681C60C36055 +:1024C000438A013B43824A60EFE700002DE9F84F61 +:1024D0001D46CB8A0F46C3F3090106298146924661 +:1024E0000B4630D00020AAB207F119049EB2052E87 +:1024F0001FFA80F80FD8904503F1010306D3FB8A39 +:102500000A4462F309030120FB821AE01AF8006012 +:102510000130E654EAE79045F1D21C23A1F1060B05 +:10252000BBFBF3F203FB12BB7C681FFA8BF6002C9B +:1025300045D14846FFF754FF044638B978606FF03C +:102540000200BDE8F88F4FF00008E6E700260660BD +:1025500078604FF0000BADB2454510D90AEB080387 +:10256000221D13F8011B08F101089155B1B21B2976 +:102570001FFA88F82BD0454506F10106F1D8FB8AF1 +:10258000C3F30902154465F30903BCE71C46013295 +:1025900092B22368002BF9D1AB1F0B441C21B3FB73 +:1025A000F1F301339BB29A42D3D2BBF1000FD0D1E9 +:1025B0004846FFF715FF20B9C4F800B0BFE7012275 +:1025C000E7E7C0F800B05E4620600446C1E7454535 +:1025D000D5D94846FFF704FF08B92060AFE7C0F837 +:1025E00000B0002620600446B6E700002DE9F04F59 +:1025F00085B007469146CDE90113BDF83C50002A4D +:1026000000F08F802DB10E9B002B00F08A80072DEB +:1026100030D807F10C00FFF7E3FE044628B96FF04D +:102620000204204605B0BDE8F08F14220021FEF719 +:10263000A7FE2A460E9904F10800FEF78FFE681CDB +:10264000C0B2FFF715FFFFF7F7FE207499F80020DE +:10265000431E9BB202F01F02234462F03F021A7233 +:10266000019B384643F0004161602146FFF720FEA0 +:102670000124D6E74FF000084FF0800A4646444652 +:1026800000F10C0303930398FFF7AAFE834600288A +:10269000C5D014220021FEF773FE002E38D102208F +:1026A000029BABF808300E9B00F10802D2B29919D8 +:1026B0005A440130C0B2082801D0AE422AD3FFF7F5 +:1026C000D7FEFFF7B9FEAE4208BF4FF0400A99F8B7 +:1026D0000020019B411E02F01F0242EA4812C9B2CB +:1026E0004AEA020A594443F0004281F808A08BF8F4 +:1026F000100059463846CBF80420FFF7D9FD0134C5 +:10270000AE424FF0000A24B288F00108BBD188E73E +:102710000020C8E711F801CB013602F801CBB6B2B0 +:10272000C7E76FF001047CE7F8B5044615460E468E +:10273000282200211F46FEF723FE069BB5F5001F49 +:102740006360079B28BF4FF6FF7223624FF00003C0 +:1027500038BF6A09A76004F10C0097B29A4205D805 +:102760000023036027826382A382F8BD06600133E1 +:1027700030462036F2E7000003781BB94BB2002B3D +:10278000C8BF017070470000007870472DE9F74F0F +:10279000DDF83C90804692469B46BDF830500D9E39 +:1027A0009DF83840BDF84070B9F1000F01D1002FFD +:1027B00051D11F2C4FD898F80000B0B9072F47D837 +:1027C00035F0030347D13A4649464FF6FF70FFF70D +:1027D000FBFD20F001002D02400445EA0464400C9A +:1027E00044EA40244FF6FF7321E040EA0520072F1A +:1027F00040EA0464F6D900254FF6FF73C5F12000C6 +:10280000A5F120022AFA05F10BFA00F001432BFA98 +:1028100002F211431846C9B2FFF7C4FD0835402D36 +:102820000346EBD13A464946FFF7CEFD0346324612 +:1028300021464046CDE90097FFF7D8FE33780133B3 +:10284000DBB21F2B88BF0023337003B0BDE8F08FCD +:102850006FF00300F9E76FF00100F6E72DE9F04FA4 +:1028600085B0DDF84880924606469B460F9D9DF850 +:1028700040209DF84490BDF84C70B8F1000F01D194 +:10288000002F48D11F2A46D83378002B46D00C029F +:1028900044EA02649DF8381044EAC93444EA014429 +:1028A0001C43072F44F0800432D900234FF6FF72F7 +:1028B000C3F1200CA3F120002AFA03F10BFA0CFC5F +:1028C00041EA0C012BFA00F00143C9B21046039310 +:1028D000FFF768FD039B02460833402BE8D13A46D8 +:1028E0004146FFF771FD03462A4621463046CDE9B1 +:1028F0000087FFF77BFEB9F1010F06D12B7801337A +:10290000DBB21F2B88BF00232B7005B0BDE8F08F12 +:102910004FF6FF73E8E76FF00100F6E76FF0030092 +:10292000F3E70000C06900B104307047C3691A685A +:10293000C261C2681A60C360438A013B4382704728 +:102940002DE9F041D0F8188014461D464146002775 +:10295000174E09B9BDE8F081D1E90223A21A65EB4F +:102960000303964277EB03031ED283698B420DD19A +:10297000FFF79AFD83691B688361C3680B60438A14 +:10298000C1608169013B88464382E2E7FFF78CFD25 +:102990000B68C8F80030C3680B60438AC160013B14 +:1029A0004382D8F80010D4E788460968D1E700BF11 +:1029B00080841E002DE9F04F8BB00D4614469B46D7 +:1029C0008046DDF85090002800F01A81B9F1000F20 +:1029D00000F01681531E3F2B00F21281012A03D111 +:1029E000BBF1000F40F00C810023CDE90833B8F8AB +:1029F0001430B5EBC30F4FEAC30703D300200BB06D +:102A0000BDE8F08F2B199F42D8F80C3036BF7F1BE2 +:102A10002746FFB21BB9D8F81030002B7BD02F2DE2 +:102A20004ED8C5F13006B7424FF0000334BF3E46E2 +:102A3000F6B2009329463246D8F8080008ABFFF7F3 +:102A400079FCA7EB060A35445FFA8AFA3021B8F818 +:102A5000143003F10053063BDB000493D8F80C302C +:102A60000393039B13B1BAF1000F2CD1D8F81000D7 +:102A700040B1BAF1000F05D05246009608AB691A72 +:102A8000FFF758FC38B2002FB8D066070AD00AAB5F +:102A900003EBD40111F8083C624202F00702134133 +:102AA00001F8083C082C3DD9102C40F2B680202CAF +:102AB00040F2B880BBF1000F00F09D80082335E0A4 +:102AC000BA460026C2E7049BE02B28BFE02306930A +:102AD0000B44AB42059315D95A1B924538BF524659 +:102AE000039828BFD2B20096691A08AB0430079247 +:102AF000FFF720FC079A1644AAEB020A1544F6B227 +:102B00005FFA8AFA049B069A05999B1A0493039B21 +:102B10001B680393A5E700933A462946D8F80800B6 +:102B200008ABADE7BBF1000F13D00123B4EBC30F2B +:102B30006CD0082C12D89DF82030621E23FA02F2C5 +:102B4000D50706D54FF0FF3202FA04F423438DF87F +:102B500020309DF8203089F8003050E7102C12D832 +:102B6000BDF82030621E23FA02F2D10706D54FF0DD +:102B7000FF3202FA04F42343ADF82030BDF82030D0 +:102B8000A9F800303BE7202C0FD80899631E21FAE2 +:102B900003F3DA0705D54FF0FF3202FA04F40C43D1 +:102BA0000894089BC9F8003029E7402C2BD0DDE9B8 +:102BB0000865611EC4F12102A4F1210326FA01F186 +:102BC00005FA02F225FA03F311431943CB0712D594 +:102BD0000122A4F12003C4F1200102FA03F322FA36 +:102BE00001F1A240524243EA010363EB4303324343 +:102BF0002B43CDE90823DDE90823C9E90023FEE6DC +:102C00006FF00100FBE66FF00800F8E6082CA0D991 +:102C1000102CB3D9202CEED8C3E7BBF1000FADD0F8 +:102C2000022383E7BBF1000FBBD004237EE7000043 +:102C3000012A30B5144638BF01220025402A28BF9A +:102C4000402285B0012CCDE9025517D81B788DF8AC +:102C5000083053070AD004AB03EBD20515F8083C43 +:102C6000544204F00704A34005F8083C03460091D1 +:102C700002A80021FFF75EFB05B030BD082CE5D9A6 +:102C8000102C03D81B88ADF80830E2E7202C02D8BE +:102C90001B680293DDE7D3E90045CDE90245D8E79B +:102CA00010B5CB681BB98B600B618B8210BDC468FB +:102CB0001A681C60C360438A013B4382CA60F0E724 +:102CC0002DE9F04FD1F8008093B018F0800FCDE9D6 +:102CD0000323C8F3C01207BF4FF0020B1646C8F318 +:102CE000C03BC8F30626B8F1000F04460D4680F23B +:102CF000D48118F0C043059340F0CF810B7B002BAB +:102D000000F0CB81BBF1020F03D00178B14240F05B +:102D1000C78108F07F0107917AB3C8F3074A2B44B3 +:102D200093F80390760646EA0B4608F07F0246EADF +:102D300082465FEAD91346EA0A06069300F09180BC +:102D400000220023CDE90A2308F07F0300935246B6 +:102D50005B46204667680AA9B84700287ED0A76965 +:102D60009FB9314604F10C00FFF748FB0746E0B974 +:102D70006FF0020013B0BDE8F08FC8F30F2A18F00F +:102D80007F0F08BF0AF0030AC9E73B699E420DD0D6 +:102D90003F68002FF9D1314604F10C00FFF72EFBFC +:102DA00007460028E4D0A3693B60A7610026DDE95F +:102DB0000A234FF6FF70C6F1200E22FA06F103FA3D +:102DC0000EFEA6F1200C23FA0CFC41EA0E0141EAAA +:102DD0000C01C9B2083609920893FFF7E3FADDE95E +:102DE0000832402EE7D1B882FB7D09F01F06C3F3FD +:102DF00084039B1B98B2002BBCBF00F120031BB2C5 +:102E0000D7E9022152EA0100C8F304680FD0039801 +:102E1000821A049860EB0101A74890424FF000022B +:102E20008A4104D3069A002A5BD0012B23DDFA7D68 +:102E30004FEA890302F0030203F07C031343FB759E +:102E400039462046FFF730FB069BA3B9FB7DC3F351 +:102E50008402013262F38603FB7504E06FF00B001D +:102E600088E7A76917B96FF00C0083E73B699E42BA +:102E7000BAD03F68F6E719F0400F32D0039B142216 +:102E8000BB60049B0021FB600DA8FEF779FA039B51 +:102E900020460A93049BADF83EA00B932B1D0C9388 +:102EA0002B7B8DF840B0013BDBB2ADF83C30079B8B +:102EB0008DF841608DF8433094F824308DF84280CD +:102EC00083F001038DF844300AA9A3689847FB7D7D +:102ED000C3F38403013303F01F039B02FB82002032 +:102EE00048E7FB7DC9F34012B2EBD31F40F0DB8013 +:102EF000C3F38403B34240F0D98006992B7B4FEA99 +:102F00009912002934D0D20741D4032B40F2D1804A +:102F1000039BAE1DBB60049B3246FB602B7B394696 +:102F2000033BDBB204F10C00FFF7D0FA00280DDA06 +:102F300020463946FFF7B8FAFB7D0320C3F384032C +:102F4000013303F01F039B02FB8213E7AB883B8333 +:102F50002A7B033AB88AD2B23146FFF735FAFB7DB5 +:102F6000B882DA43C2F3C01262F3C713FB75B6E747 +:102F70006AB92E1D013B32463946DBB204F10C0022 +:102F8000FFF7A4FA0028D3DB2A7B013AE2E7F98AAB +:102F9000013BC1F309010529DAB25BD80023281DE2 +:102FA00007F11A0C9A4208D910F801EB01330CF81A +:102FB00001E001310629DBB2F4D1934228BF00239E +:102FC000039938BF04330A91049938BFDBB20B91DF +:102FD00007F11A010C91796838BF5B190D910E93B6 +:102FE000FB8AADF83EA0C3F309031A44079BADF872 +:102FF0003C208DF8433094F824308DF840B083F0B5 +:1030000001038DF8443000238DF841608DF8428033 +:103010007B602A7BB88A013A291DFFF7D5F93B8BE3 +:10302000B882834203D12046A3680AA99847204664 +:103030000AA9FFF735FEFB7DB88AC3F38403013389 +:1030400003F01F039B02FB823B8B984214BF1120AD +:1030500000208FE67B68002BAFD0062001E063469E +:103060001C30D3F800C0BCF1000FF8D1091A081DBC +:1030700005F1040C1844DDF814E09DF814308E447A +:10308000BEF11B0F99D89A4297D91CF8013B00F862 +:10309000013B059B01330593EDE76FF0090069E6FD +:1030A0006FF00A0066E66FF00D0063E66FF00E0049 +:1030B00060E66FF00F005DE680841E00EFF3098389 +:1030C000203383F30988002383F3118870470000BD +:1030D000202080F3118862B60C4B0D4AD96821F488 +:1030E000E0610904090C0A43DA60D3F8FC200949BD +:1030F00042F08072C3F8FC200A6842F001020A60C4 +:103100001022DA7783F82200704700BF00ED00E05C +:103110000003FA05001000E0202310B583F31188A6 +:103120000B4B5B6813F400630FD0EFF309844FF08F +:103130008073203CE36184F3098800F0B9F810B192 +:10314000044BA36110BD044BFBE783F31188F9E73F +:1031500000ED00E07F05000882050008012209015A +:1031600000F1604303F56143C9B283F8001300F036 +:103170001F039A4043099B0003F1604303F5614339 +:10318000C3F880211A607047090100F16040C9B29C +:1031900000F56D40017670470022024BC3E9003311 +:1031A0009A607047BC1E0020002382680374054BA0 +:1031B0001B6899689142FBD25A68036042601060B4 +:1031C00058607047BC1E002008B5202383F3118887 +:1031D000037C032B05D0042B0DD02BB983F311886E +:1031E00008BD002243691A604FF0FF334361FFF7C7 +:1031F000DBFF0023F2E7D0E9003213605A60F3E707 +:10320000002382680374054B1B6899689142FBD8C0 +:103210005A6803604260106058607047BC1E00200E +:10322000054B196908741868026853601A601861C0 +:1032300001230374FDF792B9BC1E002030B54B1C6E +:1032400004460B4D87B010D02B690A4A01A800F044 +:10325000FDF82046FFF7E4FF049B13B101A800F03E +:1032600011F92B69586907B030BDFFF7D9FFF8E7AE +:10327000BC1E0020C931000838B50C4D41612B69D6 +:1032800081689A680446914203D8BDE83840FFF748 +:103290008BBF1846FFF7B4FF01232C61014623744E +:1032A0002046BDE83840FDF759B900BFBC1E0020DC +:1032B000044B1A681B6990689B68984294BF002071 +:1032C00001207047BC1E002010B5084C23682069FF +:1032D0001A6854602260012223611A74FFF790FF7C +:1032E00001462069BDE81040FDF738B9BC1E00203A +:1032F00008B5FFF7DDFF18B1BDE80840FFF7E4BFF0 +:1033000008BD0000FFF7E0BFFEE7000010B50C4C61 +:10331000FFF742FF00F08CF880220A49204600F0B7 +:103320003DF8012344F8180C0374FFF7D1FE002385 +:1033300083F3118862B6BDE81040034800F04EB830 +:10334000E41E0020F84000080841000808B572B6E5 +:10335000034B586200F0C8F900F060FAFEE700BFC6 +:10336000BC1E002000F0A0B8EFF3118020B9EFF3ED +:103370000583202282F311887047000010B530B910 +:10338000EFF30584C4F3080414B180F3118810BD71 +:10339000FFF7AEFF84F31188F9E700008260022294 +:1033A000028270478368A3F13C0243F80C2C026947 +:1033B00043F83C2C426943F8382C074A43F81C2C4C +:1033C000C268A3F1180043F8102C022203F8082C5D +:1033D000002203F8072C70476D05000810B5202364 +:1033E00083F31188FFF7DEFF00210446FFF744FF57 +:1033F000002383F31188204610BD0000024B1B6997 +:1034000058610F20FFF70CBFBC1E0020202383F360 +:103410001188FFF7F3BF000008B50146202383F3AE +:1034200011880820FFF70AFF002383F3118808BDE5 +:10343000054B03F11402C3E905224FF0FF32DA61B4 +:1034400000221A62704700BFBC1E002010B5C0E900 +:1034500003230B4A136A53699C68A1420CD85C6829 +:10346000816003604460206058609868411A9960E8 +:103470004FF0FF33D36110BD1B68091BECE700BFA1 +:10348000BC1E0020036881689A680A449A604268FA +:1034900013605A6000234FF0FF32C360014BDA61C2 +:1034A000704700BFBC1E002038B50F4C2246236A6F +:1034B0000133236252F8143F934206D020259A68C4 +:1034C000013A9A6063699A6802B138BDD3E9001085 +:1034D00001604860D968DA6082F31188186988470A +:1034E00085F31188EEE700BFBC1E00200C230360AB +:1034F0004FF0FF307047000000207047FEE70000EB +:10350000704700004FF0FF3070470000BFF34F8F4F +:10351000024AD368DB07FCD4704700BF002002409A +:1035200008B5074B1B7853B9FFF7F0FF054B1A6935 +:10353000120641BF044A5A6002F188325A6008BD3F +:10354000C01F0020002002402301674508B5054B3D +:103550001B7833B9FFF7DAFF034A136943F080039E +:10356000136108BDC01F0020002002407F289ABFC1 +:1035700000F58030C0020020704700004FF400606A +:1035800070470000802070477F2808B50BD8FFF7F0 +:10359000EDFF00F500630268013204D1043083427C +:1035A000F9D1012008BD0020FCE700007F2838B5D4 +:1035B000044623D8FFF7D8FEFFF7A8FFFFF7B0FFB8 +:1035C000F3220F4B0546DA60022220461A61FFF70C +:1035D000CDFF58611A694FF4006142F040021A6150 +:1035E000FFF794FF00F016F92846FFF7AFFFFFF74B +:1035F000C5FE2046BDE83840FFF7C6BF002038BDF5 +:10360000002002402DE9F047044612F001000E466A +:10361000154606D040F2BD22234B1A600020BDE8BB +:10362000F087224BA2189A4204D940F2C2221E4BC4 +:103630001A60F4E7FFF798FE4FF0010AFFF770FFFA +:10364000FFF764FFDFF868903146A61B012D88461E +:1036500006EB010705D8FFF779FFFFF78FFE012082 +:10366000DDE7B8F80030C9F810A03B800024FFF770 +:103670004DFFC9F810403B8831F8022B9BB29A42AB +:103680000FD040F2D922084B1A600A4B1F600A4B38 +:103690001D600A4BC3F80080FFF758FFFFF76EFE6E +:1036A000BCE7023DD2E700BFBC1F002000000408B9 +:1036B00000200240B01F0020B81F0020B41F0020CF +:1036C000084908B50B7828B11BB9FFF729FF01237A +:1036D0000B7008BD002BFCD0BDE808400870FFF758 +:1036E00035BF00BFC01F00204FF480314FF00050A5 +:1036F00000F092B870B5FFF737FE4FF47A710D4BBA +:103700000D4E1B6A326801FB03F3934237BF0B4A2D +:103710000A495168156836BF4C1CD1E90054546001 +:103720005D1944F100043360FFF728FE2846214666 +:1037300070BD00BFBC1E0020C41F0020C81F002099 +:1037400070B5FFF711FE4FF47A710F4B0F4E1B6AE5 +:10375000326801FB03F3934237BF0D4A0C495168AD +:1037600015683ABF4C1C5460D1E900545D1944F10E +:1037700000043360FFF702FE4FF47A7200232846FC +:103780002146FCF7F5FC70BDBC1E0020C41F0020C4 +:10379000C81F002010B5094C013AD2B2FF2A00D14F +:1037A00010BD500854F82030013054F820009BB26E +:1037B00043EA004341F8043BEEE700BF046C0040DD +:1037C00010B50748013AD2B2FF2A00D110BD0C88CB +:1037D000530840F823404C88013340F82340F1E778 +:1037E000046C004007B50122002001A9FFF7D2FFB9 +:1037F000019803B05DF804FB13B50446FFF7F2FF30 +:10380000A04205D00122002001A90194FFF7D8FFB2 +:1038100002B010BD70470000704700007047000004 +:1038200045F25552064B1A6002225A6040F6FF726A +:103830009A604CF6CC421A600122024B1A70704713 +:1038400000300040D41F0020034B1B781BB14AF608 +:10385000AA22024B1A607047D41F0020003000409B +:10386000044B1A682AB902F1804202F50432526A06 +:103870001A607047D01F00204FF08072014B5A62CF +:10388000704700BF0010024008B5FFF7E9FF024B88 +:103890001868C0F3407008BDD01F002008B5FFF7BE +:1038A000DFFF024B1868C0F3007008BDD01F002076 +:1038B00070470000FEE700000A4B0B480B4A90429D +:1038C0000BD30B4BC11EDA1C121A22F003028B42DF +:1038D00038BF00220021FDF753BD53F8041B40F808 +:1038E000041BECE7E84100086C2000206C2000205D +:1038F0006C2000207047000000F030B808B500F0E0 +:103900006DF9FFF703FDBDE80840FFF7A9BF000010 +:10391000704700004FF0FF310E4B1A6919611A69A8 +:1039200000221A611869D868D960D968DA60DA6843 +:10393000DA6942F08052DA61DA69DA6942F00062EB +:10394000DA61054ADB69136843F48073136000F0A1 +:1039500025B900BF00100240007000401E4B1A68DD +:1039600042F001021A601A689007FCD55A6822F0EA +:1039700003025A605A6812F00C02FBD1196801F078 +:10398000F90119605A601A6842F480321A601A68A4 +:103990009103FCD54EF63162DA625A6842F4E812BD +:1039A0005A601A6842F080721A601A689201FCD557 +:1039B0000A4A0B495A6012220A600A6802F007029A +:1039C000022AFAD15A6842F002025A605A6802F09A +:1039D0000C02082AFAD170470010024000641D0052 +:1039E00000200240084A08B5516913680B4003F0F3 +:1039F0000103536123B1054A13680BB1506898471E +:103A0000BDE80840FFF788BB00040140D81F002034 +:103A1000084A08B5516913680B4003F0020353616B +:103A200023B1054A93680BB1D0689847BDE80840B8 +:103A3000FFF772BB00040140D81F0020084A08B5F8 +:103A4000516913680B4003F00403536123B1054A25 +:103A500013690BB150699847BDE80840FFF75CBB9C +:103A600000040140D81F0020084A08B551691368B6 +:103A70000B4003F00803536123B1054A93690BB16E +:103A8000D0699847BDE80840FFF746BB00040140F5 +:103A9000D81F0020084A08B5516913680B4003F08D +:103AA0001003536123B1054A136A0BB1506A98475A +:103AB000BDE80840FFF730BB00040140D81F0020DC +:103AC000174B10B55A691C68144004F478725A6197 +:103AD000A30604D5134A936A0BB1D06A98476006CF +:103AE00004D5104A136B0BB1506B9847210604D5CF +:103AF0000C4A936B0BB1D06B9847E20504D5094A89 +:103B0000136C0BB1506C9847A30504D5054A936C10 +:103B10000BB1D06C9847BDE81040FFF7FDBA00BF6D +:103B200000040140D81F00201A4B10B55A691C68C8 +:103B3000144004F47C425A61620504D5164A136DA0 +:103B40000BB1506D9847230504D5134A936D0BB103 +:103B5000D06D9847E00404D50F4A136E0BB1506E38 +:103B60009847A10404D50C4A936E0BB1D06E9847C8 +:103B7000620404D5084A136F0BB1506F98472304B1 +:103B800004D5054A936F0BB1D06F9847BDE810403C +:103B9000FFF7C2BA00040140D81F0020062108B573 +:103BA0000846FFF7DBFA06210720FFF7D7FA0621C0 +:103BB0000820FFF7D3FA06210920FFF7CFFA0621E4 +:103BC0000A20FFF7CBFA06211720FFF7C7FABDE856 +:103BD000084006212820FFF7C1BA000008B5FFF70A +:103BE00099FE044800F00AF8FFF792FEBDE808408D +:103BF00000F002B82041000800F042B80023194646 +:103C00001C4A0133102BC2E9001102F10802F8D15D +:103C1000194B9A6942F07D029A619B690268174BC1 +:103C2000DA6082685A6042681A60C26803F580638D +:103C3000DA6042695A6002691A608269C3F80C242A +:103C4000026AC3F80424C269C3F80024426AC3F8B4 +:103C50000C28C26AC3F80428826AC3F80028026BE1 +:103C6000C3F80C2C826BC3F8042C426BC3F8002CF5 +:103C7000704700BFD81F002000100240000801401C +:103C80004FF0E023044A08215A6100229A6107227A +:103C90000B201A61FFF778BA3F19010008B52023FD +:103CA00083F31188FFF75EFB002383F3118808BDBF +:103CB00008B5FFF7F3FFBDE80840FFF72DBA000095 +:103CC0000B460146184600F025B8000000F038B851 +:103CD000012838BF012010B50446204600F028F81E +:103CE00030B900F007F808B900F00CF88047F4E7A5 +:103CF00010BD0000024B1868BFF35B8F704700BF18 +:103D000058200020062008B500F02CF90120FFF70C +:103D1000F5FB000010B504460448134620B10A46DE +:103D200002202146AFF3008010BD00BF000000005C +:103D3000024B0146186800F083B800BF1C08002041 +:103D4000024B0146186800F033B800BF1C08002081 +:103D500010B501390244904201D1002005E00378FA +:103D600011F8014FA34201D0181B10BD0130F2E73A +:103D70002DE9F0419BB10446C91A1778014403F1BB +:103D8000FF3C8C42204601D9002008E00578013430 +:103D9000BD42F6D10CEB0405D618A54201D1BDE811 +:103DA000F08115F8018D16F801EDF045F5D0E8E742 +:103DB00038B50546002940D051F8043C0C1F002BB3 +:103DC000B8BFE41800F0F2F81C4A136833B9636016 +:103DD00014602846BDE8384000F0EEB8A34208D988 +:103DE000206821188B4201BF19685B68091821609F +:103DF000EDE71A465B680BB1A342FAD91168501877 +:103E0000A0420BD120680144501883421160E0D1D8 +:103E100018685B68014411605360DAE702D90C232B +:103E20002B60D6E7206821188B4201BF19685B68B8 +:103E30000918216063605460CBE738BD5C20002026 +:103E4000F8B5CD1C25F0030508350C2D38BF0C2521 +:103E5000002D064601DBA94203D90C233360002064 +:103E6000F8BD00F0A3F821490A6814469CB9204F18 +:103E70003B6823B92146304600F03CF838602946BB +:103E8000304600F037F8431C23D10C233046336012 +:103E900000F092F8E3E723685B1B17D40B2B03D9E0 +:103EA00023601C44256004E06368A2420CBF0B60E1 +:103EB0005360304600F080F804F10B00231D20F021 +:103EC0000700C21ACCD01B1AA350C9E72246646867 +:103ED000CCE7C41C24F00304A042E3D0211A3046EE +:103EE00000F008F80130DDD1CFE700BF5C200020F2 +:103EF0006020002038B50023054D044608462B609D +:103F0000FFF7F4FA431C02D12B6803B1236038BDDC +:103F1000642000201F2938B504460D4604D9162315 +:103F200003604FF0FF3038BD426C12B152F82130BF +:103F30004BB9204600F030F82A4601462046BDE83D +:103F4000384000F017B8012B0AD0591C03D11623B2 +:103F500003600120E7E70024284642F825409847FF +:103F60000020E0E7024B01461868FFF7D3BF00BF0F +:103F70001C08002038B50023064D044608461146AB +:103F80002B60FFF7BFFA431C02D12B6803B12360FB +:103F900038BD00BF64200020FFF7AEBA034611F819 +:103FA000012B03F8012B002AF9D17047014800F0DA +:103FB00009B800BF68200020014800F005B800BF24 +:103FC0006820002070470000704700006F72672E65 +:103FD0006172647570696C6F742E61705F70657268 +:103FE0006970685F5A75626178474E5353000000EC +:103FF0004E6F20617070207369670A00426164200F +:104000006677206C656E6774682025750A004261CA +:104010006420626F6172645F696420257520736833 +:104020006F756C642062652025750A00426164200A +:1040300066772064657363726970746F72206C6553 +:104040006E6774682025750A004261642061707093 +:1040500020435243203078253038783A3078253064 +:104060003878203078253038783A307825303878EC +:104070000A00476F6F64206669726D776172650A26 +:104080000040A2E4F16468910600000042616420EF +:1040900043414E496661636520696E6465782E0010 +:1040A0008000000000800000000080000000000090 +:1040B0000000000031140008E51B0008491B00083F +:1040C0004114000871140008611600084514000826 +:1040D00059140008491400084D140008551400082C +:1040E000511400088D1500085D140008491E0008D1 +:1040F00069140008611500086D61696E0000000018 +:1041000069646C650000000000410008001F002089 +:10411000B01F00200100000009330008000000006B +:104120000C880000447B444444544424800E000026 +:1041300044141114947B444400000000444444445B +:10414000444444440400000044424444444444443D +:1041500000000000444444444444444444C0FF7FBD +:104160000100000000000000ED030000000000005E +:10417000006803000000000040420F00FE2A01001A +:10418000D204000020080020000000000000000011 :10419000000000000000000000000000000000001F :1041A000000000000000000000000000000000000F +:1041B00000000000000000000000000000000000FF +:1041C00000000000000000000000000000000000EF +:1041D00000000000000000000000000000000000DF +:0841E0000000000000000000D7 :00000001FF diff --git a/Tools/bootloaders/f103-ADSB_bl.bin b/Tools/bootloaders/f103-ADSB_bl.bin index a480e26f7f0..b6351b5e50a 100755 Binary files a/Tools/bootloaders/f103-ADSB_bl.bin and b/Tools/bootloaders/f103-ADSB_bl.bin differ diff --git a/Tools/bootloaders/f103-ADSB_bl.elf b/Tools/bootloaders/f103-ADSB_bl.elf index ec08bd8a0fd..a3677f545ea 100755 Binary files a/Tools/bootloaders/f103-ADSB_bl.elf and b/Tools/bootloaders/f103-ADSB_bl.elf differ diff --git a/Tools/bootloaders/f103-ADSB_bl.hex b/Tools/bootloaders/f103-ADSB_bl.hex index 98aaf506e54..d5ce6dc8072 100644 --- a/Tools/bootloaders/f103-ADSB_bl.hex +++ b/Tools/bootloaders/f103-ADSB_bl.hex @@ -1,1062 +1,963 @@ :020000040800F2 -:1000000000090020A10400081514000819140008B4 -:10001000551400081914000835140008A30400083A -:10002000A3040008A3040008A3040008C5360008C0 -:10003000A3040008A3040008A3040008593A000818 -:10004000A3040008A3040008A3040008A3040008F4 -:10005000A3040008A3040008393800086538000824 -:1000600091380008BD380008E9380008A3040008EA -:10007000A3040008A3040008A3040008A3040008C4 -:10008000A3040008A3040008A304000869250008CD -:10009000D5250008292600087D2600081539000806 -:1000A000A3040008A3040008A3040008A304000894 -:1000B000A3040008A3040008A3040008A304000884 -:1000C000A3040008A3040008A3040008A304000874 -:1000D000A3040008A12A0008B52A0008A304000808 -:1000E0007D390008A3040008A3040008A304000845 -:1000F000A3040008A3040008A3040008A304000844 -:10010000A3040008A3040008A3040008A304000833 -:10011000A3040008A3040008A3040008A304000823 -:10012000A3040008A3040008A3040008A304000813 -:10013000A3040008A3040008A3040008A304000803 -:10014000A3040008A3040008A3040008A3040008F3 -:10015000A3040008A3040008A3040008A3040008E3 -:10016000D0400B1CD1409C46203AD3401843524209 -:1001700063469340184370479140031C90409C464F -:10018000203A9340194352426346D3401943704783 -:1001900053B94AB9002908BF00281CBF4FF0FF31EE -:1001A0004FF0FF3000F07AB9ADF1080C6DE904CEE4 -:1001B00000F006F8DDF804E0DDE9022304B0704742 -:1001C0002DE9F0478C460E460446089D002B50D181 -:1001D0008A4217466CD9B2FA82FEBEF1000F0BD0EC -:1001E000CEF1200C01FA0EF620FA0CFC02FA0EF702 -:1001F0004CEA060C00FA0EF43A0CBCFBF2F9BBB266 -:1002000002FB19CC09FB03FA4FEA144848EA0C46F2 -:10021000B2450AD9F61909F1FF3180F02581B245BE -:1002200040F22281A9F102093E44A6EB0A06B6FB80 -:10023000F2F002FB106600FB03F3A4B244EA0644AA -:10024000A34209D9E41900F1FF3280F00B81A342E7 -:1002500040F2088102383C440021E41A40EA094097 -:10026000002D62D0002324FA0EF42C606B60BDE8F0 -:10027000F0878B4207D9002D55D0002185E8410039 -:100280000846BDE8F087B3FA83F1002940F08F807B -:10029000B34202D3824200F2FC80841A66EB03066A -:1002A0000120B446002D40D085E81010BDE8F0874D -:1002B00012B90127B7FBF2F7B7FA87FEBEF1000FBC -:1002C00035D10121F61B4FEA174C1FFA87F8B6FB10 -:1002D000FCF20CFB126608FB02F0230C43EA064614 -:1002E000B04207D9F61902F1FF3302D2B04200F250 -:1002F000D2801A46361AB6FBFCF00CFB106608FBDF -:1003000000F8A3B243EA0644A04507D9E41900F176 -:10031000FF3302D2A04500F2B9801846A4EB0804CE -:1003200040EA02409CE729462846BDE8F08707FAE4 -:100330000EF7CEF1200326FA03F24FEA174CB2FB78 -:10034000FCF11FFA87F80CFB112206FA0EF620FAD0 -:1003500003F301FB08F933431E0C46EA0246B1459C -:1003600000FA0EF409D9F61901F1FF3280F08C8001 -:10037000B14540F2898002393E44A6EB0906B6FB3E -:10038000FCF00CFB106200FB08F99EB246EA024644 -:10039000B14507D9F61900F1FF3371D2B1456FD9D4 -:1003A00002383E44A6EB090640EA01418FE7C1F15D -:1003B000200722FA07F88B4048EA030326FA07F4DD -:1003C0004FEA134EB4FBFEF91FFA83FC0EFB1944EF -:1003D0008E4020FA07F809FB0CFA48EA06084FEAB3 -:1003E000184646EA0444A24502FA01F200FA01F670 -:1003F00008D9E41809F1FF3044D2A24542D9A9F145 -:1004000002091C44A4EB0A04B4FBFEF00EFB1044EA -:1004100000FB0CFC1FFA88F848EA0444A44507D9FD -:10042000E41800F1FF3E29D2A44527D902381C4424 -:1004300040EA0940A0FB0289A4EB0C0CCC45C24663 -:10044000CE4615D312D055B1B6EB0A036CEB0E06AF -:1004500006FA07F7CB401F43CE402F606E600021A5 -:10046000BDE8F0871046F7E68946DEE64645EAD263 -:10047000B8EB020A69EB030E0138E4E77046D7E7F0 -:1004800018468FE78146BDE7114676E702383C44BF -:1004900044E7084606E7023A3E442BE7704700BFB0 -:1004A00002E000F000F8FEE772B6274880F3088803 -:1004B000264880F3098826484EF60851CEF20001FE -:1004C0000860022080F31488BFF36F8F03F02AF9CD -:1004D00003F046F94FF055301E491B4A91423CBF8C -:1004E00041F8040BFAE71C49184A91423CBF41F815 -:1004F000040BFAE719491A4A1A4B9A423EBF51F8BF -:10050000040B42F8040BF8E700201749174A914200 -:100510003CBF41F8040BFAE703F008F903F022F9B5 -:10052000134C144DAC4203DA54F8041B8847F9E726 -:1005300000F03AF8104C114DAC4203DA54F8041BA9 -:100540008847F9E703F0F0B8000900200011002007 -:10055000000000080001002000090020C041000840 -:1005600000110020741100207811002000260020C6 -:1005700060010008600100086001000860010008D7 -:100580002DE9F04FC1F80CD0C3689D46BDE8F08F4F -:10059000002383F311882846A047002002F07EFE46 -:1005A00002F0A8FD00DFFEE76FF01702364B2DE9E1 -:1005B000F0411A70032200245A7001266FF0630282 -:1005C0009C70DC701C715C719C71DC711C725A72C5 -:1005D0009E72DC7203F020F8804603F06DF8054649 -:1005E000D0BB2A4B984539D03344984537D0284B57 -:1005F00028F0FF029A4234D15FFA88F000F04EFAF8 -:100600002E4642F2107400F077FC00F04DFA0746D7 -:1006100058B364BB374635B11E4B984503D0002410 -:1006200003F042F82746002003F000F81A4B9B68BD -:1006300013F040031ED00FB100F030F800F07EFC44 -:1006400000F018FE00F014FF0546ACB900F0CCFC39 -:10065000012002F029FEF8E70646D4E706462C46BC -:10066000D1E706464FF47A74CDE70446D3E74FF45A -:100670007A74D0E71C46E1E700F0FAFE401BA04286 -:10068000E4D900F00BF8DDE778110020010007B095 -:10069000000008B0263A09B0000C014010B51C4B10 -:1006A0001C4953F8042F013200D110BD8B42F8D100 -:1006B000194C1A4B22689A4228D9194B9B6803F1AE -:1006C000006303F5C8439A4220D202F0C1FF02F052 -:1006D000D3FF002000F0E8FD0220124B187000F05C -:1006E0001FFE114BDA690022DA61D96999699A61B2 -:1006F0009B6972B60D4B0E4A202113601B6822685D -:1007000081F311889D4683F30888104710BD00BF10 -:10071000FC6300081C64000804640008FF63000810 -:1007200078110020841100200010024000640008AD -:1007300008ED00E049F2690008490B689AB21B0C09 -:1007400000FB02330B6044F25061054A136898B213 -:100750001B0C01FB0030106080B270470C110020B0 -:100760000811002010B504460021102200F0F4FD0D -:10077000034B03CB206061601868A06010BD00BF10 -:10078000E8F7FF1FF0B5BBB000F072FE1D4CA36888 -:10079000C31AF92B30D906AD2346A06028220021C8 -:1007A000284601F0F3FB04F10E0000F0CDFD00231C -:1007B000C6B2591D5F1CDBB2B3424FEAC10107DA72 -:1007C0000E3323440822284601F0E0FB3B46F0E7C5 -:1007D00001230393082302930B4B207B01933023C7 -:1007E000C1F3CF0105910093014604A3D3E900238F -:1007F0000495064801F09AF93BB0F0BD78F6339FB6 -:1008000093CACD8DC8210020D5210020A021002031 -:1008100070B50D4614461E4601F02EF950B9022E51 -:100820000ED1012C0CD112A3D3E90023C5E900237A -:10083000012070BD052C14D003D8012C09D0002054 -:1008400070BD282C09D0302CF9D10BA3D3E900239B -:10085000ECE70BA3D3E90023E8E70BA3D3E90023DC -:10086000E4E70BA3D3E90023E0E700BFAFF3008088 -:10087000401DA12026812A0B78F6339F93CACD8D87 -:100880009E6AC421818A46EE26417272DF25D7B75F -:10089000F017304A39059E5638B50D4604460346D2 -:1008A00020222846002101F071FB22792346032AE9 -:1008B00028BF0322284603F8042F2021022201F03A -:1008C00065FB62792346072A28BF0722284603F8DA -:1008D000052F2221032201F059FBA2792346072A82 -:1008E00028BF0722284603F8062F2521032201F0FE -:1008F0004DFB284604F108031022282101F046FB95 -:10090000382038BD2DE9F04FADF5017D21AE0EAD9B -:1009100040F2791280460F463046002100F01CFD5F -:1009200048220021284600F017FD00F0A1FD4FF4F9 -:100930007A72B0FBF2F0574B0DF15A09186093E848 -:10094000070001232B74002385E807000DF15A00EE -:100950006B74FFF707FF032385F82030E82385F841 -:10096000213006AB18464C4903F0E0F81C222864FD -:100970003146284685F83C20FFF78EFF12AB04462F -:1009800001460822304601F001FB08220DF149031F -:10099000A118304601F0FAFA0DF14A03082204F1D9 -:1009A0001001304601F0F2FA13AB202204F11801D5 -:1009B000304601F0EBFA14AB402204F13801304626 -:1009C00001F0E4FA16AB082204F17801304601F098 -:1009D000DDFA0DF15903082204F18001304601F0DF -:1009E000D5FA04F1880A04F5847B4B465146082267 -:1009F00030460AF1080A01F0C9FAD34509F10109A4 -:100A0000F3D11BAB08225946304601F0BFFA4FF034 -:100A1000000904F5887495F834304B4510D84FF030 -:100A2000000995F83C304B4515D92B6C21464B44B9 -:100A30000822304601F0AAFA083409F10109F0E76A -:100A4000AB6B21464B440822304601F09FFA083434 -:100A500009F10109DFE7E31DC3F3CF03F97E059335 -:100A6000002304960393BB7E193702930123019759 -:100A70000093404605A3D3E9002301F057F80DF594 -:100A8000017DBDE8F08F00BFAFF300809E6AC421F6 -:100A9000818A46EE88110020043D0008014B187041 -:100AA000704700BF94110020F0B5334B85B01C7B1C -:100AB00034B10E22314B1A810024204605B0F0BD1E -:100AC0002F4A02AB1068516803C308232D490DEB70 -:100AD00003022D4803F00CF8054630B90A22274BD3 -:100AE0002A481A8100F08CFCE6E70169B1F5CE3F97 -:100AF00006D90B22214B26481A8100F081FCDCE745 -:100B0000438BB3F57A7F09D00C211C4A214811810F -:100B10004FF47A72194600F073FCCEE71E4A024485 -:100B200002F11003994204D21022144B1B481A817F -:100B3000E3E710398E1A2046134900F09DFC074662 -:100B4000324605F11801204600F096FCAB689F4242 -:100B500002D1EB6898420AD00D22084B1A8100900E -:100B60003B46EA68A9680E4800F04AFCA4E70D4835 -:100B700000F046FC0124A0E7C821002088110020D5 -:100B8000D43B0008DC9B010000640008DC3B00084B -:100B9000E83B0008FA3B0008089CFFF7183C0008F7 -:100BA000353C00085E3C00082DE9F04FADB006AFC3 -:100BB00080460C4600F060FF054600286AD1237E7F -:100BC000022B18D1E38A012B15D100F051FC81468C -:100BD000FFF7B0FD4FF4C873B0FBF3F202FB130054 -:100BE000BB4E80B209F51679E37E484430608BB97C -:100BF0000022B84B1A709C37BD46BDE8F08F3B1DF4 -:100C00001D440095002308224FEAC901204601F047 -:100C100021F84D46A38A5FFA85F9013BAB420BD917 -:100C200005F10109B9F1110FE9D140F23911AA4BCF -:100C3000AA4AAB4802F02EFF07F11400FFF792FD1D -:100C40002A4607F11401381D02F042FF034600282E -:100C5000CED1B9F1100F07D09E4B83F800903368C6 -:100C6000A3F516733360C6E707F1980202F8950DF5 -:100C7000014600922046072200F0ECFFF9787F2918 -:100C800004DD984B954A4FF4A871D2E7404600F036 -:100C9000D7FEB0E7E38A052B00F0068106D8012BCA -:100CA000A9D121464046FFF72DFEA4E7282B3DD0D1 -:100CB000302BA0D1637E8C4D01336A7BDBB2934233 -:100CC000E94640F0EF80E27E2B7B9A4240F0EA80DA -:100CD000002607F1980323F8846D00931022012366 -:100CE0003146204600F0B6FFB4F81480A8F102089F -:100CF0001FFA88F808F1030323F003030A3323F0F3 -:100D00000703ADEB030D0DF1180A33469BB2B11C7E -:100D100098454FEAC10106F101066CDD534400938A -:100D200008220023204600F095FFEEE7A38A013B4E -:100D30009BB2C92B3FF65FAF6B4E357B4DBB06F1C7 -:100D40000C03009308222B462946204600F082FF20 -:100D5000A38A05F10109013BEDB29D424FEAC901A9 -:100D600009DA0E353544009500230822204600F0AC -:100D700071FF4D46ECE700230022C6E90023002363 -:100D8000B36086F8D730C6F8D830337B0BB9E37E32 -:100D90003373002507F114063B1D0822294630460F -:100DA0007D60BD60FD6001F0F1F83B7A05F101095D -:100DB000AB424FEAC90107D9FB6808222B443046F1 -:100DC00001F0E4F84D46F0E70023C1F3CF01E07EE7 -:100DD000059104960393A37E1934029328230146B8 -:100DE0000093019438A3D3E90023404600F09EFE0F -:100DF000FFF7C8FCFFE695F8D70000F05FFAD5F8DA -:100E0000D83006461BB995F8D70000F067FAD5F838 -:100E1000D83043449E4204D295F8D700013000F008 -:100E20005DFA00244FEA980BA0B2584504F1010482 -:100E300008DA2B6880000AEB00010122184400F058 -:100E400093FAF1E7D5F8D840D5E9002312EB080270 -:100E500043F10003444495F8D700C5E90023C5F8E1 -:100E6000D84000F02BFA844209D395F8D7300133EB -:100E700085F8D730D5F8D8309E1BC5F8D860B8F1C2 -:100E8000FF0F08DC00232B7300F03AFAFFF70CFE8B -:100E900008B1FFF703FC2B68144A9B0A0133138146 -:100EA0000023AB60CD46A6E6BFF34F8F1049114B30 -:100EB000CA6802F4E0621343CB60BFF34F8F00BFF8 -:100EC000FDE700BFAFF3008026417272DF25D7B780 -:100ED0009C21002099210020703C0008243D00083E -:100EE000C93C0008EB3C0008C82100208811002004 -:100EF00000ED00E00400FA0508B54FF000530B4A7E -:100F0000196891420AD1597D094A0A4811701B7D1E -:100F1000C922037308490E3000F00CFABDE80840FE -:100F2000E02200214FF0005000F016BA9AAD44C5FF -:100F300094110020C821002016000020022330B5A3 -:100F40001F4C85B0637104230025ADF808300123E0 -:100F50000722ADF80C501B498DF80C308DF80B3082 -:100F6000194B1A484B608DF80A2001F0FFFD184B11 -:100F7000019500931749184B4FF48052174800F021 -:100F800029FD174B2546197811B1144800F058FD7A -:100F900000F06EFA0446FFF7CDFB4FF4C873B0FBC8 -:100FA000F3F202FB130304F516749BB21C440D4BC1 -:100FB0001C6002F081FB08B10F232B8105B030BD0E -:100FC000881100200011002003000600E02200200C -:100FD0001108000898110020A90B0008A02100208A -:100FE000941100209C2100202DE9F04F96A7D7E90D -:100FF00000670FF25C29D9E900898F4C93B0DFF8C4 -:1010000058B2DFF858A2204600F0DCFD0CAD079086 -:1010100098B310220021284600F09EF94FF00002FC -:10102000079B197B61F3030219468DF8302051F8B4 -:10103000040F0EAA496803C21B680D9A584663F351 -:101040001C029DF830300D9243F020038DF83030B3 -:1010500000232A46194601F099FD079030B9204631 -:1010600000F0B4FD079B8AF80030CCE79AF8003016 -:10107000072B40DC01338AF8003018220021284673 -:1010800000F06AF9DFF8D0B1DFF8D4A100232A46D6 -:101090001946584601F0A2FD014680BB102208A85F -:1010A00000F05AF9DAF80C3083F01003CAF80C306B -:1010B00000F0E0F90DF1240E0B4612A9024611E9E9 -:1010C00003008EE803009DF83410C1F30300890685 -:1010D00049BF0E99BDF83810C1F31C0141F0004121 -:1010E00058BFC1F30A018DF82C000891204608A9C9 -:1010F00000F0B2FFCAE7204600F068FDBDE72046D9 -:1011000000F0BAFC824600284AD100F0B1F9DFF8BD -:1011100054B1DBF80030984242D300F0A9F90790AF -:10112000FFF708FB4FF4C873B0FBF3F101FB1300AA -:10113000079A80B202F516721044CBF80000DFF86F -:1011400028B18DF820A09BF8001011B901238DF86B -:10115000203028460791FFF705FB07990DF1210084 -:10116000C1F1100A5FFA8AFABAF1060F28BF4FF0F0 -:10117000060A2944524600F0DDF80AF101030493FF -:1011800008AB0393182302932C4B3246019301239F -:10119000204600933B4600F071FC00238BF80030A2 -:1011A00000F066F9264ADFF8C4A01368C31AB3F545 -:1011B0007A7F32D3106000F05DF902460B4620467C -:1011C00000F00AFD204600F057FC30B39AF80C30CE -:1011D000DFF89CB0002B14BF032302238BF80530EB -:1011E00000F046F94FF47A73B0FBF3F02946CBF8E0 -:1011F00000005846FFF750FB18230293114B0730AD -:10120000019340F25513C0F3CF000490009303956F -:1012100042464B46204600F031FC9AF80C300BB1A8 -:10122000FFF7B0FA9AF80C30002B7FF4E8AE13B059 -:10123000BDE8F08FAFF30080A021002098210020AE -:10124000A8220020AC220020401DA12026812A0BCC -:10125000F1C6A7C1D068080FE0220020AD2200200F -:10126000000801409C21002099210020C821002075 -:101270008811002070B502F0CDF80025084C094E09 -:10128000207030682378834208D902F0BFF83368B1 -:1012900005440133B5F5C84F3360F2D370BD00BFCC -:1012A000DC220020B022002002F04CB900F10060E6 -:1012B000920000F5C84002F0F1B80000054B1A6832 -:1012C000054B1B789B1A834202D9104402F09EB84A -:1012D00000207047B0220020DC22002038B50446F0 -:1012E000064D2868204402F097F828B92868204461 -:1012F000BDE8384002F0A2B838BD00BFB0220020DF -:10130000064991F8243033B100230822086A81F895 -:101310002430FFF7CBBF0120704700BFB42200206C -:10132000022802BF4FF48012014B1A61704700BFC0 -:1013300000080140002310B5934203D0CC5CC45494 -:101340000133F9E710BD000002460346981A13F96D -:10135000011B0029FAD1704703460244934202D090 -:1013600003F8011BFAE770472DE9F047234C0546C7 -:1013700094F824308846174683BB2E46DFF87C90CD -:10138000C7B394F824302BB92022FF2148462662A7 -:10139000FFF7E2FF94F824004146C0F10805BD4282 -:1013A00028BF3D465FFA85FAAD002A4604EB80006F -:1013B000FFF7C0FF94F82430A7EB0A079A445FFABE -:1013C0008AFABAF1080F2E44A844FFB284F824A088 -:1013D000D6D1FFF795FF0028D2D108E0266A06EBA8 -:1013E0008306B042CAD0FFF78BFF0028C5D100208A -:1013F000BDE8F0870120BDE8F08700BFB4220020DF -:101400000FB4002004B070470FB44FF0FF3004B0A9 -:1014100070470000FEE70000EFF30983EFF3058358 -:10142000034B9A6B9A6A9A6A9A6A9A6A9B6AFEE76F -:1014300000ED00E0EFF30983EFF30583044B9A6BB3 -:101440009A6A9A6A9A6A9A6A9A6A9B6AFEE700BFDF -:1014500000ED00E0EFF30983EFF30583034B5A6BD4 -:101460009A6A9A6A9A6A9A6A9B6AFEE700ED00E0B5 -:1014700002F0A0B802F07AB830B5084D0A449142A3 -:101480000BD0092411F8013B5840013CF7D040F340 -:1014900000032B4083EA5000F7E730BD2083B8ED0E -:1014A0000246006848B1036811891360D38801338C -:1014B0009BB29942D38038BF1381704770B5044600 -:1014C0000D4688B0202200216846FFF745FF2046E0 -:1014D0000495FFF7E5FF054658B16B46044608AE94 -:1014E0001A4603CAB24220606160134604F1080440 -:1014F000F6D1284608B070BD2DE9F04130B940F270 -:10150000C531264B264A274802F0C4FA0B7C23B982 -:10151000254B234A40F2C631F5E7C66986B9C16159 -:10152000BDE8F081002B29DA930CAB4229D1B442FB -:1015300001D10C60F3E7C8F800100C60BDE8F08141 -:101540004B68B04623F06047BD0C15EA230538BF51 -:101550003D4634464FEAD37EC3F3807C6368BEEBDE -:10156000D37F23F06042DDD1974203D1C3F3807370 -:101570009C450AD1974205E01C46EFE7AA4206D0F7 -:1015800013469D422CBF00230123002BCFD123689B -:10159000A046002BF0D12160BDE8F081F83F0008A3 -:1015A000EC3D0008B0400008D140000808B5034AEF -:1015B000034B40F25E31034802F06CFAC83D00086C -:1015C00070400008B040000808B503680B60C3888D -:1015D000016033B9044B054A4FF4C761044802F077 -:1015E00059FA013BC38008BD404000083C3E00085A -:1015F000B040000870B50C4600F10C05616831B9C7 -:10160000E38A002061F30903E382002170BD0E68C4 -:101610002846FFF7D9FF6660F0E7000008B542688A -:1016200032B10B4B0B4A40F22F410B4802F032FA19 -:10163000C37DC3F38401013161F38603C375C38A9B -:1016400062F30903C3821B0A62F3C713C37508BDA3 -:101650008C400008F83D0008B04000082DE9F04734 -:10166000089E32B91F4B204A40F239511F4802F000 -:1016700011FA4FF47F4901F007054FEAD6082A44D2 -:1016800006F0070600EBD100954201D1BDE8F087D6 -:1016900005F0070E06F0070AD645774638BF5746CD -:1016A000511BC7F108078F4228BF0F46EC08045DA5 -:1016B00008EBD60113F801C004FA0EF429FA07FE6C -:1016C00024FA0AF45FFA8EFE8CEA04044EFA0AFE4B -:1016D00004EA0E048CEA040C03F801C03D443E44C5 -:1016E000D2E700BF0C400008103E0008B0400008E0 -:1016F0002DE9F04106460F4600254FF6FF7441F2F2 -:1017000021082A4630463946FEF72AFD0823C0B292 -:1017100084EA002414F4004F4FEA4404A4B203F115 -:10172000FF3318BF84EA080413F0FF03F2D1083531 -:10173000402DE6D12046BDE8F081000010B541F211 -:1017400021040A44914200D110BD11F8013B80EA06 -:101750000320082310F4004F4FEA400080B203F149 -:10176000FF3318BF604013F0FF03F3D1EAE7000036 -:101770002DE9F04F85B08A468DE80C00BDF83C405D -:10178000814630B940F26E31484B494A494802F02F -:1017900081F911F0604F04D0474B454A40F26F3158 -:1017A000F4E7009B002B7ED024B10E9B002B7AD057 -:1017B000072C28D809F10C00FFF772FE054628B95E -:1017C0006FF00205284605B0BDE8F08F1422002115 -:1017D000FFF7C2FD22460E9905F10800FFF7AAFDAA -:1017E000631C2B74009B2C441B78294603F01F03B9 -:1017F00063F03F0323724AF000436B604846FFF7F3 -:101800007BFE0125DEE74FF000084FF0800B4646D7 -:101810004546019B1B0A029300F10C0303930398B6 -:10182000FFF73EFE07460028CAD014220021FFF72A -:1018300093FDB6BB02229DF804303B729DF8083040 -:101840007B720E9B711E1944B4420AD9B81801323A -:1018500011F801EFD2B20136072A80F808E0B6B2DB -:10186000F2D1B44208BF4FF0400B009BB818197872 -:10187000013201F01F0141EA48114BEA01030372F2 -:101880004AF000437B603A7439464846FFF734FE1D -:101890000135B4422DB288F001084FF0000BBED1E3 -:1018A00090E70022CDE76FF001058BE7F83F0008D5 -:1018B000DC3D0008B04000081C4000082DE9F0475E -:1018C0001E46CB8A9146C3F30902062A80460F467C -:1018D00019D013460021B0B28DB25A1992B2052A1E -:1018E00009D9A84210D8FA8A034463F30902FA829C -:1018F0000120BDE8F087A842F3D919F801403A4425 -:1019000094760131E8E70025FB8A7C68C3F309007F -:101910001C23821FB2FBF3FA03FB1A2A1FFA8AF276 -:101920007CB301212368002B39D1B31F03441C2051 -:10193000B3FBF0F301339BB299420CD2BAF1000F22 -:1019400009D14046FFF7ACFD08B1C0F800A0206007 -:1019500008B3044600224FF0000AB6B2B54230D2B6 -:101960001346691E4944E018013311F801EF9BB298 -:1019700001351C2B80F804E0ADB214D0AE42F2D891 -:10198000ECE74046FFF78CFD044608B100230360F6 -:101990007C60002CDED16FF00200BDE8F0870131E1 -:1019A00089B21C46BEE7AE42D8D94046FFF778FD63 -:1019B00008B1C0F800A020600028ECD00446002246 -:1019C000CCE7FB8AC3F30902164466F30903FB82E2 -:1019D0008EE70000F8B50E4615461F46044628B9A6 -:1019E000144B154A4F21154802F054F824220021C7 -:1019F000FFF7B2FC069B6A096360079B0020236225 -:101A00004FF6FF739A4228BF1A46A7602070A06164 -:101A1000E06197B204F10C05824205D100232B60EE -:101A200027826382A382F8BD2E60013035462036BE -:101A3000F2E700BFF43F0008683D0008B04000082E -:101A400008B528B97321084B084A094802F022F862 -:101A5000037823B94BB2002B01DD017008BD054BA3 -:101A6000024A7D21F1E700BFF83F0008743D0008FD -:101A7000B04000083C3F0008007870472DE9F7436C -:101A80000D9E074619461046BDF828900B9D9DF8FF -:101A90003040BDF8388016B9B8F1000F43D11F2C83 -:101AA00041D83B78D3B9B8F1070F39D839F00303DF -:101AB00039D1424631464FF6FF70FFF73FFE4FEAFD -:101AC000092920F0010009F44079400449EA04643E -:101AD000400C44EA40244FF6FF730DE043EA09232B -:101AE000B8F1070F43EA0464F5D9FFF701FE424657 -:101AF0003146FFF723FE03468DE840012A46214682 -:101B00003846FFF735FE0DB9FFF750FD2B7801334E -:101B1000DBB21F2B88BF00232B7003B0BDE8F0831E -:101B20006FF00300F9E76FF00100F6E72DE9F743E6 -:101B30000E9F81460B9D9DF830009DF83480BDF8C6 -:101B40003C6007B9C6BB1F2836D899F800E0BEF143 -:101B5000000F34D00C0244F080049DF8281044EAB1 -:101B6000C83444EA014444EA0E04072E44EA0064FF -:101B700015D919461046FFF7BBFD32463946FFF727 -:101B8000DDFD0346019600972A4621464846FFF7A9 -:101B9000EFFDB8F1010F0CD125B9FFF707FD4FF6A6 -:101BA000FF73EFE72B780133DBB21F2B88BF0023D5 -:101BB0002B7003B0BDE8F0836FF00100F9E76FF020 -:101BC0000300F6E7C06900B104307047C1690C300A -:101BD0000B680361FFF7F8BC2DE9F84FD0F818A0A7 -:101BE000054616461F4654464FF00009DFF8608050 -:101BF00000F10C0B0CB9BDE8F88FD4E90223B21A3E -:101C000067EB0303994508BF90451FD2AB69214696 -:101C10009C4228460DD1FFF7EDFCAB6921461B68BD -:101C20005846AB61FFF7D0FCAC692346A2461C4680 -:101C3000E0E7FFF7DFFC23682146CAF8003058468A -:101C4000FFF7C2FC5446DAF80030EFE72368EDE70F -:101C500080841E002DE9F04F8BB00D46144607938B -:101C6000DDF850908246002800F06481B9F1000F41 -:101C700000F06081531E3F2B00F25C81012A03D1EA -:101C8000079B002B40F056810023BAF8146008939C -:101C9000F600B542099380F053812B199E420AD277 -:101CA000761B16F0FF0607D140F26751AA4BAB4AEC -:101CB000AB4801F0EFFE2646DAF80C3023B9DAF82B -:101CC0001030002B00F0A5802F2D31D8C5F1300841 -:101CD00046454FF0000334BFB0465FFA88F80093E2 -:101CE000294608AB4246DAF80800FFF7B7FCA6EB36 -:101CF00008074544FFB24FF0300BBAF8143003F137 -:101D00000053063BDB000293DAF80C300593059B89 -:101D1000002B51D087B9DAF81000002861D0002FCD -:101D20005FD0AB4550D98F4B8C4A40F2A651BFE7EC -:101D300037464FF00008DEE7029B23B98A4B874AFB -:101D40004FF4B161B4E7029BE02B28BFE023069378 -:101D50005B44AB4204931DD95B1B9F4226BFDBB2A1 -:101D600003930397AB4504D97E4B7C4A40F29151D3 -:101D70009EE70598CDF8008008ABA5EB0B01039A10 -:101D80000430FFF76BFC039B9844FF1A1D445FFA75 -:101D900088F8FFB2049B9B4504D3744B6F4A40F212 -:101DA0009B5185E7029B069ADDF810B09B1A0293BF -:101DB000059B1B680593AAE7029BBB42ABD26C4B09 -:101DC000664A40F2A15173E7CDF800803A46A5EB90 -:101DD0000B0108ABB8443D44FFF740FC00275FFA15 -:101DE00088F8BAF81430B5EBC30F04D9614B5B4ADD -:101DF00040F2B1515CE7B8F1400F04D95E4B574A4D -:101E000040F2B25154E767B15C4B544A40F2B351CF -:101E10004EE70093324608AB2946DAF80800FFF790 -:101E20001DFC731E3F2B35B201D8A64204DD544B76 -:101E3000544A40F235213BE760070AD00AAB03EB76 -:101E4000D40111F8083C624202F00702134101F884 -:101E5000083C082C21D9102C21D9202C8CBF082318 -:101E60000423079A002A6DD0B4EBC30F6CD0082C62 -:101E700004F1FF3215D89DF8203023FA02F2D10781 -:101E800006D54FF0FF3202FA04F423438DF82030D8 -:101E90009DF8203089F800304EE00123E1E702236D -:101EA000DFE7102C11D8BDF8203023FA02F2D20758 -:101EB00006D54FF0FF3202FA04F42343ADF8203088 -:101EC000BDF82030A9F8003036E0202C0ED8089953 -:101ED00021FA02F2D30705D54FF0FF3303FA04F4D9 -:101EE0000C430894089BC9F8003025E0402C1CD016 -:101EF000DDE9086730463946FEF732F9002100F087 -:101F0000010050EA01030BD0224601200021FEF718 -:101F100033F9404261EB410106430F43CDE90867C5 -:101F2000DDE90823C9E9002306E0174B154A4FF401 -:101F30002071BDE66FF0010528460BB0BDE8F08FBB -:101F40001D46F9E7012CA3D0082CA1D9102CB7D934 -:101F5000202CE5D8C6E700BF483E0008203E000818 -:101F6000B04000086A3E0008573E00088F3E000857 -:101F7000B73E0008DE3E00080C3F0008243F000882 -:101F80003E3F0008A03D00083C3F000830B585B04A -:101F900030B940F2B121234B234A244801F07AFDA5 -:101FA00023B9234B204A40F2B221F6E7402A04D954 -:101FB000204B1D4A40F2B621EFE722B91D4B1A4AC9 -:101FC0004FF42F71E9E70024012A0294039417D1FA -:101FD0001B788DF8083053070AD004AB03EBD2030B -:101FE00013F8084C554205F00705AC4003F8084CBF -:101FF00000910346002102A8FFF730FB05B030BD79 -:10200000082AE5D9102A03D81B88ADF80830E2E782 -:10201000202A02D81B680293DDE7D3E90045CDE909 -:102020000245D8E7783F0008B43D0008B0400008FA -:10203000933F00083C3F000870B50C4600F10C05CA -:10204000E16819B9A1602161A18270BD0E682846BE -:10205000FFF7BAFAE660F3E72DE9F04FD1F8009008 -:1020600091B0C9F3C01604460D46CDE90223002EF7 -:1020700050D0C9F3C03BC9F30626B9F1000F80F276 -:102080009F8119F0C04F40F09B812B7B002B00F00B -:102090009781BBF1020F03D02278B24240F09381C6 -:1020A00009F07F02BBF1020F059236D119F07F0FC4 -:1020B000C9F30F2A01D10AF0030A2B447606059AC8 -:1020C00093F8038046EA0B4646EA82465FEAD81355 -:1020D00046EA0A06069300F09A800022002310A91F -:1020E00061E90823059B6768009352465B462046DA -:1020F000B847002800F08880A7698FB9314604F1FD -:102100000C00FFF7DBF90746D0B96FF0020011B001 -:10211000BDE8F08F4FF0020BAFE7C9F3074ACCE7F9 -:102120003B699E420DD03F68002FF9D1314604F142 -:102130000C00FFF7C3F907460028E6D0A3693B600F -:10214000A761DDE90801FFF7D3FAB882F97D08F04D -:102150001F06C1F38401711A89B20FFA81FEBEF124 -:10216000000FB8BF01F1200EC9F30461D7E90223C3 -:10217000B8BF0FFA8EFE079152EA030100F02F81DB -:10218000DDE90201801A61EB03010B4600210246E2 -:102190009E48994208BF9042C0F02181069B002BC7 -:1021A0003FD0BEF1010F00F31A8118F0400F38D074 -:1021B000DDE90223C7E90223202200210DEB020002 -:1021C000FFF7CAF8DDE90223CDE908232B1D0A93A6 -:1021D0002B7B2046013BDBB2ADF834309DF81C3040 -:1021E000ADF836A08DF83A309DF814308DF838B03F -:1021F0008DF83B308DF83960A36808A998473846B8 -:10220000FFF70CFA002082E76FF00B007FE7A76969 -:1022100017B96FF00C007AE73B699E4296D03F6891 -:10222000F6E7FB7DC8F34012B2EBD31F40F0CE803F -:10223000C3F38403B34240F0CC8006992B7B4FEA72 -:10224000981279B3D2073CD4032B40F2C580DDE964 -:102250000223C7E902232B7BAE1D033BDBB23246D0 -:10226000394604F10C00FFF729FB002808DA39464B -:102270002046FFF7BFF93846FFF7D0F9032046E7BD -:10228000AB883B832A7B033AD2B2B88A3146FFF748 -:1022900055FAFB7DB882DA43C2F3C01262F3C7136A -:1022A000FB75AFE76AB92E1D013BDBB232463946FA -:1022B00004F10C00FFF702FB0028D8DB2A7B013A6F -:1022C000E2E7FA8A013BC2F30902052AD9B250D8E3 -:1022D0000023281D99420AD907EB020E10F801CB02 -:1022E00001320133062A8EF81AC0DBB2F2D18B42DA -:1022F00028BF0023DDE9028907F11A02CDE9088928 -:102300000A927A683CBF04335B190B920C93FB8AE8 -:10231000ADF836A0C3F3090319449DF81C30ADF89D -:1023200034108DF83A309DF814308DF838B08DF8AF -:102330003B3000238DF839607B602A7BB88A013AF4 -:10234000291DFFF7FBF93B8BB882834203D1A368B9 -:1023500008A92046984708A92046FFF76DFE384691 -:10236000FFF75CF9B88A3B8B984214BF112000201C -:10237000CDE6786810B34FF0060E03689BB9A2EB68 -:102380000E021B2A13D80332024405F1040E1F303B -:102390009942ACD91EF801CB013302F801CF90422B -:1023A000DBB2F5D1A3E70EF11C0E1846E5E7184B9A -:1023B000184A40F2B311184801F06CFB034696E747 -:1023C0006FF00900A3E66FF00A00A0E66FF00D00C1 -:1023D0009DE66FF00E009AE66FF00F0097E6FB7D2A -:1023E000394668F386036FF3C713FB752046FFF782 -:1023F00001F9069B002B7FF4D8AEFB7DC3F384026A -:10240000013262F38603FB7503E700BF80841E0080 -:10241000A83F00088C3D0008B04000082DE9F041BD -:102420004E4EB04240F086804D4CDFF838E1E56911 -:1024300045F00075E561E469846AD4F8007207EA42 -:102440000E0747F00107C4F80072D4F8005205EAFD -:102450000E0545F0010545EA0121C4F80012002AE5 -:102460006AD000210F46C4F81C12C4F80412C4F844 -:102470000C12C4F8141204EBC10501310E29C5F881 -:102480004072C5F84472F6D14FF0000E4FF0010CC7 -:10249000964510D1826AB042D2F8003223F001038F -:1024A000C2F8003258D12E4BDA6922F00072DA619C -:1024B000DB69BDE8F0819F781D8817F0010F18BF18 -:1024C000D4F804820CFA05F11CBF41EA0808C4F8EC -:1024D000048217F0020F18BFD4F80C8204EBC50574 -:1024E0001CBF41EA0808C4F80C827F0748BFD4F833 -:1024F000147203F10C0344BF0F43C4F8147253F871 -:10250000087C0EF1010EC5F8407253F8047CC5F842 -:102510004472D4F81C522943C4F81C12B8E70021B5 -:10252000846AC4F81C12C4F80412C4F80C12C4F86B -:102530001412A9E7002AF2D10022836AC3F84022CC -:10254000C3F84422C3F80422C3F814220122C3F8BA -:102550000C22C3F81C229DE7BDE8F081E022002098 -:10256000001002400000FFFF184A08B5916A8B680E -:102570008B6013F0010105D013F00C0F14BF4FF462 -:1025800080310121D80506D513F4406F14BF41F402 -:10259000003141F00201D80306D513F4402F14BFD7 -:1025A00041F4802141F00401D3690BB107489847F9 -:1025B000202383F311880021054800F09DFE0023AD -:1025C00083F31188BDE8084001F086B8E0220020BE -:1025D000E822002038B5124CA36ADD68AA0712D0A1 -:1025E0005A6922F002025A61A36913B101212046FF -:1025F0009847202383F3118800210A4800F07CFECD -:10260000002383F31188EB0606D51021A36AD96055 -:10261000236A0BB102489847BDE8384001F05CB826 -:10262000E0220020F022002038B5124CA36A1D6978 -:10263000AA0712D05A6922F010025A61A36913B195 -:10264000022120469847202383F3118800210A485D -:1026500000F052FE002383F31188EB0606D510210B -:10266000A36A1961236A0BB102489847BDE8384054 -:1026700001F032B8E0220020F022002038B50F4CE3 -:10268000A36A5D682A075D600AD5032222701A6872 -:1026900022F002021A60636A13B1002120469847B3 -:1026A0006B0706D5A36A9969236A13B10904034825 -:1026B0009847BDE8384001F00FB800BFE022002085 -:1026C00010B50F4C204600F03FFA0E4B0B211320A3 -:1026D000A36200F019FA0B21142000F015FA0B2167 -:1026E000152000F011FA0B21162000F00DFA00233E -:1026F0002046BDE810401A460E21FFF78FBE00BFEE -:10270000E0220020006400400F4B10B598420446C0 -:1027100005D10E4BDA6942F00072DA61DB69012201 -:10272000A36A1A60A36A5A68D20707D5626851681B -:102730001268D9611A60064A5A6110BD0121082049 -:1027400000F092FCEEE700BFE02200200010024003 -:102750005B87010003291AD8DFE801F0020A0F1491 -:10276000836A9B6813F0E05F14BF0120002070476C -:10277000836A9868C0F380607047836A9868C0F382 -:10278000C0607047836A9868C0F30070704700208B -:102790007047000010B503291FD8DFE801F0021FC1 -:1027A0002327816A8B68C3F30163183301EB03139A -:1027B000107881061ED55468C0F30011490041EA23 -:1027C000C40141F0040100F00F005860906841F02E -:1027D00001019860D268DA60196010BD836A03F560 -:1027E000C073E5E7836A03F5C873E1E7836A03F51D -:1027F000D073DDE79488C0F30011490041EA4451E9 -:10280000E1E7000001290CD003D3022910D00020F9 -:102810007047836ADA68920701D1186903E00120E2 -:102820007047836AD86810F0030018BF0120704712 -:10283000836AF2E710B539B9836AD96889071BD171 -:102840001B699B0704D110BD012915D0022948D16D -:10285000816AD1F8C031D1F8C401D1F8C8411461FE -:10286000D1F8CC41546120240C610C69A40717D124 -:102870004C6944F0100412E0816AD1F8B031D1F80B -:10288000B401D1F8B8411461D1F8BC41546120249D -:10289000CC60CC68A40703D14C6944F002044C61BD -:1028A00011795C0864F304119C0864F345111171FB -:1028B00089064BBF91681189DB085B0D4CBF63F340 -:1028C0001C0163F30A01137948BF916060F30303AD -:1028D00013714FEA10234FEA104058BF1181137053 -:1028E000508010BD00231A4610B51C495A50CC1810 -:1028F0000833802B6260F9D1194B9A6942F07D024E -:102900009A619B690268174BDA6082685A60426874 -:102910001A60C26803F58063DA6042695A6002692E -:102920001A608269C3F80C24026AC3F80424C269DD -:10293000C3F80024426AC3F80C28C26AC3F804280A -:10294000826AC3F80028026BC3F80C2C826BC3F8B0 -:10295000042C426BC3F8002C10BD00BF0C230020D8 -:102960000010024000080140026843681143016002 -:1029700003B1184770470000024AD36843F0C00310 -:10298000D360704700380140024AD36843F0C00367 -:10299000D3607047004400402DE9F041D0F89C60BE -:1029A0000546F7683368DA059CB20DD5202383F31A -:1029B00011884FF400710430FFF7D6FF6FF4807375 -:1029C0003360002383F31188202383F3118805F1FA -:1029D000040814F02F0333D183F31188380615D57A -:1029E000210613D5202383F3118805F1380000F068 -:1029F0002FFA002846DA0821281DFFF7B5FF4FF609 -:102A00007F733B40F360002383F311887A060ED571 -:102A100063060CD5202383F31188EA6C2B6D9A4250 -:102A200002D12B6C002B2FD1002383F31188D5F812 -:102A3000A420D368002B31D0BDE8F04110691847BD -:102A4000230713D014F0080F0CBF00218021E007EA -:102A500048BF41F02001A20748BF41F04001630791 -:102A600048BF41F480714046FFF77EFFA4067368BB -:102A700005D595F8A0102846194000F089FA346869 -:102A8000A4B2A6E77060BEE727F040073F0410211C -:102A9000281D3F0CFFF768FFF760C5E7BDE8F08130 -:102AA00008B50348FFF778FFBDE8084000F014BE02 -:102AB0008C23002008B50348FFF76EFFBDE80840EF -:102AC00000F00ABE3424002010B5094C094A204603 -:102AD000002100F03DFA084B084AC4F89C30084C2D -:102AE0000021204600F034FA064BC4F89C3010BD9B -:102AF0008C2300207929000800380140892900082A -:102B0000342400200044004000F16043090103F533 -:102B10006143C9B283F80013012300F01F0240098A -:102B2000800000F16040934000F56140C0F88031C2 -:102B300003607047090100F16040C9B200F56D40C3 -:102B400001767047FFF7BCBD01230370002300F13D -:102B500008028260C26000F11002436002614261BB -:102B60008361C361036243627047000010B5202394 -:102B7000044683F31188022341600370FFF7C4FD0C -:102B800003232370002383F3118810BD2DE9F04146 -:102B90001F4604460D461646202383F3118800F194 -:102BA00008082378042B0ED029462046FFF7D2FDD3 -:102BB00048B1204632462946FFF7ECFD002080F35D -:102BC0001188BDE8F0813946404600F079FB0028C5 -:102BD000E7D0002383F31188BDE8F0812DE9F041AF -:102BE0001F4604460D461646202383F3118800F144 -:102BF00010082378042B0ED029462046FFF702FE4A -:102C000048B1204632462946FFF714FE002080F3E3 -:102C10001188BDE8F0813946404600F051FB00289C -:102C2000E7D0002383F31188BDE8F081F8B515469D -:102C300082680B46AA428169066938BF8568761AA0 -:102C4000B542044607D218462A46FEF773FBA3692D -:102C50002B44A3610DE011D932461846FEF76AFBFA -:102C6000AF1B3A46E1683044FEF764FBE2683A4441 -:102C7000A261A36828465B1BA360F8BD18462A46DC -:102C8000FEF758FBE368E4E72DE9F04104461546FA -:102C900083682669934238BF856840690F46361AB3 -:102CA000B54206D22A46FEF745FB63692B446361B1 -:102CB0000DE012D93246A5EB0608FEF73BFB424673 -:102CC000B919E068FEF736FBE26842446261A36826 -:102CD00028465B1BA360BDE8F0812A46FEF72AFB6D -:102CE000E368E4E710B50024C361029B0A44006076 -:102CF00040608460C160816141610261036210BD16 -:102D000008B582694369934201D1826882B98268B9 -:102D1000013282605A1C42611970426903699A4209 -:102D200001D3C3684361002100F0DAFA002008BD36 -:102D30004FF0FF3008BD000070B5202304460E465A -:102D400083F31188A568A5B1A368A269013BA360BC -:102D5000531CA36115782269934224BFE368A361E1 -:102D6000E3690BB120469847002383F31188284676 -:102D700070BD3146204600F0A3FA0028E2DA85F360 -:102D8000118870BD2DE9F74F05460F4690469A46CB -:102D9000D0F81C90202686F311884FF0000B1446C3 -:102DA00064B1224639462846FFF740FF034668B91A -:102DB0005146284600F084FA0028F1D0002383F31E -:102DC0001188A8EB040003B0BDE8F08FB9F1000F43 -:102DD00003D001902846C847019B8BF31188E41A61 -:102DE0001F4486F31188DBE7C361009BC1608161EA -:102DF000416111440060406082600161036270477C -:102E0000F8B504460E461746202383F31188A568BB -:102E1000A5B1A368013BA36063695A1C62611E707F -:102E2000236962699A4224BFE3686361E3690BB175 -:102E300020469847002080F31188F8BD3946204687 -:102E400000F03EFA0028E2DA85F31188F8BD0000B0 -:102E50008369426910B59A4201D182687AB9826861 -:102E6000013282605A1C82611C7803699A4201D344 -:102E7000C3688361002100F033FA204610BD4FF093 -:102E8000FF3010BD2DE9F74F05460F4690469A4694 -:102E9000D0F81C90202686F311884FF0000B1446C2 -:102EA00064B1224639462846FFF7EEFE034668B96C -:102EB0005146284600F004FA0028F1D0002383F39D -:102EC0001188A8EB040003B0BDE8F08FB9F1000F42 -:102ED00003D001902846C847019B8BF31188E41A60 -:102EE0001F4486F31188DBE70268436811430160E1 -:102EF00003B11847704700001430FFF743BF0000CC -:102F00004FF0FF331430FFF73DBF00003830FFF7BC -:102F1000B9BF00004FF0FF333830FFF7B3BF0000F8 -:102F20001430FFF709BF00004FF0FF311430FFF7F6 -:102F300003BF00003830FFF763BF00004FF0FF32DF -:102F40003830FFF75DBF000000207047FFF7BCBDC1 -:102F50000E4B37B50360002343608360C3600123D9 -:102F6000044615460374202200900B4600F15C01D4 -:102F70001430FFF7B7FE00942B46202204F17C01A9 -:102F800004F13800FFF730FF03B030BDEC4000081B -:102F900038B5C36904460D461BB904210844FFF740 -:102FA000A3FF294604F11400FFF7AAFE002806DA61 -:102FB000201D4FF48061BDE83840FFF795BF38BD54 -:102FC0000022024B1B605B609A607047DC2400208B -:102FD000002382680374054B1B6899689142FBD2F9 -:102FE0005A6803604260106058607047DC2400201B -:102FF00008B5202383F31188037C032B05D0042B11 -:103000000DD02BB983F3118808BD002243691A60E3 -:103010004FF0FF334361FFF7DBFF0023F2E790E857 -:103020000C001A6002685360F2E700000023826817 -:103030000374054B1B6899689142FBD85A6803607A -:103040004260106058607047DC240020054B19690D -:1030500008741868026853601A60186101230374C9 -:10306000FDF78EBADC24002030B54B1C87B0054636 -:103070000A4C10D023690A4A01A800F059F92846E1 -:10308000FFF7E4FF049B13B101A800F06BF923697B -:10309000586907B030BDFFF7D9FFF8E7DC240020FE -:1030A000F12F000838B50C4D41612B6981689A6891 -:1030B0000446914203D8BDE83840FFF789BF18465F -:1030C000FFF786FF01232C61014623742046BDE8EB -:1030D0003840FDF755BA00BFDC240020044B1A68C5 -:1030E0001B6990689B68984294BF0020012070473C -:1030F000DC24002010B5084C236820691A6854604D -:103100002260012223611A74FFF790FF01462069B3 -:10311000BDE81040FDF734BADC24002008B5FFF705 -:10312000DDFF18B1BDE80840FFF7E4BF08BD0000AF -:10313000FEE7000010B5174CFFF742FF00F0EAF879 -:1031400080221549204600F06FF8012344F8180C3E -:103150000374124B124AD96821F4E0610904090C86 -:103160000A431049DA60CA6842F08072CA600E49A8 -:103170000A6842F001020A601022DA77202283F8FE -:103180002220002383F3118862B6BDE8104007486F -:1031900000F06CB8042500201441000800ED00E0A8 -:1031A0000003FA05F0ED00E0001000E01C4100080B -:1031B000F8B50F4C226A01322262224652F8141FDF -:1031C0009142154606D020268B68013B8B606369CF -:1031D0009A6802B1F8BD1968DF68DA604D60616114 -:1031E00082F311881869B84786F31188EFE700BFAA -:1031F000DC240020EFF3118020B9EFF305832022B7 -:1032000082F311887047000010B558B9EFF30584B8 -:10321000C4F3080414B180F3118810BDFFF77EFFDA -:1032200084F3118810BD0000826002220274002223 -:10323000427470478368A3F13C0243F80C2C026986 -:1032400043F83C2C426943F8382C074A43F81C2CBD -:10325000C268A3F1180043F8102C022203F8082CCE -:10326000002203F8072C70479105000810B52023B1 -:1032700083F31188FFF7DEFF00210446FFF712FFFA -:10328000002383F31188204610BD0000024B1B6908 -:1032900058610F20FFF7DABEDC240020202383F3DF -:1032A0001188FFF7F3BF000008B50146202383F320 -:1032B00011880820FFF7D8FE002383F3118808BD8A -:1032C00049B1064B42681B6918605A60136043603D -:1032D0000420FFF7C9BE4FF0FF307047DC24002008 -:1032E0000368984206D01A68026050605961184617 -:1032F000FFF76EBE7047000038B504460D462068E3 -:10330000844200D138BD036823605C604561FFF7EB -:103310005FFEF4E7054B03F114025A619A614FF026 -:10332000FF32DA6100221A62704700BFDC240020FD -:1033300010B5C2600A4A036153699C68A1420CD867 -:103340005C68036044602060586081609868411A3E -:1033500099604FF0FF33D36110BD091B1B68ECE788 -:10336000DC240020036881689A680A449A604268F5 -:10337000136003685A6000234FF0FF32C360014BB3 -:10338000DA617047DC24002000207047FEE700006F -:10339000704700004FF0FF3070470000BFF34F8FC1 -:1033A000024AD368DB07FCD4704700BF002002400C -:1033B00008B5074B1B7853B9FFF7F0FF054B1A69A7 -:1033C000120641BF044A5A6002F188325A6008BDB1 -:1033D000E0250020002002402301674508B5054B89 -:1033E0001B7833B9FFF7DAFF034A136943F0800310 -:1033F000136108BDE0250020002002407F289ABF0D -:1034000000F5003080020020704700004FF480601B -:1034100070470000802070477F2808B50BD8FFF761 -:10342000EDFF00F580630268013204D1043083426D -:10343000F9D1012008BD002008BD00007F2838B563 -:10344000044624D800F0B6F8124D2860FFF7A6FF16 -:10345000FFF7AEFFF322104B2046DA6002221A611A -:10346000FFF7CCFF58611A6942F040021A61FFF77A -:1034700095FF4FF4806100F0E9F8FFF7AFFF00F02F -:1034800099F828602046BDE83840FFF7C5BF002006 -:1034900038BD00BFE4250020002002402DE9F8439C -:1034A00012F00103144606D040F24B221F4B1A6063 -:1034B0000020BDE8F88385181D4A954204D94FF4D1 -:1034C00014711A4A1160F3E7FFF772FFFFF766FF06 -:1034D0004FF00109DFF86880451A012C05EB010661 -:1034E0000F4604D8FFF77AFF0120BDE8F883C8F83B -:1034F000109031F8023B3380FFF750FF0020C8F8EE -:10350000100033883A889BB29A420DD040F267226D -:10351000064B1A60074B1E60074B1C60074B1F6071 -:10352000FFF75CFFBDE8F883023CD6E7DC2500200E -:10353000FFFF0108D0250020D8250020D425002039 -:1035400000200240084908B50B7828B153B9FFF7AD -:103550002FFF01230B7008BD23B1BDE808400870A0 -:10356000FFF73CBF08BD00BFE025002038B5FFF7DE -:1035700041FE4FF47A730C490C4A0C6A116803FB44 -:1035800004F38B420A49D1E9004504D2003445F1E5 -:103590000105C1E90045E41845F100051360FFF796 -:1035A00033FE2046294638BDDC240020E8250020D3 -:1035B000F025002008B5FFF7D9FF4FF47A720023F9 -:1035C000FCF7E6FD08BD00BF10B5094C0439013A0F -:1035D000D2B2FF2A00D110BD53089800043054F82D -:1035E000233000599BB243EA004341F8043FEEE721 -:1035F000046C004030B50748013AD2B2FF2A00D12E -:1036000030BD0D88540840F82450A3004C88043382 -:103610001C50F1E7046C004007B5012201A900200D -:10362000FFF7D2FF019803B05DF804FB13B5044621 -:10363000FFF7F2FFA04206D002A941F8044D012293 -:103640000020FFF7D7FF02B010BD00007047000058 -:1036500045F25552064B1A6002225A6040F6FF723C -:103660009A604CF6CC421A600122024B1A707047E5 -:1036700000300040F9250020034B1B781BB14AF6AF -:10368000AA22024B1A607047F92500200030004042 -:10369000034B1B689B0042BF0122024B1A7070470C -:1036A00024100240F82500204FF08072014B1A6070 -:1036B000704700BF24100240014B1878704700BFCC -:1036C000F8250020EFF30983203383F309880023D2 -:1036D00083F311887047000010B5202383F311880D -:1036E0000D4B5B6813F4006312D0EFF309844FF0C5 -:1036F000807344F8043CA4F1200383F30988FFF7A6 -:10370000EDFC18B1054B44F8083C10BD044BFAE73A -:1037100083F3118810BD00BF00ED00E0A105000893 -:10372000A405000870470000FEE70000084A094BA6 -:1037300009498B4204D30021084A934205D37047BC -:1037400052F8040F43F8040BF3E743F8041BF4E7C3 -:10375000304200080026002000260020002600201D -:1037600000F030B808B500F063F9FFF7E3FCBDE8FE -:103770000840FFF78DBF0000704700004FF0FF3199 -:103780000E4B1A6919611A6900221A611869D86802 -:10379000D960D968DA60DA68DA6942F08052DA61B1 -:1037A000DA69DA6942F00062DA61054ADB691368B6 -:1037B00043F48073136000F01BB900BF0010024097 -:1037C00000700040194B1A6842F001021A601A6832 -:1037D0009007FCD51A6802F0F9021A6000225A60BC -:1037E0005A6812F00C0FFBD11A6842F480321A604A -:1037F0001A689103FCD55A6842F4E8125A601A68B4 -:1038000042F080721A601A689201FCD51221084AAF -:103810005A60084A11605A6842F002025A605A68B7 -:1038200002F00C02082AFAD1704700BF00100240D3 -:1038300000641D0000200240084A08B55369116861 -:103840000B4003F00103536123B1054A13680BB128 -:1038500050689847BDE80840FFF73EBF00040140AC -:103860000C230020084A08B5536911680B4003F087 -:103870000203536123B1054A93680BB1D06898479E -:10388000BDE80840FFF728BF000401400C230020DA -:10389000084A08B5536911680B4003F004035361EB -:1038A00023B1054A13690BB150699847BDE8084038 -:1038B000FFF712BF000401400C230020084A08B59E -:1038C000536911680B4003F00803536123B1054AA3 -:1038D00093690BB1D0699847BDE80840FFF7FCBE7B -:1038E000000401400C230020084A08B55369116800 -:1038F0000B4003F01003536123B1054A136A0BB167 -:10390000506A9847BDE80840FFF7E6BE0004014052 -:103910000C230020174B10B55C691A68144004F49E -:1039200078725A61A30604D5134A936A0BB1D06A20 -:103930009847600604D5104A136B0BB1506B98473B -:10394000210604D50C4A936B0BB1D06B9847E20566 -:1039500004D5094A136C0BB1506C9847A30504D5E4 -:10396000054A936C0BB1D06C9847BDE81040FFF747 -:10397000B3BE00BF000401400C2300201A4B10B559 -:103980005C691A68144004F47C425A61620504D5EB -:10399000164A136D0BB1506D9847230504D5134A91 -:1039A000936D0BB1D06D9847E00404D50F4A136EA8 -:1039B0000BB1506E9847A10404D50C4A936E0BB11D -:1039C000D06E9847620404D5084A136F0BB1506F4C -:1039D0009847230404D5054A936F0BB1D06F9847DD -:1039E000BDE81040FFF778BE000401400C23002022 -:1039F000062108B50846FFF787F806210720FFF7DC -:103A000083F806210820FFF77FF806210920FFF739 -:103A10007BF806210A20FFF777F806211720FFF729 -:103A200073F8BDE8084006212820FFF76DB80000B4 -:103A300008B5FFF7A3FE0648FEF754FFFFF782F82C -:103A4000FFF784FAFFF798FEBDE8084000F002B8DF -:103A50003C41000800F00EB808B5202383F311881C -:103A6000FFF7A6FB002383F31188BDE80840FFF7AA -:103A700033BE0000054B064A08215A6000229A60B6 -:103A800007220B201A60FFF755B800BF10E000E0D6 -:103A90003F1901001FB51C46094B05461B68D86835 -:103AA00052B1084B8DE80A0002922B462246064985 -:103AB000FDF7AAFC00F042F8044B1A46F2E700BFFB -:103AC0001011002078410008854100086C3C000876 -:103AD00010B501390244904201D1002010BD10F808 -:103AE000013B11F8014FA342F5D0181B10BD000097 -:103AF0002DE9F8430746884691461E468BB10D4690 -:103B0000A8EB0500B54207EB000402D20020BDE897 -:103B1000F883324649462046FFF7DAFF18B1013DE7 -:103B2000EEE7BDE8F8832046BDE8F883034611F8C8 -:103B3000012B03F8012B002AF9D1704708B50620A4 -:103B400000F02CF80120FFF721FC00001F2938B5F8 -:103B500004460D4604D9162303604FF0FF3038BDEC -:103B6000426C12B152F821304BB9204600F030F8C7 -:103B70002A4601462046BDE8384000F017B8012B20 -:103B80000AD0591C03D116230360012038BD00243C -:103B9000284642F825409847002038BD024B014690 -:103BA0001868FFF7D3BF00BF1011002038B50023FD -:103BB000064C0546084611462360FFF7EBFB431C05 -:103BC00002D1236803B12B6038BD00BFFC25002063 -:103BD000FFF7DABB40A2E4F1646891064E6F206102 -:103BE0007070207369670A00426164206677206CF8 -:103BF000656E6774682025750A0042616420626FF3 -:103C00006172645F69642025752073686F756C64E8 -:103C10002062652025750A00426164206677206471 -:103C2000657363726970746F72206C656E67746817 -:103C30002025750A00426164206170702043524360 -:103C4000203078253038783A307825303878203070 -:103C500078253038783A3078253038780A00476F40 -:103C60006F64206669726D776172650A00000000FA -:103C700072656365697665645F756E697175655FA8 -:103C800069645F6C656E203C2055415643414E5F30 -:103C900050524F544F434F4C5F44594E414D49434E -:103CA0005F4E4F44455F49445F414C4C4F43415444 -:103CB000494F4E5F554E495155455F49445F4D410F -:103CC000585F4C454E475448002E2E2F2E2E2F5411 -:103CD0006F6F6C732F41505F426F6F746C6F6164D4 -:103CE00065722F63616E2E63707000616C6C6F6320 -:103CF000617465645F6E6F64655F6964203C3D203C -:103D0000313237006F72672E6172647570696C6F43 -:103D1000742E61705F7065726970685F6164736250 -:103D200000000000766F69642068616E646C655FF6 -:103D3000616C6C6F636174696F6E5F726573706FD5 -:103D40006E73652843616E617264496E7374616E4F -:103D500063652A2C2043616E6172645278547261EB -:103D60006E736665722A290063616E617264496EC2 -:103D70006974000063616E6172645365744C6F63B3 -:103D8000616C4E6F646549440000000063616E61C0 -:103D9000726448616E646C6552784672616D65004C -:103DA00063616E6172644465636F64655363616CE3 -:103DB0006172000063616E617264456E636F646579 -:103DC0005363616C61720000696E6372656D656E4C -:103DD000745472616E73666572494400656E7175E4 -:103DE00065756554784672616D65730070757368AA -:103DF00054785175657565007072657061726546BD -:103E00006F724E6578745472616E736665720000ED -:103E1000636F7079426974417272617900000000C9 -:103E20006465736361747465725472616E73666500 -:103E3000725061796C6F61640000000066726565A4 -:103E4000426C6F636B0000006269745F6C656E6743 -:103E50007468203E20300072656D61696E696E671E -:103E60005F62697473203E203000696E7075745F04 -:103E70006269745F6F6666736574203E3D20626C94 -:103E80006F636B5F6269745F6F666673657400620F -:103E90006C6F636B5F656E645F6269745F6F6666AB -:103EA000736574203E20626C6F636B5F6269745F40 -:103EB0006F66667365740072656D61696E696E67C1 -:103EC0005F6269745F6C656E677468203C3D207248 -:103ED000656D61696E696E675F6269747300696EB2 -:103EE0007075745F6269745F6F6666736574203C99 -:103EF0003D207472616E736665722D3E7061796CDF -:103F00006F61645F6C656E202A2038006F75747075 -:103F100075745F6269745F6F6666736574203C3D9B -:103F20002036340072656D61696E696E675F626923 -:103F3000745F6C656E677468203D3D2030002872A8 -:103F40006573756C74203E20302920262620287247 -:103F50006573756C74203C3D20363429202626205C -:103F600028726573756C74203C3D206269745F6CC7 -:103F7000656E67746829000064657374696E6174A6 -:103F8000696F6E20213D202828766F6964202A29D8 -:103F900030290076616C756520213D202828766FD8 -:103FA0006964202A293029006F66667365745F771B -:103FB000697468696E5F626C6F636B203C202833A4 -:103FC0003255202D205F5F6275696C74696E5F6F7A -:103FD00066667365746F66202843616E6172644221 -:103FE0007566666572426C6F636B2C2064617461E8 -:103FF000292900006F75745F696E7320213D2028A8 -:1040000028766F6964202A29302900007372635F63 -:104010006C656E203E203055000000002863616E04 -:104020005F6964202620307831464646464646463B -:104030005529203D3D2063616E5F696400000000EA -:10404000616C6C6F6361746F722D3E73746174691F -:1040500073746963732E63757272656E745F7573C2 -:104060006167655F626C6F636B73203E2030000098 -:104070007472616E736665725F696420213D2028E9 -:1040800028766F6964202A293029000073746174CE -:10409000652D3E6275666665725F626C6F636B73F9 -:1040A000203D3D202828766F6964202A2930290088 -:1040B0002E2E2F2E2E2F6D6F64756C65732F6C69ED -:1040C0006263616E6172642F63616E6172642E63FC -:1040D000006974656D2D3E6672616D652E64617454 -:1040E000615F6C656E203E20300000000000000023 -:1040F000152F0008012F00083D2F0008292F000868 -:10410000352F0008212F00080D2F0008F92E000878 -:10411000492F00086D61696E0000000034410008FD -:1041200020250020D02500200100000031310008AA -:104130000000000069646C65000000000C1E0000B7 -:10414000447B4144B4574944010000004244444484 -:10415000444444440000000044444444444444442F -:10416000000000004444444444444444000000002F -:1041700044444444444444442C2066756E6374694A -:104180006F6E3A2000617373657274696F6E2022DE -:10419000257322206661696C65643A2066696C65E6 -:1041A00020222573222C206C696E652025642573DE -:1041B00025730A000CC0FF7F010000000000000012 -:1041C0006400000000000000FE2A0100D20400008C -:1041D000141100200000000000000000000000009A -:1041E00000000000000000000000000000000000CF -:1041F00000000000000000000000000000000000BF -:1042000000000000000000000000000000000000AE -:10421000000000000000000000000000000000009E -:10422000000000000000000000000000000000008E -:04423000000000008A +:100000000009002069040008C114000865140008F4 +:10001000A514000865140008851400086B04000886 +:100020006B0400086B0400086B0400087D350008B1 +:100030006B0400086B0400086B040008113A000808 +:100040006B0400086B0400086B0400086B040008D4 +:100050006B0400086B0400083D370008693700088E +:1000600095370008C1370008ED3700086B04000819 +:100070006B0400086B0400086B0400086B040008A4 +:100080006B0400086B0400086B040008712400086E +:10009000DD240008312500088525000819380008EE +:1000A0006B0400086B0400086B0400086B04000874 +:1000B0006B0400086B0400086B0400086B04000864 +:1000C0006B0400086B0400086B0400086B04000854 +:1000D0006B04000825290008392900086B04000872 +:1000E000813800086B0400086B0400086B040008EA +:1000F0006B0400086B0400086B0400086B04000824 +:100100006B0400086B0400086B0400086B04000813 +:100110006B0400086B0400086B0400086B04000803 +:100120006B0400086B0400086B0400086B040008F3 +:100130006B0400086B0400086B0400086B040008E3 +:100140006B0400086B0400086B0400086B040008D3 +:100150006B0400086B0400086B0400086B040008C3 +:1001600053B94AB9002908BF00281CBF4FF0FF311E +:100170004FF0FF3000F076B9ADF1080C6DE904CE18 +:1001800000F006F8DDF804E0DDE9022304B0704772 +:100190002DE9F047089E0D4604468846002B4DD1B8 +:1001A0008A42944668D9B2FA82F252B101FA02F355 +:1001B000C2F1200120FA01F10CFA02FC41EA030825 +:1001C00094404FEA1C41B8FBF1F71FFA8CFE01FB8B +:1001D000178807FB0EF0230C43EA084398420AD91C +:1001E0001CEB030307F1FF3580F01E81984240F2BB +:1001F0001B81023F63441B1AB3FBF1F001FB103378 +:1002000000FB0EFEA4B244EA0344A6450AD91CEB47 +:10021000040400F1FF3380F00981A64540F2068115 +:10022000644402380021A4EB0E0440EA07401EB1EA +:100230000023D440C6E90043BDE8F0878B4208D9CB +:10024000002E00F0EE800021C6E900050846BDE85A +:10025000F087B3FA83F100294AD1AB4202D382423C +:1002600000F2FC80841A65EB030301209846002EFF +:10027000E2D0C6E90048DFE702B9FFDEB2FA82F257 +:10028000002A40F09180A1EB0C0001214FEA1C47AD +:100290001FFA8CFEB0FBF7F307FB1300250C45EAB1 +:1002A00000450EFB03F0A84208D91CEB050503F13D +:1002B000FF3802D2A84200F2CE8043462D1AB5FB89 +:1002C000F7F007FB10550EFB00FEA4B244EA05440C +:1002D000A64508D91CEB040400F1FF3502D2A6455F +:1002E00000F2B6802846A4EB0E0440EA03409EE7E5 +:1002F000C1F120078B4022FA07FC4CEA030C25FAD7 +:1003000007FA4FEA1C49BAFBF9F820FA07F309FB90 +:1003100018AA8D401FFA8CFE1D4300FA01F308FB5A +:100320000EF02C0C44EA0A44A04202FA01F20BD966 +:100330001CEB040408F1FF3A80F08880A04240F2F0 +:100340008580A8F102086444241AB4FBF9F009FB83 +:10035000104400FB0EFEADB245EA0444A64508D9A0 +:100360001CEB040400F1FF356CD2A6456AD90238B3 +:10037000644440EA0840A0FB0295A4EB0E04AC42A2 +:10038000C846AE4656D353D0002E69D0B3EB080210 +:1003900064EB0E0422FA01F304FA07F71F43CC4082 +:1003A000C6E90074002147E70CFA02FCC2F1200103 +:1003B00025FA01F34FEA1C4720FA01F195400D435D +:1003C000B3FBF7F107FB11331FFA8CFE280C40EA50 +:1003D000034001FB0EF3834204FA02F408D91CEB3C +:1003E000000001F1FF382FD283422DD90239604439 +:1003F000C01AB0FBF7F307FB1300ADB245EA0045A6 +:1004000003FB0EF0A84208D91CEB050503F1FF38E9 +:1004100016D2A84214D9023B6544281A43EA014186 +:1004200038E73146304607E72F46E4E61846F9E656 +:100430004B45A9D2B9EB020865EB0C0E0138A3E7D6 +:100440004346EAE7284694E74146D1E7D0467BE7B2 +:100450006444023847E7023B65442FE7084606E755 +:100460003146E9E6704700BF02E000F000F8FEE721 +:1004700072B6284880F30888274880F309882748FF +:100480004EF60851CEF200010860022080F3148875 +:10049000BFF36F8F03F0E4F803F0C0F803F0E2F865 +:1004A0004FF055301E491B4A91423CBF41F8040BA6 +:1004B000FAE71C49184A91423CBF41F8040BFAE79D +:1004C00019491A4A1A4B9A423EBF51F8040B42F896 +:1004D000040BF8E700201749174A91423CBF41F846 +:1004E000040BFAE703F09EF803F0BEF8134C144D2A +:1004F000AC4203DA54F8041B8847F9E700F03CF8F3 +:10050000104C114DAC4203DA54F8041B8847F9E74C +:1005100003F086B800090020001100200000000848 +:100520000001002000090020E03B0008001100202D +:100530002411002028110020A025002060010008BF +:100540006001000860010008600100082DE9F04F1B +:10055000C1F80CD0C3689D46BDE8F08F002383F33B +:1005600011882846A047002002F09CFDFEE702F01B +:1005700021FD00DFFEE700002DE9F04102F09CFFC5 +:10058000074602F0E7FF054600283ED12B4B9F426D +:100590003BD001339F423BD0294B27F0FF029A42C8 +:1005A0003AD1F8B200F052FAA84642F2107400F0C4 +:1005B00057FC08B10024A04600F04EFA064678B376 +:1005C00084BB464635B11F4B9F4203D0002402F046 +:1005D000B9FF2646002002F079FF1B4B9B6813F001 +:1005E000400322D00EB100F031F800F097FC00F08B +:1005F00077FE00F067FF0546CCB100F063FF401BBB +:10060000A04214D900F022F8F3E7A8460024CEE770 +:1006100004464FF00108CAE780464FF47A74C6E7F3 +:100620000446CFE74FF47A74CCE71C46DDE700F0D0 +:1006300025FD012002F03CFDDEE700BF010007B010 +:10064000000008B0263A09B0000C014038B51D4A38 +:100650001D4B1968013134D004339342F9D11B4C3E +:10066000194DD4F80424AA422BD3194B9B6803F1EB +:10067000006303F5C8439A4223D202F037FF02F029 +:1006800049FF002000F046FE0220124B187000F0D7 +:100690007DFE114BDA690022DA61D96999699A61A4 +:1006A0009B6972B64FF0E023C3F8085DD4F80034BC +:1006B000D4F80424202181F311889D4683F308880F +:1006C000104738BD2064000800640008006000087E +:1006D00000110020281100200010024049F269009A +:1006E000084A136899B21B0C00FB013344F25061B5 +:1006F0001360054B186882B2000C01FB0200186001 +:1007000080B27047201100201C11002010B5044653 +:100710000021102200F056FE034B03CB20606160E5 +:100720001868A06010BD00BFE8F7FF1F2DE9F04377 +:10073000BBB000F0C7FE40F2ED22204DAB68C31AFB +:10074000934232D906AF2B4628220021A8603846B2 +:1007500001F0C2FB05F10E0000F02CFE002604465D +:100760005FFA80F905F10E08F3B2F100994501F145 +:10077000280107D908EB06030822384601F0ACFB34 +:100780000136F1E708230122CDE902320C4B053492 +:1007900001933023A4B20093CDE9047405A3D3E9F7 +:1007A0000023297B074801F0ADF93BB0BDE8F08399 +:1007B000AFF3008078F6339F93CACD8D702100206F +:1007C0007D2100204421002070B50D4614461E46B0 +:1007D00001F02EF950B9022E10D1012C0ED112A326 +:1007E000D3E900230120C5E9002307E0282C10D01D +:1007F00005D8012C09D0052C0FD0002070BD302C5D +:10080000FBD10BA3D3E90023ECE70BA3D3E900232F +:10081000E8E70BA3D3E90023E4E70BA3D3E9002324 +:10082000E0E700BFAFF30080401DA12026812A0B26 +:1008300078F6339F93CACD8D9E6AC421818A46EE95 +:1008400026417272DF25D7B7F017304A39059E5618 +:1008500038B50D460446034620222846002101F003 +:100860003BFB22792346032A28BF0322284603F8AC +:10087000042F2021022201F02FFB62792346072A50 +:1008800028BF0722284603F8052F2221032201F062 +:1008900023FBA2792346072A28BF0722284603F80C +:1008A000062F2521032201F017FB284610222821BC +:1008B00004F1080301F010FB382038BD2DE9F04F9A +:1008C0000024ADF5017D0EAE40F2751280460F4654 +:1008D00022A82146219400F075FD21464822304689 +:1008E00000F070FD00F0EEFD4FF47A72B0FBF2F014 +:1008F000544B21AD186093E80700012386E80700F8 +:100900000DF15A003382FFF701FF4EF603033384E3 +:1009100006AB18464C4903F0B3F81C222946306454 +:10092000304686F83C20FFF793FF08220446014634 +:1009300012AB284601F0D0FA08222846A1180DF182 +:10094000490301F0C9FA082228460DF14A0304F1CF +:10095000100101F0C1FA2022284613AB04F118015E +:1009600001F0BAFA4022284614AB04F1380101F034 +:10097000B3FA0822284616AB04F1780101F0ACFA6C +:10098000082228460DF1590304F1800101F0A4FA70 +:1009900004F1880A0DF15A0904F5847B4B4651464F +:1009A000082228460AF1080A01F096FAD34509F10F +:1009B0000109F3D10822594628461BAB01F08CFAF5 +:1009C0004FF0000904F5887496F834304B450AD985 +:1009D000B36B21464B440822284601F07DFA0834C7 +:1009E00009F10109F0E74FF0000996F83C3004EBFB +:1009F000C9014B4508D9336C08224B44284601F005 +:100A00006BFA09F10109F0E700230393BB7E07317C +:100A1000029307F1190301930123C1F3CF01CDE93B +:100A200004510093404605A3D3E90023F97E01F069 +:100A300069F80DF5017DBDE8F08F00BF9E6AC42105 +:100A4000818A46EE2C110020903A0008014B187064 +:100A5000704700BF38110020F0B5334B85B01C7BC8 +:100A600034B10E22314B1A810024204605B0F0BD6E +:100A70002F4A02AB1068516803C308232D492E4842 +:100A80000DEB030202F0DCFF054630B90A22274BCA +:100A90002A481A8100F0E2FCE6E70169B1F5CE3F91 +:100AA00006D90B22214B26481A8100F0D7FCDCE73F +:100AB000438BB3F57A7F09D00C211C4A2148118160 +:100AC0004FF47A72194600F0C9FCCEE71E4A024480 +:100AD00002F11003994204D21022144B1B481A81D0 +:100AE000E3E710398E1A2046134900F0EFFC074661 +:100AF0003246204605F1180100F0E8FCAB689F4241 +:100B000002D1EB6898420AD00D22084B1A8100905E +:100B10003B46D5E902120E4800F0A0FCA4E70D48C0 +:100B200000F09CFC0124A0E7702100202C11002083 +:100B3000413B0008DC9B010000640008B03A00085B +:100B4000BC3A0008CE3A0008089CFFF7EC3A0008CF +:100B5000093B0008323B00082DE9F04FADB006AF6D +:100B600080460C4600F064FF0546002859D1237EDC +:100B7000022B1AD1E38A012B17D100F0A3FC064601 +:100B8000FFF7ACFD4FF4C873B0FBF3F202FB1300A8 +:100B9000DFF8B49206F5167680B2E37E0644C9F813 +:100BA000006033B90022A94B1A709C37BD46BDE8DE +:100BB000F08FA38AEEB2013BB34205F101050BD9D8 +:100BC0003B1D1E44E900002308222046009601F048 +:100BD000F80101F043F8ECE707F11400FFF796FD88 +:100BE000324607F11401381D02F01AFF03460028AF +:100BF000D8D10F2E08D8954B1E70D9F80030A3F528 +:100C00001673C9F80030D0E7FA1CF870014600925C +:100C10002046072201F022F84046F97800F000FF54 +:100C2000C3E7E38A282B26D010D8012B1ED0052B32 +:100C3000BBD1BFF34F8F8649864BCA6802F4E0628E +:100C40001343CB60BFF34F8F00BFFDE7302BACD118 +:100C5000637E814D01336A7BDBB29342E94603D167 +:100C6000E27E2B7B9A4265D0CD469EE721464046E8 +:100C7000FFF724FE99E7A38A013B9BB2C92B94D8C6 +:100C8000754D2E7B26BB05F10C03009308223346DD +:100C90003146204600F0E2FF731CF2B2D9001E4636 +:100CA000A38A013B9A4205DA0E322A4400920023BD +:100CB0000822EEE700230022C5E900230023AB60F1 +:100CC00085F8D730C5F8D8302B7B0BB9E37E2B7372 +:100CD000002507F114060822294630463B1DC7E9C6 +:100CE0000155FD6001F0F8F83B7A05F10109AB42CE +:100CF0004FEAC90107D9FB6808222B44304601F0AE +:100D0000EBF84D46F0E70023C1F3CF01E07ECDE9DB +:100D100004610393A37E19340293282301460093B0 +:100D2000404647A3D3E90023019400F0EBFEFFF710 +:100D3000FDFC3AE74FF0000807F11403A7F8148010 +:100D40001022009341460123204600F087FFA68A27 +:100D5000023EB6B2F31C9B109B000733DB08A9EBE5 +:100D6000C3039D460DF1180A1FFA88F34FEAC80124 +:100D7000B34201F110010AD20AEB080300930822E2 +:100D80000023204600F06AFF08F10108ECE795F81F +:100D9000D70000F0C9FAD5F8D83004461BB995F849 +:100DA000D70000F0D1FAD5F8D83033449C4204D2B1 +:100DB00095F8D700013000F0C7FA4FF000084FEA6D +:100DC000960B1FFA88F18B45D5E9003209D90AEB59 +:100DD000880103EB8800012200F0FCFA08F1010809 +:100DE000EFE7F31842F10002C5E90032D5F8D83038 +:100DF00095F8D70006EB0308C5F8D88000F094FA00 +:100E0000804509D395F8D730D5F8D8000133001BB9 +:100E100085F8D730C5F8D800FF2E08D800232B73EB +:100E200000F0A4FAFFF718FE08B1FFF70FFC2B68DB +:100E30000A4A9B0A013313810023AB6014E700BF09 +:100E400026417272DF25D7B7402100203D210020C6 +:100E500000ED00E00400FA05702100202C110020B4 +:100E600030B54FF00054244B226885B09A4207D029 +:100E700002F07AFB0446A8B90024204605B030BD34 +:100E8000627D1E4B1E481A70237DC92203731D49C3 +:100E90000E3000F085FA2046E022002100F092FAA0 +:100EA0000124EAE7184A194DD36943F00073D3616E +:100EB000AA6D174B9A42DFD12B6E013B7E2BDBD8FC +:100EC000144A01AB07CA83E807001846032100F063 +:100ED00013FB6B6D83424FF00003CDD12A6D8A4224 +:100EE00003BFAB652A6E054B1C4601BF1A70EA6D45 +:100EF000094B1A60C1E700BF9AAD44C53811002004 +:100F00007021002016000020001002400066004002 +:100F10005041A0B0586600401811002002232DE96E +:100F2000F0434A4C85B0637100230293484BD3F8D9 +:100F300000C0BCF57A7F12D3464F474BB7FBFCF598 +:100F40009C458CBF0A231123B5FBF3F603FB165215 +:100F5000591EC8B2002A3ED002290B46F4D89DF88B +:100F60000B303E495A1E9DF80A303D48013B1B0498 +:100F700043EA0253BDF80820013A13434B6001F0E5 +:100F800037FD00230193374B374900934FF48052CC +:100F9000364B374800F01CFD364B197811B13448F8 +:100FA00000F03EFD00F08EFA0546FFF797FB4FF488 +:100FB000C873B0FBF3F202FB130305F516709BB286 +:100FC00018442D4B186002F0C5FA08B10F23238195 +:100FD00005B0BDE8F083731EB3F5806FBFD24FF448 +:100FE0007A75C0EBC00E0EF103034FEAE30909FB6B +:100FF0000555C3F3C703C11AC9B209F101088844F2 +:10100000B5FBF8F5B5F5617F08D90EF1FF33C3F3F1 +:10101000C703C11A581E0F28C9B214D84A1E072A7E +:101020008CBF00220122581800FB0660B7FBF0F7C6 +:10103000BC4594D1002A92D0ADF808608DF80A30F2 +:101040008DF80B108BE71346EDE700BF2C11002045 +:1010500018110020005125023F420F0010110020FE +:1010600088220020C90700083C110020590B000805 +:101070004421002038110020402100202DE9F04FAC +:1010800093A7D7E900670FF25029D9E90089854D68 +:1010900093B0DFF814B2854C284600F097FD0DF1AF +:1010A000300A079070B310220021504600F08AF9F0 +:1010B0004FF00002079B197B61F303028DF830208B +:1010C000586899680EAA03C21B680D9A584663F3C4 +:1010D0001C029DF830300D9243F020038DF8303023 +:1010E00000235246194601F093FC079028B9284680 +:1010F00000F070FD079B2370CEE72378072B3CD8C8 +:101100000133237018220021504600F05BF9DFF80C +:1011100098B1674C002352461946584601F0A0FC8E +:10112000014670BB102208A800F04CF9E36883F078 +:101130001003E36000F0C8F90DF1240C0B4612A96E +:10114000024611E903008CE803009DF83410C1F356 +:101150000300890649BF0E99BDF83810C1F31C0180 +:1011600041F0004158BFC1F30A018DF82C000891ED +:10117000284608A900F0F8FECCE7284600F02AFD32 +:10118000C0E7284600F054FC8346002844D100F014 +:1011900099F9484B1A6890423ED300F093F90446FF +:1011A000FFF79CFA4FF4C872B0FBF2F101FB12009A +:1011B0008DF820B0DFF800B13E4B04F5167480B214 +:1011C0009BF8001004441C6011B901238DF82030F5 +:1011D00050460791FFF79AFA07990DF12100C1F1E6 +:1011E0001004E4B2062C28BF06245144224600F025 +:1011F000D7F808AB039318230293304B01340193C3 +:101200000123E4B2009332463B462846049400F0A2 +:1012100011FC00238BF8003000F054F9284A294CC7 +:101220001368C31AB3F57A7F31D3106000F04CF91C +:1012300002460B46284600F0D7FC284600F0F8FB93 +:1012400028B3237BDFF880B0002B14BF03230223D5 +:101250008BF8053000F036F94FF47A73B0FBF3F0F9 +:101260005146CBF800005846FFF7F2FA18230293D4 +:10127000164B0730019340F25513C0F3CF00CDE970 +:1012800003A0009342464B46284600F0D3FB237B45 +:101290002BB1FFF74BFA237B002B7FF4FAAE13B090 +:1012A000BDE8F08F44210020882200205522002034 +:1012B00000080140402100203D2100203C21002069 +:1012C00050220020702100202C11002054220020E8 +:1012D000401DA12026812A0BF1C6A7C1D068080FA6 +:1012E00070B501F0BFFF0024084E094D308028681A +:1012F0003388834208D901F0B1FF2B6804440133DD +:10130000B4F5C84F2B60F2D370BD00BF842200201B +:101310005822002002F044B800F10060920000F56D +:10132000C84001F0DFBF0000054B1A68054B1B8861 +:101330009B1A834202D9104401F090BF00207047ED +:10134000582200208422002038B50446064D286823 +:10135000204401F089FF28B928682044BDE83840BE +:1013600001F094BF38BD00BF58220020064991F813 +:10137000243033B100230822086A81F82430FFF7B3 +:10138000CBBF0120704700BF5C220020022802BFB3 +:101390004FF48012014B1A61704700BF00080140F2 +:1013A000002310B5934203D0CC5CC4540133F9E759 +:1013B00010BD000003460246D01A12F9011B002995 +:1013C000FAD1704703460244934202D003F8011B4E +:1013D000FAE770472DE9F8431F4D144695F824208D +:1013E0000746884652BBDFF870909CB395F82430CE +:1013F0002BB92022FF2148462F62FFF7E3FF95F823 +:1014000024004146C0F10802A24228BF224605EB53 +:101410008000D6B29200FFF7C3FF95F82430A41BDA +:101420001E44F6B2082E17449044E4B285F82460B6 +:10143000DBD1FFF79BFF0028D7D108E02B6A03EB35 +:1014400082038342CFD0FFF791FF0028CBD1002049 +:10145000BDE8F8830120FBE75C2200200FB40020E8 +:1014600004B07047EFF30983EFF30583044B9A6BE5 +:10147000DA6A9A6A9A6A9A6A9A6A9A6A9B6AFEE72A +:1014800000ED00E0EFF30983EFF30583044B9A6B63 +:101490009A6A9A6A9A6A9A6A9A6A9B6AFEE700BF8F +:1014A00000ED00E0EFF30983EFF30583034B5A6B84 +:1014B0009A6A9A6A9A6A9A6A9B6AFEE700ED00E065 +:1014C000FEE7000001F0A6BF01F07EBF30B5094D78 +:1014D0000A4491420DD011F8013B5840082340F3D3 +:1014E0000004013B2C4013F0FF0384EA5000F6D1C6 +:1014F000EFE730BD2083B8ED4FF0FF33F7B500EBD9 +:1015000081061946DFF848C0DFF848E0B0421BD03A +:1015100050F8042B01AF0192042217F8014B81EA25 +:10152000046108240D46DB184941013C002DBCBF75 +:1015300083EA0C0381EA0E0114F0FF04F2D1013AB0 +:1015400012F0FF02E9D1E1E7D843C94303B0F0BD8F +:101550009336EAA9EBE1F0422DE9F041C56915B9EE +:10156000C161BDE8F0814B68AC4623F06047C3F32E +:101570008A4616EA230638BF3E464FEAD37EC3F3B7 +:1015800080782B465A68BEEBD27F22F060440AD0A6 +:10159000002A18DAA40CB44217D19D420FD10D6075 +:1015A000DEE71346EEE7A74207D102F08044C2F31C +:1015B000807242450BD054B1EFE708D2EDE7CCF88A +:1015C00000100B60CDE7B44201D0B442E5D81A68F0 +:1015D0009C46002AE5D11960C3E700002DE9F047D9 +:1015E0004FF47F49089D01F007044FEAD5082244D3 +:1015F00005F0070500EBD100944201D1BDE8F0876A +:1016000004F0070705F0070A57453E4638BF56461F +:10161000111BC6F108068E4228BF0E46E108415C48 +:1016200008EBD50E13F80EC0B94029FA06F721FAD7 +:101630000AF1FFB28CEA010147FA0AF739408CEA55 +:10164000010C03F80EC034443544D5E7082341F2B9 +:10165000210280EA012001B24000002980B203F19A +:10166000FF33B8BF504013F0FF03F4D170470000C0 +:1016700038B50C468D18A54200D138BD14F8011BB1 +:10168000FFF7E4FFF7E700000346006848B102688F +:1016900019891A60DA88013292B29142DA8038BF31 +:1016A0001A81704770B504460D4688B0202200218B +:1016B0006846FFF787FE20460495FFF7E5FF0246E0 +:1016C00058B16B46054608AE1C4603CCB4422860B0 +:1016D0006960234605F10805F6D1104608B070BDD3 +:1016E000082817D909280CD00A280CD00B280CD0B0 +:1016F0000C280CD00D280CD00E2814BF4020302010 +:1017000070470C2070471020704714207047182035 +:101710007047202070470000082817D90C280CD9E2 +:1017200010280CD914280CD918280CD920280CD929 +:1017300030288CBF0F200E207047092070470A20E8 +:1017400070470B2070470C2070470D207047000039 +:1017500010B54B6823B9CA8A63F30902CA8210BD67 +:10176000C4681A681C60C360438A013B43824A60B4 +:10177000EFE700002DE9F84F1D46CB8A0F46C3F373 +:1017800009010629814692460B4630D00020AAB2B4 +:1017900007F119049EB2052E1FFA80F80FD8904564 +:1017A00003F1010306D3FB8A0A4462F30903012013 +:1017B000FB821AE01AF800600130E654EAE790452F +:1017C000F1D21C23A1F1060BBBFBF3F203FB12BB0E +:1017D0007C681FFA8BF6002C45D14846FFF754FF72 +:1017E000044638B978606FF00200BDE8F88F4FF01A +:1017F0000008E6E70026066078604FF0000BADB207 +:10180000454510D90AEB0803221D13F8011B08F106 +:1018100001089155B1B21B291FFA88F82BD0454514 +:1018200006F10106F1D8FB8AC3F30902154465F3FA +:101830000903BCE71C46013292B22368002BF9D1A0 +:10184000AB1F0B441C21B3FBF1F301339BB29A4253 +:10185000D3D2BBF1000FD0D14846FFF715FF20B916 +:10186000C4F800B0BFE70122E7E7C0F800B05E4669 +:1018700020600446C1E74545D5D94846FFF704FF37 +:1018800008B92060AFE7C0F800B000262060044629 +:10189000B6E700002DE9F04F85B007469146CDE947 +:1018A0000113BDF83C50002A00F08F802DB10E9B33 +:1018B000002B00F08A80072D30D807F10C00FFF7CD +:1018C000E3FE044628B96FF00204204605B0BDE8E7 +:1018D000F08F14220021FFF775FD2A460E9904F1BE +:1018E0000800FFF75DFD681CC0B2FFF715FFFFF7AA +:1018F000F7FE207499F80020431E9BB202F01F02ED +:10190000234462F03F021A72019B384643F00041C3 +:1019100061602146FFF720FE0124D6E74FF0000862 +:101920004FF0800A4646444600F10C0303930398A7 +:10193000FFF7AAFE83460028C5D014220021FFF736 +:1019400041FD002E38D10220029BABF808300E9BDF +:1019500000F10802D2B299195A440130C0B20828E5 +:1019600001D0AE422AD3FFF7D7FEFFF7B9FEAE4251 +:1019700008BF4FF0400A99F80020019B411E02F079 +:101980001F0242EA4812C9B24AEA020A594443F025 +:10199000004281F808A08BF8100059463846CBF871 +:1019A0000420FFF7D9FD0134AE424FF0000A24B203 +:1019B00088F00108BBD188E70020C8E711F801CB07 +:1019C000013602F801CBB6B2C7E76FF001047CE73D +:1019D000F8B5044615460E46282200211F46FFF79B +:1019E000F1FC069BB5F5001F6360079B28BF4FF60F +:1019F000FF7223624FF0000338BF6A09A76004F149 +:101A00000C0097B29A4205D80023036027826382B4 +:101A1000A382F8BD0660013330462036F2E70000AD +:101A200003781BB94BB2002BC8BF01707047000090 +:101A3000007870472DE9F74FDDF83C9080469246DC +:101A40009B46BDF830500D9E9DF83840BDF8407063 +:101A5000B9F1000F01D1002F51D11F2C4FD898F8A8 +:101A60000000B0B9072F47D835F0030347D13A46F5 +:101A700049464FF6FF70FFF7FBFD20F001002D02F5 +:101A8000400445EA0464400C44EA40244FF6FF73E6 +:101A900021E040EA0520072F40EA0464F6D900253A +:101AA0004FF6FF73C5F12000A5F120022AFA05F1D7 +:101AB0000BFA00F001432BFA02F211431846C9B2A7 +:101AC000FFF7C4FD0835402D0346EBD13A464946A1 +:101AD000FFF7CEFD0346324621464046CDE900974A +:101AE000FFF7D8FE33780133DBB21F2B88BF00230A +:101AF000337003B0BDE8F08F6FF00300F9E76FF0CB +:101B00000100F6E72DE9F04F85B0DDF848809246F8 +:101B100006469B460F9D9DF840209DF84490BDF8D9 +:101B20004C70B8F1000F01D1002F48D11F2A46D8C0 +:101B30003378002B46D00C0244EA02649DF838103A +:101B400044EAC93444EA01441C43072F44F08004AA +:101B500032D900234FF6FF72C3F1200CA3F120000D +:101B60002AFA03F10BFA0CFC41EA0C012BFA00F003 +:101B70000143C9B210460393FFF768FD039B024679 +:101B80000833402BE8D13A464146FFF771FD034642 +:101B90002A4621463046CDE90087FFF77BFEB9F1A2 +:101BA000010F06D12B780133DBB21F2B88BF002336 +:101BB0002B7005B0BDE8F08F4FF6FF73E8E76FF0CC +:101BC0000100F6E76FF00300F3E70000C06900B121 +:101BD00004307047C3691A68C261C2681A60C36082 +:101BE000438A013B438270472DE9F041D0F81880C9 +:101BF00014461D4641460027174E09B9BDE8F0813D +:101C0000D1E90223A21A65EB0303964277EB0303A3 +:101C10001ED283698B420DD1FFF79AFD83691B6841 +:101C20008361C3680B60438AC1608169013B884658 +:101C30004382E2E7FFF78CFD0B68C8F80030C36809 +:101C40000B60438AC160013B4382D8F80010D4E79F +:101C500088460968D1E700BF80841E002DE9F04F57 +:101C60008BB00D4614469B468046DDF85090002808 +:101C700000F01A81B9F1000F00F01681531E3F2BBE +:101C800000F21281012A03D1BBF1000F40F00C8158 +:101C90000023CDE90833B8F81430B5EBC30F4FEA91 +:101CA000C30703D300200BB0BDE8F08F2B199F4270 +:101CB000D8F80C3036BF7F1B2746FFB21BB9D8F8C7 +:101CC0001030002B7BD02F2D4ED8C5F13006B742F7 +:101CD0004FF0000334BF3E46F6B200932946324629 +:101CE000D8F8080008ABFFF779FCA7EB060A3544E3 +:101CF0005FFA8AFA3021B8F8143003F10053063B3A +:101D0000DB000493D8F80C300393039B13B1BAF1B2 +:101D1000000F2CD1D8F8100040B1BAF1000F05D057 +:101D20005246009608AB691AFFF758FC38B2002FEC +:101D3000B8D066070AD00AAB03EBD40111F8083C0F +:101D4000624202F00702134101F8083C082C3DD919 +:101D5000102C40F2B680202C40F2B880BBF1000F6E +:101D600000F09D80082335E0BA460026C2E7049BB8 +:101D7000E02B28BFE02306930B44AB42059315D913 +:101D80005A1B924538BF5246039828BFD2B20096DC +:101D9000691A08AB04300792FFF720FC079A164433 +:101DA000AAEB020A1544F6B25FFA8AFA049B069A75 +:101DB00005999B1A0493039B1B680393A5E7009363 +:101DC0003A462946D8F8080008ABADE7BBF1000F4A +:101DD00013D00123B4EBC30F6CD0082C12D89DF89C +:101DE0002030621E23FA02F2D50706D54FF0FF32EB +:101DF00002FA04F423438DF820309DF8203089F84E +:101E0000003050E7102C12D8BDF82030621E23FAA3 +:101E100002F2D10706D54FF0FF3202FA04F4234351 +:101E2000ADF82030BDF82030A9F800303BE7202C79 +:101E30000FD80899631E21FA03F3DA0705D54FF08E +:101E4000FF3202FA04F40C430894089BC9F80030EE +:101E500029E7402C2BD0DDE90865611EC4F1210281 +:101E6000A4F1210326FA01F105FA02F225FA03F39F +:101E700011431943CB0712D50122A4F12003C4F169 +:101E8000200102FA03F322FA01F1A240524243EA8E +:101E9000010363EB430332432B43CDE90823DDE920 +:101EA0000823C9E90023FEE66FF00100FBE66FF0AE +:101EB0000800F8E6082CA0D9102CB3D9202CEED8B5 +:101EC000C3E7BBF1000FADD0022383E7BBF1000FE6 +:101ED000BBD004237EE70000012A30B5144638BF8A +:101EE00001220025402A28BF402285B0012CCDE9DF +:101EF000025517D81B788DF8083053070AD004AB69 +:101F000003EBD20515F8083C544204F00704A34043 +:101F100005F8083C0346009102A80021FFF75EFB8C +:101F200005B030BD082CE5D9102C03D81B88ADF8BE +:101F30000830E2E7202C02D81B680293DDE7D3E9E2 +:101F40000045CDE90245D8E710B5CB681BB98B60D9 +:101F50000B618B8210BDC4681A681C60C360438A21 +:101F6000013B4382CA60F0E72DE9F04FD1F80080D1 +:101F700093B018F0800FCDE90323C8F3C01207BF58 +:101F80004FF0020B1646C8F3C03BC8F30626B8F163 +:101F9000000F04460D4680F2D48118F0C04305932B +:101FA00040F0CF810B7B002B00F0CB81BBF1020F07 +:101FB00003D00178B14240F0C78108F07F0107915A +:101FC0007AB3C8F3074A2B4493F80390760646EA9F +:101FD0000B4608F07F0246EA82465FEAD91346EADA +:101FE0000A06069300F0918000220023CDE90A231F +:101FF00008F07F03009352465B46204667680AA9B3 +:10200000B84700287ED0A7699FB9314604F10C007B +:10201000FFF748FB0746E0B96FF0020013B0BDE8D8 +:10202000F08FC8F30F2A18F07F0F08BF0AF0030AD9 +:10203000C9E73B699E420DD03F68002FF9D1314678 +:1020400004F10C00FFF72EFB07460028E4D0A3693B +:102050003B60A7610026DDE90A234FF6FF70C6F159 +:10206000200E22FA06F103FA0EFEA6F1200C23FA46 +:102070000CFC41EA0E0141EA0C01C9B20836099292 +:102080000893FFF7E3FADDE90832402EE7D1B88282 +:10209000FB7D09F01F06C3F384039B1B98B2002B42 +:1020A000BCBF00F120031BB2D7E9022152EA0100B4 +:1020B000C8F304680FD00398821A049860EB0101FA +:1020C000A74890424FF000028A4104D3069A002AA2 +:1020D0005BD0012B23DDFA7D4FEA890302F0030276 +:1020E00003F07C031343FB7539462046FFF730FBB2 +:1020F000069BA3B9FB7DC3F38402013262F386031E +:10210000FB7504E06FF00B0088E7A76917B96FF063 +:102110000C0083E73B699E42BAD03F68F6E719F0AE +:10212000400F32D0039B1422BB60049B0021FB6054 +:102130000DA8FFF747F9039B20460A93049BADF8CF +:102140003EA00B932B1D0C932B7B8DF840B0013BD5 +:10215000DBB2ADF83C30079B8DF841608DF8433021 +:1021600094F824308DF8428083F001038DF84430D8 +:102170000AA9A3689847FB7DC3F38403013303F0E6 +:102180001F039B02FB82002048E7FB7DC9F340123E +:10219000B2EBD31F40F0DB80C3F38403B34240F0C3 +:1021A000D98006992B7B4FEA9912002934D0D207A7 +:1021B00041D4032B40F2D180039BAE1DBB60049B36 +:1021C0003246FB602B7B3946033BDBB204F10C004B +:1021D000FFF7D0FA00280DDA20463946FFF7B8FAA3 +:1021E000FB7D0320C3F38403013303F01F039B0231 +:1021F000FB8213E7AB883B832A7B033AB88AD2B2CF +:102200003146FFF735FAFB7DB882DA43C2F3C012DC +:1022100062F3C713FB75B6E76AB92E1D013B324660 +:102220003946DBB204F10C00FFF7A4FA0028D3DB37 +:102230002A7B013AE2E7F98A013BC1F3090105294A +:10224000DAB25BD80023281D07F11A0C9A4208D98C +:1022500010F801EB01330CF801E001310629DBB283 +:10226000F4D1934228BF0023039938BF04330A9165 +:10227000049938BFDBB20B9107F11A010C91796810 +:1022800038BF5B190D910E93FB8AADF83EA0C3F3E6 +:1022900009031A44079BADF83C208DF8433094F8AD +:1022A00024308DF840B083F001038DF844300023D2 +:1022B0008DF841608DF842807B602A7BB88A013AB4 +:1022C000291DFFF7D5F93B8BB882834203D1204605 +:1022D000A3680AA9984720460AA9FFF735FEFB7DA7 +:1022E000B88AC3F38403013303F01F039B02FB820C +:1022F0003B8B984214BF112000208FE67B68002B97 +:10230000AFD0062001E063461C30D3F800C0BCF11A +:10231000000FF8D1091A081D05F1040C1844DDF866 +:1023200014E09DF814308E44BEF11B0F99D89A42E8 +:1023300097D91CF8013B00F8013B059B013305933D +:10234000EDE76FF0090069E66FF00A0066E66FF0EE +:102350000D0063E66FF00E0060E66FF00F005DE6C3 +:1023600080841E00F0B53F4D3F4FEB6943F0007392 +:10237000EB61EB693D4B9B6AD3F800623E4046F04F +:102380000106C3F80062D3F800423C4044EA00244E +:1023900044F00104C3F80042002955D0002006464D +:1023A000C3F81C02C3F80402C3F80C02C3F81402F9 +:1023B00003EBC00401300E28C4F84062C4F8446244 +:1023C000F6D100274FF0010C9678148816F0010F13 +:1023D00018BFD3F804E20CFA04F01CBF40EA0E0E5A +:1023E000C3F804E216F0020F18BFD3F80CE203EBB7 +:1023F000C4041CBF40EA0E0EC3F80CE2760748BFC7 +:10240000D3F8146207F1010744BF0643C3F814620E +:102410005668B942C4F84062966802F10C02C4F8EA +:102420004462D3F81C4240EA0400C3F81C02CBD13A +:10243000D3F8002222F00102C3F80022EB6923F056 +:102440000073EB61EB69F0BD0122C3F84012C3F8E1 +:102450004412C3F80412C3F81412C3F80C22C3F8D0 +:102460001C22E5E7001002400000FFFF8822002048 +:10247000184A08B5916A8B688B6013F0010104D08B +:1024800013F00C0F18BF4FF48031D80506D513F4A4 +:10249000406F14BF41F4003141F00201D80306D56A +:1024A00013F4402F14BF41F4802141F00401D3699B +:1024B0000BB108489847202383F311880021064870 +:1024C00000F01EFE002383F31188BDE8084001F0F0 +:1024D00083B800BF882200209022002038B5124C1B +:1024E000A36ADD68AA0712D05A6922F002025A6173 +:1024F000A36913B1012120469847202383F3118853 +:1025000000210A4800F0FCFD002383F31188EB064C +:1025100006D51021A36AD960236A0BB102489847F7 +:10252000BDE8384001F058B88822002098220020E9 +:1025300038B5124CA36A1D69AA0712D05A6922F055 +:1025400010025A61A36913B1022120469847202343 +:1025500083F3118800210A4800F0D2FD002383F3A1 +:102560001188EB0606D51021A36A1961236A0BB105 +:1025700002489847BDE8384001F02EB88822002074 +:102580009822002038B50F4CA36A5D682A075D6069 +:102590000AD5042222701A6822F002021A60636AC5 +:1025A00013B10021204698476B0706D5A36A9969A5 +:1025B000236A13B1034809049847BDE8384001F085 +:1025C0000BB800BF8822002010B50E4C204600F04A +:1025D000FDF90D4B0B211320A36200F0D7F90B215D +:1025E000142000F0D3F90B21152000F0CFF90B21B6 +:1025F000162000F0CBF9BDE8104000220E20114655 +:10260000FFF7B0BE88220020006400400F4B10B5D9 +:102610009842044605D10E4BDA6942F00072DA6145 +:10262000DB690122A36A1A60A36A5A68D20707D538 +:10263000626851681268D9611A60064A5A6110BD11 +:102640000121082000F052FCEEE700BF88220020A4 +:10265000001002405B87010003291AD8DFE801F06F +:10266000020A0F14836A9B6813F0E05F14BF012015 +:1026700000207047836A9868C0F380607047836A5F +:102680009868C0F3C0607047836A9868C0F30070B0 +:10269000704700207047000010B5032927D8DFE8F5 +:1026A00001F002272B2F836A9968C1F30161183169 +:1026B00003EB01131078840648BF5468C0F300117F +:1026C00058BF94884FEA410148BF41EAC40100F075 +:1026D0000F00586048BF41F00401906858BF41EABC +:1026E0004451D26841F001019860DA60196010BD70 +:1026F000836A03F5C073DDE7836A03F5C873D9E71E +:10270000836A03F5D073D5E701290AD002290FD0D7 +:1027100081B9836ADA68920701D1186903E0012060 +:102720007047836AD86810F0030018BF0120704713 +:10273000836AF2E70020704710B539B9836AD96817 +:1027400089071BD11B699C0704D110BD012915D035 +:102750000229FAD1816AD1F8C031D1F8C441D1F847 +:10276000C8011061D1F8CC015061202008610869CE +:10277000800717D1486940F0100012E0816AD1F853 +:10278000B031D1F8B441D1F8B8011061D1F8BC0131 +:1027900050612020C860C868800703D1486940F0B4 +:1027A00002004861C3F34000C3F38001000140EA26 +:1027B0004111107920F030000143117189064BBF9F +:1027C00091681189DB085B0D4CBF63F31C0163F357 +:1027D0000A01137948BF916064F3030313714FEA50 +:1027E00014234FEA144458BF118113705480ACE78E +:1027F000026843680A43026003B11847704700004B +:10280000024AD36843F0C003D360704700380140E8 +:10281000024AD36843F0C003D360704700440040CD +:102820002DE9F041D0F89C600446F7683368DA057A +:102830009DB20DD5202383F311884FF4007104302D +:10284000FFF7D6FF6FF480733360002383F31188A2 +:10285000202383F3118804F1040815F02F033AD1E3 +:1028600083F31188380615D5290613D5202383F361 +:10287000118804F1380000F02FFA00284DDA082101 +:10288000201DFFF7B5FF4FF67F733B40F360002339 +:1028900083F311887A0616D56B0614D5202383F3AB +:1028A0001188D4E913239A420AD1236C43B127F04B +:1028B00040073F041021201D3F0CFFF799FFF760F0 +:1028C000002383F31188D4F8A420D3683BB3BDE878 +:1028D000F041106918472B0713D015F0080F0CBFF3 +:1028E00000218021E80748BF41F02001AA0748BF26 +:1028F00041F040016B07404648BF41F48071FFF74B +:1029000077FFAD06736805D594F8A01020461940EE +:1029100000F082FA3568ADB29FE77060B7E7BDE8B6 +:10292000F081000008B50348FFF77AFFBDE80840D2 +:1029300000F052BEB422002008B50348FFF770FF34 +:10294000BDE8084000F048BE5C23002010B5094CEB +:1029500000212046084A00F03FFA084B0021C4F845 +:102960009C30074C074A204600F036FA064BC4F864 +:102970009C3010BDB422002001280008003801401E +:102980005C230020112800080044004001220901B6 +:1029900000F1604303F56143C9B283F8001300F00E +:1029A0001F039A4043099B0003F1604303F5614311 +:1029B000C3F880211A607047090100F16040C9B274 +:1029C00000F56D4001767047FFF7FEBD01230370EF +:1029D000002300F10802C0E9022200F11002C0E960 +:1029E0000422C0E90633C0E90833436070470000A1 +:1029F00010B52023044683F311880223416003703D +:102A0000FFF704FE04232370002383F3118810BD15 +:102A10002DE9F0411F4604460D461646202383F358 +:102A2000118800F108082378052B0DD0294620468F +:102A3000FFF712FE40B1204632462946FFF72CFE32 +:102A4000002080F3118808E03946404600F03CFB46 +:102A50000028E8D0002383F31188BDE8F08100004E +:102A60002DE9F0411F4604460D461646202383F308 +:102A7000118800F110082378052B0DD02946204637 +:102A8000FFF742FE40B1204632462946FFF754FE8A +:102A9000002080F3118808E03946404600F014FB1E +:102AA0000028E8D0002383F31188BDE8F0810000FE +:102AB000F8B5154682680B46AA428169066938BF97 +:102AC0008568761AB54204460BD218462A46FEF7A8 +:102AD00067FCA3692B44A361A36828465B1BA36022 +:102AE000F8BD0CD918463246FEF75AFCAF1B3A46E1 +:102AF000E1683044FEF754FCE3683B44EBE71846DA +:102B00002A46FEF74DFCE368E5E700002DE9F041B9 +:102B1000154683680446934238BF8568D0E904703F +:102B20003F1ABD420E460BD22A46FEF739FC6369B6 +:102B30002B446361A36828465B1BA360BDE8F0815A +:102B40000CD93A46A5EB0708FEF72AFC4246E06896 +:102B5000F119FEF725FCE3684344EAE72A46FEF74D +:102B60001FFCE368E5E7000010B50024C361029B89 +:102B7000C0E90511C1601144C0E900008460016131 +:102B8000036210BD08B5D0E90532934201D18268D5 +:102B900092B98268013282605A1C42611970D0E990 +:102BA00004329A4228BFC3684FF0000128BF436136 +:102BB00000F09AFA002008BD4FF0FF30FBE700005C +:102BC00070B5202304460D4683F31188A668A6B18C +:102BD000A368A269013BA360531CA3611578226915 +:102BE000934224BFE368A361E3690BB12046984791 +:102BF000002383F31188284607E02946204600F089 +:102C000063FA0028E2DA86F3118870BD2DE9F74FE8 +:102C100004460E4617469846D0F81C904FF0200AFE +:102C20008AF311884FF0000B154665B12A463146EC +:102C30002046FFF73DFF034660B94146204600F0BD +:102C400043FA0028F1D0002383F31188781B03B0E6 +:102C5000BDE8F08FB9F1000F03D001902046C847BE +:102C6000019B8BF31188ED1A1E448AF31188DCE76F +:102C7000C361009BC0E90511C1601144C0E90000B7 +:102C80008260016103627047F8B504460D4616463E +:102C9000202383F31188A768A7B1A368013BA36031 +:102CA00063695A1C62611D70D4E904329A4224BFE0 +:102CB000E3686361E3690BB120469847002080F325 +:102CC000118807E03146204600F0FEF90028E2DADC +:102CD00087F31188F8BD0000D0E905239A4210B5AA +:102CE00001D182687AB982680021013282605A1C5F +:102CF00082611C7803699A4224BFC368836100F033 +:102D0000F3F9204610BD4FF0FF30FBE72DE9F74FF8 +:102D100004460E4617469846D0F81C904FF0200AFD +:102D20008AF311884FF0000B154665B12A463146EB +:102D30002046FFF7EBFE034660B94146204600F00F +:102D4000C3F90028F1D0002383F31188781B03B066 +:102D5000BDE8F08FB9F1000F03D001902046C847BD +:102D6000019B8BF31188ED1A1E448AF31188DCE76E +:102D7000026843680A43026003B1184770470000C5 +:102D80001430FFF743BF00004FF0FF331430FFF75C +:102D90003DBF00003830FFF7B9BF00004FF0FF33F0 +:102DA0003830FFF7B3BF00001430FFF709BF000051 +:102DB0004FF0FF311430FFF703BF00003830FFF74A +:102DC00063BF00004FF0FF323830FFF75DBF0000F7 +:102DD00000207047FFF7BABD37B515460D4A0446C7 +:102DE000026000224260C0E9022201220B46027406 +:102DF00000F15C01009020221430FFF7B5FE2B4655 +:102E00002022009404F17C0104F13800FFF730FF28 +:102E100003B030BD4C3B000838B5C36904460D46CD +:102E20001BB904210844FFF7A3FF294604F114004D +:102E3000FFF7A8FE002806DA201D4FF48061BDE8E8 +:102E40003840FFF795BF38BD0022024BC3E900337D +:102E50009A60704704240020002382680374054BA5 +:102E60001B6899689142FBD25A6803604260106007 +:102E7000586070470424002008B5202383F311888C +:102E8000037C032B05D0042B0DD02BB983F31188C1 +:102E900008BD002243691A604FF0FF334361FFF71A +:102EA000DBFF0023F2E7D0E9003213605A60F3E75A +:102EB000002382680374054B1B6899689142FBD814 +:102EC0005A68036042601060586070470424002014 +:102ED000054B196908741868026853601A60186114 +:102EE00001230374FDF732BB0424002030B54B1CD2 +:102EF00004460B4D87B010D02B690A4A01A800F098 +:102F00001BF92046FFF7E4FF049B13B101A800F072 +:102F10002FF92B69586907B030BDFFF7D9FFF8E7E3 +:102F200004240020792E000838B50C4D41612B692E +:102F300081689A680446914203D8BDE83840FFF79B +:102F40008BBF1846FFF7B4FF01232C6101462374A1 +:102F50002046BDE83840FDF7F9BA00BF0424002040 +:102F6000044B1A681B6990689B68984294BF0020C4 +:102F7000012070470424002010B5084C2368206904 +:102F80001A6854602260012223611A74FFF790FFCF +:102F900001462069BDE81040FDF7D8BA042400209E +:102FA00008B5FFF7DDFF18B1BDE80840FFF7E4BF43 +:102FB00008BD0000FFF7E0BFFEE7000010B50C4CB5 +:102FC000FFF742FF00F0AAF880220A49204600F0ED +:102FD00031F8012344F8180C037400F0D9FA0023E7 +:102FE00083F3118862B6BDE81040034800F042B890 +:102FF0002C240020743B0008843B000800F0CAB871 +:10300000EFF3118020B9EFF30583202282F31188BA +:103010007047000010B530B9EFF30584C4F308041D +:1030200014B180F3118810BDFFF7BAFF84F3118843 +:10303000F9E7000082600222028270478368A3F1F0 +:103040003C0243F80C2C026943F83C2C426943F8DB +:10305000382C074A43F81C2CC268A3F1180043F827 +:10306000102C022203F8082C002203F8072C7047CA +:103070005D05000810B5202383F31188FFF7DEFFFC +:1030800000210446FFF750FF002383F311882046F8 +:1030900010BD0000024B1B6958610F20FFF718BFDD +:1030A00004240020202383F31188FFF7F3BF0000DE +:1030B00008B50146202383F311880820FFF716FF87 +:1030C000002383F3118808BD49B1064B42681B6990 +:1030D00018605A60136043600420FFF707BF4FF089 +:1030E000FF3070470424002003460068834205D067 +:1030F00002681A6053604161FFF7AEBE704700007E +:1031000038B504460D462068844200D138BD0368B6 +:1031100023605C604561FFF79FFEF4E7054B03F118 +:103120001402C3E905224FF0FF32DA6100221A626D +:10313000704700BF0424002010B5C0E903230B4AE8 +:10314000136A53699C68A1420CD85C688160036073 +:103150004460206058609868411A99604FF0FF33CE +:10316000D36110BD1B68091BECE700BF04240020DD +:10317000036881689A680A449A60426813605A60DA +:1031800000234FF0FF32C360014BDA61704700BF8C +:103190000424002038B50F4C2246236A01332362F1 +:1031A00052F8143F934206D020259A68013A9A605B +:1031B00063699A6802B138BDD3E9001001604860C4 +:1031C000D968DA6082F311881869884785F3118815 +:1031D000EEE700BF0424002000207047FEE7000057 +:1031E000704700004FF0FF3070470000BFF34F8F73 +:1031F000024AD368DB07FCD4704700BF00200240BE +:1032000008B5074B1B7853B9FFF7F0FF054B1A6958 +:10321000120641BF044A5A6002F188325A6008BD62 +:1032200008250020002002402301674508B5054B12 +:103230001B7833B9FFF7DAFF034A136943F08003C1 +:10324000136108BD08250020002002407F289ABF96 +:1032500000F5003080020020704700004FF48060CD +:1032600070470000802070477F2808B50BD8FFF713 +:10327000EDFF00F580630268013204D1043083421F +:10328000F9D1012008BD0020FCE700007F2838B5F7 +:10329000044623D8FFF7B4FEFFF7A8FFFFF7B0FFFF +:1032A000F3220F4B0546DA60022220461A61FFF72F +:1032B000CDFF58611A694FF4806142F040021A61F3 +:1032C000FFF794FF00F010F92846FFF7AFFFFFF774 +:1032D000A1FE2046BDE83840FFF7C6BF002038BD3C +:1032E000002002402DE9F047044612F001000E468E +:1032F000154606D040F2BD22234B1A600020BDE8DF +:10330000F087224BA2189A4204D940F2C2221E4BE7 +:103310001A60F4E7FFF774FE4FF0010AFFF770FF41 +:10332000FFF764FFDFF868903146A61B012D884641 +:1033300006EB010705D8FFF779FFFFF76BFE0120C9 +:10334000DDE7B8F80030C9F810A03B800024FFF793 +:103350004DFFC9F810403B8831F8022B9BB29A42CE +:103360000FD040F2D922084B1A600A4B1F600A4B5B +:103370001D600A4BC3F80080FFF758FFFFF74AFEB5 +:10338000BCE7023DD2E700BF042500200000020890 +:1033900000200240F824002000250020FC2400200A +:1033A000084908B50B7828B11BB9FFF729FF01239D +:1033B0000B7008BD002BFCD0BDE808400870FFF77B +:1033C00035BF00BF0825002070B5FFF719FE4FF488 +:1033D0007A710D4B0D4E1B6A326801FB03F3934269 +:1033E00037BF0B4A0A495168156836BF4C1CD1E9F2 +:1033F000005454605D1944F100043360FFF70AFE85 +:103400002846214670BD00BF042400200C25002062 +:103410001025002070B5FFF7F3FD4FF47A710F4BC4 +:103420000F4E1B6A326801FB03F3934237BF0D4A0C +:103430000C49516815683ABF4C1C5460D1E90054DE +:103440005D1944F100043360FFF7E4FD4FF47A7234 +:10345000002328462146FCF783FE70BD042400208B +:103460000C2500201025002010B5094C013AD2B2DD +:10347000FF2A00D110BD500854F82030013054F814 +:1034800020009BB243EA004341F8043BEEE700BF53 +:10349000046C004010B50748013AD2B2FF2A00D1AF +:1034A00010BD0C88530840F823404C88013340F885 +:1034B0002340F1E7046C004007B50122002001A978 +:1034C000FFF7D2FF019803B05DF804FB13B5044683 +:1034D000FFF7F2FFA04205D00122002001A90194CC +:1034E000FFF7D8FF02B010BD7047000045F25552FB +:1034F000064B1A6002225A6040F6FF729A604CF640 +:10350000CC421A600122024B1A7070470030004012 +:103510001C250020034B1B781BB14AF6AA22024B44 +:103520001A6070471C25002000300040044B1A68C8 +:103530002AB902F1804202F50432526A1A607047D9 +:10354000182500204FF08072014B5A62704700BF6F +:103550000010024008B5FFF7E9FF024B1868C0F3FE +:10356000407008BD1825002008B5FFF7DFFF024BAB +:103570001868C0F3007008BD18250020EFF3098318 +:10358000203383F30988002383F3118870470000F8 +:10359000202080F3118862B60C4B0D4AD96821F4C3 +:1035A000E0610904090C0A43DA60D3F8FC200949F8 +:1035B00042F08072C3F8FC200A6842F001020A60FF +:1035C0001022DA7783F82200704700BF00ED00E098 +:1035D0000003FA05001000E0202310B583F31188E2 +:1035E0000B4B5B6813F400630FD0EFF309844FF0CB +:1035F0008073203CE36184F30988FFF7B1FC10B1CC +:10360000044BA36110BD044BFBE783F31188F9E77A +:1036100000ED00E06F05000872050008704700002B +:10362000FEE700000A4B0B480B4A90420BD30B4BB2 +:10363000C11EDA1C121A22F003028B4238BF00228C +:103640000021FDF7BFBE53F8041B40F8041BECE754 +:10365000043C0008A0250020A0250020A025002073 +:103660007047000000F030B808B500F063F9FFF7CC +:10367000A5FCBDE80840FFF759BF000070470000F7 +:103680004FF0FF310E4B1A6919611A6900221A6155 +:103690001869D868D960D968DA60DA68DA6942F0FE +:1036A0008052DA61DA69DA6942F00062DA61054A69 +:1036B000DB69136843F48073136000F01BB900BF2B +:1036C0000010024000700040194B1A6842F00102DD +:1036D0001A601A689007FCD51A6802F0F9021A609D +:1036E00000225A605A6812F00C0FFBD11A6842F49B +:1036F00080321A601A689103FCD55A6842F4E812C5 +:103700005A601A6842F080721A601A689201FCD5F9 +:103710001221084A5A60084A11605A6842F00202AF +:103720005A605A6802F00C02082AFAD1704700BFAA +:103730000010024000641D0000200240084A08B545 +:10374000516913680B4003F00103536123B1054A2B +:1037500013680BB150689847BDE80840FFF73CBFBD +:103760000004014020250020084A08B5516913686B +:103770000B4003F00203536123B1054A93680BB178 +:10378000D0689847BDE80840FFF726BF0004014015 +:1037900020250020084A08B5516913680B4003F042 +:1037A0000403536123B1054A13690BB1506998476B +:1037B000BDE80840FFF710BF0004014020250020AD +:1037C000084A08B5516913680B4003F008035361B8 +:1037D00023B1054A93690BB1D0699847BDE8084009 +:1037E000FFF7FABE0004014020250020084A08B572 +:1037F000516913680B4003F01003536123B1054A6C +:10380000136A0BB1506A9847BDE80840FFF7E4BE61 +:103810000004014020250020174B10B55A691C6890 +:10382000144004F478725A61A30604D5134A936ACB +:103830000BB1D06A9847600604D5104A136B0BB1E0 +:10384000506B9847210604D50C4A936B0BB1D06B93 +:103850009847E20504D5094A136C0BB1506C9847A0 +:10386000A30504D5054A936C0BB1D06C9847BDE80D +:103870001040FFF7B1BE00BF00040140202500202A +:103880001A4B10B55A691C68144004F47C425A6102 +:10389000620504D5164A136D0BB1506D9847230588 +:1038A00004D5134A936D0BB1D06D9847E00404D54D +:1038B0000F4A136E0BB1506E9847A10404D50C4A01 +:1038C000936E0BB1D06E9847620404D5084A136F0B +:1038D0000BB1506F9847230404D5054A936F0BB181 +:1038E000D06F9847BDE81040FFF776BE0004014056 +:1038F00020250020062108B50846FFF747F80621D5 +:103900000720FFF743F806210820FFF73FF80621BC +:103910000920FFF73BF806210A20FFF737F80621B8 +:103920001720FFF733F8BDE8084006212820FFF7ED +:103930002DB8000008B5FFF7A3FE064800F00EF80A +:10394000FFF742F8FFF746FAFFF798FEBDE8084098 +:1039500000F002B89C3B000800F042B80023194672 +:103960001C4A0133102BC2E9001102F10802F8D100 +:10397000194B9A6942F07D029A619B690268174B64 +:10398000DA6082685A6042681A60C26803F5806330 +:10399000DA6042695A6002691A608269C3F80C24CD +:1039A000026AC3F80424C269C3F80024426AC3F857 +:1039B0000C28C26AC3F80428826AC3F80028026B84 +:1039C000C3F80C2C826BC3F8042C426BC3F8002C98 +:1039D000704700BF20250020001002400008014071 +:1039E0004FF0E023044A08215A6100229A6107221D +:1039F0000B201A61FEF7E0BF3F19010008B5202334 +:103A000083F31188FFF7FAFA002383F3118808BDC6 +:103A100008B5FFF7F3FFBDE80840FFF7DDBD000084 +:103A200010B501390244904201D1002005E003782D +:103A300011F8014FA34201D0181B10BD0130F2E76D +:103A40002DE9F0419BB10446C91A1778014403F1EE +:103A5000FF3C8C42204601D9002008E00578013463 +:103A6000BD42F6D10CEB0405D618A54201D1BDE844 +:103A7000F08115F8018D16F801EDF045F5D0E8E775 +:103A8000034611F8012B03F8012B002AF9D17047E6 +:103A90006F72672E6172647570696C6F742E6170DD +:103AA0005F7065726970685F616473620000000036 +:103AB0004E6F20617070207369670A004261642054 +:103AC0006677206C656E6774682025750A00426110 +:103AD0006420626F6172645F696420257520736879 +:103AE0006F756C642062652025750A004261642050 +:103AF00066772064657363726970746F72206C6599 +:103B00006E6774682025750A0042616420617070D8 +:103B100020435243203078253038783A30782530A9 +:103B20003878203078253038783A30782530387831 +:103B30000A00476F6F64206669726D776172650A6B +:103B40000040A2E4F164689106000000000000005B +:103B50009D2D0008892D0008C52D0008B12D0008F5 +:103B6000BD2D0008A92D0008952D0008812D000805 +:103B7000D12D00086D61696E0000000069646C65FC +:103B8000000000007C3B000848240020F8240020AE +:103B900001000000B92F0008000000000C1E00000A +:103BA000447B4144B457494401000000424444442A +:103BB00044444444000000004444444444444444D5 +:103BC00000000000444444444444444400000000D5 +:103BD0004444444444444444B8C5FF7F01000000C9 +:103BE000E803000000000000009C0100000000004D +:103BF000640000000000000040420F00FE2A0100A7 +:043C0000D2040000EA :00000001FF diff --git a/Tools/bootloaders/f103-Airspeed_bl.bin b/Tools/bootloaders/f103-Airspeed_bl.bin index 9947c2d7212..e4a956a818d 100755 Binary files a/Tools/bootloaders/f103-Airspeed_bl.bin and b/Tools/bootloaders/f103-Airspeed_bl.bin differ diff --git a/Tools/bootloaders/f103-Airspeed_bl.elf b/Tools/bootloaders/f103-Airspeed_bl.elf index 3894522d30b..1c6a11b66ec 100755 Binary files a/Tools/bootloaders/f103-Airspeed_bl.elf and b/Tools/bootloaders/f103-Airspeed_bl.elf differ diff --git a/Tools/bootloaders/f103-Airspeed_bl.hex b/Tools/bootloaders/f103-Airspeed_bl.hex index bcecbe3b7ba..3396e12d545 100644 --- a/Tools/bootloaders/f103-Airspeed_bl.hex +++ b/Tools/bootloaders/f103-Airspeed_bl.hex @@ -1,1061 +1,963 @@ :020000040800F2 -:1000000000090020A10400081514000819140008B4 -:10001000551400081914000835140008A30400083A -:10002000A3040008A3040008A3040008C5360008C0 -:10003000A3040008A3040008A3040008593A000818 -:10004000A3040008A3040008A3040008A3040008F4 -:10005000A3040008A3040008393800086538000824 -:1000600091380008BD380008E9380008A3040008EA -:10007000A3040008A3040008A3040008A3040008C4 -:10008000A3040008A3040008A304000869250008CD -:10009000D5250008292600087D2600081539000806 -:1000A000A3040008A3040008A3040008A304000894 -:1000B000A3040008A3040008A3040008A304000884 -:1000C000A3040008A3040008A3040008A304000874 -:1000D000A3040008A12A0008B52A0008A304000808 -:1000E0007D390008A3040008A3040008A304000845 -:1000F000A3040008A3040008A3040008A304000844 -:10010000A3040008A3040008A3040008A304000833 -:10011000A3040008A3040008A3040008A304000823 -:10012000A3040008A3040008A3040008A304000813 -:10013000A3040008A3040008A3040008A304000803 -:10014000A3040008A3040008A3040008A3040008F3 -:10015000A3040008A3040008A3040008A3040008E3 -:10016000D0400B1CD1409C46203AD3401843524209 -:1001700063469340184370479140031C90409C464F -:10018000203A9340194352426346D3401943704783 -:1001900053B94AB9002908BF00281CBF4FF0FF31EE -:1001A0004FF0FF3000F07AB9ADF1080C6DE904CEE4 -:1001B00000F006F8DDF804E0DDE9022304B0704742 -:1001C0002DE9F0478C460E460446089D002B50D181 -:1001D0008A4217466CD9B2FA82FEBEF1000F0BD0EC -:1001E000CEF1200C01FA0EF620FA0CFC02FA0EF702 -:1001F0004CEA060C00FA0EF43A0CBCFBF2F9BBB266 -:1002000002FB19CC09FB03FA4FEA144848EA0C46F2 -:10021000B2450AD9F61909F1FF3180F02581B245BE -:1002200040F22281A9F102093E44A6EB0A06B6FB80 -:10023000F2F002FB106600FB03F3A4B244EA0644AA -:10024000A34209D9E41900F1FF3280F00B81A342E7 -:1002500040F2088102383C440021E41A40EA094097 -:10026000002D62D0002324FA0EF42C606B60BDE8F0 -:10027000F0878B4207D9002D55D0002185E8410039 -:100280000846BDE8F087B3FA83F1002940F08F807B -:10029000B34202D3824200F2FC80841A66EB03066A -:1002A0000120B446002D40D085E81010BDE8F0874D -:1002B00012B90127B7FBF2F7B7FA87FEBEF1000FBC -:1002C00035D10121F61B4FEA174C1FFA87F8B6FB10 -:1002D000FCF20CFB126608FB02F0230C43EA064614 -:1002E000B04207D9F61902F1FF3302D2B04200F250 -:1002F000D2801A46361AB6FBFCF00CFB106608FBDF -:1003000000F8A3B243EA0644A04507D9E41900F176 -:10031000FF3302D2A04500F2B9801846A4EB0804CE -:1003200040EA02409CE729462846BDE8F08707FAE4 -:100330000EF7CEF1200326FA03F24FEA174CB2FB78 -:10034000FCF11FFA87F80CFB112206FA0EF620FAD0 -:1003500003F301FB08F933431E0C46EA0246B1459C -:1003600000FA0EF409D9F61901F1FF3280F08C8001 -:10037000B14540F2898002393E44A6EB0906B6FB3E -:10038000FCF00CFB106200FB08F99EB246EA024644 -:10039000B14507D9F61900F1FF3371D2B1456FD9D4 -:1003A00002383E44A6EB090640EA01418FE7C1F15D -:1003B000200722FA07F88B4048EA030326FA07F4DD -:1003C0004FEA134EB4FBFEF91FFA83FC0EFB1944EF -:1003D0008E4020FA07F809FB0CFA48EA06084FEAB3 -:1003E000184646EA0444A24502FA01F200FA01F670 -:1003F00008D9E41809F1FF3044D2A24542D9A9F145 -:1004000002091C44A4EB0A04B4FBFEF00EFB1044EA -:1004100000FB0CFC1FFA88F848EA0444A44507D9FD -:10042000E41800F1FF3E29D2A44527D902381C4424 -:1004300040EA0940A0FB0289A4EB0C0CCC45C24663 -:10044000CE4615D312D055B1B6EB0A036CEB0E06AF -:1004500006FA07F7CB401F43CE402F606E600021A5 -:10046000BDE8F0871046F7E68946DEE64645EAD263 -:10047000B8EB020A69EB030E0138E4E77046D7E7F0 -:1004800018468FE78146BDE7114676E702383C44BF -:1004900044E7084606E7023A3E442BE7704700BFB0 -:1004A00002E000F000F8FEE772B6274880F3088803 -:1004B000264880F3098826484EF60851CEF20001FE -:1004C0000860022080F31488BFF36F8F03F02AF9CD -:1004D00003F046F94FF055301E491B4A91423CBF8C -:1004E00041F8040BFAE71C49184A91423CBF41F815 -:1004F000040BFAE719491A4A1A4B9A423EBF51F8BF -:10050000040B42F8040BF8E700201749174A914200 -:100510003CBF41F8040BFAE703F008F903F022F9B5 -:10052000134C144DAC4203DA54F8041B8847F9E726 -:1005300000F03AF8104C114DAC4203DA54F8041BA9 -:100540008847F9E703F0F0B8000900200011002007 -:10055000000000080001002000090020B841000848 -:1005600000110020741100207811002000260020C6 -:1005700060010008600100086001000860010008D7 -:100580002DE9F04FC1F80CD0C3689D46BDE8F08F4F -:10059000002383F311882846A047002002F07EFE46 -:1005A00002F0A8FD00DFFEE76FF01702364B2DE9E1 -:1005B000F0411A70032200245A7001266FF0630282 -:1005C0009C70DC701C715C719C71DC711C725A72C5 -:1005D0009E72DC7203F020F8804603F06DF8054649 -:1005E000D0BB2A4B984539D03344984537D0284B57 -:1005F00028F0FF029A4234D15FFA88F000F04EFAF8 -:100600002E4642F2107400F077FC00F04DFA0746D7 -:1006100058B364BB374635B11E4B984503D0002410 -:1006200003F042F82746002003F000F81A4B9B68BD -:1006300013F040031ED00FB100F030F800F07EFC44 -:1006400000F018FE00F014FF0546ACB900F0CCFC39 -:10065000012002F029FEF8E70646D4E706462C46BC -:10066000D1E706464FF47A74CDE70446D3E74FF45A -:100670007A74D0E71C46E1E700F0FAFE401BA04286 -:10068000E4D900F00BF8DDE778110020010007B095 -:10069000000008B0263A09B0000C014010B51C4B10 -:1006A0001C4953F8042F013200D110BD8B42F8D100 -:1006B000194C1A4B22689A4228D9194B9B6803F1AE -:1006C000006303F5C8439A4220D202F0C1FF02F052 -:1006D000D3FF002000F0E8FD0220124B187000F05C -:1006E0001FFE114BDA690022DA61D96999699A61B2 -:1006F0009B6972B60D4B0E4A202113601B6822685D -:1007000081F311889D4683F30888104710BD00BF10 -:10071000FC6300081C64000804640008FF63000810 -:1007200078110020841100200010024000640008AD -:1007300008ED00E049F2690008490B689AB21B0C09 -:1007400000FB02330B6044F25061054A136898B213 -:100750001B0C01FB0030106080B270470C110020B0 -:100760000811002010B504460021102200F0F4FD0D -:10077000034B03CB206061601868A06010BD00BF10 -:10078000E8F7FF1FF0B5BBB000F072FE1D4CA36888 -:10079000C31AF92B30D906AD2346A06028220021C8 -:1007A000284601F0F3FB04F10E0000F0CDFD00231C -:1007B000C6B2591D5F1CDBB2B3424FEAC10107DA72 -:1007C0000E3323440822284601F0E0FB3B46F0E7C5 -:1007D00001230393082302930B4B207B01933023C7 -:1007E000C1F3CF0105910093014604A3D3E900238F -:1007F0000495064801F09AF93BB0F0BD78F6339FB6 -:1008000093CACD8DC8210020D5210020A021002031 -:1008100070B50D4614461E4601F02EF950B9022E51 -:100820000ED1012C0CD112A3D3E90023C5E900237A -:10083000012070BD052C14D003D8012C09D0002054 -:1008400070BD282C09D0302CF9D10BA3D3E900239B -:10085000ECE70BA3D3E90023E8E70BA3D3E90023DC -:10086000E4E70BA3D3E90023E0E700BFAFF3008088 -:10087000401DA12026812A0B78F6339F93CACD8D87 -:100880009E6AC421818A46EE26417272DF25D7B75F -:10089000F017304A39059E5638B50D4604460346D2 -:1008A00020222846002101F071FB22792346032AE9 -:1008B00028BF0322284603F8042F2021022201F03A -:1008C00065FB62792346072A28BF0722284603F8DA -:1008D000052F2221032201F059FBA2792346072A82 -:1008E00028BF0722284603F8062F2521032201F0FE -:1008F0004DFB284604F108031022282101F046FB95 -:10090000382038BD2DE9F04FADF5017D21AE0EAD9B -:1009100040F2791280460F463046002100F01CFD5F -:1009200048220021284600F017FD00F0A1FD4FF4F9 -:100930007A72B0FBF2F0574B0DF15A09186093E848 -:10094000070001232B74002385E807000DF15A00EE -:100950006B74FFF707FF032385F82030E82385F841 -:10096000213007AB18464C4903F0E0F81B222864FD -:100970003146284685F83C20FFF78EFF12AB04462F -:1009800001460822304601F001FB08220DF149031F -:10099000A118304601F0FAFA0DF14A03082204F1D9 -:1009A0001001304601F0F2FA13AB202204F11801D5 -:1009B000304601F0EBFA14AB402204F13801304626 -:1009C00001F0E4FA16AB082204F17801304601F098 -:1009D000DDFA0DF15903082204F18001304601F0DF -:1009E000D5FA04F1880A04F5847B4B465146082267 -:1009F00030460AF1080A01F0C9FAD34509F10109A4 -:100A0000F3D11BAB08225946304601F0BFFA4FF034 -:100A1000000904F5887495F834304B4510D84FF030 -:100A2000000995F83C304B4515D92B6C21464B44B9 -:100A30000822304601F0AAFA083409F10109F0E76A -:100A4000AB6B21464B440822304601F09FFA083434 -:100A500009F10109DFE7E31DC3F3CF03F97E059335 -:100A6000002304960393BB7E193702930123019759 -:100A70000093404605A3D3E9002301F057F80DF594 -:100A8000017DBDE8F08F00BFAFF300809E6AC421F6 -:100A9000818A46EE88110020043D0008014B187041 -:100AA000704700BF94110020F0B5334B85B01C7B1C -:100AB00034B10E22314B1A810024204605B0F0BD1E -:100AC0002F4A02AB1068516803C308232D490DEB70 -:100AD00003022D4803F00CF8054630B90A22274BD3 -:100AE0002A481A8100F08CFCE6E70169B1F5CE3F97 -:100AF00006D90B22214B26481A8100F081FCDCE745 -:100B0000438BB3F57A7F09D00C211C4A214811810F -:100B10004FF47A72194600F073FCCEE71E4A024485 -:100B200002F11003994204D21022144B1B481A817F -:100B3000E3E710398E1A2046134900F09DFC074662 -:100B4000324605F11801204600F096FCAB689F4242 -:100B500002D1EB6898420AD00D22084B1A8100900E -:100B60003B46EA68A9680E4800F04AFCA4E70D4835 -:100B700000F046FC0124A0E7C821002088110020D5 -:100B8000D43B0008DC9B010000640008DC3B00084B -:100B9000E83B0008FA3B0008089CFFF7183C0008F7 -:100BA000353C00085E3C00082DE9F04FADB006AFC3 -:100BB00080460C4600F060FF054600286AD1237E7F -:100BC000022B18D1E38A012B15D100F051FC81468C -:100BD000FFF7B0FD4FF4C873B0FBF3F202FB130054 -:100BE000BB4E80B209F51679E37E484430608BB97C -:100BF0000022B84B1A709C37BD46BDE8F08F3B1DF4 -:100C00001D440095002308224FEAC901204601F047 -:100C100021F84D46A38A5FFA85F9013BAB420BD917 -:100C200005F10109B9F1110FE9D140F23911AA4BCF -:100C3000AA4AAB4802F02EFF07F11400FFF792FD1D -:100C40002A4607F11401381D02F042FF034600282E -:100C5000CED1B9F1100F07D09E4B83F800903368C6 -:100C6000A3F516733360C6E707F1980202F8950DF5 -:100C7000014600922046072200F0ECFFF9787F2918 -:100C800004DD984B954A4FF4A871D2E7404600F036 -:100C9000D7FEB0E7E38A052B00F0068106D8012BCA -:100CA000A9D121464046FFF72DFEA4E7282B3DD0D1 -:100CB000302BA0D1637E8C4D01336A7BDBB2934233 -:100CC000E94640F0EF80E27E2B7B9A4240F0EA80DA -:100CD000002607F1980323F8846D00931022012366 -:100CE0003146204600F0B6FFB4F81480A8F102089F -:100CF0001FFA88F808F1030323F003030A3323F0F3 -:100D00000703ADEB030D0DF1180A33469BB2B11C7E -:100D100098454FEAC10106F101066CDD534400938A -:100D200008220023204600F095FFEEE7A38A013B4E -:100D30009BB2C92B3FF65FAF6B4E357B4DBB06F1C7 -:100D40000C03009308222B462946204600F082FF20 -:100D5000A38A05F10109013BEDB29D424FEAC901A9 -:100D600009DA0E353544009500230822204600F0AC -:100D700071FF4D46ECE700230022C6E90023002363 -:100D8000B36086F8D730C6F8D830337B0BB9E37E32 -:100D90003373002507F114063B1D0822294630460F -:100DA0007D60BD60FD6001F0F1F83B7A05F101095D -:100DB000AB424FEAC90107D9FB6808222B443046F1 -:100DC00001F0E4F84D46F0E70023C1F3CF01E07EE7 -:100DD000059104960393A37E1934029328230146B8 -:100DE0000093019438A3D3E90023404600F09EFE0F -:100DF000FFF7C8FCFFE695F8D70000F05FFAD5F8DA -:100E0000D83006461BB995F8D70000F067FAD5F838 -:100E1000D83043449E4204D295F8D700013000F008 -:100E20005DFA00244FEA980BA0B2584504F1010482 -:100E300008DA2B6880000AEB00010122184400F058 -:100E400093FAF1E7D5F8D840D5E9002312EB080270 -:100E500043F10003444495F8D700C5E90023C5F8E1 -:100E6000D84000F02BFA844209D395F8D7300133EB -:100E700085F8D730D5F8D8309E1BC5F8D860B8F1C2 -:100E8000FF0F08DC00232B7300F03AFAFFF70CFE8B -:100E900008B1FFF703FC2B68144A9B0A0133138146 -:100EA0000023AB60CD46A6E6BFF34F8F1049114B30 -:100EB000CA6802F4E0621343CB60BFF34F8F00BFF8 -:100EC000FDE700BFAFF3008026417272DF25D7B780 -:100ED0009C21002099210020703C0008203D000842 -:100EE000C93C0008EB3C0008C82100208811002004 -:100EF00000ED00E00400FA0508B54FF000530B4A7E -:100F0000196891420AD1597D094A0A4811701B7D1E -:100F1000C922037308490E3000F00CFABDE80840FE -:100F2000E02200214FF0005000F016BA9AAD44C5FF -:100F300094110020C821002016000020022330B5A3 -:100F40001F4C85B0637104230025ADF808300123E0 -:100F50000722ADF80C501B498DF80C308DF80B3082 -:100F6000194B1A484B608DF80A2001F0FFFD184B11 -:100F7000019500931749184B4FF48052174800F021 -:100F800029FD174B2546197811B1144800F058FD7A -:100F900000F06EFA0446FFF7CDFB4FF4C873B0FBC8 -:100FA000F3F202FB130304F516749BB21C440D4BC1 -:100FB0001C6002F081FB08B10F232B8105B030BD0E -:100FC000881100200011002003000600E02200200C -:100FD0001108000898110020A90B0008A02100208A -:100FE000941100209C2100202DE9F04F96A7D7E90D -:100FF00000670FF25C29D9E900898F4C93B0DFF8C4 -:1010000058B2DFF858A2204600F0DCFD0CAD079086 -:1010100098B310220021284600F09EF94FF00002FC -:10102000079B197B61F3030219468DF8302051F8B4 -:10103000040F0EAA496803C21B680D9A584663F351 -:101040001C029DF830300D9243F020038DF83030B3 -:1010500000232A46194601F099FD079030B9204631 -:1010600000F0B4FD079B8AF80030CCE79AF8003016 -:10107000072B40DC01338AF8003018220021284673 -:1010800000F06AF9DFF8D0B1DFF8D4A100232A46D6 -:101090001946584601F0A2FD014680BB102208A85F -:1010A00000F05AF9DAF80C3083F01003CAF80C306B -:1010B00000F0E0F90DF1240E0B4612A9024611E9E9 -:1010C00003008EE803009DF83410C1F30300890685 -:1010D00049BF0E99BDF83810C1F31C0141F0004121 -:1010E00058BFC1F30A018DF82C000891204608A9C9 -:1010F00000F0B2FFCAE7204600F068FDBDE72046D9 -:1011000000F0BAFC824600284AD100F0B1F9DFF8BD -:1011100054B1DBF80030984242D300F0A9F90790AF -:10112000FFF708FB4FF4C873B0FBF3F101FB1300AA -:10113000079A80B202F516721044CBF80000DFF86F -:1011400028B18DF820A09BF8001011B901238DF86B -:10115000203028460791FFF705FB07990DF1210084 -:10116000C1F1100A5FFA8AFABAF1060F28BF4FF0F0 -:10117000060A2944524600F0DDF80AF101030493FF -:1011800008AB0393182302932C4B3246019301239F -:10119000204600933B4600F071FC00238BF80030A2 -:1011A00000F066F9264ADFF8C4A01368C31AB3F545 -:1011B0007A7F32D3106000F05DF902460B4620467C -:1011C00000F00AFD204600F057FC30B39AF80C30CE -:1011D000DFF89CB0002B14BF032302238BF80530EB -:1011E00000F046F94FF47A73B0FBF3F02946CBF8E0 -:1011F00000005846FFF750FB18230293114B0730AD -:10120000019340F25513C0F3CF000490009303956F -:1012100042464B46204600F031FC9AF80C300BB1A8 -:10122000FFF7B0FA9AF80C30002B7FF4E8AE13B059 -:10123000BDE8F08FAFF30080A021002098210020AE -:10124000A8220020AC220020401DA12026812A0BCC -:10125000F1C6A7C1D068080FE0220020AD2200200F -:10126000000801409C21002099210020C821002075 -:101270008811002070B502F0CDF80025084C094E09 -:10128000207030682378834208D902F0BFF83368B1 -:1012900005440133B5F5C84F3360F2D370BD00BFCC -:1012A000DC220020B022002002F04CB900F10060E6 -:1012B000920000F5C84002F0F1B80000054B1A6832 -:1012C000054B1B789B1A834202D9104402F09EB84A -:1012D00000207047B0220020DC22002038B50446F0 -:1012E000064D2868204402F097F828B92868204461 -:1012F000BDE8384002F0A2B838BD00BFB0220020DF -:10130000064991F8243033B100230822086A81F895 -:101310002430FFF7CBBF0120704700BFB42200206C -:10132000022802BF4FF48012014B1A61704700BFC0 -:1013300000080140002310B5934203D0CC5CC45494 -:101340000133F9E710BD000002460346981A13F96D -:10135000011B0029FAD1704703460244934202D090 -:1013600003F8011BFAE770472DE9F047234C0546C7 -:1013700094F824308846174683BB2E46DFF87C90CD -:10138000C7B394F824302BB92022FF2148462662A7 -:10139000FFF7E2FF94F824004146C0F10805BD4282 -:1013A00028BF3D465FFA85FAAD002A4604EB80006F -:1013B000FFF7C0FF94F82430A7EB0A079A445FFABE -:1013C0008AFABAF1080F2E44A844FFB284F824A088 -:1013D000D6D1FFF795FF0028D2D108E0266A06EBA8 -:1013E0008306B042CAD0FFF78BFF0028C5D100208A -:1013F000BDE8F0870120BDE8F08700BFB4220020DF -:101400000FB4002004B070470FB44FF0FF3004B0A9 -:1014100070470000FEE70000EFF30983EFF3058358 -:10142000034B9A6B9A6A9A6A9A6A9A6A9B6AFEE76F -:1014300000ED00E0EFF30983EFF30583044B9A6BB3 -:101440009A6A9A6A9A6A9A6A9A6A9B6AFEE700BFDF -:1014500000ED00E0EFF30983EFF30583034B5A6BD4 -:101460009A6A9A6A9A6A9A6A9B6AFEE700ED00E0B5 -:1014700002F0A0B802F07AB830B5084D0A449142A3 -:101480000BD0092411F8013B5840013CF7D040F340 -:1014900000032B4083EA5000F7E730BD2083B8ED0E -:1014A0000246006848B1036811891360D38801338C -:1014B0009BB29942D38038BF1381704770B5044600 -:1014C0000D4688B0202200216846FFF745FF2046E0 -:1014D0000495FFF7E5FF054658B16B46044608AE94 -:1014E0001A4603CAB24220606160134604F1080440 -:1014F000F6D1284608B070BD2DE9F04130B940F270 -:10150000C531264B264A274802F0C4FA0B7C23B982 -:10151000254B234A40F2C631F5E7C66986B9C16159 -:10152000BDE8F081002B29DA930CAB4229D1B442FB -:1015300001D10C60F3E7C8F800100C60BDE8F08141 -:101540004B68B04623F06047BD0C15EA230538BF51 -:101550003D4634464FEAD37EC3F3807C6368BEEBDE -:10156000D37F23F06042DDD1974203D1C3F3807370 -:101570009C450AD1974205E01C46EFE7AA4206D0F7 -:1015800013469D422CBF00230123002BCFD123689B -:10159000A046002BF0D12160BDE8F081F43F0008A7 -:1015A000E83D0008AC400008CD40000808B5034AFB -:1015B000034B40F25E31034802F06CFAC43D000870 -:1015C0006C400008AC40000808B503680B60C38895 -:1015D000016033B9044B054A4FF4C761044802F077 -:1015E00059FA013BC38008BD3C400008383E000862 -:1015F000AC40000870B50C4600F10C05616831B9CB -:10160000E38A002061F30903E382002170BD0E68C4 -:101610002846FFF7D9FF6660F0E7000008B542688A -:1016200032B10B4B0B4A40F22F410B4802F032FA19 -:10163000C37DC3F38401013161F38603C375C38A9B -:1016400062F30903C3821B0A62F3C713C37508BDA3 -:1016500088400008F43D0008AC4000082DE9F04740 -:10166000089E32B91F4B204A40F239511F4802F000 -:1016700011FA4FF47F4901F007054FEAD6082A44D2 -:1016800006F0070600EBD100954201D1BDE8F087D6 -:1016900005F0070E06F0070AD645774638BF5746CD -:1016A000511BC7F108078F4228BF0F46EC08045DA5 -:1016B00008EBD60113F801C004FA0EF429FA07FE6C -:1016C00024FA0AF45FFA8EFE8CEA04044EFA0AFE4B -:1016D00004EA0E048CEA040C03F801C03D443E44C5 -:1016E000D2E700BF084000080C3E0008AC400008EC -:1016F0002DE9F04106460F4600254FF6FF7441F2F2 -:1017000021082A4630463946FEF72AFD0823C0B292 -:1017100084EA002414F4004F4FEA4404A4B203F115 -:10172000FF3318BF84EA080413F0FF03F2D1083531 -:10173000402DE6D12046BDE8F081000010B541F211 -:1017400021040A44914200D110BD11F8013B80EA06 -:101750000320082310F4004F4FEA400080B203F149 -:10176000FF3318BF604013F0FF03F3D1EAE7000036 -:101770002DE9F04F85B08A468DE80C00BDF83C405D -:10178000814630B940F26E31484B494A494802F02F -:1017900081F911F0604F04D0474B454A40F26F3158 -:1017A000F4E7009B002B7ED024B10E9B002B7AD057 -:1017B000072C28D809F10C00FFF772FE054628B95E -:1017C0006FF00205284605B0BDE8F08F1422002115 -:1017D000FFF7C2FD22460E9905F10800FFF7AAFDAA -:1017E000631C2B74009B2C441B78294603F01F03B9 -:1017F00063F03F0323724AF000436B604846FFF7F3 -:101800007BFE0125DEE74FF000084FF0800B4646D7 -:101810004546019B1B0A029300F10C0303930398B6 -:10182000FFF73EFE07460028CAD014220021FFF72A -:1018300093FDB6BB02229DF804303B729DF8083040 -:101840007B720E9B711E1944B4420AD9B81801323A -:1018500011F801EFD2B20136072A80F808E0B6B2DB -:10186000F2D1B44208BF4FF0400B009BB818197872 -:10187000013201F01F0141EA48114BEA01030372F2 -:101880004AF000437B603A7439464846FFF734FE1D -:101890000135B4422DB288F001084FF0000BBED1E3 -:1018A00090E70022CDE76FF001058BE7F43F0008D9 -:1018B000D83D0008AC400008184000082DE9F0476A -:1018C0001E46CB8A9146C3F30902062A80460F467C -:1018D00019D013460021B0B28DB25A1992B2052A1E -:1018E00009D9A84210D8FA8A034463F30902FA829C -:1018F0000120BDE8F087A842F3D919F801403A4425 -:1019000094760131E8E70025FB8A7C68C3F309007F -:101910001C23821FB2FBF3FA03FB1A2A1FFA8AF276 -:101920007CB301212368002B39D1B31F03441C2051 -:10193000B3FBF0F301339BB299420CD2BAF1000F22 -:1019400009D14046FFF7ACFD08B1C0F800A0206007 -:1019500008B3044600224FF0000AB6B2B54230D2B6 -:101960001346691E4944E018013311F801EF9BB298 -:1019700001351C2B80F804E0ADB214D0AE42F2D891 -:10198000ECE74046FFF78CFD044608B100230360F6 -:101990007C60002CDED16FF00200BDE8F0870131E1 -:1019A00089B21C46BEE7AE42D8D94046FFF778FD63 -:1019B00008B1C0F800A020600028ECD00446002246 -:1019C000CCE7FB8AC3F30902164466F30903FB82E2 -:1019D0008EE70000F8B50E4615461F46044628B9A6 -:1019E000144B154A4F21154802F054F824220021C7 -:1019F000FFF7B2FC069B6A096360079B0020236225 -:101A00004FF6FF739A4228BF1A46A7602070A06164 -:101A1000E06197B204F10C05824205D100232B60EE -:101A200027826382A382F8BD2E60013035462036BE -:101A3000F2E700BFF03F0008643D0008AC4000083A -:101A400008B528B97321084B084A094802F022F862 -:101A5000037823B94BB2002B01DD017008BD054BA3 -:101A6000024A7D21F1E700BFF43F0008703D000805 -:101A7000AC400008383F0008007870472DE9F74374 -:101A80000D9E074619461046BDF828900B9D9DF8FF -:101A90003040BDF8388016B9B8F1000F43D11F2C83 -:101AA00041D83B78D3B9B8F1070F39D839F00303DF -:101AB00039D1424631464FF6FF70FFF73FFE4FEAFD -:101AC000092920F0010009F44079400449EA04643E -:101AD000400C44EA40244FF6FF730DE043EA09232B -:101AE000B8F1070F43EA0464F5D9FFF701FE424657 -:101AF0003146FFF723FE03468DE840012A46214682 -:101B00003846FFF735FE0DB9FFF750FD2B7801334E -:101B1000DBB21F2B88BF00232B7003B0BDE8F0831E -:101B20006FF00300F9E76FF00100F6E72DE9F743E6 -:101B30000E9F81460B9D9DF830009DF83480BDF8C6 -:101B40003C6007B9C6BB1F2836D899F800E0BEF143 -:101B5000000F34D00C0244F080049DF8281044EAB1 -:101B6000C83444EA014444EA0E04072E44EA0064FF -:101B700015D919461046FFF7BBFD32463946FFF727 -:101B8000DDFD0346019600972A4621464846FFF7A9 -:101B9000EFFDB8F1010F0CD125B9FFF707FD4FF6A6 -:101BA000FF73EFE72B780133DBB21F2B88BF0023D5 -:101BB0002B7003B0BDE8F0836FF00100F9E76FF020 -:101BC0000300F6E7C06900B104307047C1690C300A -:101BD0000B680361FFF7F8BC2DE9F84FD0F818A0A7 -:101BE000054616461F4654464FF00009DFF8608050 -:101BF00000F10C0B0CB9BDE8F88FD4E90223B21A3E -:101C000067EB0303994508BF90451FD2AB69214696 -:101C10009C4228460DD1FFF7EDFCAB6921461B68BD -:101C20005846AB61FFF7D0FCAC692346A2461C4680 -:101C3000E0E7FFF7DFFC23682146CAF8003058468A -:101C4000FFF7C2FC5446DAF80030EFE72368EDE70F -:101C500080841E002DE9F04F8BB00D46144607938B -:101C6000DDF850908246002800F06481B9F1000F41 -:101C700000F06081531E3F2B00F25C81012A03D1EA -:101C8000079B002B40F056810023BAF8146008939C -:101C9000F600B542099380F053812B199E420AD277 -:101CA000761B16F0FF0607D140F26751AA4BAB4AEC -:101CB000AB4801F0EFFE2646DAF80C3023B9DAF82B -:101CC0001030002B00F0A5802F2D31D8C5F1300841 -:101CD00046454FF0000334BFB0465FFA88F80093E2 -:101CE000294608AB4246DAF80800FFF7B7FCA6EB36 -:101CF00008074544FFB24FF0300BBAF8143003F137 -:101D00000053063BDB000293DAF80C300593059B89 -:101D1000002B51D087B9DAF81000002861D0002FCD -:101D20005FD0AB4550D98F4B8C4A40F2A651BFE7EC -:101D300037464FF00008DEE7029B23B98A4B874AFB -:101D40004FF4B161B4E7029BE02B28BFE023069378 -:101D50005B44AB4204931DD95B1B9F4226BFDBB2A1 -:101D600003930397AB4504D97E4B7C4A40F29151D3 -:101D70009EE70598CDF8008008ABA5EB0B01039A10 -:101D80000430FFF76BFC039B9844FF1A1D445FFA75 -:101D900088F8FFB2049B9B4504D3744B6F4A40F212 -:101DA0009B5185E7029B069ADDF810B09B1A0293BF -:101DB000059B1B680593AAE7029BBB42ABD26C4B09 -:101DC000664A40F2A15173E7CDF800803A46A5EB90 -:101DD0000B0108ABB8443D44FFF740FC00275FFA15 -:101DE00088F8BAF81430B5EBC30F04D9614B5B4ADD -:101DF00040F2B1515CE7B8F1400F04D95E4B574A4D -:101E000040F2B25154E767B15C4B544A40F2B351CF -:101E10004EE70093324608AB2946DAF80800FFF790 -:101E20001DFC731E3F2B35B201D8A64204DD544B76 -:101E3000544A40F235213BE760070AD00AAB03EB76 -:101E4000D40111F8083C624202F00702134101F884 -:101E5000083C082C21D9102C21D9202C8CBF082318 -:101E60000423079A002A6DD0B4EBC30F6CD0082C62 -:101E700004F1FF3215D89DF8203023FA02F2D10781 -:101E800006D54FF0FF3202FA04F423438DF82030D8 -:101E90009DF8203089F800304EE00123E1E702236D -:101EA000DFE7102C11D8BDF8203023FA02F2D20758 -:101EB00006D54FF0FF3202FA04F42343ADF8203088 -:101EC000BDF82030A9F8003036E0202C0ED8089953 -:101ED00021FA02F2D30705D54FF0FF3303FA04F4D9 -:101EE0000C430894089BC9F8003025E0402C1CD016 -:101EF000DDE9086730463946FEF732F9002100F087 -:101F0000010050EA01030BD0224601200021FEF718 -:101F100033F9404261EB410106430F43CDE90867C5 -:101F2000DDE90823C9E9002306E0174B154A4FF401 -:101F30002071BDE66FF0010528460BB0BDE8F08FBB -:101F40001D46F9E7012CA3D0082CA1D9102CB7D934 -:101F5000202CE5D8C6E700BF443E00081C3E000820 -:101F6000AC400008663E0008533E00088B3E000867 -:101F7000B33E0008DA3E0008083F0008203F000892 -:101F80003A3F00089C3D0008383F000830B585B056 -:101F900030B940F2B121234B234A244801F07AFDA5 -:101FA00023B9234B204A40F2B221F6E7402A04D954 -:101FB000204B1D4A40F2B621EFE722B91D4B1A4AC9 -:101FC0004FF42F71E9E70024012A0294039417D1FA -:101FD0001B788DF8083053070AD004AB03EBD2030B -:101FE00013F8084C554205F00705AC4003F8084CBF -:101FF00000910346002102A8FFF730FB05B030BD79 -:10200000082AE5D9102A03D81B88ADF80830E2E782 -:10201000202A02D81B680293DDE7D3E90045CDE909 -:102020000245D8E7743F0008B03D0008AC40000806 -:102030008F3F0008383F000870B50C4600F10C05D2 -:10204000E16819B9A1602161A18270BD0E682846BE -:10205000FFF7BAFAE660F3E72DE9F04FD1F8009008 -:1020600091B0C9F3C01604460D46CDE90223002EF7 -:1020700050D0C9F3C03BC9F30626B9F1000F80F276 -:102080009F8119F0C04F40F09B812B7B002B00F00B -:102090009781BBF1020F03D02278B24240F09381C6 -:1020A00009F07F02BBF1020F059236D119F07F0FC4 -:1020B000C9F30F2A01D10AF0030A2B447606059AC8 -:1020C00093F8038046EA0B4646EA82465FEAD81355 -:1020D00046EA0A06069300F09A800022002310A91F -:1020E00061E90823059B6768009352465B462046DA -:1020F000B847002800F08880A7698FB9314604F1FD -:102100000C00FFF7DBF90746D0B96FF0020011B001 -:10211000BDE8F08F4FF0020BAFE7C9F3074ACCE7F9 -:102120003B699E420DD03F68002FF9D1314604F142 -:102130000C00FFF7C3F907460028E6D0A3693B600F -:10214000A761DDE90801FFF7D3FAB882F97D08F04D -:102150001F06C1F38401711A89B20FFA81FEBEF124 -:10216000000FB8BF01F1200EC9F30461D7E90223C3 -:10217000B8BF0FFA8EFE079152EA030100F02F81DB -:10218000DDE90201801A61EB03010B4600210246E2 -:102190009E48994208BF9042C0F02181069B002BC7 -:1021A0003FD0BEF1010F00F31A8118F0400F38D074 -:1021B000DDE90223C7E90223202200210DEB020002 -:1021C000FFF7CAF8DDE90223CDE908232B1D0A93A6 -:1021D0002B7B2046013BDBB2ADF834309DF81C3040 -:1021E000ADF836A08DF83A309DF814308DF838B03F -:1021F0008DF83B308DF83960A36808A998473846B8 -:10220000FFF70CFA002082E76FF00B007FE7A76969 -:1022100017B96FF00C007AE73B699E4296D03F6891 -:10222000F6E7FB7DC8F34012B2EBD31F40F0CE803F -:10223000C3F38403B34240F0CC8006992B7B4FEA72 -:10224000981279B3D2073CD4032B40F2C580DDE964 -:102250000223C7E902232B7BAE1D033BDBB23246D0 -:10226000394604F10C00FFF729FB002808DA39464B -:102270002046FFF7BFF93846FFF7D0F9032046E7BD -:10228000AB883B832A7B033AD2B2B88A3146FFF748 -:1022900055FAFB7DB882DA43C2F3C01262F3C7136A -:1022A000FB75AFE76AB92E1D013BDBB232463946FA -:1022B00004F10C00FFF702FB0028D8DB2A7B013A6F -:1022C000E2E7FA8A013BC2F30902052AD9B250D8E3 -:1022D0000023281D99420AD907EB020E10F801CB02 -:1022E00001320133062A8EF81AC0DBB2F2D18B42DA -:1022F00028BF0023DDE9028907F11A02CDE9088928 -:102300000A927A683CBF04335B190B920C93FB8AE8 -:10231000ADF836A0C3F3090319449DF81C30ADF89D -:1023200034108DF83A309DF814308DF838B08DF8AF -:102330003B3000238DF839607B602A7BB88A013AF4 -:10234000291DFFF7FBF93B8BB882834203D1A368B9 -:1023500008A92046984708A92046FFF76DFE384691 -:10236000FFF75CF9B88A3B8B984214BF112000201C -:10237000CDE6786810B34FF0060E03689BB9A2EB68 -:102380000E021B2A13D80332024405F1040E1F303B -:102390009942ACD91EF801CB013302F801CF90422B -:1023A000DBB2F5D1A3E70EF11C0E1846E5E7184B9A -:1023B000184A40F2B311184801F06CFB034696E747 -:1023C0006FF00900A3E66FF00A00A0E66FF00D00C1 -:1023D0009DE66FF00E009AE66FF00F0097E6FB7D2A -:1023E000394668F386036FF3C713FB752046FFF782 -:1023F00001F9069B002B7FF4D8AEFB7DC3F384026A -:10240000013262F38603FB7503E700BF80841E0080 -:10241000A43F0008883D0008AC4000082DE9F041C9 -:102420004E4EB04240F086804D4CDFF838E1E56911 -:1024300045F00075E561E469846AD4F8007207EA42 -:102440000E0747F00107C4F80072D4F8005205EAFD -:102450000E0545F0010545EA0121C4F80012002AE5 -:102460006AD000210F46C4F81C12C4F80412C4F844 -:102470000C12C4F8141204EBC10501310E29C5F881 -:102480004072C5F84472F6D14FF0000E4FF0010CC7 -:10249000964510D1826AB042D2F8003223F001038F -:1024A000C2F8003258D12E4BDA6922F00072DA619C -:1024B000DB69BDE8F0819F781D8817F0010F18BF18 -:1024C000D4F804820CFA05F11CBF41EA0808C4F8EC -:1024D000048217F0020F18BFD4F80C8204EBC50574 -:1024E0001CBF41EA0808C4F80C827F0748BFD4F833 -:1024F000147203F10C0344BF0F43C4F8147253F871 -:10250000087C0EF1010EC5F8407253F8047CC5F842 -:102510004472D4F81C522943C4F81C12B8E70021B5 -:10252000846AC4F81C12C4F80412C4F80C12C4F86B -:102530001412A9E7002AF2D10022836AC3F84022CC -:10254000C3F84422C3F80422C3F814220122C3F8BA -:102550000C22C3F81C229DE7BDE8F081E022002098 -:10256000001002400000FFFF184A08B5916A8B680E -:102570008B6013F0010105D013F00C0F14BF4FF462 -:1025800080310121D80506D513F4406F14BF41F402 -:10259000003141F00201D80306D513F4402F14BFD7 -:1025A00041F4802141F00401D3690BB107489847F9 -:1025B000202383F311880021054800F09DFE0023AD -:1025C00083F31188BDE8084001F086B8E0220020BE -:1025D000E822002038B5124CA36ADD68AA0712D0A1 -:1025E0005A6922F002025A61A36913B101212046FF -:1025F0009847202383F3118800210A4800F07CFECD -:10260000002383F31188EB0606D51021A36AD96055 -:10261000236A0BB102489847BDE8384001F05CB826 -:10262000E0220020F022002038B5124CA36A1D6978 -:10263000AA0712D05A6922F010025A61A36913B195 -:10264000022120469847202383F3118800210A485D -:1026500000F052FE002383F31188EB0606D510210B -:10266000A36A1961236A0BB102489847BDE8384054 -:1026700001F032B8E0220020F022002038B50F4CE3 -:10268000A36A5D682A075D600AD5032222701A6872 -:1026900022F002021A60636A13B1002120469847B3 -:1026A0006B0706D5A36A9969236A13B10904034825 -:1026B0009847BDE8384001F00FB800BFE022002085 -:1026C00010B50F4C204600F03FFA0E4B0B211320A3 -:1026D000A36200F019FA0B21142000F015FA0B2167 -:1026E000152000F011FA0B21162000F00DFA00233E -:1026F0002046BDE810401A460E21FFF78FBE00BFEE -:10270000E0220020006400400F4B10B598420446C0 -:1027100005D10E4BDA6942F00072DA61DB69012201 -:10272000A36A1A60A36A5A68D20707D5626851681B -:102730001268D9611A60064A5A6110BD0121082049 -:1027400000F092FCEEE700BFE02200200010024003 -:102750005B87010003291AD8DFE801F0020A0F1491 -:10276000836A9B6813F0E05F14BF0120002070476C -:10277000836A9868C0F380607047836A9868C0F382 -:10278000C0607047836A9868C0F30070704700208B -:102790007047000010B503291FD8DFE801F0021FC1 -:1027A0002327816A8B68C3F30163183301EB03139A -:1027B000107881061ED55468C0F30011490041EA23 -:1027C000C40141F0040100F00F005860906841F02E -:1027D00001019860D268DA60196010BD836A03F560 -:1027E000C073E5E7836A03F5C873E1E7836A03F51D -:1027F000D073DDE79488C0F30011490041EA4451E9 -:10280000E1E7000001290CD003D3022910D00020F9 -:102810007047836ADA68920701D1186903E00120E2 -:102820007047836AD86810F0030018BF0120704712 -:10283000836AF2E710B539B9836AD96889071BD171 -:102840001B699B0704D110BD012915D0022948D16D -:10285000816AD1F8C031D1F8C401D1F8C8411461FE -:10286000D1F8CC41546120240C610C69A40717D124 -:102870004C6944F0100412E0816AD1F8B031D1F80B -:10288000B401D1F8B8411461D1F8BC41546120249D -:10289000CC60CC68A40703D14C6944F002044C61BD -:1028A00011795C0864F304119C0864F345111171FB -:1028B00089064BBF91681189DB085B0D4CBF63F340 -:1028C0001C0163F30A01137948BF916060F30303AD -:1028D00013714FEA10234FEA104058BF1181137053 -:1028E000508010BD00231A4610B51C495A50CC1810 -:1028F0000833802B6260F9D1194B9A6942F07D024E -:102900009A619B690268174BDA6082685A60426874 -:102910001A60C26803F58063DA6042695A6002692E -:102920001A608269C3F80C24026AC3F80424C269DD -:10293000C3F80024426AC3F80C28C26AC3F804280A -:10294000826AC3F80028026BC3F80C2C826BC3F8B0 -:10295000042C426BC3F8002C10BD00BF0C230020D8 -:102960000010024000080140026843681143016002 -:1029700003B1184770470000024AD36843F0C00310 -:10298000D360704700380140024AD36843F0C00367 -:10299000D3607047004400402DE9F041D0F89C60BE -:1029A0000546F7683368DA059CB20DD5202383F31A -:1029B00011884FF400710430FFF7D6FF6FF4807375 -:1029C0003360002383F31188202383F3118805F1FA -:1029D000040814F02F0333D183F31188380615D57A -:1029E000210613D5202383F3118805F1380000F068 -:1029F0002FFA002846DA0821281DFFF7B5FF4FF609 -:102A00007F733B40F360002383F311887A060ED571 -:102A100063060CD5202383F31188EA6C2B6D9A4250 -:102A200002D12B6C002B2FD1002383F31188D5F812 -:102A3000A420D368002B31D0BDE8F04110691847BD -:102A4000230713D014F0080F0CBF00218021E007EA -:102A500048BF41F02001A20748BF41F04001630791 -:102A600048BF41F480714046FFF77EFFA4067368BB -:102A700005D595F8A0102846194000F089FA346869 -:102A8000A4B2A6E77060BEE727F040073F0410211C -:102A9000281D3F0CFFF768FFF760C5E7BDE8F08130 -:102AA00008B50348FFF778FFBDE8084000F014BE02 -:102AB0008C23002008B50348FFF76EFFBDE80840EF -:102AC00000F00ABE3424002010B5094C094A204603 -:102AD000002100F03DFA084B084AC4F89C30084C2D -:102AE0000021204600F034FA064BC4F89C3010BD9B -:102AF0008C2300207929000800380140892900082A -:102B0000342400200044004000F16043090103F533 -:102B10006143C9B283F80013012300F01F0240098A -:102B2000800000F16040934000F56140C0F88031C2 -:102B300003607047090100F16040C9B200F56D40C3 -:102B400001767047FFF7BCBD01230370002300F13D -:102B500008028260C26000F11002436002614261BB -:102B60008361C361036243627047000010B5202394 -:102B7000044683F31188022341600370FFF7C4FD0C -:102B800003232370002383F3118810BD2DE9F04146 -:102B90001F4604460D461646202383F3118800F194 -:102BA00008082378042B0ED029462046FFF7D2FDD3 -:102BB00048B1204632462946FFF7ECFD002080F35D -:102BC0001188BDE8F0813946404600F079FB0028C5 -:102BD000E7D0002383F31188BDE8F0812DE9F041AF -:102BE0001F4604460D461646202383F3118800F144 -:102BF00010082378042B0ED029462046FFF702FE4A -:102C000048B1204632462946FFF714FE002080F3E3 -:102C10001188BDE8F0813946404600F051FB00289C -:102C2000E7D0002383F31188BDE8F081F8B515469D -:102C300082680B46AA428169066938BF8568761AA0 -:102C4000B542044607D218462A46FEF773FBA3692D -:102C50002B44A3610DE011D932461846FEF76AFBFA -:102C6000AF1B3A46E1683044FEF764FBE2683A4441 -:102C7000A261A36828465B1BA360F8BD18462A46DC -:102C8000FEF758FBE368E4E72DE9F04104461546FA -:102C900083682669934238BF856840690F46361AB3 -:102CA000B54206D22A46FEF745FB63692B446361B1 -:102CB0000DE012D93246A5EB0608FEF73BFB424673 -:102CC000B919E068FEF736FBE26842446261A36826 -:102CD00028465B1BA360BDE8F0812A46FEF72AFB6D -:102CE000E368E4E710B50024C361029B0A44006076 -:102CF00040608460C160816141610261036210BD16 -:102D000008B582694369934201D1826882B98268B9 -:102D1000013282605A1C42611970426903699A4209 -:102D200001D3C3684361002100F0DAFA002008BD36 -:102D30004FF0FF3008BD000070B5202304460E465A -:102D400083F31188A568A5B1A368A269013BA360BC -:102D5000531CA36115782269934224BFE368A361E1 -:102D6000E3690BB120469847002383F31188284676 -:102D700070BD3146204600F0A3FA0028E2DA85F360 -:102D8000118870BD2DE9F74F05460F4690469A46CB -:102D9000D0F81C90202686F311884FF0000B1446C3 -:102DA00064B1224639462846FFF740FF034668B91A -:102DB0005146284600F084FA0028F1D0002383F31E -:102DC0001188A8EB040003B0BDE8F08FB9F1000F43 -:102DD00003D001902846C847019B8BF31188E41A61 -:102DE0001F4486F31188DBE7C361009BC1608161EA -:102DF000416111440060406082600161036270477C -:102E0000F8B504460E461746202383F31188A568BB -:102E1000A5B1A368013BA36063695A1C62611E707F -:102E2000236962699A4224BFE3686361E3690BB175 -:102E300020469847002080F31188F8BD3946204687 -:102E400000F03EFA0028E2DA85F31188F8BD0000B0 -:102E50008369426910B59A4201D182687AB9826861 -:102E6000013282605A1C82611C7803699A4201D344 -:102E7000C3688361002100F033FA204610BD4FF093 -:102E8000FF3010BD2DE9F74F05460F4690469A4694 -:102E9000D0F81C90202686F311884FF0000B1446C2 -:102EA00064B1224639462846FFF7EEFE034668B96C -:102EB0005146284600F004FA0028F1D0002383F39D -:102EC0001188A8EB040003B0BDE8F08FB9F1000F42 -:102ED00003D001902846C847019B8BF31188E41A60 -:102EE0001F4486F31188DBE70268436811430160E1 -:102EF00003B11847704700001430FFF743BF0000CC -:102F00004FF0FF331430FFF73DBF00003830FFF7BC -:102F1000B9BF00004FF0FF333830FFF7B3BF0000F8 -:102F20001430FFF709BF00004FF0FF311430FFF7F6 -:102F300003BF00003830FFF763BF00004FF0FF32DF -:102F40003830FFF75DBF000000207047FFF7BCBDC1 -:102F50000E4B37B50360002343608360C3600123D9 -:102F6000044615460374202200900B4600F15C01D4 -:102F70001430FFF7B7FE00942B46202204F17C01A9 -:102F800004F13800FFF730FF03B030BDE84000081F -:102F900038B5C36904460D461BB904210844FFF740 -:102FA000A3FF294604F11400FFF7AAFE002806DA61 -:102FB000201D4FF48061BDE83840FFF795BF38BD54 -:102FC0000022024B1B605B609A607047DC2400208B -:102FD000002382680374054B1B6899689142FBD2F9 -:102FE0005A6803604260106058607047DC2400201B -:102FF00008B5202383F31188037C032B05D0042B11 -:103000000DD02BB983F3118808BD002243691A60E3 -:103010004FF0FF334361FFF7DBFF0023F2E790E857 -:103020000C001A6002685360F2E700000023826817 -:103030000374054B1B6899689142FBD85A6803607A -:103040004260106058607047DC240020054B19690D -:1030500008741868026853601A60186101230374C9 -:10306000FDF78EBADC24002030B54B1C87B0054636 -:103070000A4C10D023690A4A01A800F059F92846E1 -:10308000FFF7E4FF049B13B101A800F06BF923697B -:10309000586907B030BDFFF7D9FFF8E7DC240020FE -:1030A000F12F000838B50C4D41612B6981689A6891 -:1030B0000446914203D8BDE83840FFF789BF18465F -:1030C000FFF786FF01232C61014623742046BDE8EB -:1030D0003840FDF755BA00BFDC240020044B1A68C5 -:1030E0001B6990689B68984294BF0020012070473C -:1030F000DC24002010B5084C236820691A6854604D -:103100002260012223611A74FFF790FF01462069B3 -:10311000BDE81040FDF734BADC24002008B5FFF705 -:10312000DDFF18B1BDE80840FFF7E4BF08BD0000AF -:10313000FEE7000010B5174CFFF742FF00F0EAF879 -:1031400080221549204600F06FF8012344F8180C3E -:103150000374124B124AD96821F4E0610904090C86 -:103160000A431049DA60CA6842F08072CA600E49A8 -:103170000A6842F001020A601022DA77202283F8FE -:103180002220002383F3118862B6BDE8104007486F -:1031900000F06CB8042500201041000800ED00E0AC -:1031A0000003FA05F0ED00E0001000E0184100080F -:1031B000F8B50F4C226A01322262224652F8141FDF -:1031C0009142154606D020268B68013B8B606369CF -:1031D0009A6802B1F8BD1968DF68DA604D60616114 -:1031E00082F311881869B84786F31188EFE700BFAA -:1031F000DC240020EFF3118020B9EFF305832022B7 -:1032000082F311887047000010B558B9EFF30584B8 -:10321000C4F3080414B180F3118810BDFFF77EFFDA -:1032200084F3118810BD0000826002220274002223 -:10323000427470478368A3F13C0243F80C2C026986 -:1032400043F83C2C426943F8382C074A43F81C2CBD -:10325000C268A3F1180043F8102C022203F8082CCE -:10326000002203F8072C70479105000810B52023B1 -:1032700083F31188FFF7DEFF00210446FFF712FFFA -:10328000002383F31188204610BD0000024B1B6908 -:1032900058610F20FFF7DABEDC240020202383F3DF -:1032A0001188FFF7F3BF000008B50146202383F320 -:1032B00011880820FFF7D8FE002383F3118808BD8A -:1032C00049B1064B42681B6918605A60136043603D -:1032D0000420FFF7C9BE4FF0FF307047DC24002008 -:1032E0000368984206D01A68026050605961184617 -:1032F000FFF76EBE7047000038B504460D462068E3 -:10330000844200D138BD036823605C604561FFF7EB -:103310005FFEF4E7054B03F114025A619A614FF026 -:10332000FF32DA6100221A62704700BFDC240020FD -:1033300010B5C2600A4A036153699C68A1420CD867 -:103340005C68036044602060586081609868411A3E -:1033500099604FF0FF33D36110BD091B1B68ECE788 -:10336000DC240020036881689A680A449A604268F5 -:10337000136003685A6000234FF0FF32C360014BB3 -:10338000DA617047DC24002000207047FEE700006F -:10339000704700004FF0FF3070470000BFF34F8FC1 -:1033A000024AD368DB07FCD4704700BF002002400C -:1033B00008B5074B1B7853B9FFF7F0FF054B1A69A7 -:1033C000120641BF044A5A6002F188325A6008BDB1 -:1033D000E0250020002002402301674508B5054B89 -:1033E0001B7833B9FFF7DAFF034A136943F0800310 -:1033F000136108BDE0250020002002407F289ABF0D -:1034000000F5003080020020704700004FF480601B -:1034100070470000802070477F2808B50BD8FFF761 -:10342000EDFF00F580630268013204D1043083426D -:10343000F9D1012008BD002008BD00007F2838B563 -:10344000044624D800F0B6F8124D2860FFF7A6FF16 -:10345000FFF7AEFFF322104B2046DA6002221A611A -:10346000FFF7CCFF58611A6942F040021A61FFF77A -:1034700095FF4FF4806100F0E9F8FFF7AFFF00F02F -:1034800099F828602046BDE83840FFF7C5BF002006 -:1034900038BD00BFE4250020002002402DE9F8439C -:1034A00012F00103144606D040F24B221F4B1A6063 -:1034B0000020BDE8F88385181D4A954204D94FF4D1 -:1034C00014711A4A1160F3E7FFF772FFFFF766FF06 -:1034D0004FF00109DFF86880451A012C05EB010661 -:1034E0000F4604D8FFF77AFF0120BDE8F883C8F83B -:1034F000109031F8023B3380FFF750FF0020C8F8EE -:10350000100033883A889BB29A420DD040F267226D -:10351000064B1A60074B1E60074B1C60074B1F6071 -:10352000FFF75CFFBDE8F883023CD6E7DC2500200E -:10353000FFFF0108D0250020D8250020D425002039 -:1035400000200240084908B50B7828B153B9FFF7AD -:103550002FFF01230B7008BD23B1BDE808400870A0 -:10356000FFF73CBF08BD00BFE025002038B5FFF7DE -:1035700041FE4FF47A730C490C4A0C6A116803FB44 -:1035800004F38B420A49D1E9004504D2003445F1E5 -:103590000105C1E90045E41845F100051360FFF796 -:1035A00033FE2046294638BDDC240020E8250020D3 -:1035B000F025002008B5FFF7D9FF4FF47A720023F9 -:1035C000FCF7E6FD08BD00BF10B5094C0439013A0F -:1035D000D2B2FF2A00D110BD53089800043054F82D -:1035E000233000599BB243EA004341F8043FEEE721 -:1035F000046C004030B50748013AD2B2FF2A00D12E -:1036000030BD0D88540840F82450A3004C88043382 -:103610001C50F1E7046C004007B5012201A900200D -:10362000FFF7D2FF019803B05DF804FB13B5044621 -:10363000FFF7F2FFA04206D002A941F8044D012293 -:103640000020FFF7D7FF02B010BD00007047000058 -:1036500045F25552064B1A6002225A6040F6FF723C -:103660009A604CF6CC421A600122024B1A707047E5 -:1036700000300040F9250020034B1B781BB14AF6AF -:10368000AA22024B1A607047F92500200030004042 -:10369000034B1B689B0042BF0122024B1A7070470C -:1036A00024100240F82500204FF08072014B1A6070 -:1036B000704700BF24100240014B1878704700BFCC -:1036C000F8250020EFF30983203383F309880023D2 -:1036D00083F311887047000010B5202383F311880D -:1036E0000D4B5B6813F4006312D0EFF309844FF0C5 -:1036F000807344F8043CA4F1200383F30988FFF7A6 -:10370000EDFC18B1054B44F8083C10BD044BFAE73A -:1037100083F3118810BD00BF00ED00E0A105000893 -:10372000A405000870470000FEE70000084A094BA6 -:1037300009498B4204D30021084A934205D37047BC -:1037400052F8040F43F8040BF3E743F8041BF4E7C3 -:103750002842000800260020002600200026002025 -:1037600000F030B808B500F063F9FFF7E3FCBDE8FE -:103770000840FFF78DBF0000704700004FF0FF3199 -:103780000E4B1A6919611A6900221A611869D86802 -:10379000D960D968DA60DA68DA6942F08052DA61B1 -:1037A000DA69DA6942F00062DA61054ADB691368B6 -:1037B00043F48073136000F01BB900BF0010024097 -:1037C00000700040194B1A6842F001021A601A6832 -:1037D0009007FCD51A6802F0F9021A6000225A60BC -:1037E0005A6812F00C0FFBD11A6842F480321A604A -:1037F0001A689103FCD55A6842F4E8125A601A68B4 -:1038000042F080721A601A689201FCD51221084AAF -:103810005A60084A11605A6842F002025A605A68B7 -:1038200002F00C02082AFAD1704700BF00100240D3 -:1038300000641D0000200240084A08B55369116861 -:103840000B4003F00103536123B1054A13680BB128 -:1038500050689847BDE80840FFF73EBF00040140AC -:103860000C230020084A08B5536911680B4003F087 -:103870000203536123B1054A93680BB1D06898479E -:10388000BDE80840FFF728BF000401400C230020DA -:10389000084A08B5536911680B4003F004035361EB -:1038A00023B1054A13690BB150699847BDE8084038 -:1038B000FFF712BF000401400C230020084A08B59E -:1038C000536911680B4003F00803536123B1054AA3 -:1038D00093690BB1D0699847BDE80840FFF7FCBE7B -:1038E000000401400C230020084A08B55369116800 -:1038F0000B4003F01003536123B1054A136A0BB167 -:10390000506A9847BDE80840FFF7E6BE0004014052 -:103910000C230020174B10B55C691A68144004F49E -:1039200078725A61A30604D5134A936A0BB1D06A20 -:103930009847600604D5104A136B0BB1506B98473B -:10394000210604D50C4A936B0BB1D06B9847E20566 -:1039500004D5094A136C0BB1506C9847A30504D5E4 -:10396000054A936C0BB1D06C9847BDE81040FFF747 -:10397000B3BE00BF000401400C2300201A4B10B559 -:103980005C691A68144004F47C425A61620504D5EB -:10399000164A136D0BB1506D9847230504D5134A91 -:1039A000936D0BB1D06D9847E00404D50F4A136EA8 -:1039B0000BB1506E9847A10404D50C4A936E0BB11D -:1039C000D06E9847620404D5084A136F0BB1506F4C -:1039D0009847230404D5054A936F0BB1D06F9847DD -:1039E000BDE81040FFF778BE000401400C23002022 -:1039F000062108B50846FFF787F806210720FFF7DC -:103A000083F806210820FFF77FF806210920FFF739 -:103A10007BF806210A20FFF777F806211720FFF729 -:103A200073F8BDE8084006212820FFF76DB80000B4 -:103A300008B5FFF7A3FE0648FEF754FFFFF782F82C -:103A4000FFF784FAFFF798FEBDE8084000F002B8DF -:103A50003841000800F00EB808B5202383F3118820 -:103A6000FFF7A6FB002383F31188BDE80840FFF7AA -:103A700033BE0000054B064A08215A6000229A60B6 -:103A800007220B201A60FFF755B800BF10E000E0D6 -:103A90003F1901001FB51C46094B05461B68D86835 -:103AA00052B1084B8DE80A0002922B462246064985 -:103AB000FDF7AAFC00F042F8044B1A46F2E700BFFB -:103AC0001011002074410008814100086C3C00087E -:103AD00010B501390244904201D1002010BD10F808 -:103AE000013B11F8014FA342F5D0181B10BD000097 -:103AF0002DE9F8430746884691461E468BB10D4690 -:103B0000A8EB0500B54207EB000402D20020BDE897 -:103B1000F883324649462046FFF7DAFF18B1013DE7 -:103B2000EEE7BDE8F8832046BDE8F883034611F8C8 -:103B3000012B03F8012B002AF9D1704708B50620A4 -:103B400000F02CF80120FFF721FC00001F2938B5F8 -:103B500004460D4604D9162303604FF0FF3038BDEC -:103B6000426C12B152F821304BB9204600F030F8C7 -:103B70002A4601462046BDE8384000F017B8012B20 -:103B80000AD0591C03D116230360012038BD00243C -:103B9000284642F825409847002038BD024B014690 -:103BA0001868FFF7D3BF00BF1011002038B50023FD -:103BB000064C0546084611462360FFF7EBFB431C05 -:103BC00002D1236803B12B6038BD00BFFC25002063 -:103BD000FFF7DABB40A2E4F1646891064E6F206102 -:103BE0007070207369670A00426164206677206CF8 -:103BF000656E6774682025750A0042616420626FF3 -:103C00006172645F69642025752073686F756C64E8 -:103C10002062652025750A00426164206677206471 -:103C2000657363726970746F72206C656E67746817 -:103C30002025750A00426164206170702043524360 -:103C4000203078253038783A307825303878203070 -:103C500078253038783A3078253038780A00476F40 -:103C60006F64206669726D776172650A00000000FA -:103C700072656365697665645F756E697175655FA8 -:103C800069645F6C656E203C2055415643414E5F30 -:103C900050524F544F434F4C5F44594E414D49434E -:103CA0005F4E4F44455F49445F414C4C4F43415444 -:103CB000494F4E5F554E495155455F49445F4D410F -:103CC000585F4C454E475448002E2E2F2E2E2F5411 -:103CD0006F6F6C732F41505F426F6F746C6F6164D4 -:103CE00065722F63616E2E63707000616C6C6F6320 -:103CF000617465645F6E6F64655F6964203C3D203C -:103D0000313237006F72672E6172647570696C6F43 -:103D1000742E663130335F6169727370656564005B -:103D2000766F69642068616E646C655F616C6C6F4E -:103D3000636174696F6E5F726573706F6E7365280F -:103D400043616E617264496E7374616E63652A2C9F -:103D50002043616E61726452785472616E7366655D -:103D6000722A290063616E617264496E6974000091 -:103D700063616E6172645365744C6F63616C4E6F06 -:103D8000646549440000000063616E6172644861CB -:103D90006E646C6552784672616D650063616E6138 -:103DA00072644465636F64655363616C61720000A3 -:103DB00063616E617264456E636F64655363616CC9 -:103DC00061720000696E6372656D656E7454726134 -:103DD0006E73666572494400656E717565756554EC -:103DE000784672616D6573007075736854785175AB -:103DF0006575650070726570617265466F724E65BB -:103E000078745472616E736665720000636F7079C6 -:103E100042697441727261790000000064657363E5 -:103E200061747465725472616E7366657250617903 -:103E30006C6F61640000000066726565426C6F63C0 -:103E40006B0000006269745F6C656E677468203E89 -:103E500020300072656D61696E696E675F626974BA -:103E600073203E203000696E7075745F6269745F04 -:103E70006F6666736574203E3D20626C6F636B5F96 -:103E80006269745F6F666673657400626C6F636B02 -:103E90005F656E645F6269745F6F666673657420E8 -:103EA0003E20626C6F636B5F6269745F6F666673FE -:103EB00065740072656D61696E696E675F626974D1 -:103EC0005F6C656E677468203C3D2072656D61694A -:103ED0006E696E675F6269747300696E7075745F96 -:103EE0006269745F6F6666736574203C3D2074720E -:103EF000616E736665722D3E7061796C6F61645F8F -:103F00006C656E202A2038006F75747075745F625E -:103F100069745F6F6666736574203C3D20363400BB -:103F200072656D61696E696E675F6269745F6C6509 -:103F30006E677468203D3D20300028726573756C93 -:103F400074203E2030292026262028726573756C47 -:103F500074203C3D203634292026262028726573A3 -:103F6000756C74203C3D206269745F6C656E67748B -:103F70006829000064657374696E6174696F6E20EE -:103F8000213D202828766F6964202A29302900766F -:103F9000616C756520213D202828766F6964202A90 -:103FA000293029006F66667365745F776974686984 -:103FB0006E5F626C6F636B203C2028333255202D7E -:103FC000205F5F6275696C74696E5F6F66667365AA -:103FD000746F66202843616E61726442756666651F -:103FE00072426C6F636B2C2064617461292900003C -:103FF0006F75745F696E7320213D202828766F6984 -:1040000064202A29302900007372635F6C656E207A -:104010003E203055000000002863616E5F69642017 -:104020002620307831464646464646465529203DAC -:104030003D2063616E5F696400000000616C6C6F1D -:104040006361746F722D3E73746174697374696314 -:10405000732E63757272656E745F75736167655FE9 -:10406000626C6F636B73203E203000007472616E6F -:10407000736665725F696420213D202828766F6928 -:1040800064202A293029000073746174652D3E6212 -:1040900075666665725F626C6F636B73203D3D2071 -:1040A0002828766F6964202A293029002E2E2F2E89 -:1040B0002E2F6D6F64756C65732F6C696263616E12 -:1040C0006172642F63616E6172642E63006974654E -:1040D0006D2D3E6672616D652E646174615F6C6505 -:1040E0006E203E203000000000000000152F000868 -:1040F000012F00083D2F0008292F0008352F000848 -:10410000212F00080D2F0008F92E0008492F000864 -:104110006D61696E0000000030410008202500201C -:10412000D02500200100000031310008000000000F -:1041300069646C65000000000C1E0000447B414473 -:10414000B4574944010000004244444444444444B8 -:10415000000000004444444444444444000000003F -:10416000444444444444444400000000444444441F -:10417000444444442C2066756E6374696F6E3A2023 -:1041800000617373657274696F6E2022257322203B -:104190006661696C65643A2066696C6520222573E6 -:1041A000222C206C696E65202564257325730A0016 -:1041B00010C0FF7F0100000064000000000000004C -:1041C000FE2A0100D20400001411002000000000AB -:1041D00000000000000000000000000000000000DF -:1041E00000000000000000000000000000000000CF -:1041F00000000000000000000000000000000000BF -:1042000000000000000000000000000000000000AE -:10421000000000000000000000000000000000009E -:0C42200000000000000000000000000092 +:100000000009002069040008C114000865140008F4 +:10001000A514000865140008851400086B04000886 +:100020006B0400086B0400086B0400087D350008B1 +:100030006B0400086B0400086B040008113A000808 +:100040006B0400086B0400086B0400086B040008D4 +:100050006B0400086B0400083D370008693700088E +:1000600095370008C1370008ED3700086B04000819 +:100070006B0400086B0400086B0400086B040008A4 +:100080006B0400086B0400086B040008712400086E +:10009000DD240008312500088525000819380008EE +:1000A0006B0400086B0400086B0400086B04000874 +:1000B0006B0400086B0400086B0400086B04000864 +:1000C0006B0400086B0400086B0400086B04000854 +:1000D0006B04000825290008392900086B04000872 +:1000E000813800086B0400086B0400086B040008EA +:1000F0006B0400086B0400086B0400086B04000824 +:100100006B0400086B0400086B0400086B04000813 +:100110006B0400086B0400086B0400086B04000803 +:100120006B0400086B0400086B0400086B040008F3 +:100130006B0400086B0400086B0400086B040008E3 +:100140006B0400086B0400086B0400086B040008D3 +:100150006B0400086B0400086B0400086B040008C3 +:1001600053B94AB9002908BF00281CBF4FF0FF311E +:100170004FF0FF3000F076B9ADF1080C6DE904CE18 +:1001800000F006F8DDF804E0DDE9022304B0704772 +:100190002DE9F047089E0D4604468846002B4DD1B8 +:1001A0008A42944668D9B2FA82F252B101FA02F355 +:1001B000C2F1200120FA01F10CFA02FC41EA030825 +:1001C00094404FEA1C41B8FBF1F71FFA8CFE01FB8B +:1001D000178807FB0EF0230C43EA084398420AD91C +:1001E0001CEB030307F1FF3580F01E81984240F2BB +:1001F0001B81023F63441B1AB3FBF1F001FB103378 +:1002000000FB0EFEA4B244EA0344A6450AD91CEB47 +:10021000040400F1FF3380F00981A64540F2068115 +:10022000644402380021A4EB0E0440EA07401EB1EA +:100230000023D440C6E90043BDE8F0878B4208D9CB +:10024000002E00F0EE800021C6E900050846BDE85A +:10025000F087B3FA83F100294AD1AB4202D382423C +:1002600000F2FC80841A65EB030301209846002EFF +:10027000E2D0C6E90048DFE702B9FFDEB2FA82F257 +:10028000002A40F09180A1EB0C0001214FEA1C47AD +:100290001FFA8CFEB0FBF7F307FB1300250C45EAB1 +:1002A00000450EFB03F0A84208D91CEB050503F13D +:1002B000FF3802D2A84200F2CE8043462D1AB5FB89 +:1002C000F7F007FB10550EFB00FEA4B244EA05440C +:1002D000A64508D91CEB040400F1FF3502D2A6455F +:1002E00000F2B6802846A4EB0E0440EA03409EE7E5 +:1002F000C1F120078B4022FA07FC4CEA030C25FAD7 +:1003000007FA4FEA1C49BAFBF9F820FA07F309FB90 +:1003100018AA8D401FFA8CFE1D4300FA01F308FB5A +:100320000EF02C0C44EA0A44A04202FA01F20BD966 +:100330001CEB040408F1FF3A80F08880A04240F2F0 +:100340008580A8F102086444241AB4FBF9F009FB83 +:10035000104400FB0EFEADB245EA0444A64508D9A0 +:100360001CEB040400F1FF356CD2A6456AD90238B3 +:10037000644440EA0840A0FB0295A4EB0E04AC42A2 +:10038000C846AE4656D353D0002E69D0B3EB080210 +:1003900064EB0E0422FA01F304FA07F71F43CC4082 +:1003A000C6E90074002147E70CFA02FCC2F1200103 +:1003B00025FA01F34FEA1C4720FA01F195400D435D +:1003C000B3FBF7F107FB11331FFA8CFE280C40EA50 +:1003D000034001FB0EF3834204FA02F408D91CEB3C +:1003E000000001F1FF382FD283422DD90239604439 +:1003F000C01AB0FBF7F307FB1300ADB245EA0045A6 +:1004000003FB0EF0A84208D91CEB050503F1FF38E9 +:1004100016D2A84214D9023B6544281A43EA014186 +:1004200038E73146304607E72F46E4E61846F9E656 +:100430004B45A9D2B9EB020865EB0C0E0138A3E7D6 +:100440004346EAE7284694E74146D1E7D0467BE7B2 +:100450006444023847E7023B65442FE7084606E755 +:100460003146E9E6704700BF02E000F000F8FEE721 +:1004700072B6284880F30888274880F309882748FF +:100480004EF60851CEF200010860022080F3148875 +:10049000BFF36F8F03F0E4F803F0C0F803F0E2F865 +:1004A0004FF055301E491B4A91423CBF41F8040BA6 +:1004B000FAE71C49184A91423CBF41F8040BFAE79D +:1004C00019491A4A1A4B9A423EBF51F8040B42F896 +:1004D000040BF8E700201749174A91423CBF41F846 +:1004E000040BFAE703F09EF803F0BEF8134C144D2A +:1004F000AC4203DA54F8041B8847F9E700F03CF8F3 +:10050000104C114DAC4203DA54F8041B8847F9E74C +:1005100003F086B800090020001100200000000848 +:100520000001002000090020E03B0008001100202D +:100530002411002028110020A025002060010008BF +:100540006001000860010008600100082DE9F04F1B +:10055000C1F80CD0C3689D46BDE8F08F002383F33B +:1005600011882846A047002002F09CFDFEE702F01B +:1005700021FD00DFFEE700002DE9F04102F09CFFC5 +:10058000074602F0E7FF054600283ED12B4B9F426D +:100590003BD001339F423BD0294B27F0FF029A42C8 +:1005A0003AD1F8B200F052FAA84642F2107400F0C4 +:1005B00057FC08B10024A04600F04EFA064678B376 +:1005C00084BB464635B11F4B9F4203D0002402F046 +:1005D000B9FF2646002002F079FF1B4B9B6813F001 +:1005E000400322D00EB100F031F800F097FC00F08B +:1005F00077FE00F067FF0546CCB100F063FF401BBB +:10060000A04214D900F022F8F3E7A8460024CEE770 +:1006100004464FF00108CAE780464FF47A74C6E7F3 +:100620000446CFE74FF47A74CCE71C46DDE700F0D0 +:1006300025FD012002F03CFDDEE700BF010007B010 +:10064000000008B0263A09B0000C014038B51D4A38 +:100650001D4B1968013134D004339342F9D11B4C3E +:10066000194DD4F80424AA422BD3194B9B6803F1EB +:10067000006303F5C8439A4223D202F037FF02F029 +:1006800049FF002000F046FE0220124B187000F0D7 +:100690007DFE114BDA690022DA61D96999699A61A4 +:1006A0009B6972B64FF0E023C3F8085DD4F80034BC +:1006B000D4F80424202181F311889D4683F308880F +:1006C000104738BD2064000800640008006000087E +:1006D00000110020281100200010024049F269009A +:1006E000084A136899B21B0C00FB013344F25061B5 +:1006F0001360054B186882B2000C01FB0200186001 +:1007000080B27047201100201C11002010B5044653 +:100710000021102200F056FE034B03CB20606160E5 +:100720001868A06010BD00BFE8F7FF1F2DE9F04377 +:10073000BBB000F0C7FE40F2ED22204DAB68C31AFB +:10074000934232D906AF2B4628220021A8603846B2 +:1007500001F0C2FB05F10E0000F02CFE002604465D +:100760005FFA80F905F10E08F3B2F100994501F145 +:10077000280107D908EB06030822384601F0ACFB34 +:100780000136F1E708230122CDE902320C4B053492 +:1007900001933023A4B20093CDE9047405A3D3E9F7 +:1007A0000023297B074801F0ADF93BB0BDE8F08399 +:1007B000AFF3008078F6339F93CACD8D702100206F +:1007C0007D2100204421002070B50D4614461E46B0 +:1007D00001F02EF950B9022E10D1012C0ED112A326 +:1007E000D3E900230120C5E9002307E0282C10D01D +:1007F00005D8012C09D0052C0FD0002070BD302C5D +:10080000FBD10BA3D3E90023ECE70BA3D3E900232F +:10081000E8E70BA3D3E90023E4E70BA3D3E9002324 +:10082000E0E700BFAFF30080401DA12026812A0B26 +:1008300078F6339F93CACD8D9E6AC421818A46EE95 +:1008400026417272DF25D7B7F017304A39059E5618 +:1008500038B50D460446034620222846002101F003 +:100860003BFB22792346032A28BF0322284603F8AC +:10087000042F2021022201F02FFB62792346072A50 +:1008800028BF0722284603F8052F2221032201F062 +:1008900023FBA2792346072A28BF0722284603F80C +:1008A000062F2521032201F017FB284610222821BC +:1008B00004F1080301F010FB382038BD2DE9F04F9A +:1008C0000024ADF5017D0EAE40F2751280460F4654 +:1008D00022A82146219400F075FD21464822304689 +:1008E00000F070FD00F0EEFD4FF47A72B0FBF2F014 +:1008F000544B21AD186093E80700012386E80700F8 +:100900000DF15A003382FFF701FF4EF603033384E3 +:1009100007AB18464C4903F0B3F81B222946306454 +:10092000304686F83C20FFF793FF08220446014634 +:1009300012AB284601F0D0FA08222846A1180DF182 +:10094000490301F0C9FA082228460DF14A0304F1CF +:10095000100101F0C1FA2022284613AB04F118015E +:1009600001F0BAFA4022284614AB04F1380101F034 +:10097000B3FA0822284616AB04F1780101F0ACFA6C +:10098000082228460DF1590304F1800101F0A4FA70 +:1009900004F1880A0DF15A0904F5847B4B4651464F +:1009A000082228460AF1080A01F096FAD34509F10F +:1009B0000109F3D10822594628461BAB01F08CFAF5 +:1009C0004FF0000904F5887496F834304B450AD985 +:1009D000B36B21464B440822284601F07DFA0834C7 +:1009E00009F10109F0E74FF0000996F83C3004EBFB +:1009F000C9014B4508D9336C08224B44284601F005 +:100A00006BFA09F10109F0E700230393BB7E07317C +:100A1000029307F1190301930123C1F3CF01CDE93B +:100A200004510093404605A3D3E90023F97E01F069 +:100A300069F80DF5017DBDE8F08F00BF9E6AC42105 +:100A4000818A46EE2C110020903A0008014B187064 +:100A5000704700BF38110020F0B5334B85B01C7BC8 +:100A600034B10E22314B1A810024204605B0F0BD6E +:100A70002F4A02AB1068516803C308232D492E4842 +:100A80000DEB030202F0DCFF054630B90A22274BCA +:100A90002A481A8100F0E2FCE6E70169B1F5CE3F91 +:100AA00006D90B22214B26481A8100F0D7FCDCE73F +:100AB000438BB3F57A7F09D00C211C4A2148118160 +:100AC0004FF47A72194600F0C9FCCEE71E4A024480 +:100AD00002F11003994204D21022144B1B481A81D0 +:100AE000E3E710398E1A2046134900F0EFFC074661 +:100AF0003246204605F1180100F0E8FCAB689F4241 +:100B000002D1EB6898420AD00D22084B1A8100905E +:100B10003B46D5E902120E4800F0A0FCA4E70D48C0 +:100B200000F09CFC0124A0E7702100202C11002083 +:100B30003D3B0008DC9B010000640008AC3A000863 +:100B4000B83A0008CA3A0008089CFFF7E83A0008DB +:100B5000053B00082E3B00082DE9F04FADB006AF75 +:100B600080460C4600F064FF0546002859D1237EDC +:100B7000022B1AD1E38A012B17D100F0A3FC064601 +:100B8000FFF7ACFD4FF4C873B0FBF3F202FB1300A8 +:100B9000DFF8B49206F5167680B2E37E0644C9F813 +:100BA000006033B90022A94B1A709C37BD46BDE8DE +:100BB000F08FA38AEEB2013BB34205F101050BD9D8 +:100BC0003B1D1E44E900002308222046009601F048 +:100BD000F80101F043F8ECE707F11400FFF796FD88 +:100BE000324607F11401381D02F01AFF03460028AF +:100BF000D8D10F2E08D8954B1E70D9F80030A3F528 +:100C00001673C9F80030D0E7FA1CF870014600925C +:100C10002046072201F022F84046F97800F000FF54 +:100C2000C3E7E38A282B26D010D8012B1ED0052B32 +:100C3000BBD1BFF34F8F8649864BCA6802F4E0628E +:100C40001343CB60BFF34F8F00BFFDE7302BACD118 +:100C5000637E814D01336A7BDBB29342E94603D167 +:100C6000E27E2B7B9A4265D0CD469EE721464046E8 +:100C7000FFF724FE99E7A38A013B9BB2C92B94D8C6 +:100C8000754D2E7B26BB05F10C03009308223346DD +:100C90003146204600F0E2FF731CF2B2D9001E4636 +:100CA000A38A013B9A4205DA0E322A4400920023BD +:100CB0000822EEE700230022C5E900230023AB60F1 +:100CC00085F8D730C5F8D8302B7B0BB9E37E2B7372 +:100CD000002507F114060822294630463B1DC7E9C6 +:100CE0000155FD6001F0F8F83B7A05F10109AB42CE +:100CF0004FEAC90107D9FB6808222B44304601F0AE +:100D0000EBF84D46F0E70023C1F3CF01E07ECDE9DB +:100D100004610393A37E19340293282301460093B0 +:100D2000404647A3D3E90023019400F0EBFEFFF710 +:100D3000FDFC3AE74FF0000807F11403A7F8148010 +:100D40001022009341460123204600F087FFA68A27 +:100D5000023EB6B2F31C9B109B000733DB08A9EBE5 +:100D6000C3039D460DF1180A1FFA88F34FEAC80124 +:100D7000B34201F110010AD20AEB080300930822E2 +:100D80000023204600F06AFF08F10108ECE795F81F +:100D9000D70000F0C9FAD5F8D83004461BB995F849 +:100DA000D70000F0D1FAD5F8D83033449C4204D2B1 +:100DB00095F8D700013000F0C7FA4FF000084FEA6D +:100DC000960B1FFA88F18B45D5E9003209D90AEB59 +:100DD000880103EB8800012200F0FCFA08F1010809 +:100DE000EFE7F31842F10002C5E90032D5F8D83038 +:100DF00095F8D70006EB0308C5F8D88000F094FA00 +:100E0000804509D395F8D730D5F8D8000133001BB9 +:100E100085F8D730C5F8D800FF2E08D800232B73EB +:100E200000F0A4FAFFF718FE08B1FFF70FFC2B68DB +:100E30000A4A9B0A013313810023AB6014E700BF09 +:100E400026417272DF25D7B7402100203D210020C6 +:100E500000ED00E00400FA05702100202C110020B4 +:100E600030B54FF00054244B226885B09A4207D029 +:100E700002F07AFB0446A8B90024204605B030BD34 +:100E8000627D1E4B1E481A70237DC92203731D49C3 +:100E90000E3000F085FA2046E022002100F092FAA0 +:100EA0000124EAE7184A194DD36943F00073D3616E +:100EB000AA6D174B9A42DFD12B6E013B7E2BDBD8FC +:100EC000144A01AB07CA83E807001846032100F063 +:100ED00013FB6B6D83424FF00003CDD12A6D8A4224 +:100EE00003BFAB652A6E054B1C4601BF1A70EA6D45 +:100EF000094B1A60C1E700BF9AAD44C53811002004 +:100F00007021002016000020001002400066004002 +:100F10005041A0B0586600401811002002232DE96E +:100F2000F0434A4C85B0637100230293484BD3F8D9 +:100F300000C0BCF57A7F12D3464F474BB7FBFCF598 +:100F40009C458CBF0A231123B5FBF3F603FB165215 +:100F5000591EC8B2002A3ED002290B46F4D89DF88B +:100F60000B303E495A1E9DF80A303D48013B1B0498 +:100F700043EA0253BDF80820013A13434B6001F0E5 +:100F800037FD00230193374B374900934FF48052CC +:100F9000364B374800F01CFD364B197811B13448F8 +:100FA00000F03EFD00F08EFA0546FFF797FB4FF488 +:100FB000C873B0FBF3F202FB130305F516709BB286 +:100FC00018442D4B186002F0C5FA08B10F23238195 +:100FD00005B0BDE8F083731EB3F5806FBFD24FF448 +:100FE0007A75C0EBC00E0EF103034FEAE30909FB6B +:100FF0000555C3F3C703C11AC9B209F101088844F2 +:10100000B5FBF8F5B5F5617F08D90EF1FF33C3F3F1 +:10101000C703C11A581E0F28C9B214D84A1E072A7E +:101020008CBF00220122581800FB0660B7FBF0F7C6 +:10103000BC4594D1002A92D0ADF808608DF80A30F2 +:101040008DF80B108BE71346EDE700BF2C11002045 +:1010500018110020005125023F420F0010110020FE +:1010600088220020C90700083C110020590B000805 +:101070004421002038110020402100202DE9F04FAC +:1010800093A7D7E900670FF25029D9E90089854D68 +:1010900093B0DFF814B2854C284600F097FD0DF1AF +:1010A000300A079070B310220021504600F08AF9F0 +:1010B0004FF00002079B197B61F303028DF830208B +:1010C000586899680EAA03C21B680D9A584663F3C4 +:1010D0001C029DF830300D9243F020038DF8303023 +:1010E00000235246194601F093FC079028B9284680 +:1010F00000F070FD079B2370CEE72378072B3CD8C8 +:101100000133237018220021504600F05BF9DFF80C +:1011100098B1674C002352461946584601F0A0FC8E +:10112000014670BB102208A800F04CF9E36883F078 +:101130001003E36000F0C8F90DF1240C0B4612A96E +:10114000024611E903008CE803009DF83410C1F356 +:101150000300890649BF0E99BDF83810C1F31C0180 +:1011600041F0004158BFC1F30A018DF82C000891ED +:10117000284608A900F0F8FECCE7284600F02AFD32 +:10118000C0E7284600F054FC8346002844D100F014 +:1011900099F9484B1A6890423ED300F093F90446FF +:1011A000FFF79CFA4FF4C872B0FBF2F101FB12009A +:1011B0008DF820B0DFF800B13E4B04F5167480B214 +:1011C0009BF8001004441C6011B901238DF82030F5 +:1011D00050460791FFF79AFA07990DF12100C1F1E6 +:1011E0001004E4B2062C28BF06245144224600F025 +:1011F000D7F808AB039318230293304B01340193C3 +:101200000123E4B2009332463B462846049400F0A2 +:1012100011FC00238BF8003000F054F9284A294CC7 +:101220001368C31AB3F57A7F31D3106000F04CF91C +:1012300002460B46284600F0D7FC284600F0F8FB93 +:1012400028B3237BDFF880B0002B14BF03230223D5 +:101250008BF8053000F036F94FF47A73B0FBF3F0F9 +:101260005146CBF800005846FFF7F2FA18230293D4 +:10127000164B0730019340F25513C0F3CF00CDE970 +:1012800003A0009342464B46284600F0D3FB237B45 +:101290002BB1FFF74BFA237B002B7FF4FAAE13B090 +:1012A000BDE8F08F44210020882200205522002034 +:1012B00000080140402100203D2100203C21002069 +:1012C00050220020702100202C11002054220020E8 +:1012D000401DA12026812A0BF1C6A7C1D068080FA6 +:1012E00070B501F0BFFF0024084E094D308028681A +:1012F0003388834208D901F0B1FF2B6804440133DD +:10130000B4F5C84F2B60F2D370BD00BF842200201B +:101310005822002002F044B800F10060920000F56D +:10132000C84001F0DFBF0000054B1A68054B1B8861 +:101330009B1A834202D9104401F090BF00207047ED +:10134000582200208422002038B50446064D286823 +:10135000204401F089FF28B928682044BDE83840BE +:1013600001F094BF38BD00BF58220020064991F813 +:10137000243033B100230822086A81F82430FFF7B3 +:10138000CBBF0120704700BF5C220020022802BFB3 +:101390004FF48012014B1A61704700BF00080140F2 +:1013A000002310B5934203D0CC5CC4540133F9E759 +:1013B00010BD000003460246D01A12F9011B002995 +:1013C000FAD1704703460244934202D003F8011B4E +:1013D000FAE770472DE9F8431F4D144695F824208D +:1013E0000746884652BBDFF870909CB395F82430CE +:1013F0002BB92022FF2148462F62FFF7E3FF95F823 +:1014000024004146C0F10802A24228BF224605EB53 +:101410008000D6B29200FFF7C3FF95F82430A41BDA +:101420001E44F6B2082E17449044E4B285F82460B6 +:10143000DBD1FFF79BFF0028D7D108E02B6A03EB35 +:1014400082038342CFD0FFF791FF0028CBD1002049 +:10145000BDE8F8830120FBE75C2200200FB40020E8 +:1014600004B07047EFF30983EFF30583044B9A6BE5 +:10147000DA6A9A6A9A6A9A6A9A6A9A6A9B6AFEE72A +:1014800000ED00E0EFF30983EFF30583044B9A6B63 +:101490009A6A9A6A9A6A9A6A9A6A9B6AFEE700BF8F +:1014A00000ED00E0EFF30983EFF30583034B5A6B84 +:1014B0009A6A9A6A9A6A9A6A9B6AFEE700ED00E065 +:1014C000FEE7000001F0A6BF01F07EBF30B5094D78 +:1014D0000A4491420DD011F8013B5840082340F3D3 +:1014E0000004013B2C4013F0FF0384EA5000F6D1C6 +:1014F000EFE730BD2083B8ED4FF0FF33F7B500EBD9 +:1015000081061946DFF848C0DFF848E0B0421BD03A +:1015100050F8042B01AF0192042217F8014B81EA25 +:10152000046108240D46DB184941013C002DBCBF75 +:1015300083EA0C0381EA0E0114F0FF04F2D1013AB0 +:1015400012F0FF02E9D1E1E7D843C94303B0F0BD8F +:101550009336EAA9EBE1F0422DE9F041C56915B9EE +:10156000C161BDE8F0814B68AC4623F06047C3F32E +:101570008A4616EA230638BF3E464FEAD37EC3F3B7 +:1015800080782B465A68BEEBD27F22F060440AD0A6 +:10159000002A18DAA40CB44217D19D420FD10D6075 +:1015A000DEE71346EEE7A74207D102F08044C2F31C +:1015B000807242450BD054B1EFE708D2EDE7CCF88A +:1015C00000100B60CDE7B44201D0B442E5D81A68F0 +:1015D0009C46002AE5D11960C3E700002DE9F047D9 +:1015E0004FF47F49089D01F007044FEAD5082244D3 +:1015F00005F0070500EBD100944201D1BDE8F0876A +:1016000004F0070705F0070A57453E4638BF56461F +:10161000111BC6F108068E4228BF0E46E108415C48 +:1016200008EBD50E13F80EC0B94029FA06F721FAD7 +:101630000AF1FFB28CEA010147FA0AF739408CEA55 +:10164000010C03F80EC034443544D5E7082341F2B9 +:10165000210280EA012001B24000002980B203F19A +:10166000FF33B8BF504013F0FF03F4D170470000C0 +:1016700038B50C468D18A54200D138BD14F8011BB1 +:10168000FFF7E4FFF7E700000346006848B102688F +:1016900019891A60DA88013292B29142DA8038BF31 +:1016A0001A81704770B504460D4688B0202200218B +:1016B0006846FFF787FE20460495FFF7E5FF0246E0 +:1016C00058B16B46054608AE1C4603CCB4422860B0 +:1016D0006960234605F10805F6D1104608B070BDD3 +:1016E000082817D909280CD00A280CD00B280CD0B0 +:1016F0000C280CD00D280CD00E2814BF4020302010 +:1017000070470C2070471020704714207047182035 +:101710007047202070470000082817D90C280CD9E2 +:1017200010280CD914280CD918280CD920280CD929 +:1017300030288CBF0F200E207047092070470A20E8 +:1017400070470B2070470C2070470D207047000039 +:1017500010B54B6823B9CA8A63F30902CA8210BD67 +:10176000C4681A681C60C360438A013B43824A60B4 +:10177000EFE700002DE9F84F1D46CB8A0F46C3F373 +:1017800009010629814692460B4630D00020AAB2B4 +:1017900007F119049EB2052E1FFA80F80FD8904564 +:1017A00003F1010306D3FB8A0A4462F30903012013 +:1017B000FB821AE01AF800600130E654EAE790452F +:1017C000F1D21C23A1F1060BBBFBF3F203FB12BB0E +:1017D0007C681FFA8BF6002C45D14846FFF754FF72 +:1017E000044638B978606FF00200BDE8F88F4FF01A +:1017F0000008E6E70026066078604FF0000BADB207 +:10180000454510D90AEB0803221D13F8011B08F106 +:1018100001089155B1B21B291FFA88F82BD0454514 +:1018200006F10106F1D8FB8AC3F30902154465F3FA +:101830000903BCE71C46013292B22368002BF9D1A0 +:10184000AB1F0B441C21B3FBF1F301339BB29A4253 +:10185000D3D2BBF1000FD0D14846FFF715FF20B916 +:10186000C4F800B0BFE70122E7E7C0F800B05E4669 +:1018700020600446C1E74545D5D94846FFF704FF37 +:1018800008B92060AFE7C0F800B000262060044629 +:10189000B6E700002DE9F04F85B007469146CDE947 +:1018A0000113BDF83C50002A00F08F802DB10E9B33 +:1018B000002B00F08A80072D30D807F10C00FFF7CD +:1018C000E3FE044628B96FF00204204605B0BDE8E7 +:1018D000F08F14220021FFF775FD2A460E9904F1BE +:1018E0000800FFF75DFD681CC0B2FFF715FFFFF7AA +:1018F000F7FE207499F80020431E9BB202F01F02ED +:10190000234462F03F021A72019B384643F00041C3 +:1019100061602146FFF720FE0124D6E74FF0000862 +:101920004FF0800A4646444600F10C0303930398A7 +:10193000FFF7AAFE83460028C5D014220021FFF736 +:1019400041FD002E38D10220029BABF808300E9BDF +:1019500000F10802D2B299195A440130C0B20828E5 +:1019600001D0AE422AD3FFF7D7FEFFF7B9FEAE4251 +:1019700008BF4FF0400A99F80020019B411E02F079 +:101980001F0242EA4812C9B24AEA020A594443F025 +:10199000004281F808A08BF8100059463846CBF871 +:1019A0000420FFF7D9FD0134AE424FF0000A24B203 +:1019B00088F00108BBD188E70020C8E711F801CB07 +:1019C000013602F801CBB6B2C7E76FF001047CE73D +:1019D000F8B5044615460E46282200211F46FFF79B +:1019E000F1FC069BB5F5001F6360079B28BF4FF60F +:1019F000FF7223624FF0000338BF6A09A76004F149 +:101A00000C0097B29A4205D80023036027826382B4 +:101A1000A382F8BD0660013330462036F2E70000AD +:101A200003781BB94BB2002BC8BF01707047000090 +:101A3000007870472DE9F74FDDF83C9080469246DC +:101A40009B46BDF830500D9E9DF83840BDF8407063 +:101A5000B9F1000F01D1002F51D11F2C4FD898F8A8 +:101A60000000B0B9072F47D835F0030347D13A46F5 +:101A700049464FF6FF70FFF7FBFD20F001002D02F5 +:101A8000400445EA0464400C44EA40244FF6FF73E6 +:101A900021E040EA0520072F40EA0464F6D900253A +:101AA0004FF6FF73C5F12000A5F120022AFA05F1D7 +:101AB0000BFA00F001432BFA02F211431846C9B2A7 +:101AC000FFF7C4FD0835402D0346EBD13A464946A1 +:101AD000FFF7CEFD0346324621464046CDE900974A +:101AE000FFF7D8FE33780133DBB21F2B88BF00230A +:101AF000337003B0BDE8F08F6FF00300F9E76FF0CB +:101B00000100F6E72DE9F04F85B0DDF848809246F8 +:101B100006469B460F9D9DF840209DF84490BDF8D9 +:101B20004C70B8F1000F01D1002F48D11F2A46D8C0 +:101B30003378002B46D00C0244EA02649DF838103A +:101B400044EAC93444EA01441C43072F44F08004AA +:101B500032D900234FF6FF72C3F1200CA3F120000D +:101B60002AFA03F10BFA0CFC41EA0C012BFA00F003 +:101B70000143C9B210460393FFF768FD039B024679 +:101B80000833402BE8D13A464146FFF771FD034642 +:101B90002A4621463046CDE90087FFF77BFEB9F1A2 +:101BA000010F06D12B780133DBB21F2B88BF002336 +:101BB0002B7005B0BDE8F08F4FF6FF73E8E76FF0CC +:101BC0000100F6E76FF00300F3E70000C06900B121 +:101BD00004307047C3691A68C261C2681A60C36082 +:101BE000438A013B438270472DE9F041D0F81880C9 +:101BF00014461D4641460027174E09B9BDE8F0813D +:101C0000D1E90223A21A65EB0303964277EB0303A3 +:101C10001ED283698B420DD1FFF79AFD83691B6841 +:101C20008361C3680B60438AC1608169013B884658 +:101C30004382E2E7FFF78CFD0B68C8F80030C36809 +:101C40000B60438AC160013B4382D8F80010D4E79F +:101C500088460968D1E700BF80841E002DE9F04F57 +:101C60008BB00D4614469B468046DDF85090002808 +:101C700000F01A81B9F1000F00F01681531E3F2BBE +:101C800000F21281012A03D1BBF1000F40F00C8158 +:101C90000023CDE90833B8F81430B5EBC30F4FEA91 +:101CA000C30703D300200BB0BDE8F08F2B199F4270 +:101CB000D8F80C3036BF7F1B2746FFB21BB9D8F8C7 +:101CC0001030002B7BD02F2D4ED8C5F13006B742F7 +:101CD0004FF0000334BF3E46F6B200932946324629 +:101CE000D8F8080008ABFFF779FCA7EB060A3544E3 +:101CF0005FFA8AFA3021B8F8143003F10053063B3A +:101D0000DB000493D8F80C300393039B13B1BAF1B2 +:101D1000000F2CD1D8F8100040B1BAF1000F05D057 +:101D20005246009608AB691AFFF758FC38B2002FEC +:101D3000B8D066070AD00AAB03EBD40111F8083C0F +:101D4000624202F00702134101F8083C082C3DD919 +:101D5000102C40F2B680202C40F2B880BBF1000F6E +:101D600000F09D80082335E0BA460026C2E7049BB8 +:101D7000E02B28BFE02306930B44AB42059315D913 +:101D80005A1B924538BF5246039828BFD2B20096DC +:101D9000691A08AB04300792FFF720FC079A164433 +:101DA000AAEB020A1544F6B25FFA8AFA049B069A75 +:101DB00005999B1A0493039B1B680393A5E7009363 +:101DC0003A462946D8F8080008ABADE7BBF1000F4A +:101DD00013D00123B4EBC30F6CD0082C12D89DF89C +:101DE0002030621E23FA02F2D50706D54FF0FF32EB +:101DF00002FA04F423438DF820309DF8203089F84E +:101E0000003050E7102C12D8BDF82030621E23FAA3 +:101E100002F2D10706D54FF0FF3202FA04F4234351 +:101E2000ADF82030BDF82030A9F800303BE7202C79 +:101E30000FD80899631E21FA03F3DA0705D54FF08E +:101E4000FF3202FA04F40C430894089BC9F80030EE +:101E500029E7402C2BD0DDE90865611EC4F1210281 +:101E6000A4F1210326FA01F105FA02F225FA03F39F +:101E700011431943CB0712D50122A4F12003C4F169 +:101E8000200102FA03F322FA01F1A240524243EA8E +:101E9000010363EB430332432B43CDE90823DDE920 +:101EA0000823C9E90023FEE66FF00100FBE66FF0AE +:101EB0000800F8E6082CA0D9102CB3D9202CEED8B5 +:101EC000C3E7BBF1000FADD0022383E7BBF1000FE6 +:101ED000BBD004237EE70000012A30B5144638BF8A +:101EE00001220025402A28BF402285B0012CCDE9DF +:101EF000025517D81B788DF8083053070AD004AB69 +:101F000003EBD20515F8083C544204F00704A34043 +:101F100005F8083C0346009102A80021FFF75EFB8C +:101F200005B030BD082CE5D9102C03D81B88ADF8BE +:101F30000830E2E7202C02D81B680293DDE7D3E9E2 +:101F40000045CDE90245D8E710B5CB681BB98B60D9 +:101F50000B618B8210BDC4681A681C60C360438A21 +:101F6000013B4382CA60F0E72DE9F04FD1F80080D1 +:101F700093B018F0800FCDE90323C8F3C01207BF58 +:101F80004FF0020B1646C8F3C03BC8F30626B8F163 +:101F9000000F04460D4680F2D48118F0C04305932B +:101FA00040F0CF810B7B002B00F0CB81BBF1020F07 +:101FB00003D00178B14240F0C78108F07F0107915A +:101FC0007AB3C8F3074A2B4493F80390760646EA9F +:101FD0000B4608F07F0246EA82465FEAD91346EADA +:101FE0000A06069300F0918000220023CDE90A231F +:101FF00008F07F03009352465B46204667680AA9B3 +:10200000B84700287ED0A7699FB9314604F10C007B +:10201000FFF748FB0746E0B96FF0020013B0BDE8D8 +:10202000F08FC8F30F2A18F07F0F08BF0AF0030AD9 +:10203000C9E73B699E420DD03F68002FF9D1314678 +:1020400004F10C00FFF72EFB07460028E4D0A3693B +:102050003B60A7610026DDE90A234FF6FF70C6F159 +:10206000200E22FA06F103FA0EFEA6F1200C23FA46 +:102070000CFC41EA0E0141EA0C01C9B20836099292 +:102080000893FFF7E3FADDE90832402EE7D1B88282 +:10209000FB7D09F01F06C3F384039B1B98B2002B42 +:1020A000BCBF00F120031BB2D7E9022152EA0100B4 +:1020B000C8F304680FD00398821A049860EB0101FA +:1020C000A74890424FF000028A4104D3069A002AA2 +:1020D0005BD0012B23DDFA7D4FEA890302F0030276 +:1020E00003F07C031343FB7539462046FFF730FBB2 +:1020F000069BA3B9FB7DC3F38402013262F386031E +:10210000FB7504E06FF00B0088E7A76917B96FF063 +:102110000C0083E73B699E42BAD03F68F6E719F0AE +:10212000400F32D0039B1422BB60049B0021FB6054 +:102130000DA8FFF747F9039B20460A93049BADF8CF +:102140003EA00B932B1D0C932B7B8DF840B0013BD5 +:10215000DBB2ADF83C30079B8DF841608DF8433021 +:1021600094F824308DF8428083F001038DF84430D8 +:102170000AA9A3689847FB7DC3F38403013303F0E6 +:102180001F039B02FB82002048E7FB7DC9F340123E +:10219000B2EBD31F40F0DB80C3F38403B34240F0C3 +:1021A000D98006992B7B4FEA9912002934D0D207A7 +:1021B00041D4032B40F2D180039BAE1DBB60049B36 +:1021C0003246FB602B7B3946033BDBB204F10C004B +:1021D000FFF7D0FA00280DDA20463946FFF7B8FAA3 +:1021E000FB7D0320C3F38403013303F01F039B0231 +:1021F000FB8213E7AB883B832A7B033AB88AD2B2CF +:102200003146FFF735FAFB7DB882DA43C2F3C012DC +:1022100062F3C713FB75B6E76AB92E1D013B324660 +:102220003946DBB204F10C00FFF7A4FA0028D3DB37 +:102230002A7B013AE2E7F98A013BC1F3090105294A +:10224000DAB25BD80023281D07F11A0C9A4208D98C +:1022500010F801EB01330CF801E001310629DBB283 +:10226000F4D1934228BF0023039938BF04330A9165 +:10227000049938BFDBB20B9107F11A010C91796810 +:1022800038BF5B190D910E93FB8AADF83EA0C3F3E6 +:1022900009031A44079BADF83C208DF8433094F8AD +:1022A00024308DF840B083F001038DF844300023D2 +:1022B0008DF841608DF842807B602A7BB88A013AB4 +:1022C000291DFFF7D5F93B8BB882834203D1204605 +:1022D000A3680AA9984720460AA9FFF735FEFB7DA7 +:1022E000B88AC3F38403013303F01F039B02FB820C +:1022F0003B8B984214BF112000208FE67B68002B97 +:10230000AFD0062001E063461C30D3F800C0BCF11A +:10231000000FF8D1091A081D05F1040C1844DDF866 +:1023200014E09DF814308E44BEF11B0F99D89A42E8 +:1023300097D91CF8013B00F8013B059B013305933D +:10234000EDE76FF0090069E66FF00A0066E66FF0EE +:102350000D0063E66FF00E0060E66FF00F005DE6C3 +:1023600080841E00F0B53F4D3F4FEB6943F0007392 +:10237000EB61EB693D4B9B6AD3F800623E4046F04F +:102380000106C3F80062D3F800423C4044EA00244E +:1023900044F00104C3F80042002955D0002006464D +:1023A000C3F81C02C3F80402C3F80C02C3F81402F9 +:1023B00003EBC00401300E28C4F84062C4F8446244 +:1023C000F6D100274FF0010C9678148816F0010F13 +:1023D00018BFD3F804E20CFA04F01CBF40EA0E0E5A +:1023E000C3F804E216F0020F18BFD3F80CE203EBB7 +:1023F000C4041CBF40EA0E0EC3F80CE2760748BFC7 +:10240000D3F8146207F1010744BF0643C3F814620E +:102410005668B942C4F84062966802F10C02C4F8EA +:102420004462D3F81C4240EA0400C3F81C02CBD13A +:10243000D3F8002222F00102C3F80022EB6923F056 +:102440000073EB61EB69F0BD0122C3F84012C3F8E1 +:102450004412C3F80412C3F81412C3F80C22C3F8D0 +:102460001C22E5E7001002400000FFFF8822002048 +:10247000184A08B5916A8B688B6013F0010104D08B +:1024800013F00C0F18BF4FF48031D80506D513F4A4 +:10249000406F14BF41F4003141F00201D80306D56A +:1024A00013F4402F14BF41F4802141F00401D3699B +:1024B0000BB108489847202383F311880021064870 +:1024C00000F01EFE002383F31188BDE8084001F0F0 +:1024D00083B800BF882200209022002038B5124C1B +:1024E000A36ADD68AA0712D05A6922F002025A6173 +:1024F000A36913B1012120469847202383F3118853 +:1025000000210A4800F0FCFD002383F31188EB064C +:1025100006D51021A36AD960236A0BB102489847F7 +:10252000BDE8384001F058B88822002098220020E9 +:1025300038B5124CA36A1D69AA0712D05A6922F055 +:1025400010025A61A36913B1022120469847202343 +:1025500083F3118800210A4800F0D2FD002383F3A1 +:102560001188EB0606D51021A36A1961236A0BB105 +:1025700002489847BDE8384001F02EB88822002074 +:102580009822002038B50F4CA36A5D682A075D6069 +:102590000AD5042222701A6822F002021A60636AC5 +:1025A00013B10021204698476B0706D5A36A9969A5 +:1025B000236A13B1034809049847BDE8384001F085 +:1025C0000BB800BF8822002010B50E4C204600F04A +:1025D000FDF90D4B0B211320A36200F0D7F90B215D +:1025E000142000F0D3F90B21152000F0CFF90B21B6 +:1025F000162000F0CBF9BDE8104000220E20114655 +:10260000FFF7B0BE88220020006400400F4B10B5D9 +:102610009842044605D10E4BDA6942F00072DA6145 +:10262000DB690122A36A1A60A36A5A68D20707D538 +:10263000626851681268D9611A60064A5A6110BD11 +:102640000121082000F052FCEEE700BF88220020A4 +:10265000001002405B87010003291AD8DFE801F06F +:10266000020A0F14836A9B6813F0E05F14BF012015 +:1026700000207047836A9868C0F380607047836A5F +:102680009868C0F3C0607047836A9868C0F30070B0 +:10269000704700207047000010B5032927D8DFE8F5 +:1026A00001F002272B2F836A9968C1F30161183169 +:1026B00003EB01131078840648BF5468C0F300117F +:1026C00058BF94884FEA410148BF41EAC40100F075 +:1026D0000F00586048BF41F00401906858BF41EABC +:1026E0004451D26841F001019860DA60196010BD70 +:1026F000836A03F5C073DDE7836A03F5C873D9E71E +:10270000836A03F5D073D5E701290AD002290FD0D7 +:1027100081B9836ADA68920701D1186903E0012060 +:102720007047836AD86810F0030018BF0120704713 +:10273000836AF2E70020704710B539B9836AD96817 +:1027400089071BD11B699C0704D110BD012915D035 +:102750000229FAD1816AD1F8C031D1F8C441D1F847 +:10276000C8011061D1F8CC015061202008610869CE +:10277000800717D1486940F0100012E0816AD1F853 +:10278000B031D1F8B441D1F8B8011061D1F8BC0131 +:1027900050612020C860C868800703D1486940F0B4 +:1027A00002004861C3F34000C3F38001000140EA26 +:1027B0004111107920F030000143117189064BBF9F +:1027C00091681189DB085B0D4CBF63F31C0163F357 +:1027D0000A01137948BF916064F3030313714FEA50 +:1027E00014234FEA144458BF118113705480ACE78E +:1027F000026843680A43026003B11847704700004B +:10280000024AD36843F0C003D360704700380140E8 +:10281000024AD36843F0C003D360704700440040CD +:102820002DE9F041D0F89C600446F7683368DA057A +:102830009DB20DD5202383F311884FF4007104302D +:10284000FFF7D6FF6FF480733360002383F31188A2 +:10285000202383F3118804F1040815F02F033AD1E3 +:1028600083F31188380615D5290613D5202383F361 +:10287000118804F1380000F02FFA00284DDA082101 +:10288000201DFFF7B5FF4FF67F733B40F360002339 +:1028900083F311887A0616D56B0614D5202383F3AB +:1028A0001188D4E913239A420AD1236C43B127F04B +:1028B00040073F041021201D3F0CFFF799FFF760F0 +:1028C000002383F31188D4F8A420D3683BB3BDE878 +:1028D000F041106918472B0713D015F0080F0CBFF3 +:1028E00000218021E80748BF41F02001AA0748BF26 +:1028F00041F040016B07404648BF41F48071FFF74B +:1029000077FFAD06736805D594F8A01020461940EE +:1029100000F082FA3568ADB29FE77060B7E7BDE8B6 +:10292000F081000008B50348FFF77AFFBDE80840D2 +:1029300000F052BEB422002008B50348FFF770FF34 +:10294000BDE8084000F048BE5C23002010B5094CEB +:1029500000212046084A00F03FFA084B0021C4F845 +:102960009C30074C074A204600F036FA064BC4F864 +:102970009C3010BDB422002001280008003801401E +:102980005C230020112800080044004001220901B6 +:1029900000F1604303F56143C9B283F8001300F00E +:1029A0001F039A4043099B0003F1604303F5614311 +:1029B000C3F880211A607047090100F16040C9B274 +:1029C00000F56D4001767047FFF7FEBD01230370EF +:1029D000002300F10802C0E9022200F11002C0E960 +:1029E0000422C0E90633C0E90833436070470000A1 +:1029F00010B52023044683F311880223416003703D +:102A0000FFF704FE04232370002383F3118810BD15 +:102A10002DE9F0411F4604460D461646202383F358 +:102A2000118800F108082378052B0DD0294620468F +:102A3000FFF712FE40B1204632462946FFF72CFE32 +:102A4000002080F3118808E03946404600F03CFB46 +:102A50000028E8D0002383F31188BDE8F08100004E +:102A60002DE9F0411F4604460D461646202383F308 +:102A7000118800F110082378052B0DD02946204637 +:102A8000FFF742FE40B1204632462946FFF754FE8A +:102A9000002080F3118808E03946404600F014FB1E +:102AA0000028E8D0002383F31188BDE8F0810000FE +:102AB000F8B5154682680B46AA428169066938BF97 +:102AC0008568761AB54204460BD218462A46FEF7A8 +:102AD00067FCA3692B44A361A36828465B1BA36022 +:102AE000F8BD0CD918463246FEF75AFCAF1B3A46E1 +:102AF000E1683044FEF754FCE3683B44EBE71846DA +:102B00002A46FEF74DFCE368E5E700002DE9F041B9 +:102B1000154683680446934238BF8568D0E904703F +:102B20003F1ABD420E460BD22A46FEF739FC6369B6 +:102B30002B446361A36828465B1BA360BDE8F0815A +:102B40000CD93A46A5EB0708FEF72AFC4246E06896 +:102B5000F119FEF725FCE3684344EAE72A46FEF74D +:102B60001FFCE368E5E7000010B50024C361029B89 +:102B7000C0E90511C1601144C0E900008460016131 +:102B8000036210BD08B5D0E90532934201D18268D5 +:102B900092B98268013282605A1C42611970D0E990 +:102BA00004329A4228BFC3684FF0000128BF436136 +:102BB00000F09AFA002008BD4FF0FF30FBE700005C +:102BC00070B5202304460D4683F31188A668A6B18C +:102BD000A368A269013BA360531CA3611578226915 +:102BE000934224BFE368A361E3690BB12046984791 +:102BF000002383F31188284607E02946204600F089 +:102C000063FA0028E2DA86F3118870BD2DE9F74FE8 +:102C100004460E4617469846D0F81C904FF0200AFE +:102C20008AF311884FF0000B154665B12A463146EC +:102C30002046FFF73DFF034660B94146204600F0BD +:102C400043FA0028F1D0002383F31188781B03B0E6 +:102C5000BDE8F08FB9F1000F03D001902046C847BE +:102C6000019B8BF31188ED1A1E448AF31188DCE76F +:102C7000C361009BC0E90511C1601144C0E90000B7 +:102C80008260016103627047F8B504460D4616463E +:102C9000202383F31188A768A7B1A368013BA36031 +:102CA00063695A1C62611D70D4E904329A4224BFE0 +:102CB000E3686361E3690BB120469847002080F325 +:102CC000118807E03146204600F0FEF90028E2DADC +:102CD00087F31188F8BD0000D0E905239A4210B5AA +:102CE00001D182687AB982680021013282605A1C5F +:102CF00082611C7803699A4224BFC368836100F033 +:102D0000F3F9204610BD4FF0FF30FBE72DE9F74FF8 +:102D100004460E4617469846D0F81C904FF0200AFD +:102D20008AF311884FF0000B154665B12A463146EB +:102D30002046FFF7EBFE034660B94146204600F00F +:102D4000C3F90028F1D0002383F31188781B03B066 +:102D5000BDE8F08FB9F1000F03D001902046C847BD +:102D6000019B8BF31188ED1A1E448AF31188DCE76E +:102D7000026843680A43026003B1184770470000C5 +:102D80001430FFF743BF00004FF0FF331430FFF75C +:102D90003DBF00003830FFF7B9BF00004FF0FF33F0 +:102DA0003830FFF7B3BF00001430FFF709BF000051 +:102DB0004FF0FF311430FFF703BF00003830FFF74A +:102DC00063BF00004FF0FF323830FFF75DBF0000F7 +:102DD00000207047FFF7BABD37B515460D4A0446C7 +:102DE000026000224260C0E9022201220B46027406 +:102DF00000F15C01009020221430FFF7B5FE2B4655 +:102E00002022009404F17C0104F13800FFF730FF28 +:102E100003B030BD483B000838B5C36904460D46D1 +:102E20001BB904210844FFF7A3FF294604F114004D +:102E3000FFF7A8FE002806DA201D4FF48061BDE8E8 +:102E40003840FFF795BF38BD0022024BC3E900337D +:102E50009A60704704240020002382680374054BA5 +:102E60001B6899689142FBD25A6803604260106007 +:102E7000586070470424002008B5202383F311888C +:102E8000037C032B05D0042B0DD02BB983F31188C1 +:102E900008BD002243691A604FF0FF334361FFF71A +:102EA000DBFF0023F2E7D0E9003213605A60F3E75A +:102EB000002382680374054B1B6899689142FBD814 +:102EC0005A68036042601060586070470424002014 +:102ED000054B196908741868026853601A60186114 +:102EE00001230374FDF732BB0424002030B54B1CD2 +:102EF00004460B4D87B010D02B690A4A01A800F098 +:102F00001BF92046FFF7E4FF049B13B101A800F072 +:102F10002FF92B69586907B030BDFFF7D9FFF8E7E3 +:102F200004240020792E000838B50C4D41612B692E +:102F300081689A680446914203D8BDE83840FFF79B +:102F40008BBF1846FFF7B4FF01232C6101462374A1 +:102F50002046BDE83840FDF7F9BA00BF0424002040 +:102F6000044B1A681B6990689B68984294BF0020C4 +:102F7000012070470424002010B5084C2368206904 +:102F80001A6854602260012223611A74FFF790FFCF +:102F900001462069BDE81040FDF7D8BA042400209E +:102FA00008B5FFF7DDFF18B1BDE80840FFF7E4BF43 +:102FB00008BD0000FFF7E0BFFEE7000010B50C4CB5 +:102FC000FFF742FF00F0AAF880220A49204600F0ED +:102FD00031F8012344F8180C037400F0D9FA0023E7 +:102FE00083F3118862B6BDE81040034800F042B890 +:102FF0002C240020703B0008803B000800F0CAB879 +:10300000EFF3118020B9EFF30583202282F31188BA +:103010007047000010B530B9EFF30584C4F308041D +:1030200014B180F3118810BDFFF7BAFF84F3118843 +:10303000F9E7000082600222028270478368A3F1F0 +:103040003C0243F80C2C026943F83C2C426943F8DB +:10305000382C074A43F81C2CC268A3F1180043F827 +:10306000102C022203F8082C002203F8072C7047CA +:103070005D05000810B5202383F31188FFF7DEFFFC +:1030800000210446FFF750FF002383F311882046F8 +:1030900010BD0000024B1B6958610F20FFF718BFDD +:1030A00004240020202383F31188FFF7F3BF0000DE +:1030B00008B50146202383F311880820FFF716FF87 +:1030C000002383F3118808BD49B1064B42681B6990 +:1030D00018605A60136043600420FFF707BF4FF089 +:1030E000FF3070470424002003460068834205D067 +:1030F00002681A6053604161FFF7AEBE704700007E +:1031000038B504460D462068844200D138BD0368B6 +:1031100023605C604561FFF79FFEF4E7054B03F118 +:103120001402C3E905224FF0FF32DA6100221A626D +:10313000704700BF0424002010B5C0E903230B4AE8 +:10314000136A53699C68A1420CD85C688160036073 +:103150004460206058609868411A99604FF0FF33CE +:10316000D36110BD1B68091BECE700BF04240020DD +:10317000036881689A680A449A60426813605A60DA +:1031800000234FF0FF32C360014BDA61704700BF8C +:103190000424002038B50F4C2246236A01332362F1 +:1031A00052F8143F934206D020259A68013A9A605B +:1031B00063699A6802B138BDD3E9001001604860C4 +:1031C000D968DA6082F311881869884785F3118815 +:1031D000EEE700BF0424002000207047FEE7000057 +:1031E000704700004FF0FF3070470000BFF34F8F73 +:1031F000024AD368DB07FCD4704700BF00200240BE +:1032000008B5074B1B7853B9FFF7F0FF054B1A6958 +:10321000120641BF044A5A6002F188325A6008BD62 +:1032200008250020002002402301674508B5054B12 +:103230001B7833B9FFF7DAFF034A136943F08003C1 +:10324000136108BD08250020002002407F289ABF96 +:1032500000F5003080020020704700004FF48060CD +:1032600070470000802070477F2808B50BD8FFF713 +:10327000EDFF00F580630268013204D1043083421F +:10328000F9D1012008BD0020FCE700007F2838B5F7 +:10329000044623D8FFF7B4FEFFF7A8FFFFF7B0FFFF +:1032A000F3220F4B0546DA60022220461A61FFF72F +:1032B000CDFF58611A694FF4806142F040021A61F3 +:1032C000FFF794FF00F010F92846FFF7AFFFFFF774 +:1032D000A1FE2046BDE83840FFF7C6BF002038BD3C +:1032E000002002402DE9F047044612F001000E468E +:1032F000154606D040F2BD22234B1A600020BDE8DF +:10330000F087224BA2189A4204D940F2C2221E4BE7 +:103310001A60F4E7FFF774FE4FF0010AFFF770FF41 +:10332000FFF764FFDFF868903146A61B012D884641 +:1033300006EB010705D8FFF779FFFFF76BFE0120C9 +:10334000DDE7B8F80030C9F810A03B800024FFF793 +:103350004DFFC9F810403B8831F8022B9BB29A42CE +:103360000FD040F2D922084B1A600A4B1F600A4B5B +:103370001D600A4BC3F80080FFF758FFFFF74AFEB5 +:10338000BCE7023DD2E700BF042500200000020890 +:1033900000200240F824002000250020FC2400200A +:1033A000084908B50B7828B11BB9FFF729FF01239D +:1033B0000B7008BD002BFCD0BDE808400870FFF77B +:1033C00035BF00BF0825002070B5FFF719FE4FF488 +:1033D0007A710D4B0D4E1B6A326801FB03F3934269 +:1033E00037BF0B4A0A495168156836BF4C1CD1E9F2 +:1033F000005454605D1944F100043360FFF70AFE85 +:103400002846214670BD00BF042400200C25002062 +:103410001025002070B5FFF7F3FD4FF47A710F4BC4 +:103420000F4E1B6A326801FB03F3934237BF0D4A0C +:103430000C49516815683ABF4C1C5460D1E90054DE +:103440005D1944F100043360FFF7E4FD4FF47A7234 +:10345000002328462146FCF783FE70BD042400208B +:103460000C2500201025002010B5094C013AD2B2DD +:10347000FF2A00D110BD500854F82030013054F814 +:1034800020009BB243EA004341F8043BEEE700BF53 +:10349000046C004010B50748013AD2B2FF2A00D1AF +:1034A00010BD0C88530840F823404C88013340F885 +:1034B0002340F1E7046C004007B50122002001A978 +:1034C000FFF7D2FF019803B05DF804FB13B5044683 +:1034D000FFF7F2FFA04205D00122002001A90194CC +:1034E000FFF7D8FF02B010BD7047000045F25552FB +:1034F000064B1A6002225A6040F6FF729A604CF640 +:10350000CC421A600122024B1A7070470030004012 +:103510001C250020034B1B781BB14AF6AA22024B44 +:103520001A6070471C25002000300040044B1A68C8 +:103530002AB902F1804202F50432526A1A607047D9 +:10354000182500204FF08072014B5A62704700BF6F +:103550000010024008B5FFF7E9FF024B1868C0F3FE +:10356000407008BD1825002008B5FFF7DFFF024BAB +:103570001868C0F3007008BD18250020EFF3098318 +:10358000203383F30988002383F3118870470000F8 +:10359000202080F3118862B60C4B0D4AD96821F4C3 +:1035A000E0610904090C0A43DA60D3F8FC200949F8 +:1035B00042F08072C3F8FC200A6842F001020A60FF +:1035C0001022DA7783F82200704700BF00ED00E098 +:1035D0000003FA05001000E0202310B583F31188E2 +:1035E0000B4B5B6813F400630FD0EFF309844FF0CB +:1035F0008073203CE36184F30988FFF7B1FC10B1CC +:10360000044BA36110BD044BFBE783F31188F9E77A +:1036100000ED00E06F05000872050008704700002B +:10362000FEE700000A4B0B480B4A90420BD30B4BB2 +:10363000C11EDA1C121A22F003028B4238BF00228C +:103640000021FDF7BFBE53F8041B40F8041BECE754 +:10365000043C0008A0250020A0250020A025002073 +:103660007047000000F030B808B500F063F9FFF7CC +:10367000A5FCBDE80840FFF759BF000070470000F7 +:103680004FF0FF310E4B1A6919611A6900221A6155 +:103690001869D868D960D968DA60DA68DA6942F0FE +:1036A0008052DA61DA69DA6942F00062DA61054A69 +:1036B000DB69136843F48073136000F01BB900BF2B +:1036C0000010024000700040194B1A6842F00102DD +:1036D0001A601A689007FCD51A6802F0F9021A609D +:1036E00000225A605A6812F00C0FFBD11A6842F49B +:1036F00080321A601A689103FCD55A6842F4E812C5 +:103700005A601A6842F080721A601A689201FCD5F9 +:103710001221084A5A60084A11605A6842F00202AF +:103720005A605A6802F00C02082AFAD1704700BFAA +:103730000010024000641D0000200240084A08B545 +:10374000516913680B4003F00103536123B1054A2B +:1037500013680BB150689847BDE80840FFF73CBFBD +:103760000004014020250020084A08B5516913686B +:103770000B4003F00203536123B1054A93680BB178 +:10378000D0689847BDE80840FFF726BF0004014015 +:1037900020250020084A08B5516913680B4003F042 +:1037A0000403536123B1054A13690BB1506998476B +:1037B000BDE80840FFF710BF0004014020250020AD +:1037C000084A08B5516913680B4003F008035361B8 +:1037D00023B1054A93690BB1D0699847BDE8084009 +:1037E000FFF7FABE0004014020250020084A08B572 +:1037F000516913680B4003F01003536123B1054A6C +:10380000136A0BB1506A9847BDE80840FFF7E4BE61 +:103810000004014020250020174B10B55A691C6890 +:10382000144004F478725A61A30604D5134A936ACB +:103830000BB1D06A9847600604D5104A136B0BB1E0 +:10384000506B9847210604D50C4A936B0BB1D06B93 +:103850009847E20504D5094A136C0BB1506C9847A0 +:10386000A30504D5054A936C0BB1D06C9847BDE80D +:103870001040FFF7B1BE00BF00040140202500202A +:103880001A4B10B55A691C68144004F47C425A6102 +:10389000620504D5164A136D0BB1506D9847230588 +:1038A00004D5134A936D0BB1D06D9847E00404D54D +:1038B0000F4A136E0BB1506E9847A10404D50C4A01 +:1038C000936E0BB1D06E9847620404D5084A136F0B +:1038D0000BB1506F9847230404D5054A936F0BB181 +:1038E000D06F9847BDE81040FFF776BE0004014056 +:1038F00020250020062108B50846FFF747F80621D5 +:103900000720FFF743F806210820FFF73FF80621BC +:103910000920FFF73BF806210A20FFF737F80621B8 +:103920001720FFF733F8BDE8084006212820FFF7ED +:103930002DB8000008B5FFF7A3FE064800F00EF80A +:10394000FFF742F8FFF746FAFFF798FEBDE8084098 +:1039500000F002B8983B000800F042B80023194676 +:103960001C4A0133102BC2E9001102F10802F8D100 +:10397000194B9A6942F07D029A619B690268174B64 +:10398000DA6082685A6042681A60C26803F5806330 +:10399000DA6042695A6002691A608269C3F80C24CD +:1039A000026AC3F80424C269C3F80024426AC3F857 +:1039B0000C28C26AC3F80428826AC3F80028026B84 +:1039C000C3F80C2C826BC3F8042C426BC3F8002C98 +:1039D000704700BF20250020001002400008014071 +:1039E0004FF0E023044A08215A6100229A6107221D +:1039F0000B201A61FEF7E0BF3F19010008B5202334 +:103A000083F31188FFF7FAFA002383F3118808BDC6 +:103A100008B5FFF7F3FFBDE80840FFF7DDBD000084 +:103A200010B501390244904201D1002005E003782D +:103A300011F8014FA34201D0181B10BD0130F2E76D +:103A40002DE9F0419BB10446C91A1778014403F1EE +:103A5000FF3C8C42204601D9002008E00578013463 +:103A6000BD42F6D10CEB0405D618A54201D1BDE844 +:103A7000F08115F8018D16F801EDF045F5D0E8E775 +:103A8000034611F8012B03F8012B002AF9D17047E6 +:103A90006F72672E6172647570696C6F742E663117 +:103AA00030335F6169727370656564004E6F2061C9 +:103AB0007070207369670A00426164206677206C29 +:103AC000656E6774682025750A0042616420626F24 +:103AD0006172645F69642025752073686F756C641A +:103AE0002062652025750A004261642066772064A3 +:103AF000657363726970746F72206C656E67746849 +:103B00002025750A00426164206170702043524391 +:103B1000203078253038783A3078253038782030A1 +:103B200078253038783A3078253038780A00476F71 +:103B30006F64206669726D776172650A0040A2E465 +:103B4000F164689106000000000000009D2D00084F +:103B5000892D0008C52D0008B12D0008BD2D0008D5 +:103B6000A92D0008952D0008812D0008D12D0008F1 +:103B70006D61696E0000000069646C650000000002 +:103B8000783B000848240020F824002001000000B1 +:103B9000B92F0008000000000C1E0000447B4144C7 +:103BA000B45749440100000042444444444444445E +:103BB00000000000444444444444444400000000E5 +:103BC00044444444444444440000000044444444C5 +:103BD00044444444BCC5FF7F0100000000000000D5 +:103BE000E803000000000000009C0100000000004D +:103BF000640000000000000040420F00FE2A0100A7 +:043C0000D2040000EA :00000001FF diff --git a/Tools/bootloaders/f103-GPS_bl.bin b/Tools/bootloaders/f103-GPS_bl.bin index ffc54ea50d5..d3e5b71c81a 100755 Binary files a/Tools/bootloaders/f103-GPS_bl.bin and b/Tools/bootloaders/f103-GPS_bl.bin differ diff --git a/Tools/bootloaders/f103-GPS_bl.hex b/Tools/bootloaders/f103-GPS_bl.hex index 25985173932..33ff7afe6a4 100644 --- a/Tools/bootloaders/f103-GPS_bl.hex +++ b/Tools/bootloaders/f103-GPS_bl.hex @@ -1,1061 +1,963 @@ :020000040800F2 -:1000000000090020A10400081514000819140008B4 -:10001000551400081914000835140008A30400083A -:10002000A3040008A3040008A3040008C5360008C0 -:10003000A3040008A3040008A3040008593A000818 -:10004000A3040008A3040008A3040008A3040008F4 -:10005000A3040008A3040008393800086538000824 -:1000600091380008BD380008E9380008A3040008EA -:10007000A3040008A3040008A3040008A3040008C4 -:10008000A3040008A3040008A304000869250008CD -:10009000D5250008292600087D2600081539000806 -:1000A000A3040008A3040008A3040008A304000894 -:1000B000A3040008A3040008A3040008A304000884 -:1000C000A3040008A3040008A3040008A304000874 -:1000D000A3040008A12A0008B52A0008A304000808 -:1000E0007D390008A3040008A3040008A304000845 -:1000F000A3040008A3040008A3040008A304000844 -:10010000A3040008A3040008A3040008A304000833 -:10011000A3040008A3040008A3040008A304000823 -:10012000A3040008A3040008A3040008A304000813 -:10013000A3040008A3040008A3040008A304000803 -:10014000A3040008A3040008A3040008A3040008F3 -:10015000A3040008A3040008A3040008A3040008E3 -:10016000D0400B1CD1409C46203AD3401843524209 -:1001700063469340184370479140031C90409C464F -:10018000203A9340194352426346D3401943704783 -:1001900053B94AB9002908BF00281CBF4FF0FF31EE -:1001A0004FF0FF3000F07AB9ADF1080C6DE904CEE4 -:1001B00000F006F8DDF804E0DDE9022304B0704742 -:1001C0002DE9F0478C460E460446089D002B50D181 -:1001D0008A4217466CD9B2FA82FEBEF1000F0BD0EC -:1001E000CEF1200C01FA0EF620FA0CFC02FA0EF702 -:1001F0004CEA060C00FA0EF43A0CBCFBF2F9BBB266 -:1002000002FB19CC09FB03FA4FEA144848EA0C46F2 -:10021000B2450AD9F61909F1FF3180F02581B245BE -:1002200040F22281A9F102093E44A6EB0A06B6FB80 -:10023000F2F002FB106600FB03F3A4B244EA0644AA -:10024000A34209D9E41900F1FF3280F00B81A342E7 -:1002500040F2088102383C440021E41A40EA094097 -:10026000002D62D0002324FA0EF42C606B60BDE8F0 -:10027000F0878B4207D9002D55D0002185E8410039 -:100280000846BDE8F087B3FA83F1002940F08F807B -:10029000B34202D3824200F2FC80841A66EB03066A -:1002A0000120B446002D40D085E81010BDE8F0874D -:1002B00012B90127B7FBF2F7B7FA87FEBEF1000FBC -:1002C00035D10121F61B4FEA174C1FFA87F8B6FB10 -:1002D000FCF20CFB126608FB02F0230C43EA064614 -:1002E000B04207D9F61902F1FF3302D2B04200F250 -:1002F000D2801A46361AB6FBFCF00CFB106608FBDF -:1003000000F8A3B243EA0644A04507D9E41900F176 -:10031000FF3302D2A04500F2B9801846A4EB0804CE -:1003200040EA02409CE729462846BDE8F08707FAE4 -:100330000EF7CEF1200326FA03F24FEA174CB2FB78 -:10034000FCF11FFA87F80CFB112206FA0EF620FAD0 -:1003500003F301FB08F933431E0C46EA0246B1459C -:1003600000FA0EF409D9F61901F1FF3280F08C8001 -:10037000B14540F2898002393E44A6EB0906B6FB3E -:10038000FCF00CFB106200FB08F99EB246EA024644 -:10039000B14507D9F61900F1FF3371D2B1456FD9D4 -:1003A00002383E44A6EB090640EA01418FE7C1F15D -:1003B000200722FA07F88B4048EA030326FA07F4DD -:1003C0004FEA134EB4FBFEF91FFA83FC0EFB1944EF -:1003D0008E4020FA07F809FB0CFA48EA06084FEAB3 -:1003E000184646EA0444A24502FA01F200FA01F670 -:1003F00008D9E41809F1FF3044D2A24542D9A9F145 -:1004000002091C44A4EB0A04B4FBFEF00EFB1044EA -:1004100000FB0CFC1FFA88F848EA0444A44507D9FD -:10042000E41800F1FF3E29D2A44527D902381C4424 -:1004300040EA0940A0FB0289A4EB0C0CCC45C24663 -:10044000CE4615D312D055B1B6EB0A036CEB0E06AF -:1004500006FA07F7CB401F43CE402F606E600021A5 -:10046000BDE8F0871046F7E68946DEE64645EAD263 -:10047000B8EB020A69EB030E0138E4E77046D7E7F0 -:1004800018468FE78146BDE7114676E702383C44BF -:1004900044E7084606E7023A3E442BE7704700BFB0 -:1004A00002E000F000F8FEE772B6274880F3088803 -:1004B000264880F3098826484EF60851CEF20001FE -:1004C0000860022080F31488BFF36F8F03F02AF9CD -:1004D00003F046F94FF055301E491B4A91423CBF8C -:1004E00041F8040BFAE71C49184A91423CBF41F815 -:1004F000040BFAE719491A4A1A4B9A423EBF51F8BF -:10050000040B42F8040BF8E700201749174A914200 -:100510003CBF41F8040BFAE703F008F903F022F9B5 -:10052000134C144DAC4203DA54F8041B8847F9E726 -:1005300000F03AF8104C114DAC4203DA54F8041BA9 -:100540008847F9E703F0F0B8000900200011002007 -:10055000000000080001002000090020B841000848 -:1005600000110020741100207811002000260020C6 -:1005700060010008600100086001000860010008D7 -:100580002DE9F04FC1F80CD0C3689D46BDE8F08F4F -:10059000002383F311882846A047002002F07EFE46 -:1005A00002F0A8FD00DFFEE76FF01702364B2DE9E1 -:1005B000F0411A70032200245A7001266FF0630282 -:1005C0009C70DC701C715C719C71DC711C725A72C5 -:1005D0009E72DC7203F020F8804603F06DF8054649 -:1005E000D0BB2A4B984539D03344984537D0284B57 -:1005F00028F0FF029A4234D15FFA88F000F04EFAF8 -:100600002E4642F2107400F077FC00F04DFA0746D7 -:1006100058B364BB374635B11E4B984503D0002410 -:1006200003F042F82746002003F000F81A4B9B68BD -:1006300013F040031ED00FB100F030F800F07EFC44 -:1006400000F018FE00F014FF0546ACB900F0CCFC39 -:10065000012002F029FEF8E70646D4E706462C46BC -:10066000D1E706464FF47A74CDE70446D3E74FF45A -:100670007A74D0E71C46E1E700F0FAFE401BA04286 -:10068000E4D900F00BF8DDE778110020010007B095 -:10069000000008B0263A09B0000C014010B51C4B10 -:1006A0001C4953F8042F013200D110BD8B42F8D100 -:1006B000194C1A4B22689A4228D9194B9B6803F1AE -:1006C000006303F5C8439A4220D202F0C1FF02F052 -:1006D000D3FF002000F0E8FD0220124B187000F05C -:1006E0001FFE114BDA690022DA61D96999699A61B2 -:1006F0009B6972B60D4B0E4A202113601B6822685D -:1007000081F311889D4683F30888104710BD00BF10 -:10071000FC6300081C64000804640008FF63000810 -:1007200078110020841100200010024000640008AD -:1007300008ED00E049F2690008490B689AB21B0C09 -:1007400000FB02330B6044F25061054A136898B213 -:100750001B0C01FB0030106080B270470C110020B0 -:100760000811002010B504460021102200F0F4FD0D -:10077000034B03CB206061601868A06010BD00BF10 -:10078000E8F7FF1FF0B5BBB000F072FE1D4CA36888 -:10079000C31AF92B30D906AD2346A06028220021C8 -:1007A000284601F0F3FB04F10E0000F0CDFD00231C -:1007B000C6B2591D5F1CDBB2B3424FEAC10107DA72 -:1007C0000E3323440822284601F0E0FB3B46F0E7C5 -:1007D00001230393082302930B4B207B01933023C7 -:1007E000C1F3CF0105910093014604A3D3E900238F -:1007F0000495064801F09AF93BB0F0BD78F6339FB6 -:1008000093CACD8DC8210020D5210020A021002031 -:1008100070B50D4614461E4601F02EF950B9022E51 -:100820000ED1012C0CD112A3D3E90023C5E900237A -:10083000012070BD052C14D003D8012C09D0002054 -:1008400070BD282C09D0302CF9D10BA3D3E900239B -:10085000ECE70BA3D3E90023E8E70BA3D3E90023DC -:10086000E4E70BA3D3E90023E0E700BFAFF3008088 -:10087000401DA12026812A0B78F6339F93CACD8D87 -:100880009E6AC421818A46EE26417272DF25D7B75F -:10089000F017304A39059E5638B50D4604460346D2 -:1008A00020222846002101F071FB22792346032AE9 -:1008B00028BF0322284603F8042F2021022201F03A -:1008C00065FB62792346072A28BF0722284603F8DA -:1008D000052F2221032201F059FBA2792346072A82 -:1008E00028BF0722284603F8062F2521032201F0FE -:1008F0004DFB284604F108031022282101F046FB95 -:10090000382038BD2DE9F04FADF5017D21AE0EAD9B -:1009100040F2791280460F463046002100F01CFD5F -:1009200048220021284600F017FD00F0A1FD4FF4F9 -:100930007A72B0FBF2F0574B0DF15A09186093E848 -:10094000070001232B74002385E807000DF15A00EE -:100950006B74FFF707FF032385F82030E82385F841 -:10096000213007AB18464C4903F0E0F81B222864FD -:100970003146284685F83C20FFF78EFF12AB04462F -:1009800001460822304601F001FB08220DF149031F -:10099000A118304601F0FAFA0DF14A03082204F1D9 -:1009A0001001304601F0F2FA13AB202204F11801D5 -:1009B000304601F0EBFA14AB402204F13801304626 -:1009C00001F0E4FA16AB082204F17801304601F098 -:1009D000DDFA0DF15903082204F18001304601F0DF -:1009E000D5FA04F1880A04F5847B4B465146082267 -:1009F00030460AF1080A01F0C9FAD34509F10109A4 -:100A0000F3D11BAB08225946304601F0BFFA4FF034 -:100A1000000904F5887495F834304B4510D84FF030 -:100A2000000995F83C304B4515D92B6C21464B44B9 -:100A30000822304601F0AAFA083409F10109F0E76A -:100A4000AB6B21464B440822304601F09FFA083434 -:100A500009F10109DFE7E31DC3F3CF03F97E059335 -:100A6000002304960393BB7E193702930123019759 -:100A70000093404605A3D3E9002301F057F80DF594 -:100A8000017DBDE8F08F00BFAFF300809E6AC421F6 -:100A9000818A46EE88110020043D0008014B187041 -:100AA000704700BF94110020F0B5334B85B01C7B1C -:100AB00034B10E22314B1A810024204605B0F0BD1E -:100AC0002F4A02AB1068516803C308232D490DEB70 -:100AD00003022D4803F00CF8054630B90A22274BD3 -:100AE0002A481A8100F08CFCE6E70169B1F5CE3F97 -:100AF00006D90B22214B26481A8100F081FCDCE745 -:100B0000438BB3F57A7F09D00C211C4A214811810F -:100B10004FF47A72194600F073FCCEE71E4A024485 -:100B200002F11003994204D21022144B1B481A817F -:100B3000E3E710398E1A2046134900F09DFC074662 -:100B4000324605F11801204600F096FCAB689F4242 -:100B500002D1EB6898420AD00D22084B1A8100900E -:100B60003B46EA68A9680E4800F04AFCA4E70D4835 -:100B700000F046FC0124A0E7C821002088110020D5 -:100B8000D43B0008DC9B010000640008DC3B00084B -:100B9000E83B0008FA3B0008089CFFF7183C0008F7 -:100BA000353C00085E3C00082DE9F04FADB006AFC3 -:100BB00080460C4600F060FF054600286AD1237E7F -:100BC000022B18D1E38A012B15D100F051FC81468C -:100BD000FFF7B0FD4FF4C873B0FBF3F202FB130054 -:100BE000BB4E80B209F51679E37E484430608BB97C -:100BF0000022B84B1A709C37BD46BDE8F08F3B1DF4 -:100C00001D440095002308224FEAC901204601F047 -:100C100021F84D46A38A5FFA85F9013BAB420BD917 -:100C200005F10109B9F1110FE9D140F23911AA4BCF -:100C3000AA4AAB4802F02EFF07F11400FFF792FD1D -:100C40002A4607F11401381D02F042FF034600282E -:100C5000CED1B9F1100F07D09E4B83F800903368C6 -:100C6000A3F516733360C6E707F1980202F8950DF5 -:100C7000014600922046072200F0ECFFF9787F2918 -:100C800004DD984B954A4FF4A871D2E7404600F036 -:100C9000D7FEB0E7E38A052B00F0068106D8012BCA -:100CA000A9D121464046FFF72DFEA4E7282B3DD0D1 -:100CB000302BA0D1637E8C4D01336A7BDBB2934233 -:100CC000E94640F0EF80E27E2B7B9A4240F0EA80DA -:100CD000002607F1980323F8846D00931022012366 -:100CE0003146204600F0B6FFB4F81480A8F102089F -:100CF0001FFA88F808F1030323F003030A3323F0F3 -:100D00000703ADEB030D0DF1180A33469BB2B11C7E -:100D100098454FEAC10106F101066CDD534400938A -:100D200008220023204600F095FFEEE7A38A013B4E -:100D30009BB2C92B3FF65FAF6B4E357B4DBB06F1C7 -:100D40000C03009308222B462946204600F082FF20 -:100D5000A38A05F10109013BEDB29D424FEAC901A9 -:100D600009DA0E353544009500230822204600F0AC -:100D700071FF4D46ECE700230022C6E90023002363 -:100D8000B36086F8D730C6F8D830337B0BB9E37E32 -:100D90003373002507F114063B1D0822294630460F -:100DA0007D60BD60FD6001F0F1F83B7A05F101095D -:100DB000AB424FEAC90107D9FB6808222B443046F1 -:100DC00001F0E4F84D46F0E70023C1F3CF01E07EE7 -:100DD000059104960393A37E1934029328230146B8 -:100DE0000093019438A3D3E90023404600F09EFE0F -:100DF000FFF7C8FCFFE695F8D70000F05FFAD5F8DA -:100E0000D83006461BB995F8D70000F067FAD5F838 -:100E1000D83043449E4204D295F8D700013000F008 -:100E20005DFA00244FEA980BA0B2584504F1010482 -:100E300008DA2B6880000AEB00010122184400F058 -:100E400093FAF1E7D5F8D840D5E9002312EB080270 -:100E500043F10003444495F8D700C5E90023C5F8E1 -:100E6000D84000F02BFA844209D395F8D7300133EB -:100E700085F8D730D5F8D8309E1BC5F8D860B8F1C2 -:100E8000FF0F08DC00232B7300F03AFAFFF70CFE8B -:100E900008B1FFF703FC2B68144A9B0A0133138146 -:100EA0000023AB60CD46A6E6BFF34F8F1049114B30 -:100EB000CA6802F4E0621343CB60BFF34F8F00BFF8 -:100EC000FDE700BFAFF3008026417272DF25D7B780 -:100ED0009C21002099210020703C0008203D000842 -:100EE000C93C0008EB3C0008C82100208811002004 -:100EF00000ED00E00400FA0508B54FF000530B4A7E -:100F0000196891420AD1597D094A0A4811701B7D1E -:100F1000C922037308490E3000F00CFABDE80840FE -:100F2000E02200214FF0005000F016BA9AAD44C5FF -:100F300094110020C821002016000020022330B5A3 -:100F40001F4C85B0637104230025ADF808300123E0 -:100F50000722ADF80C501B498DF80C308DF80B3082 -:100F6000194B1A484B608DF80A2001F0FFFD184B11 -:100F7000019500931749184B4FF48052174800F021 -:100F800029FD174B2546197811B1144800F058FD7A -:100F900000F06EFA0446FFF7CDFB4FF4C873B0FBC8 -:100FA000F3F202FB130304F516749BB21C440D4BC1 -:100FB0001C6002F081FB08B10F232B8105B030BD0E -:100FC000881100200011002003000600E02200200C -:100FD0001108000898110020A90B0008A02100208A -:100FE000941100209C2100202DE9F04F96A7D7E90D -:100FF00000670FF25C29D9E900898F4C93B0DFF8C4 -:1010000058B2DFF858A2204600F0DCFD0CAD079086 -:1010100098B310220021284600F09EF94FF00002FC -:10102000079B197B61F3030219468DF8302051F8B4 -:10103000040F0EAA496803C21B680D9A584663F351 -:101040001C029DF830300D9243F020038DF83030B3 -:1010500000232A46194601F099FD079030B9204631 -:1010600000F0B4FD079B8AF80030CCE79AF8003016 -:10107000072B40DC01338AF8003018220021284673 -:1010800000F06AF9DFF8D0B1DFF8D4A100232A46D6 -:101090001946584601F0A2FD014680BB102208A85F -:1010A00000F05AF9DAF80C3083F01003CAF80C306B -:1010B00000F0E0F90DF1240E0B4612A9024611E9E9 -:1010C00003008EE803009DF83410C1F30300890685 -:1010D00049BF0E99BDF83810C1F31C0141F0004121 -:1010E00058BFC1F30A018DF82C000891204608A9C9 -:1010F00000F0B2FFCAE7204600F068FDBDE72046D9 -:1011000000F0BAFC824600284AD100F0B1F9DFF8BD -:1011100054B1DBF80030984242D300F0A9F90790AF -:10112000FFF708FB4FF4C873B0FBF3F101FB1300AA -:10113000079A80B202F516721044CBF80000DFF86F -:1011400028B18DF820A09BF8001011B901238DF86B -:10115000203028460791FFF705FB07990DF1210084 -:10116000C1F1100A5FFA8AFABAF1060F28BF4FF0F0 -:10117000060A2944524600F0DDF80AF101030493FF -:1011800008AB0393182302932C4B3246019301239F -:10119000204600933B4600F071FC00238BF80030A2 -:1011A00000F066F9264ADFF8C4A01368C31AB3F545 -:1011B0007A7F32D3106000F05DF902460B4620467C -:1011C00000F00AFD204600F057FC30B39AF80C30CE -:1011D000DFF89CB0002B14BF032302238BF80530EB -:1011E00000F046F94FF47A73B0FBF3F02946CBF8E0 -:1011F00000005846FFF750FB18230293114B0730AD -:10120000019340F25513C0F3CF000490009303956F -:1012100042464B46204600F031FC9AF80C300BB1A8 -:10122000FFF7B0FA9AF80C30002B7FF4E8AE13B059 -:10123000BDE8F08FAFF30080A021002098210020AE -:10124000A8220020AC220020401DA12026812A0BCC -:10125000F1C6A7C1D068080FE0220020AD2200200F -:10126000000801409C21002099210020C821002075 -:101270008811002070B502F0CDF80025084C094E09 -:10128000207030682378834208D902F0BFF83368B1 -:1012900005440133B5F5C84F3360F2D370BD00BFCC -:1012A000DC220020B022002002F04CB900F10060E6 -:1012B000920000F5C84002F0F1B80000054B1A6832 -:1012C000054B1B789B1A834202D9104402F09EB84A -:1012D00000207047B0220020DC22002038B50446F0 -:1012E000064D2868204402F097F828B92868204461 -:1012F000BDE8384002F0A2B838BD00BFB0220020DF -:10130000064991F8243033B100230822086A81F895 -:101310002430FFF7CBBF0120704700BFB42200206C -:10132000022802BF4FF48012014B1A61704700BFC0 -:1013300000080140002310B5934203D0CC5CC45494 -:101340000133F9E710BD000002460346981A13F96D -:10135000011B0029FAD1704703460244934202D090 -:1013600003F8011BFAE770472DE9F047234C0546C7 -:1013700094F824308846174683BB2E46DFF87C90CD -:10138000C7B394F824302BB92022FF2148462662A7 -:10139000FFF7E2FF94F824004146C0F10805BD4282 -:1013A00028BF3D465FFA85FAAD002A4604EB80006F -:1013B000FFF7C0FF94F82430A7EB0A079A445FFABE -:1013C0008AFABAF1080F2E44A844FFB284F824A088 -:1013D000D6D1FFF795FF0028D2D108E0266A06EBA8 -:1013E0008306B042CAD0FFF78BFF0028C5D100208A -:1013F000BDE8F0870120BDE8F08700BFB4220020DF -:101400000FB4002004B070470FB44FF0FF3004B0A9 -:1014100070470000FEE70000EFF30983EFF3058358 -:10142000034B9A6B9A6A9A6A9A6A9A6A9B6AFEE76F -:1014300000ED00E0EFF30983EFF30583044B9A6BB3 -:101440009A6A9A6A9A6A9A6A9A6A9B6AFEE700BFDF -:1014500000ED00E0EFF30983EFF30583034B5A6BD4 -:101460009A6A9A6A9A6A9A6A9B6AFEE700ED00E0B5 -:1014700002F0A0B802F07AB830B5084D0A449142A3 -:101480000BD0092411F8013B5840013CF7D040F340 -:1014900000032B4083EA5000F7E730BD2083B8ED0E -:1014A0000246006848B1036811891360D38801338C -:1014B0009BB29942D38038BF1381704770B5044600 -:1014C0000D4688B0202200216846FFF745FF2046E0 -:1014D0000495FFF7E5FF054658B16B46044608AE94 -:1014E0001A4603CAB24220606160134604F1080440 -:1014F000F6D1284608B070BD2DE9F04130B940F270 -:10150000C531264B264A274802F0C4FA0B7C23B982 -:10151000254B234A40F2C631F5E7C66986B9C16159 -:10152000BDE8F081002B29DA930CAB4229D1B442FB -:1015300001D10C60F3E7C8F800100C60BDE8F08141 -:101540004B68B04623F06047BD0C15EA230538BF51 -:101550003D4634464FEAD37EC3F3807C6368BEEBDE -:10156000D37F23F06042DDD1974203D1C3F3807370 -:101570009C450AD1974205E01C46EFE7AA4206D0F7 -:1015800013469D422CBF00230123002BCFD123689B -:10159000A046002BF0D12160BDE8F081F43F0008A7 -:1015A000E83D0008AC400008CD40000808B5034AFB -:1015B000034B40F25E31034802F06CFAC43D000870 -:1015C0006C400008AC40000808B503680B60C38895 -:1015D000016033B9044B054A4FF4C761044802F077 -:1015E00059FA013BC38008BD3C400008383E000862 -:1015F000AC40000870B50C4600F10C05616831B9CB -:10160000E38A002061F30903E382002170BD0E68C4 -:101610002846FFF7D9FF6660F0E7000008B542688A -:1016200032B10B4B0B4A40F22F410B4802F032FA19 -:10163000C37DC3F38401013161F38603C375C38A9B -:1016400062F30903C3821B0A62F3C713C37508BDA3 -:1016500088400008F43D0008AC4000082DE9F04740 -:10166000089E32B91F4B204A40F239511F4802F000 -:1016700011FA4FF47F4901F007054FEAD6082A44D2 -:1016800006F0070600EBD100954201D1BDE8F087D6 -:1016900005F0070E06F0070AD645774638BF5746CD -:1016A000511BC7F108078F4228BF0F46EC08045DA5 -:1016B00008EBD60113F801C004FA0EF429FA07FE6C -:1016C00024FA0AF45FFA8EFE8CEA04044EFA0AFE4B -:1016D00004EA0E048CEA040C03F801C03D443E44C5 -:1016E000D2E700BF084000080C3E0008AC400008EC -:1016F0002DE9F04106460F4600254FF6FF7441F2F2 -:1017000021082A4630463946FEF72AFD0823C0B292 -:1017100084EA002414F4004F4FEA4404A4B203F115 -:10172000FF3318BF84EA080413F0FF03F2D1083531 -:10173000402DE6D12046BDE8F081000010B541F211 -:1017400021040A44914200D110BD11F8013B80EA06 -:101750000320082310F4004F4FEA400080B203F149 -:10176000FF3318BF604013F0FF03F3D1EAE7000036 -:101770002DE9F04F85B08A468DE80C00BDF83C405D -:10178000814630B940F26E31484B494A494802F02F -:1017900081F911F0604F04D0474B454A40F26F3158 -:1017A000F4E7009B002B7ED024B10E9B002B7AD057 -:1017B000072C28D809F10C00FFF772FE054628B95E -:1017C0006FF00205284605B0BDE8F08F1422002115 -:1017D000FFF7C2FD22460E9905F10800FFF7AAFDAA -:1017E000631C2B74009B2C441B78294603F01F03B9 -:1017F00063F03F0323724AF000436B604846FFF7F3 -:101800007BFE0125DEE74FF000084FF0800B4646D7 -:101810004546019B1B0A029300F10C0303930398B6 -:10182000FFF73EFE07460028CAD014220021FFF72A -:1018300093FDB6BB02229DF804303B729DF8083040 -:101840007B720E9B711E1944B4420AD9B81801323A -:1018500011F801EFD2B20136072A80F808E0B6B2DB -:10186000F2D1B44208BF4FF0400B009BB818197872 -:10187000013201F01F0141EA48114BEA01030372F2 -:101880004AF000437B603A7439464846FFF734FE1D -:101890000135B4422DB288F001084FF0000BBED1E3 -:1018A00090E70022CDE76FF001058BE7F43F0008D9 -:1018B000D83D0008AC400008184000082DE9F0476A -:1018C0001E46CB8A9146C3F30902062A80460F467C -:1018D00019D013460021B0B28DB25A1992B2052A1E -:1018E00009D9A84210D8FA8A034463F30902FA829C -:1018F0000120BDE8F087A842F3D919F801403A4425 -:1019000094760131E8E70025FB8A7C68C3F309007F -:101910001C23821FB2FBF3FA03FB1A2A1FFA8AF276 -:101920007CB301212368002B39D1B31F03441C2051 -:10193000B3FBF0F301339BB299420CD2BAF1000F22 -:1019400009D14046FFF7ACFD08B1C0F800A0206007 -:1019500008B3044600224FF0000AB6B2B54230D2B6 -:101960001346691E4944E018013311F801EF9BB298 -:1019700001351C2B80F804E0ADB214D0AE42F2D891 -:10198000ECE74046FFF78CFD044608B100230360F6 -:101990007C60002CDED16FF00200BDE8F0870131E1 -:1019A00089B21C46BEE7AE42D8D94046FFF778FD63 -:1019B00008B1C0F800A020600028ECD00446002246 -:1019C000CCE7FB8AC3F30902164466F30903FB82E2 -:1019D0008EE70000F8B50E4615461F46044628B9A6 -:1019E000144B154A4F21154802F054F824220021C7 -:1019F000FFF7B2FC069B6A096360079B0020236225 -:101A00004FF6FF739A4228BF1A46A7602070A06164 -:101A1000E06197B204F10C05824205D100232B60EE -:101A200027826382A382F8BD2E60013035462036BE -:101A3000F2E700BFF03F0008643D0008AC4000083A -:101A400008B528B97321084B084A094802F022F862 -:101A5000037823B94BB2002B01DD017008BD054BA3 -:101A6000024A7D21F1E700BFF43F0008703D000805 -:101A7000AC400008383F0008007870472DE9F74374 -:101A80000D9E074619461046BDF828900B9D9DF8FF -:101A90003040BDF8388016B9B8F1000F43D11F2C83 -:101AA00041D83B78D3B9B8F1070F39D839F00303DF -:101AB00039D1424631464FF6FF70FFF73FFE4FEAFD -:101AC000092920F0010009F44079400449EA04643E -:101AD000400C44EA40244FF6FF730DE043EA09232B -:101AE000B8F1070F43EA0464F5D9FFF701FE424657 -:101AF0003146FFF723FE03468DE840012A46214682 -:101B00003846FFF735FE0DB9FFF750FD2B7801334E -:101B1000DBB21F2B88BF00232B7003B0BDE8F0831E -:101B20006FF00300F9E76FF00100F6E72DE9F743E6 -:101B30000E9F81460B9D9DF830009DF83480BDF8C6 -:101B40003C6007B9C6BB1F2836D899F800E0BEF143 -:101B5000000F34D00C0244F080049DF8281044EAB1 -:101B6000C83444EA014444EA0E04072E44EA0064FF -:101B700015D919461046FFF7BBFD32463946FFF727 -:101B8000DDFD0346019600972A4621464846FFF7A9 -:101B9000EFFDB8F1010F0CD125B9FFF707FD4FF6A6 -:101BA000FF73EFE72B780133DBB21F2B88BF0023D5 -:101BB0002B7003B0BDE8F0836FF00100F9E76FF020 -:101BC0000300F6E7C06900B104307047C1690C300A -:101BD0000B680361FFF7F8BC2DE9F84FD0F818A0A7 -:101BE000054616461F4654464FF00009DFF8608050 -:101BF00000F10C0B0CB9BDE8F88FD4E90223B21A3E -:101C000067EB0303994508BF90451FD2AB69214696 -:101C10009C4228460DD1FFF7EDFCAB6921461B68BD -:101C20005846AB61FFF7D0FCAC692346A2461C4680 -:101C3000E0E7FFF7DFFC23682146CAF8003058468A -:101C4000FFF7C2FC5446DAF80030EFE72368EDE70F -:101C500080841E002DE9F04F8BB00D46144607938B -:101C6000DDF850908246002800F06481B9F1000F41 -:101C700000F06081531E3F2B00F25C81012A03D1EA -:101C8000079B002B40F056810023BAF8146008939C -:101C9000F600B542099380F053812B199E420AD277 -:101CA000761B16F0FF0607D140F26751AA4BAB4AEC -:101CB000AB4801F0EFFE2646DAF80C3023B9DAF82B -:101CC0001030002B00F0A5802F2D31D8C5F1300841 -:101CD00046454FF0000334BFB0465FFA88F80093E2 -:101CE000294608AB4246DAF80800FFF7B7FCA6EB36 -:101CF00008074544FFB24FF0300BBAF8143003F137 -:101D00000053063BDB000293DAF80C300593059B89 -:101D1000002B51D087B9DAF81000002861D0002FCD -:101D20005FD0AB4550D98F4B8C4A40F2A651BFE7EC -:101D300037464FF00008DEE7029B23B98A4B874AFB -:101D40004FF4B161B4E7029BE02B28BFE023069378 -:101D50005B44AB4204931DD95B1B9F4226BFDBB2A1 -:101D600003930397AB4504D97E4B7C4A40F29151D3 -:101D70009EE70598CDF8008008ABA5EB0B01039A10 -:101D80000430FFF76BFC039B9844FF1A1D445FFA75 -:101D900088F8FFB2049B9B4504D3744B6F4A40F212 -:101DA0009B5185E7029B069ADDF810B09B1A0293BF -:101DB000059B1B680593AAE7029BBB42ABD26C4B09 -:101DC000664A40F2A15173E7CDF800803A46A5EB90 -:101DD0000B0108ABB8443D44FFF740FC00275FFA15 -:101DE00088F8BAF81430B5EBC30F04D9614B5B4ADD -:101DF00040F2B1515CE7B8F1400F04D95E4B574A4D -:101E000040F2B25154E767B15C4B544A40F2B351CF -:101E10004EE70093324608AB2946DAF80800FFF790 -:101E20001DFC731E3F2B35B201D8A64204DD544B76 -:101E3000544A40F235213BE760070AD00AAB03EB76 -:101E4000D40111F8083C624202F00702134101F884 -:101E5000083C082C21D9102C21D9202C8CBF082318 -:101E60000423079A002A6DD0B4EBC30F6CD0082C62 -:101E700004F1FF3215D89DF8203023FA02F2D10781 -:101E800006D54FF0FF3202FA04F423438DF82030D8 -:101E90009DF8203089F800304EE00123E1E702236D -:101EA000DFE7102C11D8BDF8203023FA02F2D20758 -:101EB00006D54FF0FF3202FA04F42343ADF8203088 -:101EC000BDF82030A9F8003036E0202C0ED8089953 -:101ED00021FA02F2D30705D54FF0FF3303FA04F4D9 -:101EE0000C430894089BC9F8003025E0402C1CD016 -:101EF000DDE9086730463946FEF732F9002100F087 -:101F0000010050EA01030BD0224601200021FEF718 -:101F100033F9404261EB410106430F43CDE90867C5 -:101F2000DDE90823C9E9002306E0174B154A4FF401 -:101F30002071BDE66FF0010528460BB0BDE8F08FBB -:101F40001D46F9E7012CA3D0082CA1D9102CB7D934 -:101F5000202CE5D8C6E700BF443E00081C3E000820 -:101F6000AC400008663E0008533E00088B3E000867 -:101F7000B33E0008DA3E0008083F0008203F000892 -:101F80003A3F00089C3D0008383F000830B585B056 -:101F900030B940F2B121234B234A244801F07AFDA5 -:101FA00023B9234B204A40F2B221F6E7402A04D954 -:101FB000204B1D4A40F2B621EFE722B91D4B1A4AC9 -:101FC0004FF42F71E9E70024012A0294039417D1FA -:101FD0001B788DF8083053070AD004AB03EBD2030B -:101FE00013F8084C554205F00705AC4003F8084CBF -:101FF00000910346002102A8FFF730FB05B030BD79 -:10200000082AE5D9102A03D81B88ADF80830E2E782 -:10201000202A02D81B680293DDE7D3E90045CDE909 -:102020000245D8E7743F0008B03D0008AC40000806 -:102030008F3F0008383F000870B50C4600F10C05D2 -:10204000E16819B9A1602161A18270BD0E682846BE -:10205000FFF7BAFAE660F3E72DE9F04FD1F8009008 -:1020600091B0C9F3C01604460D46CDE90223002EF7 -:1020700050D0C9F3C03BC9F30626B9F1000F80F276 -:102080009F8119F0C04F40F09B812B7B002B00F00B -:102090009781BBF1020F03D02278B24240F09381C6 -:1020A00009F07F02BBF1020F059236D119F07F0FC4 -:1020B000C9F30F2A01D10AF0030A2B447606059AC8 -:1020C00093F8038046EA0B4646EA82465FEAD81355 -:1020D00046EA0A06069300F09A800022002310A91F -:1020E00061E90823059B6768009352465B462046DA -:1020F000B847002800F08880A7698FB9314604F1FD -:102100000C00FFF7DBF90746D0B96FF0020011B001 -:10211000BDE8F08F4FF0020BAFE7C9F3074ACCE7F9 -:102120003B699E420DD03F68002FF9D1314604F142 -:102130000C00FFF7C3F907460028E6D0A3693B600F -:10214000A761DDE90801FFF7D3FAB882F97D08F04D -:102150001F06C1F38401711A89B20FFA81FEBEF124 -:10216000000FB8BF01F1200EC9F30461D7E90223C3 -:10217000B8BF0FFA8EFE079152EA030100F02F81DB -:10218000DDE90201801A61EB03010B4600210246E2 -:102190009E48994208BF9042C0F02181069B002BC7 -:1021A0003FD0BEF1010F00F31A8118F0400F38D074 -:1021B000DDE90223C7E90223202200210DEB020002 -:1021C000FFF7CAF8DDE90223CDE908232B1D0A93A6 -:1021D0002B7B2046013BDBB2ADF834309DF81C3040 -:1021E000ADF836A08DF83A309DF814308DF838B03F -:1021F0008DF83B308DF83960A36808A998473846B8 -:10220000FFF70CFA002082E76FF00B007FE7A76969 -:1022100017B96FF00C007AE73B699E4296D03F6891 -:10222000F6E7FB7DC8F34012B2EBD31F40F0CE803F -:10223000C3F38403B34240F0CC8006992B7B4FEA72 -:10224000981279B3D2073CD4032B40F2C580DDE964 -:102250000223C7E902232B7BAE1D033BDBB23246D0 -:10226000394604F10C00FFF729FB002808DA39464B -:102270002046FFF7BFF93846FFF7D0F9032046E7BD -:10228000AB883B832A7B033AD2B2B88A3146FFF748 -:1022900055FAFB7DB882DA43C2F3C01262F3C7136A -:1022A000FB75AFE76AB92E1D013BDBB232463946FA -:1022B00004F10C00FFF702FB0028D8DB2A7B013A6F -:1022C000E2E7FA8A013BC2F30902052AD9B250D8E3 -:1022D0000023281D99420AD907EB020E10F801CB02 -:1022E00001320133062A8EF81AC0DBB2F2D18B42DA -:1022F00028BF0023DDE9028907F11A02CDE9088928 -:102300000A927A683CBF04335B190B920C93FB8AE8 -:10231000ADF836A0C3F3090319449DF81C30ADF89D -:1023200034108DF83A309DF814308DF838B08DF8AF -:102330003B3000238DF839607B602A7BB88A013AF4 -:10234000291DFFF7FBF93B8BB882834203D1A368B9 -:1023500008A92046984708A92046FFF76DFE384691 -:10236000FFF75CF9B88A3B8B984214BF112000201C -:10237000CDE6786810B34FF0060E03689BB9A2EB68 -:102380000E021B2A13D80332024405F1040E1F303B -:102390009942ACD91EF801CB013302F801CF90422B -:1023A000DBB2F5D1A3E70EF11C0E1846E5E7184B9A -:1023B000184A40F2B311184801F06CFB034696E747 -:1023C0006FF00900A3E66FF00A00A0E66FF00D00C1 -:1023D0009DE66FF00E009AE66FF00F0097E6FB7D2A -:1023E000394668F386036FF3C713FB752046FFF782 -:1023F00001F9069B002B7FF4D8AEFB7DC3F384026A -:10240000013262F38603FB7503E700BF80841E0080 -:10241000A43F0008883D0008AC4000082DE9F041C9 -:102420004E4EB04240F086804D4CDFF838E1E56911 -:1024300045F00075E561E469846AD4F8007207EA42 -:102440000E0747F00107C4F80072D4F8005205EAFD -:102450000E0545F0010545EA0121C4F80012002AE5 -:102460006AD000210F46C4F81C12C4F80412C4F844 -:102470000C12C4F8141204EBC10501310E29C5F881 -:102480004072C5F84472F6D14FF0000E4FF0010CC7 -:10249000964510D1826AB042D2F8003223F001038F -:1024A000C2F8003258D12E4BDA6922F00072DA619C -:1024B000DB69BDE8F0819F781D8817F0010F18BF18 -:1024C000D4F804820CFA05F11CBF41EA0808C4F8EC -:1024D000048217F0020F18BFD4F80C8204EBC50574 -:1024E0001CBF41EA0808C4F80C827F0748BFD4F833 -:1024F000147203F10C0344BF0F43C4F8147253F871 -:10250000087C0EF1010EC5F8407253F8047CC5F842 -:102510004472D4F81C522943C4F81C12B8E70021B5 -:10252000846AC4F81C12C4F80412C4F80C12C4F86B -:102530001412A9E7002AF2D10022836AC3F84022CC -:10254000C3F84422C3F80422C3F814220122C3F8BA -:102550000C22C3F81C229DE7BDE8F081E022002098 -:10256000001002400000FFFF184A08B5916A8B680E -:102570008B6013F0010105D013F00C0F14BF4FF462 -:1025800080310121D80506D513F4406F14BF41F402 -:10259000003141F00201D80306D513F4402F14BFD7 -:1025A00041F4802141F00401D3690BB107489847F9 -:1025B000202383F311880021054800F09DFE0023AD -:1025C00083F31188BDE8084001F086B8E0220020BE -:1025D000E822002038B5124CA36ADD68AA0712D0A1 -:1025E0005A6922F002025A61A36913B101212046FF -:1025F0009847202383F3118800210A4800F07CFECD -:10260000002383F31188EB0606D51021A36AD96055 -:10261000236A0BB102489847BDE8384001F05CB826 -:10262000E0220020F022002038B5124CA36A1D6978 -:10263000AA0712D05A6922F010025A61A36913B195 -:10264000022120469847202383F3118800210A485D -:1026500000F052FE002383F31188EB0606D510210B -:10266000A36A1961236A0BB102489847BDE8384054 -:1026700001F032B8E0220020F022002038B50F4CE3 -:10268000A36A5D682A075D600AD5032222701A6872 -:1026900022F002021A60636A13B1002120469847B3 -:1026A0006B0706D5A36A9969236A13B10904034825 -:1026B0009847BDE8384001F00FB800BFE022002085 -:1026C00010B50F4C204600F03FFA0E4B0B211320A3 -:1026D000A36200F019FA0B21142000F015FA0B2167 -:1026E000152000F011FA0B21162000F00DFA00233E -:1026F0002046BDE810401A460E21FFF78FBE00BFEE -:10270000E0220020006400400F4B10B598420446C0 -:1027100005D10E4BDA6942F00072DA61DB69012201 -:10272000A36A1A60A36A5A68D20707D5626851681B -:102730001268D9611A60064A5A6110BD0121082049 -:1027400000F092FCEEE700BFE02200200010024003 -:102750005B87010003291AD8DFE801F0020A0F1491 -:10276000836A9B6813F0E05F14BF0120002070476C -:10277000836A9868C0F380607047836A9868C0F382 -:10278000C0607047836A9868C0F30070704700208B -:102790007047000010B503291FD8DFE801F0021FC1 -:1027A0002327816A8B68C3F30163183301EB03139A -:1027B000107881061ED55468C0F30011490041EA23 -:1027C000C40141F0040100F00F005860906841F02E -:1027D00001019860D268DA60196010BD836A03F560 -:1027E000C073E5E7836A03F5C873E1E7836A03F51D -:1027F000D073DDE79488C0F30011490041EA4451E9 -:10280000E1E7000001290CD003D3022910D00020F9 -:102810007047836ADA68920701D1186903E00120E2 -:102820007047836AD86810F0030018BF0120704712 -:10283000836AF2E710B539B9836AD96889071BD171 -:102840001B699B0704D110BD012915D0022948D16D -:10285000816AD1F8C031D1F8C401D1F8C8411461FE -:10286000D1F8CC41546120240C610C69A40717D124 -:102870004C6944F0100412E0816AD1F8B031D1F80B -:10288000B401D1F8B8411461D1F8BC41546120249D -:10289000CC60CC68A40703D14C6944F002044C61BD -:1028A00011795C0864F304119C0864F345111171FB -:1028B00089064BBF91681189DB085B0D4CBF63F340 -:1028C0001C0163F30A01137948BF916060F30303AD -:1028D00013714FEA10234FEA104058BF1181137053 -:1028E000508010BD00231A4610B51C495A50CC1810 -:1028F0000833802B6260F9D1194B9A6942F07D024E -:102900009A619B690268174BDA6082685A60426874 -:102910001A60C26803F58063DA6042695A6002692E -:102920001A608269C3F80C24026AC3F80424C269DD -:10293000C3F80024426AC3F80C28C26AC3F804280A -:10294000826AC3F80028026BC3F80C2C826BC3F8B0 -:10295000042C426BC3F8002C10BD00BF0C230020D8 -:102960000010024000080140026843681143016002 -:1029700003B1184770470000024AD36843F0C00310 -:10298000D360704700380140024AD36843F0C00367 -:10299000D3607047004400402DE9F041D0F89C60BE -:1029A0000546F7683368DA059CB20DD5202383F31A -:1029B00011884FF400710430FFF7D6FF6FF4807375 -:1029C0003360002383F31188202383F3118805F1FA -:1029D000040814F02F0333D183F31188380615D57A -:1029E000210613D5202383F3118805F1380000F068 -:1029F0002FFA002846DA0821281DFFF7B5FF4FF609 -:102A00007F733B40F360002383F311887A060ED571 -:102A100063060CD5202383F31188EA6C2B6D9A4250 -:102A200002D12B6C002B2FD1002383F31188D5F812 -:102A3000A420D368002B31D0BDE8F04110691847BD -:102A4000230713D014F0080F0CBF00218021E007EA -:102A500048BF41F02001A20748BF41F04001630791 -:102A600048BF41F480714046FFF77EFFA4067368BB -:102A700005D595F8A0102846194000F089FA346869 -:102A8000A4B2A6E77060BEE727F040073F0410211C -:102A9000281D3F0CFFF768FFF760C5E7BDE8F08130 -:102AA00008B50348FFF778FFBDE8084000F014BE02 -:102AB0008C23002008B50348FFF76EFFBDE80840EF -:102AC00000F00ABE3424002010B5094C094A204603 -:102AD000002100F03DFA084B084AC4F89C30084C2D -:102AE0000021204600F034FA064BC4F89C3010BD9B -:102AF0008C2300207929000800380140892900082A -:102B0000342400200044004000F16043090103F533 -:102B10006143C9B283F80013012300F01F0240098A -:102B2000800000F16040934000F56140C0F88031C2 -:102B300003607047090100F16040C9B200F56D40C3 -:102B400001767047FFF7BCBD01230370002300F13D -:102B500008028260C26000F11002436002614261BB -:102B60008361C361036243627047000010B5202394 -:102B7000044683F31188022341600370FFF7C4FD0C -:102B800003232370002383F3118810BD2DE9F04146 -:102B90001F4604460D461646202383F3118800F194 -:102BA00008082378042B0ED029462046FFF7D2FDD3 -:102BB00048B1204632462946FFF7ECFD002080F35D -:102BC0001188BDE8F0813946404600F079FB0028C5 -:102BD000E7D0002383F31188BDE8F0812DE9F041AF -:102BE0001F4604460D461646202383F3118800F144 -:102BF00010082378042B0ED029462046FFF702FE4A -:102C000048B1204632462946FFF714FE002080F3E3 -:102C10001188BDE8F0813946404600F051FB00289C -:102C2000E7D0002383F31188BDE8F081F8B515469D -:102C300082680B46AA428169066938BF8568761AA0 -:102C4000B542044607D218462A46FEF773FBA3692D -:102C50002B44A3610DE011D932461846FEF76AFBFA -:102C6000AF1B3A46E1683044FEF764FBE2683A4441 -:102C7000A261A36828465B1BA360F8BD18462A46DC -:102C8000FEF758FBE368E4E72DE9F04104461546FA -:102C900083682669934238BF856840690F46361AB3 -:102CA000B54206D22A46FEF745FB63692B446361B1 -:102CB0000DE012D93246A5EB0608FEF73BFB424673 -:102CC000B919E068FEF736FBE26842446261A36826 -:102CD00028465B1BA360BDE8F0812A46FEF72AFB6D -:102CE000E368E4E710B50024C361029B0A44006076 -:102CF00040608460C160816141610261036210BD16 -:102D000008B582694369934201D1826882B98268B9 -:102D1000013282605A1C42611970426903699A4209 -:102D200001D3C3684361002100F0DAFA002008BD36 -:102D30004FF0FF3008BD000070B5202304460E465A -:102D400083F31188A568A5B1A368A269013BA360BC -:102D5000531CA36115782269934224BFE368A361E1 -:102D6000E3690BB120469847002383F31188284676 -:102D700070BD3146204600F0A3FA0028E2DA85F360 -:102D8000118870BD2DE9F74F05460F4690469A46CB -:102D9000D0F81C90202686F311884FF0000B1446C3 -:102DA00064B1224639462846FFF740FF034668B91A -:102DB0005146284600F084FA0028F1D0002383F31E -:102DC0001188A8EB040003B0BDE8F08FB9F1000F43 -:102DD00003D001902846C847019B8BF31188E41A61 -:102DE0001F4486F31188DBE7C361009BC1608161EA -:102DF000416111440060406082600161036270477C -:102E0000F8B504460E461746202383F31188A568BB -:102E1000A5B1A368013BA36063695A1C62611E707F -:102E2000236962699A4224BFE3686361E3690BB175 -:102E300020469847002080F31188F8BD3946204687 -:102E400000F03EFA0028E2DA85F31188F8BD0000B0 -:102E50008369426910B59A4201D182687AB9826861 -:102E6000013282605A1C82611C7803699A4201D344 -:102E7000C3688361002100F033FA204610BD4FF093 -:102E8000FF3010BD2DE9F74F05460F4690469A4694 -:102E9000D0F81C90202686F311884FF0000B1446C2 -:102EA00064B1224639462846FFF7EEFE034668B96C -:102EB0005146284600F004FA0028F1D0002383F39D -:102EC0001188A8EB040003B0BDE8F08FB9F1000F42 -:102ED00003D001902846C847019B8BF31188E41A60 -:102EE0001F4486F31188DBE70268436811430160E1 -:102EF00003B11847704700001430FFF743BF0000CC -:102F00004FF0FF331430FFF73DBF00003830FFF7BC -:102F1000B9BF00004FF0FF333830FFF7B3BF0000F8 -:102F20001430FFF709BF00004FF0FF311430FFF7F6 -:102F300003BF00003830FFF763BF00004FF0FF32DF -:102F40003830FFF75DBF000000207047FFF7BCBDC1 -:102F50000E4B37B50360002343608360C3600123D9 -:102F6000044615460374202200900B4600F15C01D4 -:102F70001430FFF7B7FE00942B46202204F17C01A9 -:102F800004F13800FFF730FF03B030BDE84000081F -:102F900038B5C36904460D461BB904210844FFF740 -:102FA000A3FF294604F11400FFF7AAFE002806DA61 -:102FB000201D4FF48061BDE83840FFF795BF38BD54 -:102FC0000022024B1B605B609A607047DC2400208B -:102FD000002382680374054B1B6899689142FBD2F9 -:102FE0005A6803604260106058607047DC2400201B -:102FF00008B5202383F31188037C032B05D0042B11 -:103000000DD02BB983F3118808BD002243691A60E3 -:103010004FF0FF334361FFF7DBFF0023F2E790E857 -:103020000C001A6002685360F2E700000023826817 -:103030000374054B1B6899689142FBD85A6803607A -:103040004260106058607047DC240020054B19690D -:1030500008741868026853601A60186101230374C9 -:10306000FDF78EBADC24002030B54B1C87B0054636 -:103070000A4C10D023690A4A01A800F059F92846E1 -:10308000FFF7E4FF049B13B101A800F06BF923697B -:10309000586907B030BDFFF7D9FFF8E7DC240020FE -:1030A000F12F000838B50C4D41612B6981689A6891 -:1030B0000446914203D8BDE83840FFF789BF18465F -:1030C000FFF786FF01232C61014623742046BDE8EB -:1030D0003840FDF755BA00BFDC240020044B1A68C5 -:1030E0001B6990689B68984294BF0020012070473C -:1030F000DC24002010B5084C236820691A6854604D -:103100002260012223611A74FFF790FF01462069B3 -:10311000BDE81040FDF734BADC24002008B5FFF705 -:10312000DDFF18B1BDE80840FFF7E4BF08BD0000AF -:10313000FEE7000010B5174CFFF742FF00F0EAF879 -:1031400080221549204600F06FF8012344F8180C3E -:103150000374124B124AD96821F4E0610904090C86 -:103160000A431049DA60CA6842F08072CA600E49A8 -:103170000A6842F001020A601022DA77202283F8FE -:103180002220002383F3118862B6BDE8104007486F -:1031900000F06CB8042500201041000800ED00E0AC -:1031A0000003FA05F0ED00E0001000E0184100080F -:1031B000F8B50F4C226A01322262224652F8141FDF -:1031C0009142154606D020268B68013B8B606369CF -:1031D0009A6802B1F8BD1968DF68DA604D60616114 -:1031E00082F311881869B84786F31188EFE700BFAA -:1031F000DC240020EFF3118020B9EFF305832022B7 -:1032000082F311887047000010B558B9EFF30584B8 -:10321000C4F3080414B180F3118810BDFFF77EFFDA -:1032200084F3118810BD0000826002220274002223 -:10323000427470478368A3F13C0243F80C2C026986 -:1032400043F83C2C426943F8382C074A43F81C2CBD -:10325000C268A3F1180043F8102C022203F8082CCE -:10326000002203F8072C70479105000810B52023B1 -:1032700083F31188FFF7DEFF00210446FFF712FFFA -:10328000002383F31188204610BD0000024B1B6908 -:1032900058610F20FFF7DABEDC240020202383F3DF -:1032A0001188FFF7F3BF000008B50146202383F320 -:1032B00011880820FFF7D8FE002383F3118808BD8A -:1032C00049B1064B42681B6918605A60136043603D -:1032D0000420FFF7C9BE4FF0FF307047DC24002008 -:1032E0000368984206D01A68026050605961184617 -:1032F000FFF76EBE7047000038B504460D462068E3 -:10330000844200D138BD036823605C604561FFF7EB -:103310005FFEF4E7054B03F114025A619A614FF026 -:10332000FF32DA6100221A62704700BFDC240020FD -:1033300010B5C2600A4A036153699C68A1420CD867 -:103340005C68036044602060586081609868411A3E -:1033500099604FF0FF33D36110BD091B1B68ECE788 -:10336000DC240020036881689A680A449A604268F5 -:10337000136003685A6000234FF0FF32C360014BB3 -:10338000DA617047DC24002000207047FEE700006F -:10339000704700004FF0FF3070470000BFF34F8FC1 -:1033A000024AD368DB07FCD4704700BF002002400C -:1033B00008B5074B1B7853B9FFF7F0FF054B1A69A7 -:1033C000120641BF044A5A6002F188325A6008BDB1 -:1033D000E0250020002002402301674508B5054B89 -:1033E0001B7833B9FFF7DAFF034A136943F0800310 -:1033F000136108BDE0250020002002407F289ABF0D -:1034000000F5003080020020704700004FF480601B -:1034100070470000802070477F2808B50BD8FFF761 -:10342000EDFF00F580630268013204D1043083426D -:10343000F9D1012008BD002008BD00007F2838B563 -:10344000044624D800F0B6F8124D2860FFF7A6FF16 -:10345000FFF7AEFFF322104B2046DA6002221A611A -:10346000FFF7CCFF58611A6942F040021A61FFF77A -:1034700095FF4FF4806100F0E9F8FFF7AFFF00F02F -:1034800099F828602046BDE83840FFF7C5BF002006 -:1034900038BD00BFE4250020002002402DE9F8439C -:1034A00012F00103144606D040F24B221F4B1A6063 -:1034B0000020BDE8F88385181D4A954204D94FF4D1 -:1034C00014711A4A1160F3E7FFF772FFFFF766FF06 -:1034D0004FF00109DFF86880451A012C05EB010661 -:1034E0000F4604D8FFF77AFF0120BDE8F883C8F83B -:1034F000109031F8023B3380FFF750FF0020C8F8EE -:10350000100033883A889BB29A420DD040F267226D -:10351000064B1A60074B1E60074B1C60074B1F6071 -:10352000FFF75CFFBDE8F883023CD6E7DC2500200E -:10353000FFFF0108D0250020D8250020D425002039 -:1035400000200240084908B50B7828B153B9FFF7AD -:103550002FFF01230B7008BD23B1BDE808400870A0 -:10356000FFF73CBF08BD00BFE025002038B5FFF7DE -:1035700041FE4FF47A730C490C4A0C6A116803FB44 -:1035800004F38B420A49D1E9004504D2003445F1E5 -:103590000105C1E90045E41845F100051360FFF796 -:1035A00033FE2046294638BDDC240020E8250020D3 -:1035B000F025002008B5FFF7D9FF4FF47A720023F9 -:1035C000FCF7E6FD08BD00BF10B5094C0439013A0F -:1035D000D2B2FF2A00D110BD53089800043054F82D -:1035E000233000599BB243EA004341F8043FEEE721 -:1035F000046C004030B50748013AD2B2FF2A00D12E -:1036000030BD0D88540840F82450A3004C88043382 -:103610001C50F1E7046C004007B5012201A900200D -:10362000FFF7D2FF019803B05DF804FB13B5044621 -:10363000FFF7F2FFA04206D002A941F8044D012293 -:103640000020FFF7D7FF02B010BD00007047000058 -:1036500045F25552064B1A6002225A6040F6FF723C -:103660009A604CF6CC421A600122024B1A707047E5 -:1036700000300040F9250020034B1B781BB14AF6AF -:10368000AA22024B1A607047F92500200030004042 -:10369000034B1B689B0042BF0122024B1A7070470C -:1036A00024100240F82500204FF08072014B1A6070 -:1036B000704700BF24100240014B1878704700BFCC -:1036C000F8250020EFF30983203383F309880023D2 -:1036D00083F311887047000010B5202383F311880D -:1036E0000D4B5B6813F4006312D0EFF309844FF0C5 -:1036F000807344F8043CA4F1200383F30988FFF7A6 -:10370000EDFC18B1054B44F8083C10BD044BFAE73A -:1037100083F3118810BD00BF00ED00E0A105000893 -:10372000A405000870470000FEE70000084A094BA6 -:1037300009498B4204D30021084A934205D37047BC -:1037400052F8040F43F8040BF3E743F8041BF4E7C3 -:103750002842000800260020002600200026002025 -:1037600000F030B808B500F063F9FFF7E3FCBDE8FE -:103770000840FFF78DBF0000704700004FF0FF3199 -:103780000E4B1A6919611A6900221A611869D86802 -:10379000D960D968DA60DA68DA6942F08052DA61B1 -:1037A000DA69DA6942F00062DA61054ADB691368B6 -:1037B00043F48073136000F01BB900BF0010024097 -:1037C00000700040194B1A6842F001021A601A6832 -:1037D0009007FCD51A6802F0F9021A6000225A60BC -:1037E0005A6812F00C0FFBD11A6842F480321A604A -:1037F0001A689103FCD55A6842F4E8125A601A68B4 -:1038000042F080721A601A689201FCD51221084AAF -:103810005A60084A11605A6842F002025A605A68B7 -:1038200002F00C02082AFAD1704700BF00100240D3 -:1038300000641D0000200240084A08B55369116861 -:103840000B4003F00103536123B1054A13680BB128 -:1038500050689847BDE80840FFF73EBF00040140AC -:103860000C230020084A08B5536911680B4003F087 -:103870000203536123B1054A93680BB1D06898479E -:10388000BDE80840FFF728BF000401400C230020DA -:10389000084A08B5536911680B4003F004035361EB -:1038A00023B1054A13690BB150699847BDE8084038 -:1038B000FFF712BF000401400C230020084A08B59E -:1038C000536911680B4003F00803536123B1054AA3 -:1038D00093690BB1D0699847BDE80840FFF7FCBE7B -:1038E000000401400C230020084A08B55369116800 -:1038F0000B4003F01003536123B1054A136A0BB167 -:10390000506A9847BDE80840FFF7E6BE0004014052 -:103910000C230020174B10B55C691A68144004F49E -:1039200078725A61A30604D5134A936A0BB1D06A20 -:103930009847600604D5104A136B0BB1506B98473B -:10394000210604D50C4A936B0BB1D06B9847E20566 -:1039500004D5094A136C0BB1506C9847A30504D5E4 -:10396000054A936C0BB1D06C9847BDE81040FFF747 -:10397000B3BE00BF000401400C2300201A4B10B559 -:103980005C691A68144004F47C425A61620504D5EB -:10399000164A136D0BB1506D9847230504D5134A91 -:1039A000936D0BB1D06D9847E00404D50F4A136EA8 -:1039B0000BB1506E9847A10404D50C4A936E0BB11D -:1039C000D06E9847620404D5084A136F0BB1506F4C -:1039D0009847230404D5054A936F0BB1D06F9847DD -:1039E000BDE81040FFF778BE000401400C23002022 -:1039F000062108B50846FFF787F806210720FFF7DC -:103A000083F806210820FFF77FF806210920FFF739 -:103A10007BF806210A20FFF777F806211720FFF729 -:103A200073F8BDE8084006212820FFF76DB80000B4 -:103A300008B5FFF7A3FE0648FEF754FFFFF782F82C -:103A4000FFF784FAFFF798FEBDE8084000F002B8DF -:103A50003841000800F00EB808B5202383F3118820 -:103A6000FFF7A6FB002383F31188BDE80840FFF7AA -:103A700033BE0000054B064A08215A6000229A60B6 -:103A800007220B201A60FFF755B800BF10E000E0D6 -:103A90003F1901001FB51C46094B05461B68D86835 -:103AA00052B1084B8DE80A0002922B462246064985 -:103AB000FDF7AAFC00F042F8044B1A46F2E700BFFB -:103AC0001011002074410008814100086C3C00087E -:103AD00010B501390244904201D1002010BD10F808 -:103AE000013B11F8014FA342F5D0181B10BD000097 -:103AF0002DE9F8430746884691461E468BB10D4690 -:103B0000A8EB0500B54207EB000402D20020BDE897 -:103B1000F883324649462046FFF7DAFF18B1013DE7 -:103B2000EEE7BDE8F8832046BDE8F883034611F8C8 -:103B3000012B03F8012B002AF9D1704708B50620A4 -:103B400000F02CF80120FFF721FC00001F2938B5F8 -:103B500004460D4604D9162303604FF0FF3038BDEC -:103B6000426C12B152F821304BB9204600F030F8C7 -:103B70002A4601462046BDE8384000F017B8012B20 -:103B80000AD0591C03D116230360012038BD00243C -:103B9000284642F825409847002038BD024B014690 -:103BA0001868FFF7D3BF00BF1011002038B50023FD -:103BB000064C0546084611462360FFF7EBFB431C05 -:103BC00002D1236803B12B6038BD00BFFC25002063 -:103BD000FFF7DABB40A2E4F1646891064E6F206102 -:103BE0007070207369670A00426164206677206CF8 -:103BF000656E6774682025750A0042616420626FF3 -:103C00006172645F69642025752073686F756C64E8 -:103C10002062652025750A00426164206677206471 -:103C2000657363726970746F72206C656E67746817 -:103C30002025750A00426164206170702043524360 -:103C4000203078253038783A307825303878203070 -:103C500078253038783A3078253038780A00476F40 -:103C60006F64206669726D776172650A00000000FA -:103C700072656365697665645F756E697175655FA8 -:103C800069645F6C656E203C2055415643414E5F30 -:103C900050524F544F434F4C5F44594E414D49434E -:103CA0005F4E4F44455F49445F414C4C4F43415444 -:103CB000494F4E5F554E495155455F49445F4D410F -:103CC000585F4C454E475448002E2E2F2E2E2F5411 -:103CD0006F6F6C732F41505F426F6F746C6F6164D4 -:103CE00065722F63616E2E63707000616C6C6F6320 -:103CF000617465645F6E6F64655F6964203C3D203C -:103D0000313237006F72672E6172647570696C6F43 -:103D1000742E61705F7065726970685F67707300A0 -:103D2000766F69642068616E646C655F616C6C6F4E -:103D3000636174696F6E5F726573706F6E7365280F -:103D400043616E617264496E7374616E63652A2C9F -:103D50002043616E61726452785472616E7366655D -:103D6000722A290063616E617264496E6974000091 -:103D700063616E6172645365744C6F63616C4E6F06 -:103D8000646549440000000063616E6172644861CB -:103D90006E646C6552784672616D650063616E6138 -:103DA00072644465636F64655363616C61720000A3 -:103DB00063616E617264456E636F64655363616CC9 -:103DC00061720000696E6372656D656E7454726134 -:103DD0006E73666572494400656E717565756554EC -:103DE000784672616D6573007075736854785175AB -:103DF0006575650070726570617265466F724E65BB -:103E000078745472616E736665720000636F7079C6 -:103E100042697441727261790000000064657363E5 -:103E200061747465725472616E7366657250617903 -:103E30006C6F61640000000066726565426C6F63C0 -:103E40006B0000006269745F6C656E677468203E89 -:103E500020300072656D61696E696E675F626974BA -:103E600073203E203000696E7075745F6269745F04 -:103E70006F6666736574203E3D20626C6F636B5F96 -:103E80006269745F6F666673657400626C6F636B02 -:103E90005F656E645F6269745F6F666673657420E8 -:103EA0003E20626C6F636B5F6269745F6F666673FE -:103EB00065740072656D61696E696E675F626974D1 -:103EC0005F6C656E677468203C3D2072656D61694A -:103ED0006E696E675F6269747300696E7075745F96 -:103EE0006269745F6F6666736574203C3D2074720E -:103EF000616E736665722D3E7061796C6F61645F8F -:103F00006C656E202A2038006F75747075745F625E -:103F100069745F6F6666736574203C3D20363400BB -:103F200072656D61696E696E675F6269745F6C6509 -:103F30006E677468203D3D20300028726573756C93 -:103F400074203E2030292026262028726573756C47 -:103F500074203C3D203634292026262028726573A3 -:103F6000756C74203C3D206269745F6C656E67748B -:103F70006829000064657374696E6174696F6E20EE -:103F8000213D202828766F6964202A29302900766F -:103F9000616C756520213D202828766F6964202A90 -:103FA000293029006F66667365745F776974686984 -:103FB0006E5F626C6F636B203C2028333255202D7E -:103FC000205F5F6275696C74696E5F6F66667365AA -:103FD000746F66202843616E61726442756666651F -:103FE00072426C6F636B2C2064617461292900003C -:103FF0006F75745F696E7320213D202828766F6984 -:1040000064202A29302900007372635F6C656E207A -:104010003E203055000000002863616E5F69642017 -:104020002620307831464646464646465529203DAC -:104030003D2063616E5F696400000000616C6C6F1D -:104040006361746F722D3E73746174697374696314 -:10405000732E63757272656E745F75736167655FE9 -:10406000626C6F636B73203E203000007472616E6F -:10407000736665725F696420213D202828766F6928 -:1040800064202A293029000073746174652D3E6212 -:1040900075666665725F626C6F636B73203D3D2071 -:1040A0002828766F6964202A293029002E2E2F2E89 -:1040B0002E2F6D6F64756C65732F6C696263616E12 -:1040C0006172642F63616E6172642E63006974654E -:1040D0006D2D3E6672616D652E646174615F6C6505 -:1040E0006E203E203000000000000000152F000868 -:1040F000012F00083D2F0008292F0008352F000848 -:10410000212F00080D2F0008F92E0008492F000864 -:104110006D61696E0000000030410008202500201C -:10412000D02500200100000031310008000000000F -:1041300069646C65000000000C1E0000447B414473 -:10414000B4574944010000004244444444444444B8 -:10415000000000004444444444444444000000003F -:10416000444444444444444400000000444444441F -:10417000444444442C2066756E6374696F6E3A2023 -:1041800000617373657274696F6E2022257322203B -:104190006661696C65643A2066696C6520222573E6 -:1041A000222C206C696E65202564257325730A0016 -:1041B00010C0FF7F0100000064000000000000004C -:1041C000FE2A0100D20400001411002000000000AB -:1041D00000000000000000000000000000000000DF -:1041E00000000000000000000000000000000000CF -:1041F00000000000000000000000000000000000BF -:1042000000000000000000000000000000000000AE -:10421000000000000000000000000000000000009E -:0C42200000000000000000000000000092 +:100000000009002069040008C114000865140008F4 +:10001000A514000865140008851400086B04000886 +:100020006B0400086B0400086B0400087D350008B1 +:100030006B0400086B0400086B040008113A000808 +:100040006B0400086B0400086B0400086B040008D4 +:100050006B0400086B0400083D370008693700088E +:1000600095370008C1370008ED3700086B04000819 +:100070006B0400086B0400086B0400086B040008A4 +:100080006B0400086B0400086B040008712400086E +:10009000DD240008312500088525000819380008EE +:1000A0006B0400086B0400086B0400086B04000874 +:1000B0006B0400086B0400086B0400086B04000864 +:1000C0006B0400086B0400086B0400086B04000854 +:1000D0006B04000825290008392900086B04000872 +:1000E000813800086B0400086B0400086B040008EA +:1000F0006B0400086B0400086B0400086B04000824 +:100100006B0400086B0400086B0400086B04000813 +:100110006B0400086B0400086B0400086B04000803 +:100120006B0400086B0400086B0400086B040008F3 +:100130006B0400086B0400086B0400086B040008E3 +:100140006B0400086B0400086B0400086B040008D3 +:100150006B0400086B0400086B0400086B040008C3 +:1001600053B94AB9002908BF00281CBF4FF0FF311E +:100170004FF0FF3000F076B9ADF1080C6DE904CE18 +:1001800000F006F8DDF804E0DDE9022304B0704772 +:100190002DE9F047089E0D4604468846002B4DD1B8 +:1001A0008A42944668D9B2FA82F252B101FA02F355 +:1001B000C2F1200120FA01F10CFA02FC41EA030825 +:1001C00094404FEA1C41B8FBF1F71FFA8CFE01FB8B +:1001D000178807FB0EF0230C43EA084398420AD91C +:1001E0001CEB030307F1FF3580F01E81984240F2BB +:1001F0001B81023F63441B1AB3FBF1F001FB103378 +:1002000000FB0EFEA4B244EA0344A6450AD91CEB47 +:10021000040400F1FF3380F00981A64540F2068115 +:10022000644402380021A4EB0E0440EA07401EB1EA +:100230000023D440C6E90043BDE8F0878B4208D9CB +:10024000002E00F0EE800021C6E900050846BDE85A +:10025000F087B3FA83F100294AD1AB4202D382423C +:1002600000F2FC80841A65EB030301209846002EFF +:10027000E2D0C6E90048DFE702B9FFDEB2FA82F257 +:10028000002A40F09180A1EB0C0001214FEA1C47AD +:100290001FFA8CFEB0FBF7F307FB1300250C45EAB1 +:1002A00000450EFB03F0A84208D91CEB050503F13D +:1002B000FF3802D2A84200F2CE8043462D1AB5FB89 +:1002C000F7F007FB10550EFB00FEA4B244EA05440C +:1002D000A64508D91CEB040400F1FF3502D2A6455F +:1002E00000F2B6802846A4EB0E0440EA03409EE7E5 +:1002F000C1F120078B4022FA07FC4CEA030C25FAD7 +:1003000007FA4FEA1C49BAFBF9F820FA07F309FB90 +:1003100018AA8D401FFA8CFE1D4300FA01F308FB5A +:100320000EF02C0C44EA0A44A04202FA01F20BD966 +:100330001CEB040408F1FF3A80F08880A04240F2F0 +:100340008580A8F102086444241AB4FBF9F009FB83 +:10035000104400FB0EFEADB245EA0444A64508D9A0 +:100360001CEB040400F1FF356CD2A6456AD90238B3 +:10037000644440EA0840A0FB0295A4EB0E04AC42A2 +:10038000C846AE4656D353D0002E69D0B3EB080210 +:1003900064EB0E0422FA01F304FA07F71F43CC4082 +:1003A000C6E90074002147E70CFA02FCC2F1200103 +:1003B00025FA01F34FEA1C4720FA01F195400D435D +:1003C000B3FBF7F107FB11331FFA8CFE280C40EA50 +:1003D000034001FB0EF3834204FA02F408D91CEB3C +:1003E000000001F1FF382FD283422DD90239604439 +:1003F000C01AB0FBF7F307FB1300ADB245EA0045A6 +:1004000003FB0EF0A84208D91CEB050503F1FF38E9 +:1004100016D2A84214D9023B6544281A43EA014186 +:1004200038E73146304607E72F46E4E61846F9E656 +:100430004B45A9D2B9EB020865EB0C0E0138A3E7D6 +:100440004346EAE7284694E74146D1E7D0467BE7B2 +:100450006444023847E7023B65442FE7084606E755 +:100460003146E9E6704700BF02E000F000F8FEE721 +:1004700072B6284880F30888274880F309882748FF +:100480004EF60851CEF200010860022080F3148875 +:10049000BFF36F8F03F0E4F803F0C0F803F0E2F865 +:1004A0004FF055301E491B4A91423CBF41F8040BA6 +:1004B000FAE71C49184A91423CBF41F8040BFAE79D +:1004C00019491A4A1A4B9A423EBF51F8040B42F896 +:1004D000040BF8E700201749174A91423CBF41F846 +:1004E000040BFAE703F09EF803F0BEF8134C144D2A +:1004F000AC4203DA54F8041B8847F9E700F03CF8F3 +:10050000104C114DAC4203DA54F8041B8847F9E74C +:1005100003F086B800090020001100200000000848 +:100520000001002000090020E03B0008001100202D +:100530002411002028110020A025002060010008BF +:100540006001000860010008600100082DE9F04F1B +:10055000C1F80CD0C3689D46BDE8F08F002383F33B +:1005600011882846A047002002F09CFDFEE702F01B +:1005700021FD00DFFEE700002DE9F04102F09CFFC5 +:10058000074602F0E7FF054600283ED12B4B9F426D +:100590003BD001339F423BD0294B27F0FF029A42C8 +:1005A0003AD1F8B200F052FAA84642F2107400F0C4 +:1005B00057FC08B10024A04600F04EFA064678B376 +:1005C00084BB464635B11F4B9F4203D0002402F046 +:1005D000B9FF2646002002F079FF1B4B9B6813F001 +:1005E000400322D00EB100F031F800F097FC00F08B +:1005F00077FE00F067FF0546CCB100F063FF401BBB +:10060000A04214D900F022F8F3E7A8460024CEE770 +:1006100004464FF00108CAE780464FF47A74C6E7F3 +:100620000446CFE74FF47A74CCE71C46DDE700F0D0 +:1006300025FD012002F03CFDDEE700BF010007B010 +:10064000000008B0263A09B0000C014038B51D4A38 +:100650001D4B1968013134D004339342F9D11B4C3E +:10066000194DD4F80424AA422BD3194B9B6803F1EB +:10067000006303F5C8439A4223D202F037FF02F029 +:1006800049FF002000F046FE0220124B187000F0D7 +:100690007DFE114BDA690022DA61D96999699A61A4 +:1006A0009B6972B64FF0E023C3F8085DD4F80034BC +:1006B000D4F80424202181F311889D4683F308880F +:1006C000104738BD2064000800640008006000087E +:1006D00000110020281100200010024049F269009A +:1006E000084A136899B21B0C00FB013344F25061B5 +:1006F0001360054B186882B2000C01FB0200186001 +:1007000080B27047201100201C11002010B5044653 +:100710000021102200F056FE034B03CB20606160E5 +:100720001868A06010BD00BFE8F7FF1F2DE9F04377 +:10073000BBB000F0C7FE40F2ED22204DAB68C31AFB +:10074000934232D906AF2B4628220021A8603846B2 +:1007500001F0C2FB05F10E0000F02CFE002604465D +:100760005FFA80F905F10E08F3B2F100994501F145 +:10077000280107D908EB06030822384601F0ACFB34 +:100780000136F1E708230122CDE902320C4B053492 +:1007900001933023A4B20093CDE9047405A3D3E9F7 +:1007A0000023297B074801F0ADF93BB0BDE8F08399 +:1007B000AFF3008078F6339F93CACD8D702100206F +:1007C0007D2100204421002070B50D4614461E46B0 +:1007D00001F02EF950B9022E10D1012C0ED112A326 +:1007E000D3E900230120C5E9002307E0282C10D01D +:1007F00005D8012C09D0052C0FD0002070BD302C5D +:10080000FBD10BA3D3E90023ECE70BA3D3E900232F +:10081000E8E70BA3D3E90023E4E70BA3D3E9002324 +:10082000E0E700BFAFF30080401DA12026812A0B26 +:1008300078F6339F93CACD8D9E6AC421818A46EE95 +:1008400026417272DF25D7B7F017304A39059E5618 +:1008500038B50D460446034620222846002101F003 +:100860003BFB22792346032A28BF0322284603F8AC +:10087000042F2021022201F02FFB62792346072A50 +:1008800028BF0722284603F8052F2221032201F062 +:1008900023FBA2792346072A28BF0722284603F80C +:1008A000062F2521032201F017FB284610222821BC +:1008B00004F1080301F010FB382038BD2DE9F04F9A +:1008C0000024ADF5017D0EAE40F2751280460F4654 +:1008D00022A82146219400F075FD21464822304689 +:1008E00000F070FD00F0EEFD4FF47A72B0FBF2F014 +:1008F000544B21AD186093E80700012386E80700F8 +:100900000DF15A003382FFF701FF4EF603033384E3 +:1009100007AB18464C4903F0B3F81B222946306454 +:10092000304686F83C20FFF793FF08220446014634 +:1009300012AB284601F0D0FA08222846A1180DF182 +:10094000490301F0C9FA082228460DF14A0304F1CF +:10095000100101F0C1FA2022284613AB04F118015E +:1009600001F0BAFA4022284614AB04F1380101F034 +:10097000B3FA0822284616AB04F1780101F0ACFA6C +:10098000082228460DF1590304F1800101F0A4FA70 +:1009900004F1880A0DF15A0904F5847B4B4651464F +:1009A000082228460AF1080A01F096FAD34509F10F +:1009B0000109F3D10822594628461BAB01F08CFAF5 +:1009C0004FF0000904F5887496F834304B450AD985 +:1009D000B36B21464B440822284601F07DFA0834C7 +:1009E00009F10109F0E74FF0000996F83C3004EBFB +:1009F000C9014B4508D9336C08224B44284601F005 +:100A00006BFA09F10109F0E700230393BB7E07317C +:100A1000029307F1190301930123C1F3CF01CDE93B +:100A200004510093404605A3D3E90023F97E01F069 +:100A300069F80DF5017DBDE8F08F00BF9E6AC42105 +:100A4000818A46EE2C110020903A0008014B187064 +:100A5000704700BF38110020F0B5334B85B01C7BC8 +:100A600034B10E22314B1A810024204605B0F0BD6E +:100A70002F4A02AB1068516803C308232D492E4842 +:100A80000DEB030202F0DCFF054630B90A22274BCA +:100A90002A481A8100F0E2FCE6E70169B1F5CE3F91 +:100AA00006D90B22214B26481A8100F0D7FCDCE73F +:100AB000438BB3F57A7F09D00C211C4A2148118160 +:100AC0004FF47A72194600F0C9FCCEE71E4A024480 +:100AD00002F11003994204D21022144B1B481A81D0 +:100AE000E3E710398E1A2046134900F0EFFC074661 +:100AF0003246204605F1180100F0E8FCAB689F4241 +:100B000002D1EB6898420AD00D22084B1A8100905E +:100B10003B46D5E902120E4800F0A0FCA4E70D48C0 +:100B200000F09CFC0124A0E7702100202C11002083 +:100B30003D3B0008DC9B010000640008AC3A000863 +:100B4000B83A0008CA3A0008089CFFF7E83A0008DB +:100B5000053B00082E3B00082DE9F04FADB006AF75 +:100B600080460C4600F064FF0546002859D1237EDC +:100B7000022B1AD1E38A012B17D100F0A3FC064601 +:100B8000FFF7ACFD4FF4C873B0FBF3F202FB1300A8 +:100B9000DFF8B49206F5167680B2E37E0644C9F813 +:100BA000006033B90022A94B1A709C37BD46BDE8DE +:100BB000F08FA38AEEB2013BB34205F101050BD9D8 +:100BC0003B1D1E44E900002308222046009601F048 +:100BD000F80101F043F8ECE707F11400FFF796FD88 +:100BE000324607F11401381D02F01AFF03460028AF +:100BF000D8D10F2E08D8954B1E70D9F80030A3F528 +:100C00001673C9F80030D0E7FA1CF870014600925C +:100C10002046072201F022F84046F97800F000FF54 +:100C2000C3E7E38A282B26D010D8012B1ED0052B32 +:100C3000BBD1BFF34F8F8649864BCA6802F4E0628E +:100C40001343CB60BFF34F8F00BFFDE7302BACD118 +:100C5000637E814D01336A7BDBB29342E94603D167 +:100C6000E27E2B7B9A4265D0CD469EE721464046E8 +:100C7000FFF724FE99E7A38A013B9BB2C92B94D8C6 +:100C8000754D2E7B26BB05F10C03009308223346DD +:100C90003146204600F0E2FF731CF2B2D9001E4636 +:100CA000A38A013B9A4205DA0E322A4400920023BD +:100CB0000822EEE700230022C5E900230023AB60F1 +:100CC00085F8D730C5F8D8302B7B0BB9E37E2B7372 +:100CD000002507F114060822294630463B1DC7E9C6 +:100CE0000155FD6001F0F8F83B7A05F10109AB42CE +:100CF0004FEAC90107D9FB6808222B44304601F0AE +:100D0000EBF84D46F0E70023C1F3CF01E07ECDE9DB +:100D100004610393A37E19340293282301460093B0 +:100D2000404647A3D3E90023019400F0EBFEFFF710 +:100D3000FDFC3AE74FF0000807F11403A7F8148010 +:100D40001022009341460123204600F087FFA68A27 +:100D5000023EB6B2F31C9B109B000733DB08A9EBE5 +:100D6000C3039D460DF1180A1FFA88F34FEAC80124 +:100D7000B34201F110010AD20AEB080300930822E2 +:100D80000023204600F06AFF08F10108ECE795F81F +:100D9000D70000F0C9FAD5F8D83004461BB995F849 +:100DA000D70000F0D1FAD5F8D83033449C4204D2B1 +:100DB00095F8D700013000F0C7FA4FF000084FEA6D +:100DC000960B1FFA88F18B45D5E9003209D90AEB59 +:100DD000880103EB8800012200F0FCFA08F1010809 +:100DE000EFE7F31842F10002C5E90032D5F8D83038 +:100DF00095F8D70006EB0308C5F8D88000F094FA00 +:100E0000804509D395F8D730D5F8D8000133001BB9 +:100E100085F8D730C5F8D800FF2E08D800232B73EB +:100E200000F0A4FAFFF718FE08B1FFF70FFC2B68DB +:100E30000A4A9B0A013313810023AB6014E700BF09 +:100E400026417272DF25D7B7402100203D210020C6 +:100E500000ED00E00400FA05702100202C110020B4 +:100E600030B54FF00054244B226885B09A4207D029 +:100E700002F07AFB0446A8B90024204605B030BD34 +:100E8000627D1E4B1E481A70237DC92203731D49C3 +:100E90000E3000F085FA2046E022002100F092FAA0 +:100EA0000124EAE7184A194DD36943F00073D3616E +:100EB000AA6D174B9A42DFD12B6E013B7E2BDBD8FC +:100EC000144A01AB07CA83E807001846032100F063 +:100ED00013FB6B6D83424FF00003CDD12A6D8A4224 +:100EE00003BFAB652A6E054B1C4601BF1A70EA6D45 +:100EF000094B1A60C1E700BF9AAD44C53811002004 +:100F00007021002016000020001002400066004002 +:100F10005041A0B0586600401811002002232DE96E +:100F2000F0434A4C85B0637100230293484BD3F8D9 +:100F300000C0BCF57A7F12D3464F474BB7FBFCF598 +:100F40009C458CBF0A231123B5FBF3F603FB165215 +:100F5000591EC8B2002A3ED002290B46F4D89DF88B +:100F60000B303E495A1E9DF80A303D48013B1B0498 +:100F700043EA0253BDF80820013A13434B6001F0E5 +:100F800037FD00230193374B374900934FF48052CC +:100F9000364B374800F01CFD364B197811B13448F8 +:100FA00000F03EFD00F08EFA0546FFF797FB4FF488 +:100FB000C873B0FBF3F202FB130305F516709BB286 +:100FC00018442D4B186002F0C5FA08B10F23238195 +:100FD00005B0BDE8F083731EB3F5806FBFD24FF448 +:100FE0007A75C0EBC00E0EF103034FEAE30909FB6B +:100FF0000555C3F3C703C11AC9B209F101088844F2 +:10100000B5FBF8F5B5F5617F08D90EF1FF33C3F3F1 +:10101000C703C11A581E0F28C9B214D84A1E072A7E +:101020008CBF00220122581800FB0660B7FBF0F7C6 +:10103000BC4594D1002A92D0ADF808608DF80A30F2 +:101040008DF80B108BE71346EDE700BF2C11002045 +:1010500018110020005125023F420F0010110020FE +:1010600088220020C90700083C110020590B000805 +:101070004421002038110020402100202DE9F04FAC +:1010800093A7D7E900670FF25029D9E90089854D68 +:1010900093B0DFF814B2854C284600F097FD0DF1AF +:1010A000300A079070B310220021504600F08AF9F0 +:1010B0004FF00002079B197B61F303028DF830208B +:1010C000586899680EAA03C21B680D9A584663F3C4 +:1010D0001C029DF830300D9243F020038DF8303023 +:1010E00000235246194601F093FC079028B9284680 +:1010F00000F070FD079B2370CEE72378072B3CD8C8 +:101100000133237018220021504600F05BF9DFF80C +:1011100098B1674C002352461946584601F0A0FC8E +:10112000014670BB102208A800F04CF9E36883F078 +:101130001003E36000F0C8F90DF1240C0B4612A96E +:10114000024611E903008CE803009DF83410C1F356 +:101150000300890649BF0E99BDF83810C1F31C0180 +:1011600041F0004158BFC1F30A018DF82C000891ED +:10117000284608A900F0F8FECCE7284600F02AFD32 +:10118000C0E7284600F054FC8346002844D100F014 +:1011900099F9484B1A6890423ED300F093F90446FF +:1011A000FFF79CFA4FF4C872B0FBF2F101FB12009A +:1011B0008DF820B0DFF800B13E4B04F5167480B214 +:1011C0009BF8001004441C6011B901238DF82030F5 +:1011D00050460791FFF79AFA07990DF12100C1F1E6 +:1011E0001004E4B2062C28BF06245144224600F025 +:1011F000D7F808AB039318230293304B01340193C3 +:101200000123E4B2009332463B462846049400F0A2 +:1012100011FC00238BF8003000F054F9284A294CC7 +:101220001368C31AB3F57A7F31D3106000F04CF91C +:1012300002460B46284600F0D7FC284600F0F8FB93 +:1012400028B3237BDFF880B0002B14BF03230223D5 +:101250008BF8053000F036F94FF47A73B0FBF3F0F9 +:101260005146CBF800005846FFF7F2FA18230293D4 +:10127000164B0730019340F25513C0F3CF00CDE970 +:1012800003A0009342464B46284600F0D3FB237B45 +:101290002BB1FFF74BFA237B002B7FF4FAAE13B090 +:1012A000BDE8F08F44210020882200205522002034 +:1012B00000080140402100203D2100203C21002069 +:1012C00050220020702100202C11002054220020E8 +:1012D000401DA12026812A0BF1C6A7C1D068080FA6 +:1012E00070B501F0BFFF0024084E094D308028681A +:1012F0003388834208D901F0B1FF2B6804440133DD +:10130000B4F5C84F2B60F2D370BD00BF842200201B +:101310005822002002F044B800F10060920000F56D +:10132000C84001F0DFBF0000054B1A68054B1B8861 +:101330009B1A834202D9104401F090BF00207047ED +:10134000582200208422002038B50446064D286823 +:10135000204401F089FF28B928682044BDE83840BE +:1013600001F094BF38BD00BF58220020064991F813 +:10137000243033B100230822086A81F82430FFF7B3 +:10138000CBBF0120704700BF5C220020022802BFB3 +:101390004FF48012014B1A61704700BF00080140F2 +:1013A000002310B5934203D0CC5CC4540133F9E759 +:1013B00010BD000003460246D01A12F9011B002995 +:1013C000FAD1704703460244934202D003F8011B4E +:1013D000FAE770472DE9F8431F4D144695F824208D +:1013E0000746884652BBDFF870909CB395F82430CE +:1013F0002BB92022FF2148462F62FFF7E3FF95F823 +:1014000024004146C0F10802A24228BF224605EB53 +:101410008000D6B29200FFF7C3FF95F82430A41BDA +:101420001E44F6B2082E17449044E4B285F82460B6 +:10143000DBD1FFF79BFF0028D7D108E02B6A03EB35 +:1014400082038342CFD0FFF791FF0028CBD1002049 +:10145000BDE8F8830120FBE75C2200200FB40020E8 +:1014600004B07047EFF30983EFF30583044B9A6BE5 +:10147000DA6A9A6A9A6A9A6A9A6A9A6A9B6AFEE72A +:1014800000ED00E0EFF30983EFF30583044B9A6B63 +:101490009A6A9A6A9A6A9A6A9A6A9B6AFEE700BF8F +:1014A00000ED00E0EFF30983EFF30583034B5A6B84 +:1014B0009A6A9A6A9A6A9A6A9B6AFEE700ED00E065 +:1014C000FEE7000001F0A6BF01F07EBF30B5094D78 +:1014D0000A4491420DD011F8013B5840082340F3D3 +:1014E0000004013B2C4013F0FF0384EA5000F6D1C6 +:1014F000EFE730BD2083B8ED4FF0FF33F7B500EBD9 +:1015000081061946DFF848C0DFF848E0B0421BD03A +:1015100050F8042B01AF0192042217F8014B81EA25 +:10152000046108240D46DB184941013C002DBCBF75 +:1015300083EA0C0381EA0E0114F0FF04F2D1013AB0 +:1015400012F0FF02E9D1E1E7D843C94303B0F0BD8F +:101550009336EAA9EBE1F0422DE9F041C56915B9EE +:10156000C161BDE8F0814B68AC4623F06047C3F32E +:101570008A4616EA230638BF3E464FEAD37EC3F3B7 +:1015800080782B465A68BEEBD27F22F060440AD0A6 +:10159000002A18DAA40CB44217D19D420FD10D6075 +:1015A000DEE71346EEE7A74207D102F08044C2F31C +:1015B000807242450BD054B1EFE708D2EDE7CCF88A +:1015C00000100B60CDE7B44201D0B442E5D81A68F0 +:1015D0009C46002AE5D11960C3E700002DE9F047D9 +:1015E0004FF47F49089D01F007044FEAD5082244D3 +:1015F00005F0070500EBD100944201D1BDE8F0876A +:1016000004F0070705F0070A57453E4638BF56461F +:10161000111BC6F108068E4228BF0E46E108415C48 +:1016200008EBD50E13F80EC0B94029FA06F721FAD7 +:101630000AF1FFB28CEA010147FA0AF739408CEA55 +:10164000010C03F80EC034443544D5E7082341F2B9 +:10165000210280EA012001B24000002980B203F19A +:10166000FF33B8BF504013F0FF03F4D170470000C0 +:1016700038B50C468D18A54200D138BD14F8011BB1 +:10168000FFF7E4FFF7E700000346006848B102688F +:1016900019891A60DA88013292B29142DA8038BF31 +:1016A0001A81704770B504460D4688B0202200218B +:1016B0006846FFF787FE20460495FFF7E5FF0246E0 +:1016C00058B16B46054608AE1C4603CCB4422860B0 +:1016D0006960234605F10805F6D1104608B070BDD3 +:1016E000082817D909280CD00A280CD00B280CD0B0 +:1016F0000C280CD00D280CD00E2814BF4020302010 +:1017000070470C2070471020704714207047182035 +:101710007047202070470000082817D90C280CD9E2 +:1017200010280CD914280CD918280CD920280CD929 +:1017300030288CBF0F200E207047092070470A20E8 +:1017400070470B2070470C2070470D207047000039 +:1017500010B54B6823B9CA8A63F30902CA8210BD67 +:10176000C4681A681C60C360438A013B43824A60B4 +:10177000EFE700002DE9F84F1D46CB8A0F46C3F373 +:1017800009010629814692460B4630D00020AAB2B4 +:1017900007F119049EB2052E1FFA80F80FD8904564 +:1017A00003F1010306D3FB8A0A4462F30903012013 +:1017B000FB821AE01AF800600130E654EAE790452F +:1017C000F1D21C23A1F1060BBBFBF3F203FB12BB0E +:1017D0007C681FFA8BF6002C45D14846FFF754FF72 +:1017E000044638B978606FF00200BDE8F88F4FF01A +:1017F0000008E6E70026066078604FF0000BADB207 +:10180000454510D90AEB0803221D13F8011B08F106 +:1018100001089155B1B21B291FFA88F82BD0454514 +:1018200006F10106F1D8FB8AC3F30902154465F3FA +:101830000903BCE71C46013292B22368002BF9D1A0 +:10184000AB1F0B441C21B3FBF1F301339BB29A4253 +:10185000D3D2BBF1000FD0D14846FFF715FF20B916 +:10186000C4F800B0BFE70122E7E7C0F800B05E4669 +:1018700020600446C1E74545D5D94846FFF704FF37 +:1018800008B92060AFE7C0F800B000262060044629 +:10189000B6E700002DE9F04F85B007469146CDE947 +:1018A0000113BDF83C50002A00F08F802DB10E9B33 +:1018B000002B00F08A80072D30D807F10C00FFF7CD +:1018C000E3FE044628B96FF00204204605B0BDE8E7 +:1018D000F08F14220021FFF775FD2A460E9904F1BE +:1018E0000800FFF75DFD681CC0B2FFF715FFFFF7AA +:1018F000F7FE207499F80020431E9BB202F01F02ED +:10190000234462F03F021A72019B384643F00041C3 +:1019100061602146FFF720FE0124D6E74FF0000862 +:101920004FF0800A4646444600F10C0303930398A7 +:10193000FFF7AAFE83460028C5D014220021FFF736 +:1019400041FD002E38D10220029BABF808300E9BDF +:1019500000F10802D2B299195A440130C0B20828E5 +:1019600001D0AE422AD3FFF7D7FEFFF7B9FEAE4251 +:1019700008BF4FF0400A99F80020019B411E02F079 +:101980001F0242EA4812C9B24AEA020A594443F025 +:10199000004281F808A08BF8100059463846CBF871 +:1019A0000420FFF7D9FD0134AE424FF0000A24B203 +:1019B00088F00108BBD188E70020C8E711F801CB07 +:1019C000013602F801CBB6B2C7E76FF001047CE73D +:1019D000F8B5044615460E46282200211F46FFF79B +:1019E000F1FC069BB5F5001F6360079B28BF4FF60F +:1019F000FF7223624FF0000338BF6A09A76004F149 +:101A00000C0097B29A4205D80023036027826382B4 +:101A1000A382F8BD0660013330462036F2E70000AD +:101A200003781BB94BB2002BC8BF01707047000090 +:101A3000007870472DE9F74FDDF83C9080469246DC +:101A40009B46BDF830500D9E9DF83840BDF8407063 +:101A5000B9F1000F01D1002F51D11F2C4FD898F8A8 +:101A60000000B0B9072F47D835F0030347D13A46F5 +:101A700049464FF6FF70FFF7FBFD20F001002D02F5 +:101A8000400445EA0464400C44EA40244FF6FF73E6 +:101A900021E040EA0520072F40EA0464F6D900253A +:101AA0004FF6FF73C5F12000A5F120022AFA05F1D7 +:101AB0000BFA00F001432BFA02F211431846C9B2A7 +:101AC000FFF7C4FD0835402D0346EBD13A464946A1 +:101AD000FFF7CEFD0346324621464046CDE900974A +:101AE000FFF7D8FE33780133DBB21F2B88BF00230A +:101AF000337003B0BDE8F08F6FF00300F9E76FF0CB +:101B00000100F6E72DE9F04F85B0DDF848809246F8 +:101B100006469B460F9D9DF840209DF84490BDF8D9 +:101B20004C70B8F1000F01D1002F48D11F2A46D8C0 +:101B30003378002B46D00C0244EA02649DF838103A +:101B400044EAC93444EA01441C43072F44F08004AA +:101B500032D900234FF6FF72C3F1200CA3F120000D +:101B60002AFA03F10BFA0CFC41EA0C012BFA00F003 +:101B70000143C9B210460393FFF768FD039B024679 +:101B80000833402BE8D13A464146FFF771FD034642 +:101B90002A4621463046CDE90087FFF77BFEB9F1A2 +:101BA000010F06D12B780133DBB21F2B88BF002336 +:101BB0002B7005B0BDE8F08F4FF6FF73E8E76FF0CC +:101BC0000100F6E76FF00300F3E70000C06900B121 +:101BD00004307047C3691A68C261C2681A60C36082 +:101BE000438A013B438270472DE9F041D0F81880C9 +:101BF00014461D4641460027174E09B9BDE8F0813D +:101C0000D1E90223A21A65EB0303964277EB0303A3 +:101C10001ED283698B420DD1FFF79AFD83691B6841 +:101C20008361C3680B60438AC1608169013B884658 +:101C30004382E2E7FFF78CFD0B68C8F80030C36809 +:101C40000B60438AC160013B4382D8F80010D4E79F +:101C500088460968D1E700BF80841E002DE9F04F57 +:101C60008BB00D4614469B468046DDF85090002808 +:101C700000F01A81B9F1000F00F01681531E3F2BBE +:101C800000F21281012A03D1BBF1000F40F00C8158 +:101C90000023CDE90833B8F81430B5EBC30F4FEA91 +:101CA000C30703D300200BB0BDE8F08F2B199F4270 +:101CB000D8F80C3036BF7F1B2746FFB21BB9D8F8C7 +:101CC0001030002B7BD02F2D4ED8C5F13006B742F7 +:101CD0004FF0000334BF3E46F6B200932946324629 +:101CE000D8F8080008ABFFF779FCA7EB060A3544E3 +:101CF0005FFA8AFA3021B8F8143003F10053063B3A +:101D0000DB000493D8F80C300393039B13B1BAF1B2 +:101D1000000F2CD1D8F8100040B1BAF1000F05D057 +:101D20005246009608AB691AFFF758FC38B2002FEC +:101D3000B8D066070AD00AAB03EBD40111F8083C0F +:101D4000624202F00702134101F8083C082C3DD919 +:101D5000102C40F2B680202C40F2B880BBF1000F6E +:101D600000F09D80082335E0BA460026C2E7049BB8 +:101D7000E02B28BFE02306930B44AB42059315D913 +:101D80005A1B924538BF5246039828BFD2B20096DC +:101D9000691A08AB04300792FFF720FC079A164433 +:101DA000AAEB020A1544F6B25FFA8AFA049B069A75 +:101DB00005999B1A0493039B1B680393A5E7009363 +:101DC0003A462946D8F8080008ABADE7BBF1000F4A +:101DD00013D00123B4EBC30F6CD0082C12D89DF89C +:101DE0002030621E23FA02F2D50706D54FF0FF32EB +:101DF00002FA04F423438DF820309DF8203089F84E +:101E0000003050E7102C12D8BDF82030621E23FAA3 +:101E100002F2D10706D54FF0FF3202FA04F4234351 +:101E2000ADF82030BDF82030A9F800303BE7202C79 +:101E30000FD80899631E21FA03F3DA0705D54FF08E +:101E4000FF3202FA04F40C430894089BC9F80030EE +:101E500029E7402C2BD0DDE90865611EC4F1210281 +:101E6000A4F1210326FA01F105FA02F225FA03F39F +:101E700011431943CB0712D50122A4F12003C4F169 +:101E8000200102FA03F322FA01F1A240524243EA8E +:101E9000010363EB430332432B43CDE90823DDE920 +:101EA0000823C9E90023FEE66FF00100FBE66FF0AE +:101EB0000800F8E6082CA0D9102CB3D9202CEED8B5 +:101EC000C3E7BBF1000FADD0022383E7BBF1000FE6 +:101ED000BBD004237EE70000012A30B5144638BF8A +:101EE00001220025402A28BF402285B0012CCDE9DF +:101EF000025517D81B788DF8083053070AD004AB69 +:101F000003EBD20515F8083C544204F00704A34043 +:101F100005F8083C0346009102A80021FFF75EFB8C +:101F200005B030BD082CE5D9102C03D81B88ADF8BE +:101F30000830E2E7202C02D81B680293DDE7D3E9E2 +:101F40000045CDE90245D8E710B5CB681BB98B60D9 +:101F50000B618B8210BDC4681A681C60C360438A21 +:101F6000013B4382CA60F0E72DE9F04FD1F80080D1 +:101F700093B018F0800FCDE90323C8F3C01207BF58 +:101F80004FF0020B1646C8F3C03BC8F30626B8F163 +:101F9000000F04460D4680F2D48118F0C04305932B +:101FA00040F0CF810B7B002B00F0CB81BBF1020F07 +:101FB00003D00178B14240F0C78108F07F0107915A +:101FC0007AB3C8F3074A2B4493F80390760646EA9F +:101FD0000B4608F07F0246EA82465FEAD91346EADA +:101FE0000A06069300F0918000220023CDE90A231F +:101FF00008F07F03009352465B46204667680AA9B3 +:10200000B84700287ED0A7699FB9314604F10C007B +:10201000FFF748FB0746E0B96FF0020013B0BDE8D8 +:10202000F08FC8F30F2A18F07F0F08BF0AF0030AD9 +:10203000C9E73B699E420DD03F68002FF9D1314678 +:1020400004F10C00FFF72EFB07460028E4D0A3693B +:102050003B60A7610026DDE90A234FF6FF70C6F159 +:10206000200E22FA06F103FA0EFEA6F1200C23FA46 +:102070000CFC41EA0E0141EA0C01C9B20836099292 +:102080000893FFF7E3FADDE90832402EE7D1B88282 +:10209000FB7D09F01F06C3F384039B1B98B2002B42 +:1020A000BCBF00F120031BB2D7E9022152EA0100B4 +:1020B000C8F304680FD00398821A049860EB0101FA +:1020C000A74890424FF000028A4104D3069A002AA2 +:1020D0005BD0012B23DDFA7D4FEA890302F0030276 +:1020E00003F07C031343FB7539462046FFF730FBB2 +:1020F000069BA3B9FB7DC3F38402013262F386031E +:10210000FB7504E06FF00B0088E7A76917B96FF063 +:102110000C0083E73B699E42BAD03F68F6E719F0AE +:10212000400F32D0039B1422BB60049B0021FB6054 +:102130000DA8FFF747F9039B20460A93049BADF8CF +:102140003EA00B932B1D0C932B7B8DF840B0013BD5 +:10215000DBB2ADF83C30079B8DF841608DF8433021 +:1021600094F824308DF8428083F001038DF84430D8 +:102170000AA9A3689847FB7DC3F38403013303F0E6 +:102180001F039B02FB82002048E7FB7DC9F340123E +:10219000B2EBD31F40F0DB80C3F38403B34240F0C3 +:1021A000D98006992B7B4FEA9912002934D0D207A7 +:1021B00041D4032B40F2D180039BAE1DBB60049B36 +:1021C0003246FB602B7B3946033BDBB204F10C004B +:1021D000FFF7D0FA00280DDA20463946FFF7B8FAA3 +:1021E000FB7D0320C3F38403013303F01F039B0231 +:1021F000FB8213E7AB883B832A7B033AB88AD2B2CF +:102200003146FFF735FAFB7DB882DA43C2F3C012DC +:1022100062F3C713FB75B6E76AB92E1D013B324660 +:102220003946DBB204F10C00FFF7A4FA0028D3DB37 +:102230002A7B013AE2E7F98A013BC1F3090105294A +:10224000DAB25BD80023281D07F11A0C9A4208D98C +:1022500010F801EB01330CF801E001310629DBB283 +:10226000F4D1934228BF0023039938BF04330A9165 +:10227000049938BFDBB20B9107F11A010C91796810 +:1022800038BF5B190D910E93FB8AADF83EA0C3F3E6 +:1022900009031A44079BADF83C208DF8433094F8AD +:1022A00024308DF840B083F001038DF844300023D2 +:1022B0008DF841608DF842807B602A7BB88A013AB4 +:1022C000291DFFF7D5F93B8BB882834203D1204605 +:1022D000A3680AA9984720460AA9FFF735FEFB7DA7 +:1022E000B88AC3F38403013303F01F039B02FB820C +:1022F0003B8B984214BF112000208FE67B68002B97 +:10230000AFD0062001E063461C30D3F800C0BCF11A +:10231000000FF8D1091A081D05F1040C1844DDF866 +:1023200014E09DF814308E44BEF11B0F99D89A42E8 +:1023300097D91CF8013B00F8013B059B013305933D +:10234000EDE76FF0090069E66FF00A0066E66FF0EE +:102350000D0063E66FF00E0060E66FF00F005DE6C3 +:1023600080841E00F0B53F4D3F4FEB6943F0007392 +:10237000EB61EB693D4B9B6AD3F800623E4046F04F +:102380000106C3F80062D3F800423C4044EA00244E +:1023900044F00104C3F80042002955D0002006464D +:1023A000C3F81C02C3F80402C3F80C02C3F81402F9 +:1023B00003EBC00401300E28C4F84062C4F8446244 +:1023C000F6D100274FF0010C9678148816F0010F13 +:1023D00018BFD3F804E20CFA04F01CBF40EA0E0E5A +:1023E000C3F804E216F0020F18BFD3F80CE203EBB7 +:1023F000C4041CBF40EA0E0EC3F80CE2760748BFC7 +:10240000D3F8146207F1010744BF0643C3F814620E +:102410005668B942C4F84062966802F10C02C4F8EA +:102420004462D3F81C4240EA0400C3F81C02CBD13A +:10243000D3F8002222F00102C3F80022EB6923F056 +:102440000073EB61EB69F0BD0122C3F84012C3F8E1 +:102450004412C3F80412C3F81412C3F80C22C3F8D0 +:102460001C22E5E7001002400000FFFF8822002048 +:10247000184A08B5916A8B688B6013F0010104D08B +:1024800013F00C0F18BF4FF48031D80506D513F4A4 +:10249000406F14BF41F4003141F00201D80306D56A +:1024A00013F4402F14BF41F4802141F00401D3699B +:1024B0000BB108489847202383F311880021064870 +:1024C00000F01EFE002383F31188BDE8084001F0F0 +:1024D00083B800BF882200209022002038B5124C1B +:1024E000A36ADD68AA0712D05A6922F002025A6173 +:1024F000A36913B1012120469847202383F3118853 +:1025000000210A4800F0FCFD002383F31188EB064C +:1025100006D51021A36AD960236A0BB102489847F7 +:10252000BDE8384001F058B88822002098220020E9 +:1025300038B5124CA36A1D69AA0712D05A6922F055 +:1025400010025A61A36913B1022120469847202343 +:1025500083F3118800210A4800F0D2FD002383F3A1 +:102560001188EB0606D51021A36A1961236A0BB105 +:1025700002489847BDE8384001F02EB88822002074 +:102580009822002038B50F4CA36A5D682A075D6069 +:102590000AD5042222701A6822F002021A60636AC5 +:1025A00013B10021204698476B0706D5A36A9969A5 +:1025B000236A13B1034809049847BDE8384001F085 +:1025C0000BB800BF8822002010B50E4C204600F04A +:1025D000FDF90D4B0B211320A36200F0D7F90B215D +:1025E000142000F0D3F90B21152000F0CFF90B21B6 +:1025F000162000F0CBF9BDE8104000220E20114655 +:10260000FFF7B0BE88220020006400400F4B10B5D9 +:102610009842044605D10E4BDA6942F00072DA6145 +:10262000DB690122A36A1A60A36A5A68D20707D538 +:10263000626851681268D9611A60064A5A6110BD11 +:102640000121082000F052FCEEE700BF88220020A4 +:10265000001002405B87010003291AD8DFE801F06F +:10266000020A0F14836A9B6813F0E05F14BF012015 +:1026700000207047836A9868C0F380607047836A5F +:102680009868C0F3C0607047836A9868C0F30070B0 +:10269000704700207047000010B5032927D8DFE8F5 +:1026A00001F002272B2F836A9968C1F30161183169 +:1026B00003EB01131078840648BF5468C0F300117F +:1026C00058BF94884FEA410148BF41EAC40100F075 +:1026D0000F00586048BF41F00401906858BF41EABC +:1026E0004451D26841F001019860DA60196010BD70 +:1026F000836A03F5C073DDE7836A03F5C873D9E71E +:10270000836A03F5D073D5E701290AD002290FD0D7 +:1027100081B9836ADA68920701D1186903E0012060 +:102720007047836AD86810F0030018BF0120704713 +:10273000836AF2E70020704710B539B9836AD96817 +:1027400089071BD11B699C0704D110BD012915D035 +:102750000229FAD1816AD1F8C031D1F8C441D1F847 +:10276000C8011061D1F8CC015061202008610869CE +:10277000800717D1486940F0100012E0816AD1F853 +:10278000B031D1F8B441D1F8B8011061D1F8BC0131 +:1027900050612020C860C868800703D1486940F0B4 +:1027A00002004861C3F34000C3F38001000140EA26 +:1027B0004111107920F030000143117189064BBF9F +:1027C00091681189DB085B0D4CBF63F31C0163F357 +:1027D0000A01137948BF916064F3030313714FEA50 +:1027E00014234FEA144458BF118113705480ACE78E +:1027F000026843680A43026003B11847704700004B +:10280000024AD36843F0C003D360704700380140E8 +:10281000024AD36843F0C003D360704700440040CD +:102820002DE9F041D0F89C600446F7683368DA057A +:102830009DB20DD5202383F311884FF4007104302D +:10284000FFF7D6FF6FF480733360002383F31188A2 +:10285000202383F3118804F1040815F02F033AD1E3 +:1028600083F31188380615D5290613D5202383F361 +:10287000118804F1380000F02FFA00284DDA082101 +:10288000201DFFF7B5FF4FF67F733B40F360002339 +:1028900083F311887A0616D56B0614D5202383F3AB +:1028A0001188D4E913239A420AD1236C43B127F04B +:1028B00040073F041021201D3F0CFFF799FFF760F0 +:1028C000002383F31188D4F8A420D3683BB3BDE878 +:1028D000F041106918472B0713D015F0080F0CBFF3 +:1028E00000218021E80748BF41F02001AA0748BF26 +:1028F00041F040016B07404648BF41F48071FFF74B +:1029000077FFAD06736805D594F8A01020461940EE +:1029100000F082FA3568ADB29FE77060B7E7BDE8B6 +:10292000F081000008B50348FFF77AFFBDE80840D2 +:1029300000F052BEB422002008B50348FFF770FF34 +:10294000BDE8084000F048BE5C23002010B5094CEB +:1029500000212046084A00F03FFA084B0021C4F845 +:102960009C30074C074A204600F036FA064BC4F864 +:102970009C3010BDB422002001280008003801401E +:102980005C230020112800080044004001220901B6 +:1029900000F1604303F56143C9B283F8001300F00E +:1029A0001F039A4043099B0003F1604303F5614311 +:1029B000C3F880211A607047090100F16040C9B274 +:1029C00000F56D4001767047FFF7FEBD01230370EF +:1029D000002300F10802C0E9022200F11002C0E960 +:1029E0000422C0E90633C0E90833436070470000A1 +:1029F00010B52023044683F311880223416003703D +:102A0000FFF704FE04232370002383F3118810BD15 +:102A10002DE9F0411F4604460D461646202383F358 +:102A2000118800F108082378052B0DD0294620468F +:102A3000FFF712FE40B1204632462946FFF72CFE32 +:102A4000002080F3118808E03946404600F03CFB46 +:102A50000028E8D0002383F31188BDE8F08100004E +:102A60002DE9F0411F4604460D461646202383F308 +:102A7000118800F110082378052B0DD02946204637 +:102A8000FFF742FE40B1204632462946FFF754FE8A +:102A9000002080F3118808E03946404600F014FB1E +:102AA0000028E8D0002383F31188BDE8F0810000FE +:102AB000F8B5154682680B46AA428169066938BF97 +:102AC0008568761AB54204460BD218462A46FEF7A8 +:102AD00067FCA3692B44A361A36828465B1BA36022 +:102AE000F8BD0CD918463246FEF75AFCAF1B3A46E1 +:102AF000E1683044FEF754FCE3683B44EBE71846DA +:102B00002A46FEF74DFCE368E5E700002DE9F041B9 +:102B1000154683680446934238BF8568D0E904703F +:102B20003F1ABD420E460BD22A46FEF739FC6369B6 +:102B30002B446361A36828465B1BA360BDE8F0815A +:102B40000CD93A46A5EB0708FEF72AFC4246E06896 +:102B5000F119FEF725FCE3684344EAE72A46FEF74D +:102B60001FFCE368E5E7000010B50024C361029B89 +:102B7000C0E90511C1601144C0E900008460016131 +:102B8000036210BD08B5D0E90532934201D18268D5 +:102B900092B98268013282605A1C42611970D0E990 +:102BA00004329A4228BFC3684FF0000128BF436136 +:102BB00000F09AFA002008BD4FF0FF30FBE700005C +:102BC00070B5202304460D4683F31188A668A6B18C +:102BD000A368A269013BA360531CA3611578226915 +:102BE000934224BFE368A361E3690BB12046984791 +:102BF000002383F31188284607E02946204600F089 +:102C000063FA0028E2DA86F3118870BD2DE9F74FE8 +:102C100004460E4617469846D0F81C904FF0200AFE +:102C20008AF311884FF0000B154665B12A463146EC +:102C30002046FFF73DFF034660B94146204600F0BD +:102C400043FA0028F1D0002383F31188781B03B0E6 +:102C5000BDE8F08FB9F1000F03D001902046C847BE +:102C6000019B8BF31188ED1A1E448AF31188DCE76F +:102C7000C361009BC0E90511C1601144C0E90000B7 +:102C80008260016103627047F8B504460D4616463E +:102C9000202383F31188A768A7B1A368013BA36031 +:102CA00063695A1C62611D70D4E904329A4224BFE0 +:102CB000E3686361E3690BB120469847002080F325 +:102CC000118807E03146204600F0FEF90028E2DADC +:102CD00087F31188F8BD0000D0E905239A4210B5AA +:102CE00001D182687AB982680021013282605A1C5F +:102CF00082611C7803699A4224BFC368836100F033 +:102D0000F3F9204610BD4FF0FF30FBE72DE9F74FF8 +:102D100004460E4617469846D0F81C904FF0200AFD +:102D20008AF311884FF0000B154665B12A463146EB +:102D30002046FFF7EBFE034660B94146204600F00F +:102D4000C3F90028F1D0002383F31188781B03B066 +:102D5000BDE8F08FB9F1000F03D001902046C847BD +:102D6000019B8BF31188ED1A1E448AF31188DCE76E +:102D7000026843680A43026003B1184770470000C5 +:102D80001430FFF743BF00004FF0FF331430FFF75C +:102D90003DBF00003830FFF7B9BF00004FF0FF33F0 +:102DA0003830FFF7B3BF00001430FFF709BF000051 +:102DB0004FF0FF311430FFF703BF00003830FFF74A +:102DC00063BF00004FF0FF323830FFF75DBF0000F7 +:102DD00000207047FFF7BABD37B515460D4A0446C7 +:102DE000026000224260C0E9022201220B46027406 +:102DF00000F15C01009020221430FFF7B5FE2B4655 +:102E00002022009404F17C0104F13800FFF730FF28 +:102E100003B030BD483B000838B5C36904460D46D1 +:102E20001BB904210844FFF7A3FF294604F114004D +:102E3000FFF7A8FE002806DA201D4FF48061BDE8E8 +:102E40003840FFF795BF38BD0022024BC3E900337D +:102E50009A60704704240020002382680374054BA5 +:102E60001B6899689142FBD25A6803604260106007 +:102E7000586070470424002008B5202383F311888C +:102E8000037C032B05D0042B0DD02BB983F31188C1 +:102E900008BD002243691A604FF0FF334361FFF71A +:102EA000DBFF0023F2E7D0E9003213605A60F3E75A +:102EB000002382680374054B1B6899689142FBD814 +:102EC0005A68036042601060586070470424002014 +:102ED000054B196908741868026853601A60186114 +:102EE00001230374FDF732BB0424002030B54B1CD2 +:102EF00004460B4D87B010D02B690A4A01A800F098 +:102F00001BF92046FFF7E4FF049B13B101A800F072 +:102F10002FF92B69586907B030BDFFF7D9FFF8E7E3 +:102F200004240020792E000838B50C4D41612B692E +:102F300081689A680446914203D8BDE83840FFF79B +:102F40008BBF1846FFF7B4FF01232C6101462374A1 +:102F50002046BDE83840FDF7F9BA00BF0424002040 +:102F6000044B1A681B6990689B68984294BF0020C4 +:102F7000012070470424002010B5084C2368206904 +:102F80001A6854602260012223611A74FFF790FFCF +:102F900001462069BDE81040FDF7D8BA042400209E +:102FA00008B5FFF7DDFF18B1BDE80840FFF7E4BF43 +:102FB00008BD0000FFF7E0BFFEE7000010B50C4CB5 +:102FC000FFF742FF00F0AAF880220A49204600F0ED +:102FD00031F8012344F8180C037400F0D9FA0023E7 +:102FE00083F3118862B6BDE81040034800F042B890 +:102FF0002C240020703B0008803B000800F0CAB879 +:10300000EFF3118020B9EFF30583202282F31188BA +:103010007047000010B530B9EFF30584C4F308041D +:1030200014B180F3118810BDFFF7BAFF84F3118843 +:10303000F9E7000082600222028270478368A3F1F0 +:103040003C0243F80C2C026943F83C2C426943F8DB +:10305000382C074A43F81C2CC268A3F1180043F827 +:10306000102C022203F8082C002203F8072C7047CA +:103070005D05000810B5202383F31188FFF7DEFFFC +:1030800000210446FFF750FF002383F311882046F8 +:1030900010BD0000024B1B6958610F20FFF718BFDD +:1030A00004240020202383F31188FFF7F3BF0000DE +:1030B00008B50146202383F311880820FFF716FF87 +:1030C000002383F3118808BD49B1064B42681B6990 +:1030D00018605A60136043600420FFF707BF4FF089 +:1030E000FF3070470424002003460068834205D067 +:1030F00002681A6053604161FFF7AEBE704700007E +:1031000038B504460D462068844200D138BD0368B6 +:1031100023605C604561FFF79FFEF4E7054B03F118 +:103120001402C3E905224FF0FF32DA6100221A626D +:10313000704700BF0424002010B5C0E903230B4AE8 +:10314000136A53699C68A1420CD85C688160036073 +:103150004460206058609868411A99604FF0FF33CE +:10316000D36110BD1B68091BECE700BF04240020DD +:10317000036881689A680A449A60426813605A60DA +:1031800000234FF0FF32C360014BDA61704700BF8C +:103190000424002038B50F4C2246236A01332362F1 +:1031A00052F8143F934206D020259A68013A9A605B +:1031B00063699A6802B138BDD3E9001001604860C4 +:1031C000D968DA6082F311881869884785F3118815 +:1031D000EEE700BF0424002000207047FEE7000057 +:1031E000704700004FF0FF3070470000BFF34F8F73 +:1031F000024AD368DB07FCD4704700BF00200240BE +:1032000008B5074B1B7853B9FFF7F0FF054B1A6958 +:10321000120641BF044A5A6002F188325A6008BD62 +:1032200008250020002002402301674508B5054B12 +:103230001B7833B9FFF7DAFF034A136943F08003C1 +:10324000136108BD08250020002002407F289ABF96 +:1032500000F5003080020020704700004FF48060CD +:1032600070470000802070477F2808B50BD8FFF713 +:10327000EDFF00F580630268013204D1043083421F +:10328000F9D1012008BD0020FCE700007F2838B5F7 +:10329000044623D8FFF7B4FEFFF7A8FFFFF7B0FFFF +:1032A000F3220F4B0546DA60022220461A61FFF72F +:1032B000CDFF58611A694FF4806142F040021A61F3 +:1032C000FFF794FF00F010F92846FFF7AFFFFFF774 +:1032D000A1FE2046BDE83840FFF7C6BF002038BD3C +:1032E000002002402DE9F047044612F001000E468E +:1032F000154606D040F2BD22234B1A600020BDE8DF +:10330000F087224BA2189A4204D940F2C2221E4BE7 +:103310001A60F4E7FFF774FE4FF0010AFFF770FF41 +:10332000FFF764FFDFF868903146A61B012D884641 +:1033300006EB010705D8FFF779FFFFF76BFE0120C9 +:10334000DDE7B8F80030C9F810A03B800024FFF793 +:103350004DFFC9F810403B8831F8022B9BB29A42CE +:103360000FD040F2D922084B1A600A4B1F600A4B5B +:103370001D600A4BC3F80080FFF758FFFFF74AFEB5 +:10338000BCE7023DD2E700BF042500200000020890 +:1033900000200240F824002000250020FC2400200A +:1033A000084908B50B7828B11BB9FFF729FF01239D +:1033B0000B7008BD002BFCD0BDE808400870FFF77B +:1033C00035BF00BF0825002070B5FFF719FE4FF488 +:1033D0007A710D4B0D4E1B6A326801FB03F3934269 +:1033E00037BF0B4A0A495168156836BF4C1CD1E9F2 +:1033F000005454605D1944F100043360FFF70AFE85 +:103400002846214670BD00BF042400200C25002062 +:103410001025002070B5FFF7F3FD4FF47A710F4BC4 +:103420000F4E1B6A326801FB03F3934237BF0D4A0C +:103430000C49516815683ABF4C1C5460D1E90054DE +:103440005D1944F100043360FFF7E4FD4FF47A7234 +:10345000002328462146FCF783FE70BD042400208B +:103460000C2500201025002010B5094C013AD2B2DD +:10347000FF2A00D110BD500854F82030013054F814 +:1034800020009BB243EA004341F8043BEEE700BF53 +:10349000046C004010B50748013AD2B2FF2A00D1AF +:1034A00010BD0C88530840F823404C88013340F885 +:1034B0002340F1E7046C004007B50122002001A978 +:1034C000FFF7D2FF019803B05DF804FB13B5044683 +:1034D000FFF7F2FFA04205D00122002001A90194CC +:1034E000FFF7D8FF02B010BD7047000045F25552FB +:1034F000064B1A6002225A6040F6FF729A604CF640 +:10350000CC421A600122024B1A7070470030004012 +:103510001C250020034B1B781BB14AF6AA22024B44 +:103520001A6070471C25002000300040044B1A68C8 +:103530002AB902F1804202F50432526A1A607047D9 +:10354000182500204FF08072014B5A62704700BF6F +:103550000010024008B5FFF7E9FF024B1868C0F3FE +:10356000407008BD1825002008B5FFF7DFFF024BAB +:103570001868C0F3007008BD18250020EFF3098318 +:10358000203383F30988002383F3118870470000F8 +:10359000202080F3118862B60C4B0D4AD96821F4C3 +:1035A000E0610904090C0A43DA60D3F8FC200949F8 +:1035B00042F08072C3F8FC200A6842F001020A60FF +:1035C0001022DA7783F82200704700BF00ED00E098 +:1035D0000003FA05001000E0202310B583F31188E2 +:1035E0000B4B5B6813F400630FD0EFF309844FF0CB +:1035F0008073203CE36184F30988FFF7B1FC10B1CC +:10360000044BA36110BD044BFBE783F31188F9E77A +:1036100000ED00E06F05000872050008704700002B +:10362000FEE700000A4B0B480B4A90420BD30B4BB2 +:10363000C11EDA1C121A22F003028B4238BF00228C +:103640000021FDF7BFBE53F8041B40F8041BECE754 +:10365000043C0008A0250020A0250020A025002073 +:103660007047000000F030B808B500F063F9FFF7CC +:10367000A5FCBDE80840FFF759BF000070470000F7 +:103680004FF0FF310E4B1A6919611A6900221A6155 +:103690001869D868D960D968DA60DA68DA6942F0FE +:1036A0008052DA61DA69DA6942F00062DA61054A69 +:1036B000DB69136843F48073136000F01BB900BF2B +:1036C0000010024000700040194B1A6842F00102DD +:1036D0001A601A689007FCD51A6802F0F9021A609D +:1036E00000225A605A6812F00C0FFBD11A6842F49B +:1036F00080321A601A689103FCD55A6842F4E812C5 +:103700005A601A6842F080721A601A689201FCD5F9 +:103710001221084A5A60084A11605A6842F00202AF +:103720005A605A6802F00C02082AFAD1704700BFAA +:103730000010024000641D0000200240084A08B545 +:10374000516913680B4003F00103536123B1054A2B +:1037500013680BB150689847BDE80840FFF73CBFBD +:103760000004014020250020084A08B5516913686B +:103770000B4003F00203536123B1054A93680BB178 +:10378000D0689847BDE80840FFF726BF0004014015 +:1037900020250020084A08B5516913680B4003F042 +:1037A0000403536123B1054A13690BB1506998476B +:1037B000BDE80840FFF710BF0004014020250020AD +:1037C000084A08B5516913680B4003F008035361B8 +:1037D00023B1054A93690BB1D0699847BDE8084009 +:1037E000FFF7FABE0004014020250020084A08B572 +:1037F000516913680B4003F01003536123B1054A6C +:10380000136A0BB1506A9847BDE80840FFF7E4BE61 +:103810000004014020250020174B10B55A691C6890 +:10382000144004F478725A61A30604D5134A936ACB +:103830000BB1D06A9847600604D5104A136B0BB1E0 +:10384000506B9847210604D50C4A936B0BB1D06B93 +:103850009847E20504D5094A136C0BB1506C9847A0 +:10386000A30504D5054A936C0BB1D06C9847BDE80D +:103870001040FFF7B1BE00BF00040140202500202A +:103880001A4B10B55A691C68144004F47C425A6102 +:10389000620504D5164A136D0BB1506D9847230588 +:1038A00004D5134A936D0BB1D06D9847E00404D54D +:1038B0000F4A136E0BB1506E9847A10404D50C4A01 +:1038C000936E0BB1D06E9847620404D5084A136F0B +:1038D0000BB1506F9847230404D5054A936F0BB181 +:1038E000D06F9847BDE81040FFF776BE0004014056 +:1038F00020250020062108B50846FFF747F80621D5 +:103900000720FFF743F806210820FFF73FF80621BC +:103910000920FFF73BF806210A20FFF737F80621B8 +:103920001720FFF733F8BDE8084006212820FFF7ED +:103930002DB8000008B5FFF7A3FE064800F00EF80A +:10394000FFF742F8FFF746FAFFF798FEBDE8084098 +:1039500000F002B8983B000800F042B80023194676 +:103960001C4A0133102BC2E9001102F10802F8D100 +:10397000194B9A6942F07D029A619B690268174B64 +:10398000DA6082685A6042681A60C26803F5806330 +:10399000DA6042695A6002691A608269C3F80C24CD +:1039A000026AC3F80424C269C3F80024426AC3F857 +:1039B0000C28C26AC3F80428826AC3F80028026B84 +:1039C000C3F80C2C826BC3F8042C426BC3F8002C98 +:1039D000704700BF20250020001002400008014071 +:1039E0004FF0E023044A08215A6100229A6107221D +:1039F0000B201A61FEF7E0BF3F19010008B5202334 +:103A000083F31188FFF7FAFA002383F3118808BDC6 +:103A100008B5FFF7F3FFBDE80840FFF7DDBD000084 +:103A200010B501390244904201D1002005E003782D +:103A300011F8014FA34201D0181B10BD0130F2E76D +:103A40002DE9F0419BB10446C91A1778014403F1EE +:103A5000FF3C8C42204601D9002008E00578013463 +:103A6000BD42F6D10CEB0405D618A54201D1BDE844 +:103A7000F08115F8018D16F801EDF045F5D0E8E775 +:103A8000034611F8012B03F8012B002AF9D17047E6 +:103A90006F72672E6172647570696C6F742E6170DD +:103AA0005F7065726970685F677073004E6F206148 +:103AB0007070207369670A00426164206677206C29 +:103AC000656E6774682025750A0042616420626F24 +:103AD0006172645F69642025752073686F756C641A +:103AE0002062652025750A004261642066772064A3 +:103AF000657363726970746F72206C656E67746849 +:103B00002025750A00426164206170702043524391 +:103B1000203078253038783A3078253038782030A1 +:103B200078253038783A3078253038780A00476F71 +:103B30006F64206669726D776172650A0040A2E465 +:103B4000F164689106000000000000009D2D00084F +:103B5000892D0008C52D0008B12D0008BD2D0008D5 +:103B6000A92D0008952D0008812D0008D12D0008F1 +:103B70006D61696E0000000069646C650000000002 +:103B8000783B000848240020F824002001000000B1 +:103B9000B92F0008000000000C1E0000447B4144C7 +:103BA000B45749440100000042444444444444445E +:103BB00000000000444444444444444400000000E5 +:103BC00044444444444444440000000044444444C5 +:103BD00044444444BCC5FF7F0100000000000000D5 +:103BE000E803000000000000009C0100000000004D +:103BF000640000000000000040420F00FE2A0100A7 +:043C0000D2040000EA :00000001FF diff --git a/Tools/bootloaders/f103-QiotekPeriph_bl.bin b/Tools/bootloaders/f103-QiotekPeriph_bl.bin old mode 100644 new mode 100755 index 1fdf322a673..c809ad2c0f1 Binary files a/Tools/bootloaders/f103-QiotekPeriph_bl.bin and b/Tools/bootloaders/f103-QiotekPeriph_bl.bin differ diff --git a/Tools/bootloaders/f103-QiotekPeriph_bl.hex b/Tools/bootloaders/f103-QiotekPeriph_bl.hex index 79019683944..b0e1d4711df 100644 --- a/Tools/bootloaders/f103-QiotekPeriph_bl.hex +++ b/Tools/bootloaders/f103-QiotekPeriph_bl.hex @@ -1,1184 +1,963 @@ :020000040800F2 -:1000000000090020A1040008FD1C0008011D0008D3 -:10001000411D0008011D0008211D0008A30400085F -:10002000A3040008A3040008A3040008A93F0008D3 -:10003000A3040008A3040008A30400083D4300082B -:10004000A3040008A3040008A3040008A3040008F4 -:10005000A3040008A30400081D410008494100084A -:1000600075410008A1410008CD410008A304000823 -:10007000A3040008A3040008A3040008A3040008C4 -:10008000A3040008A3040008A3040008552E0008D8 -:10009000C12E0008152F0008692F0008F94100083B -:1000A000A3040008A3040008A3040008A304000894 -:1000B000A3040008A3040008A3040008A304000884 -:1000C000A3040008A3040008A3040008A304000874 -:1000D000A30400088D330008A1330008A30400081E -:1000E00061420008A3040008A3040008A304000858 -:1000F000A3040008A3040008A3040008A304000844 -:10010000A3040008A3040008A3040008A304000833 -:10011000A3040008A3040008A3040008A304000823 -:10012000A3040008A3040008A3040008A304000813 -:10013000A3040008A3040008A3040008A304000803 -:10014000A3040008A3040008A3040008A3040008F3 -:10015000A3040008A3040008A3040008A3040008E3 -:10016000D0400B1CD1409C46203AD3401843524209 -:1001700063469340184370479140031C90409C464F -:10018000203A9340194352426346D3401943704783 -:1001900053B94AB9002908BF00281CBF4FF0FF31EE -:1001A0004FF0FF3000F07AB9ADF1080C6DE904CEE4 -:1001B00000F006F8DDF804E0DDE9022304B0704742 -:1001C0002DE9F0478C460E460446089D002B50D181 -:1001D0008A4217466CD9B2FA82FEBEF1000F0BD0EC -:1001E000CEF1200C01FA0EF620FA0CFC02FA0EF702 -:1001F0004CEA060C00FA0EF43A0CBCFBF2F9BBB266 -:1002000002FB19CC09FB03FA4FEA144848EA0C46F2 -:10021000B2450AD9F61909F1FF3180F02581B245BE -:1002200040F22281A9F102093E44A6EB0A06B6FB80 -:10023000F2F002FB106600FB03F3A4B244EA0644AA -:10024000A34209D9E41900F1FF3280F00B81A342E7 -:1002500040F2088102383C440021E41A40EA094097 -:10026000002D62D0002324FA0EF42C606B60BDE8F0 -:10027000F0878B4207D9002D55D0002185E8410039 -:100280000846BDE8F087B3FA83F1002940F08F807B -:10029000B34202D3824200F2FC80841A66EB03066A -:1002A0000120B446002D40D085E81010BDE8F0874D -:1002B00012B90127B7FBF2F7B7FA87FEBEF1000FBC -:1002C00035D10121F61B4FEA174C1FFA87F8B6FB10 -:1002D000FCF20CFB126608FB02F0230C43EA064614 -:1002E000B04207D9F61902F1FF3302D2B04200F250 -:1002F000D2801A46361AB6FBFCF00CFB106608FBDF -:1003000000F8A3B243EA0644A04507D9E41900F176 -:10031000FF3302D2A04500F2B9801846A4EB0804CE -:1003200040EA02409CE729462846BDE8F08707FAE4 -:100330000EF7CEF1200326FA03F24FEA174CB2FB78 -:10034000FCF11FFA87F80CFB112206FA0EF620FAD0 -:1003500003F301FB08F933431E0C46EA0246B1459C -:1003600000FA0EF409D9F61901F1FF3280F08C8001 -:10037000B14540F2898002393E44A6EB0906B6FB3E -:10038000FCF00CFB106200FB08F99EB246EA024644 -:10039000B14507D9F61900F1FF3371D2B1456FD9D4 -:1003A00002383E44A6EB090640EA01418FE7C1F15D -:1003B000200722FA07F88B4048EA030326FA07F4DD -:1003C0004FEA134EB4FBFEF91FFA83FC0EFB1944EF -:1003D0008E4020FA07F809FB0CFA48EA06084FEAB3 -:1003E000184646EA0444A24502FA01F200FA01F670 -:1003F00008D9E41809F1FF3044D2A24542D9A9F145 -:1004000002091C44A4EB0A04B4FBFEF00EFB1044EA -:1004100000FB0CFC1FFA88F848EA0444A44507D9FD -:10042000E41800F1FF3E29D2A44527D902381C4424 -:1004300040EA0940A0FB0289A4EB0C0CCC45C24663 -:10044000CE4615D312D055B1B6EB0A036CEB0E06AF -:1004500006FA07F7CB401F43CE402F606E600021A5 -:10046000BDE8F0871046F7E68946DEE64645EAD263 -:10047000B8EB020A69EB030E0138E4E77046D7E7F0 -:1004800018468FE78146BDE7114676E702383C44BF -:1004900044E7084606E7023A3E442BE7704700BFB0 -:1004A00002E000F000F8FEE772B6274880F3088803 -:1004B000264880F3098826484EF60851CEF20001FE -:1004C0000860022080F31488BFF36F8F03F09CFD57 -:1004D00003F0B8FD4FF055301E491B4A91423CBF16 -:1004E00041F8040BFAE71C49184A91423CBF41F815 -:1004F000040BFAE719491A4A1A4B9A423EBF51F8BF -:10050000040B42F8040BF8E700201749174A914200 -:100510003CBF41F8040BFAE703F07AFD03F094FDC9 -:10052000134C144DAC4203DA54F8041B8847F9E726 -:1005300000F0AEFC104C114DAC4203DA54F8041B31 -:100540008847F9E703F062BD000900200011002090 -:100550000000000800010020000900206849000890 -:1005600000110020741100207811002000260020C6 -:1005700060010008600100086001000860010008D7 -:100580002DE9F04FC1F80CD0C3689D46BDE8F08F4F -:10059000002383F311882846A047002003F0F4FAD3 -:1005A00003F01EFA00DFFEE700B50A4C054620689E -:1005B00085B01C46C06852B1074B8DE80A00029214 -:1005C0002B462246054901F093FB00F045FB044B06 -:1005D0001A46F2E7001100201C4900082C490008C7 -:1005E0002849000808B513460022FFF7DDFF00BFC9 -:1005F000032A70B422D940EA01039B0711D0037883 -:100600000C78A3421DD10A44013105E010F8013FE6 -:1006100011F8014BA34214D19142F7D1002070BCD4 -:1006200070470D6806680C46AE42034601F10401AE -:1006300000F1040008D1043A032AF2D8002ADED1DE -:10064000ECE7181B70BC704721461846D7E700BF7F -:100650002DE9F0414FF0010E002574464FF0FF36B2 -:100660002B198B4200EB06070DD23F5D10F803C03B -:10067000BC452DD21D460124A3EB060E2B198B423F -:1006800000EB0607F1D34FF00108002544464FF078 -:10069000FF37C2F800E02B19994200EB070E0ED984 -:1006A0001EF804E010F803C0F44518D91D460124D3 -:1006B000A3EB07082B19994200EB070EF0D801377E -:1006C000701C874224BF3846C2F80080BDE8F08124 -:1006D0000CD04FF0010E2E4674467544C0E70BD087 -:1006E0004FF001082F4644464544D4E7744512BFF5 -:1006F00001341D460124B3E7444512BF01341D46B1 -:100700000124C8E72DE9F04FADF22C4D16460746FF -:100710008A461046194609AA0193FFF799FF8146B8 -:10072000019B09AA0DF2244142F8043F8A42FBD101 -:10073000002B00F0E5805C1E2246711E0DF128089A -:1007400011F8010F48F8202012F1FF32F8D2099970 -:100750004A46314430460193FFF74AFF019B002887 -:1007600070D1099A09F1FF31AAEB03059B1A049392 -:10077000731803920693C9F101023B190195CDF854 -:100780000890864605910792054699460AE020B1F1 -:10079000049A03998B4238BF13461D44019B0020E5 -:1007A000AB4247D319F8053058F82330002BEED16F -:1007B000029B834238BF03469C4213D95A1917F84B -:1007C00002E016F803C03A44F44506EB030106D0F4 -:1007D00035E011F801CF12F801EFF4452FD10133C4 -:1007E0009C42F6D8029B0599834298BF194618D9B6 -:1007F000059B5A19069B17F802C093F800E03A448B -:10080000E64540F082809E4600F1FF3B06E01EF880 -:1008100001AD12F801CDE24503D119464B1E9B45AF -:10082000F5D10130884268D8039B04981D44019B90 -:10083000AB42B7D200200DF22C4DBDE8F08F079AE5 -:100840001544AAE7A3EB09024A4538BF4A4609F115 -:10085000FF3BAAEB030A531C039306EB0B03049321 -:100860003B19CDF804B04FF0000E9B46C9F10102D0 -:1008700006EB090C02921BF80E3058F82330A3BB8C -:100880004C4515D909EB0E02B95C9CF800303A448E -:10089000994218BF4B462CD161464B4605E011F8F2 -:1008A000015F12F8010F854223D101339C42F6D833 -:1008B000019B013312D0019B049803EB0E02BB5C39 -:1008C00001783A4499420FD1034605E013F8010D2F -:1008D00012F8011D884207D1B342F7D107EB0E0091 -:1008E0000DF22C4DBDE8F08F039B9E44F245C2D221 -:1008F000A0E7029A96449E44F8E7AE4678199AE734 -:100900004FF0FF340DF1280821E7029989E700BF75 -:100910002DE9F04F054689B0002B72D08B428B46F3 -:100920001C466DD81F2B6FD890460A4698F80010C9 -:1009300000F09AF98146002862D0012C61D0421B58 -:10094000ABEB0205AC425BD807AA21464046FFF755 -:100950007FFE07998346024641444046FFF748FE22 -:1009600000285CD18446079B0BF1FF3A0393E31AFE -:10097000049308EB0A032A1B0593CBF101030192B0 -:100980000293E3455B4638BF63469C4213D91A186D -:1009900019F8025018F803604A44AE4208EB03010C -:1009A00006D036E011F8016F12F8015FAE4230D187 -:1009B00001339C42F6D1E34551467DD9059E0AEBB1 -:1009C000000219F8025033784A449D4274D13546EA -:1009D0000CF1FF3E06E015F8017D12F8016DB742FB -:1009E00003D119464B1E7345F5D10CF1010C8C4512 -:1009F00054D8039BDDF810C01844019B8342C0D239 -:100A0000002009B0BDE8F08FFFF77CFE09B0BDE81B -:100A1000F08F029A4FF0000C10441844EDE7A4EB5D -:100A20000B035B4538BF5B46002001330BF1FF3CF5 -:100A30000293CBF101032A1B08EB0C0A08EB0B0E07 -:100A400001935C4514D90BEB000119F801509EF895 -:100A5000003049449D4225D175465B4605E015F8B6 -:100A6000017F11F8016FB7421DD101339C42F6D1CD -:100A7000BCF1FF3F12D00CEB000119F801309AF8DD -:100A8000005049449D4214D1534605E013F8016DCE -:100A900011F8015DAE420CD14345F7D1484409B08D -:100AA000BDE8F08F5B460199084418448242C8D2E1 -:100AB000A6E7029B1844F9E7594696E770B5CC1CA7 -:100AC00024F0030408340C2C38BF0C24002C0646F8 -:100AD0003BDBA14239D8274D296851B10B681B1B5C -:100AE00004D436E013681B1B1AD511464A68002A45 -:100AF000F8D16968002937D02146304600F03CF82B -:100B0000431C22D0C51C25F00305A84205D0291A94 -:100B1000304600F031F8013017D02A462C6004E04E -:100B20000B2B0DD913601A44146002F10B0020F056 -:100B30000700131DC31A02D05942D15070BD70BDB9 -:100B40008A420ED053684B60EFE70C2300203360DD -:100B500070BD0B2B03D80A464B682B60E5E70A46AD -:100B6000E0E70B460A46F8E7304600F005F8686013 -:100B7000C2E700BF7811002038B50023064C0546B7 -:100B80000846236003F076F8431C00D038BD236884 -:100B9000002BFBD02B6038BDFC25002080EA010231 -:100BA000844612F0030F4FD111F0030F32D14DF8EC -:100BB000044D11F0040F51F8043B0BD0A3F10132A6 -:100BC0009A4312F0803F04BF4CF8043B51F8043BB9 -:100BD00016D100BF51F8044BA3F101329A4312F031 -:100BE000803FA4F101320BD14CF8043BA24312F038 -:100BF000803F04BF51F8043B4CF8044BEAD0234635 -:100C00000CF8013B13F0FF0F4FEA3323F8D15DF8E6 -:100C1000044B704711F0010F06D011F8012B0CF8AE -:100C2000012B002A08BF704711F0020FBFD031F826 -:100C3000022B12F0FF0F16BF2CF8022B8CF80020AD -:100C400012F47F4FB3D1704711F8012B0CF8012B30 -:100C5000002AF9D1704700BF08B5062000F0E0F87F -:100C6000012003F00FF800BF830770B4CDB23DD070 -:100C7000541E0AB30378AB421FD0431C05E014F1A5 -:100C8000FF3419D30278AA4217D013F0030F184685 -:100C900003F10103F3D1032C11D84CB30378AB4219 -:100CA0000BD00444431C02E00278AA4205D09C42C7 -:100CB000184603F10103F7D1002070BC7047090208 -:100CC00089B2294341EA0141036806464B40A3F13A -:100CD000013222EA030313F0803F00F1040003D144 -:100CE000043C032CF0D8D8E73046D7E71446D2E7C7 -:100CF0002046E2E710B580210446FFF7DFFE60647E -:100D000040B10022031F7C3043F8042F8342FBD103 -:100D1000002010BD4FF0FF3010BD00BF436C0BB181 -:100D200000207047E6E700BF1F29034609D810B529 -:100D3000446C84B054B154F8210044F8212004B02C -:100D400010BD16224FF0FF301A60704703900292D8 -:100D50000191FFF7CFFF20B9039B029A5C6C0199C8 -:100D6000E9E74FF0FF30EAE720B51F2982B00546DA -:100D700024D8426CAAB152F8213093B1012B0ED085 -:100D8000581C07D00025084642F8215098472846AD -:100D900002B020BD162301202B6002B020BD002030 -:100DA000F6E72846019100F071F801990A460146DC -:100DB000284602B0BDE8204000F054B816234FF09A -:100DC000FF302B60E4E700BF1F2926D820B5436C15 -:100DD00082B00546BBB153F8212003EB810382B1F9 -:100DE000501C0BD0012A06D0002508461D609047F4 -:100DF000284602B020BD032002B020BD022002B070 -:100E000020BD0120F5E70191FFF774FF10B96B6C6D -:100E10000199E0E74FF0FF30EBE74FF0FF3070470C -:100E2000024B01461868FFF79FBF00BF001100206A -:100E3000024B0A4601461868FFF776BF00110020F2 -:100E4000034B1868436C0BB10020704752E700BF9A -:100E500000110020024B01461868FFF7B5BF00BF24 -:100E60000011002070B50D460023074C06461146C0 -:100E70002846236002F00AFF431C00D070BD23689F -:100E8000002BFBD0336070BDFC25002002F0F8BEC3 -:100E90006FF01702364B2DE9F0411A70032200243F -:100EA0005A7001266FF063029C70DC701C715C71DB -:100EB0009C71DC711C725A729E72DC7203F01EF817 -:100EC000804603F06BF80546D0BB2A4B984539D0D5 -:100ED0003344984537D0284B28F0FF029A4234D14A -:100EE0005FFA88F000F04EFA2E4642F2107400F0DD -:100EF00077FC00F04DFA074658B364BB374635B16E -:100F00001E4B984503D0002403F040F827460020EC -:100F100002F0FEFF1A4B9B6813F040031ED00FB186 -:100F200000F030F800F07EFC00F018FE00F016FF34 -:100F30000546ACB900F0CCFC012002F02BFEF8E72E -:100F40000646D4E706462C46D1E706464FF47A74A7 -:100F5000CDE70446D3E74FF47A74D0E71C46E1E7C7 -:100F600000F0FCFE401BA042E4D900F00BF8DDE7E6 -:100F700080110020010007B0000008B0263A09B037 -:100F8000000C014010B51C4B1C4953F8042F0132D2 -:100F900000D110BD8B42F8D1194C1A4B22689A42ED -:100FA00028D9194B9B6803F1006303F5C8439A42A3 -:100FB00020D202F0BFFF02F0D1FF002000F0E8FDD8 -:100FC0000220124B187000F01FFE114BDA6900224C -:100FD000DA61D96999699A619B6972B60D4B0E4ABB -:100FE000202113601B68226881F311889D4683F3DA -:100FF0000888104710BD00BFFC6300081C6400088F -:1010000004640008FF630008801100208C11002098 -:10101000001002400064000808ED00E049F2690099 -:1010200008490B689AB21B0C00FB02330B6044F2B8 -:101030005061054A136898B21B0C01FB0030106028 -:1010400080B27047701100206C11002010B504466A -:101050000021102200F0F4FD034B03CB20606160FF -:101060001868A06010BD00BFE8F7FF1FF0B5BBB067 -:1010700000F074FE1D4CA368C31AF92B30D906ADDD -:101080002346A06028220021284601F0F5FB04F148 -:101090000E0000F0CDFD0023C6B2591D5F1CDBB26F -:1010A000B3424FEAC10107DA0E332344082228462F -:1010B00001F0E2FB3B46F0E7012303930823029390 -:1010C0000B4B207B01933023C1F3CF01059100939B -:1010D000014604A3D3E900230495064801F09CF9D6 -:1010E0003BB0F0BD78F6339F93CACD8DD021002060 -:1010F000DD210020A821002070B50D4614461E46B3 -:1011000001F030F950B9022E0ED1012C0CD112A3EE -:10111000D3E90023C5E90023012070BD052C14D0BC -:1011200003D8012C09D0002070BD282C09D0302C08 -:10113000F9D10BA3D3E90023ECE70BA3D3E90023F8 -:10114000E8E70BA3D3E90023E4E70BA3D3E90023EB -:10115000E0E700BFAFF30080401DA12026812A0BED -:1011600078F6339F93CACD8D9E6AC421818A46EE5C -:1011700026417272DF25D7B7F017304A39059E56DF -:1011800038B50D460446034620222846002101F0CA -:1011900073FB22792346032A28BF0322284603F83B -:1011A000042F2021022201F067FB62792346072ADF -:1011B00028BF0722284603F8052F2221032201F029 -:1011C0005BFBA2792346072A28BF0722284603F89B -:1011D000062F2521032201F04FFB284604F10803C6 -:1011E0001022282101F048FB382038BD2DE9F04FAE -:1011F000ADF5017D21AE0EAD40F2791280460F466D -:101200003046002100F01CFD48220021284600F055 -:1012100017FD00F0A3FD4FF47A72B0FBF2F0574BCC -:101220000DF15A09186093E8070001232B7400237D -:1012300085E807000DF15A006B74FFF707FF0323E1 -:1012400085F82030E82385F8213006AB18464C4954 -:10125000FFF7A4FC1F2228643146284685F83C206D -:10126000FFF78EFF12AB044601460822304601F01C -:1012700003FB08220DF14903A118304601F0FCFAE6 -:101280000DF14A03082204F11001304601F0F4FA8E -:1012900013AB202204F11801304601F0EDFA14AB33 -:1012A000402204F13801304601F0E6FA16AB08227C -:1012B00004F17801304601F0DFFA0DF159030822FC -:1012C00004F18001304601F0D7FA04F1880A04F5F0 -:1012D000847B4B465146082230460AF1080A01F049 -:1012E000CBFAD34509F10109F3D11BAB08225946CA -:1012F000304601F0C1FA4FF0000904F5887495F802 -:1013000034304B4510D84FF0000995F83C304B4530 -:1013100015D92B6C21464B440822304601F0ACFA1B -:10132000083409F10109F0E7AB6B21464B44082270 -:10133000304601F0A1FA083409F10109DFE7E31DA5 -:10134000C3F3CF03F97E0593002304960393BB7E7A -:1013500019370293012301970093404605A3D3E96F -:10136000002301F059F80DF5017DBDE8F08F00BFB5 -:10137000AFF300809E6AC421818A46EE901100205E -:10138000A8440008014B1870704700BF9C11002052 -:10139000F0B5334B85B01C7B34B10E22314B1A8132 -:1013A0000024204605B0F0BD2F4A02AB10685168FA -:1013B00003C308232D490DEB03022D48FFF7A8FABC -:1013C000054630B90A22274B2A481A8100F08CFCC6 -:1013D000E6E70169B1F5CE3F06D90B22214B26483D -:1013E0001A8100F081FCDCE7438BB3F57A7F09D0EA -:1013F0000C211C4A214811814FF47A72194600F0E1 -:1014000073FCCEE71E4A024402F11003994204D253 -:101410001022144B1B481A81E3E710398E1A20461C -:10142000134900F09FFC0746324605F1180120469B -:1014300000F098FCAB689F4202D1EB6898420AD05A -:101440000D22084B1A8100903B46EA68A9680E48B5 -:1014500000F04AFCA4E70D4800F046FC0124A0E798 -:10146000D02100209011002078430008DC9B01006F -:1014700000640008804300088C4300089E43000875 -:10148000089CFFF7BC430008D94300080244000849 -:101490002DE9F04FADB006AF80460C4600F062FF7C -:1014A000054600286AD1237E022B18D1E38A012B3E -:1014B00015D100F053FC8146FFF7B0FD4FF4C8731F -:1014C000B0FBF3F202FB1300BB4E80B209F51679B4 -:1014D000E37E484430608BB90022B84B1A709C37C9 -:1014E000BD46BDE8F08F3B1D1D440095002308223A -:1014F0004FEAC901204601F023F84D46A38A5FFA5E -:1015000085F9013BAB420BD905F10109B9F1110F86 -:10151000E9D140F23911AA4BAA4AAB48FFF744F887 -:1015200007F11400FFF792FD2A4607F11401381D58 -:10153000FFF75EF803460028CED1B9F1100F07D0AF -:101540009E4B83F800903368A3F516733360C6E7AB -:1015500007F1980202F8950D0146009220460722F5 -:1015600000F0EEFFF9787F2904DD984B954A4FF49F -:10157000A871D2E7404600F0D9FEB0E7E38A052B18 -:1015800000F0068106D8012BA9D121464046FFF77D -:101590002DFEA4E7282B3DD0302BA0D1637E8C4DAF -:1015A00001336A7BDBB29342E94640F0EF80E27E92 -:1015B0002B7B9A4240F0EA80002607F1980323F83B -:1015C000846D0093102201233146204600F0B8FFBD -:1015D000B4F81480A8F102081FFA88F808F1030390 -:1015E00023F003030A3323F00703ADEB030D0DF1E2 -:1015F000180A33469BB2B11C98454FEAC10106F167 -:1016000001066CDD5344009308220023204600F0BD -:1016100097FFEEE7A38A013B9BB2C92B3FF65FAF72 -:101620006B4E357B4DBB06F10C03009308222B4615 -:101630002946204600F084FFA38A05F10109013BF9 -:10164000EDB29D424FEAC90109DA0E3535440095E5 -:1016500000230822204600F073FF4D46ECE70023EC -:101660000022C6E900230023B36086F8D730C6F80D -:10167000D830337B0BB9E37E3373002507F11406B2 -:101680003B1D0822294630467D60BD60FD6001F0AB -:10169000F3F83B7A05F10109AB424FEAC90107D9DA -:1016A000FB6808222B44304601F0E6F84D46F0E78F -:1016B0000023C1F3CF01E07E059104960393A37E3E -:1016C00019340293282301460093019438A3D3E9E7 -:1016D0000023404600F0A0FEFFF7C8FCFFE695F8A7 -:1016E000D70000F05FFAD5F8D83006461BB995F858 -:1016F000D70000F067FAD5F8D83043449E4204D2B0 -:1017000095F8D700013000F05DFA00244FEA980BFD -:10171000A0B2584504F1010408DA2B6880000AEBF6 -:1017200000010122184400F093FAF1E7D5F8D840FF -:10173000D5E9002312EB080243F10003444495F875 -:10174000D700C5E90023C5F8D84000F02BFA844241 -:1017500009D395F8D730013385F8D730D5F8D8308C -:101760009E1BC5F8D860B8F1FF0F08DC00232B736F -:1017700000F03AFAFFF70CFE08B1FFF703FC2B6804 -:10178000144A9B0A013313810023AB60CD46A6E6C1 -:10179000BFF34F8F1049114BCA6802F4E062134344 -:1017A000CB60BFF34F8F00BFFDE700BFAFF30080FA -:1017B00026417272DF25D7B7A4210020A121002085 -:1017C00014440008C84400086D4400088F44000811 -:1017D000D02100209011002000ED00E00400FA0567 -:1017E00008B54FF000530B4A196891420AD1597D50 -:1017F000094A0A4811701B7DC922037308490E303B -:1018000000F00CFABDE80840E02200214FF0005043 -:1018100000F016BA9AAD44C59C110020D0210020DA -:1018200016000020022330B51F4C85B063710423DD -:101830000025ADF8083001230722ADF80C501B49F4 -:101840008DF80C308DF80B30194B1A484B608DF821 -:101850000A2001F001FE184B019500931749184B1F -:101860004FF48052174800F02BFD174B254619788E -:1018700011B1144800F05AFD00F070FA0446FFF769 -:10188000CDFB4FF4C873B0FBF3F202FB130304F576 -:1018900016749BB21C440D4B1C6002F07FFB08B118 -:1018A0000F232B8105B030BD901100206411002062 -:1018B00003000600E8220020F9100008A011002013 -:1018C00091140008A82100209C110020A4210020D0 -:1018D0002DE9F04F96A7D7E900670FF25C29D9E907 -:1018E00000898F4C93B0DFF858B2DFF858A2204639 -:1018F00000F0DEFD0CAD079098B3102200212846C1 -:1019000000F09EF94FF00002079B197B61F3030280 -:1019100019468DF8302051F8040F0EAA496803C209 -:101920001B680D9A584663F31C029DF830300D92E7 -:1019300043F020038DF8303000232A46194601F089 -:101940009BFD079030B9204600F0B6FD079B8AF852 -:101950000030CCE79AF80030072B40DC01338AF8DE -:10196000003018220021284600F06AF9DFF8D0B1D3 -:10197000DFF8D4A100232A461946584601F0A4FDF9 -:10198000014680BB102208A800F05AF9DAF80C30A2 -:1019900083F01003CAF80C3000F0E2F90DF1240EC8 -:1019A0000B4612A9024611E903008EE803009DF8D8 -:1019B0003410C1F30300890649BF0E99BDF83810F1 -:1019C000C1F31C0141F0004158BFC1F30A018DF879 -:1019D0002C000891204608A900F0B4FFCAE7204671 -:1019E00000F06AFDBDE7204600F0BCFC82460028FE -:1019F0004AD100F0B3F9DFF854B1DBF80030984277 -:101A000042D300F0ABF90790FFF708FB4FF4C8731F -:101A1000B0FBF3F101FB1300079A80B202F51672D6 -:101A20001044CBF80000DFF828B18DF820A09BF817 -:101A3000001011B901238DF8203028460791FFF7D7 -:101A400005FB07990DF12100C1F1100A5FFA8AFA2E -:101A5000BAF1060F28BF4FF0060A2944524600F09B -:101A6000DDF80AF10103049308AB039318230293F2 -:101A70002C4B324601930123204600933B4600F055 -:101A800073FC00238BF8003000F068F9264ADFF879 -:101A9000C4A01368C31AB3F57A7F32D3106000F084 -:101AA0005FF902460B46204600F00CFD204600F090 -:101AB00059FC30B39AF80C30DFF89CB0002B14BFFF -:101AC000032302238BF8053000F048F94FF47A73B2 -:101AD000B0FBF3F02946CBF800005846FFF750FB67 -:101AE00018230293114B0730019340F25513C0F3B2 -:101AF000CF0004900093039542464B46204600F0E9 -:101B000033FC9AF80C300BB1FFF7B0FA9AF80C30AE -:101B1000002B7FF4E8AE13B0BDE8F08FAFF3008088 -:101B2000A8210020A0210020B0220020B422002003 -:101B3000401DA12026812A0BF1C6A7C1D068080F3D -:101B4000E8220020B522002000080140A421002046 -:101B5000A1210020D02100209011002070B502F0BA -:101B6000D5F80025084C094E207030682378834250 -:101B700008D902F0C7F8336805440133B5F5C84FFA -:101B80003360F2D370BD00BFE4220020B8220020F1 -:101B900002F04AB900F10060920000F5C84002F07E -:101BA000EFB80000054B1A68054B1B789B1A83425F -:101BB00002D9104402F0A6B800207047B8220020D5 -:101BC000E422002038B50446064D2868204402F07F -:101BD0009FF828B928682044BDE8384002F0AAB828 -:101BE00038BD00BFB8220020064991F8243033B137 -:101BF00000230822086A81F82430FFF7CBBF0120B8 -:101C0000704700BFBC220020022802BF4FF48012A0 -:101C1000014B1A61704700BF00080140002310B556 -:101C2000934203D0CC5CC4540133F9E710BD0000EB -:101C300002460346981A13F9011B0029FAD170478E -:101C400003460244934202D003F8011BFAE77047AF -:101C50002DE9F047234C054694F824308846174672 -:101C600083BB2E46DFF87C90C7B394F824302BB9A1 -:101C70002022FF2148462662FFF7E2FF94F8240065 -:101C80004146C0F10805BD4228BF3D465FFA85FACE -:101C9000AD002A4604EB8000FFF7C0FF94F8243023 -:101CA000A7EB0A079A445FFA8AFABAF1080F2E44A2 -:101CB000A844FFB284F824A0D6D1FFF795FF0028EE -:101CC000D2D108E0266A06EB8306B042CAD0FFF7FD -:101CD0008BFF0028C5D10020BDE8F0870120BDE8BA -:101CE000F08700BFBC2200200FB4002004B0704772 -:101CF0000FB44FF0FF3004B070470000FEE7000063 -:101D0000EFF30983EFF30583044B9A6BDA6A9A6A5F -:101D10009A6A9A6A9A6A9A6A9B6AFEE700ED00E0FC -:101D2000EFF30983EFF30583044B9A6B9A6A9A6A7F -:101D30009A6A9A6A9A6A9B6AFEE700BF00ED00E021 -:101D4000EFF30983EFF30583034B5A6B9A6A9A6AA0 -:101D50009A6A9A6A9B6AFEE700ED00E002F09CB87E -:101D600002F076B830B5084D0A4491420BD00924F0 -:101D700011F8013B5840013CF7D040F300032B40E1 -:101D800083EA5000F7E730BD2083B8ED02460068D3 -:101D900048B1036811891360D38801339BB299421B -:101DA000D38038BF1381704770B504460D4688B0A4 -:101DB000202200216846FFF743FF20460495FFF7E5 -:101DC000E5FF054658B16B46044608AE1A4603CAFD -:101DD000B24220606160134604F10804F6D128463F -:101DE00008B070BD2DE9F04130B940F2C531264B45 -:101DF000264A2748FEF7D8FB0B7C23B9254B234AFC -:101E000040F2C631F5E7C66986B9C161BDE8F08127 -:101E1000002B29DA930CAB4229D1B44201D10C60DA -:101E2000F3E7C8F800100C60BDE8F0814B68B046DD -:101E300023F06047BD0C15EA230538BF3D46344604 -:101E40004FEAD37EC3F3807C6368BEEBD37F23F07D -:101E50006042DDD1974203D1C3F380739C450AD120 -:101E6000974205E01C46EFE7AA4206D013469D4282 -:101E70002CBF00230123002BCFD12368A046002BC9 -:101E8000F0D12160BDE8F0819C4700089045000832 -:101E9000544800087548000808B5034A034B40F24F -:101EA0005E310348FEF780FB6C45000814480008CB -:101EB0005448000808B503680B60C388016033B953 -:101EC000044B054A4FF4C7610448FEF76DFB013B24 -:101ED000C38008BDE4470008E045000854480008F6 -:101EE00070B50C4600F10C05616831B9E38A002039 -:101EF00061F30903E382002170BD0E682846FFF7F5 -:101F0000D9FF6660F0E7000008B5426832B10B4BBC -:101F10000B4A40F22F410B48FEF746FBC37DC3F34B -:101F20008401013161F38603C375C38A62F3090337 -:101F3000C3821B0A62F3C713C37508BD304800088B -:101F40009C450008544800082DE9F047089E32B926 -:101F50001F4B204A40F239511F48FEF725FB4FF432 -:101F60007F4901F007054FEAD6082A4406F0070624 -:101F700000EBD100954201D1BDE8F08705F0070ED6 -:101F800006F0070AD645774638BF5746511BC7F1BA -:101F900008078F4228BF0F46EC08045D08EBD60106 -:101FA00013F801C004FA0EF429FA07FE24FA0AF421 -:101FB0005FFA8EFE8CEA04044EFA0AFE04EA0E046E -:101FC0008CEA040C03F801C03D443E44D2E700BF54 -:101FD000B0470008B4450008544800082DE9F04116 -:101FE00006460F4600254FF6FF7441F221082A46A7 -:101FF00030463946FEF7B4F80823C0B284EA00241C -:1020000014F4004F4FEA4404A4B203F1FF3318BFA5 -:1020100084EA080413F0FF03F2D10835402DE6D11D -:102020002046BDE8F081000010B541F221040A44C9 -:10203000914200D110BD11F8013B80EA0320082332 -:1020400010F4004F4FEA400080B203F1FF3318BF95 -:10205000604013F0FF03F3D1EAE700002DE9F04FF1 -:1020600085B08A468DE80C00BDF83C40814630B909 -:1020700040F26E31484B494A4948FEF795FA11F053 -:10208000604F04D0474B454A40F26F31F4E7009B64 -:10209000002B7ED024B10E9B002B7AD0072C28D8A1 -:1020A00009F10C00FFF772FE054628B96FF0020532 -:1020B000284605B0BDE8F08F14220021FFF7C0FDCF -:1020C00022460E9905F10800FFF7A8FD631C2B744A -:1020D000009B2C441B78294603F01F0363F03F0349 -:1020E00023724AF000436B604846FFF77BFE0125F0 -:1020F000DEE74FF000084FF0800B46464546019B57 -:102100001B0A029300F10C0303930398FFF73EFEB2 -:1021100007460028CAD014220021FFF791FDB6BB64 -:1021200002229DF804303B729DF808307B720E9BB2 -:10213000711E1944B4420AD9B818013211F801EFDE -:10214000D2B20136072A80F808E0B6B2F2D1B44222 -:1021500008BF4FF0400B009BB8181978013201F00E -:102160001F0141EA48114BEA010303724AF00043A0 -:102170007B603A7439464846FFF734FE0135B44275 -:102180002DB288F001084FF0000BBED190E700227D -:10219000CDE76FF001058BE79C47000880450008FC -:1021A00054480008C04700082DE9F0471E46CB8A76 -:1021B0009146C3F30902062A80460F4619D01346FA -:1021C0000021B0B28DB25A1992B2052A09D9A8429B -:1021D00010D8FA8A034463F30902FA820120BDE8A9 -:1021E000F087A842F3D919F801403A4494760131B6 -:1021F000E8E70025FB8A7C68C3F309001C23821FE3 -:10220000B2FBF3FA03FB1A2A1FFA8AF27CB301210C -:102210002368002B39D1B31F03441C20B3FBF0F318 -:1022200001339BB299420CD2BAF1000F09D140465A -:10223000FFF7ACFD08B1C0F800A0206008B3044669 -:1022400000224FF0000AB6B2B54230D21346691EE2 -:102250004944E018013311F801EF9BB201351C2B02 -:1022600080F804E0ADB214D0AE42F2D8ECE74046BC -:10227000FFF78CFD044608B1002303607C60002C4E -:10228000DED16FF00200BDE8F087013189B21C4653 -:10229000BEE7AE42D8D94046FFF778FD08B1C0F896 -:1022A00000A020600028ECD004460022CCE7FB8A86 -:1022B000C3F30902164466F30903FB828EE70000AC -:1022C000F8B50E4615461F46044628B9144B154A64 -:1022D0004F211548FEF768F924220021FFF7B0FCD2 -:1022E000069B6A096360079B002023624FF6FF7319 -:1022F0009A4228BF1A46A7602070A061E06197B299 -:1023000004F10C05824205D100232B6027826382F1 -:10231000A382F8BD2E60013035462036F2E700BFBB -:10232000984700080C4500085448000808B528B92B -:102330007321084B084A0948FEF736F9037823B998 -:102340004BB2002B01DD017008BD054B024A7D2117 -:10235000F1E700BF9C4700081845000854480008F2 -:10236000E0460008007870472DE9F7430D9E0746C8 -:1023700019461046BDF828900B9D9DF83040BDF8D9 -:10238000388016B9B8F1000F43D11F2C41D83B78E3 -:10239000D3B9B8F1070F39D839F0030339D1424620 -:1023A00031464FF6FF70FFF73FFE4FEA092920F054 -:1023B000010009F44079400449EA0464400C44EA0D -:1023C00040244FF6FF730DE043EA0923B8F1070FED -:1023D00043EA0464F5D9FFF701FE42463146FFF7B0 -:1023E00023FE03468DE840012A4621463846FFF782 -:1023F00035FE0DB9FFF750FD2B780133DBB21F2BF3 -:1024000088BF00232B7003B0BDE8F0836FF003009A -:10241000F9E76FF00100F6E72DE9F7430E9F8146DB -:102420000B9D9DF830009DF83480BDF83C6007B9E5 -:10243000C6BB1F2836D899F800E0BEF1000F34D093 -:102440000C0244F080049DF8281044EAC83444EAA1 -:10245000014444EA0E04072E44EA006415D91946E3 -:102460001046FFF7BBFD32463946FFF7DDFD034658 -:10247000019600972A4621464846FFF7EFFDB8F13E -:10248000010F0CD125B9FFF707FD4FF6FF73EFE7FA -:102490002B780133DBB21F2B88BF00232B7003B0D6 -:1024A000BDE8F0836FF00100F9E76FF00300F6E795 -:1024B000C06900B104307047C1690C300B6803611A -:1024C000FFF7F8BC2DE9F84FD0F818A005461646DE -:1024D0001F4654464FF00009DFF8608000F10C0BF6 -:1024E0000CB9BDE8F88FD4E90223B21A67EB0303F5 -:1024F000994508BF90451FD2AB6921469C422846AA -:102500000DD1FFF7EDFCAB6921461B685846AB6166 -:10251000FFF7D0FCAC692346A2461C46E0E7FFF774 -:10252000DFFC23682146CAF800305846FFF7C2FC9A -:102530005446DAF80030EFE72368EDE780841E00A8 -:102540002DE9F04F8BB00D4614460793DDF85090FF -:102550008246002800F06481B9F1000F00F060812C -:10256000531E3F2B00F25C81012A03D1079B002BF5 -:1025700040F056810023BAF814600893F600B54283 -:10258000099380F053812B199E420AD2761B16F0D4 -:10259000FF0607D140F26751AA4BAB4AAB48FEF7A2 -:1025A00003F82646DAF80C3023B9DAF81030002B9D -:1025B00000F0A5802F2D31D8C5F1300846454FF0E9 -:1025C000000334BFB0465FFA88F80093294608AB91 -:1025D0004246DAF80800FFF7B7FCA6EB08074544C7 -:1025E000FFB24FF0300BBAF8143003F10053063B42 -:1025F000DB000293DAF80C300593059B002B51D0D9 -:1026000087B9DAF81000002861D0002F5FD0AB4501 -:1026100050D98F4B8C4A40F2A651BFE737464FF056 -:102620000008DEE7029B23B98A4B874A4FF4B16169 -:10263000B4E7029BE02B28BFE02306935B44AB4248 -:1026400004931DD95B1B9F4226BFDBB20393039704 -:10265000AB4504D97E4B7C4A40F291519EE70598E8 -:10266000CDF8008008ABA5EB0B01039A0430FFF70F -:102670006BFC039B9844FF1A1D445FFA88F8FFB275 -:10268000049B9B4504D3744B6F4A40F29B5185E7F2 -:10269000029B069ADDF810B09B1A0293059B1B68FB -:1026A0000593AAE7029BBB42ABD26C4B664A40F251 -:1026B000A15173E7CDF800803A46A5EB0B0108ABBA -:1026C000B8443D44FFF740FC00275FFA88F8BAF8A9 -:1026D0001430B5EBC30F04D9614B5B4A40F2B151E2 -:1026E0005CE7B8F1400F04D95E4B574A40F2B25153 -:1026F00054E767B15C4B544A40F2B3514EE7009344 -:10270000324608AB2946DAF80800FFF71DFC731EB5 -:102710003F2B35B201D8A64204DD544B544A40F257 -:1027200035213BE760070AD00AAB03EBD40111F86F -:10273000083C624202F00702134101F8083C082CF1 -:1027400021D9102C21D9202C8CBF08230423079ACF -:10275000002A6DD0B4EBC30F6CD0082C04F1FF320B -:1027600015D89DF8203023FA02F2D10706D54FF094 -:10277000FF3202FA04F423438DF820309DF8203014 -:1027800089F800304EE00123E1E70223DFE7102C57 -:1027900011D8BDF8203023FA02F2D20706D54FF047 -:1027A000FF3202FA04F42343ADF82030BDF82030A4 -:1027B000A9F8003036E0202C0ED8089921FA02F250 -:1027C000D30705D54FF0FF3303FA04F40C43089404 -:1027D000089BC9F8003025E0402C1CD0DDE90867D3 -:1027E00030463946FDF7BCFC002100F0010050EAFC -:1027F00001030BD0224601200021FDF7BDFC404221 -:1028000061EB410106430F43CDE90867DDE9082389 -:10281000C9E9002306E0174B154A4FF42071BDE6C5 -:102820006FF0010528460BB0BDE8F08F1D46F9E7B3 -:10283000012CA3D0082CA1D9102CB7D9202CE5D875 -:10284000C6E700BFEC450008C4450008544800082E -:102850000E460008FB450008334600085B460008AA -:1028600082460008B0460008C8460008E246000854 -:1028700044450008E046000830B585B030B940F264 -:10288000B121234B234A2448FDF78EFE23B9234B65 -:10289000204A40F2B221F6E7402A04D9204B1D4AD3 -:1028A00040F2B621EFE722B91D4B1A4A4FF42F71BF -:1028B000E9E70024012A0294039417D11B788DF8CC -:1028C000083053070AD004AB03EBD20313F8084CCB -:1028D000554205F00705AC4003F8084C009103464B -:1028E000002102A8FFF730FB05B030BD082AE5D96A -:1028F000102A03D81B88ADF80830E2E7202A02D856 -:102900001B680293DDE7D3E90045CDE90245D8E72E -:102910001C4700085845000854480008374700087D -:10292000E046000870B50C4600F10C05E16819B9E5 -:10293000A1602161A18270BD0E682846FFF7BAFA36 -:10294000E660F3E72DE9F04FD1F8009091B0C9F3BC -:10295000C01604460D46CDE90223002E50D0C9F31F -:10296000C03BC9F30626B9F1000F80F29F8119F030 -:10297000C04F40F09B812B7B002B00F09781BBF177 -:10298000020F03D02278B24240F0938109F07F0217 -:10299000BBF1020F059236D119F07F0FC9F30F2A50 -:1029A00001D10AF0030A2B447606059A93F80380B6 -:1029B00046EA0B4646EA82465FEAD81346EA0A062A -:1029C000069300F09A800022002310A961E90823F1 -:1029D000059B6768009352465B462046B84700282F -:1029E00000F08880A7698FB9314604F10C00FFF729 -:1029F000DBF90746D0B96FF0020011B0BDE8F08FE7 -:102A00004FF0020BAFE7C9F3074ACCE73B699E42A0 -:102A10000DD03F68002FF9D1314604F10C00FFF7CB -:102A2000C3F907460028E6D0A3693B60A761DDE94A -:102A30000801FFF7D3FAB882F97D08F01F06C1F349 -:102A40008401711A89B20FFA81FEBEF1000FB8BF7E -:102A500001F1200EC9F30461D7E90223B8BF0FFAD0 -:102A60008EFE079152EA030100F02F81DDE9020199 -:102A7000801A61EB03010B46002102469E489942F1 -:102A800008BF9042C0F02181069B002B3FD0BEF1D1 -:102A9000010F00F31A8118F0400F38D0DDE902234E -:102AA000C7E90223202200210DEB0200FFF7C8F83E -:102AB000DDE90223CDE908232B1D0A932B7B204659 -:102AC000013BDBB2ADF834309DF81C30ADF836A0D8 -:102AD0008DF83A309DF814308DF838B08DF83B30D1 -:102AE0008DF83960A36808A998473846FFF70CFAB3 -:102AF000002082E76FF00B007FE7A76917B96FF03E -:102B00000C007AE73B699E4296D03F68F6E7FB7D72 -:102B1000C8F34012B2EBD31F40F0CE80C3F384035E -:102B2000B34240F0CC8006992B7B4FEA981279B3E0 -:102B3000D2073CD4032B40F2C580DDE90223C7E96C -:102B400002232B7BAE1D033BDBB23246394604F138 -:102B50000C00FFF729FB002808DA39462046FFF76A -:102B6000BFF93846FFF7D0F9032046E7AB883B832F -:102B70002A7B033AD2B2B88A3146FFF755FAFB7D79 -:102B8000B882DA43C2F3C01262F3C713FB75AFE732 -:102B90006AB92E1D013BDBB23246394604F10C0006 -:102BA000FFF702FB0028D8DB2A7B013AE2E7FA8A2A -:102BB000013BC2F30902052AD9B250D80023281DCF -:102BC00099420AD907EB020E10F801CB013201330A -:102BD000062A8EF81AC0DBB2F2D18B4228BF00233E -:102BE000DDE9028907F11A02CDE908890A927A68BB -:102BF0003CBF04335B190B920C93FB8AADF836A0F3 -:102C0000C3F3090319449DF81C30ADF834108DF856 -:102C10003A309DF814308DF838B08DF83B300023F1 -:102C20008DF839607B602A7BB88A013A291DFFF74D -:102C3000FBF93B8BB882834203D1A36808A92046E5 -:102C4000984708A92046FFF76DFE3846FFF75CF964 -:102C5000B88A3B8B984214BF11200020CDE67868DB -:102C600010B34FF0060E03689BB9A2EB0E021B2AAD -:102C700013D80332024405F1040E1F309942ACD937 -:102C80001EF801CB013302F801CF9042DBB2F5D13F -:102C9000A3E70EF11C0E1846E5E7184B184A40F260 -:102CA000B3111848FDF780FC034696E76FF0090062 -:102CB000A3E66FF00A00A0E66FF00D009DE66FF04E -:102CC0000E009AE66FF00F0097E6FB7D394668F339 -:102CD00086036FF3C713FB752046FFF701F9069BC8 -:102CE000002B7FF4D8AEFB7DC3F38402013262F384 -:102CF0008603FB7503E700BF80841E004C47000875 -:102D000030450008544800082DE9F0414E4EB042CD -:102D100040F086804D4CDFF838E1E56945F00075FC -:102D2000E561E469846AD4F8007207EA0E0747F0A7 -:102D30000107C4F80072D4F8005205EA0E0545F008 -:102D4000010545EA0121C4F80012002A6AD00021D9 -:102D50000F46C4F81C12C4F80412C4F80C12C4F8CC -:102D6000141204EBC10501310E29C5F84072C5F8F3 -:102D70004472F6D14FF0000E4FF0010C964510D181 -:102D8000826AB042D2F8003223F00103C2F8003266 -:102D900058D12E4BDA6922F00072DA61DB69BDE8A6 -:102DA000F0819F781D8817F0010F18BFD4F80482B6 -:102DB0000CFA05F11CBF41EA0808C4F8048217F0B8 -:102DC000020F18BFD4F80C8204EBC5051CBF41EA02 -:102DD0000808C4F80C827F0748BFD4F8147203F1C6 -:102DE0000C0344BF0F43C4F8147253F8087C0EF16F -:102DF000010EC5F8407253F8047CC5F84472D4F84B -:102E00001C522943C4F81C12B8E70021846AC4F894 -:102E10001C12C4F80412C4F80C12C4F81412A9E766 -:102E2000002AF2D10022836AC3F84022C3F8442268 -:102E3000C3F80422C3F814220122C3F80C22C3F8F9 -:102E40001C229DE7BDE8F081E8220020001002402E -:102E50000000FFFF184A08B5916A8B688B6013F079 -:102E6000010105D013F00C0F14BF4FF48031012184 -:102E7000D80506D513F4406F14BF41F4003141F07A -:102E80000201D80306D513F4402F14BF41F480216A -:102E900041F00401D3690BB107489847202383F31D -:102EA00011880021054800F09DFE002383F311885E -:102EB000BDE8084001F082B8E8220020F02200209E -:102EC00038B5124CA36ADD68AA0712D05A6922F0FD -:102ED00002025A61A36913B10121204698472023B9 -:102EE00083F3118800210A4800F07CFE002383F35D -:102EF0001188EB0606D51021A36AD960236A0BB1AD -:102F000002489847BDE8384001F058B8E822002050 -:102F1000F822002038B5124CA36A1D69AA0712D006 -:102F20005A6922F010025A61A36913B102212046A6 -:102F30009847202383F3118800210A4800F052FEAD -:102F4000002383F31188EB0606D51021A36A1961CB -:102F5000236A0BB102489847BDE8384001F02EB80B -:102F6000E8220020F822002038B50F4CA36A5D68E3 -:102F70002A075D600AD5032222701A6822F0020235 -:102F80001A60636A13B10021204698476B0706D583 -:102F9000A36A9969236A13B1090403489847BDE8F5 -:102FA000384001F00BB800BFE822002010B50F4CEC -:102FB000204600F03FFA0E4B0B211320A36200F0D5 -:102FC00019FA0B21142000F015FA0B21152000F03E -:102FD00011FA0B21162000F00DFA00232046BDE85F -:102FE00010401A460E21FFF78FBE00BFE8220020D6 -:102FF000006400400F4B10B59842044605D10E4BBB -:10300000DA6942F00072DA61DB690122A36A1A60B0 -:10301000A36A5A68D20707D5626851681268D961F5 -:103020001A60064A5A6110BD0121082000F092FC86 -:10303000EEE700BFE8220020001002405B8701009D -:1030400003291AD8DFE801F0020A0F14836A9B688B -:1030500013F0E05F14BF012000207047836A986876 -:10306000C0F380607047836A9868C0F3C06070479F -:10307000836A9868C0F300707047002070470000B2 -:1030800010B503291FD8DFE801F0021F2327816A4A -:103090008B68C3F30163183301EB031310788106C7 -:1030A0001ED55468C0F30011490041EAC40141F043 -:1030B000040100F00F005860906841F00101986031 -:1030C000D268DA60196010BD836A03F5C073E5E762 -:1030D000836A03F5C873E1E7836A03F5D073DDE71C -:1030E0009488C0F30011490041EA4451E1E700002F -:1030F00001290CD003D3022910D000207047836A25 -:10310000DA68920701D1186903E001207047836AE9 -:10311000D86810F0030018BF01207047836AF2E7F7 -:1031200010B539B9836AD96889071BD11B699B0718 -:1031300004D110BD012915D0022948D1816AD1F8E6 -:10314000C031D1F8C401D1F8C8411461D1F8CC41E3 -:10315000546120240C610C69A40717D14C6944F018 -:10316000100412E0816AD1F8B031D1F8B401D1F87D -:10317000B8411461D1F8BC4154612024CC60CC68C2 -:10318000A40703D14C6944F002044C6111795C0836 -:1031900064F304119C0864F34511117189064BBF57 -:1031A00091681189DB085B0D4CBF63F31C0163F36D -:1031B0000A01137948BF916060F3030313714FEA6A -:1031C00010234FEA104058BF11811370508010BD7A -:1031D00000231A4610B51C495A50CC180833802BCE -:1031E0006260F9D1194B9A6942F07D029A619B693C -:1031F0000268174BDA6082685A6042681A60C268D7 -:1032000003F58063DA6042695A6002691A60826974 -:10321000C3F80C24026AC3F80424C269C3F800246A -:10322000426AC3F80C28C26AC3F80428826AC3F849 -:103230000028026BC3F80C2C826BC3F8042C426B81 -:10324000C3F8002C10BD00BF142300200010024062 -:1032500000080140026843681143016003B1184748 -:1032600070470000024AD36843F0C003D360704740 -:1032700000380140024AD36843F0C003D36070476E -:10328000004400402DE9F041D0F89C600546F76805 -:103290003368DA059CB20DD5202383F311884FF4EF -:1032A00000710430FFF7D6FF6FF4807333600023A2 -:1032B00083F31188202383F3118805F1040814F0A7 -:1032C0002F0333D183F31188380615D5210613D582 -:1032D000202383F3118805F1380000F02FFA00282D -:1032E00046DA0821281DFFF7B5FF4FF67F733B40F4 -:1032F000F360002383F311887A060ED563060CD59C -:10330000202383F31188EA6C2B6D9A4202D12B6C37 -:10331000002B2FD1002383F31188D5F8A420D36884 -:10332000002B31D0BDE8F04110691847230713D0B6 -:1033300014F0080F0CBF00218021E00748BF41F0C6 -:103340002001A20748BF41F04001630748BF41F494 -:1033500080714046FFF77EFFA406736805D595F897 -:10336000A0102846194000F089FA3468A4B2A6E7F4 -:103370007060BEE727F040073F041021281D3F0C76 -:10338000FFF768FFF760C5E7BDE8F08108B50348BF -:10339000FFF778FFBDE8084000F010BE942300203E -:1033A00008B50348FFF76EFFBDE8084000F006BE11 -:1033B0003C24002010B5094C094A2046002100F0A9 -:1033C0003DFA084B084AC4F89C30084C00212046BE -:1033D00000F034FA064BC4F89C3010BD9423002052 -:1033E0006532000800380140753200083C24002096 -:1033F0000044004000F16043090103F56143C9B294 -:1034000083F80013012300F01F024009800000F13F -:103410006040934000F56140C0F880310360704720 -:10342000090100F16040C9B200F56D4001767047B6 -:10343000FFF7BCBD01230370002300F10802826086 -:10344000C26000F110024360026142618361C361A6 -:10345000036243627047000010B52023044683F3E3 -:103460001188022341600370FFF7C4FD032323701A -:10347000002383F3118810BD2DE9F0411F46044657 -:103480000D461646202383F3118800F1080823789F -:10349000042B0ED029462046FFF7D2FD48B1204626 -:1034A00032462946FFF7ECFD002080F31188BDE885 -:1034B000F0813946404600F079FB0028E7D0002330 -:1034C00083F31188BDE8F0812DE9F0411F460446E1 -:1034D0000D461646202383F3118800F11008237847 -:1034E000042B0ED029462046FFF702FE48B12046A5 -:1034F00032462946FFF714FE002080F31188BDE80C -:10350000F0813946404600F051FB0028E7D0002307 -:1035100083F31188BDE8F081F8B5154682680B4643 -:10352000AA428169066938BF8568761AB5420446A1 -:1035300007D218462A46FEF771FBA3692B44A36104 -:103540000DE011D932461846FEF768FBAF1B3A462C -:10355000E1683044FEF762FBE2683A44A261A36886 -:1035600028465B1BA360F8BD18462A46FEF756FBAB -:10357000E368E4E72DE9F0410446154683682669CF -:10358000934238BF856840690F46361AB54206D265 -:103590002A46FEF743FB63692B4463610DE012D9B1 -:1035A0003246A5EB0608FEF739FB4246B919E0683A -:1035B000FEF734FBE26842446261A36828465B1B65 -:1035C000A360BDE8F0812A46FEF728FBE368E4E744 -:1035D00010B50024C361029B0A440060406084600F -:1035E000C160816141610261036210BD08B58269F9 -:1035F0004369934201D1826882B982680132826054 -:103600005A1C42611970426903699A4201D3C36826 -:103610004361002100F0DAFA002008BD4FF0FF30CE -:1036200008BD000070B5202304460E4683F31188C0 -:10363000A568A5B1A368A269013BA360531CA3615F -:1036400015782269934224BFE368A361E3690BB153 -:1036500020469847002383F31188284670BD3146E1 -:10366000204600F0A3FA0028E2DA85F3118870BD45 -:103670002DE9F74F05460F4690469A46D0F81C9024 -:10368000202686F311884FF0000B144664B12246C1 -:1036900039462846FFF740FF034668B95146284699 -:1036A00000F084FA0028F1D0002383F31188A8EBFE -:1036B000040003B0BDE8F08FB9F1000F03D0019012 -:1036C0002846C847019B8BF31188E41A1F4486F3F0 -:1036D0001188DBE7C361009BC160816141611144D6 -:1036E000006040608260016103627047F8B5044683 -:1036F0000E461746202383F31188A568A5B1A36859 -:10370000013BA36063695A1C62611E702369626990 -:103710009A4224BFE3686361E3690BB1204698478E -:10372000002080F31188F8BD3946204600F03EFAAB -:103730000028E2DA85F31188F8BD00008369426948 -:1037400010B59A4201D182687AB9826801328260EA -:103750005A1C82611C7803699A4201D3C368836151 -:10376000002100F033FA204610BD4FF0FF3010BDAD -:103770002DE9F74F05460F4690469A46D0F81C9023 -:10378000202686F311884FF0000B144664B12246C0 -:1037900039462846FFF7EEFE034668B951462846EB -:1037A00000F004FA0028F1D0002383F31188A8EB7D -:1037B000040003B0BDE8F08FB9F1000F03D0019011 -:1037C0002846C847019B8BF31188E41A1F4486F3EF -:1037D0001188DBE7026843681143016003B11847B1 -:1037E000704700001430FFF743BF00004FF0FF3375 -:1037F0001430FFF73DBF00003830FFF7B9BF0000BD -:103800004FF0FF333830FFF7B3BF00001430FFF73D -:1038100009BF00004FF0FF311430FFF703BF000075 -:103820003830FFF763BF00004FF0FF323830FFF74A -:103830005DBF000000207047FFF7BCBD0E4B37B5E1 -:103840000360002343608360C36001230446154680 -:103850000374202200900B4600F15C011430FFF746 -:10386000B7FE00942B46202204F17C0104F13800BD -:10387000FFF730FF03B030BD9048000838B5C3698A -:1038800004460D461BB904210844FFF7A3FF29464F -:1038900004F11400FFF7AAFE002806DA201D4FF4F9 -:1038A0008061BDE83840FFF795BF38BD0022024B6C -:1038B0001B605B609A607047E424002000238268EC -:1038C0000374054B1B6899689142FBD25A680360E8 -:1038D0004260106058607047E424002008B520233F -:1038E00083F31188037C032B05D0042B0DD02BB957 -:1038F00083F3118808BD002243691A604FF0FF333B -:103900004361FFF7DBFF0023F2E790E80C001A6049 -:1039100002685360F2E70000002382680374054BDD -:103920001B6899689142FBD85A6803604260106036 -:1039300058607047E4240020054B19690874186822 -:10394000026853601A60186101230374FCF718BE03 -:10395000E424002030B54B1C87B005460A4C10D03B -:1039600023690A4A01A800F059F92846FFF7E4FF45 -:10397000049B13B101A800F06BF92369586907B0E3 -:1039800030BDFFF7D9FFF8E7E4240020DD38000858 -:1039900038B50C4D41612B6981689A6804469142A3 -:1039A00003D8BDE83840FFF789BF1846FFF786FF08 -:1039B00001232C61014623742046BDE83840FCF702 -:1039C000DFBD00BFE4240020044B1A681B69906827 -:1039D0009B68984294BF002001207047E424002097 -:1039E00010B5084C236820691A68546022600122CF -:1039F00023611A74FFF790FF01462069BDE810406B -:103A0000FCF7BEBDE424002008B5FFF7DDFF18B1C8 -:103A1000BDE80840FFF7E4BF08BD0000FEE7000076 -:103A200010B5174CFFF742FF00F0EAF88022154965 -:103A3000204600F06FF8012344F8180C0374124B71 -:103A4000124AD96821F4E0610904090C0A431049BB -:103A5000DA60CA6842F08072CA600E490A6842F0B1 -:103A600001020A601022DA77202283F82220002344 -:103A700083F3118862B6BDE81040074800F06CB8C7 -:103A80000C250020B848000800ED00E00003FA050E -:103A9000F0ED00E0001000E0C0480008F8B50F4C61 -:103AA000226A01322262224652F8141F91421546C0 -:103AB00006D020268B68013B8B6063699A6802B14F -:103AC000F8BD1968DF68DA604D60616182F31188C2 -:103AD0001869B84786F31188EFE700BFE424002097 -:103AE000EFF3118020B9EFF30583202282F31188D0 -:103AF0007047000010B558B9EFF30584C4F308040B -:103B000014B180F3118810BDFFF77EFF84F3118894 -:103B100010BD0000826002220274002242747047CD -:103B20008368A3F13C0243F80C2C026943F83C2C57 -:103B3000426943F8382C074A43F81C2CC268A3F1A9 -:103B4000180043F8102C022203F8082C002203F876 -:103B5000072C70479105000810B5202383F31188C6 -:103B6000FFF7DEFF00210446FFF712FF002383F377 -:103B70001188204610BD0000024B1B6958610F20C0 -:103B8000FFF7DABEE4240020202383F31188FFF737 -:103B9000F3BF000008B50146202383F311880820F5 -:103BA000FFF7D8FE002383F3118808BD49B1064B07 -:103BB00042681B6918605A60136043600420FFF775 -:103BC000C9BE4FF0FF307047E424002003689842DC -:103BD00006D01A680260506059611846FFF76EBE41 -:103BE0007047000038B504460D462068844200D175 -:103BF00038BD036823605C604561FFF75FFEF4E752 -:103C0000054B03F114025A619A614FF0FF32DA61F9 -:103C100000221A62704700BFE424002010B5C26081 -:103C20000A4A036153699C68A1420CD85C6803602E -:103C300044602060586081609868411A99604FF034 -:103C4000FF33D36110BD091B1B68ECE7E42400209F -:103C5000036881689A680A449A604268136003683E -:103C60005A6000234FF0FF32C360014BDA617047A6 -:103C7000E42400200C2303604FF0FF307047000065 -:103C800000207047FEE70000704700004FF0FF3053 -:103C900070470000BFF34F8F024AD368DB07FCD4A4 -:103CA000704700BF0020024008B5074B1B7853B98E -:103CB000FFF7F0FF054B1A69120641BF044A5A602C -:103CC00002F188325A6008BDE82500200020024039 -:103CD0002301674508B5054B1B7833B9FFF7DAFFB9 -:103CE000034A136943F08003136108BDE8250020EF -:103CF000002002407F289ABF00F50030800200209B -:103D0000704700004FF480607047000080207047CB -:103D10007F2808B50BD8FFF7EDFF00F58063026838 -:103D2000013204D104308342F9D1012008BD0020C2 -:103D300008BD00007F2810B504461CD8FFF7AAFF75 -:103D4000FFF7B2FFF3220D4BDA6002221A61FFF790 -:103D5000D1FF58611A6942F040021A61FFF79AFFD9 -:103D60004FF4806100F0E4F8FFF7B4FF2046BDE8AF -:103D70001040FFF7CDBF002010BD00BF0020024063 -:103D80002DE9F84312F00103144606D040F27322E5 -:103D90001F4B1A600020BDE8F88385181D4A954224 -:103DA00004D94FF41E711A4A1160F3E7FFF77CFF44 -:103DB000FFF770FF4FF00109DFF86880451A012C0A -:103DC00005EB01060F4604D8FFF784FF0120BDE88C -:103DD000F883C8F8109031F8023B3380FFF75AFFA0 -:103DE0000020C8F8100033883A889BB29A420DD060 -:103DF00040F28F22064B1A60074B1E60074B1C6077 -:103E0000074B1F60FFF766FFBDE8F883023CD6E76B -:103E1000E4250020FFFF0108D8250020E025002030 -:103E2000DC25002000200240084908B50B7828B1A5 -:103E300053B9FFF739FF01230B7008BD23B1BDE86B -:103E400008400870FFF746BF08BD00BFE825002006 -:103E500038B5FFF745FE4FF47A730C490C4A0C6AEB -:103E6000116803FB04F38B420A49D1E9004504D2EF -:103E7000003445F10105C1E90045E41845F10005AC -:103E80001360FFF737FE2046294638BDE4240020A2 -:103E9000EC250020F025002008B5FFF7D9FF4FF4EE -:103EA0007A720023FCF774F908BD00BF10B5094C05 -:103EB0000439013AD2B2FF2A00D110BD530898004C -:103EC000043054F8233000599BB243EA004341F8D0 -:103ED000043FEEE7046C004030B50748013AD2B227 -:103EE000FF2A00D130BD0D88540840F82450A300AB -:103EF0004C8804331C50F1E7046C004007B50122E4 -:103F000001A90020FFF7D2FF019803B05DF804FB80 -:103F100013B50446FFF7F2FFA04206D002A941F80C -:103F2000044D01220020FFF7D7FF02B010BD0000B2 -:103F30007047000045F25552064B1A6002225A6043 -:103F400040F6FF729A604CF6CC421A600122024B96 -:103F50001A70704700300040F9250020034B1B7891 -:103F60001BB14AF6AA22024B1A607047F9250020BD -:103F700000300040034B1B689B0042BF0122024BF4 -:103F80001A70704724100240F82500204FF080720C -:103F9000014B1A60704700BF24100240014B187893 -:103FA000704700BFF8250020EFF30983203383F327 -:103FB0000988002383F311887047000010B520237F -:103FC00083F311880D4B5B6813F4006312D0EFF399 -:103FD00009844FF0807344F8043CA4F1200383F378 -:103FE0000988FFF7F1FC18B1054B44F8083C10BDF7 -:103FF000044BFAE783F3118810BD00BF00ED00E029 -:10400000A1050008A405000870470000FEE70000B5 -:10401000084A094B09498B4204D30021084A9342BC -:1040200005D3704752F8040F43F8040BF3E743F845 -:10403000041BF4E7D84900080026002000260020D1 -:104040000026002000F030B808B500F063F9FFF753 -:10405000E7FCBDE80840FFF78DBF00007047000097 -:104060004FF0FF310E4B1A6919611A6900221A616B -:104070001869D868D960D968DA60DA68DA6942F014 -:104080008052DA61DA69DA6942F00062DA61054A7F -:10409000DB69136843F48073136000F01BB900BF41 -:1040A0000010024000700040194B1A6842F00102F3 -:1040B0001A601A689007FCD51A6802F0F9021A60B3 -:1040C00000225A605A6812F00C0FFBD11A6842F4B1 -:1040D00080321A601A689103FCD55A6842F4E812DB -:1040E0005A601A6842F080721A601A689201FCD510 -:1040F0001221084A5A60084A11605A6842F00202C6 -:104100005A605A6802F00C02082AFAD1704700BFC0 -:104110000010024000641D0000200240084A08B55B -:10412000536911680B4003F00103536123B1054A41 -:1041300013680BB150689847BDE80840FFF73EBFD1 -:104140000004014014230020084A08B5536911688F -:104150000B4003F00203536123B1054A93680BB18E -:10416000D0689847BDE80840FFF728BF0004014029 -:1041700014230020084A08B5536911680B4003F066 -:104180000403536123B1054A13690BB15069984781 -:10419000BDE80840FFF712BF0004014014230020CF -:1041A000084A08B5536911680B4003F008035361CE -:1041B00023B1054A93690BB1D0699847BDE808401F -:1041C000FFF7FCBE0004014014230020084A08B594 -:1041D000536911680B4003F01003536123B1054A82 -:1041E000136A0BB1506A9847BDE80840FFF7E6BE76 -:1041F0000004014014230020174B10B55C691A68B5 -:10420000144004F478725A61A30604D5134A936AE1 -:104210000BB1D06A9847600604D5104A136B0BB1F6 -:10422000506B9847210604D50C4A936B0BB1D06BA9 -:104230009847E20504D5094A136C0BB1506C9847B6 -:10424000A30504D5054A936C0BB1D06C9847BDE823 -:104250001040FFF7B3BE00BF00040140142300204C -:104260001A4B10B55C691A68144004F47C425A6118 -:10427000620504D5164A136D0BB1506D984723059E -:1042800004D5134A936D0BB1D06D9847E00404D563 -:104290000F4A136E0BB1506E9847A10404D50C4A17 -:1042A000936E0BB1D06E9847620404D5084A136F21 -:1042B0000BB1506F9847230404D5054A936F0BB197 -:1042C000D06F9847BDE81040FFF778BE000401406A -:1042D00014230020062108B50846FFF78BF80621B5 -:1042E0000720FFF787F806210820FFF783F806214B -:1042F0000920FFF77FF806210A20FFF77BF8062147 -:104300001720FFF777F8BDE8084006212820FFF7BF -:1043100071B8000008B5FFF7A3FE0648FEF758FF86 -:10432000FFF786F8FFF788FAFFF798FEBDE8084028 -:1043300000F002B8E048000800F00EB808B52023ED -:1043400083F31188FFF7AAFB002383F31188BDE8EC -:104350000840FFF733BE0000054B064A08215A60AB -:1043600000229A6007220B201A60FFF759B800BF9D -:1043700010E000E03F19010040A2E4F164689106FA -:104380004E6F20617070207369670A00426164207B -:104390006677206C656E6774682025750A00426137 -:1043A0006420626F6172645F6964202575207368A0 -:1043B0006F756C642062652025750A004261642077 -:1043C00066772064657363726970746F72206C65C0 -:1043D0006E6774682025750A004261642061707000 -:1043E00020435243203078253038783A30782530D1 -:1043F0003878203078253038783A30782530387859 -:104400000A00476F6F64206669726D776172650A92 -:104410000000000072656365697665645F756E69AA -:104420007175655F69645F6C656E203C205541560F -:1044300043414E5F50524F544F434F4C5F44594E8F -:10444000414D49435F4E4F44455F49445F414C4CA9 -:104450004F434154494F4E5F554E495155455F4971 -:10446000445F4D41585F4C454E475448002E2E2F17 -:104470002E2E2F546F6F6C732F41505F426F6F74ED -:104480006C6F616465722F63616E2E637070006182 -:104490006C6C6F63617465645F6E6F64655F6964A3 -:1044A000203C3D20313237006F72672E6172647597 -:1044B00070696C6F742E6631303351696F74656B3F -:1044C0005F50657269706800766F69642068616E1C -:1044D000646C655F616C6C6F636174696F6E5F7251 -:1044E0006573706F6E73652843616E617264496EA7 -:1044F0007374616E63652A2C2043616E617264522D -:10450000785472616E736665722A290063616E6108 -:104510007264496E6974000063616E617264536510 -:10452000744C6F63616C4E6F646549440000000019 -:1045300063616E61726448616E646C655278467244 -:10454000616D650063616E6172644465636F64658B -:104550005363616C6172000063616E617264456EE9 -:10456000636F64655363616C61720000696E6372AE -:10457000656D656E745472616E7366657249440050 -:10458000656E717565756554784672616D65730009 -:1045900070757368547851756575650070726570D3 -:1045A000617265466F724E6578745472616E73669F -:1045B00065720000636F707942697441727261794B -:1045C0000000000064657363617474657254726105 -:1045D0006E736665725061796C6F616400000000F3 -:1045E00066726565426C6F636B0000006269745FA0 -:1045F0006C656E677468203E20300072656D61697D -:104600006E696E675F62697473203E203000696E68 -:104610007075745F6269745F6F6666736574203E5F -:104620003D20626C6F636B5F6269745F6F66667377 -:10463000657400626C6F636B5F656E645F62697462 -:104640005F6F6666736574203E20626C6F636B5F9C -:104650006269745F6F66667365740072656D616927 -:104660006E696E675F6269745F6C656E67746820FF -:104670003C3D2072656D61696E696E675F62697449 -:104680007300696E7075745F6269745F6F666673DC -:104690006574203C3D207472616E736665722D3EB8 -:1046A0007061796C6F61645F6C656E202A203800E0 -:1046B0006F75747075745F6269745F6F6666736539 -:1046C00074203C3D2036340072656D61696E696E00 -:1046D000675F6269745F6C656E677468203D3D203A -:1046E000300028726573756C74203E2030292026B6 -:1046F000262028726573756C74203C3D2036342961 -:104700002026262028726573756C74203C3D20623B -:1047100069745F6C656E6774682900006465737402 -:10472000696E6174696F6E20213D202828766F695B -:1047300064202A2930290076616C756520213D208E -:104740002828766F6964202A293029006F666673ED -:1047500065745F77697468696E5F626C6F636B2004 -:104760003C2028333255202D205F5F6275696C74C0 -:10477000696E5F6F66667365746F66202843616E4D -:10478000617264427566666572426C6F636B2C2061 -:1047900064617461292900006F75745F696E73200C -:1047A000213D202828766F6964202A2930290000BD -:1047B0007372635F6C656E203E2030550000000010 -:1047C0002863616E5F696420262030783146464652 -:1047D000464646465529203D3D2063616E5F69642B -:1047E00000000000616C6C6F6361746F722D3E732A -:1047F0007461746973746963732E63757272656E24 -:10480000745F75736167655F626C6F636B73203E85 -:10481000203000007472616E736665725F69642097 -:10482000213D202828766F6964202A29302900003C -:1048300073746174652D3E6275666665725F626C45 -:104840006F636B73203D3D202828766F6964202AB2 -:10485000293029002E2E2F2E2E2F6D6F64756C653A -:10486000732F6C696263616E6172642F63616E6144 -:1048700072642E63006974656D2D3E6672616D65AC -:104880002E646174615F6C656E203E203000000014 -:104890000000000001380008ED3700082938000842 -:1048A00015380008213800080D380008F9370008CD -:1048B000E5370008353800086D61696E00000000BA -:1048C000D848000828250020D82500200100000035 -:1048D0001D3A00080000000069646C6500000000DB -:1048E0000C1E0000447B4144B457494401000000C1 -:1048F000424444444444444400000000444444448A -:104900004444444400000000444444444444444477 -:104910000000000044444444444444442C20667550 -:104920006E6374696F6E3A200000000061737365F6 -:104930007274696F6E2022257322206661696C652E -:10494000643A2066696C6520222573222C206C69EC -:104950006E65202564257325730A0000430000005E -:1049600060B8FF7F0100000004110020000000007B -:104970000000000000000000000000000000000037 -:104980000000000000000000000000005C4900087A -:104990000000000000000000000000000000000017 -:1049A0000000000000000000000000000000000007 -:1049B00000000000000000000000000000000000F7 -:1049C0000000000000000000000000006400000083 -:0C49D00000000000FE2A0100D2040000DC +:100000000009002069040008C114000865140008F4 +:10001000A514000865140008851400086B04000886 +:100020006B0400086B0400086B0400087D350008B1 +:100030006B0400086B0400086B040008113A000808 +:100040006B0400086B0400086B0400086B040008D4 +:100050006B0400086B0400083D370008693700088E +:1000600095370008C1370008ED3700086B04000819 +:100070006B0400086B0400086B0400086B040008A4 +:100080006B0400086B0400086B040008712400086E +:10009000DD240008312500088525000819380008EE +:1000A0006B0400086B0400086B0400086B04000874 +:1000B0006B0400086B0400086B0400086B04000864 +:1000C0006B0400086B0400086B0400086B04000854 +:1000D0006B04000825290008392900086B04000872 +:1000E000813800086B0400086B0400086B040008EA +:1000F0006B0400086B0400086B0400086B04000824 +:100100006B0400086B0400086B0400086B04000813 +:100110006B0400086B0400086B0400086B04000803 +:100120006B0400086B0400086B0400086B040008F3 +:100130006B0400086B0400086B0400086B040008E3 +:100140006B0400086B0400086B0400086B040008D3 +:100150006B0400086B0400086B0400086B040008C3 +:1001600053B94AB9002908BF00281CBF4FF0FF311E +:100170004FF0FF3000F076B9ADF1080C6DE904CE18 +:1001800000F006F8DDF804E0DDE9022304B0704772 +:100190002DE9F047089E0D4604468846002B4DD1B8 +:1001A0008A42944668D9B2FA82F252B101FA02F355 +:1001B000C2F1200120FA01F10CFA02FC41EA030825 +:1001C00094404FEA1C41B8FBF1F71FFA8CFE01FB8B +:1001D000178807FB0EF0230C43EA084398420AD91C +:1001E0001CEB030307F1FF3580F01E81984240F2BB +:1001F0001B81023F63441B1AB3FBF1F001FB103378 +:1002000000FB0EFEA4B244EA0344A6450AD91CEB47 +:10021000040400F1FF3380F00981A64540F2068115 +:10022000644402380021A4EB0E0440EA07401EB1EA +:100230000023D440C6E90043BDE8F0878B4208D9CB +:10024000002E00F0EE800021C6E900050846BDE85A +:10025000F087B3FA83F100294AD1AB4202D382423C +:1002600000F2FC80841A65EB030301209846002EFF +:10027000E2D0C6E90048DFE702B9FFDEB2FA82F257 +:10028000002A40F09180A1EB0C0001214FEA1C47AD +:100290001FFA8CFEB0FBF7F307FB1300250C45EAB1 +:1002A00000450EFB03F0A84208D91CEB050503F13D +:1002B000FF3802D2A84200F2CE8043462D1AB5FB89 +:1002C000F7F007FB10550EFB00FEA4B244EA05440C +:1002D000A64508D91CEB040400F1FF3502D2A6455F +:1002E00000F2B6802846A4EB0E0440EA03409EE7E5 +:1002F000C1F120078B4022FA07FC4CEA030C25FAD7 +:1003000007FA4FEA1C49BAFBF9F820FA07F309FB90 +:1003100018AA8D401FFA8CFE1D4300FA01F308FB5A +:100320000EF02C0C44EA0A44A04202FA01F20BD966 +:100330001CEB040408F1FF3A80F08880A04240F2F0 +:100340008580A8F102086444241AB4FBF9F009FB83 +:10035000104400FB0EFEADB245EA0444A64508D9A0 +:100360001CEB040400F1FF356CD2A6456AD90238B3 +:10037000644440EA0840A0FB0295A4EB0E04AC42A2 +:10038000C846AE4656D353D0002E69D0B3EB080210 +:1003900064EB0E0422FA01F304FA07F71F43CC4082 +:1003A000C6E90074002147E70CFA02FCC2F1200103 +:1003B00025FA01F34FEA1C4720FA01F195400D435D +:1003C000B3FBF7F107FB11331FFA8CFE280C40EA50 +:1003D000034001FB0EF3834204FA02F408D91CEB3C +:1003E000000001F1FF382FD283422DD90239604439 +:1003F000C01AB0FBF7F307FB1300ADB245EA0045A6 +:1004000003FB0EF0A84208D91CEB050503F1FF38E9 +:1004100016D2A84214D9023B6544281A43EA014186 +:1004200038E73146304607E72F46E4E61846F9E656 +:100430004B45A9D2B9EB020865EB0C0E0138A3E7D6 +:100440004346EAE7284694E74146D1E7D0467BE7B2 +:100450006444023847E7023B65442FE7084606E755 +:100460003146E9E6704700BF02E000F000F8FEE721 +:1004700072B6284880F30888274880F309882748FF +:100480004EF60851CEF200010860022080F3148875 +:10049000BFF36F8F03F0E4F803F0C0F803F0E2F865 +:1004A0004FF055301E491B4A91423CBF41F8040BA6 +:1004B000FAE71C49184A91423CBF41F8040BFAE79D +:1004C00019491A4A1A4B9A423EBF51F8040B42F896 +:1004D000040BF8E700201749174A91423CBF41F846 +:1004E000040BFAE703F09EF803F0BEF8134C144D2A +:1004F000AC4203DA54F8041B8847F9E700F03CF8F3 +:10050000104C114DAC4203DA54F8041B8847F9E74C +:1005100003F086B800090020001100200000000848 +:100520000001002000090020E03B0008001100202D +:100530002411002028110020A025002060010008BF +:100540006001000860010008600100082DE9F04F1B +:10055000C1F80CD0C3689D46BDE8F08F002383F33B +:1005600011882846A047002002F09CFDFEE702F01B +:1005700021FD00DFFEE700002DE9F04102F09CFFC5 +:10058000074602F0E7FF054600283ED12B4B9F426D +:100590003BD001339F423BD0294B27F0FF029A42C8 +:1005A0003AD1F8B200F052FAA84642F2107400F0C4 +:1005B00057FC08B10024A04600F04EFA064678B376 +:1005C00084BB464635B11F4B9F4203D0002402F046 +:1005D000B9FF2646002002F079FF1B4B9B6813F001 +:1005E000400322D00EB100F031F800F097FC00F08B +:1005F00077FE00F067FF0546CCB100F063FF401BBB +:10060000A04214D900F022F8F3E7A8460024CEE770 +:1006100004464FF00108CAE780464FF47A74C6E7F3 +:100620000446CFE74FF47A74CCE71C46DDE700F0D0 +:1006300025FD012002F03CFDDEE700BF010007B010 +:10064000000008B0263A09B0000C014038B51D4A38 +:100650001D4B1968013134D004339342F9D11B4C3E +:10066000194DD4F80424AA422BD3194B9B6803F1EB +:10067000006303F5C8439A4223D202F037FF02F029 +:1006800049FF002000F046FE0220124B187000F0D7 +:100690007DFE114BDA690022DA61D96999699A61A4 +:1006A0009B6972B64FF0E023C3F8085DD4F80034BC +:1006B000D4F80424202181F311889D4683F308880F +:1006C000104738BD2064000800640008006000087E +:1006D00000110020281100200010024049F269009A +:1006E000084A136899B21B0C00FB013344F25061B5 +:1006F0001360054B186882B2000C01FB0200186001 +:1007000080B27047201100201C11002010B5044653 +:100710000021102200F056FE034B03CB20606160E5 +:100720001868A06010BD00BFE8F7FF1F2DE9F04377 +:10073000BBB000F0C7FE40F2ED22204DAB68C31AFB +:10074000934232D906AF2B4628220021A8603846B2 +:1007500001F0C2FB05F10E0000F02CFE002604465D +:100760005FFA80F905F10E08F3B2F100994501F145 +:10077000280107D908EB06030822384601F0ACFB34 +:100780000136F1E708230122CDE902320C4B053492 +:1007900001933023A4B20093CDE9047405A3D3E9F7 +:1007A0000023297B074801F0ADF93BB0BDE8F08399 +:1007B000AFF3008078F6339F93CACD8D702100206F +:1007C0007D2100204421002070B50D4614461E46B0 +:1007D00001F02EF950B9022E10D1012C0ED112A326 +:1007E000D3E900230120C5E9002307E0282C10D01D +:1007F00005D8012C09D0052C0FD0002070BD302C5D +:10080000FBD10BA3D3E90023ECE70BA3D3E900232F +:10081000E8E70BA3D3E90023E4E70BA3D3E9002324 +:10082000E0E700BFAFF30080401DA12026812A0B26 +:1008300078F6339F93CACD8D9E6AC421818A46EE95 +:1008400026417272DF25D7B7F017304A39059E5618 +:1008500038B50D460446034620222846002101F003 +:100860003BFB22792346032A28BF0322284603F8AC +:10087000042F2021022201F02FFB62792346072A50 +:1008800028BF0722284603F8052F2221032201F062 +:1008900023FBA2792346072A28BF0722284603F80C +:1008A000062F2521032201F017FB284610222821BC +:1008B00004F1080301F010FB382038BD2DE9F04F9A +:1008C0000024ADF5017D0EAE40F2751280460F4654 +:1008D00022A82146219400F075FD21464822304689 +:1008E00000F070FD00F0EEFD4FF47A72B0FBF2F014 +:1008F000544B21AD186093E80700012386E80700F8 +:100900000DF15A003382FFF701FF4EF603033384E3 +:1009100006AB18464C4903F0B3F81F222946306451 +:10092000304686F83C20FFF793FF08220446014634 +:1009300012AB284601F0D0FA08222846A1180DF182 +:10094000490301F0C9FA082228460DF14A0304F1CF +:10095000100101F0C1FA2022284613AB04F118015E +:1009600001F0BAFA4022284614AB04F1380101F034 +:10097000B3FA0822284616AB04F1780101F0ACFA6C +:10098000082228460DF1590304F1800101F0A4FA70 +:1009900004F1880A0DF15A0904F5847B4B4651464F +:1009A000082228460AF1080A01F096FAD34509F10F +:1009B0000109F3D10822594628461BAB01F08CFAF5 +:1009C0004FF0000904F5887496F834304B450AD985 +:1009D000B36B21464B440822284601F07DFA0834C7 +:1009E00009F10109F0E74FF0000996F83C3004EBFB +:1009F000C9014B4508D9336C08224B44284601F005 +:100A00006BFA09F10109F0E700230393BB7E07317C +:100A1000029307F1190301930123C1F3CF01CDE93B +:100A200004510093404605A3D3E90023F97E01F069 +:100A300069F80DF5017DBDE8F08F00BF9E6AC42105 +:100A4000818A46EE2C110020903A0008014B187064 +:100A5000704700BF38110020F0B5334B85B01C7BC8 +:100A600034B10E22314B1A810024204605B0F0BD6E +:100A70002F4A02AB1068516803C308232D492E4842 +:100A80000DEB030202F0DCFF054630B90A22274BCA +:100A90002A481A8100F0E2FCE6E70169B1F5CE3F91 +:100AA00006D90B22214B26481A8100F0D7FCDCE73F +:100AB000438BB3F57A7F09D00C211C4A2148118160 +:100AC0004FF47A72194600F0C9FCCEE71E4A024480 +:100AD00002F11003994204D21022144B1B481A81D0 +:100AE000E3E710398E1A2046134900F0EFFC074661 +:100AF0003246204605F1180100F0E8FCAB689F4241 +:100B000002D1EB6898420AD00D22084B1A8100905E +:100B10003B46D5E902120E4800F0A0FCA4E70D48C0 +:100B200000F09CFC0124A0E7702100202C11002083 +:100B3000413B0008DC9B010000640008B03A00085B +:100B4000BC3A0008CE3A0008089CFFF7EC3A0008CF +:100B5000093B0008323B00082DE9F04FADB006AF6D +:100B600080460C4600F064FF0546002859D1237EDC +:100B7000022B1AD1E38A012B17D100F0A3FC064601 +:100B8000FFF7ACFD4FF4C873B0FBF3F202FB1300A8 +:100B9000DFF8B49206F5167680B2E37E0644C9F813 +:100BA000006033B90022A94B1A709C37BD46BDE8DE +:100BB000F08FA38AEEB2013BB34205F101050BD9D8 +:100BC0003B1D1E44E900002308222046009601F048 +:100BD000F80101F043F8ECE707F11400FFF796FD88 +:100BE000324607F11401381D02F01AFF03460028AF +:100BF000D8D10F2E08D8954B1E70D9F80030A3F528 +:100C00001673C9F80030D0E7FA1CF870014600925C +:100C10002046072201F022F84046F97800F000FF54 +:100C2000C3E7E38A282B26D010D8012B1ED0052B32 +:100C3000BBD1BFF34F8F8649864BCA6802F4E0628E +:100C40001343CB60BFF34F8F00BFFDE7302BACD118 +:100C5000637E814D01336A7BDBB29342E94603D167 +:100C6000E27E2B7B9A4265D0CD469EE721464046E8 +:100C7000FFF724FE99E7A38A013B9BB2C92B94D8C6 +:100C8000754D2E7B26BB05F10C03009308223346DD +:100C90003146204600F0E2FF731CF2B2D9001E4636 +:100CA000A38A013B9A4205DA0E322A4400920023BD +:100CB0000822EEE700230022C5E900230023AB60F1 +:100CC00085F8D730C5F8D8302B7B0BB9E37E2B7372 +:100CD000002507F114060822294630463B1DC7E9C6 +:100CE0000155FD6001F0F8F83B7A05F10109AB42CE +:100CF0004FEAC90107D9FB6808222B44304601F0AE +:100D0000EBF84D46F0E70023C1F3CF01E07ECDE9DB +:100D100004610393A37E19340293282301460093B0 +:100D2000404647A3D3E90023019400F0EBFEFFF710 +:100D3000FDFC3AE74FF0000807F11403A7F8148010 +:100D40001022009341460123204600F087FFA68A27 +:100D5000023EB6B2F31C9B109B000733DB08A9EBE5 +:100D6000C3039D460DF1180A1FFA88F34FEAC80124 +:100D7000B34201F110010AD20AEB080300930822E2 +:100D80000023204600F06AFF08F10108ECE795F81F +:100D9000D70000F0C9FAD5F8D83004461BB995F849 +:100DA000D70000F0D1FAD5F8D83033449C4204D2B1 +:100DB00095F8D700013000F0C7FA4FF000084FEA6D +:100DC000960B1FFA88F18B45D5E9003209D90AEB59 +:100DD000880103EB8800012200F0FCFA08F1010809 +:100DE000EFE7F31842F10002C5E90032D5F8D83038 +:100DF00095F8D70006EB0308C5F8D88000F094FA00 +:100E0000804509D395F8D730D5F8D8000133001BB9 +:100E100085F8D730C5F8D800FF2E08D800232B73EB +:100E200000F0A4FAFFF718FE08B1FFF70FFC2B68DB +:100E30000A4A9B0A013313810023AB6014E700BF09 +:100E400026417272DF25D7B7402100203D210020C6 +:100E500000ED00E00400FA05702100202C110020B4 +:100E600030B54FF00054244B226885B09A4207D029 +:100E700002F07AFB0446A8B90024204605B030BD34 +:100E8000627D1E4B1E481A70237DC92203731D49C3 +:100E90000E3000F085FA2046E022002100F092FAA0 +:100EA0000124EAE7184A194DD36943F00073D3616E +:100EB000AA6D174B9A42DFD12B6E013B7E2BDBD8FC +:100EC000144A01AB07CA83E807001846032100F063 +:100ED00013FB6B6D83424FF00003CDD12A6D8A4224 +:100EE00003BFAB652A6E054B1C4601BF1A70EA6D45 +:100EF000094B1A60C1E700BF9AAD44C53811002004 +:100F00007021002016000020001002400066004002 +:100F10005041A0B0586600401811002002232DE96E +:100F2000F0434A4C85B0637100230293484BD3F8D9 +:100F300000C0BCF57A7F12D3464F474BB7FBFCF598 +:100F40009C458CBF0A231123B5FBF3F603FB165215 +:100F5000591EC8B2002A3ED002290B46F4D89DF88B +:100F60000B303E495A1E9DF80A303D48013B1B0498 +:100F700043EA0253BDF80820013A13434B6001F0E5 +:100F800037FD00230193374B374900934FF48052CC +:100F9000364B374800F01CFD364B197811B13448F8 +:100FA00000F03EFD00F08EFA0546FFF797FB4FF488 +:100FB000C873B0FBF3F202FB130305F516709BB286 +:100FC00018442D4B186002F0C5FA08B10F23238195 +:100FD00005B0BDE8F083731EB3F5806FBFD24FF448 +:100FE0007A75C0EBC00E0EF103034FEAE30909FB6B +:100FF0000555C3F3C703C11AC9B209F101088844F2 +:10100000B5FBF8F5B5F5617F08D90EF1FF33C3F3F1 +:10101000C703C11A581E0F28C9B214D84A1E072A7E +:101020008CBF00220122581800FB0660B7FBF0F7C6 +:10103000BC4594D1002A92D0ADF808608DF80A30F2 +:101040008DF80B108BE71346EDE700BF2C11002045 +:1010500018110020005125023F420F0010110020FE +:1010600088220020C90700083C110020590B000805 +:101070004421002038110020402100202DE9F04FAC +:1010800093A7D7E900670FF25029D9E90089854D68 +:1010900093B0DFF814B2854C284600F097FD0DF1AF +:1010A000300A079070B310220021504600F08AF9F0 +:1010B0004FF00002079B197B61F303028DF830208B +:1010C000586899680EAA03C21B680D9A584663F3C4 +:1010D0001C029DF830300D9243F020038DF8303023 +:1010E00000235246194601F093FC079028B9284680 +:1010F00000F070FD079B2370CEE72378072B3CD8C8 +:101100000133237018220021504600F05BF9DFF80C +:1011100098B1674C002352461946584601F0A0FC8E +:10112000014670BB102208A800F04CF9E36883F078 +:101130001003E36000F0C8F90DF1240C0B4612A96E +:10114000024611E903008CE803009DF83410C1F356 +:101150000300890649BF0E99BDF83810C1F31C0180 +:1011600041F0004158BFC1F30A018DF82C000891ED +:10117000284608A900F0F8FECCE7284600F02AFD32 +:10118000C0E7284600F054FC8346002844D100F014 +:1011900099F9484B1A6890423ED300F093F90446FF +:1011A000FFF79CFA4FF4C872B0FBF2F101FB12009A +:1011B0008DF820B0DFF800B13E4B04F5167480B214 +:1011C0009BF8001004441C6011B901238DF82030F5 +:1011D00050460791FFF79AFA07990DF12100C1F1E6 +:1011E0001004E4B2062C28BF06245144224600F025 +:1011F000D7F808AB039318230293304B01340193C3 +:101200000123E4B2009332463B462846049400F0A2 +:1012100011FC00238BF8003000F054F9284A294CC7 +:101220001368C31AB3F57A7F31D3106000F04CF91C +:1012300002460B46284600F0D7FC284600F0F8FB93 +:1012400028B3237BDFF880B0002B14BF03230223D5 +:101250008BF8053000F036F94FF47A73B0FBF3F0F9 +:101260005146CBF800005846FFF7F2FA18230293D4 +:10127000164B0730019340F25513C0F3CF00CDE970 +:1012800003A0009342464B46284600F0D3FB237B45 +:101290002BB1FFF74BFA237B002B7FF4FAAE13B090 +:1012A000BDE8F08F44210020882200205522002034 +:1012B00000080140402100203D2100203C21002069 +:1012C00050220020702100202C11002054220020E8 +:1012D000401DA12026812A0BF1C6A7C1D068080FA6 +:1012E00070B501F0BFFF0024084E094D308028681A +:1012F0003388834208D901F0B1FF2B6804440133DD +:10130000B4F5C84F2B60F2D370BD00BF842200201B +:101310005822002002F044B800F10060920000F56D +:10132000C84001F0DFBF0000054B1A68054B1B8861 +:101330009B1A834202D9104401F090BF00207047ED +:10134000582200208422002038B50446064D286823 +:10135000204401F089FF28B928682044BDE83840BE +:1013600001F094BF38BD00BF58220020064991F813 +:10137000243033B100230822086A81F82430FFF7B3 +:10138000CBBF0120704700BF5C220020022802BFB3 +:101390004FF48012014B1A61704700BF00080140F2 +:1013A000002310B5934203D0CC5CC4540133F9E759 +:1013B00010BD000003460246D01A12F9011B002995 +:1013C000FAD1704703460244934202D003F8011B4E +:1013D000FAE770472DE9F8431F4D144695F824208D +:1013E0000746884652BBDFF870909CB395F82430CE +:1013F0002BB92022FF2148462F62FFF7E3FF95F823 +:1014000024004146C0F10802A24228BF224605EB53 +:101410008000D6B29200FFF7C3FF95F82430A41BDA +:101420001E44F6B2082E17449044E4B285F82460B6 +:10143000DBD1FFF79BFF0028D7D108E02B6A03EB35 +:1014400082038342CFD0FFF791FF0028CBD1002049 +:10145000BDE8F8830120FBE75C2200200FB40020E8 +:1014600004B07047EFF30983EFF30583044B9A6BE5 +:10147000DA6A9A6A9A6A9A6A9A6A9A6A9B6AFEE72A +:1014800000ED00E0EFF30983EFF30583044B9A6B63 +:101490009A6A9A6A9A6A9A6A9A6A9B6AFEE700BF8F +:1014A00000ED00E0EFF30983EFF30583034B5A6B84 +:1014B0009A6A9A6A9A6A9A6A9B6AFEE700ED00E065 +:1014C000FEE7000001F0A6BF01F07EBF30B5094D78 +:1014D0000A4491420DD011F8013B5840082340F3D3 +:1014E0000004013B2C4013F0FF0384EA5000F6D1C6 +:1014F000EFE730BD2083B8ED4FF0FF33F7B500EBD9 +:1015000081061946DFF848C0DFF848E0B0421BD03A +:1015100050F8042B01AF0192042217F8014B81EA25 +:10152000046108240D46DB184941013C002DBCBF75 +:1015300083EA0C0381EA0E0114F0FF04F2D1013AB0 +:1015400012F0FF02E9D1E1E7D843C94303B0F0BD8F +:101550009336EAA9EBE1F0422DE9F041C56915B9EE +:10156000C161BDE8F0814B68AC4623F06047C3F32E +:101570008A4616EA230638BF3E464FEAD37EC3F3B7 +:1015800080782B465A68BEEBD27F22F060440AD0A6 +:10159000002A18DAA40CB44217D19D420FD10D6075 +:1015A000DEE71346EEE7A74207D102F08044C2F31C +:1015B000807242450BD054B1EFE708D2EDE7CCF88A +:1015C00000100B60CDE7B44201D0B442E5D81A68F0 +:1015D0009C46002AE5D11960C3E700002DE9F047D9 +:1015E0004FF47F49089D01F007044FEAD5082244D3 +:1015F00005F0070500EBD100944201D1BDE8F0876A +:1016000004F0070705F0070A57453E4638BF56461F +:10161000111BC6F108068E4228BF0E46E108415C48 +:1016200008EBD50E13F80EC0B94029FA06F721FAD7 +:101630000AF1FFB28CEA010147FA0AF739408CEA55 +:10164000010C03F80EC034443544D5E7082341F2B9 +:10165000210280EA012001B24000002980B203F19A +:10166000FF33B8BF504013F0FF03F4D170470000C0 +:1016700038B50C468D18A54200D138BD14F8011BB1 +:10168000FFF7E4FFF7E700000346006848B102688F +:1016900019891A60DA88013292B29142DA8038BF31 +:1016A0001A81704770B504460D4688B0202200218B +:1016B0006846FFF787FE20460495FFF7E5FF0246E0 +:1016C00058B16B46054608AE1C4603CCB4422860B0 +:1016D0006960234605F10805F6D1104608B070BDD3 +:1016E000082817D909280CD00A280CD00B280CD0B0 +:1016F0000C280CD00D280CD00E2814BF4020302010 +:1017000070470C2070471020704714207047182035 +:101710007047202070470000082817D90C280CD9E2 +:1017200010280CD914280CD918280CD920280CD929 +:1017300030288CBF0F200E207047092070470A20E8 +:1017400070470B2070470C2070470D207047000039 +:1017500010B54B6823B9CA8A63F30902CA8210BD67 +:10176000C4681A681C60C360438A013B43824A60B4 +:10177000EFE700002DE9F84F1D46CB8A0F46C3F373 +:1017800009010629814692460B4630D00020AAB2B4 +:1017900007F119049EB2052E1FFA80F80FD8904564 +:1017A00003F1010306D3FB8A0A4462F30903012013 +:1017B000FB821AE01AF800600130E654EAE790452F +:1017C000F1D21C23A1F1060BBBFBF3F203FB12BB0E +:1017D0007C681FFA8BF6002C45D14846FFF754FF72 +:1017E000044638B978606FF00200BDE8F88F4FF01A +:1017F0000008E6E70026066078604FF0000BADB207 +:10180000454510D90AEB0803221D13F8011B08F106 +:1018100001089155B1B21B291FFA88F82BD0454514 +:1018200006F10106F1D8FB8AC3F30902154465F3FA +:101830000903BCE71C46013292B22368002BF9D1A0 +:10184000AB1F0B441C21B3FBF1F301339BB29A4253 +:10185000D3D2BBF1000FD0D14846FFF715FF20B916 +:10186000C4F800B0BFE70122E7E7C0F800B05E4669 +:1018700020600446C1E74545D5D94846FFF704FF37 +:1018800008B92060AFE7C0F800B000262060044629 +:10189000B6E700002DE9F04F85B007469146CDE947 +:1018A0000113BDF83C50002A00F08F802DB10E9B33 +:1018B000002B00F08A80072D30D807F10C00FFF7CD +:1018C000E3FE044628B96FF00204204605B0BDE8E7 +:1018D000F08F14220021FFF775FD2A460E9904F1BE +:1018E0000800FFF75DFD681CC0B2FFF715FFFFF7AA +:1018F000F7FE207499F80020431E9BB202F01F02ED +:10190000234462F03F021A72019B384643F00041C3 +:1019100061602146FFF720FE0124D6E74FF0000862 +:101920004FF0800A4646444600F10C0303930398A7 +:10193000FFF7AAFE83460028C5D014220021FFF736 +:1019400041FD002E38D10220029BABF808300E9BDF +:1019500000F10802D2B299195A440130C0B20828E5 +:1019600001D0AE422AD3FFF7D7FEFFF7B9FEAE4251 +:1019700008BF4FF0400A99F80020019B411E02F079 +:101980001F0242EA4812C9B24AEA020A594443F025 +:10199000004281F808A08BF8100059463846CBF871 +:1019A0000420FFF7D9FD0134AE424FF0000A24B203 +:1019B00088F00108BBD188E70020C8E711F801CB07 +:1019C000013602F801CBB6B2C7E76FF001047CE73D +:1019D000F8B5044615460E46282200211F46FFF79B +:1019E000F1FC069BB5F5001F6360079B28BF4FF60F +:1019F000FF7223624FF0000338BF6A09A76004F149 +:101A00000C0097B29A4205D80023036027826382B4 +:101A1000A382F8BD0660013330462036F2E70000AD +:101A200003781BB94BB2002BC8BF01707047000090 +:101A3000007870472DE9F74FDDF83C9080469246DC +:101A40009B46BDF830500D9E9DF83840BDF8407063 +:101A5000B9F1000F01D1002F51D11F2C4FD898F8A8 +:101A60000000B0B9072F47D835F0030347D13A46F5 +:101A700049464FF6FF70FFF7FBFD20F001002D02F5 +:101A8000400445EA0464400C44EA40244FF6FF73E6 +:101A900021E040EA0520072F40EA0464F6D900253A +:101AA0004FF6FF73C5F12000A5F120022AFA05F1D7 +:101AB0000BFA00F001432BFA02F211431846C9B2A7 +:101AC000FFF7C4FD0835402D0346EBD13A464946A1 +:101AD000FFF7CEFD0346324621464046CDE900974A +:101AE000FFF7D8FE33780133DBB21F2B88BF00230A +:101AF000337003B0BDE8F08F6FF00300F9E76FF0CB +:101B00000100F6E72DE9F04F85B0DDF848809246F8 +:101B100006469B460F9D9DF840209DF84490BDF8D9 +:101B20004C70B8F1000F01D1002F48D11F2A46D8C0 +:101B30003378002B46D00C0244EA02649DF838103A +:101B400044EAC93444EA01441C43072F44F08004AA +:101B500032D900234FF6FF72C3F1200CA3F120000D +:101B60002AFA03F10BFA0CFC41EA0C012BFA00F003 +:101B70000143C9B210460393FFF768FD039B024679 +:101B80000833402BE8D13A464146FFF771FD034642 +:101B90002A4621463046CDE90087FFF77BFEB9F1A2 +:101BA000010F06D12B780133DBB21F2B88BF002336 +:101BB0002B7005B0BDE8F08F4FF6FF73E8E76FF0CC +:101BC0000100F6E76FF00300F3E70000C06900B121 +:101BD00004307047C3691A68C261C2681A60C36082 +:101BE000438A013B438270472DE9F041D0F81880C9 +:101BF00014461D4641460027174E09B9BDE8F0813D +:101C0000D1E90223A21A65EB0303964277EB0303A3 +:101C10001ED283698B420DD1FFF79AFD83691B6841 +:101C20008361C3680B60438AC1608169013B884658 +:101C30004382E2E7FFF78CFD0B68C8F80030C36809 +:101C40000B60438AC160013B4382D8F80010D4E79F +:101C500088460968D1E700BF80841E002DE9F04F57 +:101C60008BB00D4614469B468046DDF85090002808 +:101C700000F01A81B9F1000F00F01681531E3F2BBE +:101C800000F21281012A03D1BBF1000F40F00C8158 +:101C90000023CDE90833B8F81430B5EBC30F4FEA91 +:101CA000C30703D300200BB0BDE8F08F2B199F4270 +:101CB000D8F80C3036BF7F1B2746FFB21BB9D8F8C7 +:101CC0001030002B7BD02F2D4ED8C5F13006B742F7 +:101CD0004FF0000334BF3E46F6B200932946324629 +:101CE000D8F8080008ABFFF779FCA7EB060A3544E3 +:101CF0005FFA8AFA3021B8F8143003F10053063B3A +:101D0000DB000493D8F80C300393039B13B1BAF1B2 +:101D1000000F2CD1D8F8100040B1BAF1000F05D057 +:101D20005246009608AB691AFFF758FC38B2002FEC +:101D3000B8D066070AD00AAB03EBD40111F8083C0F +:101D4000624202F00702134101F8083C082C3DD919 +:101D5000102C40F2B680202C40F2B880BBF1000F6E +:101D600000F09D80082335E0BA460026C2E7049BB8 +:101D7000E02B28BFE02306930B44AB42059315D913 +:101D80005A1B924538BF5246039828BFD2B20096DC +:101D9000691A08AB04300792FFF720FC079A164433 +:101DA000AAEB020A1544F6B25FFA8AFA049B069A75 +:101DB00005999B1A0493039B1B680393A5E7009363 +:101DC0003A462946D8F8080008ABADE7BBF1000F4A +:101DD00013D00123B4EBC30F6CD0082C12D89DF89C +:101DE0002030621E23FA02F2D50706D54FF0FF32EB +:101DF00002FA04F423438DF820309DF8203089F84E +:101E0000003050E7102C12D8BDF82030621E23FAA3 +:101E100002F2D10706D54FF0FF3202FA04F4234351 +:101E2000ADF82030BDF82030A9F800303BE7202C79 +:101E30000FD80899631E21FA03F3DA0705D54FF08E +:101E4000FF3202FA04F40C430894089BC9F80030EE +:101E500029E7402C2BD0DDE90865611EC4F1210281 +:101E6000A4F1210326FA01F105FA02F225FA03F39F +:101E700011431943CB0712D50122A4F12003C4F169 +:101E8000200102FA03F322FA01F1A240524243EA8E +:101E9000010363EB430332432B43CDE90823DDE920 +:101EA0000823C9E90023FEE66FF00100FBE66FF0AE +:101EB0000800F8E6082CA0D9102CB3D9202CEED8B5 +:101EC000C3E7BBF1000FADD0022383E7BBF1000FE6 +:101ED000BBD004237EE70000012A30B5144638BF8A +:101EE00001220025402A28BF402285B0012CCDE9DF +:101EF000025517D81B788DF8083053070AD004AB69 +:101F000003EBD20515F8083C544204F00704A34043 +:101F100005F8083C0346009102A80021FFF75EFB8C +:101F200005B030BD082CE5D9102C03D81B88ADF8BE +:101F30000830E2E7202C02D81B680293DDE7D3E9E2 +:101F40000045CDE90245D8E710B5CB681BB98B60D9 +:101F50000B618B8210BDC4681A681C60C360438A21 +:101F6000013B4382CA60F0E72DE9F04FD1F80080D1 +:101F700093B018F0800FCDE90323C8F3C01207BF58 +:101F80004FF0020B1646C8F3C03BC8F30626B8F163 +:101F9000000F04460D4680F2D48118F0C04305932B +:101FA00040F0CF810B7B002B00F0CB81BBF1020F07 +:101FB00003D00178B14240F0C78108F07F0107915A +:101FC0007AB3C8F3074A2B4493F80390760646EA9F +:101FD0000B4608F07F0246EA82465FEAD91346EADA +:101FE0000A06069300F0918000220023CDE90A231F +:101FF00008F07F03009352465B46204667680AA9B3 +:10200000B84700287ED0A7699FB9314604F10C007B +:10201000FFF748FB0746E0B96FF0020013B0BDE8D8 +:10202000F08FC8F30F2A18F07F0F08BF0AF0030AD9 +:10203000C9E73B699E420DD03F68002FF9D1314678 +:1020400004F10C00FFF72EFB07460028E4D0A3693B +:102050003B60A7610026DDE90A234FF6FF70C6F159 +:10206000200E22FA06F103FA0EFEA6F1200C23FA46 +:102070000CFC41EA0E0141EA0C01C9B20836099292 +:102080000893FFF7E3FADDE90832402EE7D1B88282 +:10209000FB7D09F01F06C3F384039B1B98B2002B42 +:1020A000BCBF00F120031BB2D7E9022152EA0100B4 +:1020B000C8F304680FD00398821A049860EB0101FA +:1020C000A74890424FF000028A4104D3069A002AA2 +:1020D0005BD0012B23DDFA7D4FEA890302F0030276 +:1020E00003F07C031343FB7539462046FFF730FBB2 +:1020F000069BA3B9FB7DC3F38402013262F386031E +:10210000FB7504E06FF00B0088E7A76917B96FF063 +:102110000C0083E73B699E42BAD03F68F6E719F0AE +:10212000400F32D0039B1422BB60049B0021FB6054 +:102130000DA8FFF747F9039B20460A93049BADF8CF +:102140003EA00B932B1D0C932B7B8DF840B0013BD5 +:10215000DBB2ADF83C30079B8DF841608DF8433021 +:1021600094F824308DF8428083F001038DF84430D8 +:102170000AA9A3689847FB7DC3F38403013303F0E6 +:102180001F039B02FB82002048E7FB7DC9F340123E +:10219000B2EBD31F40F0DB80C3F38403B34240F0C3 +:1021A000D98006992B7B4FEA9912002934D0D207A7 +:1021B00041D4032B40F2D180039BAE1DBB60049B36 +:1021C0003246FB602B7B3946033BDBB204F10C004B +:1021D000FFF7D0FA00280DDA20463946FFF7B8FAA3 +:1021E000FB7D0320C3F38403013303F01F039B0231 +:1021F000FB8213E7AB883B832A7B033AB88AD2B2CF +:102200003146FFF735FAFB7DB882DA43C2F3C012DC +:1022100062F3C713FB75B6E76AB92E1D013B324660 +:102220003946DBB204F10C00FFF7A4FA0028D3DB37 +:102230002A7B013AE2E7F98A013BC1F3090105294A +:10224000DAB25BD80023281D07F11A0C9A4208D98C +:1022500010F801EB01330CF801E001310629DBB283 +:10226000F4D1934228BF0023039938BF04330A9165 +:10227000049938BFDBB20B9107F11A010C91796810 +:1022800038BF5B190D910E93FB8AADF83EA0C3F3E6 +:1022900009031A44079BADF83C208DF8433094F8AD +:1022A00024308DF840B083F001038DF844300023D2 +:1022B0008DF841608DF842807B602A7BB88A013AB4 +:1022C000291DFFF7D5F93B8BB882834203D1204605 +:1022D000A3680AA9984720460AA9FFF735FEFB7DA7 +:1022E000B88AC3F38403013303F01F039B02FB820C +:1022F0003B8B984214BF112000208FE67B68002B97 +:10230000AFD0062001E063461C30D3F800C0BCF11A +:10231000000FF8D1091A081D05F1040C1844DDF866 +:1023200014E09DF814308E44BEF11B0F99D89A42E8 +:1023300097D91CF8013B00F8013B059B013305933D +:10234000EDE76FF0090069E66FF00A0066E66FF0EE +:102350000D0063E66FF00E0060E66FF00F005DE6C3 +:1023600080841E00F0B53F4D3F4FEB6943F0007392 +:10237000EB61EB693D4B9B6AD3F800623E4046F04F +:102380000106C3F80062D3F800423C4044EA00244E +:1023900044F00104C3F80042002955D0002006464D +:1023A000C3F81C02C3F80402C3F80C02C3F81402F9 +:1023B00003EBC00401300E28C4F84062C4F8446244 +:1023C000F6D100274FF0010C9678148816F0010F13 +:1023D00018BFD3F804E20CFA04F01CBF40EA0E0E5A +:1023E000C3F804E216F0020F18BFD3F80CE203EBB7 +:1023F000C4041CBF40EA0E0EC3F80CE2760748BFC7 +:10240000D3F8146207F1010744BF0643C3F814620E +:102410005668B942C4F84062966802F10C02C4F8EA +:102420004462D3F81C4240EA0400C3F81C02CBD13A +:10243000D3F8002222F00102C3F80022EB6923F056 +:102440000073EB61EB69F0BD0122C3F84012C3F8E1 +:102450004412C3F80412C3F81412C3F80C22C3F8D0 +:102460001C22E5E7001002400000FFFF8822002048 +:10247000184A08B5916A8B688B6013F0010104D08B +:1024800013F00C0F18BF4FF48031D80506D513F4A4 +:10249000406F14BF41F4003141F00201D80306D56A +:1024A00013F4402F14BF41F4802141F00401D3699B +:1024B0000BB108489847202383F311880021064870 +:1024C00000F01EFE002383F31188BDE8084001F0F0 +:1024D00083B800BF882200209022002038B5124C1B +:1024E000A36ADD68AA0712D05A6922F002025A6173 +:1024F000A36913B1012120469847202383F3118853 +:1025000000210A4800F0FCFD002383F31188EB064C +:1025100006D51021A36AD960236A0BB102489847F7 +:10252000BDE8384001F058B88822002098220020E9 +:1025300038B5124CA36A1D69AA0712D05A6922F055 +:1025400010025A61A36913B1022120469847202343 +:1025500083F3118800210A4800F0D2FD002383F3A1 +:102560001188EB0606D51021A36A1961236A0BB105 +:1025700002489847BDE8384001F02EB88822002074 +:102580009822002038B50F4CA36A5D682A075D6069 +:102590000AD5042222701A6822F002021A60636AC5 +:1025A00013B10021204698476B0706D5A36A9969A5 +:1025B000236A13B1034809049847BDE8384001F085 +:1025C0000BB800BF8822002010B50E4C204600F04A +:1025D000FDF90D4B0B211320A36200F0D7F90B215D +:1025E000142000F0D3F90B21152000F0CFF90B21B6 +:1025F000162000F0CBF9BDE8104000220E20114655 +:10260000FFF7B0BE88220020006400400F4B10B5D9 +:102610009842044605D10E4BDA6942F00072DA6145 +:10262000DB690122A36A1A60A36A5A68D20707D538 +:10263000626851681268D9611A60064A5A6110BD11 +:102640000121082000F052FCEEE700BF88220020A4 +:10265000001002405B87010003291AD8DFE801F06F +:10266000020A0F14836A9B6813F0E05F14BF012015 +:1026700000207047836A9868C0F380607047836A5F +:102680009868C0F3C0607047836A9868C0F30070B0 +:10269000704700207047000010B5032927D8DFE8F5 +:1026A00001F002272B2F836A9968C1F30161183169 +:1026B00003EB01131078840648BF5468C0F300117F +:1026C00058BF94884FEA410148BF41EAC40100F075 +:1026D0000F00586048BF41F00401906858BF41EABC +:1026E0004451D26841F001019860DA60196010BD70 +:1026F000836A03F5C073DDE7836A03F5C873D9E71E +:10270000836A03F5D073D5E701290AD002290FD0D7 +:1027100081B9836ADA68920701D1186903E0012060 +:102720007047836AD86810F0030018BF0120704713 +:10273000836AF2E70020704710B539B9836AD96817 +:1027400089071BD11B699C0704D110BD012915D035 +:102750000229FAD1816AD1F8C031D1F8C441D1F847 +:10276000C8011061D1F8CC015061202008610869CE +:10277000800717D1486940F0100012E0816AD1F853 +:10278000B031D1F8B441D1F8B8011061D1F8BC0131 +:1027900050612020C860C868800703D1486940F0B4 +:1027A00002004861C3F34000C3F38001000140EA26 +:1027B0004111107920F030000143117189064BBF9F +:1027C00091681189DB085B0D4CBF63F31C0163F357 +:1027D0000A01137948BF916064F3030313714FEA50 +:1027E00014234FEA144458BF118113705480ACE78E +:1027F000026843680A43026003B11847704700004B +:10280000024AD36843F0C003D360704700380140E8 +:10281000024AD36843F0C003D360704700440040CD +:102820002DE9F041D0F89C600446F7683368DA057A +:102830009DB20DD5202383F311884FF4007104302D +:10284000FFF7D6FF6FF480733360002383F31188A2 +:10285000202383F3118804F1040815F02F033AD1E3 +:1028600083F31188380615D5290613D5202383F361 +:10287000118804F1380000F02FFA00284DDA082101 +:10288000201DFFF7B5FF4FF67F733B40F360002339 +:1028900083F311887A0616D56B0614D5202383F3AB +:1028A0001188D4E913239A420AD1236C43B127F04B +:1028B00040073F041021201D3F0CFFF799FFF760F0 +:1028C000002383F31188D4F8A420D3683BB3BDE878 +:1028D000F041106918472B0713D015F0080F0CBFF3 +:1028E00000218021E80748BF41F02001AA0748BF26 +:1028F00041F040016B07404648BF41F48071FFF74B +:1029000077FFAD06736805D594F8A01020461940EE +:1029100000F082FA3568ADB29FE77060B7E7BDE8B6 +:10292000F081000008B50348FFF77AFFBDE80840D2 +:1029300000F052BEB422002008B50348FFF770FF34 +:10294000BDE8084000F048BE5C23002010B5094CEB +:1029500000212046084A00F03FFA084B0021C4F845 +:102960009C30074C074A204600F036FA064BC4F864 +:102970009C3010BDB422002001280008003801401E +:102980005C230020112800080044004001220901B6 +:1029900000F1604303F56143C9B283F8001300F00E +:1029A0001F039A4043099B0003F1604303F5614311 +:1029B000C3F880211A607047090100F16040C9B274 +:1029C00000F56D4001767047FFF7FEBD01230370EF +:1029D000002300F10802C0E9022200F11002C0E960 +:1029E0000422C0E90633C0E90833436070470000A1 +:1029F00010B52023044683F311880223416003703D +:102A0000FFF704FE04232370002383F3118810BD15 +:102A10002DE9F0411F4604460D461646202383F358 +:102A2000118800F108082378052B0DD0294620468F +:102A3000FFF712FE40B1204632462946FFF72CFE32 +:102A4000002080F3118808E03946404600F03CFB46 +:102A50000028E8D0002383F31188BDE8F08100004E +:102A60002DE9F0411F4604460D461646202383F308 +:102A7000118800F110082378052B0DD02946204637 +:102A8000FFF742FE40B1204632462946FFF754FE8A +:102A9000002080F3118808E03946404600F014FB1E +:102AA0000028E8D0002383F31188BDE8F0810000FE +:102AB000F8B5154682680B46AA428169066938BF97 +:102AC0008568761AB54204460BD218462A46FEF7A8 +:102AD00067FCA3692B44A361A36828465B1BA36022 +:102AE000F8BD0CD918463246FEF75AFCAF1B3A46E1 +:102AF000E1683044FEF754FCE3683B44EBE71846DA +:102B00002A46FEF74DFCE368E5E700002DE9F041B9 +:102B1000154683680446934238BF8568D0E904703F +:102B20003F1ABD420E460BD22A46FEF739FC6369B6 +:102B30002B446361A36828465B1BA360BDE8F0815A +:102B40000CD93A46A5EB0708FEF72AFC4246E06896 +:102B5000F119FEF725FCE3684344EAE72A46FEF74D +:102B60001FFCE368E5E7000010B50024C361029B89 +:102B7000C0E90511C1601144C0E900008460016131 +:102B8000036210BD08B5D0E90532934201D18268D5 +:102B900092B98268013282605A1C42611970D0E990 +:102BA00004329A4228BFC3684FF0000128BF436136 +:102BB00000F09AFA002008BD4FF0FF30FBE700005C +:102BC00070B5202304460D4683F31188A668A6B18C +:102BD000A368A269013BA360531CA3611578226915 +:102BE000934224BFE368A361E3690BB12046984791 +:102BF000002383F31188284607E02946204600F089 +:102C000063FA0028E2DA86F3118870BD2DE9F74FE8 +:102C100004460E4617469846D0F81C904FF0200AFE +:102C20008AF311884FF0000B154665B12A463146EC +:102C30002046FFF73DFF034660B94146204600F0BD +:102C400043FA0028F1D0002383F31188781B03B0E6 +:102C5000BDE8F08FB9F1000F03D001902046C847BE +:102C6000019B8BF31188ED1A1E448AF31188DCE76F +:102C7000C361009BC0E90511C1601144C0E90000B7 +:102C80008260016103627047F8B504460D4616463E +:102C9000202383F31188A768A7B1A368013BA36031 +:102CA00063695A1C62611D70D4E904329A4224BFE0 +:102CB000E3686361E3690BB120469847002080F325 +:102CC000118807E03146204600F0FEF90028E2DADC +:102CD00087F31188F8BD0000D0E905239A4210B5AA +:102CE00001D182687AB982680021013282605A1C5F +:102CF00082611C7803699A4224BFC368836100F033 +:102D0000F3F9204610BD4FF0FF30FBE72DE9F74FF8 +:102D100004460E4617469846D0F81C904FF0200AFD +:102D20008AF311884FF0000B154665B12A463146EB +:102D30002046FFF7EBFE034660B94146204600F00F +:102D4000C3F90028F1D0002383F31188781B03B066 +:102D5000BDE8F08FB9F1000F03D001902046C847BD +:102D6000019B8BF31188ED1A1E448AF31188DCE76E +:102D7000026843680A43026003B1184770470000C5 +:102D80001430FFF743BF00004FF0FF331430FFF75C +:102D90003DBF00003830FFF7B9BF00004FF0FF33F0 +:102DA0003830FFF7B3BF00001430FFF709BF000051 +:102DB0004FF0FF311430FFF703BF00003830FFF74A +:102DC00063BF00004FF0FF323830FFF75DBF0000F7 +:102DD00000207047FFF7BABD37B515460D4A0446C7 +:102DE000026000224260C0E9022201220B46027406 +:102DF00000F15C01009020221430FFF7B5FE2B4655 +:102E00002022009404F17C0104F13800FFF730FF28 +:102E100003B030BD4C3B000838B5C36904460D46CD +:102E20001BB904210844FFF7A3FF294604F114004D +:102E3000FFF7A8FE002806DA201D4FF48061BDE8E8 +:102E40003840FFF795BF38BD0022024BC3E900337D +:102E50009A60704704240020002382680374054BA5 +:102E60001B6899689142FBD25A6803604260106007 +:102E7000586070470424002008B5202383F311888C +:102E8000037C032B05D0042B0DD02BB983F31188C1 +:102E900008BD002243691A604FF0FF334361FFF71A +:102EA000DBFF0023F2E7D0E9003213605A60F3E75A +:102EB000002382680374054B1B6899689142FBD814 +:102EC0005A68036042601060586070470424002014 +:102ED000054B196908741868026853601A60186114 +:102EE00001230374FDF732BB0424002030B54B1CD2 +:102EF00004460B4D87B010D02B690A4A01A800F098 +:102F00001BF92046FFF7E4FF049B13B101A800F072 +:102F10002FF92B69586907B030BDFFF7D9FFF8E7E3 +:102F200004240020792E000838B50C4D41612B692E +:102F300081689A680446914203D8BDE83840FFF79B +:102F40008BBF1846FFF7B4FF01232C6101462374A1 +:102F50002046BDE83840FDF7F9BA00BF0424002040 +:102F6000044B1A681B6990689B68984294BF0020C4 +:102F7000012070470424002010B5084C2368206904 +:102F80001A6854602260012223611A74FFF790FFCF +:102F900001462069BDE81040FDF7D8BA042400209E +:102FA00008B5FFF7DDFF18B1BDE80840FFF7E4BF43 +:102FB00008BD0000FFF7E0BFFEE7000010B50C4CB5 +:102FC000FFF742FF00F0AAF880220A49204600F0ED +:102FD00031F8012344F8180C037400F0D9FA0023E7 +:102FE00083F3118862B6BDE81040034800F042B890 +:102FF0002C240020743B0008843B000800F0CAB871 +:10300000EFF3118020B9EFF30583202282F31188BA +:103010007047000010B530B9EFF30584C4F308041D +:1030200014B180F3118810BDFFF7BAFF84F3118843 +:10303000F9E7000082600222028270478368A3F1F0 +:103040003C0243F80C2C026943F83C2C426943F8DB +:10305000382C074A43F81C2CC268A3F1180043F827 +:10306000102C022203F8082C002203F8072C7047CA +:103070005D05000810B5202383F31188FFF7DEFFFC +:1030800000210446FFF750FF002383F311882046F8 +:1030900010BD0000024B1B6958610F20FFF718BFDD +:1030A00004240020202383F31188FFF7F3BF0000DE +:1030B00008B50146202383F311880820FFF716FF87 +:1030C000002383F3118808BD49B1064B42681B6990 +:1030D00018605A60136043600420FFF707BF4FF089 +:1030E000FF3070470424002003460068834205D067 +:1030F00002681A6053604161FFF7AEBE704700007E +:1031000038B504460D462068844200D138BD0368B6 +:1031100023605C604561FFF79FFEF4E7054B03F118 +:103120001402C3E905224FF0FF32DA6100221A626D +:10313000704700BF0424002010B5C0E903230B4AE8 +:10314000136A53699C68A1420CD85C688160036073 +:103150004460206058609868411A99604FF0FF33CE +:10316000D36110BD1B68091BECE700BF04240020DD +:10317000036881689A680A449A60426813605A60DA +:1031800000234FF0FF32C360014BDA61704700BF8C +:103190000424002038B50F4C2246236A01332362F1 +:1031A00052F8143F934206D020259A68013A9A605B +:1031B00063699A6802B138BDD3E9001001604860C4 +:1031C000D968DA6082F311881869884785F3118815 +:1031D000EEE700BF0424002000207047FEE7000057 +:1031E000704700004FF0FF3070470000BFF34F8F73 +:1031F000024AD368DB07FCD4704700BF00200240BE +:1032000008B5074B1B7853B9FFF7F0FF054B1A6958 +:10321000120641BF044A5A6002F188325A6008BD62 +:1032200008250020002002402301674508B5054B12 +:103230001B7833B9FFF7DAFF034A136943F08003C1 +:10324000136108BD08250020002002407F289ABF96 +:1032500000F5003080020020704700004FF48060CD +:1032600070470000802070477F2808B50BD8FFF713 +:10327000EDFF00F580630268013204D1043083421F +:10328000F9D1012008BD0020FCE700007F2838B5F7 +:10329000044623D8FFF7B4FEFFF7A8FFFFF7B0FFFF +:1032A000F3220F4B0546DA60022220461A61FFF72F +:1032B000CDFF58611A694FF4806142F040021A61F3 +:1032C000FFF794FF00F010F92846FFF7AFFFFFF774 +:1032D000A1FE2046BDE83840FFF7C6BF002038BD3C +:1032E000002002402DE9F047044612F001000E468E +:1032F000154606D040F2BD22234B1A600020BDE8DF +:10330000F087224BA2189A4204D940F2C2221E4BE7 +:103310001A60F4E7FFF774FE4FF0010AFFF770FF41 +:10332000FFF764FFDFF868903146A61B012D884641 +:1033300006EB010705D8FFF779FFFFF76BFE0120C9 +:10334000DDE7B8F80030C9F810A03B800024FFF793 +:103350004DFFC9F810403B8831F8022B9BB29A42CE +:103360000FD040F2D922084B1A600A4B1F600A4B5B +:103370001D600A4BC3F80080FFF758FFFFF74AFEB5 +:10338000BCE7023DD2E700BF042500200000020890 +:1033900000200240F824002000250020FC2400200A +:1033A000084908B50B7828B11BB9FFF729FF01239D +:1033B0000B7008BD002BFCD0BDE808400870FFF77B +:1033C00035BF00BF0825002070B5FFF719FE4FF488 +:1033D0007A710D4B0D4E1B6A326801FB03F3934269 +:1033E00037BF0B4A0A495168156836BF4C1CD1E9F2 +:1033F000005454605D1944F100043360FFF70AFE85 +:103400002846214670BD00BF042400200C25002062 +:103410001025002070B5FFF7F3FD4FF47A710F4BC4 +:103420000F4E1B6A326801FB03F3934237BF0D4A0C +:103430000C49516815683ABF4C1C5460D1E90054DE +:103440005D1944F100043360FFF7E4FD4FF47A7234 +:10345000002328462146FCF783FE70BD042400208B +:103460000C2500201025002010B5094C013AD2B2DD +:10347000FF2A00D110BD500854F82030013054F814 +:1034800020009BB243EA004341F8043BEEE700BF53 +:10349000046C004010B50748013AD2B2FF2A00D1AF +:1034A00010BD0C88530840F823404C88013340F885 +:1034B0002340F1E7046C004007B50122002001A978 +:1034C000FFF7D2FF019803B05DF804FB13B5044683 +:1034D000FFF7F2FFA04205D00122002001A90194CC +:1034E000FFF7D8FF02B010BD7047000045F25552FB +:1034F000064B1A6002225A6040F6FF729A604CF640 +:10350000CC421A600122024B1A7070470030004012 +:103510001C250020034B1B781BB14AF6AA22024B44 +:103520001A6070471C25002000300040044B1A68C8 +:103530002AB902F1804202F50432526A1A607047D9 +:10354000182500204FF08072014B5A62704700BF6F +:103550000010024008B5FFF7E9FF024B1868C0F3FE +:10356000407008BD1825002008B5FFF7DFFF024BAB +:103570001868C0F3007008BD18250020EFF3098318 +:10358000203383F30988002383F3118870470000F8 +:10359000202080F3118862B60C4B0D4AD96821F4C3 +:1035A000E0610904090C0A43DA60D3F8FC200949F8 +:1035B00042F08072C3F8FC200A6842F001020A60FF +:1035C0001022DA7783F82200704700BF00ED00E098 +:1035D0000003FA05001000E0202310B583F31188E2 +:1035E0000B4B5B6813F400630FD0EFF309844FF0CB +:1035F0008073203CE36184F30988FFF7B1FC10B1CC +:10360000044BA36110BD044BFBE783F31188F9E77A +:1036100000ED00E06F05000872050008704700002B +:10362000FEE700000A4B0B480B4A90420BD30B4BB2 +:10363000C11EDA1C121A22F003028B4238BF00228C +:103640000021FDF7BFBE53F8041B40F8041BECE754 +:10365000043C0008A0250020A0250020A025002073 +:103660007047000000F030B808B500F063F9FFF7CC +:10367000A5FCBDE80840FFF759BF000070470000F7 +:103680004FF0FF310E4B1A6919611A6900221A6155 +:103690001869D868D960D968DA60DA68DA6942F0FE +:1036A0008052DA61DA69DA6942F00062DA61054A69 +:1036B000DB69136843F48073136000F01BB900BF2B +:1036C0000010024000700040194B1A6842F00102DD +:1036D0001A601A689007FCD51A6802F0F9021A609D +:1036E00000225A605A6812F00C0FFBD11A6842F49B +:1036F00080321A601A689103FCD55A6842F4E812C5 +:103700005A601A6842F080721A601A689201FCD5F9 +:103710001221084A5A60084A11605A6842F00202AF +:103720005A605A6802F00C02082AFAD1704700BFAA +:103730000010024000641D0000200240084A08B545 +:10374000516913680B4003F00103536123B1054A2B +:1037500013680BB150689847BDE80840FFF73CBFBD +:103760000004014020250020084A08B5516913686B +:103770000B4003F00203536123B1054A93680BB178 +:10378000D0689847BDE80840FFF726BF0004014015 +:1037900020250020084A08B5516913680B4003F042 +:1037A0000403536123B1054A13690BB1506998476B +:1037B000BDE80840FFF710BF0004014020250020AD +:1037C000084A08B5516913680B4003F008035361B8 +:1037D00023B1054A93690BB1D0699847BDE8084009 +:1037E000FFF7FABE0004014020250020084A08B572 +:1037F000516913680B4003F01003536123B1054A6C +:10380000136A0BB1506A9847BDE80840FFF7E4BE61 +:103810000004014020250020174B10B55A691C6890 +:10382000144004F478725A61A30604D5134A936ACB +:103830000BB1D06A9847600604D5104A136B0BB1E0 +:10384000506B9847210604D50C4A936B0BB1D06B93 +:103850009847E20504D5094A136C0BB1506C9847A0 +:10386000A30504D5054A936C0BB1D06C9847BDE80D +:103870001040FFF7B1BE00BF00040140202500202A +:103880001A4B10B55A691C68144004F47C425A6102 +:10389000620504D5164A136D0BB1506D9847230588 +:1038A00004D5134A936D0BB1D06D9847E00404D54D +:1038B0000F4A136E0BB1506E9847A10404D50C4A01 +:1038C000936E0BB1D06E9847620404D5084A136F0B +:1038D0000BB1506F9847230404D5054A936F0BB181 +:1038E000D06F9847BDE81040FFF776BE0004014056 +:1038F00020250020062108B50846FFF747F80621D5 +:103900000720FFF743F806210820FFF73FF80621BC +:103910000920FFF73BF806210A20FFF737F80621B8 +:103920001720FFF733F8BDE8084006212820FFF7ED +:103930002DB8000008B5FFF7A3FE064800F00EF80A +:10394000FFF742F8FFF746FAFFF798FEBDE8084098 +:1039500000F002B89C3B000800F042B80023194672 +:103960001C4A0133102BC2E9001102F10802F8D100 +:10397000194B9A6942F07D029A619B690268174B64 +:10398000DA6082685A6042681A60C26803F5806330 +:10399000DA6042695A6002691A608269C3F80C24CD +:1039A000026AC3F80424C269C3F80024426AC3F857 +:1039B0000C28C26AC3F80428826AC3F80028026B84 +:1039C000C3F80C2C826BC3F8042C426BC3F8002C98 +:1039D000704700BF20250020001002400008014071 +:1039E0004FF0E023044A08215A6100229A6107221D +:1039F0000B201A61FEF7E0BF3F19010008B5202334 +:103A000083F31188FFF7FAFA002383F3118808BDC6 +:103A100008B5FFF7F3FFBDE80840FFF7DDBD000084 +:103A200010B501390244904201D1002005E003782D +:103A300011F8014FA34201D0181B10BD0130F2E76D +:103A40002DE9F0419BB10446C91A1778014403F1EE +:103A5000FF3C8C42204601D9002008E00578013463 +:103A6000BD42F6D10CEB0405D618A54201D1BDE844 +:103A7000F08115F8018D16F801EDF045F5D0E8E775 +:103A8000034611F8012B03F8012B002AF9D17047E6 +:103A90006F72672E6172647570696C6F742E663117 +:103AA000303351696F74656B5F506572697068007F +:103AB0004E6F20617070207369670A004261642054 +:103AC0006677206C656E6774682025750A00426110 +:103AD0006420626F6172645F696420257520736879 +:103AE0006F756C642062652025750A004261642050 +:103AF00066772064657363726970746F72206C6599 +:103B00006E6774682025750A0042616420617070D8 +:103B100020435243203078253038783A30782530A9 +:103B20003878203078253038783A30782530387831 +:103B30000A00476F6F64206669726D776172650A6B +:103B40000040A2E4F164689106000000000000005B +:103B50009D2D0008892D0008C52D0008B12D0008F5 +:103B6000BD2D0008A92D0008952D0008812D000805 +:103B7000D12D00086D61696E0000000069646C65FC +:103B8000000000007C3B000848240020F8240020AE +:103B900001000000B92F0008000000000C1E00000A +:103BA000447B4144B457494401000000424444442A +:103BB00044444444000000004444444444444444D5 +:103BC00000000000444444444444444400000000D5 +:103BD0004444444444444444B8C5FF7F01000000C9 +:103BE000E803000000000000009C0100000000004D +:103BF000640000000000000040420F00FE2A0100A7 +:043C0000D2040000EA :00000001FF diff --git a/Tools/bootloaders/f103-RangeFinder_bl.bin b/Tools/bootloaders/f103-RangeFinder_bl.bin index 13e73a38357..d0d82766beb 100755 Binary files a/Tools/bootloaders/f103-RangeFinder_bl.bin and b/Tools/bootloaders/f103-RangeFinder_bl.bin differ diff --git a/Tools/bootloaders/f103-RangeFinder_bl.elf b/Tools/bootloaders/f103-RangeFinder_bl.elf index 6b10b046e39..2ecce5147fa 100755 Binary files a/Tools/bootloaders/f103-RangeFinder_bl.elf and b/Tools/bootloaders/f103-RangeFinder_bl.elf differ diff --git a/Tools/bootloaders/f103-RangeFinder_bl.hex b/Tools/bootloaders/f103-RangeFinder_bl.hex index f9339f5d047..16c84aded7c 100644 --- a/Tools/bootloaders/f103-RangeFinder_bl.hex +++ b/Tools/bootloaders/f103-RangeFinder_bl.hex @@ -1,1062 +1,963 @@ :020000040800F2 -:1000000000090020A10400081514000819140008B4 -:10001000551400081914000835140008A30400083A -:10002000A3040008A3040008A3040008C5360008C0 -:10003000A3040008A3040008A3040008593A000818 -:10004000A3040008A3040008A3040008A3040008F4 -:10005000A3040008A3040008393800086538000824 -:1000600091380008BD380008E9380008A3040008EA -:10007000A3040008A3040008A3040008A3040008C4 -:10008000A3040008A3040008A304000869250008CD -:10009000D5250008292600087D2600081539000806 -:1000A000A3040008A3040008A3040008A304000894 -:1000B000A3040008A3040008A3040008A304000884 -:1000C000A3040008A3040008A3040008A304000874 -:1000D000A3040008A12A0008B52A0008A304000808 -:1000E0007D390008A3040008A3040008A304000845 -:1000F000A3040008A3040008A3040008A304000844 -:10010000A3040008A3040008A3040008A304000833 -:10011000A3040008A3040008A3040008A304000823 -:10012000A3040008A3040008A3040008A304000813 -:10013000A3040008A3040008A3040008A304000803 -:10014000A3040008A3040008A3040008A3040008F3 -:10015000A3040008A3040008A3040008A3040008E3 -:10016000D0400B1CD1409C46203AD3401843524209 -:1001700063469340184370479140031C90409C464F -:10018000203A9340194352426346D3401943704783 -:1001900053B94AB9002908BF00281CBF4FF0FF31EE -:1001A0004FF0FF3000F07AB9ADF1080C6DE904CEE4 -:1001B00000F006F8DDF804E0DDE9022304B0704742 -:1001C0002DE9F0478C460E460446089D002B50D181 -:1001D0008A4217466CD9B2FA82FEBEF1000F0BD0EC -:1001E000CEF1200C01FA0EF620FA0CFC02FA0EF702 -:1001F0004CEA060C00FA0EF43A0CBCFBF2F9BBB266 -:1002000002FB19CC09FB03FA4FEA144848EA0C46F2 -:10021000B2450AD9F61909F1FF3180F02581B245BE -:1002200040F22281A9F102093E44A6EB0A06B6FB80 -:10023000F2F002FB106600FB03F3A4B244EA0644AA -:10024000A34209D9E41900F1FF3280F00B81A342E7 -:1002500040F2088102383C440021E41A40EA094097 -:10026000002D62D0002324FA0EF42C606B60BDE8F0 -:10027000F0878B4207D9002D55D0002185E8410039 -:100280000846BDE8F087B3FA83F1002940F08F807B -:10029000B34202D3824200F2FC80841A66EB03066A -:1002A0000120B446002D40D085E81010BDE8F0874D -:1002B00012B90127B7FBF2F7B7FA87FEBEF1000FBC -:1002C00035D10121F61B4FEA174C1FFA87F8B6FB10 -:1002D000FCF20CFB126608FB02F0230C43EA064614 -:1002E000B04207D9F61902F1FF3302D2B04200F250 -:1002F000D2801A46361AB6FBFCF00CFB106608FBDF -:1003000000F8A3B243EA0644A04507D9E41900F176 -:10031000FF3302D2A04500F2B9801846A4EB0804CE -:1003200040EA02409CE729462846BDE8F08707FAE4 -:100330000EF7CEF1200326FA03F24FEA174CB2FB78 -:10034000FCF11FFA87F80CFB112206FA0EF620FAD0 -:1003500003F301FB08F933431E0C46EA0246B1459C -:1003600000FA0EF409D9F61901F1FF3280F08C8001 -:10037000B14540F2898002393E44A6EB0906B6FB3E -:10038000FCF00CFB106200FB08F99EB246EA024644 -:10039000B14507D9F61900F1FF3371D2B1456FD9D4 -:1003A00002383E44A6EB090640EA01418FE7C1F15D -:1003B000200722FA07F88B4048EA030326FA07F4DD -:1003C0004FEA134EB4FBFEF91FFA83FC0EFB1944EF -:1003D0008E4020FA07F809FB0CFA48EA06084FEAB3 -:1003E000184646EA0444A24502FA01F200FA01F670 -:1003F00008D9E41809F1FF3044D2A24542D9A9F145 -:1004000002091C44A4EB0A04B4FBFEF00EFB1044EA -:1004100000FB0CFC1FFA88F848EA0444A44507D9FD -:10042000E41800F1FF3E29D2A44527D902381C4424 -:1004300040EA0940A0FB0289A4EB0C0CCC45C24663 -:10044000CE4615D312D055B1B6EB0A036CEB0E06AF -:1004500006FA07F7CB401F43CE402F606E600021A5 -:10046000BDE8F0871046F7E68946DEE64645EAD263 -:10047000B8EB020A69EB030E0138E4E77046D7E7F0 -:1004800018468FE78146BDE7114676E702383C44BF -:1004900044E7084606E7023A3E442BE7704700BFB0 -:1004A00002E000F000F8FEE772B6274880F3088803 -:1004B000264880F3098826484EF60851CEF20001FE -:1004C0000860022080F31488BFF36F8F03F02AF9CD -:1004D00003F046F94FF055301E491B4A91423CBF8C -:1004E00041F8040BFAE71C49184A91423CBF41F815 -:1004F000040BFAE719491A4A1A4B9A423EBF51F8BF -:10050000040B42F8040BF8E700201749174A914200 -:100510003CBF41F8040BFAE703F008F903F022F9B5 -:10052000134C144DAC4203DA54F8041B8847F9E726 -:1005300000F03AF8104C114DAC4203DA54F8041BA9 -:100540008847F9E703F0F0B8000900200011002007 -:10055000000000080001002000090020C041000840 -:1005600000110020741100207811002000260020C6 -:1005700060010008600100086001000860010008D7 -:100580002DE9F04FC1F80CD0C3689D46BDE8F08F4F -:10059000002383F311882846A047002002F07EFE46 -:1005A00002F0A8FD00DFFEE76FF01702364B2DE9E1 -:1005B000F0411A70032200245A7001266FF0630282 -:1005C0009C70DC701C715C719C71DC711C725A72C5 -:1005D0009E72DC7203F020F8804603F06DF8054649 -:1005E000D0BB2A4B984539D03344984537D0284B57 -:1005F00028F0FF029A4234D15FFA88F000F04EFAF8 -:100600002E4642F2107400F077FC00F04DFA0746D7 -:1006100058B364BB374635B11E4B984503D0002410 -:1006200003F042F82746002003F000F81A4B9B68BD -:1006300013F040031ED00FB100F030F800F07EFC44 -:1006400000F018FE00F014FF0546ACB900F0CCFC39 -:10065000012002F029FEF8E70646D4E706462C46BC -:10066000D1E706464FF47A74CDE70446D3E74FF45A -:100670007A74D0E71C46E1E700F0FAFE401BA04286 -:10068000E4D900F00BF8DDE778110020010007B095 -:10069000000008B0263A09B0000C014010B51C4B10 -:1006A0001C4953F8042F013200D110BD8B42F8D100 -:1006B000194C1A4B22689A4228D9194B9B6803F1AE -:1006C000006303F5C8439A4220D202F0C1FF02F052 -:1006D000D3FF002000F0E8FD0220124B187000F05C -:1006E0001FFE114BDA690022DA61D96999699A61B2 -:1006F0009B6972B60D4B0E4A202113601B6822685D -:1007000081F311889D4683F30888104710BD00BF10 -:10071000FC6300081C64000804640008FF63000810 -:1007200078110020841100200010024000640008AD -:1007300008ED00E049F2690008490B689AB21B0C09 -:1007400000FB02330B6044F25061054A136898B213 -:100750001B0C01FB0030106080B270470C110020B0 -:100760000811002010B504460021102200F0F4FD0D -:10077000034B03CB206061601868A06010BD00BF10 -:10078000E8F7FF1FF0B5BBB000F072FE1D4CA36888 -:10079000C31AF92B30D906AD2346A06028220021C8 -:1007A000284601F0F3FB04F10E0000F0CDFD00231C -:1007B000C6B2591D5F1CDBB2B3424FEAC10107DA72 -:1007C0000E3323440822284601F0E0FB3B46F0E7C5 -:1007D00001230393082302930B4B207B01933023C7 -:1007E000C1F3CF0105910093014604A3D3E900238F -:1007F0000495064801F09AF93BB0F0BD78F6339FB6 -:1008000093CACD8DC8210020D5210020A021002031 -:1008100070B50D4614461E4601F02EF950B9022E51 -:100820000ED1012C0CD112A3D3E90023C5E900237A -:10083000012070BD052C14D003D8012C09D0002054 -:1008400070BD282C09D0302CF9D10BA3D3E900239B -:10085000ECE70BA3D3E90023E8E70BA3D3E90023DC -:10086000E4E70BA3D3E90023E0E700BFAFF3008088 -:10087000401DA12026812A0B78F6339F93CACD8D87 -:100880009E6AC421818A46EE26417272DF25D7B75F -:10089000F017304A39059E5638B50D4604460346D2 -:1008A00020222846002101F071FB22792346032AE9 -:1008B00028BF0322284603F8042F2021022201F03A -:1008C00065FB62792346072A28BF0722284603F8DA -:1008D000052F2221032201F059FBA2792346072A82 -:1008E00028BF0722284603F8062F2521032201F0FE -:1008F0004DFB284604F108031022282101F046FB95 -:10090000382038BD2DE9F04FADF5037D23AE10AD95 -:1009100040F2791280460F463046002100F01CFD5F -:1009200048220021284600F017FD00F0A1FD4FF4F9 -:100930007A72B0FBF2F0574B0DF16209186093E840 -:10094000070001232B74002385E807000DF16200E6 -:100950006B74FFF707FF032385F82030E82385F841 -:10096000213007AB18464C4903F0E0F823222864F5 -:100970003146284685F83C20FFF78EFF14AB04462D -:1009800001460822304601F001FB08220DF1510317 -:10099000A118304601F0FAFA0DF15203082204F1D1 -:1009A0001001304601F0F2FA15AB202204F11801D3 -:1009B000304601F0EBFA16AB402204F13801304624 -:1009C00001F0E4FA18AB082204F17801304601F096 -:1009D000DDFA0DF16103082204F18001304601F0D7 -:1009E000D5FA04F1880A04F5847B4B465146082267 -:1009F00030460AF1080A01F0C9FAD34509F10109A4 -:100A0000F3D11DAB08225946304601F0BFFA4FF032 -:100A1000000904F5887495F834304B4510D84FF030 -:100A2000000995F83C304B4515D92B6C21464B44B9 -:100A30000822304601F0AAFA083409F10109F0E76A -:100A4000AB6B21464B440822304601F09FFA083434 -:100A500009F10109DFE7E31DC3F3CF03F97E059335 -:100A6000002304960393BB7E193702930123019759 -:100A70000093404605A3D3E9002301F057F80DF594 -:100A8000037DBDE8F08F00BFAFF300809E6AC421F4 -:100A9000818A46EE88110020043D0008014B187041 -:100AA000704700BF94110020F0B5334B85B01C7B1C -:100AB00034B10E22314B1A810024204605B0F0BD1E -:100AC0002F4A02AB1068516803C308232D490DEB70 -:100AD00003022D4803F00CF8054630B90A22274BD3 -:100AE0002A481A8100F08CFCE6E70169B1F5CE3F97 -:100AF00006D90B22214B26481A8100F081FCDCE745 -:100B0000438BB3F57A7F09D00C211C4A214811810F -:100B10004FF47A72194600F073FCCEE71E4A024485 -:100B200002F11003994204D21022144B1B481A817F -:100B3000E3E710398E1A2046134900F09DFC074662 -:100B4000324605F11801204600F096FCAB689F4242 -:100B500002D1EB6898420AD00D22084B1A8100900E -:100B60003B46EA68A9680E4800F04AFCA4E70D4835 -:100B700000F046FC0124A0E7C821002088110020D5 -:100B8000D43B0008DC9B010000640008DC3B00084B -:100B9000E83B0008FA3B0008089CFFF7183C0008F7 -:100BA000353C00085E3C00082DE9F04FADB006AFC3 -:100BB00080460C4600F060FF054600286AD1237E7F -:100BC000022B18D1E38A012B15D100F051FC81468C -:100BD000FFF7B0FD4FF4C873B0FBF3F202FB130054 -:100BE000BB4E80B209F51679E37E484430608BB97C -:100BF0000022B84B1A709C37BD46BDE8F08F3B1DF4 -:100C00001D440095002308224FEAC901204601F047 -:100C100021F84D46A38A5FFA85F9013BAB420BD917 -:100C200005F10109B9F1110FE9D140F23911AA4BCF -:100C3000AA4AAB4802F02EFF07F11400FFF792FD1D -:100C40002A4607F11401381D02F042FF034600282E -:100C5000CED1B9F1100F07D09E4B83F800903368C6 -:100C6000A3F516733360C6E707F1980202F8950DF5 -:100C7000014600922046072200F0ECFFF9787F2918 -:100C800004DD984B954A4FF4A871D2E7404600F036 -:100C9000D7FEB0E7E38A052B00F0068106D8012BCA -:100CA000A9D121464046FFF72DFEA4E7282B3DD0D1 -:100CB000302BA0D1637E8C4D01336A7BDBB2934233 -:100CC000E94640F0EF80E27E2B7B9A4240F0EA80DA -:100CD000002607F1980323F8846D00931022012366 -:100CE0003146204600F0B6FFB4F81480A8F102089F -:100CF0001FFA88F808F1030323F003030A3323F0F3 -:100D00000703ADEB030D0DF1180A33469BB2B11C7E -:100D100098454FEAC10106F101066CDD534400938A -:100D200008220023204600F095FFEEE7A38A013B4E -:100D30009BB2C92B3FF65FAF6B4E357B4DBB06F1C7 -:100D40000C03009308222B462946204600F082FF20 -:100D5000A38A05F10109013BEDB29D424FEAC901A9 -:100D600009DA0E353544009500230822204600F0AC -:100D700071FF4D46ECE700230022C6E90023002363 -:100D8000B36086F8D730C6F8D830337B0BB9E37E32 -:100D90003373002507F114063B1D0822294630460F -:100DA0007D60BD60FD6001F0F1F83B7A05F101095D -:100DB000AB424FEAC90107D9FB6808222B443046F1 -:100DC00001F0E4F84D46F0E70023C1F3CF01E07EE7 -:100DD000059104960393A37E1934029328230146B8 -:100DE0000093019438A3D3E90023404600F09EFE0F -:100DF000FFF7C8FCFFE695F8D70000F05FFAD5F8DA -:100E0000D83006461BB995F8D70000F067FAD5F838 -:100E1000D83043449E4204D295F8D700013000F008 -:100E20005DFA00244FEA980BA0B2584504F1010482 -:100E300008DA2B6880000AEB00010122184400F058 -:100E400093FAF1E7D5F8D840D5E9002312EB080270 -:100E500043F10003444495F8D700C5E90023C5F8E1 -:100E6000D84000F02BFA844209D395F8D7300133EB -:100E700085F8D730D5F8D8309E1BC5F8D860B8F1C2 -:100E8000FF0F08DC00232B7300F03AFAFFF70CFE8B -:100E900008B1FFF703FC2B68144A9B0A0133138146 -:100EA0000023AB60CD46A6E6BFF34F8F1049114B30 -:100EB000CA6802F4E0621343CB60BFF34F8F00BFF8 -:100EC000FDE700BFAFF3008026417272DF25D7B780 -:100ED0009C21002099210020703C0008283D00083A -:100EE000C93C0008EB3C0008C82100208811002004 -:100EF00000ED00E00400FA0508B54FF000530B4A7E -:100F0000196891420AD1597D094A0A4811701B7D1E -:100F1000C922037308490E3000F00CFABDE80840FE -:100F2000E02200214FF0005000F016BA9AAD44C5FF -:100F300094110020C821002016000020022330B5A3 -:100F40001F4C85B0637104230025ADF808300123E0 -:100F50000722ADF80C501B498DF80C308DF80B3082 -:100F6000194B1A484B608DF80A2001F0FFFD184B11 -:100F7000019500931749184B4FF48052174800F021 -:100F800029FD174B2546197811B1144800F058FD7A -:100F900000F06EFA0446FFF7CDFB4FF4C873B0FBC8 -:100FA000F3F202FB130304F516749BB21C440D4BC1 -:100FB0001C6002F081FB08B10F232B8105B030BD0E -:100FC000881100200011002003000600E02200200C -:100FD0001108000898110020A90B0008A02100208A -:100FE000941100209C2100202DE9F04F96A7D7E90D -:100FF00000670FF25C29D9E900898F4C93B0DFF8C4 -:1010000058B2DFF858A2204600F0DCFD0CAD079086 -:1010100098B310220021284600F09EF94FF00002FC -:10102000079B197B61F3030219468DF8302051F8B4 -:10103000040F0EAA496803C21B680D9A584663F351 -:101040001C029DF830300D9243F020038DF83030B3 -:1010500000232A46194601F099FD079030B9204631 -:1010600000F0B4FD079B8AF80030CCE79AF8003016 -:10107000072B40DC01338AF8003018220021284673 -:1010800000F06AF9DFF8D0B1DFF8D4A100232A46D6 -:101090001946584601F0A2FD014680BB102208A85F -:1010A00000F05AF9DAF80C3083F01003CAF80C306B -:1010B00000F0E0F90DF1240E0B4612A9024611E9E9 -:1010C00003008EE803009DF83410C1F30300890685 -:1010D00049BF0E99BDF83810C1F31C0141F0004121 -:1010E00058BFC1F30A018DF82C000891204608A9C9 -:1010F00000F0B2FFCAE7204600F068FDBDE72046D9 -:1011000000F0BAFC824600284AD100F0B1F9DFF8BD -:1011100054B1DBF80030984242D300F0A9F90790AF -:10112000FFF708FB4FF4C873B0FBF3F101FB1300AA -:10113000079A80B202F516721044CBF80000DFF86F -:1011400028B18DF820A09BF8001011B901238DF86B -:10115000203028460791FFF705FB07990DF1210084 -:10116000C1F1100A5FFA8AFABAF1060F28BF4FF0F0 -:10117000060A2944524600F0DDF80AF101030493FF -:1011800008AB0393182302932C4B3246019301239F -:10119000204600933B4600F071FC00238BF80030A2 -:1011A00000F066F9264ADFF8C4A01368C31AB3F545 -:1011B0007A7F32D3106000F05DF902460B4620467C -:1011C00000F00AFD204600F057FC30B39AF80C30CE -:1011D000DFF89CB0002B14BF032302238BF80530EB -:1011E00000F046F94FF47A73B0FBF3F02946CBF8E0 -:1011F00000005846FFF750FB18230293114B0730AD -:10120000019340F25513C0F3CF000490009303956F -:1012100042464B46204600F031FC9AF80C300BB1A8 -:10122000FFF7B0FA9AF80C30002B7FF4E8AE13B059 -:10123000BDE8F08FAFF30080A021002098210020AE -:10124000A8220020AC220020401DA12026812A0BCC -:10125000F1C6A7C1D068080FE0220020AD2200200F -:10126000000801409C21002099210020C821002075 -:101270008811002070B502F0CDF80025084C094E09 -:10128000207030682378834208D902F0BFF83368B1 -:1012900005440133B5F5C84F3360F2D370BD00BFCC -:1012A000DC220020B022002002F04CB900F10060E6 -:1012B000920000F5C84002F0F1B80000054B1A6832 -:1012C000054B1B789B1A834202D9104402F09EB84A -:1012D00000207047B0220020DC22002038B50446F0 -:1012E000064D2868204402F097F828B92868204461 -:1012F000BDE8384002F0A2B838BD00BFB0220020DF -:10130000064991F8243033B100230822086A81F895 -:101310002430FFF7CBBF0120704700BFB42200206C -:10132000022802BF4FF48012014B1A61704700BFC0 -:1013300000080140002310B5934203D0CC5CC45494 -:101340000133F9E710BD000002460346981A13F96D -:10135000011B0029FAD1704703460244934202D090 -:1013600003F8011BFAE770472DE9F047234C0546C7 -:1013700094F824308846174683BB2E46DFF87C90CD -:10138000C7B394F824302BB92022FF2148462662A7 -:10139000FFF7E2FF94F824004146C0F10805BD4282 -:1013A00028BF3D465FFA85FAAD002A4604EB80006F -:1013B000FFF7C0FF94F82430A7EB0A079A445FFABE -:1013C0008AFABAF1080F2E44A844FFB284F824A088 -:1013D000D6D1FFF795FF0028D2D108E0266A06EBA8 -:1013E0008306B042CAD0FFF78BFF0028C5D100208A -:1013F000BDE8F0870120BDE8F08700BFB4220020DF -:101400000FB4002004B070470FB44FF0FF3004B0A9 -:1014100070470000FEE70000EFF30983EFF3058358 -:10142000034B9A6B9A6A9A6A9A6A9A6A9B6AFEE76F -:1014300000ED00E0EFF30983EFF30583044B9A6BB3 -:101440009A6A9A6A9A6A9A6A9A6A9B6AFEE700BFDF -:1014500000ED00E0EFF30983EFF30583034B5A6BD4 -:101460009A6A9A6A9A6A9A6A9B6AFEE700ED00E0B5 -:1014700002F0A0B802F07AB830B5084D0A449142A3 -:101480000BD0092411F8013B5840013CF7D040F340 -:1014900000032B4083EA5000F7E730BD2083B8ED0E -:1014A0000246006848B1036811891360D38801338C -:1014B0009BB29942D38038BF1381704770B5044600 -:1014C0000D4688B0202200216846FFF745FF2046E0 -:1014D0000495FFF7E5FF054658B16B46044608AE94 -:1014E0001A4603CAB24220606160134604F1080440 -:1014F000F6D1284608B070BD2DE9F04130B940F270 -:10150000C531264B264A274802F0C4FA0B7C23B982 -:10151000254B234A40F2C631F5E7C66986B9C16159 -:10152000BDE8F081002B29DA930CAB4229D1B442FB -:1015300001D10C60F3E7C8F800100C60BDE8F08141 -:101540004B68B04623F06047BD0C15EA230538BF51 -:101550003D4634464FEAD37EC3F3807C6368BEEBDE -:10156000D37F23F06042DDD1974203D1C3F3807370 -:101570009C450AD1974205E01C46EFE7AA4206D0F7 -:1015800013469D422CBF00230123002BCFD123689B -:10159000A046002BF0D12160BDE8F081FC3F00089F -:1015A000F03D0008B4400008D540000808B5034AE3 -:1015B000034B40F25E31034802F06CFACC3D000868 -:1015C00074400008B440000808B503680B60C38885 -:1015D000016033B9044B054A4FF4C761044802F077 -:1015E00059FA013BC38008BD44400008403E000852 -:1015F000B440000870B50C4600F10C05616831B9C3 -:10160000E38A002061F30903E382002170BD0E68C4 -:101610002846FFF7D9FF6660F0E7000008B542688A -:1016200032B10B4B0B4A40F22F410B4802F032FA19 -:10163000C37DC3F38401013161F38603C375C38A9B -:1016400062F30903C3821B0A62F3C713C37508BDA3 -:1016500090400008FC3D0008B44000082DE9F04728 -:10166000089E32B91F4B204A40F239511F4802F000 -:1016700011FA4FF47F4901F007054FEAD6082A44D2 -:1016800006F0070600EBD100954201D1BDE8F087D6 -:1016900005F0070E06F0070AD645774638BF5746CD -:1016A000511BC7F108078F4228BF0F46EC08045DA5 -:1016B00008EBD60113F801C004FA0EF429FA07FE6C -:1016C00024FA0AF45FFA8EFE8CEA04044EFA0AFE4B -:1016D00004EA0E048CEA040C03F801C03D443E44C5 -:1016E000D2E700BF10400008143E0008B4400008D4 -:1016F0002DE9F04106460F4600254FF6FF7441F2F2 -:1017000021082A4630463946FEF72AFD0823C0B292 -:1017100084EA002414F4004F4FEA4404A4B203F115 -:10172000FF3318BF84EA080413F0FF03F2D1083531 -:10173000402DE6D12046BDE8F081000010B541F211 -:1017400021040A44914200D110BD11F8013B80EA06 -:101750000320082310F4004F4FEA400080B203F149 -:10176000FF3318BF604013F0FF03F3D1EAE7000036 -:101770002DE9F04F85B08A468DE80C00BDF83C405D -:10178000814630B940F26E31484B494A494802F02F -:1017900081F911F0604F04D0474B454A40F26F3158 -:1017A000F4E7009B002B7ED024B10E9B002B7AD057 -:1017B000072C28D809F10C00FFF772FE054628B95E -:1017C0006FF00205284605B0BDE8F08F1422002115 -:1017D000FFF7C2FD22460E9905F10800FFF7AAFDAA -:1017E000631C2B74009B2C441B78294603F01F03B9 -:1017F00063F03F0323724AF000436B604846FFF7F3 -:101800007BFE0125DEE74FF000084FF0800B4646D7 -:101810004546019B1B0A029300F10C0303930398B6 -:10182000FFF73EFE07460028CAD014220021FFF72A -:1018300093FDB6BB02229DF804303B729DF8083040 -:101840007B720E9B711E1944B4420AD9B81801323A -:1018500011F801EFD2B20136072A80F808E0B6B2DB -:10186000F2D1B44208BF4FF0400B009BB818197872 -:10187000013201F01F0141EA48114BEA01030372F2 -:101880004AF000437B603A7439464846FFF734FE1D -:101890000135B4422DB288F001084FF0000BBED1E3 -:1018A00090E70022CDE76FF001058BE7FC3F0008D1 -:1018B000E03D0008B4400008204000082DE9F04752 -:1018C0001E46CB8A9146C3F30902062A80460F467C -:1018D00019D013460021B0B28DB25A1992B2052A1E -:1018E00009D9A84210D8FA8A034463F30902FA829C -:1018F0000120BDE8F087A842F3D919F801403A4425 -:1019000094760131E8E70025FB8A7C68C3F309007F -:101910001C23821FB2FBF3FA03FB1A2A1FFA8AF276 -:101920007CB301212368002B39D1B31F03441C2051 -:10193000B3FBF0F301339BB299420CD2BAF1000F22 -:1019400009D14046FFF7ACFD08B1C0F800A0206007 -:1019500008B3044600224FF0000AB6B2B54230D2B6 -:101960001346691E4944E018013311F801EF9BB298 -:1019700001351C2B80F804E0ADB214D0AE42F2D891 -:10198000ECE74046FFF78CFD044608B100230360F6 -:101990007C60002CDED16FF00200BDE8F0870131E1 -:1019A00089B21C46BEE7AE42D8D94046FFF778FD63 -:1019B00008B1C0F800A020600028ECD00446002246 -:1019C000CCE7FB8AC3F30902164466F30903FB82E2 -:1019D0008EE70000F8B50E4615461F46044628B9A6 -:1019E000144B154A4F21154802F054F824220021C7 -:1019F000FFF7B2FC069B6A096360079B0020236225 -:101A00004FF6FF739A4228BF1A46A7602070A06164 -:101A1000E06197B204F10C05824205D100232B60EE -:101A200027826382A382F8BD2E60013035462036BE -:101A3000F2E700BFF83F00086C3D0008B440000822 -:101A400008B528B97321084B084A094802F022F862 -:101A5000037823B94BB2002B01DD017008BD054BA3 -:101A6000024A7D21F1E700BFFC3F0008783D0008F5 -:101A7000B4400008403F0008007870472DE9F74364 -:101A80000D9E074619461046BDF828900B9D9DF8FF -:101A90003040BDF8388016B9B8F1000F43D11F2C83 -:101AA00041D83B78D3B9B8F1070F39D839F00303DF -:101AB00039D1424631464FF6FF70FFF73FFE4FEAFD -:101AC000092920F0010009F44079400449EA04643E -:101AD000400C44EA40244FF6FF730DE043EA09232B -:101AE000B8F1070F43EA0464F5D9FFF701FE424657 -:101AF0003146FFF723FE03468DE840012A46214682 -:101B00003846FFF735FE0DB9FFF750FD2B7801334E -:101B1000DBB21F2B88BF00232B7003B0BDE8F0831E -:101B20006FF00300F9E76FF00100F6E72DE9F743E6 -:101B30000E9F81460B9D9DF830009DF83480BDF8C6 -:101B40003C6007B9C6BB1F2836D899F800E0BEF143 -:101B5000000F34D00C0244F080049DF8281044EAB1 -:101B6000C83444EA014444EA0E04072E44EA0064FF -:101B700015D919461046FFF7BBFD32463946FFF727 -:101B8000DDFD0346019600972A4621464846FFF7A9 -:101B9000EFFDB8F1010F0CD125B9FFF707FD4FF6A6 -:101BA000FF73EFE72B780133DBB21F2B88BF0023D5 -:101BB0002B7003B0BDE8F0836FF00100F9E76FF020 -:101BC0000300F6E7C06900B104307047C1690C300A -:101BD0000B680361FFF7F8BC2DE9F84FD0F818A0A7 -:101BE000054616461F4654464FF00009DFF8608050 -:101BF00000F10C0B0CB9BDE8F88FD4E90223B21A3E -:101C000067EB0303994508BF90451FD2AB69214696 -:101C10009C4228460DD1FFF7EDFCAB6921461B68BD -:101C20005846AB61FFF7D0FCAC692346A2461C4680 -:101C3000E0E7FFF7DFFC23682146CAF8003058468A -:101C4000FFF7C2FC5446DAF80030EFE72368EDE70F -:101C500080841E002DE9F04F8BB00D46144607938B -:101C6000DDF850908246002800F06481B9F1000F41 -:101C700000F06081531E3F2B00F25C81012A03D1EA -:101C8000079B002B40F056810023BAF8146008939C -:101C9000F600B542099380F053812B199E420AD277 -:101CA000761B16F0FF0607D140F26751AA4BAB4AEC -:101CB000AB4801F0EFFE2646DAF80C3023B9DAF82B -:101CC0001030002B00F0A5802F2D31D8C5F1300841 -:101CD00046454FF0000334BFB0465FFA88F80093E2 -:101CE000294608AB4246DAF80800FFF7B7FCA6EB36 -:101CF00008074544FFB24FF0300BBAF8143003F137 -:101D00000053063BDB000293DAF80C300593059B89 -:101D1000002B51D087B9DAF81000002861D0002FCD -:101D20005FD0AB4550D98F4B8C4A40F2A651BFE7EC -:101D300037464FF00008DEE7029B23B98A4B874AFB -:101D40004FF4B161B4E7029BE02B28BFE023069378 -:101D50005B44AB4204931DD95B1B9F4226BFDBB2A1 -:101D600003930397AB4504D97E4B7C4A40F29151D3 -:101D70009EE70598CDF8008008ABA5EB0B01039A10 -:101D80000430FFF76BFC039B9844FF1A1D445FFA75 -:101D900088F8FFB2049B9B4504D3744B6F4A40F212 -:101DA0009B5185E7029B069ADDF810B09B1A0293BF -:101DB000059B1B680593AAE7029BBB42ABD26C4B09 -:101DC000664A40F2A15173E7CDF800803A46A5EB90 -:101DD0000B0108ABB8443D44FFF740FC00275FFA15 -:101DE00088F8BAF81430B5EBC30F04D9614B5B4ADD -:101DF00040F2B1515CE7B8F1400F04D95E4B574A4D -:101E000040F2B25154E767B15C4B544A40F2B351CF -:101E10004EE70093324608AB2946DAF80800FFF790 -:101E20001DFC731E3F2B35B201D8A64204DD544B76 -:101E3000544A40F235213BE760070AD00AAB03EB76 -:101E4000D40111F8083C624202F00702134101F884 -:101E5000083C082C21D9102C21D9202C8CBF082318 -:101E60000423079A002A6DD0B4EBC30F6CD0082C62 -:101E700004F1FF3215D89DF8203023FA02F2D10781 -:101E800006D54FF0FF3202FA04F423438DF82030D8 -:101E90009DF8203089F800304EE00123E1E702236D -:101EA000DFE7102C11D8BDF8203023FA02F2D20758 -:101EB00006D54FF0FF3202FA04F42343ADF8203088 -:101EC000BDF82030A9F8003036E0202C0ED8089953 -:101ED00021FA02F2D30705D54FF0FF3303FA04F4D9 -:101EE0000C430894089BC9F8003025E0402C1CD016 -:101EF000DDE9086730463946FEF732F9002100F087 -:101F0000010050EA01030BD0224601200021FEF718 -:101F100033F9404261EB410106430F43CDE90867C5 -:101F2000DDE90823C9E9002306E0174B154A4FF401 -:101F30002071BDE66FF0010528460BB0BDE8F08FBB -:101F40001D46F9E7012CA3D0082CA1D9102CB7D934 -:101F5000202CE5D8C6E700BF4C3E0008243E000810 -:101F6000B44000086E3E00085B3E0008933E000847 -:101F7000BB3E0008E23E0008103F0008283F000872 -:101F8000423F0008A43D0008403F000830B585B03E -:101F900030B940F2B121234B234A244801F07AFDA5 -:101FA00023B9234B204A40F2B221F6E7402A04D954 -:101FB000204B1D4A40F2B621EFE722B91D4B1A4AC9 -:101FC0004FF42F71E9E70024012A0294039417D1FA -:101FD0001B788DF8083053070AD004AB03EBD2030B -:101FE00013F8084C554205F00705AC4003F8084CBF -:101FF00000910346002102A8FFF730FB05B030BD79 -:10200000082AE5D9102A03D81B88ADF80830E2E782 -:10201000202A02D81B680293DDE7D3E90045CDE909 -:102020000245D8E77C3F0008B83D0008B4400008EE -:10203000973F0008403F000870B50C4600F10C05C2 -:10204000E16819B9A1602161A18270BD0E682846BE -:10205000FFF7BAFAE660F3E72DE9F04FD1F8009008 -:1020600091B0C9F3C01604460D46CDE90223002EF7 -:1020700050D0C9F3C03BC9F30626B9F1000F80F276 -:102080009F8119F0C04F40F09B812B7B002B00F00B -:102090009781BBF1020F03D02278B24240F09381C6 -:1020A00009F07F02BBF1020F059236D119F07F0FC4 -:1020B000C9F30F2A01D10AF0030A2B447606059AC8 -:1020C00093F8038046EA0B4646EA82465FEAD81355 -:1020D00046EA0A06069300F09A800022002310A91F -:1020E00061E90823059B6768009352465B462046DA -:1020F000B847002800F08880A7698FB9314604F1FD -:102100000C00FFF7DBF90746D0B96FF0020011B001 -:10211000BDE8F08F4FF0020BAFE7C9F3074ACCE7F9 -:102120003B699E420DD03F68002FF9D1314604F142 -:102130000C00FFF7C3F907460028E6D0A3693B600F -:10214000A761DDE90801FFF7D3FAB882F97D08F04D -:102150001F06C1F38401711A89B20FFA81FEBEF124 -:10216000000FB8BF01F1200EC9F30461D7E90223C3 -:10217000B8BF0FFA8EFE079152EA030100F02F81DB -:10218000DDE90201801A61EB03010B4600210246E2 -:102190009E48994208BF9042C0F02181069B002BC7 -:1021A0003FD0BEF1010F00F31A8118F0400F38D074 -:1021B000DDE90223C7E90223202200210DEB020002 -:1021C000FFF7CAF8DDE90223CDE908232B1D0A93A6 -:1021D0002B7B2046013BDBB2ADF834309DF81C3040 -:1021E000ADF836A08DF83A309DF814308DF838B03F -:1021F0008DF83B308DF83960A36808A998473846B8 -:10220000FFF70CFA002082E76FF00B007FE7A76969 -:1022100017B96FF00C007AE73B699E4296D03F6891 -:10222000F6E7FB7DC8F34012B2EBD31F40F0CE803F -:10223000C3F38403B34240F0CC8006992B7B4FEA72 -:10224000981279B3D2073CD4032B40F2C580DDE964 -:102250000223C7E902232B7BAE1D033BDBB23246D0 -:10226000394604F10C00FFF729FB002808DA39464B -:102270002046FFF7BFF93846FFF7D0F9032046E7BD -:10228000AB883B832A7B033AD2B2B88A3146FFF748 -:1022900055FAFB7DB882DA43C2F3C01262F3C7136A -:1022A000FB75AFE76AB92E1D013BDBB232463946FA -:1022B00004F10C00FFF702FB0028D8DB2A7B013A6F -:1022C000E2E7FA8A013BC2F30902052AD9B250D8E3 -:1022D0000023281D99420AD907EB020E10F801CB02 -:1022E00001320133062A8EF81AC0DBB2F2D18B42DA -:1022F00028BF0023DDE9028907F11A02CDE9088928 -:102300000A927A683CBF04335B190B920C93FB8AE8 -:10231000ADF836A0C3F3090319449DF81C30ADF89D -:1023200034108DF83A309DF814308DF838B08DF8AF -:102330003B3000238DF839607B602A7BB88A013AF4 -:10234000291DFFF7FBF93B8BB882834203D1A368B9 -:1023500008A92046984708A92046FFF76DFE384691 -:10236000FFF75CF9B88A3B8B984214BF112000201C -:10237000CDE6786810B34FF0060E03689BB9A2EB68 -:102380000E021B2A13D80332024405F1040E1F303B -:102390009942ACD91EF801CB013302F801CF90422B -:1023A000DBB2F5D1A3E70EF11C0E1846E5E7184B9A -:1023B000184A40F2B311184801F06CFB034696E747 -:1023C0006FF00900A3E66FF00A00A0E66FF00D00C1 -:1023D0009DE66FF00E009AE66FF00F0097E6FB7D2A -:1023E000394668F386036FF3C713FB752046FFF782 -:1023F00001F9069B002B7FF4D8AEFB7DC3F384026A -:10240000013262F38603FB7503E700BF80841E0080 -:10241000AC3F0008903D0008B44000082DE9F041B1 -:102420004E4EB04240F086804D4CDFF838E1E56911 -:1024300045F00075E561E469846AD4F8007207EA42 -:102440000E0747F00107C4F80072D4F8005205EAFD -:102450000E0545F0010545EA0121C4F80012002AE5 -:102460006AD000210F46C4F81C12C4F80412C4F844 -:102470000C12C4F8141204EBC10501310E29C5F881 -:102480004072C5F84472F6D14FF0000E4FF0010CC7 -:10249000964510D1826AB042D2F8003223F001038F -:1024A000C2F8003258D12E4BDA6922F00072DA619C -:1024B000DB69BDE8F0819F781D8817F0010F18BF18 -:1024C000D4F804820CFA05F11CBF41EA0808C4F8EC -:1024D000048217F0020F18BFD4F80C8204EBC50574 -:1024E0001CBF41EA0808C4F80C827F0748BFD4F833 -:1024F000147203F10C0344BF0F43C4F8147253F871 -:10250000087C0EF1010EC5F8407253F8047CC5F842 -:102510004472D4F81C522943C4F81C12B8E70021B5 -:10252000846AC4F81C12C4F80412C4F80C12C4F86B -:102530001412A9E7002AF2D10022836AC3F84022CC -:10254000C3F84422C3F80422C3F814220122C3F8BA -:102550000C22C3F81C229DE7BDE8F081E022002098 -:10256000001002400000FFFF184A08B5916A8B680E -:102570008B6013F0010105D013F00C0F14BF4FF462 -:1025800080310121D80506D513F4406F14BF41F402 -:10259000003141F00201D80306D513F4402F14BFD7 -:1025A00041F4802141F00401D3690BB107489847F9 -:1025B000202383F311880021054800F09DFE0023AD -:1025C00083F31188BDE8084001F086B8E0220020BE -:1025D000E822002038B5124CA36ADD68AA0712D0A1 -:1025E0005A6922F002025A61A36913B101212046FF -:1025F0009847202383F3118800210A4800F07CFECD -:10260000002383F31188EB0606D51021A36AD96055 -:10261000236A0BB102489847BDE8384001F05CB826 -:10262000E0220020F022002038B5124CA36A1D6978 -:10263000AA0712D05A6922F010025A61A36913B195 -:10264000022120469847202383F3118800210A485D -:1026500000F052FE002383F31188EB0606D510210B -:10266000A36A1961236A0BB102489847BDE8384054 -:1026700001F032B8E0220020F022002038B50F4CE3 -:10268000A36A5D682A075D600AD5032222701A6872 -:1026900022F002021A60636A13B1002120469847B3 -:1026A0006B0706D5A36A9969236A13B10904034825 -:1026B0009847BDE8384001F00FB800BFE022002085 -:1026C00010B50F4C204600F03FFA0E4B0B211320A3 -:1026D000A36200F019FA0B21142000F015FA0B2167 -:1026E000152000F011FA0B21162000F00DFA00233E -:1026F0002046BDE810401A460E21FFF78FBE00BFEE -:10270000E0220020006400400F4B10B598420446C0 -:1027100005D10E4BDA6942F00072DA61DB69012201 -:10272000A36A1A60A36A5A68D20707D5626851681B -:102730001268D9611A60064A5A6110BD0121082049 -:1027400000F092FCEEE700BFE02200200010024003 -:102750005B87010003291AD8DFE801F0020A0F1491 -:10276000836A9B6813F0E05F14BF0120002070476C -:10277000836A9868C0F380607047836A9868C0F382 -:10278000C0607047836A9868C0F30070704700208B -:102790007047000010B503291FD8DFE801F0021FC1 -:1027A0002327816A8B68C3F30163183301EB03139A -:1027B000107881061ED55468C0F30011490041EA23 -:1027C000C40141F0040100F00F005860906841F02E -:1027D00001019860D268DA60196010BD836A03F560 -:1027E000C073E5E7836A03F5C873E1E7836A03F51D -:1027F000D073DDE79488C0F30011490041EA4451E9 -:10280000E1E7000001290CD003D3022910D00020F9 -:102810007047836ADA68920701D1186903E00120E2 -:102820007047836AD86810F0030018BF0120704712 -:10283000836AF2E710B539B9836AD96889071BD171 -:102840001B699B0704D110BD012915D0022948D16D -:10285000816AD1F8C031D1F8C401D1F8C8411461FE -:10286000D1F8CC41546120240C610C69A40717D124 -:102870004C6944F0100412E0816AD1F8B031D1F80B -:10288000B401D1F8B8411461D1F8BC41546120249D -:10289000CC60CC68A40703D14C6944F002044C61BD -:1028A00011795C0864F304119C0864F345111171FB -:1028B00089064BBF91681189DB085B0D4CBF63F340 -:1028C0001C0163F30A01137948BF916060F30303AD -:1028D00013714FEA10234FEA104058BF1181137053 -:1028E000508010BD00231A4610B51C495A50CC1810 -:1028F0000833802B6260F9D1194B9A6942F07D024E -:102900009A619B690268174BDA6082685A60426874 -:102910001A60C26803F58063DA6042695A6002692E -:102920001A608269C3F80C24026AC3F80424C269DD -:10293000C3F80024426AC3F80C28C26AC3F804280A -:10294000826AC3F80028026BC3F80C2C826BC3F8B0 -:10295000042C426BC3F8002C10BD00BF0C230020D8 -:102960000010024000080140026843681143016002 -:1029700003B1184770470000024AD36843F0C00310 -:10298000D360704700380140024AD36843F0C00367 -:10299000D3607047004400402DE9F041D0F89C60BE -:1029A0000546F7683368DA059CB20DD5202383F31A -:1029B00011884FF400710430FFF7D6FF6FF4807375 -:1029C0003360002383F31188202383F3118805F1FA -:1029D000040814F02F0333D183F31188380615D57A -:1029E000210613D5202383F3118805F1380000F068 -:1029F0002FFA002846DA0821281DFFF7B5FF4FF609 -:102A00007F733B40F360002383F311887A060ED571 -:102A100063060CD5202383F31188EA6C2B6D9A4250 -:102A200002D12B6C002B2FD1002383F31188D5F812 -:102A3000A420D368002B31D0BDE8F04110691847BD -:102A4000230713D014F0080F0CBF00218021E007EA -:102A500048BF41F02001A20748BF41F04001630791 -:102A600048BF41F480714046FFF77EFFA4067368BB -:102A700005D595F8A0102846194000F089FA346869 -:102A8000A4B2A6E77060BEE727F040073F0410211C -:102A9000281D3F0CFFF768FFF760C5E7BDE8F08130 -:102AA00008B50348FFF778FFBDE8084000F014BE02 -:102AB0008C23002008B50348FFF76EFFBDE80840EF -:102AC00000F00ABE3424002010B5094C094A204603 -:102AD000002100F03DFA084B084AC4F89C30084C2D -:102AE0000021204600F034FA064BC4F89C3010BD9B -:102AF0008C2300207929000800380140892900082A -:102B0000342400200044004000F16043090103F533 -:102B10006143C9B283F80013012300F01F0240098A -:102B2000800000F16040934000F56140C0F88031C2 -:102B300003607047090100F16040C9B200F56D40C3 -:102B400001767047FFF7BCBD01230370002300F13D -:102B500008028260C26000F11002436002614261BB -:102B60008361C361036243627047000010B5202394 -:102B7000044683F31188022341600370FFF7C4FD0C -:102B800003232370002383F3118810BD2DE9F04146 -:102B90001F4604460D461646202383F3118800F194 -:102BA00008082378042B0ED029462046FFF7D2FDD3 -:102BB00048B1204632462946FFF7ECFD002080F35D -:102BC0001188BDE8F0813946404600F079FB0028C5 -:102BD000E7D0002383F31188BDE8F0812DE9F041AF -:102BE0001F4604460D461646202383F3118800F144 -:102BF00010082378042B0ED029462046FFF702FE4A -:102C000048B1204632462946FFF714FE002080F3E3 -:102C10001188BDE8F0813946404600F051FB00289C -:102C2000E7D0002383F31188BDE8F081F8B515469D -:102C300082680B46AA428169066938BF8568761AA0 -:102C4000B542044607D218462A46FEF773FBA3692D -:102C50002B44A3610DE011D932461846FEF76AFBFA -:102C6000AF1B3A46E1683044FEF764FBE2683A4441 -:102C7000A261A36828465B1BA360F8BD18462A46DC -:102C8000FEF758FBE368E4E72DE9F04104461546FA -:102C900083682669934238BF856840690F46361AB3 -:102CA000B54206D22A46FEF745FB63692B446361B1 -:102CB0000DE012D93246A5EB0608FEF73BFB424673 -:102CC000B919E068FEF736FBE26842446261A36826 -:102CD00028465B1BA360BDE8F0812A46FEF72AFB6D -:102CE000E368E4E710B50024C361029B0A44006076 -:102CF00040608460C160816141610261036210BD16 -:102D000008B582694369934201D1826882B98268B9 -:102D1000013282605A1C42611970426903699A4209 -:102D200001D3C3684361002100F0DAFA002008BD36 -:102D30004FF0FF3008BD000070B5202304460E465A -:102D400083F31188A568A5B1A368A269013BA360BC -:102D5000531CA36115782269934224BFE368A361E1 -:102D6000E3690BB120469847002383F31188284676 -:102D700070BD3146204600F0A3FA0028E2DA85F360 -:102D8000118870BD2DE9F74F05460F4690469A46CB -:102D9000D0F81C90202686F311884FF0000B1446C3 -:102DA00064B1224639462846FFF740FF034668B91A -:102DB0005146284600F084FA0028F1D0002383F31E -:102DC0001188A8EB040003B0BDE8F08FB9F1000F43 -:102DD00003D001902846C847019B8BF31188E41A61 -:102DE0001F4486F31188DBE7C361009BC1608161EA -:102DF000416111440060406082600161036270477C -:102E0000F8B504460E461746202383F31188A568BB -:102E1000A5B1A368013BA36063695A1C62611E707F -:102E2000236962699A4224BFE3686361E3690BB175 -:102E300020469847002080F31188F8BD3946204687 -:102E400000F03EFA0028E2DA85F31188F8BD0000B0 -:102E50008369426910B59A4201D182687AB9826861 -:102E6000013282605A1C82611C7803699A4201D344 -:102E7000C3688361002100F033FA204610BD4FF093 -:102E8000FF3010BD2DE9F74F05460F4690469A4694 -:102E9000D0F81C90202686F311884FF0000B1446C2 -:102EA00064B1224639462846FFF7EEFE034668B96C -:102EB0005146284600F004FA0028F1D0002383F39D -:102EC0001188A8EB040003B0BDE8F08FB9F1000F42 -:102ED00003D001902846C847019B8BF31188E41A60 -:102EE0001F4486F31188DBE70268436811430160E1 -:102EF00003B11847704700001430FFF743BF0000CC -:102F00004FF0FF331430FFF73DBF00003830FFF7BC -:102F1000B9BF00004FF0FF333830FFF7B3BF0000F8 -:102F20001430FFF709BF00004FF0FF311430FFF7F6 -:102F300003BF00003830FFF763BF00004FF0FF32DF -:102F40003830FFF75DBF000000207047FFF7BCBDC1 -:102F50000E4B37B50360002343608360C3600123D9 -:102F6000044615460374202200900B4600F15C01D4 -:102F70001430FFF7B7FE00942B46202204F17C01A9 -:102F800004F13800FFF730FF03B030BDF040000817 -:102F900038B5C36904460D461BB904210844FFF740 -:102FA000A3FF294604F11400FFF7AAFE002806DA61 -:102FB000201D4FF48061BDE83840FFF795BF38BD54 -:102FC0000022024B1B605B609A607047DC2400208B -:102FD000002382680374054B1B6899689142FBD2F9 -:102FE0005A6803604260106058607047DC2400201B -:102FF00008B5202383F31188037C032B05D0042B11 -:103000000DD02BB983F3118808BD002243691A60E3 -:103010004FF0FF334361FFF7DBFF0023F2E790E857 -:103020000C001A6002685360F2E700000023826817 -:103030000374054B1B6899689142FBD85A6803607A -:103040004260106058607047DC240020054B19690D -:1030500008741868026853601A60186101230374C9 -:10306000FDF78EBADC24002030B54B1C87B0054636 -:103070000A4C10D023690A4A01A800F059F92846E1 -:10308000FFF7E4FF049B13B101A800F06BF923697B -:10309000586907B030BDFFF7D9FFF8E7DC240020FE -:1030A000F12F000838B50C4D41612B6981689A6891 -:1030B0000446914203D8BDE83840FFF789BF18465F -:1030C000FFF786FF01232C61014623742046BDE8EB -:1030D0003840FDF755BA00BFDC240020044B1A68C5 -:1030E0001B6990689B68984294BF0020012070473C -:1030F000DC24002010B5084C236820691A6854604D -:103100002260012223611A74FFF790FF01462069B3 -:10311000BDE81040FDF734BADC24002008B5FFF705 -:10312000DDFF18B1BDE80840FFF7E4BF08BD0000AF -:10313000FEE7000010B5174CFFF742FF00F0EAF879 -:1031400080221549204600F06FF8012344F8180C3E -:103150000374124B124AD96821F4E0610904090C86 -:103160000A431049DA60CA6842F08072CA600E49A8 -:103170000A6842F001020A601022DA77202283F8FE -:103180002220002383F3118862B6BDE8104007486F -:1031900000F06CB8042500201841000800ED00E0A4 -:1031A0000003FA05F0ED00E0001000E02041000807 -:1031B000F8B50F4C226A01322262224652F8141FDF -:1031C0009142154606D020268B68013B8B606369CF -:1031D0009A6802B1F8BD1968DF68DA604D60616114 -:1031E00082F311881869B84786F31188EFE700BFAA -:1031F000DC240020EFF3118020B9EFF305832022B7 -:1032000082F311887047000010B558B9EFF30584B8 -:10321000C4F3080414B180F3118810BDFFF77EFFDA -:1032200084F3118810BD0000826002220274002223 -:10323000427470478368A3F13C0243F80C2C026986 -:1032400043F83C2C426943F8382C074A43F81C2CBD -:10325000C268A3F1180043F8102C022203F8082CCE -:10326000002203F8072C70479105000810B52023B1 -:1032700083F31188FFF7DEFF00210446FFF712FFFA -:10328000002383F31188204610BD0000024B1B6908 -:1032900058610F20FFF7DABEDC240020202383F3DF -:1032A0001188FFF7F3BF000008B50146202383F320 -:1032B00011880820FFF7D8FE002383F3118808BD8A -:1032C00049B1064B42681B6918605A60136043603D -:1032D0000420FFF7C9BE4FF0FF307047DC24002008 -:1032E0000368984206D01A68026050605961184617 -:1032F000FFF76EBE7047000038B504460D462068E3 -:10330000844200D138BD036823605C604561FFF7EB -:103310005FFEF4E7054B03F114025A619A614FF026 -:10332000FF32DA6100221A62704700BFDC240020FD -:1033300010B5C2600A4A036153699C68A1420CD867 -:103340005C68036044602060586081609868411A3E -:1033500099604FF0FF33D36110BD091B1B68ECE788 -:10336000DC240020036881689A680A449A604268F5 -:10337000136003685A6000234FF0FF32C360014BB3 -:10338000DA617047DC24002000207047FEE700006F -:10339000704700004FF0FF3070470000BFF34F8FC1 -:1033A000024AD368DB07FCD4704700BF002002400C -:1033B00008B5074B1B7853B9FFF7F0FF054B1A69A7 -:1033C000120641BF044A5A6002F188325A6008BDB1 -:1033D000E0250020002002402301674508B5054B89 -:1033E0001B7833B9FFF7DAFF034A136943F0800310 -:1033F000136108BDE0250020002002407F289ABF0D -:1034000000F5003080020020704700004FF480601B -:1034100070470000802070477F2808B50BD8FFF761 -:10342000EDFF00F580630268013204D1043083426D -:10343000F9D1012008BD002008BD00007F2838B563 -:10344000044624D800F0B6F8124D2860FFF7A6FF16 -:10345000FFF7AEFFF322104B2046DA6002221A611A -:10346000FFF7CCFF58611A6942F040021A61FFF77A -:1034700095FF4FF4806100F0E9F8FFF7AFFF00F02F -:1034800099F828602046BDE83840FFF7C5BF002006 -:1034900038BD00BFE4250020002002402DE9F8439C -:1034A00012F00103144606D040F24B221F4B1A6063 -:1034B0000020BDE8F88385181D4A954204D94FF4D1 -:1034C00014711A4A1160F3E7FFF772FFFFF766FF06 -:1034D0004FF00109DFF86880451A012C05EB010661 -:1034E0000F4604D8FFF77AFF0120BDE8F883C8F83B -:1034F000109031F8023B3380FFF750FF0020C8F8EE -:10350000100033883A889BB29A420DD040F267226D -:10351000064B1A60074B1E60074B1C60074B1F6071 -:10352000FFF75CFFBDE8F883023CD6E7DC2500200E -:10353000FFFF0108D0250020D8250020D425002039 -:1035400000200240084908B50B7828B153B9FFF7AD -:103550002FFF01230B7008BD23B1BDE808400870A0 -:10356000FFF73CBF08BD00BFE025002038B5FFF7DE -:1035700041FE4FF47A730C490C4A0C6A116803FB44 -:1035800004F38B420A49D1E9004504D2003445F1E5 -:103590000105C1E90045E41845F100051360FFF796 -:1035A00033FE2046294638BDDC240020E8250020D3 -:1035B000F025002008B5FFF7D9FF4FF47A720023F9 -:1035C000FCF7E6FD08BD00BF10B5094C0439013A0F -:1035D000D2B2FF2A00D110BD53089800043054F82D -:1035E000233000599BB243EA004341F8043FEEE721 -:1035F000046C004030B50748013AD2B2FF2A00D12E -:1036000030BD0D88540840F82450A3004C88043382 -:103610001C50F1E7046C004007B5012201A900200D -:10362000FFF7D2FF019803B05DF804FB13B5044621 -:10363000FFF7F2FFA04206D002A941F8044D012293 -:103640000020FFF7D7FF02B010BD00007047000058 -:1036500045F25552064B1A6002225A6040F6FF723C -:103660009A604CF6CC421A600122024B1A707047E5 -:1036700000300040F9250020034B1B781BB14AF6AF -:10368000AA22024B1A607047F92500200030004042 -:10369000034B1B689B0042BF0122024B1A7070470C -:1036A00024100240F82500204FF08072014B1A6070 -:1036B000704700BF24100240014B1878704700BFCC -:1036C000F8250020EFF30983203383F309880023D2 -:1036D00083F311887047000010B5202383F311880D -:1036E0000D4B5B6813F4006312D0EFF309844FF0C5 -:1036F000807344F8043CA4F1200383F30988FFF7A6 -:10370000EDFC18B1054B44F8083C10BD044BFAE73A -:1037100083F3118810BD00BF00ED00E0A105000893 -:10372000A405000870470000FEE70000084A094BA6 -:1037300009498B4204D30021084A934205D37047BC -:1037400052F8040F43F8040BF3E743F8041BF4E7C3 -:10375000304200080026002000260020002600201D -:1037600000F030B808B500F063F9FFF7E3FCBDE8FE -:103770000840FFF78DBF0000704700004FF0FF3199 -:103780000E4B1A6919611A6900221A611869D86802 -:10379000D960D968DA60DA68DA6942F08052DA61B1 -:1037A000DA69DA6942F00062DA61054ADB691368B6 -:1037B00043F48073136000F01BB900BF0010024097 -:1037C00000700040194B1A6842F001021A601A6832 -:1037D0009007FCD51A6802F0F9021A6000225A60BC -:1037E0005A6812F00C0FFBD11A6842F480321A604A -:1037F0001A689103FCD55A6842F4E8125A601A68B4 -:1038000042F080721A601A689201FCD51221084AAF -:103810005A60084A11605A6842F002025A605A68B7 -:1038200002F00C02082AFAD1704700BF00100240D3 -:1038300000641D0000200240084A08B55369116861 -:103840000B4003F00103536123B1054A13680BB128 -:1038500050689847BDE80840FFF73EBF00040140AC -:103860000C230020084A08B5536911680B4003F087 -:103870000203536123B1054A93680BB1D06898479E -:10388000BDE80840FFF728BF000401400C230020DA -:10389000084A08B5536911680B4003F004035361EB -:1038A00023B1054A13690BB150699847BDE8084038 -:1038B000FFF712BF000401400C230020084A08B59E -:1038C000536911680B4003F00803536123B1054AA3 -:1038D00093690BB1D0699847BDE80840FFF7FCBE7B -:1038E000000401400C230020084A08B55369116800 -:1038F0000B4003F01003536123B1054A136A0BB167 -:10390000506A9847BDE80840FFF7E6BE0004014052 -:103910000C230020174B10B55C691A68144004F49E -:1039200078725A61A30604D5134A936A0BB1D06A20 -:103930009847600604D5104A136B0BB1506B98473B -:10394000210604D50C4A936B0BB1D06B9847E20566 -:1039500004D5094A136C0BB1506C9847A30504D5E4 -:10396000054A936C0BB1D06C9847BDE81040FFF747 -:10397000B3BE00BF000401400C2300201A4B10B559 -:103980005C691A68144004F47C425A61620504D5EB -:10399000164A136D0BB1506D9847230504D5134A91 -:1039A000936D0BB1D06D9847E00404D50F4A136EA8 -:1039B0000BB1506E9847A10404D50C4A936E0BB11D -:1039C000D06E9847620404D5084A136F0BB1506F4C -:1039D0009847230404D5054A936F0BB1D06F9847DD -:1039E000BDE81040FFF778BE000401400C23002022 -:1039F000062108B50846FFF787F806210720FFF7DC -:103A000083F806210820FFF77FF806210920FFF739 -:103A10007BF806210A20FFF777F806211720FFF729 -:103A200073F8BDE8084006212820FFF76DB80000B4 -:103A300008B5FFF7A3FE0648FEF754FFFFF782F82C -:103A4000FFF784FAFFF798FEBDE8084000F002B8DF -:103A50004041000800F00EB808B5202383F3118818 -:103A6000FFF7A6FB002383F31188BDE80840FFF7AA -:103A700033BE0000054B064A08215A6000229A60B6 -:103A800007220B201A60FFF755B800BF10E000E0D6 -:103A90003F1901001FB51C46094B05461B68D86835 -:103AA00052B1084B8DE80A0002922B462246064985 -:103AB000FDF7AAFC00F042F8044B1A46F2E700BFFB -:103AC000101100207C410008894100086C3C00086E -:103AD00010B501390244904201D1002010BD10F808 -:103AE000013B11F8014FA342F5D0181B10BD000097 -:103AF0002DE9F8430746884691461E468BB10D4690 -:103B0000A8EB0500B54207EB000402D20020BDE897 -:103B1000F883324649462046FFF7DAFF18B1013DE7 -:103B2000EEE7BDE8F8832046BDE8F883034611F8C8 -:103B3000012B03F8012B002AF9D1704708B50620A4 -:103B400000F02CF80120FFF721FC00001F2938B5F8 -:103B500004460D4604D9162303604FF0FF3038BDEC -:103B6000426C12B152F821304BB9204600F030F8C7 -:103B70002A4601462046BDE8384000F017B8012B20 -:103B80000AD0591C03D116230360012038BD00243C -:103B9000284642F825409847002038BD024B014690 -:103BA0001868FFF7D3BF00BF1011002038B50023FD -:103BB000064C0546084611462360FFF7EBFB431C05 -:103BC00002D1236803B12B6038BD00BFFC25002063 -:103BD000FFF7DABB40A2E4F1646891064E6F206102 -:103BE0007070207369670A00426164206677206CF8 -:103BF000656E6774682025750A0042616420626FF3 -:103C00006172645F69642025752073686F756C64E8 -:103C10002062652025750A00426164206677206471 -:103C2000657363726970746F72206C656E67746817 -:103C30002025750A00426164206170702043524360 -:103C4000203078253038783A307825303878203070 -:103C500078253038783A3078253038780A00476F40 -:103C60006F64206669726D776172650A00000000FA -:103C700072656365697665645F756E697175655FA8 -:103C800069645F6C656E203C2055415643414E5F30 -:103C900050524F544F434F4C5F44594E414D49434E -:103CA0005F4E4F44455F49445F414C4C4F43415444 -:103CB000494F4E5F554E495155455F49445F4D410F -:103CC000585F4C454E475448002E2E2F2E2E2F5411 -:103CD0006F6F6C732F41505F426F6F746C6F6164D4 -:103CE00065722F63616E2E63707000616C6C6F6320 -:103CF000617465645F6E6F64655F6964203C3D203C -:103D0000313237006F72672E6172647570696C6F43 -:103D1000742E61705F7065726970685F72616E6742 -:103D20006566696E64657200766F69642068616EAD -:103D3000646C655F616C6C6F636174696F6E5F72F8 -:103D40006573706F6E73652843616E617264496E4E -:103D50007374616E63652A2C2043616E61726452D4 -:103D6000785472616E736665722A290063616E61B0 -:103D70007264496E6974000063616E6172645365B8 -:103D8000744C6F63616C4E6F6465494400000000C1 -:103D900063616E61726448616E646C6552784672EC -:103DA000616D650063616E6172644465636F646533 -:103DB0005363616C6172000063616E617264456E91 -:103DC000636F64655363616C61720000696E637256 -:103DD000656D656E745472616E73666572494400F8 -:103DE000656E717565756554784672616D657300B1 -:103DF000707573685478517565756500707265707B -:103E0000617265466F724E6578745472616E736646 -:103E100065720000636F70794269744172726179F2 -:103E200000000000646573636174746572547261AC -:103E30006E736665725061796C6F6164000000009A -:103E400066726565426C6F636B0000006269745F47 -:103E50006C656E677468203E20300072656D616924 -:103E60006E696E675F62697473203E203000696E10 -:103E70007075745F6269745F6F6666736574203E07 -:103E80003D20626C6F636B5F6269745F6F6666731F -:103E9000657400626C6F636B5F656E645F6269740A -:103EA0005F6F6666736574203E20626C6F636B5F44 -:103EB0006269745F6F66667365740072656D6169CF -:103EC0006E696E675F6269745F6C656E67746820A7 -:103ED0003C3D2072656D61696E696E675F626974F1 -:103EE0007300696E7075745F6269745F6F66667384 -:103EF0006574203C3D207472616E736665722D3E60 -:103F00007061796C6F61645F6C656E202A20380087 -:103F10006F75747075745F6269745F6F66667365E0 -:103F200074203C3D2036340072656D61696E696EA7 -:103F3000675F6269745F6C656E677468203D3D20E1 -:103F4000300028726573756C74203E20302920265D -:103F5000262028726573756C74203C3D2036342908 -:103F60002026262028726573756C74203C3D2062E3 -:103F700069745F6C656E67746829000064657374AA -:103F8000696E6174696F6E20213D202828766F6903 -:103F900064202A2930290076616C756520213D2036 -:103FA0002828766F6964202A293029006F66667395 -:103FB00065745F77697468696E5F626C6F636B20AC -:103FC0003C2028333255202D205F5F6275696C7468 -:103FD000696E5F6F66667365746F66202843616EF5 -:103FE000617264427566666572426C6F636B2C2009 -:103FF00064617461292900006F75745F696E7320B4 -:10400000213D202828766F6964202A293029000064 -:104010007372635F6C656E203E20305500000000B7 -:104020002863616E5F6964202620307831464646F9 -:10403000464646465529203D3D2063616E5F6964D2 -:1040400000000000616C6C6F6361746F722D3E73D1 -:104050007461746973746963732E63757272656ECB -:10406000745F75736167655F626C6F636B73203E2D -:10407000203000007472616E736665725F6964203F -:10408000213D202828766F6964202A2930290000E4 -:1040900073746174652D3E6275666665725F626CED -:1040A0006F636B73203D3D202828766F6964202A5A -:1040B000293029002E2E2F2E2E2F6D6F64756C65E2 -:1040C000732F6C696263616E6172642F63616E61EC -:1040D00072642E63006974656D2D3E6672616D6554 -:1040E0002E646174615F6C656E203E2030000000BC -:1040F00000000000152F0008012F00083D2F0008C8 -:10410000292F0008352F0008212F00080D2F000847 -:10411000F92E0008492F00086D61696E000000004B -:104120003841000820250020D02500200100000093 -:10413000313100080000000069646C650000000077 -:104140000C1E0000447B4144B45749440100000068 -:104150004244444444444444000000004444444431 -:10416000444444440000000044444444444444441F -:104170000000000044444444444444442C206675F8 -:104180006E6374696F6E3A2000617373657274694F -:104190006F6E2022257322206661696C65643A2067 -:1041A00066696C6520222573222C206C696E65205F -:1041B0002564257325730A0008C0FF7F01000000F5 -:1041C0006400000000000000FE2A0100D20400008C -:1041D000141100200000000000000000000000009A -:1041E00000000000000000000000000000000000CF -:1041F00000000000000000000000000000000000BF -:1042000000000000000000000000000000000000AE -:10421000000000000000000000000000000000009E -:10422000000000000000000000000000000000008E -:04423000000000008A +:100000000009002069040008C114000865140008F4 +:10001000A514000865140008851400086B04000886 +:100020006B0400086B0400086B0400087D350008B1 +:100030006B0400086B0400086B040008113A000808 +:100040006B0400086B0400086B0400086B040008D4 +:100050006B0400086B0400083D370008693700088E +:1000600095370008C1370008ED3700086B04000819 +:100070006B0400086B0400086B0400086B040008A4 +:100080006B0400086B0400086B040008712400086E +:10009000DD240008312500088525000819380008EE +:1000A0006B0400086B0400086B0400086B04000874 +:1000B0006B0400086B0400086B0400086B04000864 +:1000C0006B0400086B0400086B0400086B04000854 +:1000D0006B04000825290008392900086B04000872 +:1000E000813800086B0400086B0400086B040008EA +:1000F0006B0400086B0400086B0400086B04000824 +:100100006B0400086B0400086B0400086B04000813 +:100110006B0400086B0400086B0400086B04000803 +:100120006B0400086B0400086B0400086B040008F3 +:100130006B0400086B0400086B0400086B040008E3 +:100140006B0400086B0400086B0400086B040008D3 +:100150006B0400086B0400086B0400086B040008C3 +:1001600053B94AB9002908BF00281CBF4FF0FF311E +:100170004FF0FF3000F076B9ADF1080C6DE904CE18 +:1001800000F006F8DDF804E0DDE9022304B0704772 +:100190002DE9F047089E0D4604468846002B4DD1B8 +:1001A0008A42944668D9B2FA82F252B101FA02F355 +:1001B000C2F1200120FA01F10CFA02FC41EA030825 +:1001C00094404FEA1C41B8FBF1F71FFA8CFE01FB8B +:1001D000178807FB0EF0230C43EA084398420AD91C +:1001E0001CEB030307F1FF3580F01E81984240F2BB +:1001F0001B81023F63441B1AB3FBF1F001FB103378 +:1002000000FB0EFEA4B244EA0344A6450AD91CEB47 +:10021000040400F1FF3380F00981A64540F2068115 +:10022000644402380021A4EB0E0440EA07401EB1EA +:100230000023D440C6E90043BDE8F0878B4208D9CB +:10024000002E00F0EE800021C6E900050846BDE85A +:10025000F087B3FA83F100294AD1AB4202D382423C +:1002600000F2FC80841A65EB030301209846002EFF +:10027000E2D0C6E90048DFE702B9FFDEB2FA82F257 +:10028000002A40F09180A1EB0C0001214FEA1C47AD +:100290001FFA8CFEB0FBF7F307FB1300250C45EAB1 +:1002A00000450EFB03F0A84208D91CEB050503F13D +:1002B000FF3802D2A84200F2CE8043462D1AB5FB89 +:1002C000F7F007FB10550EFB00FEA4B244EA05440C +:1002D000A64508D91CEB040400F1FF3502D2A6455F +:1002E00000F2B6802846A4EB0E0440EA03409EE7E5 +:1002F000C1F120078B4022FA07FC4CEA030C25FAD7 +:1003000007FA4FEA1C49BAFBF9F820FA07F309FB90 +:1003100018AA8D401FFA8CFE1D4300FA01F308FB5A +:100320000EF02C0C44EA0A44A04202FA01F20BD966 +:100330001CEB040408F1FF3A80F08880A04240F2F0 +:100340008580A8F102086444241AB4FBF9F009FB83 +:10035000104400FB0EFEADB245EA0444A64508D9A0 +:100360001CEB040400F1FF356CD2A6456AD90238B3 +:10037000644440EA0840A0FB0295A4EB0E04AC42A2 +:10038000C846AE4656D353D0002E69D0B3EB080210 +:1003900064EB0E0422FA01F304FA07F71F43CC4082 +:1003A000C6E90074002147E70CFA02FCC2F1200103 +:1003B00025FA01F34FEA1C4720FA01F195400D435D +:1003C000B3FBF7F107FB11331FFA8CFE280C40EA50 +:1003D000034001FB0EF3834204FA02F408D91CEB3C +:1003E000000001F1FF382FD283422DD90239604439 +:1003F000C01AB0FBF7F307FB1300ADB245EA0045A6 +:1004000003FB0EF0A84208D91CEB050503F1FF38E9 +:1004100016D2A84214D9023B6544281A43EA014186 +:1004200038E73146304607E72F46E4E61846F9E656 +:100430004B45A9D2B9EB020865EB0C0E0138A3E7D6 +:100440004346EAE7284694E74146D1E7D0467BE7B2 +:100450006444023847E7023B65442FE7084606E755 +:100460003146E9E6704700BF02E000F000F8FEE721 +:1004700072B6284880F30888274880F309882748FF +:100480004EF60851CEF200010860022080F3148875 +:10049000BFF36F8F03F0E4F803F0C0F803F0E2F865 +:1004A0004FF055301E491B4A91423CBF41F8040BA6 +:1004B000FAE71C49184A91423CBF41F8040BFAE79D +:1004C00019491A4A1A4B9A423EBF51F8040B42F896 +:1004D000040BF8E700201749174A91423CBF41F846 +:1004E000040BFAE703F09EF803F0BEF8134C144D2A +:1004F000AC4203DA54F8041B8847F9E700F03CF8F3 +:10050000104C114DAC4203DA54F8041B8847F9E74C +:1005100003F086B800090020001100200000000848 +:100520000001002000090020E83B00080011002025 +:100530002411002028110020A025002060010008BF +:100540006001000860010008600100082DE9F04F1B +:10055000C1F80CD0C3689D46BDE8F08F002383F33B +:1005600011882846A047002002F09CFDFEE702F01B +:1005700021FD00DFFEE700002DE9F04102F09CFFC5 +:10058000074602F0E7FF054600283ED12B4B9F426D +:100590003BD001339F423BD0294B27F0FF029A42C8 +:1005A0003AD1F8B200F052FAA84642F2107400F0C4 +:1005B00057FC08B10024A04600F04EFA064678B376 +:1005C00084BB464635B11F4B9F4203D0002402F046 +:1005D000B9FF2646002002F079FF1B4B9B6813F001 +:1005E000400322D00EB100F031F800F097FC00F08B +:1005F00077FE00F067FF0546CCB100F063FF401BBB +:10060000A04214D900F022F8F3E7A8460024CEE770 +:1006100004464FF00108CAE780464FF47A74C6E7F3 +:100620000446CFE74FF47A74CCE71C46DDE700F0D0 +:1006300025FD012002F03CFDDEE700BF010007B010 +:10064000000008B0263A09B0000C014038B51D4A38 +:100650001D4B1968013134D004339342F9D11B4C3E +:10066000194DD4F80424AA422BD3194B9B6803F1EB +:10067000006303F5C8439A4223D202F037FF02F029 +:1006800049FF002000F046FE0220124B187000F0D7 +:100690007DFE114BDA690022DA61D96999699A61A4 +:1006A0009B6972B64FF0E023C3F8085DD4F80034BC +:1006B000D4F80424202181F311889D4683F308880F +:1006C000104738BD2064000800640008006000087E +:1006D00000110020281100200010024049F269009A +:1006E000084A136899B21B0C00FB013344F25061B5 +:1006F0001360054B186882B2000C01FB0200186001 +:1007000080B27047201100201C11002010B5044653 +:100710000021102200F056FE034B03CB20606160E5 +:100720001868A06010BD00BFE8F7FF1F2DE9F04377 +:10073000BBB000F0C7FE40F2ED22204DAB68C31AFB +:10074000934232D906AF2B4628220021A8603846B2 +:1007500001F0C2FB05F10E0000F02CFE002604465D +:100760005FFA80F905F10E08F3B2F100994501F145 +:10077000280107D908EB06030822384601F0ACFB34 +:100780000136F1E708230122CDE902320C4B053492 +:1007900001933023A4B20093CDE9047405A3D3E9F7 +:1007A0000023297B074801F0ADF93BB0BDE8F08399 +:1007B000AFF3008078F6339F93CACD8D702100206F +:1007C0007D2100204421002070B50D4614461E46B0 +:1007D00001F02EF950B9022E10D1012C0ED112A326 +:1007E000D3E900230120C5E9002307E0282C10D01D +:1007F00005D8012C09D0052C0FD0002070BD302C5D +:10080000FBD10BA3D3E90023ECE70BA3D3E900232F +:10081000E8E70BA3D3E90023E4E70BA3D3E9002324 +:10082000E0E700BFAFF30080401DA12026812A0B26 +:1008300078F6339F93CACD8D9E6AC421818A46EE95 +:1008400026417272DF25D7B7F017304A39059E5618 +:1008500038B50D460446034620222846002101F003 +:100860003BFB22792346032A28BF0322284603F8AC +:10087000042F2021022201F02FFB62792346072A50 +:1008800028BF0722284603F8052F2221032201F062 +:1008900023FBA2792346072A28BF0722284603F80C +:1008A000062F2521032201F017FB284610222821BC +:1008B00004F1080301F010FB382038BD2DE9F04F9A +:1008C0000024ADF5037D10AE40F2751280460F4650 +:1008D00024A82146239400F075FD21464822304685 +:1008E00000F070FD00F0EEFD4FF47A72B0FBF2F014 +:1008F000544B23AD186093E80700012386E80700F6 +:100900000DF162003382FFF701FF4EF603033384DB +:1009100007AB18464C4903F0B3F82322294630644C +:10092000304686F83C20FFF793FF08220446014634 +:1009300014AB284601F0D0FA08222846A1180DF180 +:10094000510301F0C9FA082228460DF1520304F1BF +:10095000100101F0C1FA2022284615AB04F118015C +:1009600001F0BAFA4022284616AB04F1380101F032 +:10097000B3FA0822284618AB04F1780101F0ACFA6A +:10098000082228460DF1610304F1800101F0A4FA68 +:1009900004F1880A0DF1620904F5847B4B46514647 +:1009A000082228460AF1080A01F096FAD34509F10F +:1009B0000109F3D10822594628461DAB01F08CFAF3 +:1009C0004FF0000904F5887496F834304B450AD985 +:1009D000B36B21464B440822284601F07DFA0834C7 +:1009E00009F10109F0E74FF0000996F83C3004EBFB +:1009F000C9014B4508D9336C08224B44284601F005 +:100A00006BFA09F10109F0E700230393BB7E07317C +:100A1000029307F1190301930123C1F3CF01CDE93B +:100A200004510093404605A3D3E90023F97E01F069 +:100A300069F80DF5037DBDE8F08F00BF9E6AC42103 +:100A4000818A46EE2C110020903A0008014B187064 +:100A5000704700BF38110020F0B5334B85B01C7BC8 +:100A600034B10E22314B1A810024204605B0F0BD6E +:100A70002F4A02AB1068516803C308232D492E4842 +:100A80000DEB030202F0DCFF054630B90A22274BCA +:100A90002A481A8100F0E2FCE6E70169B1F5CE3F91 +:100AA00006D90B22214B26481A8100F0D7FCDCE73F +:100AB000438BB3F57A7F09D00C211C4A2148118160 +:100AC0004FF47A72194600F0C9FCCEE71E4A024480 +:100AD00002F11003994204D21022144B1B481A81D0 +:100AE000E3E710398E1A2046134900F0EFFC074661 +:100AF0003246204605F1180100F0E8FCAB689F4241 +:100B000002D1EB6898420AD00D22084B1A8100905E +:100B10003B46D5E902120E4800F0A0FCA4E70D48C0 +:100B200000F09CFC0124A0E7702100202C11002083 +:100B3000453B0008DC9B010000640008B43A000853 +:100B4000C03A0008D23A0008089CFFF7F03A0008C3 +:100B50000D3B0008363B00082DE9F04FADB006AF65 +:100B600080460C4600F064FF0546002859D1237EDC +:100B7000022B1AD1E38A012B17D100F0A3FC064601 +:100B8000FFF7ACFD4FF4C873B0FBF3F202FB1300A8 +:100B9000DFF8B49206F5167680B2E37E0644C9F813 +:100BA000006033B90022A94B1A709C37BD46BDE8DE +:100BB000F08FA38AEEB2013BB34205F101050BD9D8 +:100BC0003B1D1E44E900002308222046009601F048 +:100BD000F80101F043F8ECE707F11400FFF796FD88 +:100BE000324607F11401381D02F01AFF03460028AF +:100BF000D8D10F2E08D8954B1E70D9F80030A3F528 +:100C00001673C9F80030D0E7FA1CF870014600925C +:100C10002046072201F022F84046F97800F000FF54 +:100C2000C3E7E38A282B26D010D8012B1ED0052B32 +:100C3000BBD1BFF34F8F8649864BCA6802F4E0628E +:100C40001343CB60BFF34F8F00BFFDE7302BACD118 +:100C5000637E814D01336A7BDBB29342E94603D167 +:100C6000E27E2B7B9A4265D0CD469EE721464046E8 +:100C7000FFF724FE99E7A38A013B9BB2C92B94D8C6 +:100C8000754D2E7B26BB05F10C03009308223346DD +:100C90003146204600F0E2FF731CF2B2D9001E4636 +:100CA000A38A013B9A4205DA0E322A4400920023BD +:100CB0000822EEE700230022C5E900230023AB60F1 +:100CC00085F8D730C5F8D8302B7B0BB9E37E2B7372 +:100CD000002507F114060822294630463B1DC7E9C6 +:100CE0000155FD6001F0F8F83B7A05F10109AB42CE +:100CF0004FEAC90107D9FB6808222B44304601F0AE +:100D0000EBF84D46F0E70023C1F3CF01E07ECDE9DB +:100D100004610393A37E19340293282301460093B0 +:100D2000404647A3D3E90023019400F0EBFEFFF710 +:100D3000FDFC3AE74FF0000807F11403A7F8148010 +:100D40001022009341460123204600F087FFA68A27 +:100D5000023EB6B2F31C9B109B000733DB08A9EBE5 +:100D6000C3039D460DF1180A1FFA88F34FEAC80124 +:100D7000B34201F110010AD20AEB080300930822E2 +:100D80000023204600F06AFF08F10108ECE795F81F +:100D9000D70000F0C9FAD5F8D83004461BB995F849 +:100DA000D70000F0D1FAD5F8D83033449C4204D2B1 +:100DB00095F8D700013000F0C7FA4FF000084FEA6D +:100DC000960B1FFA88F18B45D5E9003209D90AEB59 +:100DD000880103EB8800012200F0FCFA08F1010809 +:100DE000EFE7F31842F10002C5E90032D5F8D83038 +:100DF00095F8D70006EB0308C5F8D88000F094FA00 +:100E0000804509D395F8D730D5F8D8000133001BB9 +:100E100085F8D730C5F8D800FF2E08D800232B73EB +:100E200000F0A4FAFFF718FE08B1FFF70FFC2B68DB +:100E30000A4A9B0A013313810023AB6014E700BF09 +:100E400026417272DF25D7B7402100203D210020C6 +:100E500000ED00E00400FA05702100202C110020B4 +:100E600030B54FF00054244B226885B09A4207D029 +:100E700002F07AFB0446A8B90024204605B030BD34 +:100E8000627D1E4B1E481A70237DC92203731D49C3 +:100E90000E3000F085FA2046E022002100F092FAA0 +:100EA0000124EAE7184A194DD36943F00073D3616E +:100EB000AA6D174B9A42DFD12B6E013B7E2BDBD8FC +:100EC000144A01AB07CA83E807001846032100F063 +:100ED00013FB6B6D83424FF00003CDD12A6D8A4224 +:100EE00003BFAB652A6E054B1C4601BF1A70EA6D45 +:100EF000094B1A60C1E700BF9AAD44C53811002004 +:100F00007021002016000020001002400066004002 +:100F10005041A0B0586600401811002002232DE96E +:100F2000F0434A4C85B0637100230293484BD3F8D9 +:100F300000C0BCF57A7F12D3464F474BB7FBFCF598 +:100F40009C458CBF0A231123B5FBF3F603FB165215 +:100F5000591EC8B2002A3ED002290B46F4D89DF88B +:100F60000B303E495A1E9DF80A303D48013B1B0498 +:100F700043EA0253BDF80820013A13434B6001F0E5 +:100F800037FD00230193374B374900934FF48052CC +:100F9000364B374800F01CFD364B197811B13448F8 +:100FA00000F03EFD00F08EFA0546FFF797FB4FF488 +:100FB000C873B0FBF3F202FB130305F516709BB286 +:100FC00018442D4B186002F0C5FA08B10F23238195 +:100FD00005B0BDE8F083731EB3F5806FBFD24FF448 +:100FE0007A75C0EBC00E0EF103034FEAE30909FB6B +:100FF0000555C3F3C703C11AC9B209F101088844F2 +:10100000B5FBF8F5B5F5617F08D90EF1FF33C3F3F1 +:10101000C703C11A581E0F28C9B214D84A1E072A7E +:101020008CBF00220122581800FB0660B7FBF0F7C6 +:10103000BC4594D1002A92D0ADF808608DF80A30F2 +:101040008DF80B108BE71346EDE700BF2C11002045 +:1010500018110020005125023F420F0010110020FE +:1010600088220020C90700083C110020590B000805 +:101070004421002038110020402100202DE9F04FAC +:1010800093A7D7E900670FF25029D9E90089854D68 +:1010900093B0DFF814B2854C284600F097FD0DF1AF +:1010A000300A079070B310220021504600F08AF9F0 +:1010B0004FF00002079B197B61F303028DF830208B +:1010C000586899680EAA03C21B680D9A584663F3C4 +:1010D0001C029DF830300D9243F020038DF8303023 +:1010E00000235246194601F093FC079028B9284680 +:1010F00000F070FD079B2370CEE72378072B3CD8C8 +:101100000133237018220021504600F05BF9DFF80C +:1011100098B1674C002352461946584601F0A0FC8E +:10112000014670BB102208A800F04CF9E36883F078 +:101130001003E36000F0C8F90DF1240C0B4612A96E +:10114000024611E903008CE803009DF83410C1F356 +:101150000300890649BF0E99BDF83810C1F31C0180 +:1011600041F0004158BFC1F30A018DF82C000891ED +:10117000284608A900F0F8FECCE7284600F02AFD32 +:10118000C0E7284600F054FC8346002844D100F014 +:1011900099F9484B1A6890423ED300F093F90446FF +:1011A000FFF79CFA4FF4C872B0FBF2F101FB12009A +:1011B0008DF820B0DFF800B13E4B04F5167480B214 +:1011C0009BF8001004441C6011B901238DF82030F5 +:1011D00050460791FFF79AFA07990DF12100C1F1E6 +:1011E0001004E4B2062C28BF06245144224600F025 +:1011F000D7F808AB039318230293304B01340193C3 +:101200000123E4B2009332463B462846049400F0A2 +:1012100011FC00238BF8003000F054F9284A294CC7 +:101220001368C31AB3F57A7F31D3106000F04CF91C +:1012300002460B46284600F0D7FC284600F0F8FB93 +:1012400028B3237BDFF880B0002B14BF03230223D5 +:101250008BF8053000F036F94FF47A73B0FBF3F0F9 +:101260005146CBF800005846FFF7F2FA18230293D4 +:10127000164B0730019340F25513C0F3CF00CDE970 +:1012800003A0009342464B46284600F0D3FB237B45 +:101290002BB1FFF74BFA237B002B7FF4FAAE13B090 +:1012A000BDE8F08F44210020882200205522002034 +:1012B00000080140402100203D2100203C21002069 +:1012C00050220020702100202C11002054220020E8 +:1012D000401DA12026812A0BF1C6A7C1D068080FA6 +:1012E00070B501F0BFFF0024084E094D308028681A +:1012F0003388834208D901F0B1FF2B6804440133DD +:10130000B4F5C84F2B60F2D370BD00BF842200201B +:101310005822002002F044B800F10060920000F56D +:10132000C84001F0DFBF0000054B1A68054B1B8861 +:101330009B1A834202D9104401F090BF00207047ED +:10134000582200208422002038B50446064D286823 +:10135000204401F089FF28B928682044BDE83840BE +:1013600001F094BF38BD00BF58220020064991F813 +:10137000243033B100230822086A81F82430FFF7B3 +:10138000CBBF0120704700BF5C220020022802BFB3 +:101390004FF48012014B1A61704700BF00080140F2 +:1013A000002310B5934203D0CC5CC4540133F9E759 +:1013B00010BD000003460246D01A12F9011B002995 +:1013C000FAD1704703460244934202D003F8011B4E +:1013D000FAE770472DE9F8431F4D144695F824208D +:1013E0000746884652BBDFF870909CB395F82430CE +:1013F0002BB92022FF2148462F62FFF7E3FF95F823 +:1014000024004146C0F10802A24228BF224605EB53 +:101410008000D6B29200FFF7C3FF95F82430A41BDA +:101420001E44F6B2082E17449044E4B285F82460B6 +:10143000DBD1FFF79BFF0028D7D108E02B6A03EB35 +:1014400082038342CFD0FFF791FF0028CBD1002049 +:10145000BDE8F8830120FBE75C2200200FB40020E8 +:1014600004B07047EFF30983EFF30583044B9A6BE5 +:10147000DA6A9A6A9A6A9A6A9A6A9A6A9B6AFEE72A +:1014800000ED00E0EFF30983EFF30583044B9A6B63 +:101490009A6A9A6A9A6A9A6A9A6A9B6AFEE700BF8F +:1014A00000ED00E0EFF30983EFF30583034B5A6B84 +:1014B0009A6A9A6A9A6A9A6A9B6AFEE700ED00E065 +:1014C000FEE7000001F0A6BF01F07EBF30B5094D78 +:1014D0000A4491420DD011F8013B5840082340F3D3 +:1014E0000004013B2C4013F0FF0384EA5000F6D1C6 +:1014F000EFE730BD2083B8ED4FF0FF33F7B500EBD9 +:1015000081061946DFF848C0DFF848E0B0421BD03A +:1015100050F8042B01AF0192042217F8014B81EA25 +:10152000046108240D46DB184941013C002DBCBF75 +:1015300083EA0C0381EA0E0114F0FF04F2D1013AB0 +:1015400012F0FF02E9D1E1E7D843C94303B0F0BD8F +:101550009336EAA9EBE1F0422DE9F041C56915B9EE +:10156000C161BDE8F0814B68AC4623F06047C3F32E +:101570008A4616EA230638BF3E464FEAD37EC3F3B7 +:1015800080782B465A68BEEBD27F22F060440AD0A6 +:10159000002A18DAA40CB44217D19D420FD10D6075 +:1015A000DEE71346EEE7A74207D102F08044C2F31C +:1015B000807242450BD054B1EFE708D2EDE7CCF88A +:1015C00000100B60CDE7B44201D0B442E5D81A68F0 +:1015D0009C46002AE5D11960C3E700002DE9F047D9 +:1015E0004FF47F49089D01F007044FEAD5082244D3 +:1015F00005F0070500EBD100944201D1BDE8F0876A +:1016000004F0070705F0070A57453E4638BF56461F +:10161000111BC6F108068E4228BF0E46E108415C48 +:1016200008EBD50E13F80EC0B94029FA06F721FAD7 +:101630000AF1FFB28CEA010147FA0AF739408CEA55 +:10164000010C03F80EC034443544D5E7082341F2B9 +:10165000210280EA012001B24000002980B203F19A +:10166000FF33B8BF504013F0FF03F4D170470000C0 +:1016700038B50C468D18A54200D138BD14F8011BB1 +:10168000FFF7E4FFF7E700000346006848B102688F +:1016900019891A60DA88013292B29142DA8038BF31 +:1016A0001A81704770B504460D4688B0202200218B +:1016B0006846FFF787FE20460495FFF7E5FF0246E0 +:1016C00058B16B46054608AE1C4603CCB4422860B0 +:1016D0006960234605F10805F6D1104608B070BDD3 +:1016E000082817D909280CD00A280CD00B280CD0B0 +:1016F0000C280CD00D280CD00E2814BF4020302010 +:1017000070470C2070471020704714207047182035 +:101710007047202070470000082817D90C280CD9E2 +:1017200010280CD914280CD918280CD920280CD929 +:1017300030288CBF0F200E207047092070470A20E8 +:1017400070470B2070470C2070470D207047000039 +:1017500010B54B6823B9CA8A63F30902CA8210BD67 +:10176000C4681A681C60C360438A013B43824A60B4 +:10177000EFE700002DE9F84F1D46CB8A0F46C3F373 +:1017800009010629814692460B4630D00020AAB2B4 +:1017900007F119049EB2052E1FFA80F80FD8904564 +:1017A00003F1010306D3FB8A0A4462F30903012013 +:1017B000FB821AE01AF800600130E654EAE790452F +:1017C000F1D21C23A1F1060BBBFBF3F203FB12BB0E +:1017D0007C681FFA8BF6002C45D14846FFF754FF72 +:1017E000044638B978606FF00200BDE8F88F4FF01A +:1017F0000008E6E70026066078604FF0000BADB207 +:10180000454510D90AEB0803221D13F8011B08F106 +:1018100001089155B1B21B291FFA88F82BD0454514 +:1018200006F10106F1D8FB8AC3F30902154465F3FA +:101830000903BCE71C46013292B22368002BF9D1A0 +:10184000AB1F0B441C21B3FBF1F301339BB29A4253 +:10185000D3D2BBF1000FD0D14846FFF715FF20B916 +:10186000C4F800B0BFE70122E7E7C0F800B05E4669 +:1018700020600446C1E74545D5D94846FFF704FF37 +:1018800008B92060AFE7C0F800B000262060044629 +:10189000B6E700002DE9F04F85B007469146CDE947 +:1018A0000113BDF83C50002A00F08F802DB10E9B33 +:1018B000002B00F08A80072D30D807F10C00FFF7CD +:1018C000E3FE044628B96FF00204204605B0BDE8E7 +:1018D000F08F14220021FFF775FD2A460E9904F1BE +:1018E0000800FFF75DFD681CC0B2FFF715FFFFF7AA +:1018F000F7FE207499F80020431E9BB202F01F02ED +:10190000234462F03F021A72019B384643F00041C3 +:1019100061602146FFF720FE0124D6E74FF0000862 +:101920004FF0800A4646444600F10C0303930398A7 +:10193000FFF7AAFE83460028C5D014220021FFF736 +:1019400041FD002E38D10220029BABF808300E9BDF +:1019500000F10802D2B299195A440130C0B20828E5 +:1019600001D0AE422AD3FFF7D7FEFFF7B9FEAE4251 +:1019700008BF4FF0400A99F80020019B411E02F079 +:101980001F0242EA4812C9B24AEA020A594443F025 +:10199000004281F808A08BF8100059463846CBF871 +:1019A0000420FFF7D9FD0134AE424FF0000A24B203 +:1019B00088F00108BBD188E70020C8E711F801CB07 +:1019C000013602F801CBB6B2C7E76FF001047CE73D +:1019D000F8B5044615460E46282200211F46FFF79B +:1019E000F1FC069BB5F5001F6360079B28BF4FF60F +:1019F000FF7223624FF0000338BF6A09A76004F149 +:101A00000C0097B29A4205D80023036027826382B4 +:101A1000A382F8BD0660013330462036F2E70000AD +:101A200003781BB94BB2002BC8BF01707047000090 +:101A3000007870472DE9F74FDDF83C9080469246DC +:101A40009B46BDF830500D9E9DF83840BDF8407063 +:101A5000B9F1000F01D1002F51D11F2C4FD898F8A8 +:101A60000000B0B9072F47D835F0030347D13A46F5 +:101A700049464FF6FF70FFF7FBFD20F001002D02F5 +:101A8000400445EA0464400C44EA40244FF6FF73E6 +:101A900021E040EA0520072F40EA0464F6D900253A +:101AA0004FF6FF73C5F12000A5F120022AFA05F1D7 +:101AB0000BFA00F001432BFA02F211431846C9B2A7 +:101AC000FFF7C4FD0835402D0346EBD13A464946A1 +:101AD000FFF7CEFD0346324621464046CDE900974A +:101AE000FFF7D8FE33780133DBB21F2B88BF00230A +:101AF000337003B0BDE8F08F6FF00300F9E76FF0CB +:101B00000100F6E72DE9F04F85B0DDF848809246F8 +:101B100006469B460F9D9DF840209DF84490BDF8D9 +:101B20004C70B8F1000F01D1002F48D11F2A46D8C0 +:101B30003378002B46D00C0244EA02649DF838103A +:101B400044EAC93444EA01441C43072F44F08004AA +:101B500032D900234FF6FF72C3F1200CA3F120000D +:101B60002AFA03F10BFA0CFC41EA0C012BFA00F003 +:101B70000143C9B210460393FFF768FD039B024679 +:101B80000833402BE8D13A464146FFF771FD034642 +:101B90002A4621463046CDE90087FFF77BFEB9F1A2 +:101BA000010F06D12B780133DBB21F2B88BF002336 +:101BB0002B7005B0BDE8F08F4FF6FF73E8E76FF0CC +:101BC0000100F6E76FF00300F3E70000C06900B121 +:101BD00004307047C3691A68C261C2681A60C36082 +:101BE000438A013B438270472DE9F041D0F81880C9 +:101BF00014461D4641460027174E09B9BDE8F0813D +:101C0000D1E90223A21A65EB0303964277EB0303A3 +:101C10001ED283698B420DD1FFF79AFD83691B6841 +:101C20008361C3680B60438AC1608169013B884658 +:101C30004382E2E7FFF78CFD0B68C8F80030C36809 +:101C40000B60438AC160013B4382D8F80010D4E79F +:101C500088460968D1E700BF80841E002DE9F04F57 +:101C60008BB00D4614469B468046DDF85090002808 +:101C700000F01A81B9F1000F00F01681531E3F2BBE +:101C800000F21281012A03D1BBF1000F40F00C8158 +:101C90000023CDE90833B8F81430B5EBC30F4FEA91 +:101CA000C30703D300200BB0BDE8F08F2B199F4270 +:101CB000D8F80C3036BF7F1B2746FFB21BB9D8F8C7 +:101CC0001030002B7BD02F2D4ED8C5F13006B742F7 +:101CD0004FF0000334BF3E46F6B200932946324629 +:101CE000D8F8080008ABFFF779FCA7EB060A3544E3 +:101CF0005FFA8AFA3021B8F8143003F10053063B3A +:101D0000DB000493D8F80C300393039B13B1BAF1B2 +:101D1000000F2CD1D8F8100040B1BAF1000F05D057 +:101D20005246009608AB691AFFF758FC38B2002FEC +:101D3000B8D066070AD00AAB03EBD40111F8083C0F +:101D4000624202F00702134101F8083C082C3DD919 +:101D5000102C40F2B680202C40F2B880BBF1000F6E +:101D600000F09D80082335E0BA460026C2E7049BB8 +:101D7000E02B28BFE02306930B44AB42059315D913 +:101D80005A1B924538BF5246039828BFD2B20096DC +:101D9000691A08AB04300792FFF720FC079A164433 +:101DA000AAEB020A1544F6B25FFA8AFA049B069A75 +:101DB00005999B1A0493039B1B680393A5E7009363 +:101DC0003A462946D8F8080008ABADE7BBF1000F4A +:101DD00013D00123B4EBC30F6CD0082C12D89DF89C +:101DE0002030621E23FA02F2D50706D54FF0FF32EB +:101DF00002FA04F423438DF820309DF8203089F84E +:101E0000003050E7102C12D8BDF82030621E23FAA3 +:101E100002F2D10706D54FF0FF3202FA04F4234351 +:101E2000ADF82030BDF82030A9F800303BE7202C79 +:101E30000FD80899631E21FA03F3DA0705D54FF08E +:101E4000FF3202FA04F40C430894089BC9F80030EE +:101E500029E7402C2BD0DDE90865611EC4F1210281 +:101E6000A4F1210326FA01F105FA02F225FA03F39F +:101E700011431943CB0712D50122A4F12003C4F169 +:101E8000200102FA03F322FA01F1A240524243EA8E +:101E9000010363EB430332432B43CDE90823DDE920 +:101EA0000823C9E90023FEE66FF00100FBE66FF0AE +:101EB0000800F8E6082CA0D9102CB3D9202CEED8B5 +:101EC000C3E7BBF1000FADD0022383E7BBF1000FE6 +:101ED000BBD004237EE70000012A30B5144638BF8A +:101EE00001220025402A28BF402285B0012CCDE9DF +:101EF000025517D81B788DF8083053070AD004AB69 +:101F000003EBD20515F8083C544204F00704A34043 +:101F100005F8083C0346009102A80021FFF75EFB8C +:101F200005B030BD082CE5D9102C03D81B88ADF8BE +:101F30000830E2E7202C02D81B680293DDE7D3E9E2 +:101F40000045CDE90245D8E710B5CB681BB98B60D9 +:101F50000B618B8210BDC4681A681C60C360438A21 +:101F6000013B4382CA60F0E72DE9F04FD1F80080D1 +:101F700093B018F0800FCDE90323C8F3C01207BF58 +:101F80004FF0020B1646C8F3C03BC8F30626B8F163 +:101F9000000F04460D4680F2D48118F0C04305932B +:101FA00040F0CF810B7B002B00F0CB81BBF1020F07 +:101FB00003D00178B14240F0C78108F07F0107915A +:101FC0007AB3C8F3074A2B4493F80390760646EA9F +:101FD0000B4608F07F0246EA82465FEAD91346EADA +:101FE0000A06069300F0918000220023CDE90A231F +:101FF00008F07F03009352465B46204667680AA9B3 +:10200000B84700287ED0A7699FB9314604F10C007B +:10201000FFF748FB0746E0B96FF0020013B0BDE8D8 +:10202000F08FC8F30F2A18F07F0F08BF0AF0030AD9 +:10203000C9E73B699E420DD03F68002FF9D1314678 +:1020400004F10C00FFF72EFB07460028E4D0A3693B +:102050003B60A7610026DDE90A234FF6FF70C6F159 +:10206000200E22FA06F103FA0EFEA6F1200C23FA46 +:102070000CFC41EA0E0141EA0C01C9B20836099292 +:102080000893FFF7E3FADDE90832402EE7D1B88282 +:10209000FB7D09F01F06C3F384039B1B98B2002B42 +:1020A000BCBF00F120031BB2D7E9022152EA0100B4 +:1020B000C8F304680FD00398821A049860EB0101FA +:1020C000A74890424FF000028A4104D3069A002AA2 +:1020D0005BD0012B23DDFA7D4FEA890302F0030276 +:1020E00003F07C031343FB7539462046FFF730FBB2 +:1020F000069BA3B9FB7DC3F38402013262F386031E +:10210000FB7504E06FF00B0088E7A76917B96FF063 +:102110000C0083E73B699E42BAD03F68F6E719F0AE +:10212000400F32D0039B1422BB60049B0021FB6054 +:102130000DA8FFF747F9039B20460A93049BADF8CF +:102140003EA00B932B1D0C932B7B8DF840B0013BD5 +:10215000DBB2ADF83C30079B8DF841608DF8433021 +:1021600094F824308DF8428083F001038DF84430D8 +:102170000AA9A3689847FB7DC3F38403013303F0E6 +:102180001F039B02FB82002048E7FB7DC9F340123E +:10219000B2EBD31F40F0DB80C3F38403B34240F0C3 +:1021A000D98006992B7B4FEA9912002934D0D207A7 +:1021B00041D4032B40F2D180039BAE1DBB60049B36 +:1021C0003246FB602B7B3946033BDBB204F10C004B +:1021D000FFF7D0FA00280DDA20463946FFF7B8FAA3 +:1021E000FB7D0320C3F38403013303F01F039B0231 +:1021F000FB8213E7AB883B832A7B033AB88AD2B2CF +:102200003146FFF735FAFB7DB882DA43C2F3C012DC +:1022100062F3C713FB75B6E76AB92E1D013B324660 +:102220003946DBB204F10C00FFF7A4FA0028D3DB37 +:102230002A7B013AE2E7F98A013BC1F3090105294A +:10224000DAB25BD80023281D07F11A0C9A4208D98C +:1022500010F801EB01330CF801E001310629DBB283 +:10226000F4D1934228BF0023039938BF04330A9165 +:10227000049938BFDBB20B9107F11A010C91796810 +:1022800038BF5B190D910E93FB8AADF83EA0C3F3E6 +:1022900009031A44079BADF83C208DF8433094F8AD +:1022A00024308DF840B083F001038DF844300023D2 +:1022B0008DF841608DF842807B602A7BB88A013AB4 +:1022C000291DFFF7D5F93B8BB882834203D1204605 +:1022D000A3680AA9984720460AA9FFF735FEFB7DA7 +:1022E000B88AC3F38403013303F01F039B02FB820C +:1022F0003B8B984214BF112000208FE67B68002B97 +:10230000AFD0062001E063461C30D3F800C0BCF11A +:10231000000FF8D1091A081D05F1040C1844DDF866 +:1023200014E09DF814308E44BEF11B0F99D89A42E8 +:1023300097D91CF8013B00F8013B059B013305933D +:10234000EDE76FF0090069E66FF00A0066E66FF0EE +:102350000D0063E66FF00E0060E66FF00F005DE6C3 +:1023600080841E00F0B53F4D3F4FEB6943F0007392 +:10237000EB61EB693D4B9B6AD3F800623E4046F04F +:102380000106C3F80062D3F800423C4044EA00244E +:1023900044F00104C3F80042002955D0002006464D +:1023A000C3F81C02C3F80402C3F80C02C3F81402F9 +:1023B00003EBC00401300E28C4F84062C4F8446244 +:1023C000F6D100274FF0010C9678148816F0010F13 +:1023D00018BFD3F804E20CFA04F01CBF40EA0E0E5A +:1023E000C3F804E216F0020F18BFD3F80CE203EBB7 +:1023F000C4041CBF40EA0E0EC3F80CE2760748BFC7 +:10240000D3F8146207F1010744BF0643C3F814620E +:102410005668B942C4F84062966802F10C02C4F8EA +:102420004462D3F81C4240EA0400C3F81C02CBD13A +:10243000D3F8002222F00102C3F80022EB6923F056 +:102440000073EB61EB69F0BD0122C3F84012C3F8E1 +:102450004412C3F80412C3F81412C3F80C22C3F8D0 +:102460001C22E5E7001002400000FFFF8822002048 +:10247000184A08B5916A8B688B6013F0010104D08B +:1024800013F00C0F18BF4FF48031D80506D513F4A4 +:10249000406F14BF41F4003141F00201D80306D56A +:1024A00013F4402F14BF41F4802141F00401D3699B +:1024B0000BB108489847202383F311880021064870 +:1024C00000F01EFE002383F31188BDE8084001F0F0 +:1024D00083B800BF882200209022002038B5124C1B +:1024E000A36ADD68AA0712D05A6922F002025A6173 +:1024F000A36913B1012120469847202383F3118853 +:1025000000210A4800F0FCFD002383F31188EB064C +:1025100006D51021A36AD960236A0BB102489847F7 +:10252000BDE8384001F058B88822002098220020E9 +:1025300038B5124CA36A1D69AA0712D05A6922F055 +:1025400010025A61A36913B1022120469847202343 +:1025500083F3118800210A4800F0D2FD002383F3A1 +:102560001188EB0606D51021A36A1961236A0BB105 +:1025700002489847BDE8384001F02EB88822002074 +:102580009822002038B50F4CA36A5D682A075D6069 +:102590000AD5042222701A6822F002021A60636AC5 +:1025A00013B10021204698476B0706D5A36A9969A5 +:1025B000236A13B1034809049847BDE8384001F085 +:1025C0000BB800BF8822002010B50E4C204600F04A +:1025D000FDF90D4B0B211320A36200F0D7F90B215D +:1025E000142000F0D3F90B21152000F0CFF90B21B6 +:1025F000162000F0CBF9BDE8104000220E20114655 +:10260000FFF7B0BE88220020006400400F4B10B5D9 +:102610009842044605D10E4BDA6942F00072DA6145 +:10262000DB690122A36A1A60A36A5A68D20707D538 +:10263000626851681268D9611A60064A5A6110BD11 +:102640000121082000F052FCEEE700BF88220020A4 +:10265000001002405B87010003291AD8DFE801F06F +:10266000020A0F14836A9B6813F0E05F14BF012015 +:1026700000207047836A9868C0F380607047836A5F +:102680009868C0F3C0607047836A9868C0F30070B0 +:10269000704700207047000010B5032927D8DFE8F5 +:1026A00001F002272B2F836A9968C1F30161183169 +:1026B00003EB01131078840648BF5468C0F300117F +:1026C00058BF94884FEA410148BF41EAC40100F075 +:1026D0000F00586048BF41F00401906858BF41EABC +:1026E0004451D26841F001019860DA60196010BD70 +:1026F000836A03F5C073DDE7836A03F5C873D9E71E +:10270000836A03F5D073D5E701290AD002290FD0D7 +:1027100081B9836ADA68920701D1186903E0012060 +:102720007047836AD86810F0030018BF0120704713 +:10273000836AF2E70020704710B539B9836AD96817 +:1027400089071BD11B699C0704D110BD012915D035 +:102750000229FAD1816AD1F8C031D1F8C441D1F847 +:10276000C8011061D1F8CC015061202008610869CE +:10277000800717D1486940F0100012E0816AD1F853 +:10278000B031D1F8B441D1F8B8011061D1F8BC0131 +:1027900050612020C860C868800703D1486940F0B4 +:1027A00002004861C3F34000C3F38001000140EA26 +:1027B0004111107920F030000143117189064BBF9F +:1027C00091681189DB085B0D4CBF63F31C0163F357 +:1027D0000A01137948BF916064F3030313714FEA50 +:1027E00014234FEA144458BF118113705480ACE78E +:1027F000026843680A43026003B11847704700004B +:10280000024AD36843F0C003D360704700380140E8 +:10281000024AD36843F0C003D360704700440040CD +:102820002DE9F041D0F89C600446F7683368DA057A +:102830009DB20DD5202383F311884FF4007104302D +:10284000FFF7D6FF6FF480733360002383F31188A2 +:10285000202383F3118804F1040815F02F033AD1E3 +:1028600083F31188380615D5290613D5202383F361 +:10287000118804F1380000F02FFA00284DDA082101 +:10288000201DFFF7B5FF4FF67F733B40F360002339 +:1028900083F311887A0616D56B0614D5202383F3AB +:1028A0001188D4E913239A420AD1236C43B127F04B +:1028B00040073F041021201D3F0CFFF799FFF760F0 +:1028C000002383F31188D4F8A420D3683BB3BDE878 +:1028D000F041106918472B0713D015F0080F0CBFF3 +:1028E00000218021E80748BF41F02001AA0748BF26 +:1028F00041F040016B07404648BF41F48071FFF74B +:1029000077FFAD06736805D594F8A01020461940EE +:1029100000F082FA3568ADB29FE77060B7E7BDE8B6 +:10292000F081000008B50348FFF77AFFBDE80840D2 +:1029300000F052BEB422002008B50348FFF770FF34 +:10294000BDE8084000F048BE5C23002010B5094CEB +:1029500000212046084A00F03FFA084B0021C4F845 +:102960009C30074C074A204600F036FA064BC4F864 +:102970009C3010BDB422002001280008003801401E +:102980005C230020112800080044004001220901B6 +:1029900000F1604303F56143C9B283F8001300F00E +:1029A0001F039A4043099B0003F1604303F5614311 +:1029B000C3F880211A607047090100F16040C9B274 +:1029C00000F56D4001767047FFF7FEBD01230370EF +:1029D000002300F10802C0E9022200F11002C0E960 +:1029E0000422C0E90633C0E90833436070470000A1 +:1029F00010B52023044683F311880223416003703D +:102A0000FFF704FE04232370002383F3118810BD15 +:102A10002DE9F0411F4604460D461646202383F358 +:102A2000118800F108082378052B0DD0294620468F +:102A3000FFF712FE40B1204632462946FFF72CFE32 +:102A4000002080F3118808E03946404600F03CFB46 +:102A50000028E8D0002383F31188BDE8F08100004E +:102A60002DE9F0411F4604460D461646202383F308 +:102A7000118800F110082378052B0DD02946204637 +:102A8000FFF742FE40B1204632462946FFF754FE8A +:102A9000002080F3118808E03946404600F014FB1E +:102AA0000028E8D0002383F31188BDE8F0810000FE +:102AB000F8B5154682680B46AA428169066938BF97 +:102AC0008568761AB54204460BD218462A46FEF7A8 +:102AD00067FCA3692B44A361A36828465B1BA36022 +:102AE000F8BD0CD918463246FEF75AFCAF1B3A46E1 +:102AF000E1683044FEF754FCE3683B44EBE71846DA +:102B00002A46FEF74DFCE368E5E700002DE9F041B9 +:102B1000154683680446934238BF8568D0E904703F +:102B20003F1ABD420E460BD22A46FEF739FC6369B6 +:102B30002B446361A36828465B1BA360BDE8F0815A +:102B40000CD93A46A5EB0708FEF72AFC4246E06896 +:102B5000F119FEF725FCE3684344EAE72A46FEF74D +:102B60001FFCE368E5E7000010B50024C361029B89 +:102B7000C0E90511C1601144C0E900008460016131 +:102B8000036210BD08B5D0E90532934201D18268D5 +:102B900092B98268013282605A1C42611970D0E990 +:102BA00004329A4228BFC3684FF0000128BF436136 +:102BB00000F09AFA002008BD4FF0FF30FBE700005C +:102BC00070B5202304460D4683F31188A668A6B18C +:102BD000A368A269013BA360531CA3611578226915 +:102BE000934224BFE368A361E3690BB12046984791 +:102BF000002383F31188284607E02946204600F089 +:102C000063FA0028E2DA86F3118870BD2DE9F74FE8 +:102C100004460E4617469846D0F81C904FF0200AFE +:102C20008AF311884FF0000B154665B12A463146EC +:102C30002046FFF73DFF034660B94146204600F0BD +:102C400043FA0028F1D0002383F31188781B03B0E6 +:102C5000BDE8F08FB9F1000F03D001902046C847BE +:102C6000019B8BF31188ED1A1E448AF31188DCE76F +:102C7000C361009BC0E90511C1601144C0E90000B7 +:102C80008260016103627047F8B504460D4616463E +:102C9000202383F31188A768A7B1A368013BA36031 +:102CA00063695A1C62611D70D4E904329A4224BFE0 +:102CB000E3686361E3690BB120469847002080F325 +:102CC000118807E03146204600F0FEF90028E2DADC +:102CD00087F31188F8BD0000D0E905239A4210B5AA +:102CE00001D182687AB982680021013282605A1C5F +:102CF00082611C7803699A4224BFC368836100F033 +:102D0000F3F9204610BD4FF0FF30FBE72DE9F74FF8 +:102D100004460E4617469846D0F81C904FF0200AFD +:102D20008AF311884FF0000B154665B12A463146EB +:102D30002046FFF7EBFE034660B94146204600F00F +:102D4000C3F90028F1D0002383F31188781B03B066 +:102D5000BDE8F08FB9F1000F03D001902046C847BD +:102D6000019B8BF31188ED1A1E448AF31188DCE76E +:102D7000026843680A43026003B1184770470000C5 +:102D80001430FFF743BF00004FF0FF331430FFF75C +:102D90003DBF00003830FFF7B9BF00004FF0FF33F0 +:102DA0003830FFF7B3BF00001430FFF709BF000051 +:102DB0004FF0FF311430FFF703BF00003830FFF74A +:102DC00063BF00004FF0FF323830FFF75DBF0000F7 +:102DD00000207047FFF7BABD37B515460D4A0446C7 +:102DE000026000224260C0E9022201220B46027406 +:102DF00000F15C01009020221430FFF7B5FE2B4655 +:102E00002022009404F17C0104F13800FFF730FF28 +:102E100003B030BD503B000838B5C36904460D46C9 +:102E20001BB904210844FFF7A3FF294604F114004D +:102E3000FFF7A8FE002806DA201D4FF48061BDE8E8 +:102E40003840FFF795BF38BD0022024BC3E900337D +:102E50009A60704704240020002382680374054BA5 +:102E60001B6899689142FBD25A6803604260106007 +:102E7000586070470424002008B5202383F311888C +:102E8000037C032B05D0042B0DD02BB983F31188C1 +:102E900008BD002243691A604FF0FF334361FFF71A +:102EA000DBFF0023F2E7D0E9003213605A60F3E75A +:102EB000002382680374054B1B6899689142FBD814 +:102EC0005A68036042601060586070470424002014 +:102ED000054B196908741868026853601A60186114 +:102EE00001230374FDF732BB0424002030B54B1CD2 +:102EF00004460B4D87B010D02B690A4A01A800F098 +:102F00001BF92046FFF7E4FF049B13B101A800F072 +:102F10002FF92B69586907B030BDFFF7D9FFF8E7E3 +:102F200004240020792E000838B50C4D41612B692E +:102F300081689A680446914203D8BDE83840FFF79B +:102F40008BBF1846FFF7B4FF01232C6101462374A1 +:102F50002046BDE83840FDF7F9BA00BF0424002040 +:102F6000044B1A681B6990689B68984294BF0020C4 +:102F7000012070470424002010B5084C2368206904 +:102F80001A6854602260012223611A74FFF790FFCF +:102F900001462069BDE81040FDF7D8BA042400209E +:102FA00008B5FFF7DDFF18B1BDE80840FFF7E4BF43 +:102FB00008BD0000FFF7E0BFFEE7000010B50C4CB5 +:102FC000FFF742FF00F0AAF880220A49204600F0ED +:102FD00031F8012344F8180C037400F0D9FA0023E7 +:102FE00083F3118862B6BDE81040034800F042B890 +:102FF0002C240020783B0008883B000800F0CAB869 +:10300000EFF3118020B9EFF30583202282F31188BA +:103010007047000010B530B9EFF30584C4F308041D +:1030200014B180F3118810BDFFF7BAFF84F3118843 +:10303000F9E7000082600222028270478368A3F1F0 +:103040003C0243F80C2C026943F83C2C426943F8DB +:10305000382C074A43F81C2CC268A3F1180043F827 +:10306000102C022203F8082C002203F8072C7047CA +:103070005D05000810B5202383F31188FFF7DEFFFC +:1030800000210446FFF750FF002383F311882046F8 +:1030900010BD0000024B1B6958610F20FFF718BFDD +:1030A00004240020202383F31188FFF7F3BF0000DE +:1030B00008B50146202383F311880820FFF716FF87 +:1030C000002383F3118808BD49B1064B42681B6990 +:1030D00018605A60136043600420FFF707BF4FF089 +:1030E000FF3070470424002003460068834205D067 +:1030F00002681A6053604161FFF7AEBE704700007E +:1031000038B504460D462068844200D138BD0368B6 +:1031100023605C604561FFF79FFEF4E7054B03F118 +:103120001402C3E905224FF0FF32DA6100221A626D +:10313000704700BF0424002010B5C0E903230B4AE8 +:10314000136A53699C68A1420CD85C688160036073 +:103150004460206058609868411A99604FF0FF33CE +:10316000D36110BD1B68091BECE700BF04240020DD +:10317000036881689A680A449A60426813605A60DA +:1031800000234FF0FF32C360014BDA61704700BF8C +:103190000424002038B50F4C2246236A01332362F1 +:1031A00052F8143F934206D020259A68013A9A605B +:1031B00063699A6802B138BDD3E9001001604860C4 +:1031C000D968DA6082F311881869884785F3118815 +:1031D000EEE700BF0424002000207047FEE7000057 +:1031E000704700004FF0FF3070470000BFF34F8F73 +:1031F000024AD368DB07FCD4704700BF00200240BE +:1032000008B5074B1B7853B9FFF7F0FF054B1A6958 +:10321000120641BF044A5A6002F188325A6008BD62 +:1032200008250020002002402301674508B5054B12 +:103230001B7833B9FFF7DAFF034A136943F08003C1 +:10324000136108BD08250020002002407F289ABF96 +:1032500000F5003080020020704700004FF48060CD +:1032600070470000802070477F2808B50BD8FFF713 +:10327000EDFF00F580630268013204D1043083421F +:10328000F9D1012008BD0020FCE700007F2838B5F7 +:10329000044623D8FFF7B4FEFFF7A8FFFFF7B0FFFF +:1032A000F3220F4B0546DA60022220461A61FFF72F +:1032B000CDFF58611A694FF4806142F040021A61F3 +:1032C000FFF794FF00F010F92846FFF7AFFFFFF774 +:1032D000A1FE2046BDE83840FFF7C6BF002038BD3C +:1032E000002002402DE9F047044612F001000E468E +:1032F000154606D040F2BD22234B1A600020BDE8DF +:10330000F087224BA2189A4204D940F2C2221E4BE7 +:103310001A60F4E7FFF774FE4FF0010AFFF770FF41 +:10332000FFF764FFDFF868903146A61B012D884641 +:1033300006EB010705D8FFF779FFFFF76BFE0120C9 +:10334000DDE7B8F80030C9F810A03B800024FFF793 +:103350004DFFC9F810403B8831F8022B9BB29A42CE +:103360000FD040F2D922084B1A600A4B1F600A4B5B +:103370001D600A4BC3F80080FFF758FFFFF74AFEB5 +:10338000BCE7023DD2E700BF042500200000020890 +:1033900000200240F824002000250020FC2400200A +:1033A000084908B50B7828B11BB9FFF729FF01239D +:1033B0000B7008BD002BFCD0BDE808400870FFF77B +:1033C00035BF00BF0825002070B5FFF719FE4FF488 +:1033D0007A710D4B0D4E1B6A326801FB03F3934269 +:1033E00037BF0B4A0A495168156836BF4C1CD1E9F2 +:1033F000005454605D1944F100043360FFF70AFE85 +:103400002846214670BD00BF042400200C25002062 +:103410001025002070B5FFF7F3FD4FF47A710F4BC4 +:103420000F4E1B6A326801FB03F3934237BF0D4A0C +:103430000C49516815683ABF4C1C5460D1E90054DE +:103440005D1944F100043360FFF7E4FD4FF47A7234 +:10345000002328462146FCF783FE70BD042400208B +:103460000C2500201025002010B5094C013AD2B2DD +:10347000FF2A00D110BD500854F82030013054F814 +:1034800020009BB243EA004341F8043BEEE700BF53 +:10349000046C004010B50748013AD2B2FF2A00D1AF +:1034A00010BD0C88530840F823404C88013340F885 +:1034B0002340F1E7046C004007B50122002001A978 +:1034C000FFF7D2FF019803B05DF804FB13B5044683 +:1034D000FFF7F2FFA04205D00122002001A90194CC +:1034E000FFF7D8FF02B010BD7047000045F25552FB +:1034F000064B1A6002225A6040F6FF729A604CF640 +:10350000CC421A600122024B1A7070470030004012 +:103510001C250020034B1B781BB14AF6AA22024B44 +:103520001A6070471C25002000300040044B1A68C8 +:103530002AB902F1804202F50432526A1A607047D9 +:10354000182500204FF08072014B5A62704700BF6F +:103550000010024008B5FFF7E9FF024B1868C0F3FE +:10356000407008BD1825002008B5FFF7DFFF024BAB +:103570001868C0F3007008BD18250020EFF3098318 +:10358000203383F30988002383F3118870470000F8 +:10359000202080F3118862B60C4B0D4AD96821F4C3 +:1035A000E0610904090C0A43DA60D3F8FC200949F8 +:1035B00042F08072C3F8FC200A6842F001020A60FF +:1035C0001022DA7783F82200704700BF00ED00E098 +:1035D0000003FA05001000E0202310B583F31188E2 +:1035E0000B4B5B6813F400630FD0EFF309844FF0CB +:1035F0008073203CE36184F30988FFF7B1FC10B1CC +:10360000044BA36110BD044BFBE783F31188F9E77A +:1036100000ED00E06F05000872050008704700002B +:10362000FEE700000A4B0B480B4A90420BD30B4BB2 +:10363000C11EDA1C121A22F003028B4238BF00228C +:103640000021FDF7BFBE53F8041B40F8041BECE754 +:103650000C3C0008A0250020A0250020A02500206B +:103660007047000000F030B808B500F063F9FFF7CC +:10367000A5FCBDE80840FFF759BF000070470000F7 +:103680004FF0FF310E4B1A6919611A6900221A6155 +:103690001869D868D960D968DA60DA68DA6942F0FE +:1036A0008052DA61DA69DA6942F00062DA61054A69 +:1036B000DB69136843F48073136000F01BB900BF2B +:1036C0000010024000700040194B1A6842F00102DD +:1036D0001A601A689007FCD51A6802F0F9021A609D +:1036E00000225A605A6812F00C0FFBD11A6842F49B +:1036F00080321A601A689103FCD55A6842F4E812C5 +:103700005A601A6842F080721A601A689201FCD5F9 +:103710001221084A5A60084A11605A6842F00202AF +:103720005A605A6802F00C02082AFAD1704700BFAA +:103730000010024000641D0000200240084A08B545 +:10374000516913680B4003F00103536123B1054A2B +:1037500013680BB150689847BDE80840FFF73CBFBD +:103760000004014020250020084A08B5516913686B +:103770000B4003F00203536123B1054A93680BB178 +:10378000D0689847BDE80840FFF726BF0004014015 +:1037900020250020084A08B5516913680B4003F042 +:1037A0000403536123B1054A13690BB1506998476B +:1037B000BDE80840FFF710BF0004014020250020AD +:1037C000084A08B5516913680B4003F008035361B8 +:1037D00023B1054A93690BB1D0699847BDE8084009 +:1037E000FFF7FABE0004014020250020084A08B572 +:1037F000516913680B4003F01003536123B1054A6C +:10380000136A0BB1506A9847BDE80840FFF7E4BE61 +:103810000004014020250020174B10B55A691C6890 +:10382000144004F478725A61A30604D5134A936ACB +:103830000BB1D06A9847600604D5104A136B0BB1E0 +:10384000506B9847210604D50C4A936B0BB1D06B93 +:103850009847E20504D5094A136C0BB1506C9847A0 +:10386000A30504D5054A936C0BB1D06C9847BDE80D +:103870001040FFF7B1BE00BF00040140202500202A +:103880001A4B10B55A691C68144004F47C425A6102 +:10389000620504D5164A136D0BB1506D9847230588 +:1038A00004D5134A936D0BB1D06D9847E00404D54D +:1038B0000F4A136E0BB1506E9847A10404D50C4A01 +:1038C000936E0BB1D06E9847620404D5084A136F0B +:1038D0000BB1506F9847230404D5054A936F0BB181 +:1038E000D06F9847BDE81040FFF776BE0004014056 +:1038F00020250020062108B50846FFF747F80621D5 +:103900000720FFF743F806210820FFF73FF80621BC +:103910000920FFF73BF806210A20FFF737F80621B8 +:103920001720FFF733F8BDE8084006212820FFF7ED +:103930002DB8000008B5FFF7A3FE064800F00EF80A +:10394000FFF742F8FFF746FAFFF798FEBDE8084098 +:1039500000F002B8A03B000800F042B8002319466E +:103960001C4A0133102BC2E9001102F10802F8D100 +:10397000194B9A6942F07D029A619B690268174B64 +:10398000DA6082685A6042681A60C26803F5806330 +:10399000DA6042695A6002691A608269C3F80C24CD +:1039A000026AC3F80424C269C3F80024426AC3F857 +:1039B0000C28C26AC3F80428826AC3F80028026B84 +:1039C000C3F80C2C826BC3F8042C426BC3F8002C98 +:1039D000704700BF20250020001002400008014071 +:1039E0004FF0E023044A08215A6100229A6107221D +:1039F0000B201A61FEF7E0BF3F19010008B5202334 +:103A000083F31188FFF7FAFA002383F3118808BDC6 +:103A100008B5FFF7F3FFBDE80840FFF7DDBD000084 +:103A200010B501390244904201D1002005E003782D +:103A300011F8014FA34201D0181B10BD0130F2E76D +:103A40002DE9F0419BB10446C91A1778014403F1EE +:103A5000FF3C8C42204601D9002008E00578013463 +:103A6000BD42F6D10CEB0405D618A54201D1BDE844 +:103A7000F08115F8018D16F801EDF045F5D0E8E775 +:103A8000034611F8012B03F8012B002AF9D17047E6 +:103A90006F72672E6172647570696C6F742E6170DD +:103AA0005F7065726970685F72616E676566696E86 +:103AB000646572004E6F20617070207369670A0040 +:103AC000426164206677206C656E67746820257596 +:103AD0000A0042616420626F6172645F696420253C +:103AE000752073686F756C642062652025750A0007 +:103AF0004261642066772064657363726970746FD5 +:103B000072206C656E6774682025750A00426164D6 +:103B10002061707020435243203078253038783A45 +:103B2000307825303878203078253038783A307839 +:103B3000253038780A00476F6F64206669726D77A8 +:103B40006172650A0040A2E4F16468910600000019 +:103B5000000000009D2D0008892D0008C52D0008DB +:103B6000B12D0008BD2D0008A92D0008952D0008D5 +:103B7000812D0008D12D00086D61696E00000000E4 +:103B800069646C6500000000803B00084824002048 +:103B9000F824002001000000B92F000800000000F8 +:103BA0000C1E0000447B4144B4574944010000000E +:103BB00042444444444444440000000044444444D7 +:103BC00044444444000000004444444444444444C5 +:103BD000000000004444444444444444B4C5FF7FCE +:103BE0000100000000000000E803000000000000E9 +:103BF000009C0100000000006400000000000000C4 +:0C3C000040420F00FE2A0100D204000028 :00000001FF diff --git a/Tools/bootloaders/f303-GPS_bl.bin b/Tools/bootloaders/f303-GPS_bl.bin index 216069d95e5..af275afb736 100755 Binary files a/Tools/bootloaders/f303-GPS_bl.bin and b/Tools/bootloaders/f303-GPS_bl.bin differ diff --git a/Tools/bootloaders/f303-GPS_bl.hex b/Tools/bootloaders/f303-GPS_bl.hex index 57fbe3d66b6..ff576ceeaa1 100644 --- a/Tools/bootloaders/f303-GPS_bl.hex +++ b/Tools/bootloaders/f303-GPS_bl.hex @@ -1,1095 +1,980 @@ :020000040800F2 -:1000000000090020E1040008991400089D1400086C -:10001000F11400089D140008C5140008E30400084A -:10002000E3040008E3040008E30400085D37000867 -:10003000E3040008E3040008E3040008013C0008AE -:10004000E3040008E3040008E3040008E3040008F4 -:10005000E3040008E3040008E5390008113A000849 -:100060003D3A0008693A0008953A0008E3040008A0 -:10007000E3040008E3040008E3040008E3040008C4 -:10008000E3040008E3040008E3040008092600086C -:1000900075260008C92600081D270008C13A000877 -:1000A000E3040008E3040008E3040008E304000894 -:1000B000E3040008E3040008E3040008E304000884 -:1000C000E3040008E3040008E3040008E304000874 -:1000D000E3040008D92A0008ED2A0008E304000818 -:1000E000293B0008E3040008E3040008E3040008D7 -:1000F000E3040008E3040008E3040008E304000844 -:10010000E3040008E3040008E3040008E304000833 -:10011000E3040008E3040008E3040008E304000823 -:10012000E3040008E3040008E3040008E304000813 -:10013000E3040008E3040008E3040008E304000803 -:10014000E3040008E3040008E3040008E3040008F3 -:10015000E3040008E3040008E3040008E3040008E3 -:10016000E3040008E3040008E3040008E3040008D3 -:10017000E3040008E3040008E3040008E3040008C3 -:10018000E3040008E3040008E3040008E3040008B3 -:10019000E3040008E3040008E3040008E3040008A3 -:1001A000D0400B1CD1409C46203AD34018435242C9 -:1001B00063469340184370479140031C90409C460F -:1001C000203A9340194352426346D3401943704743 -:1001D00053B94AB9002908BF00281CBF4FF0FF31AE -:1001E0004FF0FF3000F07AB9ADF1080C6DE904CEA4 -:1001F00000F006F8DDF804E0DDE9022304B0704702 -:100200002DE9F0478C460D460446089E002B51D13F -:100210008A4217466DD9B2FA82FEBEF1000F0BD0AA -:10022000CEF1200C01FA0EF520FA0CFC02FA0EF7C2 -:100230004CEA050C00FA0EF44FEA174A250CBCFBF9 -:10024000FAF81FFA87F90AFB18CC45EA0C4508FBB7 -:1002500009F3AB420AD9ED1908F1FF3280F023818E -:10026000AB4240F22081A8F102083D44ED1AA4B24D -:10027000B5FBFAF00AFB105544EA054400FB09F906 -:10028000A14509D9E41900F1FF3380F00A81A145A5 -:1002900040F2078102383C44A4EB090440EA0840DC -:1002A0000021002E61D024FA0EF400233460736024 -:1002B000BDE8F0878B4207D9002E54D0002186E894 -:1002C00021000846BDE8F087B3FA83F1002940F029 -:1002D0008E80AB4202D3824200F2FA80841A65EB30 -:1002E00003050120AC46002E3FD086E81010BDE883 -:1002F000F08712B90127B7FBF2F7B7FA87FEBEF114 -:10030000000F34D1EB1B3A0C1FFA87FC0121B3FB21 -:10031000F2F8250C02FB183345EA03450CFB08F301 -:10032000AB4207D9ED1908F1FF3002D2AB4200F21F -:10033000D1808046ED1AA3B2B5FBF2F002FB105556 -:1003400043EA05440CFB00FCA44507D9E41900F17D -:10035000FF3302D2A44500F2B8801846A4EB0C0487 -:1003600040EA08409DE731463046BDE8F087CEF1CF -:10037000200405FA0EF307FA0EF720FA04F83A0CF7 -:1003800025FA04F448EA0308B4FBF2F14FEA1845F1 -:1003900002FB11441FFA87FC45EA044501FB0CF3FC -:1003A000AB4200FA0EF409D9ED1901F1FF3080F0EB -:1003B0008A80AB4240F2878002393D44EB1A1FFA33 -:1003C00088F5B3FBF2F002FB103345EA034500FB6E -:1003D0000CF3AB4207D9ED1900F1FF386FD2AB42F5 -:1003E0006DD902383D44EB1A40EA01418FE7C1F173 -:1003F000200722FA07F88B4005FA01F448EA0303C4 -:1004000020FA07FE4FEA134CFD404EEA040EB5FBFE -:10041000FCF94FEA1E440CFB19551FFA83F844EA15 -:10042000054509FB08F4AC4202FA01F200FA01FAB0 -:1004300008D9ED1809F1FF3043D2AC4241D9A9F1F6 -:1004400002091D442D1B1FFA8EFEB5FBFCF00CFBB0 -:1004500010554EEA054400FB08F8A04507D9E418FA -:1004600000F1FF3529D2A04527D902381C4440EAC3 -:100470000940A4EB0804A0FB02894C45C6464D4642 -:1004800015D312D056B1BAEB0E0364EB050404FA8F -:1004900007F7CB401F43CC40376074600021BDE8B4 -:1004A000F0871846F8E69046E0E6C245EAD2B8EB97 -:1004B000020E69EB03050138E4E72846D7E740461A -:1004C00091E78146BEE7014678E702383C4445E7BC -:1004D000084608E7A8F102083D442BE7704700BF33 -:1004E00002E000F000F8FEE772B6394880F30888B1 -:1004F000384880F3098838484EF60851CEF200019A -:10050000086040F20000CCF200004EF63471CEF2EA -:1005100000010860BFF34F8FBFF36F8F40F2000000 -:10052000C0F2F0004EF68851CEF200010860BFF331 -:100530004F8FBFF36F8F4FF00000E1EE100A4EF6C1 -:100540003C71CEF200010860062080F31488BFF3EE -:100550006F8F03F041F903F06DF94FF055301F49EB -:100560001B4A91423CBF41F8040BFAE71C49194A67 -:1005700091423CBF41F8040BFAE71A491A4A1B4B57 -:100580009A423EBF51F8040B42F8040BF8E70020F2 -:100590001749184A91423CBF41F8040BFAE703F0AF -:1005A0001FF903F089F9144C144DAC4203DA54F8E6 -:1005B000041B8847F9E700F03FF8114C114DAC429D -:1005C00003DA54F8041B8847F9E703F007B9000081 -:1005D0000009002000110020000000080001002098 -:1005E00000090020D04300080011002074110020F1 -:1005F0007811002090260020A0010008A00100082A -:10060000A0010008A00100082DE9F04F2DED108A8F -:10061000C1F80CD0C3689D46BDEC108ABDE8F08FD0 -:10062000002383F311882846A047002002F070FEC3 -:1006300002F09AFD00DFFEE7384B6FF013022DE960 -:10064000F0416FF0670100241A7003225A709C7009 -:10065000DC701C715C719C71DC711C7259729A7235 -:10066000DC7203F025F8074603F072F80546C8BBB4 -:100670002B4B9F4238D001339F4238D0294B27F073 -:10068000FF029A4237D1F8B200F052FAA84642F27D -:10069000107400F07BFC00F051FA064678B384BB7E -:1006A000464635B1204B9F4203D003F049F8002461 -:1006B0002646002003F006F81C4B1B6913F040038C -:1006C00022D00EB100F034F800F082FC00F016FEEB -:1006D00000F022FF0546CCB900F0D0FC012002F06A -:1006E0001DFEF8E78046D4E780460446D1E704467D -:1006F0004FF00108CDE780464FF47A74C9E704460D -:10070000CFE74FF47A74CCE71C46DDE700F004FF36 -:10071000401BA042E0D900F00BF8D9E77811002087 -:10072000010007B0000008B0263A09B000040048F4 -:1007300010B51C4B1C4953F8042F013200D110BDD9 -:100740008B42F8D1194C1A4B22689A4228D9194B7E -:100750009B6803F1006303F5D0439A4220D202F074 -:10076000C3FF02F0D5FF002000F0E2FD124B022093 -:10077000187000F019FE114BDA690022DA61D969AC -:1007800099699A619B6972B60D4A0E4B13601B689A -:100790002268202181F311889D4683F30888104741 -:1007A00010BD00BFFC6700081C6800080468000852 -:1007B000FF6700087811002084110020001002401B -:1007C00008ED00E00068000809490B6849F269007B -:1007D0009AB21B0C00FB0233064A0B60136844F20A -:1007E000506198B21B0C01FB0030106080B2704762 -:1007F0000C1100200811002010B500211022044621 -:1008000000F0ECFD034B03CB206061601868A06032 -:1008100010BD00BFACF7FF1FF0B51F4CBBB000F020 -:100820007BFEA368C31AF92B30D906AD2346A0601E -:1008300028220021284601F0FDFB04F10E0000F003 -:10084000C5FD0023C6B2591D5F1CDBB2B3424FEA9F -:10085000C10107DA0E3323440822284601F0EAFBDF -:100860003B46F0E7012303930823207B02930B4BC5 -:100870000193C1F3CF013023059100930146049504 -:1008800003A3D3E90023064801F0A4F93BB0F0BD6F -:1008900078F6339F93CACD8DC8210020D521002042 -:1008A000A021002070B50D4614461E4601F038F90F -:1008B00050B9022E0ED1012C0CD112A3D3E9002382 -:1008C000C5E90023012070BD052C14D003D8012CEC -:1008D00009D0002070BD282C09D0302CF9D10BA3F1 -:1008E000D3E90023ECE70BA3D3E90023E8E70BA34C -:1008F000D3E90023E4E70BA3D3E90023E0E700BF3B -:10090000AFF30080401DA12026812A0B78F6339F8B -:1009100093CACD8D9E6AC421818A46EE26417272A9 -:10092000DF25D7B7F017304A39059E5638B504464B -:100930000D46034620222846002101F07BFB227948 -:100940002346032A28BF032203F8042F2846022245 -:10095000202101F06FFB62792346072A28BF072276 -:1009600003F8052F28460322222101F063FBA27918 -:100970002346072A28BF072203F8062F284603220A -:10098000252101F057FB284604F1080310222821F5 -:1009900001F050FB382038BD2DE9F04FADF5017D59 -:1009A00021AE0EAD40F2791280460F46304600214E -:1009B00000F014FD48220021284600F00FFD00F051 -:1009C000ABFD594B4FF47A72B0FBF2F0186093E82C -:1009D0000700012385E807002B740DF15A0000235E -:1009E0006B74FFF709FF032385F82030EC2385F8AB -:1009F000213007AB18464D4903F06CF91B222864DF -:100A00003146284685F83C20FFF790FF12AB04469C -:100A100001460822304601F00DFB0822A1180DF115 -:100A20004903304601F006FB0DF14A03082204F1A8 -:100A30001001304601F0FEFA13AB202204F1180138 -:100A4000304601F0F7FA14AB402204F13801304689 -:100A500001F0F0FA16AB082204F17801304601F0FB -:100A6000E9FA0DF15903082204F18001304601F042 -:100A7000E1FA04F1880A0DF15A0904F5847B4B462A -:100A80005146082230460AF1080A01F0D3FAD3454C -:100A900009F10109F3D11BAB08225946304601F098 -:100AA000C9FA04F588744FF0000995F834304B45C5 -:100AB00010D84FF0000995F83C304B4515D92B6CF8 -:100AC00021464B440822304601F0B4FA083409F1BB -:100AD0000109F0E7AB6B21464B440822304601F098 -:100AE000A9FA083409F10109DFE7E31DC3F3CF03D5 -:100AF000F97E0593002304960393BB7E0293193776 -:100B000001230093019706A3D3E90023404601F097 -:100B100061F80DF5017DBDE8F08F00BFAFF30080F7 -:100B20009E6AC421818A46EE88110020AC3E0008EE -:100B3000014B1870704700BF94110020F0B5334B83 -:100B40001C7B85B034B1324B0E221A810024204622 -:100B500005B0F0BD2F4A1068516802AB03C30823EB -:100B60000DEB03022C492D4803F096F8054630B9E9 -:100B7000274B2B480A221A8100F084FCE6E7016922 -:100B8000B1F5663F06D9224B26480B221A8100F0A8 -:100B900079FCDCE7438BB3F57B7F09D01C4A224804 -:100BA0000C2111814FF47B72194600F06BFCCEE7EB -:100BB0001E4A024402F11003994204D2144B1C480D -:100BC00010221A81E3E710398E1A2046134900F0EB -:100BD000A7FC3246074605F11801204600F0A0FCAC -:100BE000AB689F4202D1EB6898420AD0084B0D22B5 -:100BF0001A8100903B46EA68A9680E4800F042FC62 -:100C0000A4E70D4800F03EFC0124A0E7C821002025 -:100C1000881100207C3D0008DC9703000068000874 -:100C2000843D0008903D0008A23D00080898FFF7A9 -:100C3000C03D0008DD3D0008063E00082DE9F04FEC -:100C4000ADB006AF80460C4600F06AFF05460028AE -:100C50006AD1237E022B18D1E38A012B15D100F033 -:100C60005BFC8146FFF7B0FD4FF4C873BD4EB0FB8F -:100C7000F3F209F5167902FB1300E37E19FA80F00E -:100C800030608BB9B84B00221A709C37BD46BDE866 -:100C9000F08F3B1D1D440095002308224FEAC90137 -:100CA000204601F02BF84D46A38A013BAB425FFA88 -:100CB00085F90BD905F10109B9F1110FE9D1AB4B58 -:100CC000AB4A40F23911AB4802F0B8FF07F114000B -:100CD000FFF792FD2A4607F11401381D02F0CCFF00 -:100CE00003460028CED1B9F1100F07D09E4B83F8F0 -:100CF00000903368A3F516733360C6E707F19802D6 -:100D0000014602F8950D20460092072200F0F6FFFA -:100D1000F9787F2904DD984B954A4FF4A871D2E702 -:100D2000404600F0E1FEB0E7E38A052B00F00681C3 -:100D300006D8012BA9D121464046FFF72DFEA4E796 -:100D4000282B3DD0302BA0D1637E8C4D01336A7BA4 -:100D5000DBB29342E94640F0EF80E27E2B7B9A4281 -:100D600040F0EA8007F19803002623F8846D1022F2 -:100D7000009331460123204600F0C0FFB4F81480F0 -:100D8000A8F102081FFA88F808F1030323F003030F -:100D90000A3323F00703ADEB030D0DF1180A3346B8 -:100DA0009BB2B11C98454FEAC10106F101066CDD0A -:100DB0005344009308220023204600F09FFFEEE7F3 -:100DC000A38A013B9BB2C92B3FF65FAF6B4E357BCD -:100DD0004DBB06F10C03009308222B462946204602 -:100DE00000F08CFFA38A05F10109013BEDB29D42A1 -:100DF0004FEAC90109DA0E3535440095002308226F -:100E0000204600F07BFF4D46ECE700230022C6E9B8 -:100E100000230023B36086F8D730C6F8D830337B80 -:100E20000BB9E37E3373002507F114063B1D08223E -:100E3000294630467D60BD60FD6001F0FBF83B7ADD -:100E400005F10109AB424FEAC90107D9FB68082245 -:100E50002B44304601F0EEF84D46F0E7C1F3CF01E8 -:100E60000023E07E059104960393A37E0293193438 -:100E7000282301460093019438A3D3E90023404678 -:100E800000F0A8FEFFF7C8FCFFE695F8D70000F0D9 -:100E900059FAD5F8D83006461BB995F8D70000F0B6 -:100EA00061FAD5F8D83043449E4204D295F8D70071 -:100EB000013000F057FA4FEA980B0024A0B25845D1 -:100EC00004F1010408DA2B6880000AEB000101221A -:100ED000184400F08BFAF1E7D5E90023D5F8D840A3 -:100EE00095F8D70012EB080243F100034444C5E92A -:100EF0000023C5F8D84000F025FA844209D395F8BC -:100F0000D730013385F8D730D5F8D8309E1BC5F8D7 -:100F1000D860B8F1FF0F08DC00232B7300F034FA1F -:100F2000FFF70CFE08B1FFF703FC2B68144A9B0A7D -:100F3000013313810023AB60CD46A6E6BFF34F8F8C -:100F40001049114BCA6802F4E0621343CB60BFF34F -:100F50004F8F00BFFDE700BFAFF3008026417272E4 -:100F6000DF25D7B79C21002099210020183E0008DA -:100F7000C83E0008713E0008933E0008C8210020CA -:100F80008811002000ED00E00400FA0508B54FF0DC -:100F900000530B4A196891420AD10A4A597D1170CF -:100FA00009481B7D0373C92208490E3000F004FA7A -:100FB000E02200214FF00050BDE8084000F00EBADA -:100FC0009AAD44C594110020C821002016000020CD -:100FD00030B5204C2049214885B002236371042399 -:100FE0000025ADF808300123ADF80C5007228DF82C -:100FF0000C308DF80B301A4B4B608DF80A2001F045 -:1010000003FE184B019500931749184B18484FF4ED -:10101000805200F033FD174B1978254611B1144862 -:1010200000F062FD00F078FA0446FFF7CDFB4FF4C4 -:10103000C87304F51674B0FBF3F202FB13000E4BF9 -:1010400014FA80F0186002F083FB08B10F232B81A3 -:1010500005B030BD8811002000110020E0220020E2 -:1010600003000600A5080008981100203D0C0008A8 -:10107000A0210020941100209C2100202DE9F04F98 -:1010800094A7D7E900670FF25429D9E900898D4C5C -:1010900093B0DFF850B2DFF850A2204600F0E6FD32 -:1010A0000CAD079098B310220021284600F096F965 -:1010B000079B197B4FF0000261F3030219468DF87C -:1010C000302051F8040F49680EAA03C21B680D9A1C -:1010D00063F31C029DF830300D9243F020038DF82D -:1010E000303000232A461946584601F09DFD0790EE -:1010F00030B9204600F0BEFD079B8AF80030CCE7EF -:101100009AF80030072B3EDC01338AF800301822B1 -:101110000021284600F062F9DFF8C8A10023194633 -:101120002A46504601F0A8FD014680BB102208A8BF -:1011300000F054F94FF09042536983F0100353616B -:1011400000F0ECF90B4612A9024611E903000DF17B -:10115000240E8EE803009DF83410C1F303008906C5 -:101160004CBF0E99BDF838108DF82C0046BFC1F366 -:101170001C0141F00041C1F30A010891204608A971 -:1011800000F0BEFFCAE7204600F074FDBFE720462E -:1011900000F0C6FC824600284AD1DFF850B100F0CA -:1011A000BBF9DBF80030984242D300F0B5F9079064 -:1011B000FFF70AFB079A8DF820A04FF4C87302F5D9 -:1011C0001672B0FBF3F101FB130012FA80F0CBF8BA -:1011D0000000DFF81CB19BF8001011B901238DF855 -:1011E000203028460791FFF707FB0799C1F1100A45 -:1011F0005FFA8AFABAF1060F28BF4FF0060A524684 -:1012000029440DF1210000F0D7F80AF101030493FD -:1012100008AB0393182302932B4B019301230093F4 -:1012200032463B46204600F07DFC00238BF8003020 -:1012300000F072F9254ADFF8BCA01368C31AB3F5B1 -:101240007A7F32D3106000F069F902460B462046DF -:1012500000F016FD204600F063FC30B39AF80C3025 -:10126000DFF894B0002B14BF032302238BF8053062 -:1012700000F052F94FF47A732946B0FBF3F0CBF843 -:1012800000005846FFF752FB182307300293104B1B -:101290000193C0F3CF0040F25513049000930395DF -:1012A00042464B46204600F03DFC9AF80C300BB10C -:1012B000FFF7B2FA9AF80C30002B7FF4EAAE13B0C5 -:1012C000BDE8F08FA021002098210020A822002056 -:1012D000AC220020401DA12026812A0BF1C6A7C107 -:1012E000D068080FE0220020AD2200209C210020C1 -:1012F00099210020C82100208811002070B502F03B -:10130000C3F8094C094E20700025306823788342C9 -:1013100008D902F0B5F8336805440133B5F5D04F6C -:101320003360F2D370BD00BFDC220020B022002069 -:1013300002F042B900F10060920000F5D04002F0E6 -:10134000E7B80000054B1A68054B1B789B1A8342CF -:1013500002D9104402F094B800207047B022002057 -:10136000DC22002038B5074D04462868204402F0EE -:101370008DF828B928682044BDE8384002F098B8B4 -:1013800038BD00BFB0220020064991F8243033B1A7 -:1013900000230822086A81F82430FFF7CBBF012020 -:1013A000704700BFB4220020022802BF4FF09043D4 -:1013B0004FF480129A61704710B50023934203D016 -:1013C000CC5CC4540133F9E710BD0000024603466B -:1013D000981A13F9011B0029FAD1704702440346F9 -:1013E000934202D003F8011BFAE770472DE9F0475A -:1013F000234C94F8243005468846174683BB2E4676 -:10140000DFF87C90C7B394F824302BB92022FF2159 -:1014100048462662FFF7E2FF94F82400C0F1080571 -:10142000BD4228BF3D465FFA85FAAD0041462A46D7 -:1014300004EB8000FFF7C0FF94F82430A7EB0A0705 -:101440009A445FFA8AFABAF1080F2E44A844FFB210 -:1014500084F824A0D6D1FFF797FF0028D2D108E066 -:10146000266A06EB8306B042CAD0FFF78DFF00283C -:10147000C5D10020BDE8F0870120BDE8F08700BF9E -:10148000B42200200FB4002004B070470FB44FF016 -:10149000FF3004B070470000FEE7000000B59BB0CD -:1014A000EFF3098168226846FFF786FFEFF30583B3 -:1014B000034B9A6B9A6A9A6A9A6A9A6A9B6AFEE7DF -:1014C00000ED00E000B59BB0EFF3098168226846AB -:1014D000FFF772FFEFF30583044B9A6B9A6A9A6ADF -:1014E0009A6A9A6A9A6A9B6AFEE700BF00ED00E07A -:1014F00000B59BB0EFF3098168226846FFF75CFFF7 -:10150000EFF30583034B5A6B9A6A9A6A9A6A9A6A4E -:101510009B6AFEE700ED00E002F086B802F060B8DA -:1015200030B5084D0A4491420BD011F8013B092413 -:101530005840013CF7D040F300032B4083EA5000B1 -:10154000F7E730BD2083B8ED0246006848B1036874 -:101550001360D388118901339BB29942D38038BF7D -:101560001381704770B588B00D46044620220021D3 -:101570006846FFF733FF20460495FFF7E5FF054671 -:1015800058B16B46044608AE1A4603CAB242206000 -:101590006160134604F10804F6D1284608B070BD16 -:1015A0002DE9F04130B9274B274A40F2C531274891 -:1015B00002F044FB0B7C23B9254B234A40F2C63191 -:1015C000F5E7C66986B9C161BDE8F081002B29DA6B -:1015D000930CAB4229D1B44201D10C60F3E7C8F8B7 -:1015E00000100C60BDE8F0814B6823F06047BD0C33 -:1015F0004FEAD37EC3F3807C15EA230538BF3D460E -:10160000B04634466368BEEBD37F23F06042DDD141 -:10161000974203D1C3F380739C450AD1974205E0FA -:101620001C46EFE7AA4206D013469D422CBF00237A -:101630000123002BCFD12368A046002BF0D12160DD -:10164000BDE8F0819C410008903F0008544200082A -:101650007542000808B5034A034B044840F25E3166 -:1016600002F0ECFA6C3F00081442000854420008F3 -:1016700008B503680B60C388016033B9044B054AA1 -:1016800005484FF4C76102F0D9FA013BC38008BD99 -:10169000E4410008E03F00085442000870B50C46E1 -:1016A00000F10C05616831B9E38A61F30903E38253 -:1016B0000020002170BD0E682846FFF7D9FF666044 -:1016C000F0E7000008B5426832B10B4B0B4A0C48FA -:1016D00040F22F4102F0B2FAC37DC3F3840101311D -:1016E00061F38603C375C38A62F30903C3821B0ACD -:1016F00062F3C713C37508BD304200089C3F000861 -:10170000544200082DE9F047089E32B91F4B204A89 -:10171000204840F2395102F091FA01F007054FEAF2 -:10172000D6082A4406F0070600EBD1004FF47F49A3 -:10173000954201D1BDE8F08705F0070E06F0070AD3 -:10174000D645774638BF5746C7F10807511BEC0806 -:101750008F4228BF0F46045D08EBD60104FA0EF451 -:1017600013F801C029FA07FE24FA0AF45FFA8EFE84 -:101770008CEA04044EFA0AFE04EA0E048CEA040C15 -:1017800003F801C03D443E44D2E700BFB041000829 -:10179000B43F0008544200082DE9F04106460F46C8 -:1017A00000254FF6FF7441F221082A46304639469B -:1017B000FEF7F6FCC0B284EA0024082314F4004FBC -:1017C0004FEA4404A4B203F1FF3318BF84EA0804CB -:1017D00013F0FF03F2D10835402DE6D12046BDE8D5 -:1017E000F081000010B50A4441F22104914200D179 -:1017F00010BD11F8013B80EA0320082310F4004FCC -:101800004FEA400080B203F1FF3318BF604013F08D -:10181000FF03F3D1EAE700002DE9F04F85B08A46D7 -:101820008DE80C00BDF83C40814630B9494B4A4A2E -:1018300040F26E31494802F001FA11F0604F04D0D5 -:10184000474B454A40F26F31F4E7009B002B7ED0B6 -:1018500024B10E9B002B7AD0072C28D809F10C005C -:10186000FFF772FE054628B96FF00205284605B05D -:10187000BDE8F08F14220021FFF7B0FD22460E993B -:1018800005F10800FFF798FD631C2B74009B1B7883 -:101890002C4403F01F0363F03F0323724AF000431C -:1018A0006B6029464846FFF77BFE0125DEE7019B7A -:1018B0001B0A4FF00008029300F10C034FF0800B5D -:1018C0004646454603930398FFF73EFE0746002829 -:1018D000CAD014220021FFF781FDB6BB9DF8043069 -:1018E0003B729DF808307B7202220E9B711E1944D8 -:1018F000B4420AD9B8180132D2B211F801EF80F817 -:1019000008E00136072AB6B2F2D1009B197801F03F -:101910001F01B44208BF4FF0400BB81841EA48110C -:101920004BEA0103037201324AF000437B603A74D0 -:1019300039464846FFF734FE0135B4422DB288F0EF -:1019400001084FF0000BBED190E70022CDE76FF009 -:1019500001058BE79C410008803F000854420008C5 -:10196000C04100082DE9F0471E46CB8A9146C3F3DB -:101970000902062A80460F4619D013460021B0B24C -:101980008DB25A1992B2052A09D9A84210D8FA8AFA -:10199000034463F30902FA820120BDE8F087A842FC -:1019A000F3D93A4419F8014094760131E8E700256B -:1019B000FB8A7C68C3F30900821F1C23B2FBF3FA85 -:1019C00003FB1A2A1FFA8AF27CB301212368002B39 -:1019D00039D1B31F03441C20B3FBF0F301339BB296 -:1019E00099420CD2BAF1000F09D14046FFF7ACFD85 -:1019F00008B1C0F800A0206008B304460022B6B2C7 -:101A00004FF0000AB54230D2691E49441346E0182F -:101A100001339BB211F801EF80F804E001351C2B73 -:101A2000ADB214D0AE42F2D8ECE74046FFF78CFDE1 -:101A3000044608B1002303607C60002CDED16FF007 -:101A40000200BDE8F087013189B21C46BEE7AE4214 -:101A5000D8D94046FFF778FD08B1C0F800A0206053 -:101A60000028ECD004460022CCE7FB8AC3F309022D -:101A7000164466F30903FB828EE70000F8B50E46B4 -:101A800015461F46044628B9144B154A15484F21E0 -:101A900002F0D4F824220021FFF7A0FC069B63602B -:101AA000079B23626A094FF6FF739A424FF00000CA -:101AB00028BF1A46A7602070A061E06197B204F1C8 -:101AC0000C05824205D100232B6027826382A3820A -:101AD000F8BD2E60013035462036F2E79841000807 -:101AE0000C3F00085442000808B528B9084B094AC1 -:101AF0007321094802F0A2F8037823B94BB2002BF6 -:101B000001DD017008BD054B024A7D21F1E700BFF0 -:101B10009C410008183F000854420008E0400008BB -:101B2000007870472DE9F7430D9EBDF828900B9D76 -:101B30009DF83040BDF8388007461946104616B962 -:101B4000B8F1000F43D11F2C41D83B78D3B9B8F17D -:101B5000070F39D839F0030339D1424631464FF6E1 -:101B6000FF70FFF73FFE4FEA092920F0010009F45A -:101B70004079400449EA0464400C44EA40244FF6AA -:101B8000FF730DE043EA0923B8F1070F43EA046449 -:101B9000F5D9FFF701FE42463146FFF723FE034623 -:101BA0008DE840012A4621463846FFF735FE0DB93B -:101BB000FFF750FD2B780133DBB21F2B88BF0023CA -:101BC0002B7003B0BDE8F0836FF00300F9E76FF00E -:101BD0000100F6E72DE9F7430E9F0B9D9DF8348039 -:101BE000BDF83C6081469DF8300007B9C6BB1F2890 -:101BF00036D899F800E0BEF1000F34D00C0244F062 -:101C000080049DF8281044EAC83444EA014444EAB8 -:101C10000E04072E44EA006415D919461046FFF752 -:101C2000BBFD32463946FFF7DDFD034601960097BE -:101C30002A4621464846FFF7EFFDB8F1010F0CD1C7 -:101C400025B9FFF707FD4FF6FF73EFE72B78013358 -:101C5000DBB21F2B88BF00232B7003B0BDE8F083DD -:101C60006FF00100F9E76FF00300F6E7C06900B11B -:101C700004307047C1690B68C3610C30FFF7F8BCD2 -:101C80002DE9F84FD0F818A0DFF86C80054616460D -:101C90001F4654464FF0000900F10C0B0CB9BDE88B -:101CA000F88FD4E90223B21A67EB0303994508BF02 -:101CB00090451FD2AB699C42214628460DD1FFF7C3 -:101CC000EDFCAB691B68AB6121465846FFF7D0FCC1 -:101CD000AC692346A2461C46E0E7FFF7DFFC236819 -:101CE000CAF8003021465846FFF7C2FC5446DAF8DD -:101CF0000030EFE72368EDE780841E002DE9F04F08 -:101D00008BB00D4614460793DDF8509082460028AC -:101D100000F06481B9F1000F00F06081531E3F2B89 -:101D200000F25C81012A03D1079B002B40F0568111 -:101D3000BAF81460F6000023B5420893099380F0C6 -:101D400053812B199E420AD2761B16F0FF0607D14B -:101D5000AB4BAC4A40F26751AB4801F06FFF2646EF -:101D6000DAF80C3023B9DAF81030002B00F0A58037 -:101D70002F2D31D8C5F1300846454FF000032CBF58 -:101D80005FFA88F8B0460093294608AB4246DAF875 -:101D90000800FFF7B7FCA6EB08074544FFB2BAF806 -:101DA000143003F10053063BDB000293DAF80C30E9 -:101DB00005934FF0300B059B002B51D087B9DAF813 -:101DC0001000002861D0002F5FD0AB4550D98F4B59 -:101DD0008C4A40F2A651BFE737464FF00008DEE7D5 -:101DE000029B23B98A4B874A4FF4B161B4E7029B47 -:101DF000E02B28BFE02306935B44AB4204931DD93C -:101E00005B1B9F4226BFDBB203930397AB4504D90C -:101E10007E4B7C4A40F291519EE70598CDF80080B8 -:101E200008ABA5EB0B01039A0430FFF76BFC039B97 -:101E30009844FF1A1D445FFA88F8FFB2049B9B4543 -:101E400004D3744B6F4A40F29B5185E7029B069A7C -:101E5000DDF810B09B1A0293059B1B680593AAE757 -:101E6000029BBB42ABD26C4B664A40F2A15173E776 -:101E7000CDF800803A46A5EB0B0108ABFFF742FC1A -:101E8000B8443D445FFA88F80027BAF81430B5EB3F -:101E9000C30F04D9614B5B4A40F2B1515CE7B8F122 -:101EA000400F04D95E4B574A40F2B25154E767B134 -:101EB0005C4B544A40F2B3514EE70093324608ABB4 -:101EC0002946DAF80800FFF71DFC731E3F2B35B2D8 -:101ED00001D8A64204DD544B544A40F235213BE779 -:101EE00060070AD00AAB03EBD401624211F8083C48 -:101EF00002F00702134101F8083C082C21D9102CEC -:101F000021D9202C8CBF08230423079A002A6DD0E6 -:101F1000B4EBC30F6CD0082C04F1FF3215D89DF838 -:101F2000203023FA02F2D10706D54FF0FF3202FA31 -:101F300004F423438DF820309DF8203089F80030D8 -:101F40004EE00123E1E70223DFE7102C11D8BDF8B2 -:101F5000203023FA02F2D20706D54FF0FF3202FA00 -:101F600004F42343ADF82030BDF82030A9F8003048 -:101F700036E0202C0ED8089921FA02F2D30705D5B5 -:101F80004FF0FF3303FA04F40C430894089BC9F89C -:101F9000003025E0402C1CD0DDE90867304639468A -:101FA000FEF7FEF8002100F0010050EA01030BD01B -:101FB000224601200021FEF7FFF8404261EB41017B -:101FC00006430F43CDE90867DDE90823C9E900238B -:101FD00006E0174B154A4FF42071BDE66FF001057E -:101FE00028460BB0BDE8F08F1D46F9E7012CA3D0C1 -:101FF000082CA1D9102CB7D9202CE5D8C6E700BFF2 -:10200000EC3F0008C43F0008544200080E4000089E -:10201000FB3F0008334000085B4000088240000896 -:10202000B0400008C8400008E2400008443F0008F3 -:10203000E040000830B585B030B9244B244A40F266 -:10204000B121244801F0FAFD23B9234B204A40F284 -:10205000B221F6E7402A04D9204B1D4A40F2B621AE -:10206000EFE722B91D4B1A4A4FF42F71E9E700241C -:10207000012A0294039417D11B788DF80830530776 -:102080000AD004AB03EBD203554213F8084C05F019 -:102090000705AC4003F8084C00910346002102A854 -:1020A000FFF730FB05B030BD082AE5D9102A03D868 -:1020B0001B88ADF80830E2E7202A02D81B6802939B -:1020C000DDE7D3E90045CDE90245D8E71C4100082A -:1020D000583F00085442000837410008E04000081B -:1020E00070B50C4600F10C05E16819B9A1602161D9 -:1020F000A18270BD0E682846FFF7BAFAE660F3E7E2 -:102100002DE9F04FD1F8009091B0C9F3C016044604 -:102110000D46CDE90223002E50D0C9F3C03BC9F3D0 -:102120000626B9F1000F80F29F8119F0C04F40F0F0 -:102130009B812B7B002B00F09781BBF1020F03D01A -:102140002278B24240F0938109F07F02BBF1020F86 -:10215000059236D119F07F0FC9F30F2A01D10AF089 -:10216000030A2B447606059A93F8038046EA0B4649 -:1021700046EA82465FEAD81346EA0A06069300F06A -:102180009A800022002310A961E90823059B00938F -:1021900067685B4652462046B847002800F08880B2 -:1021A000A7698FB9314604F10C00FFF7DBF9074648 -:1021B000D0B96FF0020011B0BDE8F08F4FF0020B04 -:1021C000AFE7C9F3074ACCE73B699E420DD03F68B1 -:1021D000002FF9D1314604F10C00FFF7C3F907468F -:1021E0000028E6D0A3693B60A761DDE90801FFF79D -:1021F000D3FAB882F97D08F01F06C1F38401711A81 -:1022000089B20FFA81FED7E90223BEF1000FB8BFF1 -:1022100001F1200EC9F30461B8BF0FFA8EFE0791D9 -:1022200052EA030100F02F81DDE90201801A61EB1F -:10223000030102460B469F480021994208BF904285 -:10224000C0F02181069B002B3FD0BEF1010F00F3AF -:102250001A8118F0400F38D0DDE90223C7E90223C4 -:10226000202200210DEB0200FFF7B8F8DDE9022380 -:10227000CDE908232B1D0A932B7BADF836A0013B3B -:10228000DBB2ADF834309DF81C308DF83A309DF853 -:1022900014308DF83B3020468DF838B08DF8396019 -:1022A000A36808A998473846FFF70CFA002082E790 -:1022B0006FF00B007FE7A76917B96FF00C007AE7A2 -:1022C0003B699E4296D03F68F6E7FB7DC8F340121B -:1022D000B2EBD31F40F0CE80C3F38403B34240F08F -:1022E000CC8006992B7B4FEA981279B3D2073CD465 -:1022F000032B40F2C580DDE90223C7E902232B7BD3 -:10230000AE1D033BDBB23246394604F10C00FFF749 -:1023100029FB002808DA39462046FFF7BFF938467E -:10232000FFF7D0F9032046E7AB883B832A7B033ACB -:10233000D2B2B88A3146FFF755FAFB7DB882DA434C -:10234000C2F3C01262F3C713FB75AFE76AB92E1D63 -:10235000013BDBB23246394604F10C00FFF702FBC9 -:102360000028D8DB2A7B013AE2E7FA8AC2F30902A5 -:10237000013B052AD9B250D8281D002399420AD919 -:1023800007EB020E013210F801CB8EF81AC00133B0 -:10239000062ADBB2F2D1DDE902898B4207F11A028B -:1023A000CDE908890A9238BF04337A680B9234BFAA -:1023B0005B1900230C93FB8AADF836A0C3F3090325 -:1023C00019449DF81C308DF83A309DF814308DF882 -:1023D0003B300023ADF834108DF838B08DF83960FB -:1023E0007B602A7BB88A013A291DFFF7FBF93B8BFA -:1023F000B882834203D1A36808A92046984708A958 -:102400002046FFF76DFE3846FFF75CF9B88A3B8B34 -:10241000984214BF11200020CDE6786810B34FF029 -:10242000060E03689BB9A2EB0E021B2A13D80332D7 -:10243000024405F1040E1F309942ACD91EF801CBBD -:1024400002F801CF01339042DBB2F5D1A3E70EF1E0 -:102450001C0E1846E5E7184B184A194840F2B3110C -:1024600001F0ECFB034696E76FF00900A3E66FF07E -:102470000A00A0E66FF00D009DE66FF00E009AE6F0 -:102480006FF00F0097E6FB7D68F386036FF3C713C9 -:10249000FB7539462046FFF701F9069B002B7FF4B8 -:1024A000D8AEFB7DC3F38402013262F38603FB7571 -:1024B00003E700BF80841E004C410008303F000845 -:1024C000544200082DE9F0414C4EB04240F081806A -:1024D0004B4CDFF830E1E56945F00075E561E469F2 -:1024E000846AD4F8007207EA0E0747F00107C4F8BF -:1024F0000072D4F8005205EA0E0545F0010545EAE0 -:102500000121C4F80012002A65D00021C4F81C1271 -:102510000F46C4F80412C4F80C12C4F8141204EBE9 -:10252000C10501310E29C5F84072C5F84472F6D1D3 -:102530004FF0000E4FF0010C964510D1826AD2F890 -:102540000032B04223F00103C2F8003253D12C4BC9 -:10255000DA6922F00072DA61DB69BDE8F0819F7808 -:102560001D8817F0010F18BFD4F804820CFA05F18A -:102570001CBF41EA0808C4F8048217F0020F1EBF0E -:10258000D4F80C8241EA0808C4F80C827F0742BFE5 -:10259000D4F814720F43C4F8147204EBC5055F68D5 -:1025A000C5F840729F68C5F84472D4F81C5229439C -:1025B000C4F81C120C330EF1010EBDE7846A002131 -:1025C000C4F81C12C4F80412C4F80C12C4F8141293 -:1025D000AEE7002AF2D1836A0022C3F84022C3F892 -:1025E0004422C3F80422C3F814220122C3F80C22A7 -:1025F000C3F81C22A2E7BDE8F08100BFE022002062 -:10260000001002400000FFFF184A916A08B58B686D -:102610008B6013F0010105D013F00C0F14BF4FF4C1 -:1026200080310121D80506D513F4406F14BF41F461 -:10263000003141F00201D80306D513F4402F14BF36 -:1026400041F4802141F00401D3690BB10748984758 -:10265000202383F311880021054800F087FE002322 -:1026600083F31188BDE8084001F088B8E02200201B -:10267000E822002038B5124CA36ADD68AA0712D000 -:102680005A6922F002025A61A36913B1012120465E -:102690009847202383F3118800210A4800F066FE42 -:1026A000002383F31188EB0606D5A36A1021D960B5 -:1026B000236A0BB102489847BDE8384001F05EB884 -:1026C000E0220020F022002038B5124CA36A1D69D8 -:1026D000AA0712D05A6922F010025A61A36913B1F5 -:1026E000022120469847202383F3118800210A48BD -:1026F00000F03CFE002383F31188EB0606D5A36AA5 -:1027000010211961236A0BB102489847BDE838408F -:1027100001F034B8E0220020F022002038B50F4C40 -:10272000A36A5D685D602A070AD5032222701A68D1 -:1027300022F002021A60636A13B100212046984712 -:102740006B0706D5A36A9969236A13B10904034884 -:102750009847BDE8384001F011B800BFE0220020E2 -:1027600010B50F4C204600F03DFA0E4BA3620B2132 -:10277000132000F017FA0B21142000F013FA0B219C -:10278000152000F00FFA0B21162000F00BFA0023A1 -:1027900020461A460E21BDE81040FFF793BE00BF49 -:1027A000E0220020006400400F4B984210B5044620 -:1027B00005D10E4BDA6942F00072DA61DB69A36A77 -:1027C00001221A60A36A5A68D20707D56268516865 -:1027D0001268D9611A60064A5A6110BD01210820A9 -:1027E00000F07CFCEEE700BFE02200200010024079 -:1027F0005B87010003291AD8DFE801F0020A0F14F1 -:10280000836A9B6813F0E05F14BF012000207047CB -:10281000836A9868C0F380607047836A9868C0F3E1 -:10282000C0607047836A9868C0F3007070470020EA -:102830007047000010B503291FD8DFE801F0021F20 -:102840002327816A8B68C3F30163183301EB0313F9 -:10285000107881061ED55468C0F30011490041EA82 -:10286000C40141F0040100F00F00586090689860C6 -:10287000D268DA6041F00101196010BD836A03F586 -:10288000C073E5E7836A03F5C873E1E7836A03F57C -:10289000D073DDE79488C0F30011490041EA445148 -:1028A000E1E7000001290CD003D3022910D0002059 -:1028B0007047836ADA68920701D1186903E0012042 -:1028C0007047836AD86810F0030018BF0120704772 -:1028D000836AF2E710B539B9836AD96889071BD1D1 -:1028E0001B699B0704D110BD012915D0022948D1CD -:1028F000816AD1F8C031D1F8C401D1F8C84114615E -:10290000D1F8CC41546120240C610C69A40717D183 -:102910004C6944F0100412E0816AD1F8B031D1F86A -:10292000B401D1F8B8411461D1F8BC4154612024FC -:10293000CC60CC68A40703D14C6944F002044C611C -:1029400011795C0864F304119C0864F3451111715A -:1029500089064BBF91681189DB085B0D4CBF63F39F -:102960001C0163F30A01137948BF916060F303030C -:1029700013714FEA10234FEA104058BF11811370B2 -:10298000508010BD002304491A465A50C818083315 -:10299000802B4260F9D170470C2300200268436805 -:1029A0001143016003B1184770470000024A1368E1 -:1029B00043F0C0031360704700380140024A1368B7 -:1029C00043F0C00313607047004400402DE9F04716 -:1029D000C66D3768F46934620546200719D014F0D3 -:1029E000080F0CBF00218021E20748BF41F0200101 -:1029F000A30748BF41F04001600748BF41F4807120 -:102A0000202383F31188281DFFF7C8FF002383F3D9 -:102A10001188E2050AD5202383F311884FF4007151 -:102A2000281DFFF7BBFF002383F311884FF0200917 -:102A30004FF0000A14F0200831D13B0616D54FF0B4 -:102A4000200905F1380A200610D589F3118850466F -:102A500000F04CFA00282FDA0821281DFFF79EFF0E -:102A600027F080033360002383F3118879060DD5A6 -:102A700062060BD5202383F31188EA6C2B6D9A42F2 -:102A800001D12B6CF3B9002383F31188E30621D520 -:102A9000AA6E1369F3B15069BDE8F047184789F38E -:102AA0001188B38C95F864102846194000F0AAFAF2 -:102AB0008AF31188F469BDE780B2308588F3118804 -:102AC000F469C0E71021281D27F04007FFF766FFD3 -:102AD0003760D8E7BDE8F08708B50348FFF776FF11 -:102AE000BDE8084000F04ABE8C23002008B503482A -:102AF000FFF76CFFBDE8084000F040BEF82300205F -:102B000037B51D4C1D4D204600F070FA009404F1BD -:102B10001400002320221A4900F032F920220094E8 -:102B200004F13800174B184900F0ACF9174BE36576 -:102B30002566174C0C21252000F034F8204600F0C3 -:102B400055FA04F11400009400232022114900F0EA -:102B500017F904F1380000940F4B1049202200F0BF -:102B600091F90F4BE3650C212620256603B0BDE8E3 -:102B7000304000F017B800BF8C2300200051250220 -:102B800064240020AD290008A4240020003801405E -:102B9000F823002084240020BD290008C42400203C -:102BA0000044004000F1604300F01F02400903F5BB -:102BB000614309018000C9B200F1604083F800134D -:102BC00000F5614001239340C0F8803103607047F5 -:102BD00000F16040090100F56D40C9B2017670470F -:102BE000FFF7BEBD00F108020123037082600023DD -:102BF000C26000F110024360026142618361C361FF -:102C0000036243627047000010B52023044683F33B -:102C10001188022303704160FFF7C6FD0323237070 -:102C2000002383F3118810BD2DE9F0411F460446AF -:102C30000D461646202383F3118800F108082378F7 -:102C4000042B0ED029462046FFF7D4FD48B120467C -:102C500032462946FFF7EEFD002080F31188BDE8DB -:102C6000F0813946404600F065FB0028E7D000239C -:102C700083F31188BDE8F0812DE9F0411F46044639 -:102C80000D461646202383F3118800F1100823789F -:102C9000042B0ED029462046FFF704FE48B12046FB -:102CA00032462946FFF716FE002080F31188BDE862 -:102CB000F0813946404600F03DFB0028E7D0002374 -:102CC00083F31188BDE8F081F8B51546826806697E -:102CD000AA420B46816938BF8568761AB542044618 -:102CE00007D218462A46FEF767FBA3692B44A36167 -:102CF0000DE011D932461846FEF75EFBAF1B3A468F -:102D0000E1683044FEF758FBE2683A44A261A368E8 -:102D10005B1BA3602846F8BD18462A46FEF74CFB0D -:102D2000E368E4E783682DE9F041044693421546E1 -:102D3000266938BF85684069361AB5420F4606D203 -:102D40002A46FEF739FB63692B4463610DE012D913 -:102D50003246A5EB0608FEF72FFB4246B919E0689C -:102D6000FEF72AFBE26842446261A3685B1BA36032 -:102D70002846BDE8F0812A46FEF71EFBE368E4E73B -:102D800010B50A440024C361029B00604060846067 -:102D9000C160816141610261036210BD08B5826951 -:102DA0004369934201D1826882B9826801328260AC -:102DB0005A1C42611970426903699A4201D3C3687F -:102DC0004361002100F0C6FA002008BD4FF0FF303B -:102DD00008BD000070B5202304460E4683F3118819 -:102DE000A568A5B1A368A269013BA360531CA361B8 -:102DF00015782269934224BFE368A361E3690BB1AC -:102E000020469847002383F31188284670BD314639 -:102E1000204600F08FFA0028E2DA85F3118870BDB1 -:102E20002DE9F74F05460F4690469A46D0F81C907C -:102E3000202686F311884FF0000B144664B1224619 -:102E400039462846FFF740FF034668B951462846F1 -:102E500000F070FA0028F1D0002383F31188A8EB6A -:102E6000040003B0BDE8F08FB9F1000F03D001906A -:102E70002846C847019B8BF31188E41A1F4486F348 -:102E80001188DBE7C16081614161C3611144009B2E -:102E9000006040608260016103627047F8B50446DB -:102EA0000E461746202383F31188A568A5B1A368B1 -:102EB000013BA36063695A1C62611E7023696269E9 -:102EC0009A4224BFE3686361E3690BB120469847E7 -:102ED000002080F31188F8BD3946204600F02AFA18 -:102EE0000028E2DA85F31188F8BD000083694269A1 -:102EF0009A4210B501D182687AB982680132826043 -:102F00005A1C82611C7803699A4201D3C3688361A9 -:102F1000002100F01FFA204610BD4FF0FF3010BD19 -:102F20002DE9F74F05460F4690469A46D0F81C907B -:102F3000202686F311884FF0000B144664B1224618 -:102F400039462846FFF7EEFE034668B95146284643 -:102F500000F0F0F90028F1D0002383F31188A8EBEA -:102F6000040003B0BDE8F08FB9F1000F03D0019069 -:102F70002846C847019B8BF31188E41A1F4486F347 -:102F80001188DBE7026843681143016003B1184709 -:102F9000704700001430FFF743BF00004FF0FF33CD -:102FA0001430FFF73DBF00003830FFF7B9BF000015 -:102FB0004FF0FF333830FFF7B3BF00001430FFF796 -:102FC00009BF00004FF0FF311430FFF703BF0000CE -:102FD0003830FFF763BF00004FF0FF323830FFF7A3 -:102FE0005DBF000000207047FFF78ABD044B0360FF -:102FF000002343608360C36001230374704700BFF4 -:103000009042000838B5C36904460D461BB9042137 -:103010000844FFF7B7FF294604F11400FFF7BEFE8E -:10302000002806DA201D4FF48061BDE83840FFF724 -:10303000A9BF38BD024B00221B605B609A607047DD -:10304000E4240020002303748268054B1B68996800 -:103050009142FBD25A68036042601060586070472A -:10306000E424002008B5202383F31188037C032B7C -:1030700005D0042B0DD02BB983F3118808BD43690B -:1030800000221A604FF0FF334361FFF7DBFF00239C -:10309000F2E790E80C001A6002685360F2E7000063 -:1030A000002303748268054B1B6899689142FBD822 -:1030B0005A6803604260106058607047E424002042 -:1030C000054B19690874186802681A605360186122 -:1030D00001230374FDF798BAE424002030B54B1C9B -:1030E00087B005460A4C10D023690A4A01A800F0AF -:1030F00059F92846FFF7E4FF049B13B101A800F03B -:103100006BF92369586907B030BDFFF7D9FFF8E7BD -:10311000E42400206530000838B50C4D41612B696E -:1031200081689A689142044603D8BDE83840FFF7A9 -:1031300089BF1846FFF786FF01232C6101462374DF -:103140002046BDE83840FDF75FBA00BFE424002008 -:10315000044B1A681B6990689B68984294BF0020D2 -:1031600001207047E424002010B5084C2368206932 -:103170001A6822605460012223611A74FFF790FFDD -:1031800001462069BDE81040FDF73EBAE424002066 -:1031900008B5FFF7DDFF18B1BDE80840FFF7E4BF51 -:1031A00008BD0000FEE7000010B5174CFFF742FF16 -:1031B00000F0EAF880221549204600F06FF801235C -:1031C00044F8180C0374124B124AD96821F4E061D8 -:1031D0000904090C0A431049DA60CA6842F0807297 -:1031E000CA600E490A6842F001020A601022DA77CA -:1031F000202283F82220002383F3118862B6084836 -:10320000BDE8104000F06CB80C250020B842000862 -:1032100000ED00E00003FA05F0ED00E0001000E032 -:10322000C0420008F8B50F4C226A013222622246E1 -:1032300052F8141F9142154606D08B68013B8B60F3 -:10324000202663699A6802B1F8BD1968DF68DA6000 -:103250004D60616182F311881869B84786F311885F -:10326000EFE700BFE4240020EFF3118020B9EFF373 -:103270000583202282F311887047000010B558B9E9 -:10328000EFF30584C4F3080414B180F3118810BD72 -:10329000FFF77EFF84F3118810BD000082600222D8 -:1032A00002740022427470478368A3F17C0243F8E1 -:1032B0000C2C026943F83C2C426943F8382C074A2D -:1032C00043F81C2CC26843F8102C022203F8082C87 -:1032D000002203F8072CA3F118007047210600080C -:1032E00010B5202383F31188FFF7DEFF0021044689 -:1032F000FFF712FF002383F31188204610BD000062 -:10330000024B1B6958610F20FFF7DABEE42400204E -:10331000202383F31188FFF7F3BF000008B50146AF -:10332000202383F311880820FFF7D8FE002383F3BE -:10333000118808BD49B1064B42681B6918605A6084 -:10334000136043600420FFF7C9BE4FF0FF307047A1 -:10335000E42400200368984206D01A680260506096 -:1033600059611846FFF76EBE7047000038B5044635 -:103370000D462068844200D138BD036823605C603C -:103380004561FFF75FFEF4E7054B03F114025A6154 -:103390009A614FF0FF32DA6100221A62704700BF73 -:1033A000E424002010B5C2600A4A036153699C6896 -:1033B000A1420CD85C680360446020605860816062 -:1033C0009868411A99604FF0FF33D36110BD091B13 -:1033D0001B68ECE7E4240020036881689A680A44CB -:1033E0009A604268136003685A600023C360024B0E -:1033F0004FF0FF32DA617047E4240020002070476C -:10340000FEE70000704700004FF0FF3070470000FB -:10341000BFF34F8F024AD368DB07FCD4704700BF6D -:103420000020024008B5074B1B7853B9FFF7F0FFA7 -:10343000054B1A69120641BF044A5A6002F18832EC -:103440005A6008BD70260020002002402301674515 -:1034500008B5054B1B7833B9FFF7DAFF034A136948 -:1034600043F08003136108BD702600200020024055 -:103470007F289ABF00F58030C0020020704700000E -:103480004FF4006070470000802070477F2808B527 -:103490000BD8FFF7EDFF00F500630268013204D19D -:1034A00004308342F9D1012008BD002008BD00008E -:1034B0007F2838B5044624D800F0B6F8124D2860AD -:1034C000FFF7A6FFFFF7AEFF104BF322DA600222F0 -:1034D0001A612046FFF7CCFF58611A6942F040029A -:1034E0001A61FFF795FF4FF4006100F0FBF8FFF75A -:1034F000AFFF00F099F828602046BDE83840FFF79C -:10350000C5BF002038BD00BF742600200020024047 -:103510002DE9F84312F00103144606D0204B40F287 -:103520004B221A600020BDE8F88385181D4A954299 -:1035300004D91B4A4FF414711160F3E7FFF772FFCF -:10354000FFF766FFDFF86C80451A4FF00109012C88 -:1035500005EB01060F4604D8FFF77AFF0120BDE80E -:10356000F883C8F8109031F8023B3380FFF750FF22 -:103570000020C8F8100033883A889BB29A420DD0D8 -:10358000074B40F267221A60074B1E60074B1C6016 -:10359000074B1F60FFF75CFFBDE8F883023CD6E7EE -:1035A0006C260020FFFF030860260020682600200C -:1035B0006426002000200240084908B50B7828B195 -:1035C00053B9FFF72FFF01230B7008BD23B1BDE8EE -:1035D00008400870FFF73CBF08BD00BF7026002000 -:1035E00038B5FFF741FE0D4B0D4A1C6A11684FF4C8 -:1035F0007A7303FB04F38B420A49D1E9004504D2F4 -:10360000003445F10105C1E90045E41845F1000524 -:103610001360FFF733FE2046294638BDE42400201E -:10362000782600208026002008B5FFF7D9FF4FF448 -:103630007A720023FCF7CCFD08BD00BF10B5024430 -:10364000064B0439D2B2904200D110BD441C00B2E6 -:1036500053F8200041F8040FE0B2F4E7502800408E -:10366000104B30B51C6A240407D41C6A44F440741F -:103670001C621C6A44F400441C620B4C236843F433 -:10368000807323600244094B0439D2B2904200D1C6 -:1036900030BD441C00B251F8045F43F82050E0B242 -:1036A000F4E700BF001002400070004050280040C6 -:1036B00007B5012201A90020FFF7C0FF019803B060 -:1036C0005DF804FB13B50446FFF7F2FFA04206D0F5 -:1036D00002A9012241F8044D0020FFF7C1FF02B00A -:1036E00010BD000070470000074B45F255521A60AC -:1036F00002225A6040F6FF729A604CF6CC421A6081 -:10370000024B01221A7070470030004089260020C9 -:10371000034B1B781BB1034B4AF6AA221A60704771 -:103720008926002000300040034B1B689B0042BFED -:10373000024B01221A707047241002408826002094 -:10374000024B4FF080721A60704700BF2410024095 -:10375000014B1878704700BF88260020064A53683E -:1037600023F001035360EFF30983683383F309887F -:10377000002383F31188704730EF00E010B5202359 -:1037800083F31188104B5B6813F4006318D0F1EEDB -:10379000103AEFF309844FF0807344F84C3C0B4B24 -:1037A000DB6844F8083CA4F1680383F30988FFF759 -:1037B000CFFC18B1064B44F8503C10BD054BFAE75E -:1037C00083F3118810BD00BF00ED00E030EF00E092 -:1037D000310600083406000870470000FEE70000CC -:1037E000084A094B09498B4204D3094A00219342F4 -:1037F00005D3704752F8040F43F8040BF3E743F87E -:10380000041BF4E740440008902600209026002086 -:10381000902600204B6843608B688360CB68C36050 -:103820000B6943614B6903628B6943620B680360F8 -:103830007047000008B5194B9A6A42F4FC029A627C -:103840009A6A22F4FC029A629A6A5A6942F4FC0269 -:103850005A61134A5B6911464FF09040FFF7DAFF57 -:10386000104802F11C01FFF7D5FF0F4802F13801A3 -:10387000FFF7D0FF0D4802F15401FFF7CBFF0C48D2 -:1038800002F17001FFF7C6FF0A4802F18C01FFF751 -:10389000C1FFBDE8084000F065B800BF001002405D -:1038A000E04200080004004800080048000C0048FE -:1038B000001000480014004808B500F08FF9FFF729 -:1038C00073FCBDE80840FFF72FBF00007047000001 -:1038D00010B5214CA26A62F4FC02A262A26A02F450 -:1038E000FC02A2624FF0FF31A26A226921612269C3 -:1038F000002222612069E068E160E168E260E1683D -:10390000E169164841F08051E161E169016841F4E3 -:1039100080710160216A01F44071B1F5407F1EBFE2 -:103920004FF4803323622262236A1B0407D4236A84 -:1039300043F440732362236A43F40043236200F09C -:103940002DF9A369064A43F00103A361A369136833 -:1039500043F02003136010BD0010024000700040CF -:10396000000001401C4B1A6842F001021A601A68FC -:103970009007FCD55A6822F003025A605A6812F088 -:103980000C02FBD1196801F0F90119605A601A683C -:1039900042F480321A601A689103FCD50F4A5A60CB -:1039A0004FF40452DA6230221A631A6842F08072CD -:1039B0001A601A689201FCD5094A122111605A68EE -:1039C00042F002025A605A6802F00C02082AFAD148 -:1039D0001A6B1A63704700BF0010024000241D00DC -:1039E00000200240084A08B5536911680B4003F0F3 -:1039F0000103536123B1054A13680BB1506898471E -:103A0000BDE80840FFF7BABE000401400C230020C7 -:103A1000084A08B5536911680B4003F0020353616B -:103A200023B1054A93680BB1D0689847BDE80840B8 -:103A3000FFF7A4BE000401400C230020084A08B58B -:103A4000536911680B4003F00403536123B1054A25 -:103A500013690BB150699847BDE80840FFF78EBE67 -:103A6000000401400C230020084A08B5536911687E -:103A70000B4003F00803536123B1054A93690BB16E -:103A8000D0699847BDE80840FFF778BE00040140C0 -:103A90000C230020084A08B5536911680B4003F055 -:103AA0001003536123B1054A136A0BB1506A98475A -:103AB000BDE80840FFF762BE000401400C2300206F -:103AC000174B10B55C691A68144004F478725A6197 -:103AD000A30604D5134A936A0BB1D06A98476006CF -:103AE00004D5104A136B0BB1506B9847210604D5CF -:103AF0000C4A936B0BB1D06B9847E20504D5094A89 -:103B0000136C0BB1506C9847A30504D5054A936C10 -:103B10000BB1D06C9847BDE81040FFF72FBE00BF37 -:103B2000000401400C2300201A4B10B55C691A6890 -:103B3000144004F47C425A61620504D5164A136DA0 -:103B40000BB1506D9847230504D5134A936D0BB103 -:103B5000D06D9847E00404D50F4A136E0BB1506E38 -:103B60009847A10404D50C4A936E0BB1D06E9847C8 -:103B7000620404D5084A136F0BB1506F98472304B1 -:103B800004D5054A936F0BB1D06F9847BDE810403C -:103B9000FFF7F4BD000401400C230020062108B506 -:103BA0000846FEF7FFFF06210720FEF7FBFF062170 -:103BB0000820FEF7F7FF06210920FEF7F3FF062194 -:103BC0000A20FEF7EFFF06211720FEF7EBFF062184 -:103BD0002820BDE80840FEF7E5BF000008B5FFF764 -:103BE00077FEFEF7CFFEFEF7FBFFFFF7FDF9FFF7CD -:103BF0006DFEBDE8084000F001B8000000F00EB80E -:103C000008B5202383F31188FFF70CFB002383F30F -:103C10001188BDE80840FFF7B1BD0000054B064A1A -:103C20005A6000229A6007221A6008210B20FEF7D2 -:103C3000CFBF00BF10E000E03F1901001FB51C46D8 -:103C4000094B1B680546D86852B1084B02928DE8B3 -:103C50000A0022462B460649FDF718FC00F042F800 -:103C6000044B1A46F2E700BF1011002088430008F9 -:103C700095430008143E000810B5013902449042F3 -:103C800001D1002010BD10F8013B11F8014FA342F3 -:103C9000F5D0181B10BD00002DE9F84307468846F3 -:103CA00091461E468BB10D46A8EB0500B54207EBC9 -:103CB000000402D20020BDE8F8833246494620467F -:103CC000FFF7DAFF18B1013DEEE7BDE8F8832046C3 -:103CD000BDE8F883034611F8012B03F8012B002AF5 -:103CE000F9D1704708B5062000F02CF80120FFF745 -:103CF00087FB00001F2938B504460D4604D916235A -:103D000003604FF0FF3038BD426C12B152F82130E1 -:103D10004BB9204600F030F82A4601462046BDE85F -:103D2000384000F017B8012B0AD0591C03D11623D4 -:103D30000360012038BD002442F8254028469847FA -:103D4000002038BD024B01461868FFF7D3BF00BF03 -:103D50001011002038B5074C0023054608461146CF -:103D60002360FFF751FB431C02D1236803B12B6092 -:103D700038BD00BF8C260020FFF740BB40A2E4F115 -:103D8000646891064E6F20617070207369670A0045 -:103D9000426164206677206C656E677468202575C3 -:103DA0000A0042616420626F6172645F6964202569 -:103DB000752073686F756C642062652025750A0034 -:103DC0004261642066772064657363726970746F02 -:103DD00072206C656E6774682025750A0042616404 -:103DE0002061707020435243203078253038783A73 -:103DF000307825303878203078253038783A307867 -:103E0000253038780A00476F6F64206669726D77D5 -:103E10006172650A00000000726563656976656419 -:103E20005F756E697175655F69645F6C656E203C76 -:103E30002055415643414E5F50524F544F434F4CD3 -:103E40005F44594E414D49435F4E4F44455F49449D -:103E50005F414C4C4F434154494F4E5F554E495181 -:103E600055455F49445F4D41585F4C454E47544866 -:103E7000002E2E2F2E2E2F546F6F6C732F41505FFC -:103E8000426F6F746C6F616465722F63616E2E6335 -:103E9000707000616C6C6F63617465645F6E6F64F9 -:103EA000655F6964203C3D20313237006F72672EB8 -:103EB0006172647570696C6F742E61705F70657289 -:103EC0006970685F67707300766F69642068616EFF -:103ED000646C655F616C6C6F636174696F6E5F7257 -:103EE0006573706F6E73652843616E617264496EAD -:103EF0007374616E63652A2C2043616E6172645233 -:103F0000785472616E736665722A290063616E610E -:103F10007264496E6974000063616E617264536516 -:103F2000744C6F63616C4E6F64654944000000001F -:103F300063616E61726448616E646C65527846724A -:103F4000616D650063616E6172644465636F646591 -:103F50005363616C6172000063616E617264456EEF -:103F6000636F64655363616C61720000696E6372B4 -:103F7000656D656E745472616E7366657249440056 -:103F8000656E717565756554784672616D6573000F -:103F900070757368547851756575650070726570D9 -:103FA000617265466F724E6578745472616E7366A5 -:103FB00065720000636F7079426974417272617951 -:103FC000000000006465736361747465725472610B -:103FD0006E736665725061796C6F616400000000F9 -:103FE00066726565426C6F636B0000006269745FA6 -:103FF0006C656E677468203E20300072656D616983 -:104000006E696E675F62697473203E203000696E6E -:104010007075745F6269745F6F6666736574203E65 -:104020003D20626C6F636B5F6269745F6F6666737D -:10403000657400626C6F636B5F656E645F62697468 -:104040005F6F6666736574203E20626C6F636B5FA2 -:104050006269745F6F66667365740072656D61692D -:104060006E696E675F6269745F6C656E6774682005 -:104070003C3D2072656D61696E696E675F6269744F -:104080007300696E7075745F6269745F6F666673E2 -:104090006574203C3D207472616E736665722D3EBE -:1040A0007061796C6F61645F6C656E202A203800E6 -:1040B0006F75747075745F6269745F6F666673653F -:1040C00074203C3D2036340072656D61696E696E06 -:1040D000675F6269745F6C656E677468203D3D2040 -:1040E000300028726573756C74203E2030292026BC -:1040F000262028726573756C74203C3D2036342967 -:104100002026262028726573756C74203C3D206241 -:1041100069745F6C656E6774682900006465737408 -:10412000696E6174696F6E20213D202828766F6961 -:1041300064202A2930290076616C756520213D2094 -:104140002828766F6964202A293029006F666673F3 -:1041500065745F77697468696E5F626C6F636B200A -:104160003C2028333255202D205F5F6275696C74C6 -:10417000696E5F6F66667365746F66202843616E53 -:10418000617264427566666572426C6F636B2C2067 -:1041900064617461292900006F75745F696E732012 -:1041A000213D202828766F6964202A2930290000C3 -:1041B0007372635F6C656E203E2030550000000016 -:1041C0002863616E5F696420262030783146464658 -:1041D000464646465529203D3D2063616E5F696431 -:1041E00000000000616C6C6F6361746F722D3E7330 -:1041F0007461746973746963732E63757272656E2A -:10420000745F75736167655F626C6F636B73203E8B -:10421000203000007472616E736665725F6964209D -:10422000213D202828766F6964202A293029000042 -:1042300073746174652D3E6275666665725F626C4B -:104240006F636B73203D3D202828766F6964202AB8 -:10425000293029002E2E2F2E2E2F6D6F64756C6540 -:10426000732F6C696263616E6172642F63616E614A -:1042700072642E63006974656D2D3E6672616D65B2 -:104280002E646174615F6C656E203E20300000001A -:1042900000000000B12F00089D2F0008D92F000852 -:1042A000C52F0008D12F0008BD2F0008A92F000836 -:1042B000952F0008E52F00086D61696E0000000071 -:1042C000D8420008282500206026002001000000B8 -:1042D000A53100080000000069646C650000000062 -:1042E000A001A82A00000000FAAABEAA50001400EB -:1042F000EFFF000000770000709709000100000048 -:1043000000000000AAAAAAAA01000000FFFF000006 -:10431000000000000000000000000000000000009D -:10432000AAAAAAAA00000000FFFF000000000000E7 -:10433000000000000000000000000000AAAAAAAAD5 -:1043400000000000FFFF000000000000000000006F -:104350000000000000000000AAAAAAAA00000000B5 -:10436000FFFF00000000000000000000000000004F -:1043700000000000AAAAAAAA00000000FFFF000097 -:1043800000000000000000002C2066756E63746958 -:104390006F6E3A2000617373657274696F6E2022CC -:1043A000257322206661696C65643A2066696C65D4 -:1043B00020222573222C206C696E652025642573CC -:1043C00025730A003CBEFF7F0100000000000000D2 -:1043D0006400000000000000FE2A0100D20400007A -:1043E0001411002000000000000000000000000088 -:1043F00000000000000000000000000000000000BD -:1044000000000000000000000000000000000000AC -:10441000000000000000000000000000000000009C -:10442000000000000000000000000000000000008C -:10443000000000000000000000000000000000007C -:044440000000000078 +:1000000000090020A5040008E1140008611400089C +:10001000B9140008611400088D140008A704000832 +:10002000A7040008A7040008A704000881350008F9 +:10003000A7040008A7040008A7040008B93A0008AC +:10004000A7040008A7040008A7040008A7040008E4 +:10005000A7040008A7040008513800087D380008EC +:10006000A9380008D538000801390008A70400089D +:10007000A7040008A7040008A7040008A7040008B4 +:10008000A7040008A7040008A70400082924000802 +:1000900095240008E92400083D2500082D390008B2 +:1000A000A7040008A7040008A7040008A704000884 +:1000B000A7040008A7040008A7040008A704000874 +:1000C000A7040008A7040008A7040008A704000864 +:1000D000A70400088129000895290008A704000842 +:1000E00095390008A7040008A7040008A704000821 +:1000F000A7040008A7040008A7040008A704000834 +:10010000A7040008A7040008A7040008A704000823 +:10011000A7040008A7040008A7040008A704000813 +:10012000A7040008A7040008A7040008A704000803 +:10013000A7040008A7040008A7040008A7040008F3 +:10014000A7040008A7040008A7040008A7040008E3 +:10015000A7040008A7040008A7040008A7040008D3 +:10016000A7040008A7040008A7040008A7040008C3 +:10017000A7040008A7040008A7040008A7040008B3 +:10018000A7040008A7040008A7040008A7040008A3 +:10019000A7040008A7040008A7040008A704000893 +:1001A00053B94AB9002908BF00281CBF4FF0FF31DE +:1001B0004FF0FF3000F074B9ADF1080C6DE904CEDA +:1001C00000F006F8DDF804E0DDE9022304B0704732 +:1001D0002DE9F047089D04468E46002B4DD18A42FA +:1001E000944669D9B2FA82F252B101FA02F3C2F12D +:1001F000200120FA01F10CFA02FC41EA030E9440BE +:100200004FEA1C48210CBEFBF8F61FFA8CF708FBDE +:1002100016E341EA034306FB07F199420AD91CEBB6 +:10022000030306F1FF3080F01F81994240F21C81E8 +:10023000023E63445B1AA4B2B3FBF8F008FB103330 +:1002400044EA034400FB07F7A7420AD91CEB040465 +:1002500000F1FF3380F00A81A74240F20781644435 +:10026000023840EA0640E41B00261DB1D4400023BA +:10027000C5E900433146BDE8F0878B4209D9002D1E +:1002800000F0EF800026C5E9000130463146BDE8A8 +:10029000F087B3FA83F6002E4AD18B4202D3824212 +:1002A00000F2F980841A61EB030301209E46002DC1 +:1002B000E0D0C5E9004EDDE702B9FFDEB2FA82F216 +:1002C000002A40F09280A1EB0C014FEA1C471FFA74 +:1002D0008CFE0126200CB1FBF7F307FB131140EA5B +:1002E00001410EFB03F0884208D91CEB010103F128 +:1002F000FF3802D2884200F2CB804346091AA4B2EA +:10030000B1FBF7F007FB101144EA01440EFB00FEBD +:10031000A64508D91CEB040400F1FF3102D2A64522 +:1003200000F2BB800846A4EB0E0440EA03409CE7C1 +:10033000C6F12007B34022FA07FC4CEA030C20FA6E +:1003400007F401FA06F31C43F9404FEA1C4900FA8E +:1003500006F3B1FBF9F8200C1FFA8CFE09FB18110B +:1003600040EA014108FB0EF0884202FA06F20BD97E +:100370001CEB010108F1FF3A80F08880884240F2CE +:100380008580A8F102086144091AA4B2B1FBF9F012 +:1003900009FB101144EA014100FB0EFE8E4508D90D +:1003A0001CEB010100F1FF346CD28E456AD9023892 +:1003B000614440EA0840A0FB0294A1EB0E01A14277 +:1003C000C846A64656D353D05DB1B3EB080261EBE5 +:1003D0000E0101FA07F722FA06F3F1401F43C5E9BF +:1003E000007100263146BDE8F087C2F12003D840F5 +:1003F0000CFA02FC21FA03F3914001434FEA1C4737 +:100400001FFA8CFEB3FBF7F007FB10360B0C43EA28 +:10041000064300FB0EF69E4204FA02F408D91CEBD8 +:10042000030300F1FF382FD29E422DD902386344D6 +:100430009B1B89B2B3FBF7F607FB163341EA034176 +:1004400006FB0EF38B4208D91CEB010106F1FF38C5 +:1004500016D28B4214D9023E6144C91A46EA0046BC +:1004600038E72E46284605E70646E3E61846F8E64E +:100470004B45A9D2B9EB020864EB0C0E0138A3E797 +:100480004646EAE7204694E74046D1E7D0467BE778 +:10049000023B614432E7304609E76444023842E7F0 +:1004A000704700BF02E000F000F8FEE772B63A487D +:1004B00080F30888394880F3098839484EF6085196 +:1004C000CEF20001086040F20000CCF200004EF6CF +:1004D0003471CEF200010860BFF34F8FBFF36F8F0E +:1004E00040F20000C0F2F0004EF68851CEF200015A +:1004F0000860BFF34F8FBFF36F8F4FF00000E1EE46 +:10050000100A4EF63C71CEF200010860062080F31E +:100510001488BFF36F8F03F0B3F803F08FF803F084 +:10052000C1F84FF055301F491B4A91423CBF41F87A +:10053000040BFAE71C49194A91423CBF41F8040BED +:10054000FAE71A491A4A1B4B9A423EBF51F8040B6C +:1005500042F8040BF8E700201749184A91423CBFC3 +:1005600041F8040BFAE703F06DF803F0D7F8144CE8 +:10057000144DAC4203DA54F8041B8847F9E700F045 +:1005800041F8114C114DAC4203DA54F8041B884772 +:10059000F9E703F055B80000000900200011002021 +:1005A000000000080001002000090020F83C0008BD +:1005B00000110020201100202011002028260020FA +:1005C000A0010008A0010008A0010008A001000887 +:1005D0002DE9F04F2DED108AC1F80CD0C3689D466F +:1005E000BDEC108ABDE8F08F002383F31188284604 +:1005F000A047002002F04CFDFEE702F0D1FC00DF36 +:10060000FEE700002DE9F04102F062FF074602F02C +:10061000ADFF054600283ED12B4B9F423BD0013316 +:100620009F423BD0294B27F0FF029A423AD1F8B2C1 +:1006300000F054FAA84642F2107400F059FC08B1D8 +:100640000024A04600F050FA064678B384BB464624 +:1006500035B11F4B9F4203D002F080FF0024264695 +:10066000002002F03FFF1B4B1B6913F0400322D018 +:100670000EB100F031F800F05FFC00F031FE00F048 +:1006800031FF0546CCB100F02DFF401BA04214D92C +:1006900000F022F8F3E7A8460024CEE704464FF026 +:1006A0000108CAE780464FF47A74C6E70446CFE7EC +:1006B0004FF47A74CCE71C46DDE700F0DDFC012046 +:1006C00002F0ECFCDEE700BF010007B0000008B05C +:1006D000263A09B00004004838B51D4A1D4B196878 +:1006E000013134D004339342F9D11B4C194DD4F865 +:1006F0000428AA422BD3194B9B6803F1006303F52E +:10070000D0439A4223D202F0FDFE02F00FFF0020F8 +:1007100000F000FE124B0220187000F037FE114B63 +:10072000DA690022DA61D96999699A619B6972B6BE +:100730004FF0E0232021C3F8085DD4F80038D4F846 +:10074000042881F311889D4683F30888104738BD3B +:100750002068000800680008006000080011002000 +:100760002011002000100240094A136849F2690074 +:1007700099B21B0C00FB01331360064B186844F25E +:10078000506182B2000C01FB0200186080B2704719 +:100790001C1100201811002010B500211022044661 +:1007A00000F00EFE034B03CB206061601868A06070 +:1007B00010BD00BFACF7FF1F2DE9F043224DBBB0C9 +:1007C00000F090FEAB6840F2ED22C31A934232D99A +:1007D00006AFA8602B4628220021384601F05EFBB8 +:1007E00005F10E0000F0E4FD002604465FFA80F9F2 +:1007F00005F10E08F3B2F100994501F1280107D97E +:1008000008EB06030822384601F048FB0136F1E701 +:1008100008230122CDE9023205340C4B0193A4B226 +:1008200030230093CDE9047405A3D3E90023297B89 +:10083000074801F04BF93BB0BDE8F083AFF300800F +:1008400078F6339F93CACD8D682100207521002052 +:100850003C21002070B50D4614461E4601F0CCF830 +:1008600050B9022E10D1012C0ED112A3D3E90023CE +:10087000C5E90023012007E0282C10D005D8012C61 +:1008800009D0052C0FD0002070BD302CFBD10BA35C +:10089000D3E90023ECE70BA3D3E90023E8E70BA39C +:1008A000D3E90023E4E70BA3D3E90023E0E700BF8B +:1008B000AFF30080401DA12026812A0B78F6339FDC +:1008C00093CACD8D9E6AC421818A46EE26417272FA +:1008D000DF25D7B7F017304A39059E5613B50446C1 +:1008E0002346084620220021019001F0D7FA227900 +:1008F0000198032A234628BF032203F8042F20214E +:10090000022201F0CBFA62790198072A234628BF18 +:10091000072203F8052F2221032201F0BFFAA27952 +:100920000198072A234628BF072203F8062F25210E +:10093000032201F0B3FA019804F1080310222821E0 +:1009400001F0ACFA382002B010BD00002DE9F04FE4 +:10095000ADF5017D21AD0EAE40F2751280460F4619 +:1009600022A80021296000F02BFD482200213046FA +:1009700000F026FD00F0B6FD564B4FF47A72B0FB46 +:10098000F2F0186093E80700012386E807000DF1F4 +:100990005A003382FFF700FF4EF60343338407AB60 +:1009A00018464D4903F0C2F81B22306429463046F0 +:1009B00086F83C20FFF792FF12AB0446014608225E +:1009C000284601F06BFA0822A1180DF149032846C8 +:1009D00001F064FA0DF14A03082204F110012846DF +:1009E00001F05CFA13AB202204F11801284601F053 +:1009F00055FA14AB402204F13801284601F04EFAB2 +:100A000016AB082204F17801284601F047FA0DF1EF +:100A10005903082204F18001284601F03FFA04F14D +:100A2000880A0DF15A0904F5847B4B465146082289 +:100A300028460AF1080A01F031FAD34509F1010903 +:100A4000F3D11BAB08225946284601F027FA04F5DA +:100A500088744FF0000996F834304B450AD9B36BCF +:100A600021464B440822284601F018FA083409F1BF +:100A70000109F0E74FF0000996F83C304B4504EBD4 +:100A8000C90108D9336C08224B44284601F006FA04 +:100A900009F10109F0E700230393BB7E02930731BC +:100AA00007F119030193C1F3CF010123CDE90451EB +:100AB0000093F97E05A3D3E90023404601F006F830 +:100AC0000DF5017DBDE8F08FAFF300809E6AC42173 +:100AD000818A46EE241100203C3B0008014B18702F +:100AE000704700BF30110020F0B5334B1C7B85B040 +:100AF00034B1324B0E221A810024204605B0F0BDDD +:100B00002F4A1068516802AB03C308232D492E48B1 +:100B10000DEB030202F0E8FF054630B9274B2B48E6 +:100B20000A221A8100F098FCE6E70169B1F5663FF8 +:100B300006D9224B26480B221A8100F08DFCDCE7F7 +:100B4000438BB3F57B7F09D01C4A22480C211181CD +:100B50004FF47B72194600F07FFCCEE71E4A024438 +:100B600002F11003994204D2144B1C4810221A813E +:100B7000E3E710398E1A2046134900F0B7FC3246DD +:100B8000074605F11801204600F0B0FCAB689F4213 +:100B900002D1EB6898420AD0084B0D221A810090CE +:100BA000D5E902123B460E4800F056FCA4E70D487A +:100BB00000F052FC0124A0E768210020241100204D +:100BC000E93B0008DC97030000680008583B000878 +:100BD000643B0008763B00080898FFF7943B000848 +:100BE000B13B0008DA3B00082DE9F04FADB006AF8D +:100BF00080460C4600F000FF054600285AD1237EAF +:100C0000022B1BD1E38A012B18D100F06BFC0646A6 +:100C1000FFF7AAFD03464FF4C870DFF8D092B3FB8C +:100C2000F0F206F5167602FB103316FA83F3C9F8D4 +:100C30000030E37E33B9A84B00221A709C37BD46C2 +:100C4000BDE8F08FA38AEEB2013BB34205F1010586 +:100C50000BD93B1D1E44E90000960023082201F039 +:100C6000F801204600F0DEFFECE707F11400FFF783 +:100C700093FD324607F11401381D02F025FF0028CC +:100C8000D9D10F2E08D8944B1E70D9F80030A3F597 +:100C90001673C9F80030D1E7FB1CF87001460093C9 +:100CA00007220346204600F0BDFFF978404600F0D9 +:100CB0009BFEC3E7E38A282B26D010D8012B1ED039 +:100CC000052BBBD1BFF34F8F8449854BCA6802F413 +:100CD000E0621343CB60BFF34F8F00BFFDE7302BC3 +:100CE000ACD1637E7F4D01336A7BDBB29342E94630 +:100CF00003D1E27E2B7B9A4265D0CD469EE721460A +:100D00004046FFF723FE99E7A38A013B9BB2C92B1C +:100D100094D8744D2E7B26BB05F10C03009308225A +:100D200033463146204600F07DFF731CF2B2D900F5 +:100D30001E46A38A013B9A4205DA0E322A440092EB +:100D400000230822EEE700230022C5E90023002348 +:100D5000AB6085F8D730C5F8D8302B7B0BB9E37E74 +:100D60002B73002507F114093B1D0822294648462C +:100D7000C7E90155FD6001F091F83B7A05F1010AE0 +:100D8000AB424FEACA0608D9FB6808222B44314619 +:100D9000484601F083F85546EFE7C6F3CF06E17EFB +:100DA000CDE9049600230393A37E029319342823EC +:100DB0000093019446A3D3E90023404600F086FE49 +:100DC000FFF7FAFC3AE74FF0000807F11403A7F821 +:100DD00014801022009341460123204600F022FF98 +:100DE000A68A023EB6B2F31C9B109B000733DB08B9 +:100DF000A9EBC3039D460DF1180A1FFA88F34FEAC9 +:100E0000C801B34201F110010AD20AEB08030093B2 +:100E100008220023204600F005FF08F10108ECE756 +:100E200095F8D70000F080FAD5F8D83004461BB901 +:100E300095F8D70000F088FAD5F8D83033449C42B2 +:100E400004D295F8D700013000F07EFA4FEA960BF5 +:100E50004FF000081FFA88F18B45D5E9003209D917 +:100E60000AEB880103EB8800012200F0B1FA08F1D7 +:100E70000108EFE7F31842F10002C5E90032D5F8A6 +:100E8000D83095F8D70006EB0308C5F8D88000F0F5 +:100E90004BFA804509D395F8D730D5F8D8000133FF +:100EA000001B85F8D730C5F8D800FF2E08D80023DE +:100EB0002B7300F05BFAFFF717FE08B1FFF70CFC8D +:100EC0002B68094A9B0A013313810023AB6014E7A6 +:100ED00026417272DF25D7B73521002000ED00E0F2 +:100EE0000400FA0568210020241100203821002088 +:100EF00010B54FF000540C4B22689A4211D10B4BA5 +:100F0000627D1A700A48237D03730A49C9220E3094 +:100F100000F044FAE0220021204600F051FA0120BE +:100F200010BD0020FCE700BF9AAD44C53011002081 +:100F300068210020160000202DE9FF41434C0223C8 +:100F400063710023029324250A23581EB5FBF3F690 +:100F50007343D3F12402C1B23ED002280346F4D138 +:100F60009DF80B303A493B485A1E9DF80A30013B28 +:100F70001B0443EA0253BDF80820013A13434B60B7 +:100F800001F044FD00230193334B3449009334486E +:100F9000344B4FF4805200F001FD334B197811B1FE +:100FA0002F4800F021FD00F09DFA0546FFF7DCFB1D +:100FB0004FF4C873B0FBF3F202FB130305F5167090 +:100FC00010FA83F0294B186002F0D0FA08B10F2311 +:100FD000238104B0BDE8F081C1EBC107FB1C4FEADF +:100FE000E30EC3F3C703A1EB030C0EF101084FF4AA +:100FF0007A705FFA8CF50EFB000058FA8CFCB0FB9F +:10100000FCF0B0F5617F07D97B1EC3F3C703C91A93 +:10101000CDB2591E0F2916D86A1E072A8CBF00228E +:101020000122591901FB06601149B1FBF0F1114889 +:10103000814295D1002A93D0ADF808608DF80A302E +:101040008DF80B508CE71346EBE700BF241100200E +:1010500010110020802200205508000834110020C3 +:101060003C210020E90B000830110020382100202D +:101070000051250240420F002DE9F04F90A7D7E91B +:1010800000670FF24429D9E90089874D93B0DFF852 +:1010900040B2864C284600F07DFD0DF1300A0790E5 +:1010A00070B310220021504600F08AF9079B197B8B +:1010B0004FF0000261F303028DF830205868996800 +:1010C0000EAA03C21B680D9A63F31C029DF8303010 +:1010D0000D9243F020038DF830300023524619461C +:1010E000584601F0A3FC079028B9284600F056FDA9 +:1010F000079B2370CEE72378072B3CD8013323705E +:1011000018220021504600F05BF9DFF8C4B100233B +:1011100019465246584601F0B1FC014678BB1022F0 +:1011200008A800F04DF94FF0904209AC536983F0E4 +:101130001003536100F0D8F90B4612A9024611E9D9 +:10114000030084E803009DF83410C1F3030089060E +:101150004CBF0E9CBDF838408DF82C0046BFC4F340 +:101160001C0444F00044C4F30A0408A92846089467 +:1011700000F0DCFECBE7284600F010FDC0E7284673 +:1011800000F03AFC0446002848D1DFF848B100F0EE +:10119000A9F9DBF80030984240D300F0A3F907909A +:1011A000FFF7E2FA079A8DF8204003464FF4C87023 +:1011B00002F51672B3FBF0F101FB103312FA83F360 +:1011C000CBF80030DFF810B19BF8001011B9012303 +:1011D0008DF8203050460791FFF7DEFA0799C1F1EC +:1011E0001004E4B2062C28BF0624224651440DF117 +:1011F000210000F0D3F808AB0393182302930134C5 +:101200002B4B0193E4B20123009304943B463246F6 +:10121000284600F0F3FB00238BF8003000F062F961 +:10122000244A254C1368C31AB3F57A7F31D3106072 +:1012300000F05AF902460B46284600F0B9FC284651 +:1012400000F0DAFB28B3237BDFF890B0002B14BF4B +:10125000032302238BF8053000F044F94FF47A732E +:101260005146B0FBF3F0CBF800005846FFF736FBD1 +:10127000182307300293114B0193C0F3CF0040F2C3 +:101280005513CDE903A0009342464B46284600F093 +:10129000B5FB237B2BB1FFF78FFA237B002B7FF469 +:1012A000F6AE13B0BDE8F08F3C2100204D220020A7 +:1012B0003421002048220020682100204C220020F8 +:1012C000401DA12026812A0BF1C6A7C1D068080FB6 +:1012D0008022002038210020352100202411002008 +:1012E00070B501F0B5FF094E094D30800024286823 +:1012F0003388834208D901F0A7FF2B6804440133E7 +:10130000B4F5D04F2B60F2D370BD00BF7C2200201B +:101310005022002002F03AB800F10060920000F57F +:10132000D04001F0D5BF0000054B1A68054B1B8863 +:101330009B1A834202D9104401F086BF00207047F7 +:10134000502200207C22002038B5074D0446286832 +:10135000204401F07FFF28B928682044BDE83840C8 +:1013600001F08ABF38BD00BF50220020064991F825 +:10137000243033B10023086A81F824300822FFF7B3 +:10138000CBBF0120704700BF54220020022802BFBB +:101390004FF090434FF480129A61704710B50023CC +:1013A000934203D0CC5CC4540133F9E710BD000074 +:1013B00003460246D01A12F9011B0029FAD17047E0 +:1013C00002440346934202D003F8011BFAE7704738 +:1013D0002DE9F8431F4D144695F82420074688460A +:1013E00052BBDFF870909CB395F824302BB92022C3 +:1013F000FF2148462F62FFF7E3FF95F82400C0F174 +:101400000802A24228BF2246D6B24146920005EB0E +:101410008000FFF7C3FF95F82430A41B1E44F6B2EA +:10142000082E17449044E4B285F82460DBD1FFF71E +:101430009DFF0028D7D108E02B6A03EB820383428B +:10144000CFD0FFF793FF0028CBD10020BDE8F88371 +:101450000120FBE7542200200FB4002004B07047A5 +:1014600000B59BB0EFF3098168226846FFF796FF4D +:10147000EFF30583044B9A6BDA6A9A6A9A6A9A6A5E +:101480009A6A9A6A9B6AFEE700ED00E000B59BB09D +:10149000EFF3098168226846FFF780FFEFF30583C9 +:1014A000044B9A6B9A6A9A6A9A6A9A6A9A6A9B6ACF +:1014B000FEE700BF00ED00E000B59BB0EFF309814F +:1014C00068226846FFF76AFFEFF30583034B5A6B08 +:1014D0009A6A9A6A9A6A9A6A9B6AFEE700ED00E045 +:1014E000FEE7000001F08EBF01F064BF30B5094D8A +:1014F0000A4491420DD011F8013B5840082340F3B3 +:101500000004013B2C4013F0FF0384EA5000F6D1A5 +:10151000EFE730BD2083B8ED2DE9F041C56915B97D +:10152000C161BDE8F0814B6823F06047C3F38A4690 +:101530004FEAD37EC3F3807816EA230638BF3E46CF +:10154000AC462B465A68BEEBD27F22F060440AD0EC +:10155000002A18DAA40CB44217D19D420FD10D60B5 +:10156000DEE71346EEE7A74207D102F08044C2F35C +:10157000807242450BD054B1EFE708D2EDE7CCF8CA +:1015800000100B60CDE7B44201D0B442E5D81A6830 +:101590009C46002AE5D11960C3E700002DE9F04719 +:1015A000089D01F007044FEAD508224405F007051D +:1015B00000EBD1004FF47F49944201D1BDE8F087A0 +:1015C00004F0070705F0070A57453E4638BF564660 +:1015D000C6F10806111B8E4228BF0E46E10808EB33 +:1015E000D50E415C13F80EC0B94029FA06F721FA6E +:1015F0000AF1FFB28CEA010147FA0AF739408CEA96 +:10160000010C03F80EC034443544D5E780EA0120CC +:10161000082341F2210201B24000002980B203F107 +:10162000FF33B8BF504013F0FF03F4D17047000000 +:1016300038B50C468D18A54200D138BD14F8011BF1 +:10164000FFF7E4FFF7E7000002684AB113680360A0 +:10165000C388018901339BB29942C38038BF03819B +:101660001046704770B588B0202204460D46684683 +:101670000021FFF7A5FE20460495FFF7E5FF02468F +:1016800058B16B46054608AE1C4603CCB4422860F0 +:101690006960234605F10805F6D1104608B070BD13 +:1016A000082817D909280CD00A280CD00B280CD0F0 +:1016B0000C280CD00D280CD00E2814BF4020302050 +:1016C00070470C2070471020704714207047182076 +:1016D0007047202070470000082817D90C280CD923 +:1016E00010280CD914280CD918280CD920280CD96A +:1016F00030288CBF0F200E207047092070470A2029 +:1017000070470B2070470C2070470D207047000079 +:1017100010B54B6823B9CA8A63F30902CA8210BDA7 +:10172000C4681A681C60C360438A013B43824A60F4 +:10173000EFE700002DE9F84F1D46CB8A0F46C3F3B3 +:1017400009010629814692460B4630D00020AAB2F4 +:1017500007F119049EB2052E1FFA80F80FD89045A4 +:1017600003F1010306D3FB8A0A4462F30903FB82F7 +:1017700001201AE01AF80060E6540130EAE79045CB +:10178000F1D2A1F1060B1C237C68BBFBF3F203FB37 +:1017900012BB1FFA8BF6002C45D14846FFF754FFC9 +:1017A000044638B978606FF00200BDE8F88F4FF05A +:1017B0000008E6E7002606607860ADB24FF0000B47 +:1017C000454510D90AEB0803221D13F8011B91555A +:1017D000B1B208F101081B291FFA88F82BD0454542 +:1017E00006F10106F1D8FB8AC3F30902154465F33B +:1017F0000903BCE7013292B21C462368002BF9D1E1 +:10180000AB1F0B441C21B3FBF1F301339BB29A4293 +:10181000D3D2BBF1000FD0D14846FFF715FF20B956 +:10182000C4F800B0BFE70122E7E7C0F800B05E46A9 +:1018300020600446C1E74545D5D94846FFF704FF77 +:1018400008B92060AFE7C0F800B000262060044669 +:10185000B6E700002DE9F04F2DED028B83B0CDE906 +:101860000013BDF83C5007469146002A00F09280D4 +:101870002DB10E9B002B00F08D80072D32D807F183 +:101880000C00FFF7E1FE044638B96FF00204204671 +:1018900003B0BDEC028BBDE8F08F14220021FFF7EE +:1018A0008FFD0E992A4604F10800FFF777FD681CAA +:1018B000C0B2FFF711FFFFF7F3FE207499F8003074 +:1018C000013814FA80F003F01F0363F03F03037242 +:1018D000009B43F00041616038462146FFF71CFE43 +:1018E0000124D4E700F10C034FF0000808EE103A91 +:1018F0004FF0800A4646444618EE100AFFF7A4FE51 +:1019000083460028C1D014220021FFF759FDC6BB31 +:10191000019BABF8083002200E9B00F108029919D8 +:101920005BFA82F20130C0B2082801D0AE422AD35D +:10193000FFF7D2FEFFF7B4FE99F80020009B411E8E +:1019400002F01F0242EA4812AE4208BF4FF0400ABE +:101950005BFA81F14AEA020A43F0004281F808A0EA +:101960008BF81000CBF8042059463846FFF7D4FD19 +:101970000134AE4224B288F001084FF0000ABBD116 +:1019800085E70020C8E711F801CB02F801CB01364A +:10199000B6B2C7E76FF0010479E70000F8B5154665 +:1019A0000E462822002104461F46FFF709FD069B2C +:1019B0006360B5F5001F079BA76034BF6A094FF647 +:1019C000FF72236204F10C0097B200239A4205D8FB +:1019D0000023036027826382A382F8BD066001337F +:1019E00030462036F2E7000003781BB94BB2002BDB +:1019F000C8BF017070470000007870472DE9F74FAD +:101A0000DDF83C90BDF830500D9E9DF83840BDF893 +:101A10004070804692469B46B9F1000F01D1002FDD +:101A200051D11F2C4FD898F80000B0B9072F47D8D4 +:101A300035F0030347D13A4649464FF6FF70FFF7AA +:101A4000F7FD20F001002D02400445EA0464400C3B +:101A500044EA40244FF6FF7321E040EA0520072FB7 +:101A600040EA0464F6D900254FF6FF73C5F1200063 +:101A7000A5F120022AFA05F10BFA00F001432BFA36 +:101A800002F211431846C9B2FFF7C0FD0835402DD8 +:101A90000346EBD13A464946FFF7CAFD0346CDE976 +:101AA0000097324621464046FFF7D4FE3378013393 +:101AB000DBB21F2B88BF0023337003B0BDE8F08F6B +:101AC0006FF00300F9E76FF00100F6E72DE9F04F42 +:101AD00085B09246DDF848800F9D9DF840209DF826 +:101AE0004490BDF84C7006469B46B8F1000F01D1FA +:101AF000002F48D11F2A46D83378002B46D00C023D +:101B000044EA02649DF8381044EAC93444EA0144C6 +:101B10001C43072F44F0800432D900234FF6FF7294 +:101B2000C3F1200CA3F120002AFA03F10BFA0CFCFC +:101B300041EA0C012BFA00F00143C9B210460393AD +:101B4000FFF764FD039B0833402B0246E8D13A4679 +:101B50004146FFF76DFD0346CDE900872A46214641 +:101B60003046FFF777FEB9F1010F06D12B7801332C +:101B7000DBB21F2B88BF00232B7005B0BDE8F08FB0 +:101B80004FF6FF73E8E76FF00100F6E76FF0030030 +:101B9000F3E70000C06900B104307047C3691A68F8 +:101BA000C261C2681A60C360438A013B43827047C6 +:101BB0002DE9F041D0F81880194E14461D464146D3 +:101BC000002709B9BDE8F081D1E90223A21A65EB2B +:101BD0000303964277EB03031ED283698B420DD138 +:101BE000FFF796FD83691B688361C3680B60438AB6 +:101BF000C1608169013B43828846E2E7FFF788FDC7 +:101C00000B68C8F80030C3680B60438AC160013BB1 +:101C10004382D8F80010D4E788460968D1E700BFAE +:101C200080841E002DE9F04F8BB00D46DDF85090FA +:101C300014469B468046002800F01981B9F1000F38 +:101C400000F01581531E3F2B00F21181012A03D1B0 +:101C5000BBF1000F40F00B810023CDE90833B8F849 +:101C60001430B5EBC30F4FEAC30703D300200BB00A +:101C7000BDE8F08F2B199F42D8F80C303ABF7F1B7C +:101C8000FFB227461BB9D8F81030002B7AD02F2D81 +:101C90004ED8C5F13006B7424FF000032CBFF6B264 +:101CA0003E4600932946D8F8080008AB3246FFF7B5 +:101CB00075FCA7EB060A35445FFA8AFAB8F81430C7 +:101CC00003F10053063BDB000493D8F80C30039378 +:101CD0003021039B13B1BAF1000F2CD1D8F81000BA +:101CE00040B1BAF1000F05D0009608AB5246691A10 +:101CF000FFF754FC38B2002FB8D066070AD00AAB01 +:101D000003EBD401624211F8083C02F007021341D0 +:101D100001F8083C082C3CD9102C40F2B580202C4E +:101D200040F2B780BBF1000F00F09C80082334E044 +:101D3000BA460026C2E7049BE02B28BFE0230693A7 +:101D40000B44AB42059314D95A1B03980096924555 +:101D500034BF5246D2B2691A08AB04300792FFF77B +:101D60001DFC079A1644AAEB020A1544F6B25FFA64 +:101D70008AFA049B069A05999B1A0493039B1B6895 +:101D80000393A6E70093D8F8080008AB3A46294623 +:101D9000AEE7BBF1000F13D00123B4EBC30F6CD03F +:101DA000082C12D89DF82030621E23FA02F2D507C3 +:101DB00006D54FF0FF3202FA04F423438DF82030A9 +:101DC0009DF8203089F8003051E7102C12D8BDF86A +:101DD0002030621E23FA02F2D10706D54FF0FF32FF +:101DE00002FA04F42343ADF82030BDF82030A9F8FE +:101DF00000303CE7202C0FD80899631E21FA03F32A +:101E0000DA0705D54FF0FF3202FA04F40C430894C8 +:101E1000089BC9F800302AE7402C2BD0DDE9086583 +:101E2000611EC4F12102A4F1210326FA01F105FA91 +:101E300002F225FA03F311431943CB0712D501220D +:101E4000A4F12003C4F1200102FA03F322FA01F104 +:101E5000A240524243EA010363EB430332432B4364 +:101E6000CDE90823DDE90823C9E90023FFE66FF087 +:101E70000100FCE66FF00800F9E6082CA0D9102C50 +:101E8000B3D9202CEED8C3E7BBF1000FADD00223AD +:101E900083E7BBF1000FBBD004237EE730B5012AF6 +:101EA000144638BF0124402C85B028BF40240025AB +:101EB000012ACDE9025518D81B788DF80830630740 +:101EC0000AD004AB03EBD405624215F8083C02F0DB +:101ED0000702934005F8083C009103462246002182 +:101EE00002A8FFF75BFB05B030BD082AE4D9102A31 +:101EF00003D81B88ADF80830E1E7202A8DBFD3E96D +:101F000000231B680293CDE90223D8E710B5CB6804 +:101F10001BB98B600B618B8210BDC4681A681C6092 +:101F2000C360438A013B4382CA60F0E72DE9F04F6A +:101F3000D1F8008093B018F0800FCDE90323C8F3E7 +:101F4000C01219BFC8F3C03BC8F306264FF0020BFE +:101F50001646B8F1000F04460D4680F2D18118F004 +:101F6000C043059340F0CC810B7B002B00F0C8816F +:101F7000BBF1020F03D00178B14240F0C48108F0F8 +:101F80007F0106916AB3C8F3074A2B44069A93F877 +:101F90000390760646EA0B4646EA82465FEAD91384 +:101FA00046EA0A06079300F0908000220023CDE95C +:101FB0000A23069B009367685B4652460AA920469F +:101FC000B84700287ED0A7699FB9314604F10C00BC +:101FD000FFF748FB0746E0B96FF0020013B0BDE819 +:101FE000F08FC8F30F2A18F07F0F08BF0AF0030A1A +:101FF000CBE73B699E420DD03F68002FF9D13146B7 +:1020000004F10C00FFF72EFB07460028E4D0A3697B +:102010003B60A761DDE90A2300264FF6FF70C6F199 +:10202000200E22FA06F103FA0EFEA6F1200C23FA86 +:102030000CFC41EA0E0141EA0C01C9B208360992D2 +:102040000893FFF7E3FA402EDDE90832E7D1B882C2 +:10205000FB7D09F01F06C3F384039B1BD7E9022114 +:1020600098B2002BBCBF00F120031BB252EA010062 +:10207000C8F304680FD00398821A049860EB01013A +:10208000A74890424FF000028A4104D3079A002AE1 +:102090005BD0012B23DDFA7D4FEA890302F00302B6 +:1020A00003F07C031343FB7539462046FFF730FBF2 +:1020B000079BA3B9FB7DC3F38402013262F386035D +:1020C000FB7504E06FF00B0088E7A76917B96FF0A4 +:1020D0000C0083E73B699E42BAD03F68F6E719F0EF +:1020E000400F32D0039BBB60049BFB601422002195 +:1020F0000DA8FFF765F9039B0A93049B0B932B1D17 +:102100000C932B7BADF83EA0013BDBB2ADF83C302D +:10211000069B8DF8433094F824308DF840B083F05E +:1021200001038DF844308DF84160A3688DF842803A +:102130000AA920469847FB7DC3F38403013303F0CB +:102140001F039B02FB82002048E7FB7DC9F340127E +:10215000B2EBD31F40F0DA80C3F38403B34240F004 +:10216000D88007992B7B4FEA9912002934D0D207E7 +:1021700041D4032B40F2D080039BBB60049BFB60E7 +:102180002B7BAE1D033BDBB23246394604F10C001B +:10219000FFF7D0FA00280DDA20463946FFF7B8FAE3 +:1021A000FB7DC3F38403013303F01F039B02FB8217 +:1021B000032013E7AB883B832A7B033AB88AD2B269 +:1021C0003146FFF735FAFB7DB882DA43C2F3C0121D +:1021D00062F3C713FB75B6E76AB92E1D013BDBB28C +:1021E0003246394604F10C00FFF7A4FA0028D3DB8D +:1021F0002A7B013AE2E7F98AC1F30901013B05298B +:10220000DAB259D8281D002307F11A0C9A4208D9CE +:1022100010F801EB0CF801E0013101330629DBB2C3 +:10222000F4D103990A9104990B91934207F11A0191 +:102230000C9138BF043379680D9134BF55FA83F39C +:1022400000230E93FB8AADF83EA0C3F309031A44A2 +:10225000069B8DF8433094F82430ADF83C2083F091 +:1022600001038DF8443000238DF840B08DF84160B3 +:102270008DF842807B602A7BB88A013A291DFFF7DE +:10228000D7F93B8BB882834203D1A3680AA92046C1 +:10229000984720460AA9FFF739FEFB7DB88AC3F3A9 +:1022A0008403013303F01F039B02FB823B8B9842A4 +:1022B00014BF1120002091E67B68002BB1D00620CE +:1022C00001E01C306346D3F800C0BCF1000FF8D128 +:1022D000091A081D05F1040C00EB030905989DF887 +:1022E000143001EB000EBEF11B0F9AD89A4298D918 +:1022F0001CF8013B09F8013B059B01330593EDE711 +:102300006FF009006AE66FF00A0067E66FF00D00F3 +:1023100064E66FF00E0061E66FF00F005EE600BF4E +:1023200080841E00F0B53D4D3D4FEB6943F00073D6 +:10233000EB61EB693B4B9B6AD3F800623E4046F091 +:102340000106C3F80062D3F800423C4044EA002092 +:1023500040F00100C3F80002002951D00020C3F86A +:102360001C020646C3F80402C3F80C02C3F81402A8 +:1023700003EBC00401300E28C4F84062C4F8446284 +:10238000F6D100274FF0010C9678148816F0010F53 +:1023900018BFD3F804E20CFA04F01CBF40EA0E0E9A +:1023A000C3F804E216F0020F1EBFD3F80CE240EAB5 +:1023B0000E0EC3F80CE2760742BFD3F81462064350 +:1023C000C3F8146203EBC4045668C4F8406296680C +:1023D000C4F84462D3F81C4201372043B942C3F821 +:1023E0001C0202F10C02CFD1D3F8002222F001022C +:1023F000C3F80022EB6923F00073EB61EB69F0BDD9 +:102400000122C3F84012C3F84412C3F80412C3F8FF +:102410001412C3F80C22C3F81C22E5E70010024096 +:102420000000FFFF80220020184A916A08B58B68DF +:102430008B6013F0010104D013F00C0F18BF4FF4A0 +:102440008031D80506D513F4406F14BF41F4003134 +:1024500041F00201D80306D513F4402F14BF41F414 +:10246000802141F00401D3690BB10848984720232B +:1024700083F311880648002100F038FE002383F31F +:102480001188BDE8084001F0AFB800BF80220020ED +:102490008822002038B5124CA36ADD68AA0712D042 +:1024A0005A6922F002025A61A36913B10121204640 +:1024B0009847202383F311880A48002100F016FE74 +:1024C000002383F31188EB0606D5A36A1021D96097 +:1024D000236A0BB102489847BDE8384001F084B840 +:1024E000802200209022002038B5124CA36A1D697A +:1024F000AA0712D05A6922F010025A61A36913B1D7 +:10250000022120469847202383F311880A4800219E +:1025100000F0ECFD002383F31188EB0606D5A36AD7 +:1025200010211961236A0BB102489847BDE8384071 +:1025300001F05AB8802200209022002038B50F4CBC +:10254000A36A5D685D602A070AD5042222701A68B2 +:1025500022F002021A60636A13B1002120469847F4 +:102560006B0706D5A36A9969236A13B10348090466 +:102570009847BDE8384001F037B800BF80220020FE +:1025800010B50E4C204600F02FFA0D4BA3620B2124 +:10259000132000F009FA0B21142000F005FA0B219A +:1025A000152000F001FA0B21162000F0FDF90022A1 +:1025B000BDE8104011460E20FFF7B4BE8022002077 +:1025C000006400400F4B984210B5044605D10E4BF5 +:1025D000DA6942F00072DA61DB69A36A01221A60EB +:1025E000A36A5A68D20707D5626851681268D96130 +:1025F0001A60064A5A6110BD0121082000F06CFCE7 +:10260000EEE700BF80220020001002405B8701003F +:1026100003291AD8DFE801F0020A0F14836A9B68C5 +:1026200013F0E05F14BF012000207047836A9868B0 +:10263000C0F380607047836A9868C0F3C0607047D9 +:10264000836A9868C0F300707047002070470000EC +:1026500010B5032925D8DFE801F00225292D836A6A +:102660009968C1F30161183103EB011310788406F6 +:102670004CBF54689488C0F300114FEA410148BF31 +:1026800041EAC40100F00F004CBF41F0040141EAEF +:102690004451586041F001019068D2689860DA6056 +:1026A000196010BD836A03F5C073DFE7836A03F521 +:1026B000C873DBE7836A03F5D073D7E701290AD033 +:1026C00002290FD081B9836ADA68920701D11869AB +:1026D00003E001207047836AD86810F0030018BF38 +:1026E00001207047836AF2E70020704710B539B9BE +:1026F000836AD96889071BD11B699C0704D110BD67 +:10270000012915D00229FAD1816AD1F8C031D1F856 +:10271000C441D1F8C8011061D1F8CC01506120202A +:1027200008610869800717D1486940F0100012E07D +:10273000816AD1F8B031D1F8B441D1F8B801106153 +:10274000D1F8BC0150612020C860C868800703D15F +:10275000486940F002004861C3F34000C3F38001C0 +:10276000000140EA4111107920F03000014311715D +:1027700089064BBF91681189DB085B0D4CBF63F381 +:102780001C0163F30A01137948BF916064F30303EA +:1027900013714FEA14234FEA144458BF1181137088 +:1027A0005480ACE7026843681143016003B11847E5 +:1027B00070470000024A136843F0C003136070477B +:1027C00000380140024A136843F0C00313607047A9 +:1027D0000044004037B51D4C1D4D204600F006FB5F +:1027E000009404F114001B490023202200F0C8F9D2 +:1027F0002022009404F13800174B184900F042FAE7 +:10280000174BC4E91735174C0C21252000F0CCF8E4 +:10281000204600F0EBFA04F1140013490094002361 +:10282000202200F0ADF904F13800104B104900945B +:10283000202200F027FA0F4B0C212620C4E917357F +:1028400003B0BDE8304000F0AFB800BFAC220020BC +:102850000051250284230020B5270008C42300204E +:102860000038014018230020A4230020C5270008B9 +:10287000E4230020004400402DE9F047C66D37688E +:10288000F46934622107054618D014F0080118BF16 +:102890008021E20748BF41F02001A30748BF41F073 +:1028A0004001600748BF41F48071202383F3118801 +:1028B000281DFFF777FF002383F31188E2050AD56F +:1028C000202383F311884FF40071281DFFF76AFF5E +:1028D000002383F311884FF020094FF0000A14F011 +:1028E000200838D13B0616D54FF0200905F1380AEB +:1028F000200610D589F31188504600F0F7F900281A +:1029000036DA0821281DFFF74DFF27F080033360DA +:10291000002383F31188790614D5620612D520238B +:1029200083F31188D5E913239A4208D12B6C33B174 +:102930001021281D27F04007FFF734FF37600023E0 +:1029400083F31188E30619D5AA6E1369B3B1BDE804 +:10295000F0475069184789F31188B38C95F86410D3 +:102960002846194000F04EFA8AF31188F469B6E758 +:1029700080B2308588F31188F469B9E7BDE8F08743 +:1029800008B50348FFF778FFBDE8084000F02CBE0B +:10299000AC22002008B50348FFF76EFFBDE80840F1 +:1029A00000F022BE1823002000F1604303F56143CC +:1029B0000901C9B283F80013012200F01F039A40F5 +:1029C00043099B0003F1604303F56143C3F8802191 +:1029D0001A60704700F16040090100F56D40C9B20E +:1029E00001767047FFF7CCBD012300F10802C0E972 +:1029F0000222037000F110020023C0E90422C0E9A2 +:102A00000633C0E9083343607047000010B5202347 +:102A1000044683F31188022303704160FFF7D2FD5F +:102A200004232370002383F3118810BD2DE9F041A6 +:102A30001F4604460D461646202383F3118800F1F5 +:102A400008082378052B0DD029462046FFF7E0FD26 +:102A500040B1204632462946FFF7FAFD002080F3B8 +:102A6000118808E03946404600F024FB0028E8D0F1 +:102A7000002383F31188BDE8F08100002DE9F041C7 +:102A80001F4604460D461646202383F3118800F1A5 +:102A900010082378052B0DD029462046FFF70EFE9F +:102AA00040B1204632462946FFF720FE002080F341 +:102AB000118808E03946404600F0FCFA0028E8D0CA +:102AC000002383F31188BDE8F0810000F8B51546B6 +:102AD00082680669AA420B46816938BF8568761A02 +:102AE000B54204460BD218462A46FEF757FCA369A6 +:102AF0002B44A361A3685B1BA3602846F8BD0CD9D7 +:102B000018463246FEF74AFCAF1BE1683A463044AD +:102B1000FEF744FCE3683B44EBE718462A46FEF721 +:102B20003DFCE368E5E7000083689342F7B515468E +:102B3000044638BF8568D0E90460361AB5420BD226 +:102B40002A46FEF72BFC63692B446361A368284681 +:102B50005B1BA36003B0F0BD0DD932460191FEF7B7 +:102B60001DFC0199E068AF1B3A463144FEF716FCA4 +:102B7000E3683B44E9E72A46FEF710FCE368E4E734 +:102B800010B50A440024C361029B8460C0E90000C0 +:102B9000C0E90511C1600261036210BD08B5D0E94A +:102BA0000532934201D1826882B982680132826023 +:102BB0005A1C42611970D0E904329A4224BFC3689A +:102BC0004361002100F086FA002008BD4FF0FF307D +:102BD000FBE7000070B5202304460E4683F31188FE +:102BE000A568A5B1A368A269013BA360531CA361BA +:102BF00015782269934224BFE368A361E3690BB1AE +:102C000020469847002383F31188284607E0314681 +:102C1000204600F04FFA0028E2DA85F3118870BDF3 +:102C20002DE9F74F04460E4617469846D0F81C90FB +:102C30004FF0200A8AF311884FF0000B154665B15A +:102C40002A4631462046FFF741FF034660B9414618 +:102C5000204600F02FFA0028F1D0002383F31188DA +:102C6000781B03B0BDE8F08FB9F1000F03D00190DD +:102C70002046C847019B8BF31188ED1A1E448AF346 +:102C80001188DCE7C0E90511C160C3611144009BF4 +:102C90008260C0E90000016103627047F8B5044634 +:102CA0000D461646202383F31188A768A7B1A368B1 +:102CB000013BA36063695A1C62611D70D4E9043250 +:102CC0009A4224BFE3686361E3690BB120469847E9 +:102CD000002080F3118807E03146204600F0EAF931 +:102CE0000028E2DA87F31188F8BD0000D0E9052357 +:102CF0009A4210B501D182687AB982680132826045 +:102D00005A1C82611C7803699A4224BFC36883619C +:102D1000002100F0DFF9204610BD4FF0FF30FBE747 +:102D20002DE9F74F04460E4617469846D0F81C90FA +:102D30004FF0200A8AF311884FF0000B154665B159 +:102D40002A4631462046FFF7EFFE034660B941466A +:102D5000204600F0AFF90028F1D0002383F311885A +:102D6000781B03B0BDE8F08FB9F1000F03D00190DC +:102D70002046C847019B8BF31188ED1A1E448AF345 +:102D80001188DCE7026843681143016003B118470A +:102D9000704700001430FFF743BF00004FF0FF33CF +:102DA0001430FFF73DBF00003830FFF7B9BF000017 +:102DB0004FF0FF333830FFF7B3BF00001430FFF798 +:102DC00009BF00004FF0FF311430FFF703BF0000D0 +:102DD0003830FFF763BF00004FF0FF323830FFF7A5 +:102DE0005DBF000000207047FFF7F4BC044B036098 +:102DF0000023C0E90233436001230374704700BF1E +:102E0000F43B000838B5C36904460D461BB90421DC +:102E10000844FFF7B7FF294604F11400FFF7BEFE90 +:102E2000002806DA201D4FF48061BDE83840FFF726 +:102E3000A9BF38BD024B0022C3E900339A60704736 +:102E400004240020002303748268054B1B689968E2 +:102E50009142FBD25A68036042601060586070472C +:102E60000424002008B5202383F31188037C032B5E +:102E700005D0042B0DD02BB983F3118808BD43690D +:102E800000221A604FF0FF334361FFF7DBFF00239E +:102E9000F2E7D0E9003213605A60F3E700230374CD +:102EA0008268054B1B6899689142FBD85A68036099 +:102EB000426010605860704704240020054B196977 +:102EC0000874186802681A6053601861012303745B +:102ED000FDF77EBB0424002030B54B1C0B4D87B0A2 +:102EE000044610D02B690A4A01A800F01BF92046BD +:102EF000FFF7E4FF049B13B101A800F02FF92B6941 +:102F0000586907B030BDFFF7D9FFF8E70424002067 +:102F1000652E000838B50C4D41612B6981689A68AF +:102F20009142044603D8BDE83840FFF78BBF1846EE +:102F3000FFF7B4FF01232C61014623742046BDE84E +:102F40003840FDF745BB00BF04240020044B1A683D +:102F50001B6990689B68984294BF002001207047CD +:102F60000424002010B5084C236820691A682260E8 +:102F70005460012223611A74FFF790FF0146206913 +:102F8000BDE81040FDF724BB0424002008B5FFF77E +:102F9000DDFF18B1BDE80840FFF7E4BF08BD000041 +:102FA000FFF7E0BFFEE7000010B50C4CFFF742FF53 +:102FB00000F0AAF80A498022204600F031F80123E7 +:102FC00044F8180C037400F0EBFA002383F3118823 +:102FD00062B60448BDE8104000F042B82C2400203E +:102FE0001C3C00082C3C000800F0CAB8EFF311802C +:102FF00020B9EFF30583202282F311887047000087 +:1030000010B530B9EFF30584C4F3080414B180F3AC +:10301000118810BDFFF7BAFF84F31188F9E70000AB +:1030200082600222028270478368A3F17C0243F827 +:103030000C2C026943F83C2C426943F8382C074AAF +:1030400043F81C2CC26843F8102C022203F8082C09 +:10305000002203F8072CA3F118007047E9050008C7 +:1030600010B5202383F31188FFF7DEFF002104460B +:10307000FFF750FF002383F31188204610BD0000A6 +:10308000024B1B6958610F20FFF718BF0424002072 +:10309000202383F31188FFF7F3BF000008B5014632 +:1030A000202383F311880820FFF716FF002383F302 +:1030B000118808BD49B1064B42681B6918605A6007 +:1030C000136043600420FFF707BF4FF0FF307047E5 +:1030D000042400200368984206D01A6802605060F9 +:1030E00059611846FFF7AEBE7047000038B5044678 +:1030F0000D462068844200D138BD036823605C60BF +:103100004561FFF79FFEF4E7054B03F11402C3E9A5 +:1031100005224FF0FF32DA6100221A62704700BFC9 +:103120000424002010B5C0E903230B4A136A536935 +:103130009C68A1420CD85C68816003604460206098 +:1031400058609868411A99604FF0FF33D36110BD01 +:103150001B68091BECE700BF04240020036881689A +:103160009A680A449A60426813605A600023C360F8 +:10317000024B4FF0FF32DA61704700BF0424002099 +:1031800038B50F4C236A22460133236252F8143FAC +:10319000934206D09A68013A9A60202563699A683A +:1031A00002B138BDD3E9001001604860D968DA6027 +:1031B00082F311881869884785F31188EEE700BF0C +:1031C0000424002000207047FEE700007047000044 +:1031D0004FF0FF3070470000BFF34F8F024AD368B3 +:1031E000DB07FCD4704700BF0020024008B5074B46 +:1031F0001B7853B9FFF7F0FF054B1A69120641BF60 +:10320000044A5A6002F188325A6008BD90250020B5 +:10321000002002402301674508B5054B1B7833B9F0 +:10322000FFF7DAFF034A136943F08003136108BD17 +:1032300090250020002002407F289ABF00F58030B2 +:10324000C0020020704700004FF40060704700008B +:10325000802070477F2808B50BD8FFF7EDFF00F5F9 +:1032600000630268013204D104308342F9D10120A5 +:1032700008BD0020FCE700007F2838B5044623D8AD +:10328000FFF7B4FEFFF7A8FFFFF7B0FF0F4BF322E5 +:10329000DA6002221A6105462046FFF7CDFF586129 +:1032A0001A6942F040021A614FF40061FFF794FF7F +:1032B00000F026F92846FFF7AFFFFFF7A1FE2046F2 +:1032C000BDE83840FFF7C6BF002038BD00200240EF +:1032D00012F001032DE9F04704460E46154606D0CC +:1032E000244B40F2BD221A600020BDE8F08781180F +:1032F000214A914204D91F4A40F2C2211160F3E7EA +:10330000FFF774FEFFF772FFFFF766FFDFF87890B4 +:1033100031464FF0010AA61B012D06EB0107884636 +:1033200005D8FFF779FFFFF76BFE0120DDE7B8F85E +:103330000030C9F810A03B800024FFF74DFFC9F80A +:1033400010403B8831F8022B9BB29A420FD0094BB8 +:1033500040F2D9221A60094B1F60094B1D60094BCE +:10336000C3F80080FFF758FFFFF74AFEBCE7023DB5 +:10337000D2E700BF8C250020000004088025002033 +:10338000882500208425002000200240084908B537 +:103390000B7828B11BB9FFF729FF01230B7008BD7B +:1033A000002BFCD0BDE808400870FFF735BF00BF18 +:1033B0009025002030B583B0FFF718FE0E4B0F4D5F +:1033C0001B6A2A684FF47A7101FB03F3934237BFFB +:1033D0000B4A0B49516814682B602EBFD1E900419C +:1033E000013151601C1941F100010191FFF708FE04 +:1033F0000199204603B030BD04240020942500200C +:103400009825002030B583B0FFF7F0FD114B124D29 +:103410001B6A2A684FF47A7101FB03F3934237BFAA +:103420000E4A0E49516814682B602EBFD1E9004145 +:10343000013151601C1941F100010191FFF7E0FDDC +:1034400001994FF47A7200232046FCF7A9FE03B0DD +:1034500030BD00BF042400209425002098250020C2 +:1034600010B50244064BD2B2904200D110BD441CAC +:1034700000B253F8200041F8040BE0B2F4E700BFBB +:10348000502800400F4B30B51C6A240407D41C6A36 +:1034900044F440741C621C6A44F400441C620A4CEC +:1034A000236843F4807323600244084BD2B29042F5 +:1034B00000D130BD441C00B251F8045B43F82050E9 +:1034C000E0B2F4E7001002400070004050280040D5 +:1034D00007B5012201A90020FFF7C2FF019803B040 +:1034E0005DF804FB13B50446FFF7F2FFA04205D0D8 +:1034F000012201A900200194FFF7C4FF02B010BD12 +:1035000070470000074B45F255521A6002225A607C +:1035100040F6FF729A604CF6CC421A60024B0122D0 +:103520001A70704700300040A4250020034B1B7820 +:103530001BB1034B4AF6AA221A607047A42500204B +:1035400000300040044B1A682AB902F1804202F5AB +:103550000432526A1A607047A0250020024B4FF0D7 +:1035600080725A62704700BF0010024008B5FFF732 +:10357000E9FF024B1868C0F3407008BDA025002089 +:10358000EFF3098305494A6B22F001024A6368336D +:1035900083F30988002383F31188704700EF00E06C +:1035A000202080F3118862B60C4B0D4AD96821F4B3 +:1035B000E0610904090C0A43DA60D3F8FC200949E8 +:1035C00042F08072C3F8FC200A6842F001020A60EF +:1035D0001022DA7783F82200704700BF00ED00E088 +:1035E0000003FA05001000E010B5202383F31188D2 +:1035F0000E4B5B6813F4006314D0F1EE103AEFF356 +:103600000984683C4FF08073E361094BDB6B2366F0 +:1036100084F30988FFF79AFC10B1064BA36110BD33 +:10362000054BFBE783F31188F9E700BF00ED00E0ED +:1036300000EF00E0FB050008FE05000870470000F1 +:10364000FEE700000A4B0B480B4A90420BD30B4B92 +:10365000DA1C121AC11E22F003028B4238BF00226C +:103660000021FDF7ADBE53F8041B40F8041BECE746 +:10367000183D0008282600202826002028260020A3 +:10368000704700004B6843608B688360CB68C36001 +:103690000B6943614B6903628B6943620B6803608A +:1036A0007047000008B51B4B9A6A42F4FC029A620C +:1036B0009A6A22F4FC029A629A6A5A6942F4FC02FB +:1036C0005A61154A5B6911464FF09040FFF7DAFFE7 +:1036D00002F11C0100F58060FFF7D4FF02F1380110 +:1036E00000F58060FFF7CEFF02F1540100F5806025 +:1036F000FFF7C8FF02F1700100F58060FFF7C2FF1D +:1037000002F18C0100F58060FFF7BCFFBDE80840C6 +:1037100000F05AB800100240443C000808B500F020 +:1037200093F9FFF741FCBDE80840FFF70BBF00002D +:103730007047000010B5214CA36A63F4FC03A36238 +:10374000A36A03F4FC03A3624FF0FF32A36A236968 +:1037500022612369002323612169E168E260E26854 +:10376000E360E268E269164942F08052E261E26990 +:103770000A6842F480720A60226A02F44072B2F56A +:10378000407F1EBF4FF4803222622362236A1B04F3 +:1037900007D4236A43F440732362236A43F400434B +:1037A000236200F031F9A369064A43F00103A361E3 +:1037B000A369136843F02003136010BD001002409A +:1037C00000700040000001401E4B1A6842F00102E8 +:1037D0001A601A689007FCD55A6822F003025A60F2 +:1037E0005A6812F00C02FBD1196801F0F901196056 +:1037F0005A601A6842F480321A601A689103FCD544 +:10380000114A5A604FF40452DA6230221A631A687D +:1038100042F080721A601A689201FCD50B4912229C +:103820000A600A6802F00702022AFAD15A6842F0D6 +:1038300002025A605A6802F00C02082AFAD11A6B86 +:103840001A6370470010024000241D00002002404F +:10385000084A08B5516913680B4003F0010353612E +:1038600023B1054A13680BB150689847BDE808407A +:10387000FFF7BABE00040140A8250020084A08B599 +:10388000516913680B4003F00203536123B1054AE9 +:1038900093680BB1D0689847BDE80840FFF7A4BE15 +:1038A00000040140A8250020084A08B551691368A2 +:1038B0000B4003F00403536123B1054A13690BB1B4 +:1038C00050699847BDE80840FFF78EBE00040140EC +:1038D000A8250020084A08B5516913680B4003F079 +:1038E0000803536123B1054A93690BB1D069984726 +:1038F000BDE80840FFF778BE00040140A82500207D +:10390000084A08B5516913680B4003F0100353616E +:1039100023B1054A136A0BB1506A9847BDE80840C5 +:10392000FFF762BE00040140A8250020174B10B528 +:103930005A691C68144004F478725A61A30604D5CD +:10394000134A936A0BB1D06A9847600604D5104AAF +:10395000136B0BB1506B9847210604D50C4A936B3F +:103960000BB1D06B9847E20504D5094A136C0BB133 +:10397000506C9847A30504D5054A936C0BB1D06CE5 +:103980009847BDE81040FFF72FBE00BF000401407C +:10399000A82500201A4B10B55A691C68144004F47D +:1039A0007C425A61620504D5164A136D0BB1506D05 +:1039B0009847230504D5134A936D0BB1D06D9847F2 +:1039C000E00404D50F4A136E0BB1506E9847A10462 +:1039D00004D50C4A936E0BB1D06E9847620404D59F +:1039E000084A136F0BB1506F9847230404D5054A5A +:1039F000936F0BB1D06F9847BDE81040FFF7F4BD4F +:103A000000040140A8250020062108B50846FEF75D +:103A1000CBFF06210720FEF7C7FF06210820FEF78F +:103A2000C3FF06210920FEF7BFFF06210A20FEF78B +:103A3000BBFF06211720FEF7B7FFBDE808400621AF +:103A40002820FEF7B1BF000008B5FFF773FE00F0B5 +:103A50000DF8FEF7C7FFFFF7C7F9FFF769FEBDE8EE +:103A6000084000F001B8000000F00EB80023054A3D +:103A700019460133102BC2E9001102F10802F8D1F6 +:103A8000704700BFA82500204FF0E023044A5A6188 +:103A900000229A6107221A6108210B20FEF79ABFC3 +:103AA0003F19010008B5202383F31188FFF79CFA22 +:103AB000002383F3118808BD08B5FFF7F3FFBDE8C5 +:103AC0000840FFF791BD000010B501390244904253 +:103AD00001D1002005E0037811F8014FA34201D085 +:103AE000181B10BD0130F2E72DE9F041A3B1C91A4E +:103AF00017780144044603F1FF3C8C42204601D96B +:103B0000002009E00578BD4204F10104F5D10CEB79 +:103B10000405D618A54201D1BDE8F08115F8018D44 +:103B200016F801EDF045F5D0E7E70000034611F87F +:103B3000012B03F8012B002AF9D170476F72672E11 +:103B40006172647570696C6F742E61705F706572FC +:103B50006970685F677073004E6F206170702073CA +:103B600069670A00426164206677206C656E67743D +:103B7000682025750A0042616420626F6172645F8B +:103B800069642025752073686F756C6420626520F8 +:103B900025750A004261642066772064657363724C +:103BA0006970746F72206C656E6774682025750A81 +:103BB00000426164206170702043524320307825B8 +:103BC0003038783A307825303878203078253038D9 +:103BD000783A3078253038780A00476F6F6420666D +:103BE00069726D776172650A0040A2E4F1646891C0 +:103BF0000600000000000000B12D00089D2D000807 +:103C0000D92D0008C52D0008D12D0008BD2D0008B4 +:103C1000A92D0008952D0008E52D00086D61696E3D +:103C20000000000069646C6500000000243C00088E +:103C3000482400208025002001000000A52F000856 +:103C400000000000A001A82A00000000FAAABEAAF5 +:103C500050001424EFFF0000007700007097090067 +:103C60000100000000000000AAAAAAAA01000000AA +:103C7000FFFF000000000000000000000000000046 +:103C800000000000AAAAAAAA00000000FFFF00008E +:103C90000000000000000000000000000000000024 +:103CA000AAAAAAAA00000000FFFF0000000000006E +:103CB000000000000000000000000000AAAAAAAA5C +:103CC00000000000FFFF00000000000000000000F6 +:103CD0000000000000000000AAAAAAAA000000003C +:103CE000FFFF00000000000000000000E4C4FF7FB0 +:103CF0000100000000000000EC03000000000000D4 +:103D000000980300000000006400000000000000B4 +:083D1000FE2A0100D2040000AC :00000001FF diff --git a/Tools/bootloaders/f303-HWESC_bl.bin b/Tools/bootloaders/f303-HWESC_bl.bin index 3d48e3f3510..b03410ae096 100755 Binary files a/Tools/bootloaders/f303-HWESC_bl.bin and b/Tools/bootloaders/f303-HWESC_bl.bin differ diff --git a/Tools/bootloaders/f303-HWESC_bl.hex b/Tools/bootloaders/f303-HWESC_bl.hex index 03a78f29d5d..9b0eeda4989 100644 --- a/Tools/bootloaders/f303-HWESC_bl.hex +++ b/Tools/bootloaders/f303-HWESC_bl.hex @@ -1,1095 +1,980 @@ :020000040800F2 -:1000000000090020E1040008991400089D1400086C -:10001000F11400089D140008C5140008E30400084A -:10002000E3040008E3040008E30400085D37000867 -:10003000E3040008E3040008E3040008013C0008AE -:10004000E3040008E3040008E3040008E3040008F4 -:10005000E3040008E3040008E5390008113A000849 -:100060003D3A0008693A0008953A0008E3040008A0 -:10007000E3040008E3040008E3040008E3040008C4 -:10008000E3040008E3040008E3040008092600086C -:1000900075260008C92600081D270008C13A000877 -:1000A000E3040008E3040008E3040008E304000894 -:1000B000E3040008E3040008E3040008E304000884 -:1000C000E3040008E3040008E3040008E304000874 -:1000D000E3040008D92A0008ED2A0008E304000818 -:1000E000293B0008E3040008E3040008E3040008D7 -:1000F000E3040008E3040008E3040008E304000844 -:10010000E3040008E3040008E3040008E304000833 -:10011000E3040008E3040008E3040008E304000823 -:10012000E3040008E3040008E3040008E304000813 -:10013000E3040008E3040008E3040008E304000803 -:10014000E3040008E3040008E3040008E3040008F3 -:10015000E3040008E3040008E3040008E3040008E3 -:10016000E3040008E3040008E3040008E3040008D3 -:10017000E3040008E3040008E3040008E3040008C3 -:10018000E3040008E3040008E3040008E3040008B3 -:10019000E3040008E3040008E3040008E3040008A3 -:1001A000D0400B1CD1409C46203AD34018435242C9 -:1001B00063469340184370479140031C90409C460F -:1001C000203A9340194352426346D3401943704743 -:1001D00053B94AB9002908BF00281CBF4FF0FF31AE -:1001E0004FF0FF3000F07AB9ADF1080C6DE904CEA4 -:1001F00000F006F8DDF804E0DDE9022304B0704702 -:100200002DE9F0478C460D460446089E002B51D13F -:100210008A4217466DD9B2FA82FEBEF1000F0BD0AA -:10022000CEF1200C01FA0EF520FA0CFC02FA0EF7C2 -:100230004CEA050C00FA0EF44FEA174A250CBCFBF9 -:10024000FAF81FFA87F90AFB18CC45EA0C4508FBB7 -:1002500009F3AB420AD9ED1908F1FF3280F023818E -:10026000AB4240F22081A8F102083D44ED1AA4B24D -:10027000B5FBFAF00AFB105544EA054400FB09F906 -:10028000A14509D9E41900F1FF3380F00A81A145A5 -:1002900040F2078102383C44A4EB090440EA0840DC -:1002A0000021002E61D024FA0EF400233460736024 -:1002B000BDE8F0878B4207D9002E54D0002186E894 -:1002C00021000846BDE8F087B3FA83F1002940F029 -:1002D0008E80AB4202D3824200F2FA80841A65EB30 -:1002E00003050120AC46002E3FD086E81010BDE883 -:1002F000F08712B90127B7FBF2F7B7FA87FEBEF114 -:10030000000F34D1EB1B3A0C1FFA87FC0121B3FB21 -:10031000F2F8250C02FB183345EA03450CFB08F301 -:10032000AB4207D9ED1908F1FF3002D2AB4200F21F -:10033000D1808046ED1AA3B2B5FBF2F002FB105556 -:1003400043EA05440CFB00FCA44507D9E41900F17D -:10035000FF3302D2A44500F2B8801846A4EB0C0487 -:1003600040EA08409DE731463046BDE8F087CEF1CF -:10037000200405FA0EF307FA0EF720FA04F83A0CF7 -:1003800025FA04F448EA0308B4FBF2F14FEA1845F1 -:1003900002FB11441FFA87FC45EA044501FB0CF3FC -:1003A000AB4200FA0EF409D9ED1901F1FF3080F0EB -:1003B0008A80AB4240F2878002393D44EB1A1FFA33 -:1003C00088F5B3FBF2F002FB103345EA034500FB6E -:1003D0000CF3AB4207D9ED1900F1FF386FD2AB42F5 -:1003E0006DD902383D44EB1A40EA01418FE7C1F173 -:1003F000200722FA07F88B4005FA01F448EA0303C4 -:1004000020FA07FE4FEA134CFD404EEA040EB5FBFE -:10041000FCF94FEA1E440CFB19551FFA83F844EA15 -:10042000054509FB08F4AC4202FA01F200FA01FAB0 -:1004300008D9ED1809F1FF3043D2AC4241D9A9F1F6 -:1004400002091D442D1B1FFA8EFEB5FBFCF00CFBB0 -:1004500010554EEA054400FB08F8A04507D9E418FA -:1004600000F1FF3529D2A04527D902381C4440EAC3 -:100470000940A4EB0804A0FB02894C45C6464D4642 -:1004800015D312D056B1BAEB0E0364EB050404FA8F -:1004900007F7CB401F43CC40376074600021BDE8B4 -:1004A000F0871846F8E69046E0E6C245EAD2B8EB97 -:1004B000020E69EB03050138E4E72846D7E740461A -:1004C00091E78146BEE7014678E702383C4445E7BC -:1004D000084608E7A8F102083D442BE7704700BF33 -:1004E00002E000F000F8FEE772B6394880F30888B1 -:1004F000384880F3098838484EF60851CEF200019A -:10050000086040F20000CCF200004EF63471CEF2EA -:1005100000010860BFF34F8FBFF36F8F40F2000000 -:10052000C0F2F0004EF68851CEF200010860BFF331 -:100530004F8FBFF36F8F4FF00000E1EE100A4EF6C1 -:100540003C71CEF200010860062080F31488BFF3EE -:100550006F8F03F041F903F06DF94FF055301F49EB -:100560001B4A91423CBF41F8040BFAE71C49194A67 -:1005700091423CBF41F8040BFAE71A491A4A1B4B57 -:100580009A423EBF51F8040B42F8040BF8E70020F2 -:100590001749184A91423CBF41F8040BFAE703F0AF -:1005A0001FF903F089F9144C144DAC4203DA54F8E6 -:1005B000041B8847F9E700F03FF8114C114DAC429D -:1005C00003DA54F8041B8847F9E703F007B9000081 -:1005D0000009002000110020000000080001002098 -:1005E00000090020D04300080011002074110020F1 -:1005F0007811002090260020A0010008A00100082A -:10060000A0010008A00100082DE9F04F2DED108A8F -:10061000C1F80CD0C3689D46BDEC108ABDE8F08FD0 -:10062000002383F311882846A047002002F070FEC3 -:1006300002F09AFD00DFFEE7384B6FF013022DE960 -:10064000F0416FF0670100241A7003225A709C7009 -:10065000DC701C715C719C71DC711C7259729A7235 -:10066000DC7203F025F8074603F072F80546C8BBB4 -:100670002B4B9F4238D001339F4238D0294B27F073 -:10068000FF029A4237D1F8B200F052FAA84642F27D -:10069000107400F07BFC00F051FA064678B384BB7E -:1006A000464635B1204B9F4203D003F049F8002461 -:1006B0002646002003F006F81C4B1B6913F040038C -:1006C00022D00EB100F034F800F082FC00F016FEEB -:1006D00000F022FF0546CCB900F0D0FC012002F06A -:1006E0001DFEF8E78046D4E780460446D1E704467D -:1006F0004FF00108CDE780464FF47A74C9E704460D -:10070000CFE74FF47A74CCE71C46DDE700F004FF36 -:10071000401BA042E0D900F00BF8D9E77811002087 -:10072000010007B0000008B0263A09B000040048F4 -:1007300010B51C4B1C4953F8042F013200D110BDD9 -:100740008B42F8D1194C1A4B22689A4228D9194B7E -:100750009B6803F1006303F5D0439A4220D202F074 -:10076000C3FF02F0D5FF002000F0E2FD124B022093 -:10077000187000F019FE114BDA690022DA61D969AC -:1007800099699A619B6972B60D4A0E4B13601B689A -:100790002268202181F311889D4683F30888104741 -:1007A00010BD00BFFC6700081C6800080468000852 -:1007B000FF6700087811002084110020001002401B -:1007C00008ED00E00068000809490B6849F269007B -:1007D0009AB21B0C00FB0233064A0B60136844F20A -:1007E000506198B21B0C01FB0030106080B2704762 -:1007F0000C1100200811002010B500211022044621 -:1008000000F0ECFD034B03CB206061601868A06032 -:1008100010BD00BFACF7FF1FF0B51F4CBBB000F020 -:100820007BFEA368C31AF92B30D906AD2346A0601E -:1008300028220021284601F0FDFB04F10E0000F003 -:10084000C5FD0023C6B2591D5F1CDBB2B3424FEA9F -:10085000C10107DA0E3323440822284601F0EAFBDF -:100860003B46F0E7012303930823207B02930B4BC5 -:100870000193C1F3CF013023059100930146049504 -:1008800003A3D3E90023064801F0A4F93BB0F0BD6F -:1008900078F6339F93CACD8DC8210020D521002042 -:1008A000A021002070B50D4614461E4601F038F90F -:1008B00050B9022E0ED1012C0CD112A3D3E9002382 -:1008C000C5E90023012070BD052C14D003D8012CEC -:1008D00009D0002070BD282C09D0302CF9D10BA3F1 -:1008E000D3E90023ECE70BA3D3E90023E8E70BA34C -:1008F000D3E90023E4E70BA3D3E90023E0E700BF3B -:10090000AFF30080401DA12026812A0B78F6339F8B -:1009100093CACD8D9E6AC421818A46EE26417272A9 -:10092000DF25D7B7F017304A39059E5638B504464B -:100930000D46034620222846002101F07BFB227948 -:100940002346032A28BF032203F8042F2846022245 -:10095000202101F06FFB62792346072A28BF072276 -:1009600003F8052F28460322222101F063FBA27918 -:100970002346072A28BF072203F8062F284603220A -:10098000252101F057FB284604F1080310222821F5 -:1009900001F050FB382038BD2DE9F04FADF5017D59 -:1009A00021AE0EAD40F2791280460F46304600214E -:1009B00000F014FD48220021284600F00FFD00F051 -:1009C000ABFD594B4FF47A72B0FBF2F0186093E82C -:1009D0000700012385E807002B740DF15A0000235E -:1009E0006B74FFF709FF032385F82030EC2385F8AB -:1009F000213006AB18464D4903F06CF91D222864DE -:100A00003146284685F83C20FFF790FF12AB04469C -:100A100001460822304601F00DFB0822A1180DF115 -:100A20004903304601F006FB0DF14A03082204F1A8 -:100A30001001304601F0FEFA13AB202204F1180138 -:100A4000304601F0F7FA14AB402204F13801304689 -:100A500001F0F0FA16AB082204F17801304601F0FB -:100A6000E9FA0DF15903082204F18001304601F042 -:100A7000E1FA04F1880A0DF15A0904F5847B4B462A -:100A80005146082230460AF1080A01F0D3FAD3454C -:100A900009F10109F3D11BAB08225946304601F098 -:100AA000C9FA04F588744FF0000995F834304B45C5 -:100AB00010D84FF0000995F83C304B4515D92B6CF8 -:100AC00021464B440822304601F0B4FA083409F1BB -:100AD0000109F0E7AB6B21464B440822304601F098 -:100AE000A9FA083409F10109DFE7E31DC3F3CF03D5 -:100AF000F97E0593002304960393BB7E0293193776 -:100B000001230093019706A3D3E90023404601F097 -:100B100061F80DF5017DBDE8F08F00BFAFF30080F7 -:100B20009E6AC421818A46EE88110020AC3E0008EE -:100B3000014B1870704700BF94110020F0B5334B83 -:100B40001C7B85B034B1324B0E221A810024204622 -:100B500005B0F0BD2F4A1068516802AB03C30823EB -:100B60000DEB03022C492D4803F096F8054630B9E9 -:100B7000274B2B480A221A8100F084FCE6E7016922 -:100B8000B1F5663F06D9224B26480B221A8100F0A8 -:100B900079FCDCE7438BB3F57B7F09D01C4A224804 -:100BA0000C2111814FF47B72194600F06BFCCEE7EB -:100BB0001E4A024402F11003994204D2144B1C480D -:100BC00010221A81E3E710398E1A2046134900F0EB -:100BD000A7FC3246074605F11801204600F0A0FCAC -:100BE000AB689F4202D1EB6898420AD0084B0D22B5 -:100BF0001A8100903B46EA68A9680E4800F042FC62 -:100C0000A4E70D4800F03EFC0124A0E7C821002025 -:100C1000881100207C3D0008DC9703000068000874 -:100C2000843D0008903D0008A23D00080898FFF7A9 -:100C3000C03D0008DD3D0008063E00082DE9F04FEC -:100C4000ADB006AF80460C4600F06AFF05460028AE -:100C50006AD1237E022B18D1E38A012B15D100F033 -:100C60005BFC8146FFF7B0FD4FF4C873BD4EB0FB8F -:100C7000F3F209F5167902FB1300E37E19FA80F00E -:100C800030608BB9B84B00221A709C37BD46BDE866 -:100C9000F08F3B1D1D440095002308224FEAC90137 -:100CA000204601F02BF84D46A38A013BAB425FFA88 -:100CB00085F90BD905F10109B9F1110FE9D1AB4B58 -:100CC000AB4A40F23911AB4802F0B8FF07F114000B -:100CD000FFF792FD2A4607F11401381D02F0CCFF00 -:100CE00003460028CED1B9F1100F07D09E4B83F8F0 -:100CF00000903368A3F516733360C6E707F19802D6 -:100D0000014602F8950D20460092072200F0F6FFFA -:100D1000F9787F2904DD984B954A4FF4A871D2E702 -:100D2000404600F0E1FEB0E7E38A052B00F00681C3 -:100D300006D8012BA9D121464046FFF72DFEA4E796 -:100D4000282B3DD0302BA0D1637E8C4D01336A7BA4 -:100D5000DBB29342E94640F0EF80E27E2B7B9A4281 -:100D600040F0EA8007F19803002623F8846D1022F2 -:100D7000009331460123204600F0C0FFB4F81480F0 -:100D8000A8F102081FFA88F808F1030323F003030F -:100D90000A3323F00703ADEB030D0DF1180A3346B8 -:100DA0009BB2B11C98454FEAC10106F101066CDD0A -:100DB0005344009308220023204600F09FFFEEE7F3 -:100DC000A38A013B9BB2C92B3FF65FAF6B4E357BCD -:100DD0004DBB06F10C03009308222B462946204602 -:100DE00000F08CFFA38A05F10109013BEDB29D42A1 -:100DF0004FEAC90109DA0E3535440095002308226F -:100E0000204600F07BFF4D46ECE700230022C6E9B8 -:100E100000230023B36086F8D730C6F8D830337B80 -:100E20000BB9E37E3373002507F114063B1D08223E -:100E3000294630467D60BD60FD6001F0FBF83B7ADD -:100E400005F10109AB424FEAC90107D9FB68082245 -:100E50002B44304601F0EEF84D46F0E7C1F3CF01E8 -:100E60000023E07E059104960393A37E0293193438 -:100E7000282301460093019438A3D3E90023404678 -:100E800000F0A8FEFFF7C8FCFFE695F8D70000F0D9 -:100E900059FAD5F8D83006461BB995F8D70000F0B6 -:100EA00061FAD5F8D83043449E4204D295F8D70071 -:100EB000013000F057FA4FEA980B0024A0B25845D1 -:100EC00004F1010408DA2B6880000AEB000101221A -:100ED000184400F08BFAF1E7D5E90023D5F8D840A3 -:100EE00095F8D70012EB080243F100034444C5E92A -:100EF0000023C5F8D84000F025FA844209D395F8BC -:100F0000D730013385F8D730D5F8D8309E1BC5F8D7 -:100F1000D860B8F1FF0F08DC00232B7300F034FA1F -:100F2000FFF70CFE08B1FFF703FC2B68144A9B0A7D -:100F3000013313810023AB60CD46A6E6BFF34F8F8C -:100F40001049114BCA6802F4E0621343CB60BFF34F -:100F50004F8F00BFFDE700BFAFF3008026417272E4 -:100F6000DF25D7B79C21002099210020183E0008DA -:100F7000CC3E0008713E0008933E0008C8210020C6 -:100F80008811002000ED00E00400FA0508B54FF0DC -:100F900000530B4A196891420AD10A4A597D1170CF -:100FA00009481B7D0373C92208490E3000F004FA7A -:100FB000E02200214FF00050BDE8084000F00EBADA -:100FC0009AAD44C594110020C821002016000020CD -:100FD00030B5204C2049214885B002236371042399 -:100FE0000025ADF808300123ADF80C5007228DF82C -:100FF0000C308DF80B301A4B4B608DF80A2001F045 -:1010000003FE184B019500931749184B18484FF4ED -:10101000805200F033FD174B1978254611B1144862 -:1010200000F062FD00F078FA0446FFF7CDFB4FF4C4 -:10103000C87304F51674B0FBF3F202FB13000E4BF9 -:1010400014FA80F0186002F083FB08B10F232B81A3 -:1010500005B030BD8811002000110020E0220020E2 -:1010600003000600A5080008981100203D0C0008A8 -:10107000A0210020941100209C2100202DE9F04F98 -:1010800094A7D7E900670FF25429D9E900898D4C5C -:1010900093B0DFF850B2DFF850A2204600F0E6FD32 -:1010A0000CAD079098B310220021284600F096F965 -:1010B000079B197B4FF0000261F3030219468DF87C -:1010C000302051F8040F49680EAA03C21B680D9A1C -:1010D00063F31C029DF830300D9243F020038DF82D -:1010E000303000232A461946584601F09DFD0790EE -:1010F00030B9204600F0BEFD079B8AF80030CCE7EF -:101100009AF80030072B3EDC01338AF800301822B1 -:101110000021284600F062F9DFF8C8A10023194633 -:101120002A46504601F0A8FD014680BB102208A8BF -:1011300000F054F94FF09042536983F0100353616B -:1011400000F0ECF90B4612A9024611E903000DF17B -:10115000240E8EE803009DF83410C1F303008906C5 -:101160004CBF0E99BDF838108DF82C0046BFC1F366 -:101170001C0141F00041C1F30A010891204608A971 -:1011800000F0BEFFCAE7204600F074FDBFE720462E -:1011900000F0C6FC824600284AD1DFF850B100F0CA -:1011A000BBF9DBF80030984242D300F0B5F9079064 -:1011B000FFF70AFB079A8DF820A04FF4C87302F5D9 -:1011C0001672B0FBF3F101FB130012FA80F0CBF8BA -:1011D0000000DFF81CB19BF8001011B901238DF855 -:1011E000203028460791FFF707FB0799C1F1100A45 -:1011F0005FFA8AFABAF1060F28BF4FF0060A524684 -:1012000029440DF1210000F0D7F80AF101030493FD -:1012100008AB0393182302932B4B019301230093F4 -:1012200032463B46204600F07DFC00238BF8003020 -:1012300000F072F9254ADFF8BCA01368C31AB3F5B1 -:101240007A7F32D3106000F069F902460B462046DF -:1012500000F016FD204600F063FC30B39AF80C3025 -:10126000DFF894B0002B14BF032302238BF8053062 -:1012700000F052F94FF47A732946B0FBF3F0CBF843 -:1012800000005846FFF752FB182307300293104B1B -:101290000193C0F3CF0040F25513049000930395DF -:1012A00042464B46204600F03DFC9AF80C300BB10C -:1012B000FFF7B2FA9AF80C30002B7FF4EAAE13B0C5 -:1012C000BDE8F08FA021002098210020A822002056 -:1012D000AC220020401DA12026812A0BF1C6A7C107 -:1012E000D068080FE0220020AD2200209C210020C1 -:1012F00099210020C82100208811002070B502F03B -:10130000C3F8094C094E20700025306823788342C9 -:1013100008D902F0B5F8336805440133B5F5D04F6C -:101320003360F2D370BD00BFDC220020B022002069 -:1013300002F042B900F10060920000F5D04002F0E6 -:10134000E7B80000054B1A68054B1B789B1A8342CF -:1013500002D9104402F094B800207047B022002057 -:10136000DC22002038B5074D04462868204402F0EE -:101370008DF828B928682044BDE8384002F098B8B4 -:1013800038BD00BFB0220020064991F8243033B1A7 -:1013900000230822086A81F82430FFF7CBBF012020 -:1013A000704700BFB4220020022802BF4FF09043D4 -:1013B0004FF480129A61704710B50023934203D016 -:1013C000CC5CC4540133F9E710BD0000024603466B -:1013D000981A13F9011B0029FAD1704702440346F9 -:1013E000934202D003F8011BFAE770472DE9F0475A -:1013F000234C94F8243005468846174683BB2E4676 -:10140000DFF87C90C7B394F824302BB92022FF2159 -:1014100048462662FFF7E2FF94F82400C0F1080571 -:10142000BD4228BF3D465FFA85FAAD0041462A46D7 -:1014300004EB8000FFF7C0FF94F82430A7EB0A0705 -:101440009A445FFA8AFABAF1080F2E44A844FFB210 -:1014500084F824A0D6D1FFF797FF0028D2D108E066 -:10146000266A06EB8306B042CAD0FFF78DFF00283C -:10147000C5D10020BDE8F0870120BDE8F08700BF9E -:10148000B42200200FB4002004B070470FB44FF016 -:10149000FF3004B070470000FEE7000000B59BB0CD -:1014A000EFF3098168226846FFF786FFEFF30583B3 -:1014B000034B9A6B9A6A9A6A9A6A9A6A9B6AFEE7DF -:1014C00000ED00E000B59BB0EFF3098168226846AB -:1014D000FFF772FFEFF30583044B9A6B9A6A9A6ADF -:1014E0009A6A9A6A9A6A9B6AFEE700BF00ED00E07A -:1014F00000B59BB0EFF3098168226846FFF75CFFF7 -:10150000EFF30583034B5A6B9A6A9A6A9A6A9A6A4E -:101510009B6AFEE700ED00E002F086B802F060B8DA -:1015200030B5084D0A4491420BD011F8013B092413 -:101530005840013CF7D040F300032B4083EA5000B1 -:10154000F7E730BD2083B8ED0246006848B1036874 -:101550001360D388118901339BB29942D38038BF7D -:101560001381704770B588B00D46044620220021D3 -:101570006846FFF733FF20460495FFF7E5FF054671 -:1015800058B16B46044608AE1A4603CAB242206000 -:101590006160134604F10804F6D1284608B070BD16 -:1015A0002DE9F04130B9274B274A40F2C531274891 -:1015B00002F044FB0B7C23B9254B234A40F2C63191 -:1015C000F5E7C66986B9C161BDE8F081002B29DA6B -:1015D000930CAB4229D1B44201D10C60F3E7C8F8B7 -:1015E00000100C60BDE8F0814B6823F06047BD0C33 -:1015F0004FEAD37EC3F3807C15EA230538BF3D460E -:10160000B04634466368BEEBD37F23F06042DDD141 -:10161000974203D1C3F380739C450AD1974205E0FA -:101620001C46EFE7AA4206D013469D422CBF00237A -:101630000123002BCFD12368A046002BF0D12160DD -:10164000BDE8F081A0410008943F0008584200081E -:101650007942000808B5034A034B044840F25E3162 -:1016600002F0ECFA703F00081842000858420008E7 -:1016700008B503680B60C388016033B9044B054AA1 -:1016800005484FF4C76102F0D9FA013BC38008BD99 -:10169000E8410008E43F00085842000870B50C46D5 -:1016A00000F10C05616831B9E38A61F30903E38253 -:1016B0000020002170BD0E682846FFF7D9FF666044 -:1016C000F0E7000008B5426832B10B4B0B4A0C48FA -:1016D00040F22F4102F0B2FAC37DC3F3840101311D -:1016E00061F38603C375C38A62F30903C3821B0ACD -:1016F00062F3C713C37508BD34420008A03F000859 -:10170000584200082DE9F047089E32B91F4B204A85 -:10171000204840F2395102F091FA01F007054FEAF2 -:10172000D6082A4406F0070600EBD1004FF47F49A3 -:10173000954201D1BDE8F08705F0070E06F0070AD3 -:10174000D645774638BF5746C7F10807511BEC0806 -:101750008F4228BF0F46045D08EBD60104FA0EF451 -:1017600013F801C029FA07FE24FA0AF45FFA8EFE84 -:101770008CEA04044EFA0AFE04EA0E048CEA040C15 -:1017800003F801C03D443E44D2E700BFB441000825 -:10179000B83F0008584200082DE9F04106460F46C0 -:1017A00000254FF6FF7441F221082A46304639469B -:1017B000FEF7F6FCC0B284EA0024082314F4004FBC -:1017C0004FEA4404A4B203F1FF3318BF84EA0804CB -:1017D00013F0FF03F2D10835402DE6D12046BDE8D5 -:1017E000F081000010B50A4441F22104914200D179 -:1017F00010BD11F8013B80EA0320082310F4004FCC -:101800004FEA400080B203F1FF3318BF604013F08D -:10181000FF03F3D1EAE700002DE9F04F85B08A46D7 -:101820008DE80C00BDF83C40814630B9494B4A4A2E -:1018300040F26E31494802F001FA11F0604F04D0D5 -:10184000474B454A40F26F31F4E7009B002B7ED0B6 -:1018500024B10E9B002B7AD0072C28D809F10C005C -:10186000FFF772FE054628B96FF00205284605B05D -:10187000BDE8F08F14220021FFF7B0FD22460E993B -:1018800005F10800FFF798FD631C2B74009B1B7883 -:101890002C4403F01F0363F03F0323724AF000431C -:1018A0006B6029464846FFF77BFE0125DEE7019B7A -:1018B0001B0A4FF00008029300F10C034FF0800B5D -:1018C0004646454603930398FFF73EFE0746002829 -:1018D000CAD014220021FFF781FDB6BB9DF8043069 -:1018E0003B729DF808307B7202220E9B711E1944D8 -:1018F000B4420AD9B8180132D2B211F801EF80F817 -:1019000008E00136072AB6B2F2D1009B197801F03F -:101910001F01B44208BF4FF0400BB81841EA48110C -:101920004BEA0103037201324AF000437B603A74D0 -:1019300039464846FFF734FE0135B4422DB288F0EF -:1019400001084FF0000BBED190E70022CDE76FF009 -:1019500001058BE7A0410008843F000858420008B9 -:10196000C44100082DE9F0471E46CB8A9146C3F3D7 -:101970000902062A80460F4619D013460021B0B24C -:101980008DB25A1992B2052A09D9A84210D8FA8AFA -:10199000034463F30902FA820120BDE8F087A842FC -:1019A000F3D93A4419F8014094760131E8E700256B -:1019B000FB8A7C68C3F30900821F1C23B2FBF3FA85 -:1019C00003FB1A2A1FFA8AF27CB301212368002B39 -:1019D00039D1B31F03441C20B3FBF0F301339BB296 -:1019E00099420CD2BAF1000F09D14046FFF7ACFD85 -:1019F00008B1C0F800A0206008B304460022B6B2C7 -:101A00004FF0000AB54230D2691E49441346E0182F -:101A100001339BB211F801EF80F804E001351C2B73 -:101A2000ADB214D0AE42F2D8ECE74046FFF78CFDE1 -:101A3000044608B1002303607C60002CDED16FF007 -:101A40000200BDE8F087013189B21C46BEE7AE4214 -:101A5000D8D94046FFF778FD08B1C0F800A0206053 -:101A60000028ECD004460022CCE7FB8AC3F309022D -:101A7000164466F30903FB828EE70000F8B50E46B4 -:101A800015461F46044628B9144B154A15484F21E0 -:101A900002F0D4F824220021FFF7A0FC069B63602B -:101AA000079B23626A094FF6FF739A424FF00000CA -:101AB00028BF1A46A7602070A061E06197B204F1C8 -:101AC0000C05824205D100232B6027826382A3820A -:101AD000F8BD2E60013035462036F2E79C41000803 -:101AE000103F00085842000808B528B9084B094AB9 -:101AF0007321094802F0A2F8037823B94BB2002BF6 -:101B000001DD017008BD054B024A7D21F1E700BFF0 -:101B1000A04100081C3F000858420008E4400008AB -:101B2000007870472DE9F7430D9EBDF828900B9D76 -:101B30009DF83040BDF8388007461946104616B962 -:101B4000B8F1000F43D11F2C41D83B78D3B9B8F17D -:101B5000070F39D839F0030339D1424631464FF6E1 -:101B6000FF70FFF73FFE4FEA092920F0010009F45A -:101B70004079400449EA0464400C44EA40244FF6AA -:101B8000FF730DE043EA0923B8F1070F43EA046449 -:101B9000F5D9FFF701FE42463146FFF723FE034623 -:101BA0008DE840012A4621463846FFF735FE0DB93B -:101BB000FFF750FD2B780133DBB21F2B88BF0023CA -:101BC0002B7003B0BDE8F0836FF00300F9E76FF00E -:101BD0000100F6E72DE9F7430E9F0B9D9DF8348039 -:101BE000BDF83C6081469DF8300007B9C6BB1F2890 -:101BF00036D899F800E0BEF1000F34D00C0244F062 -:101C000080049DF8281044EAC83444EA014444EAB8 -:101C10000E04072E44EA006415D919461046FFF752 -:101C2000BBFD32463946FFF7DDFD034601960097BE -:101C30002A4621464846FFF7EFFDB8F1010F0CD1C7 -:101C400025B9FFF707FD4FF6FF73EFE72B78013358 -:101C5000DBB21F2B88BF00232B7003B0BDE8F083DD -:101C60006FF00100F9E76FF00300F6E7C06900B11B -:101C700004307047C1690B68C3610C30FFF7F8BCD2 -:101C80002DE9F84FD0F818A0DFF86C80054616460D -:101C90001F4654464FF0000900F10C0B0CB9BDE88B -:101CA000F88FD4E90223B21A67EB0303994508BF02 -:101CB00090451FD2AB699C42214628460DD1FFF7C3 -:101CC000EDFCAB691B68AB6121465846FFF7D0FCC1 -:101CD000AC692346A2461C46E0E7FFF7DFFC236819 -:101CE000CAF8003021465846FFF7C2FC5446DAF8DD -:101CF0000030EFE72368EDE780841E002DE9F04F08 -:101D00008BB00D4614460793DDF8509082460028AC -:101D100000F06481B9F1000F00F06081531E3F2B89 -:101D200000F25C81012A03D1079B002B40F0568111 -:101D3000BAF81460F6000023B5420893099380F0C6 -:101D400053812B199E420AD2761B16F0FF0607D14B -:101D5000AB4BAC4A40F26751AB4801F06FFF2646EF -:101D6000DAF80C3023B9DAF81030002B00F0A58037 -:101D70002F2D31D8C5F1300846454FF000032CBF58 -:101D80005FFA88F8B0460093294608AB4246DAF875 -:101D90000800FFF7B7FCA6EB08074544FFB2BAF806 -:101DA000143003F10053063BDB000293DAF80C30E9 -:101DB00005934FF0300B059B002B51D087B9DAF813 -:101DC0001000002861D0002F5FD0AB4550D98F4B59 -:101DD0008C4A40F2A651BFE737464FF00008DEE7D5 -:101DE000029B23B98A4B874A4FF4B161B4E7029B47 -:101DF000E02B28BFE02306935B44AB4204931DD93C -:101E00005B1B9F4226BFDBB203930397AB4504D90C -:101E10007E4B7C4A40F291519EE70598CDF80080B8 -:101E200008ABA5EB0B01039A0430FFF76BFC039B97 -:101E30009844FF1A1D445FFA88F8FFB2049B9B4543 -:101E400004D3744B6F4A40F29B5185E7029B069A7C -:101E5000DDF810B09B1A0293059B1B680593AAE757 -:101E6000029BBB42ABD26C4B664A40F2A15173E776 -:101E7000CDF800803A46A5EB0B0108ABFFF742FC1A -:101E8000B8443D445FFA88F80027BAF81430B5EB3F -:101E9000C30F04D9614B5B4A40F2B1515CE7B8F122 -:101EA000400F04D95E4B574A40F2B25154E767B134 -:101EB0005C4B544A40F2B3514EE70093324608ABB4 -:101EC0002946DAF80800FFF71DFC731E3F2B35B2D8 -:101ED00001D8A64204DD544B544A40F235213BE779 -:101EE00060070AD00AAB03EBD401624211F8083C48 -:101EF00002F00702134101F8083C082C21D9102CEC -:101F000021D9202C8CBF08230423079A002A6DD0E6 -:101F1000B4EBC30F6CD0082C04F1FF3215D89DF838 -:101F2000203023FA02F2D10706D54FF0FF3202FA31 -:101F300004F423438DF820309DF8203089F80030D8 -:101F40004EE00123E1E70223DFE7102C11D8BDF8B2 -:101F5000203023FA02F2D20706D54FF0FF3202FA00 -:101F600004F42343ADF82030BDF82030A9F8003048 -:101F700036E0202C0ED8089921FA02F2D30705D5B5 -:101F80004FF0FF3303FA04F40C430894089BC9F89C -:101F9000003025E0402C1CD0DDE90867304639468A -:101FA000FEF7FEF8002100F0010050EA01030BD01B -:101FB000224601200021FEF7FFF8404261EB41017B -:101FC00006430F43CDE90867DDE90823C9E900238B -:101FD00006E0174B154A4FF42071BDE66FF001057E -:101FE00028460BB0BDE8F08F1D46F9E7012CA3D0C1 -:101FF000082CA1D9102CB7D9202CE5D8C6E700BFF2 -:10200000F03F0008C83F000858420008124000088E -:10201000FF3F0008374000085F4000088640000886 -:10202000B4400008CC400008E6400008483F0008E3 -:10203000E440000830B585B030B9244B244A40F262 -:10204000B121244801F0FAFD23B9234B204A40F284 -:10205000B221F6E7402A04D9204B1D4A40F2B621AE -:10206000EFE722B91D4B1A4A4FF42F71E9E700241C -:10207000012A0294039417D11B788DF80830530776 -:102080000AD004AB03EBD203554213F8084C05F019 -:102090000705AC4003F8084C00910346002102A854 -:1020A000FFF730FB05B030BD082AE5D9102A03D868 -:1020B0001B88ADF80830E2E7202A02D81B6802939B -:1020C000DDE7D3E90045CDE90245D8E72041000826 -:1020D0005C3F0008584200083B410008E44000080B -:1020E00070B50C4600F10C05E16819B9A1602161D9 -:1020F000A18270BD0E682846FFF7BAFAE660F3E7E2 -:102100002DE9F04FD1F8009091B0C9F3C016044604 -:102110000D46CDE90223002E50D0C9F3C03BC9F3D0 -:102120000626B9F1000F80F29F8119F0C04F40F0F0 -:102130009B812B7B002B00F09781BBF1020F03D01A -:102140002278B24240F0938109F07F02BBF1020F86 -:10215000059236D119F07F0FC9F30F2A01D10AF089 -:10216000030A2B447606059A93F8038046EA0B4649 -:1021700046EA82465FEAD81346EA0A06069300F06A -:102180009A800022002310A961E90823059B00938F -:1021900067685B4652462046B847002800F08880B2 -:1021A000A7698FB9314604F10C00FFF7DBF9074648 -:1021B000D0B96FF0020011B0BDE8F08F4FF0020B04 -:1021C000AFE7C9F3074ACCE73B699E420DD03F68B1 -:1021D000002FF9D1314604F10C00FFF7C3F907468F -:1021E0000028E6D0A3693B60A761DDE90801FFF79D -:1021F000D3FAB882F97D08F01F06C1F38401711A81 -:1022000089B20FFA81FED7E90223BEF1000FB8BFF1 -:1022100001F1200EC9F30461B8BF0FFA8EFE0791D9 -:1022200052EA030100F02F81DDE90201801A61EB1F -:10223000030102460B469F480021994208BF904285 -:10224000C0F02181069B002B3FD0BEF1010F00F3AF -:102250001A8118F0400F38D0DDE90223C7E90223C4 -:10226000202200210DEB0200FFF7B8F8DDE9022380 -:10227000CDE908232B1D0A932B7BADF836A0013B3B -:10228000DBB2ADF834309DF81C308DF83A309DF853 -:1022900014308DF83B3020468DF838B08DF8396019 -:1022A000A36808A998473846FFF70CFA002082E790 -:1022B0006FF00B007FE7A76917B96FF00C007AE7A2 -:1022C0003B699E4296D03F68F6E7FB7DC8F340121B -:1022D000B2EBD31F40F0CE80C3F38403B34240F08F -:1022E000CC8006992B7B4FEA981279B3D2073CD465 -:1022F000032B40F2C580DDE90223C7E902232B7BD3 -:10230000AE1D033BDBB23246394604F10C00FFF749 -:1023100029FB002808DA39462046FFF7BFF938467E -:10232000FFF7D0F9032046E7AB883B832A7B033ACB -:10233000D2B2B88A3146FFF755FAFB7DB882DA434C -:10234000C2F3C01262F3C713FB75AFE76AB92E1D63 -:10235000013BDBB23246394604F10C00FFF702FBC9 -:102360000028D8DB2A7B013AE2E7FA8AC2F30902A5 -:10237000013B052AD9B250D8281D002399420AD919 -:1023800007EB020E013210F801CB8EF81AC00133B0 -:10239000062ADBB2F2D1DDE902898B4207F11A028B -:1023A000CDE908890A9238BF04337A680B9234BFAA -:1023B0005B1900230C93FB8AADF836A0C3F3090325 -:1023C00019449DF81C308DF83A309DF814308DF882 -:1023D0003B300023ADF834108DF838B08DF83960FB -:1023E0007B602A7BB88A013A291DFFF7FBF93B8BFA -:1023F000B882834203D1A36808A92046984708A958 -:102400002046FFF76DFE3846FFF75CF9B88A3B8B34 -:10241000984214BF11200020CDE6786810B34FF029 -:10242000060E03689BB9A2EB0E021B2A13D80332D7 -:10243000024405F1040E1F309942ACD91EF801CBBD -:1024400002F801CF01339042DBB2F5D1A3E70EF1E0 -:102450001C0E1846E5E7184B184A194840F2B3110C -:1024600001F0ECFB034696E76FF00900A3E66FF07E -:102470000A00A0E66FF00D009DE66FF00E009AE6F0 -:102480006FF00F0097E6FB7D68F386036FF3C713C9 -:10249000FB7539462046FFF701F9069B002B7FF4B8 -:1024A000D8AEFB7DC3F38402013262F38603FB7571 -:1024B00003E700BF80841E0050410008343F00083D -:1024C000584200082DE9F0414C4EB04240F0818066 -:1024D0004B4CDFF830E1E56945F00075E561E469F2 -:1024E000846AD4F8007207EA0E0747F00107C4F8BF -:1024F0000072D4F8005205EA0E0545F0010545EAE0 -:102500000121C4F80012002A65D00021C4F81C1271 -:102510000F46C4F80412C4F80C12C4F8141204EBE9 -:10252000C10501310E29C5F84072C5F84472F6D1D3 -:102530004FF0000E4FF0010C964510D1826AD2F890 -:102540000032B04223F00103C2F8003253D12C4BC9 -:10255000DA6922F00072DA61DB69BDE8F0819F7808 -:102560001D8817F0010F18BFD4F804820CFA05F18A -:102570001CBF41EA0808C4F8048217F0020F1EBF0E -:10258000D4F80C8241EA0808C4F80C827F0742BFE5 -:10259000D4F814720F43C4F8147204EBC5055F68D5 -:1025A000C5F840729F68C5F84472D4F81C5229439C -:1025B000C4F81C120C330EF1010EBDE7846A002131 -:1025C000C4F81C12C4F80412C4F80C12C4F8141293 -:1025D000AEE7002AF2D1836A0022C3F84022C3F892 -:1025E0004422C3F80422C3F814220122C3F80C22A7 -:1025F000C3F81C22A2E7BDE8F08100BFE022002062 -:10260000001002400000FFFF184A916A08B58B686D -:102610008B6013F0010105D013F00C0F14BF4FF4C1 -:1026200080310121D80506D513F4406F14BF41F461 -:10263000003141F00201D80306D513F4402F14BF36 -:1026400041F4802141F00401D3690BB10748984758 -:10265000202383F311880021054800F087FE002322 -:1026600083F31188BDE8084001F088B8E02200201B -:10267000E822002038B5124CA36ADD68AA0712D000 -:102680005A6922F002025A61A36913B1012120465E -:102690009847202383F3118800210A4800F066FE42 -:1026A000002383F31188EB0606D5A36A1021D960B5 -:1026B000236A0BB102489847BDE8384001F05EB884 -:1026C000E0220020F022002038B5124CA36A1D69D8 -:1026D000AA0712D05A6922F010025A61A36913B1F5 -:1026E000022120469847202383F3118800210A48BD -:1026F00000F03CFE002383F31188EB0606D5A36AA5 -:1027000010211961236A0BB102489847BDE838408F -:1027100001F034B8E0220020F022002038B50F4C40 -:10272000A36A5D685D602A070AD5032222701A68D1 -:1027300022F002021A60636A13B100212046984712 -:102740006B0706D5A36A9969236A13B10904034884 -:102750009847BDE8384001F011B800BFE0220020E2 -:1027600010B50F4C204600F03DFA0E4BA3620B2132 -:10277000132000F017FA0B21142000F013FA0B219C -:10278000152000F00FFA0B21162000F00BFA0023A1 -:1027900020461A460E21BDE81040FFF793BE00BF49 -:1027A000E0220020006400400F4B984210B5044620 -:1027B00005D10E4BDA6942F00072DA61DB69A36A77 -:1027C00001221A60A36A5A68D20707D56268516865 -:1027D0001268D9611A60064A5A6110BD01210820A9 -:1027E00000F07CFCEEE700BFE02200200010024079 -:1027F0005B87010003291AD8DFE801F0020A0F14F1 -:10280000836A9B6813F0E05F14BF012000207047CB -:10281000836A9868C0F380607047836A9868C0F3E1 -:10282000C0607047836A9868C0F3007070470020EA -:102830007047000010B503291FD8DFE801F0021F20 -:102840002327816A8B68C3F30163183301EB0313F9 -:10285000107881061ED55468C0F30011490041EA82 -:10286000C40141F0040100F00F00586090689860C6 -:10287000D268DA6041F00101196010BD836A03F586 -:10288000C073E5E7836A03F5C873E1E7836A03F57C -:10289000D073DDE79488C0F30011490041EA445148 -:1028A000E1E7000001290CD003D3022910D0002059 -:1028B0007047836ADA68920701D1186903E0012042 -:1028C0007047836AD86810F0030018BF0120704772 -:1028D000836AF2E710B539B9836AD96889071BD1D1 -:1028E0001B699B0704D110BD012915D0022948D1CD -:1028F000816AD1F8C031D1F8C401D1F8C84114615E -:10290000D1F8CC41546120240C610C69A40717D183 -:102910004C6944F0100412E0816AD1F8B031D1F86A -:10292000B401D1F8B8411461D1F8BC4154612024FC -:10293000CC60CC68A40703D14C6944F002044C611C -:1029400011795C0864F304119C0864F3451111715A -:1029500089064BBF91681189DB085B0D4CBF63F39F -:102960001C0163F30A01137948BF916060F303030C -:1029700013714FEA10234FEA104058BF11811370B2 -:10298000508010BD002304491A465A50C818083315 -:10299000802B4260F9D170470C2300200268436805 -:1029A0001143016003B1184770470000024A1368E1 -:1029B00043F0C0031360704700380140024A1368B7 -:1029C00043F0C00313607047004400402DE9F04716 -:1029D000C66D3768F46934620546200719D014F0D3 -:1029E000080F0CBF00218021E20748BF41F0200101 -:1029F000A30748BF41F04001600748BF41F4807120 -:102A0000202383F31188281DFFF7C8FF002383F3D9 -:102A10001188E2050AD5202383F311884FF4007151 -:102A2000281DFFF7BBFF002383F311884FF0200917 -:102A30004FF0000A14F0200831D13B0616D54FF0B4 -:102A4000200905F1380A200610D589F3118850466F -:102A500000F04CFA00282FDA0821281DFFF79EFF0E -:102A600027F080033360002383F3118879060DD5A6 -:102A700062060BD5202383F31188EA6C2B6D9A42F2 -:102A800001D12B6CF3B9002383F31188E30621D520 -:102A9000AA6E1369F3B15069BDE8F047184789F38E -:102AA0001188B38C95F864102846194000F0AAFAF2 -:102AB0008AF31188F469BDE780B2308588F3118804 -:102AC000F469C0E71021281D27F04007FFF766FFD3 -:102AD0003760D8E7BDE8F08708B50348FFF776FF11 -:102AE000BDE8084000F04ABE8C23002008B503482A -:102AF000FFF76CFFBDE8084000F040BEF82300205F -:102B000037B51D4C1D4D204600F070FA009404F1BD -:102B10001400002320221A4900F032F920220094E8 -:102B200004F13800174B184900F0ACF9174BE36576 -:102B30002566174C0C21252000F034F8204600F0C3 -:102B400055FA04F11400009400232022114900F0EA -:102B500017F904F1380000940F4B1049202200F0BF -:102B600091F90F4BE3650C212620256603B0BDE8E3 -:102B7000304000F017B800BF8C2300200051250220 -:102B800064240020AD290008A4240020003801405E -:102B9000F823002084240020BD290008C42400203C -:102BA0000044004000F1604300F01F02400903F5BB -:102BB000614309018000C9B200F1604083F800134D -:102BC00000F5614001239340C0F8803103607047F5 -:102BD00000F16040090100F56D40C9B2017670470F -:102BE000FFF7BEBD00F108020123037082600023DD -:102BF000C26000F110024360026142618361C361FF -:102C0000036243627047000010B52023044683F33B -:102C10001188022303704160FFF7C6FD0323237070 -:102C2000002383F3118810BD2DE9F0411F460446AF -:102C30000D461646202383F3118800F108082378F7 -:102C4000042B0ED029462046FFF7D4FD48B120467C -:102C500032462946FFF7EEFD002080F31188BDE8DB -:102C6000F0813946404600F065FB0028E7D000239C -:102C700083F31188BDE8F0812DE9F0411F46044639 -:102C80000D461646202383F3118800F1100823789F -:102C9000042B0ED029462046FFF704FE48B12046FB -:102CA00032462946FFF716FE002080F31188BDE862 -:102CB000F0813946404600F03DFB0028E7D0002374 -:102CC00083F31188BDE8F081F8B51546826806697E -:102CD000AA420B46816938BF8568761AB542044618 -:102CE00007D218462A46FEF767FBA3692B44A36167 -:102CF0000DE011D932461846FEF75EFBAF1B3A468F -:102D0000E1683044FEF758FBE2683A44A261A368E8 -:102D10005B1BA3602846F8BD18462A46FEF74CFB0D -:102D2000E368E4E783682DE9F041044693421546E1 -:102D3000266938BF85684069361AB5420F4606D203 -:102D40002A46FEF739FB63692B4463610DE012D913 -:102D50003246A5EB0608FEF72FFB4246B919E0689C -:102D6000FEF72AFBE26842446261A3685B1BA36032 -:102D70002846BDE8F0812A46FEF71EFBE368E4E73B -:102D800010B50A440024C361029B00604060846067 -:102D9000C160816141610261036210BD08B5826951 -:102DA0004369934201D1826882B9826801328260AC -:102DB0005A1C42611970426903699A4201D3C3687F -:102DC0004361002100F0C6FA002008BD4FF0FF303B -:102DD00008BD000070B5202304460E4683F3118819 -:102DE000A568A5B1A368A269013BA360531CA361B8 -:102DF00015782269934224BFE368A361E3690BB1AC -:102E000020469847002383F31188284670BD314639 -:102E1000204600F08FFA0028E2DA85F3118870BDB1 -:102E20002DE9F74F05460F4690469A46D0F81C907C -:102E3000202686F311884FF0000B144664B1224619 -:102E400039462846FFF740FF034668B951462846F1 -:102E500000F070FA0028F1D0002383F31188A8EB6A -:102E6000040003B0BDE8F08FB9F1000F03D001906A -:102E70002846C847019B8BF31188E41A1F4486F348 -:102E80001188DBE7C16081614161C3611144009B2E -:102E9000006040608260016103627047F8B50446DB -:102EA0000E461746202383F31188A568A5B1A368B1 -:102EB000013BA36063695A1C62611E7023696269E9 -:102EC0009A4224BFE3686361E3690BB120469847E7 -:102ED000002080F31188F8BD3946204600F02AFA18 -:102EE0000028E2DA85F31188F8BD000083694269A1 -:102EF0009A4210B501D182687AB982680132826043 -:102F00005A1C82611C7803699A4201D3C3688361A9 -:102F1000002100F01FFA204610BD4FF0FF3010BD19 -:102F20002DE9F74F05460F4690469A46D0F81C907B -:102F3000202686F311884FF0000B144664B1224618 -:102F400039462846FFF7EEFE034668B95146284643 -:102F500000F0F0F90028F1D0002383F31188A8EBEA -:102F6000040003B0BDE8F08FB9F1000F03D0019069 -:102F70002846C847019B8BF31188E41A1F4486F347 -:102F80001188DBE7026843681143016003B1184709 -:102F9000704700001430FFF743BF00004FF0FF33CD -:102FA0001430FFF73DBF00003830FFF7B9BF000015 -:102FB0004FF0FF333830FFF7B3BF00001430FFF796 -:102FC00009BF00004FF0FF311430FFF703BF0000CE -:102FD0003830FFF763BF00004FF0FF323830FFF7A3 -:102FE0005DBF000000207047FFF78ABD044B0360FF -:102FF000002343608360C36001230374704700BFF4 -:103000009442000838B5C36904460D461BB9042133 -:103010000844FFF7B7FF294604F11400FFF7BEFE8E -:10302000002806DA201D4FF48061BDE83840FFF724 -:10303000A9BF38BD024B00221B605B609A607047DD -:10304000E4240020002303748268054B1B68996800 -:103050009142FBD25A68036042601060586070472A -:10306000E424002008B5202383F31188037C032B7C -:1030700005D0042B0DD02BB983F3118808BD43690B -:1030800000221A604FF0FF334361FFF7DBFF00239C -:10309000F2E790E80C001A6002685360F2E7000063 -:1030A000002303748268054B1B6899689142FBD822 -:1030B0005A6803604260106058607047E424002042 -:1030C000054B19690874186802681A605360186122 -:1030D00001230374FDF798BAE424002030B54B1C9B -:1030E00087B005460A4C10D023690A4A01A800F0AF -:1030F00059F92846FFF7E4FF049B13B101A800F03B -:103100006BF92369586907B030BDFFF7D9FFF8E7BD -:10311000E42400206530000838B50C4D41612B696E -:1031200081689A689142044603D8BDE83840FFF7A9 -:1031300089BF1846FFF786FF01232C6101462374DF -:103140002046BDE83840FDF75FBA00BFE424002008 -:10315000044B1A681B6990689B68984294BF0020D2 -:1031600001207047E424002010B5084C2368206932 -:103170001A6822605460012223611A74FFF790FFDD -:1031800001462069BDE81040FDF73EBAE424002066 -:1031900008B5FFF7DDFF18B1BDE80840FFF7E4BF51 -:1031A00008BD0000FEE7000010B5174CFFF742FF16 -:1031B00000F0EAF880221549204600F06FF801235C -:1031C00044F8180C0374124B124AD96821F4E061D8 -:1031D0000904090C0A431049DA60CA6842F0807297 -:1031E000CA600E490A6842F001020A601022DA77CA -:1031F000202283F82220002383F3118862B6084836 -:10320000BDE8104000F06CB80C250020BC4200085E -:1032100000ED00E00003FA05F0ED00E0001000E032 -:10322000C4420008F8B50F4C226A013222622246DD -:1032300052F8141F9142154606D08B68013B8B60F3 -:10324000202663699A6802B1F8BD1968DF68DA6000 -:103250004D60616182F311881869B84786F311885F -:10326000EFE700BFE4240020EFF3118020B9EFF373 -:103270000583202282F311887047000010B558B9E9 -:10328000EFF30584C4F3080414B180F3118810BD72 -:10329000FFF77EFF84F3118810BD000082600222D8 -:1032A00002740022427470478368A3F17C0243F8E1 -:1032B0000C2C026943F83C2C426943F8382C074A2D -:1032C00043F81C2CC26843F8102C022203F8082C87 -:1032D000002203F8072CA3F118007047210600080C -:1032E00010B5202383F31188FFF7DEFF0021044689 -:1032F000FFF712FF002383F31188204610BD000062 -:10330000024B1B6958610F20FFF7DABEE42400204E -:10331000202383F31188FFF7F3BF000008B50146AF -:10332000202383F311880820FFF7D8FE002383F3BE -:10333000118808BD49B1064B42681B6918605A6084 -:10334000136043600420FFF7C9BE4FF0FF307047A1 -:10335000E42400200368984206D01A680260506096 -:1033600059611846FFF76EBE7047000038B5044635 -:103370000D462068844200D138BD036823605C603C -:103380004561FFF75FFEF4E7054B03F114025A6154 -:103390009A614FF0FF32DA6100221A62704700BF73 -:1033A000E424002010B5C2600A4A036153699C6896 -:1033B000A1420CD85C680360446020605860816062 -:1033C0009868411A99604FF0FF33D36110BD091B13 -:1033D0001B68ECE7E4240020036881689A680A44CB -:1033E0009A604268136003685A600023C360024B0E -:1033F0004FF0FF32DA617047E4240020002070476C -:10340000FEE70000704700004FF0FF3070470000FB -:10341000BFF34F8F024AD368DB07FCD4704700BF6D -:103420000020024008B5074B1B7853B9FFF7F0FFA7 -:10343000054B1A69120641BF044A5A6002F18832EC -:103440005A6008BD70260020002002402301674515 -:1034500008B5054B1B7833B9FFF7DAFF034A136948 -:1034600043F08003136108BD702600200020024055 -:103470007F289ABF00F58030C0020020704700000E -:103480004FF4006070470000802070477F2808B527 -:103490000BD8FFF7EDFF00F500630268013204D19D -:1034A00004308342F9D1012008BD002008BD00008E -:1034B0007F2838B5044624D800F0B6F8124D2860AD -:1034C000FFF7A6FFFFF7AEFF104BF322DA600222F0 -:1034D0001A612046FFF7CCFF58611A6942F040029A -:1034E0001A61FFF795FF4FF4006100F0FBF8FFF75A -:1034F000AFFF00F099F828602046BDE83840FFF79C -:10350000C5BF002038BD00BF742600200020024047 -:103510002DE9F84312F00103144606D0204B40F287 -:103520004B221A600020BDE8F88385181D4A954299 -:1035300004D91B4A4FF414711160F3E7FFF772FFCF -:10354000FFF766FFDFF86C80451A4FF00109012C88 -:1035500005EB01060F4604D8FFF77AFF0120BDE80E -:10356000F883C8F8109031F8023B3380FFF750FF22 -:103570000020C8F8100033883A889BB29A420DD0D8 -:10358000074B40F267221A60074B1E60074B1C6016 -:10359000074B1F60FFF75CFFBDE8F883023CD6E7EE -:1035A0006C260020FFFF030860260020682600200C -:1035B0006426002000200240084908B50B7828B195 -:1035C00053B9FFF72FFF01230B7008BD23B1BDE8EE -:1035D00008400870FFF73CBF08BD00BF7026002000 -:1035E00038B5FFF741FE0D4B0D4A1C6A11684FF4C8 -:1035F0007A7303FB04F38B420A49D1E9004504D2F4 -:10360000003445F10105C1E90045E41845F1000524 -:103610001360FFF733FE2046294638BDE42400201E -:10362000782600208026002008B5FFF7D9FF4FF448 -:103630007A720023FCF7CCFD08BD00BF10B5024430 -:10364000064B0439D2B2904200D110BD441C00B2E6 -:1036500053F8200041F8040FE0B2F4E7502800408E -:10366000104B30B51C6A240407D41C6A44F440741F -:103670001C621C6A44F400441C620B4C236843F433 -:10368000807323600244094B0439D2B2904200D1C6 -:1036900030BD441C00B251F8045F43F82050E0B242 -:1036A000F4E700BF001002400070004050280040C6 -:1036B00007B5012201A90020FFF7C0FF019803B060 -:1036C0005DF804FB13B50446FFF7F2FFA04206D0F5 -:1036D00002A9012241F8044D0020FFF7C1FF02B00A -:1036E00010BD000070470000074B45F255521A60AC -:1036F00002225A6040F6FF729A604CF6CC421A6081 -:10370000024B01221A7070470030004089260020C9 -:10371000034B1B781BB1034B4AF6AA221A60704771 -:103720008926002000300040034B1B689B0042BFED -:10373000024B01221A707047241002408826002094 -:10374000024B4FF080721A60704700BF2410024095 -:10375000014B1878704700BF88260020064A53683E -:1037600023F001035360EFF30983683383F309887F -:10377000002383F31188704730EF00E010B5202359 -:1037800083F31188104B5B6813F4006318D0F1EEDB -:10379000103AEFF309844FF0807344F84C3C0B4B24 -:1037A000DB6844F8083CA4F1680383F30988FFF759 -:1037B000CFFC18B1064B44F8503C10BD054BFAE75E -:1037C00083F3118810BD00BF00ED00E030EF00E092 -:1037D000310600083406000870470000FEE70000CC -:1037E000084A094B09498B4204D3094A00219342F4 -:1037F00005D3704752F8040F43F8040BF3E743F87E -:10380000041BF4E740440008902600209026002086 -:10381000902600204B6843608B688360CB68C36050 -:103820000B6943614B6903628B6943620B680360F8 -:103830007047000008B5194B9A6A42F4FC029A627C -:103840009A6A22F4FC029A629A6A5A6942F4FC0269 -:103850005A61134A5B6911464FF09040FFF7DAFF57 -:10386000104802F11C01FFF7D5FF0F4802F13801A3 -:10387000FFF7D0FF0D4802F15401FFF7CBFF0C48D2 -:1038800002F17001FFF7C6FF0A4802F18C01FFF751 -:10389000C1FFBDE8084000F065B800BF001002405D -:1038A000E44200080004004800080048000C0048FA -:1038B000001000480014004808B500F08FF9FFF729 -:1038C00073FCBDE80840FFF72FBF00007047000001 -:1038D00010B5214CA26A62F4FC02A262A26A02F450 -:1038E000FC02A2624FF0FF31A26A226921612269C3 -:1038F000002222612069E068E160E168E260E1683D -:10390000E169164841F08051E161E169016841F4E3 -:1039100080710160216A01F44071B1F5407F1EBFE2 -:103920004FF4803323622262236A1B0407D4236A84 -:1039300043F440732362236A43F40043236200F09C -:103940002DF9A369064A43F00103A361A369136833 -:1039500043F02003136010BD0010024000700040CF -:10396000000001401C4B1A6842F001021A601A68FC -:103970009007FCD55A6822F003025A605A6812F088 -:103980000C02FBD1196801F0F90119605A601A683C -:1039900042F480321A601A689103FCD50F4A5A60CB -:1039A0004FF40452DA6230221A631A6842F08072CD -:1039B0001A601A689201FCD5094A122111605A68EE -:1039C00042F002025A605A6802F00C02082AFAD148 -:1039D0001A6B1A63704700BF0010024000241D00DC -:1039E00000200240084A08B5536911680B4003F0F3 -:1039F0000103536123B1054A13680BB1506898471E -:103A0000BDE80840FFF7BABE000401400C230020C7 -:103A1000084A08B5536911680B4003F0020353616B -:103A200023B1054A93680BB1D0689847BDE80840B8 -:103A3000FFF7A4BE000401400C230020084A08B58B -:103A4000536911680B4003F00403536123B1054A25 -:103A500013690BB150699847BDE80840FFF78EBE67 -:103A6000000401400C230020084A08B5536911687E -:103A70000B4003F00803536123B1054A93690BB16E -:103A8000D0699847BDE80840FFF778BE00040140C0 -:103A90000C230020084A08B5536911680B4003F055 -:103AA0001003536123B1054A136A0BB1506A98475A -:103AB000BDE80840FFF762BE000401400C2300206F -:103AC000174B10B55C691A68144004F478725A6197 -:103AD000A30604D5134A936A0BB1D06A98476006CF -:103AE00004D5104A136B0BB1506B9847210604D5CF -:103AF0000C4A936B0BB1D06B9847E20504D5094A89 -:103B0000136C0BB1506C9847A30504D5054A936C10 -:103B10000BB1D06C9847BDE81040FFF72FBE00BF37 -:103B2000000401400C2300201A4B10B55C691A6890 -:103B3000144004F47C425A61620504D5164A136DA0 -:103B40000BB1506D9847230504D5134A936D0BB103 -:103B5000D06D9847E00404D50F4A136E0BB1506E38 -:103B60009847A10404D50C4A936E0BB1D06E9847C8 -:103B7000620404D5084A136F0BB1506F98472304B1 -:103B800004D5054A936F0BB1D06F9847BDE810403C -:103B9000FFF7F4BD000401400C230020062108B506 -:103BA0000846FEF7FFFF06210720FEF7FBFF062170 -:103BB0000820FEF7F7FF06210920FEF7F3FF062194 -:103BC0000A20FEF7EFFF06211720FEF7EBFF062184 -:103BD0002820BDE80840FEF7E5BF000008B5FFF764 -:103BE00077FEFEF7CFFEFEF7FBFFFFF7FDF9FFF7CD -:103BF0006DFEBDE8084000F001B8000000F00EB80E -:103C000008B5202383F31188FFF70CFB002383F30F -:103C10001188BDE80840FFF7B1BD0000054B064A1A -:103C20005A6000229A6007221A6008210B20FEF7D2 -:103C3000CFBF00BF10E000E03F1901001FB51C46D8 -:103C4000094B1B680546D86852B1084B02928DE8B3 -:103C50000A0022462B460649FDF718FC00F042F800 -:103C6000044B1A46F2E700BF101100208C430008F5 -:103C700099430008143E000810B5013902449042EF -:103C800001D1002010BD10F8013B11F8014FA342F3 -:103C9000F5D0181B10BD00002DE9F84307468846F3 -:103CA00091461E468BB10D46A8EB0500B54207EBC9 -:103CB000000402D20020BDE8F8833246494620467F -:103CC000FFF7DAFF18B1013DEEE7BDE8F8832046C3 -:103CD000BDE8F883034611F8012B03F8012B002AF5 -:103CE000F9D1704708B5062000F02CF80120FFF745 -:103CF00087FB00001F2938B504460D4604D916235A -:103D000003604FF0FF3038BD426C12B152F82130E1 -:103D10004BB9204600F030F82A4601462046BDE85F -:103D2000384000F017B8012B0AD0591C03D11623D4 -:103D30000360012038BD002442F8254028469847FA -:103D4000002038BD024B01461868FFF7D3BF00BF03 -:103D50001011002038B5074C0023054608461146CF -:103D60002360FFF751FB431C02D1236803B12B6092 -:103D700038BD00BF8C260020FFF740BB40A2E4F115 -:103D8000646891064E6F20617070207369670A0045 -:103D9000426164206677206C656E677468202575C3 -:103DA0000A0042616420626F6172645F6964202569 -:103DB000752073686F756C642062652025750A0034 -:103DC0004261642066772064657363726970746F02 -:103DD00072206C656E6774682025750A0042616404 -:103DE0002061707020435243203078253038783A73 -:103DF000307825303878203078253038783A307867 -:103E0000253038780A00476F6F64206669726D77D5 -:103E10006172650A00000000726563656976656419 -:103E20005F756E697175655F69645F6C656E203C76 -:103E30002055415643414E5F50524F544F434F4CD3 -:103E40005F44594E414D49435F4E4F44455F49449D -:103E50005F414C4C4F434154494F4E5F554E495181 -:103E600055455F49445F4D41585F4C454E47544866 -:103E7000002E2E2F2E2E2F546F6F6C732F41505FFC -:103E8000426F6F746C6F616465722F63616E2E6335 -:103E9000707000616C6C6F63617465645F6E6F64F9 -:103EA000655F6964203C3D20313237006F72672EB8 -:103EB0006172647570696C6F742E61705F70657289 -:103EC0006970685F4857455343000000766F696426 -:103ED0002068616E646C655F616C6C6F63617469AE -:103EE0006F6E5F726573706F6E73652843616E618C -:103EF0007264496E7374616E63652A2C2043616E2F -:103F000061726452785472616E736665722A290018 -:103F100063616E617264496E6974000063616E6111 -:103F200072645365744C6F63616C4E6F6465494491 -:103F30000000000063616E61726448616E646C65CC -:103F400052784672616D650063616E6172644465AA -:103F5000636F64655363616C6172000063616E61DD -:103F60007264456E636F64655363616C61720000D7 -:103F7000696E6372656D656E745472616E736665A9 -:103F800072494400656E7175657565547846726155 -:103F90006D6573007075736854785175657565004B -:103FA00070726570617265466F724E657874547296 -:103FB000616E736665720000636F70794269744167 -:103FC00072726179000000006465736361747465E6 -:103FD000725472616E736665725061796C6F616460 -:103FE0000000000066726565426C6F636B00000044 -:103FF0006269745F6C656E677468203E2030007281 -:10400000656D61696E696E675F62697473203E20D9 -:104010003000696E7075745F6269745F6F66667395 -:104020006574203E3D20626C6F636B5F6269745FF4 -:104030006F666673657400626C6F636B5F656E6458 -:104040005F6269745F6F6666736574203E20626CA0 -:104050006F636B5F6269745F6F666673657400722D -:10406000656D61696E696E675F6269745F6C656ECC -:10407000677468203C3D2072656D61696E696E678A -:104080005F6269747300696E7075745F6269745FF2 -:104090006F6666736574203C3D207472616E736652 -:1040A00065722D3E7061796C6F61645F6C656E2026 -:1040B0002A2038006F75747075745F6269745F6F61 -:1040C0006666736574203C3D2036340072656D6110 -:1040D000696E696E675F6269745F6C656E6774684C -:1040E000203D3D20300028726573756C74203E20A1 -:1040F00030292026262028726573756C74203C3D7B -:10410000203634292026262028726573756C742089 -:104110003C3D206269745F6C656E677468290000BD -:1041200064657374696E6174696F6E20213D202827 -:1041300028766F6964202A2930290076616C7565BC -:1041400020213D202828766F6964202A2930290003 -:104150006F66667365745F77697468696E5F626CB9 -:104160006F636B203C2028333255202D205F5F6227 -:1041700075696C74696E5F6F66667365746F6620CF -:104180002843616E617264427566666572426C6F47 -:10419000636B2C2064617461292900006F75745F62 -:1041A000696E7320213D202828766F6964202A29B2 -:1041B000302900007372635F6C656E203E203055BD -:1041C000000000002863616E5F696420262030785B -:1041D00031464646464646465529203D3D206361C8 -:1041E0006E5F696400000000616C6C6F6361746FE6 -:1041F000722D3E737461746973746963732E637591 -:104200007272656E745F75736167655F626C6F6310 -:104210006B73203E203000007472616E73666572AD -:104220005F696420213D202828766F6964202A294F -:104230003029000073746174652D3E627566666591 -:10424000725F626C6F636B73203D3D202828766F30 -:104250006964202A293029002E2E2F2E2E2F6D6FD3 -:1042600064756C65732F6C696263616E6172642F33 -:1042700063616E6172642E63006974656D2D3E66C4 -:1042800072616D652E646174615F6C656E203E20A5 -:104290003000000000000000B12F00089D2F000832 -:1042A000D92F0008C52F0008D12F0008BD2F000806 -:1042B000A92F0008952F0008E52F00086D61696E91 -:1042C00000000000DC4200082825002060260020B5 -:1042D00001000000A53100080000000069646C6561 -:1042E00000000000A001A82A00000000FAAABEAA4F -:1042F00050001400EFFF00000077000070970900E5 -:104300000100000000000000AAAAAAAA0100000003 -:10431000FFFF00000000000000000000000000009F -:1043200000000000AAAAAAAA00000000FFFF0000E7 -:10433000000000000000000000000000000000007D -:10434000AAAAAAAA00000000FFFF000000000000C7 -:10435000000000000000000000000000AAAAAAAAB5 -:1043600000000000FFFF000000000000000000004F -:104370000000000000000000AAAAAAAA0000000095 -:10438000FFFF000000000000000000002C20667508 -:104390006E6374696F6E3A2000617373657274693D -:1043A0006F6E2022257322206661696C65643A2055 -:1043B00066696C6520222573222C206C696E65204D -:1043C0002564257325730A0038BEFF7F01000000B5 -:1043D0006400000000000000FE2A0100D20400007A -:1043E0001411002000000000000000000000000088 -:1043F00000000000000000000000000000000000BD -:1044000000000000000000000000000000000000AC -:10441000000000000000000000000000000000009C -:10442000000000000000000000000000000000008C -:10443000000000000000000000000000000000007C -:044440000000000078 +:1000000000090020A5040008E1140008611400089C +:10001000B9140008611400088D140008A704000832 +:10002000A7040008A7040008A704000881350008F9 +:10003000A7040008A7040008A7040008B93A0008AC +:10004000A7040008A7040008A7040008A7040008E4 +:10005000A7040008A7040008513800087D380008EC +:10006000A9380008D538000801390008A70400089D +:10007000A7040008A7040008A7040008A7040008B4 +:10008000A7040008A7040008A70400082924000802 +:1000900095240008E92400083D2500082D390008B2 +:1000A000A7040008A7040008A7040008A704000884 +:1000B000A7040008A7040008A7040008A704000874 +:1000C000A7040008A7040008A7040008A704000864 +:1000D000A70400088129000895290008A704000842 +:1000E00095390008A7040008A7040008A704000821 +:1000F000A7040008A7040008A7040008A704000834 +:10010000A7040008A7040008A7040008A704000823 +:10011000A7040008A7040008A7040008A704000813 +:10012000A7040008A7040008A7040008A704000803 +:10013000A7040008A7040008A7040008A7040008F3 +:10014000A7040008A7040008A7040008A7040008E3 +:10015000A7040008A7040008A7040008A7040008D3 +:10016000A7040008A7040008A7040008A7040008C3 +:10017000A7040008A7040008A7040008A7040008B3 +:10018000A7040008A7040008A7040008A7040008A3 +:10019000A7040008A7040008A7040008A704000893 +:1001A00053B94AB9002908BF00281CBF4FF0FF31DE +:1001B0004FF0FF3000F074B9ADF1080C6DE904CEDA +:1001C00000F006F8DDF804E0DDE9022304B0704732 +:1001D0002DE9F047089D04468E46002B4DD18A42FA +:1001E000944669D9B2FA82F252B101FA02F3C2F12D +:1001F000200120FA01F10CFA02FC41EA030E9440BE +:100200004FEA1C48210CBEFBF8F61FFA8CF708FBDE +:1002100016E341EA034306FB07F199420AD91CEBB6 +:10022000030306F1FF3080F01F81994240F21C81E8 +:10023000023E63445B1AA4B2B3FBF8F008FB103330 +:1002400044EA034400FB07F7A7420AD91CEB040465 +:1002500000F1FF3380F00A81A74240F20781644435 +:10026000023840EA0640E41B00261DB1D4400023BA +:10027000C5E900433146BDE8F0878B4209D9002D1E +:1002800000F0EF800026C5E9000130463146BDE8A8 +:10029000F087B3FA83F6002E4AD18B4202D3824212 +:1002A00000F2F980841A61EB030301209E46002DC1 +:1002B000E0D0C5E9004EDDE702B9FFDEB2FA82F216 +:1002C000002A40F09280A1EB0C014FEA1C471FFA74 +:1002D0008CFE0126200CB1FBF7F307FB131140EA5B +:1002E00001410EFB03F0884208D91CEB010103F128 +:1002F000FF3802D2884200F2CB804346091AA4B2EA +:10030000B1FBF7F007FB101144EA01440EFB00FEBD +:10031000A64508D91CEB040400F1FF3102D2A64522 +:1003200000F2BB800846A4EB0E0440EA03409CE7C1 +:10033000C6F12007B34022FA07FC4CEA030C20FA6E +:1003400007F401FA06F31C43F9404FEA1C4900FA8E +:1003500006F3B1FBF9F8200C1FFA8CFE09FB18110B +:1003600040EA014108FB0EF0884202FA06F20BD97E +:100370001CEB010108F1FF3A80F08880884240F2CE +:100380008580A8F102086144091AA4B2B1FBF9F012 +:1003900009FB101144EA014100FB0EFE8E4508D90D +:1003A0001CEB010100F1FF346CD28E456AD9023892 +:1003B000614440EA0840A0FB0294A1EB0E01A14277 +:1003C000C846A64656D353D05DB1B3EB080261EBE5 +:1003D0000E0101FA07F722FA06F3F1401F43C5E9BF +:1003E000007100263146BDE8F087C2F12003D840F5 +:1003F0000CFA02FC21FA03F3914001434FEA1C4737 +:100400001FFA8CFEB3FBF7F007FB10360B0C43EA28 +:10041000064300FB0EF69E4204FA02F408D91CEBD8 +:10042000030300F1FF382FD29E422DD902386344D6 +:100430009B1B89B2B3FBF7F607FB163341EA034176 +:1004400006FB0EF38B4208D91CEB010106F1FF38C5 +:1004500016D28B4214D9023E6144C91A46EA0046BC +:1004600038E72E46284605E70646E3E61846F8E64E +:100470004B45A9D2B9EB020864EB0C0E0138A3E797 +:100480004646EAE7204694E74046D1E7D0467BE778 +:10049000023B614432E7304609E76444023842E7F0 +:1004A000704700BF02E000F000F8FEE772B63A487D +:1004B00080F30888394880F3098839484EF6085196 +:1004C000CEF20001086040F20000CCF200004EF6CF +:1004D0003471CEF200010860BFF34F8FBFF36F8F0E +:1004E00040F20000C0F2F0004EF68851CEF200015A +:1004F0000860BFF34F8FBFF36F8F4FF00000E1EE46 +:10050000100A4EF63C71CEF200010860062080F31E +:100510001488BFF36F8F03F0B3F803F08FF803F084 +:10052000C1F84FF055301F491B4A91423CBF41F87A +:10053000040BFAE71C49194A91423CBF41F8040BED +:10054000FAE71A491A4A1B4B9A423EBF51F8040B6C +:1005500042F8040BF8E700201749184A91423CBFC3 +:1005600041F8040BFAE703F06DF803F0D7F8144CE8 +:10057000144DAC4203DA54F8041B8847F9E700F045 +:1005800041F8114C114DAC4203DA54F8041B884772 +:10059000F9E703F055B80000000900200011002021 +:1005A000000000080001002000090020F83C0008BD +:1005B00000110020201100202011002028260020FA +:1005C000A0010008A0010008A0010008A001000887 +:1005D0002DE9F04F2DED108AC1F80CD0C3689D466F +:1005E000BDEC108ABDE8F08F002383F31188284604 +:1005F000A047002002F04CFDFEE702F0D1FC00DF36 +:10060000FEE700002DE9F04102F062FF074602F02C +:10061000ADFF054600283ED12B4B9F423BD0013316 +:100620009F423BD0294B27F0FF029A423AD1F8B2C1 +:1006300000F054FAA84642F2107400F059FC08B1D8 +:100640000024A04600F050FA064678B384BB464624 +:1006500035B11F4B9F4203D002F080FF0024264695 +:10066000002002F03FFF1B4B1B6913F0400322D018 +:100670000EB100F031F800F05FFC00F031FE00F048 +:1006800031FF0546CCB100F02DFF401BA04214D92C +:1006900000F022F8F3E7A8460024CEE704464FF026 +:1006A0000108CAE780464FF47A74C6E70446CFE7EC +:1006B0004FF47A74CCE71C46DDE700F0DDFC012046 +:1006C00002F0ECFCDEE700BF010007B0000008B05C +:1006D000263A09B00004004838B51D4A1D4B196878 +:1006E000013134D004339342F9D11B4C194DD4F865 +:1006F0000428AA422BD3194B9B6803F1006303F52E +:10070000D0439A4223D202F0FDFE02F00FFF0020F8 +:1007100000F000FE124B0220187000F037FE114B63 +:10072000DA690022DA61D96999699A619B6972B6BE +:100730004FF0E0232021C3F8085DD4F80038D4F846 +:10074000042881F311889D4683F30888104738BD3B +:100750002068000800680008006000080011002000 +:100760002011002000100240094A136849F2690074 +:1007700099B21B0C00FB01331360064B186844F25E +:10078000506182B2000C01FB0200186080B2704719 +:100790001C1100201811002010B500211022044661 +:1007A00000F00EFE034B03CB206061601868A06070 +:1007B00010BD00BFACF7FF1F2DE9F043224DBBB0C9 +:1007C00000F090FEAB6840F2ED22C31A934232D99A +:1007D00006AFA8602B4628220021384601F05EFBB8 +:1007E00005F10E0000F0E4FD002604465FFA80F9F2 +:1007F00005F10E08F3B2F100994501F1280107D97E +:1008000008EB06030822384601F048FB0136F1E701 +:1008100008230122CDE9023205340C4B0193A4B226 +:1008200030230093CDE9047405A3D3E90023297B89 +:10083000074801F04BF93BB0BDE8F083AFF300800F +:1008400078F6339F93CACD8D682100207521002052 +:100850003C21002070B50D4614461E4601F0CCF830 +:1008600050B9022E10D1012C0ED112A3D3E90023CE +:10087000C5E90023012007E0282C10D005D8012C61 +:1008800009D0052C0FD0002070BD302CFBD10BA35C +:10089000D3E90023ECE70BA3D3E90023E8E70BA39C +:1008A000D3E90023E4E70BA3D3E90023E0E700BF8B +:1008B000AFF30080401DA12026812A0B78F6339FDC +:1008C00093CACD8D9E6AC421818A46EE26417272FA +:1008D000DF25D7B7F017304A39059E5613B50446C1 +:1008E0002346084620220021019001F0D7FA227900 +:1008F0000198032A234628BF032203F8042F20214E +:10090000022201F0CBFA62790198072A234628BF18 +:10091000072203F8052F2221032201F0BFFAA27952 +:100920000198072A234628BF072203F8062F25210E +:10093000032201F0B3FA019804F1080310222821E0 +:1009400001F0ACFA382002B010BD00002DE9F04FE4 +:10095000ADF5017D21AD0EAE40F2751280460F4619 +:1009600022A80021296000F02BFD482200213046FA +:1009700000F026FD00F0B6FD564B4FF47A72B0FB46 +:10098000F2F0186093E80700012386E807000DF1F4 +:100990005A003382FFF700FF4EF60343338406AB61 +:1009A00018464D4903F0C2F81D22306429463046EE +:1009B00086F83C20FFF792FF12AB0446014608225E +:1009C000284601F06BFA0822A1180DF149032846C8 +:1009D00001F064FA0DF14A03082204F110012846DF +:1009E00001F05CFA13AB202204F11801284601F053 +:1009F00055FA14AB402204F13801284601F04EFAB2 +:100A000016AB082204F17801284601F047FA0DF1EF +:100A10005903082204F18001284601F03FFA04F14D +:100A2000880A0DF15A0904F5847B4B465146082289 +:100A300028460AF1080A01F031FAD34509F1010903 +:100A4000F3D11BAB08225946284601F027FA04F5DA +:100A500088744FF0000996F834304B450AD9B36BCF +:100A600021464B440822284601F018FA083409F1BF +:100A70000109F0E74FF0000996F83C304B4504EBD4 +:100A8000C90108D9336C08224B44284601F006FA04 +:100A900009F10109F0E700230393BB7E02930731BC +:100AA00007F119030193C1F3CF010123CDE90451EB +:100AB0000093F97E05A3D3E90023404601F006F830 +:100AC0000DF5017DBDE8F08FAFF300809E6AC42173 +:100AD000818A46EE241100203C3B0008014B18702F +:100AE000704700BF30110020F0B5334B1C7B85B040 +:100AF00034B1324B0E221A810024204605B0F0BDDD +:100B00002F4A1068516802AB03C308232D492E48B1 +:100B10000DEB030202F0E8FF054630B9274B2B48E6 +:100B20000A221A8100F098FCE6E70169B1F5663FF8 +:100B300006D9224B26480B221A8100F08DFCDCE7F7 +:100B4000438BB3F57B7F09D01C4A22480C211181CD +:100B50004FF47B72194600F07FFCCEE71E4A024438 +:100B600002F11003994204D2144B1C4810221A813E +:100B7000E3E710398E1A2046134900F0B7FC3246DD +:100B8000074605F11801204600F0B0FCAB689F4213 +:100B900002D1EB6898420AD0084B0D221A810090CE +:100BA000D5E902123B460E4800F056FCA4E70D487A +:100BB00000F052FC0124A0E768210020241100204D +:100BC000ED3B0008DC970300006800085C3B000870 +:100BD000683B00087A3B00080898FFF7983B00083C +:100BE000B53B0008DE3B00082DE9F04FADB006AF85 +:100BF00080460C4600F000FF054600285AD1237EAF +:100C0000022B1BD1E38A012B18D100F06BFC0646A6 +:100C1000FFF7AAFD03464FF4C870DFF8D092B3FB8C +:100C2000F0F206F5167602FB103316FA83F3C9F8D4 +:100C30000030E37E33B9A84B00221A709C37BD46C2 +:100C4000BDE8F08FA38AEEB2013BB34205F1010586 +:100C50000BD93B1D1E44E90000960023082201F039 +:100C6000F801204600F0DEFFECE707F11400FFF783 +:100C700093FD324607F11401381D02F025FF0028CC +:100C8000D9D10F2E08D8944B1E70D9F80030A3F597 +:100C90001673C9F80030D1E7FB1CF87001460093C9 +:100CA00007220346204600F0BDFFF978404600F0D9 +:100CB0009BFEC3E7E38A282B26D010D8012B1ED039 +:100CC000052BBBD1BFF34F8F8449854BCA6802F413 +:100CD000E0621343CB60BFF34F8F00BFFDE7302BC3 +:100CE000ACD1637E7F4D01336A7BDBB29342E94630 +:100CF00003D1E27E2B7B9A4265D0CD469EE721460A +:100D00004046FFF723FE99E7A38A013B9BB2C92B1C +:100D100094D8744D2E7B26BB05F10C03009308225A +:100D200033463146204600F07DFF731CF2B2D900F5 +:100D30001E46A38A013B9A4205DA0E322A440092EB +:100D400000230822EEE700230022C5E90023002348 +:100D5000AB6085F8D730C5F8D8302B7B0BB9E37E74 +:100D60002B73002507F114093B1D0822294648462C +:100D7000C7E90155FD6001F091F83B7A05F1010AE0 +:100D8000AB424FEACA0608D9FB6808222B44314619 +:100D9000484601F083F85546EFE7C6F3CF06E17EFB +:100DA000CDE9049600230393A37E029319342823EC +:100DB0000093019446A3D3E90023404600F086FE49 +:100DC000FFF7FAFC3AE74FF0000807F11403A7F821 +:100DD00014801022009341460123204600F022FF98 +:100DE000A68A023EB6B2F31C9B109B000733DB08B9 +:100DF000A9EBC3039D460DF1180A1FFA88F34FEAC9 +:100E0000C801B34201F110010AD20AEB08030093B2 +:100E100008220023204600F005FF08F10108ECE756 +:100E200095F8D70000F080FAD5F8D83004461BB901 +:100E300095F8D70000F088FAD5F8D83033449C42B2 +:100E400004D295F8D700013000F07EFA4FEA960BF5 +:100E50004FF000081FFA88F18B45D5E9003209D917 +:100E60000AEB880103EB8800012200F0B1FA08F1D7 +:100E70000108EFE7F31842F10002C5E90032D5F8A6 +:100E8000D83095F8D70006EB0308C5F8D88000F0F5 +:100E90004BFA804509D395F8D730D5F8D8000133FF +:100EA000001B85F8D730C5F8D800FF2E08D80023DE +:100EB0002B7300F05BFAFFF717FE08B1FFF70CFC8D +:100EC0002B68094A9B0A013313810023AB6014E7A6 +:100ED00026417272DF25D7B73521002000ED00E0F2 +:100EE0000400FA0568210020241100203821002088 +:100EF00010B54FF000540C4B22689A4211D10B4BA5 +:100F0000627D1A700A48237D03730A49C9220E3094 +:100F100000F044FAE0220021204600F051FA0120BE +:100F200010BD0020FCE700BF9AAD44C53011002081 +:100F300068210020160000202DE9FF41434C0223C8 +:100F400063710023029324250A23581EB5FBF3F690 +:100F50007343D3F12402C1B23ED002280346F4D138 +:100F60009DF80B303A493B485A1E9DF80A30013B28 +:100F70001B0443EA0253BDF80820013A13434B60B7 +:100F800001F044FD00230193334B3449009334486E +:100F9000344B4FF4805200F001FD334B197811B1FE +:100FA0002F4800F021FD00F09DFA0546FFF7DCFB1D +:100FB0004FF4C873B0FBF3F202FB130305F5167090 +:100FC00010FA83F0294B186002F0D0FA08B10F2311 +:100FD000238104B0BDE8F081C1EBC107FB1C4FEADF +:100FE000E30EC3F3C703A1EB030C0EF101084FF4AA +:100FF0007A705FFA8CF50EFB000058FA8CFCB0FB9F +:10100000FCF0B0F5617F07D97B1EC3F3C703C91A93 +:10101000CDB2591E0F2916D86A1E072A8CBF00228E +:101020000122591901FB06601149B1FBF0F1114889 +:10103000814295D1002A93D0ADF808608DF80A302E +:101040008DF80B508CE71346EBE700BF241100200E +:1010500010110020802200205508000834110020C3 +:101060003C210020E90B000830110020382100202D +:101070000051250240420F002DE9F04F90A7D7E91B +:1010800000670FF24429D9E90089874D93B0DFF852 +:1010900040B2864C284600F07DFD0DF1300A0790E5 +:1010A00070B310220021504600F08AF9079B197B8B +:1010B0004FF0000261F303028DF830205868996800 +:1010C0000EAA03C21B680D9A63F31C029DF8303010 +:1010D0000D9243F020038DF830300023524619461C +:1010E000584601F0A3FC079028B9284600F056FDA9 +:1010F000079B2370CEE72378072B3CD8013323705E +:1011000018220021504600F05BF9DFF8C4B100233B +:1011100019465246584601F0B1FC014678BB1022F0 +:1011200008A800F04DF94FF0904209AC536983F0E4 +:101130001003536100F0D8F90B4612A9024611E9D9 +:10114000030084E803009DF83410C1F3030089060E +:101150004CBF0E9CBDF838408DF82C0046BFC4F340 +:101160001C0444F00044C4F30A0408A92846089467 +:1011700000F0DCFECBE7284600F010FDC0E7284673 +:1011800000F03AFC0446002848D1DFF848B100F0EE +:10119000A9F9DBF80030984240D300F0A3F907909A +:1011A000FFF7E2FA079A8DF8204003464FF4C87023 +:1011B00002F51672B3FBF0F101FB103312FA83F360 +:1011C000CBF80030DFF810B19BF8001011B9012303 +:1011D0008DF8203050460791FFF7DEFA0799C1F1EC +:1011E0001004E4B2062C28BF0624224651440DF117 +:1011F000210000F0D3F808AB0393182302930134C5 +:101200002B4B0193E4B20123009304943B463246F6 +:10121000284600F0F3FB00238BF8003000F062F961 +:10122000244A254C1368C31AB3F57A7F31D3106072 +:1012300000F05AF902460B46284600F0B9FC284651 +:1012400000F0DAFB28B3237BDFF890B0002B14BF4B +:10125000032302238BF8053000F044F94FF47A732E +:101260005146B0FBF3F0CBF800005846FFF736FBD1 +:10127000182307300293114B0193C0F3CF0040F2C3 +:101280005513CDE903A0009342464B46284600F093 +:10129000B5FB237B2BB1FFF78FFA237B002B7FF469 +:1012A000F6AE13B0BDE8F08F3C2100204D220020A7 +:1012B0003421002048220020682100204C220020F8 +:1012C000401DA12026812A0BF1C6A7C1D068080FB6 +:1012D0008022002038210020352100202411002008 +:1012E00070B501F0B5FF094E094D30800024286823 +:1012F0003388834208D901F0A7FF2B6804440133E7 +:10130000B4F5D04F2B60F2D370BD00BF7C2200201B +:101310005022002002F03AB800F10060920000F57F +:10132000D04001F0D5BF0000054B1A68054B1B8863 +:101330009B1A834202D9104401F086BF00207047F7 +:10134000502200207C22002038B5074D0446286832 +:10135000204401F07FFF28B928682044BDE83840C8 +:1013600001F08ABF38BD00BF50220020064991F825 +:10137000243033B10023086A81F824300822FFF7B3 +:10138000CBBF0120704700BF54220020022802BFBB +:101390004FF090434FF480129A61704710B50023CC +:1013A000934203D0CC5CC4540133F9E710BD000074 +:1013B00003460246D01A12F9011B0029FAD17047E0 +:1013C00002440346934202D003F8011BFAE7704738 +:1013D0002DE9F8431F4D144695F82420074688460A +:1013E00052BBDFF870909CB395F824302BB92022C3 +:1013F000FF2148462F62FFF7E3FF95F82400C0F174 +:101400000802A24228BF2246D6B24146920005EB0E +:101410008000FFF7C3FF95F82430A41B1E44F6B2EA +:10142000082E17449044E4B285F82460DBD1FFF71E +:101430009DFF0028D7D108E02B6A03EB820383428B +:10144000CFD0FFF793FF0028CBD10020BDE8F88371 +:101450000120FBE7542200200FB4002004B07047A5 +:1014600000B59BB0EFF3098168226846FFF796FF4D +:10147000EFF30583044B9A6BDA6A9A6A9A6A9A6A5E +:101480009A6A9A6A9B6AFEE700ED00E000B59BB09D +:10149000EFF3098168226846FFF780FFEFF30583C9 +:1014A000044B9A6B9A6A9A6A9A6A9A6A9A6A9B6ACF +:1014B000FEE700BF00ED00E000B59BB0EFF309814F +:1014C00068226846FFF76AFFEFF30583034B5A6B08 +:1014D0009A6A9A6A9A6A9A6A9B6AFEE700ED00E045 +:1014E000FEE7000001F08EBF01F064BF30B5094D8A +:1014F0000A4491420DD011F8013B5840082340F3B3 +:101500000004013B2C4013F0FF0384EA5000F6D1A5 +:10151000EFE730BD2083B8ED2DE9F041C56915B97D +:10152000C161BDE8F0814B6823F06047C3F38A4690 +:101530004FEAD37EC3F3807816EA230638BF3E46CF +:10154000AC462B465A68BEEBD27F22F060440AD0EC +:10155000002A18DAA40CB44217D19D420FD10D60B5 +:10156000DEE71346EEE7A74207D102F08044C2F35C +:10157000807242450BD054B1EFE708D2EDE7CCF8CA +:1015800000100B60CDE7B44201D0B442E5D81A6830 +:101590009C46002AE5D11960C3E700002DE9F04719 +:1015A000089D01F007044FEAD508224405F007051D +:1015B00000EBD1004FF47F49944201D1BDE8F087A0 +:1015C00004F0070705F0070A57453E4638BF564660 +:1015D000C6F10806111B8E4228BF0E46E10808EB33 +:1015E000D50E415C13F80EC0B94029FA06F721FA6E +:1015F0000AF1FFB28CEA010147FA0AF739408CEA96 +:10160000010C03F80EC034443544D5E780EA0120CC +:10161000082341F2210201B24000002980B203F107 +:10162000FF33B8BF504013F0FF03F4D17047000000 +:1016300038B50C468D18A54200D138BD14F8011BF1 +:10164000FFF7E4FFF7E7000002684AB113680360A0 +:10165000C388018901339BB29942C38038BF03819B +:101660001046704770B588B0202204460D46684683 +:101670000021FFF7A5FE20460495FFF7E5FF02468F +:1016800058B16B46054608AE1C4603CCB4422860F0 +:101690006960234605F10805F6D1104608B070BD13 +:1016A000082817D909280CD00A280CD00B280CD0F0 +:1016B0000C280CD00D280CD00E2814BF4020302050 +:1016C00070470C2070471020704714207047182076 +:1016D0007047202070470000082817D90C280CD923 +:1016E00010280CD914280CD918280CD920280CD96A +:1016F00030288CBF0F200E207047092070470A2029 +:1017000070470B2070470C2070470D207047000079 +:1017100010B54B6823B9CA8A63F30902CA8210BDA7 +:10172000C4681A681C60C360438A013B43824A60F4 +:10173000EFE700002DE9F84F1D46CB8A0F46C3F3B3 +:1017400009010629814692460B4630D00020AAB2F4 +:1017500007F119049EB2052E1FFA80F80FD89045A4 +:1017600003F1010306D3FB8A0A4462F30903FB82F7 +:1017700001201AE01AF80060E6540130EAE79045CB +:10178000F1D2A1F1060B1C237C68BBFBF3F203FB37 +:1017900012BB1FFA8BF6002C45D14846FFF754FFC9 +:1017A000044638B978606FF00200BDE8F88F4FF05A +:1017B0000008E6E7002606607860ADB24FF0000B47 +:1017C000454510D90AEB0803221D13F8011B91555A +:1017D000B1B208F101081B291FFA88F82BD0454542 +:1017E00006F10106F1D8FB8AC3F30902154465F33B +:1017F0000903BCE7013292B21C462368002BF9D1E1 +:10180000AB1F0B441C21B3FBF1F301339BB29A4293 +:10181000D3D2BBF1000FD0D14846FFF715FF20B956 +:10182000C4F800B0BFE70122E7E7C0F800B05E46A9 +:1018300020600446C1E74545D5D94846FFF704FF77 +:1018400008B92060AFE7C0F800B000262060044669 +:10185000B6E700002DE9F04F2DED028B83B0CDE906 +:101860000013BDF83C5007469146002A00F09280D4 +:101870002DB10E9B002B00F08D80072D32D807F183 +:101880000C00FFF7E1FE044638B96FF00204204671 +:1018900003B0BDEC028BBDE8F08F14220021FFF7EE +:1018A0008FFD0E992A4604F10800FFF777FD681CAA +:1018B000C0B2FFF711FFFFF7F3FE207499F8003074 +:1018C000013814FA80F003F01F0363F03F03037242 +:1018D000009B43F00041616038462146FFF71CFE43 +:1018E0000124D4E700F10C034FF0000808EE103A91 +:1018F0004FF0800A4646444618EE100AFFF7A4FE51 +:1019000083460028C1D014220021FFF759FDC6BB31 +:10191000019BABF8083002200E9B00F108029919D8 +:101920005BFA82F20130C0B2082801D0AE422AD35D +:10193000FFF7D2FEFFF7B4FE99F80020009B411E8E +:1019400002F01F0242EA4812AE4208BF4FF0400ABE +:101950005BFA81F14AEA020A43F0004281F808A0EA +:101960008BF81000CBF8042059463846FFF7D4FD19 +:101970000134AE4224B288F001084FF0000ABBD116 +:1019800085E70020C8E711F801CB02F801CB01364A +:10199000B6B2C7E76FF0010479E70000F8B5154665 +:1019A0000E462822002104461F46FFF709FD069B2C +:1019B0006360B5F5001F079BA76034BF6A094FF647 +:1019C000FF72236204F10C0097B200239A4205D8FB +:1019D0000023036027826382A382F8BD066001337F +:1019E00030462036F2E7000003781BB94BB2002BDB +:1019F000C8BF017070470000007870472DE9F74FAD +:101A0000DDF83C90BDF830500D9E9DF83840BDF893 +:101A10004070804692469B46B9F1000F01D1002FDD +:101A200051D11F2C4FD898F80000B0B9072F47D8D4 +:101A300035F0030347D13A4649464FF6FF70FFF7AA +:101A4000F7FD20F001002D02400445EA0464400C3B +:101A500044EA40244FF6FF7321E040EA0520072FB7 +:101A600040EA0464F6D900254FF6FF73C5F1200063 +:101A7000A5F120022AFA05F10BFA00F001432BFA36 +:101A800002F211431846C9B2FFF7C0FD0835402DD8 +:101A90000346EBD13A464946FFF7CAFD0346CDE976 +:101AA0000097324621464046FFF7D4FE3378013393 +:101AB000DBB21F2B88BF0023337003B0BDE8F08F6B +:101AC0006FF00300F9E76FF00100F6E72DE9F04F42 +:101AD00085B09246DDF848800F9D9DF840209DF826 +:101AE0004490BDF84C7006469B46B8F1000F01D1FA +:101AF000002F48D11F2A46D83378002B46D00C023D +:101B000044EA02649DF8381044EAC93444EA0144C6 +:101B10001C43072F44F0800432D900234FF6FF7294 +:101B2000C3F1200CA3F120002AFA03F10BFA0CFCFC +:101B300041EA0C012BFA00F00143C9B210460393AD +:101B4000FFF764FD039B0833402B0246E8D13A4679 +:101B50004146FFF76DFD0346CDE900872A46214641 +:101B60003046FFF777FEB9F1010F06D12B7801332C +:101B7000DBB21F2B88BF00232B7005B0BDE8F08FB0 +:101B80004FF6FF73E8E76FF00100F6E76FF0030030 +:101B9000F3E70000C06900B104307047C3691A68F8 +:101BA000C261C2681A60C360438A013B43827047C6 +:101BB0002DE9F041D0F81880194E14461D464146D3 +:101BC000002709B9BDE8F081D1E90223A21A65EB2B +:101BD0000303964277EB03031ED283698B420DD138 +:101BE000FFF796FD83691B688361C3680B60438AB6 +:101BF000C1608169013B43828846E2E7FFF788FDC7 +:101C00000B68C8F80030C3680B60438AC160013BB1 +:101C10004382D8F80010D4E788460968D1E700BFAE +:101C200080841E002DE9F04F8BB00D46DDF85090FA +:101C300014469B468046002800F01981B9F1000F38 +:101C400000F01581531E3F2B00F21181012A03D1B0 +:101C5000BBF1000F40F00B810023CDE90833B8F849 +:101C60001430B5EBC30F4FEAC30703D300200BB00A +:101C7000BDE8F08F2B199F42D8F80C303ABF7F1B7C +:101C8000FFB227461BB9D8F81030002B7AD02F2D81 +:101C90004ED8C5F13006B7424FF000032CBFF6B264 +:101CA0003E4600932946D8F8080008AB3246FFF7B5 +:101CB00075FCA7EB060A35445FFA8AFAB8F81430C7 +:101CC00003F10053063BDB000493D8F80C30039378 +:101CD0003021039B13B1BAF1000F2CD1D8F81000BA +:101CE00040B1BAF1000F05D0009608AB5246691A10 +:101CF000FFF754FC38B2002FB8D066070AD00AAB01 +:101D000003EBD401624211F8083C02F007021341D0 +:101D100001F8083C082C3CD9102C40F2B580202C4E +:101D200040F2B780BBF1000F00F09C80082334E044 +:101D3000BA460026C2E7049BE02B28BFE0230693A7 +:101D40000B44AB42059314D95A1B03980096924555 +:101D500034BF5246D2B2691A08AB04300792FFF77B +:101D60001DFC079A1644AAEB020A1544F6B25FFA64 +:101D70008AFA049B069A05999B1A0493039B1B6895 +:101D80000393A6E70093D8F8080008AB3A46294623 +:101D9000AEE7BBF1000F13D00123B4EBC30F6CD03F +:101DA000082C12D89DF82030621E23FA02F2D507C3 +:101DB00006D54FF0FF3202FA04F423438DF82030A9 +:101DC0009DF8203089F8003051E7102C12D8BDF86A +:101DD0002030621E23FA02F2D10706D54FF0FF32FF +:101DE00002FA04F42343ADF82030BDF82030A9F8FE +:101DF00000303CE7202C0FD80899631E21FA03F32A +:101E0000DA0705D54FF0FF3202FA04F40C430894C8 +:101E1000089BC9F800302AE7402C2BD0DDE9086583 +:101E2000611EC4F12102A4F1210326FA01F105FA91 +:101E300002F225FA03F311431943CB0712D501220D +:101E4000A4F12003C4F1200102FA03F322FA01F104 +:101E5000A240524243EA010363EB430332432B4364 +:101E6000CDE90823DDE90823C9E90023FFE66FF087 +:101E70000100FCE66FF00800F9E6082CA0D9102C50 +:101E8000B3D9202CEED8C3E7BBF1000FADD00223AD +:101E900083E7BBF1000FBBD004237EE730B5012AF6 +:101EA000144638BF0124402C85B028BF40240025AB +:101EB000012ACDE9025518D81B788DF80830630740 +:101EC0000AD004AB03EBD405624215F8083C02F0DB +:101ED0000702934005F8083C009103462246002182 +:101EE00002A8FFF75BFB05B030BD082AE4D9102A31 +:101EF00003D81B88ADF80830E1E7202A8DBFD3E96D +:101F000000231B680293CDE90223D8E710B5CB6804 +:101F10001BB98B600B618B8210BDC4681A681C6092 +:101F2000C360438A013B4382CA60F0E72DE9F04F6A +:101F3000D1F8008093B018F0800FCDE90323C8F3E7 +:101F4000C01219BFC8F3C03BC8F306264FF0020BFE +:101F50001646B8F1000F04460D4680F2D18118F004 +:101F6000C043059340F0CC810B7B002B00F0C8816F +:101F7000BBF1020F03D00178B14240F0C48108F0F8 +:101F80007F0106916AB3C8F3074A2B44069A93F877 +:101F90000390760646EA0B4646EA82465FEAD91384 +:101FA00046EA0A06079300F0908000220023CDE95C +:101FB0000A23069B009367685B4652460AA920469F +:101FC000B84700287ED0A7699FB9314604F10C00BC +:101FD000FFF748FB0746E0B96FF0020013B0BDE819 +:101FE000F08FC8F30F2A18F07F0F08BF0AF0030A1A +:101FF000CBE73B699E420DD03F68002FF9D13146B7 +:1020000004F10C00FFF72EFB07460028E4D0A3697B +:102010003B60A761DDE90A2300264FF6FF70C6F199 +:10202000200E22FA06F103FA0EFEA6F1200C23FA86 +:102030000CFC41EA0E0141EA0C01C9B208360992D2 +:102040000893FFF7E3FA402EDDE90832E7D1B882C2 +:10205000FB7D09F01F06C3F384039B1BD7E9022114 +:1020600098B2002BBCBF00F120031BB252EA010062 +:10207000C8F304680FD00398821A049860EB01013A +:10208000A74890424FF000028A4104D3079A002AE1 +:102090005BD0012B23DDFA7D4FEA890302F00302B6 +:1020A00003F07C031343FB7539462046FFF730FBF2 +:1020B000079BA3B9FB7DC3F38402013262F386035D +:1020C000FB7504E06FF00B0088E7A76917B96FF0A4 +:1020D0000C0083E73B699E42BAD03F68F6E719F0EF +:1020E000400F32D0039BBB60049BFB601422002195 +:1020F0000DA8FFF765F9039B0A93049B0B932B1D17 +:102100000C932B7BADF83EA0013BDBB2ADF83C302D +:10211000069B8DF8433094F824308DF840B083F05E +:1021200001038DF844308DF84160A3688DF842803A +:102130000AA920469847FB7DC3F38403013303F0CB +:102140001F039B02FB82002048E7FB7DC9F340127E +:10215000B2EBD31F40F0DA80C3F38403B34240F004 +:10216000D88007992B7B4FEA9912002934D0D207E7 +:1021700041D4032B40F2D080039BBB60049BFB60E7 +:102180002B7BAE1D033BDBB23246394604F10C001B +:10219000FFF7D0FA00280DDA20463946FFF7B8FAE3 +:1021A000FB7DC3F38403013303F01F039B02FB8217 +:1021B000032013E7AB883B832A7B033AB88AD2B269 +:1021C0003146FFF735FAFB7DB882DA43C2F3C0121D +:1021D00062F3C713FB75B6E76AB92E1D013BDBB28C +:1021E0003246394604F10C00FFF7A4FA0028D3DB8D +:1021F0002A7B013AE2E7F98AC1F30901013B05298B +:10220000DAB259D8281D002307F11A0C9A4208D9CE +:1022100010F801EB0CF801E0013101330629DBB2C3 +:10222000F4D103990A9104990B91934207F11A0191 +:102230000C9138BF043379680D9134BF55FA83F39C +:1022400000230E93FB8AADF83EA0C3F309031A44A2 +:10225000069B8DF8433094F82430ADF83C2083F091 +:1022600001038DF8443000238DF840B08DF84160B3 +:102270008DF842807B602A7BB88A013A291DFFF7DE +:10228000D7F93B8BB882834203D1A3680AA92046C1 +:10229000984720460AA9FFF739FEFB7DB88AC3F3A9 +:1022A0008403013303F01F039B02FB823B8B9842A4 +:1022B00014BF1120002091E67B68002BB1D00620CE +:1022C00001E01C306346D3F800C0BCF1000FF8D128 +:1022D000091A081D05F1040C00EB030905989DF887 +:1022E000143001EB000EBEF11B0F9AD89A4298D918 +:1022F0001CF8013B09F8013B059B01330593EDE711 +:102300006FF009006AE66FF00A0067E66FF00D00F3 +:1023100064E66FF00E0061E66FF00F005EE600BF4E +:1023200080841E00F0B53D4D3D4FEB6943F00073D6 +:10233000EB61EB693B4B9B6AD3F800623E4046F091 +:102340000106C3F80062D3F800423C4044EA002092 +:1023500040F00100C3F80002002951D00020C3F86A +:102360001C020646C3F80402C3F80C02C3F81402A8 +:1023700003EBC00401300E28C4F84062C4F8446284 +:10238000F6D100274FF0010C9678148816F0010F53 +:1023900018BFD3F804E20CFA04F01CBF40EA0E0E9A +:1023A000C3F804E216F0020F1EBFD3F80CE240EAB5 +:1023B0000E0EC3F80CE2760742BFD3F81462064350 +:1023C000C3F8146203EBC4045668C4F8406296680C +:1023D000C4F84462D3F81C4201372043B942C3F821 +:1023E0001C0202F10C02CFD1D3F8002222F001022C +:1023F000C3F80022EB6923F00073EB61EB69F0BDD9 +:102400000122C3F84012C3F84412C3F80412C3F8FF +:102410001412C3F80C22C3F81C22E5E70010024096 +:102420000000FFFF80220020184A916A08B58B68DF +:102430008B6013F0010104D013F00C0F18BF4FF4A0 +:102440008031D80506D513F4406F14BF41F4003134 +:1024500041F00201D80306D513F4402F14BF41F414 +:10246000802141F00401D3690BB10848984720232B +:1024700083F311880648002100F038FE002383F31F +:102480001188BDE8084001F0AFB800BF80220020ED +:102490008822002038B5124CA36ADD68AA0712D042 +:1024A0005A6922F002025A61A36913B10121204640 +:1024B0009847202383F311880A48002100F016FE74 +:1024C000002383F31188EB0606D5A36A1021D96097 +:1024D000236A0BB102489847BDE8384001F084B840 +:1024E000802200209022002038B5124CA36A1D697A +:1024F000AA0712D05A6922F010025A61A36913B1D7 +:10250000022120469847202383F311880A4800219E +:1025100000F0ECFD002383F31188EB0606D5A36AD7 +:1025200010211961236A0BB102489847BDE8384071 +:1025300001F05AB8802200209022002038B50F4CBC +:10254000A36A5D685D602A070AD5042222701A68B2 +:1025500022F002021A60636A13B1002120469847F4 +:102560006B0706D5A36A9969236A13B10348090466 +:102570009847BDE8384001F037B800BF80220020FE +:1025800010B50E4C204600F02FFA0D4BA3620B2124 +:10259000132000F009FA0B21142000F005FA0B219A +:1025A000152000F001FA0B21162000F0FDF90022A1 +:1025B000BDE8104011460E20FFF7B4BE8022002077 +:1025C000006400400F4B984210B5044605D10E4BF5 +:1025D000DA6942F00072DA61DB69A36A01221A60EB +:1025E000A36A5A68D20707D5626851681268D96130 +:1025F0001A60064A5A6110BD0121082000F06CFCE7 +:10260000EEE700BF80220020001002405B8701003F +:1026100003291AD8DFE801F0020A0F14836A9B68C5 +:1026200013F0E05F14BF012000207047836A9868B0 +:10263000C0F380607047836A9868C0F3C0607047D9 +:10264000836A9868C0F300707047002070470000EC +:1026500010B5032925D8DFE801F00225292D836A6A +:102660009968C1F30161183103EB011310788406F6 +:102670004CBF54689488C0F300114FEA410148BF31 +:1026800041EAC40100F00F004CBF41F0040141EAEF +:102690004451586041F001019068D2689860DA6056 +:1026A000196010BD836A03F5C073DFE7836A03F521 +:1026B000C873DBE7836A03F5D073D7E701290AD033 +:1026C00002290FD081B9836ADA68920701D11869AB +:1026D00003E001207047836AD86810F0030018BF38 +:1026E00001207047836AF2E70020704710B539B9BE +:1026F000836AD96889071BD11B699C0704D110BD67 +:10270000012915D00229FAD1816AD1F8C031D1F856 +:10271000C441D1F8C8011061D1F8CC01506120202A +:1027200008610869800717D1486940F0100012E07D +:10273000816AD1F8B031D1F8B441D1F8B801106153 +:10274000D1F8BC0150612020C860C868800703D15F +:10275000486940F002004861C3F34000C3F38001C0 +:10276000000140EA4111107920F03000014311715D +:1027700089064BBF91681189DB085B0D4CBF63F381 +:102780001C0163F30A01137948BF916064F30303EA +:1027900013714FEA14234FEA144458BF1181137088 +:1027A0005480ACE7026843681143016003B11847E5 +:1027B00070470000024A136843F0C003136070477B +:1027C00000380140024A136843F0C00313607047A9 +:1027D0000044004037B51D4C1D4D204600F006FB5F +:1027E000009404F114001B490023202200F0C8F9D2 +:1027F0002022009404F13800174B184900F042FAE7 +:10280000174BC4E91735174C0C21252000F0CCF8E4 +:10281000204600F0EBFA04F1140013490094002361 +:10282000202200F0ADF904F13800104B104900945B +:10283000202200F027FA0F4B0C212620C4E917357F +:1028400003B0BDE8304000F0AFB800BFAC220020BC +:102850000051250284230020B5270008C42300204E +:102860000038014018230020A4230020C5270008B9 +:10287000E4230020004400402DE9F047C66D37688E +:10288000F46934622107054618D014F0080118BF16 +:102890008021E20748BF41F02001A30748BF41F073 +:1028A0004001600748BF41F48071202383F3118801 +:1028B000281DFFF777FF002383F31188E2050AD56F +:1028C000202383F311884FF40071281DFFF76AFF5E +:1028D000002383F311884FF020094FF0000A14F011 +:1028E000200838D13B0616D54FF0200905F1380AEB +:1028F000200610D589F31188504600F0F7F900281A +:1029000036DA0821281DFFF74DFF27F080033360DA +:10291000002383F31188790614D5620612D520238B +:1029200083F31188D5E913239A4208D12B6C33B174 +:102930001021281D27F04007FFF734FF37600023E0 +:1029400083F31188E30619D5AA6E1369B3B1BDE804 +:10295000F0475069184789F31188B38C95F86410D3 +:102960002846194000F04EFA8AF31188F469B6E758 +:1029700080B2308588F31188F469B9E7BDE8F08743 +:1029800008B50348FFF778FFBDE8084000F02CBE0B +:10299000AC22002008B50348FFF76EFFBDE80840F1 +:1029A00000F022BE1823002000F1604303F56143CC +:1029B0000901C9B283F80013012200F01F039A40F5 +:1029C00043099B0003F1604303F56143C3F8802191 +:1029D0001A60704700F16040090100F56D40C9B20E +:1029E00001767047FFF7CCBD012300F10802C0E972 +:1029F0000222037000F110020023C0E90422C0E9A2 +:102A00000633C0E9083343607047000010B5202347 +:102A1000044683F31188022303704160FFF7D2FD5F +:102A200004232370002383F3118810BD2DE9F041A6 +:102A30001F4604460D461646202383F3118800F1F5 +:102A400008082378052B0DD029462046FFF7E0FD26 +:102A500040B1204632462946FFF7FAFD002080F3B8 +:102A6000118808E03946404600F024FB0028E8D0F1 +:102A7000002383F31188BDE8F08100002DE9F041C7 +:102A80001F4604460D461646202383F3118800F1A5 +:102A900010082378052B0DD029462046FFF70EFE9F +:102AA00040B1204632462946FFF720FE002080F341 +:102AB000118808E03946404600F0FCFA0028E8D0CA +:102AC000002383F31188BDE8F0810000F8B51546B6 +:102AD00082680669AA420B46816938BF8568761A02 +:102AE000B54204460BD218462A46FEF757FCA369A6 +:102AF0002B44A361A3685B1BA3602846F8BD0CD9D7 +:102B000018463246FEF74AFCAF1BE1683A463044AD +:102B1000FEF744FCE3683B44EBE718462A46FEF721 +:102B20003DFCE368E5E7000083689342F7B515468E +:102B3000044638BF8568D0E90460361AB5420BD226 +:102B40002A46FEF72BFC63692B446361A368284681 +:102B50005B1BA36003B0F0BD0DD932460191FEF7B7 +:102B60001DFC0199E068AF1B3A463144FEF716FCA4 +:102B7000E3683B44E9E72A46FEF710FCE368E4E734 +:102B800010B50A440024C361029B8460C0E90000C0 +:102B9000C0E90511C1600261036210BD08B5D0E94A +:102BA0000532934201D1826882B982680132826023 +:102BB0005A1C42611970D0E904329A4224BFC3689A +:102BC0004361002100F086FA002008BD4FF0FF307D +:102BD000FBE7000070B5202304460E4683F31188FE +:102BE000A568A5B1A368A269013BA360531CA361BA +:102BF00015782269934224BFE368A361E3690BB1AE +:102C000020469847002383F31188284607E0314681 +:102C1000204600F04FFA0028E2DA85F3118870BDF3 +:102C20002DE9F74F04460E4617469846D0F81C90FB +:102C30004FF0200A8AF311884FF0000B154665B15A +:102C40002A4631462046FFF741FF034660B9414618 +:102C5000204600F02FFA0028F1D0002383F31188DA +:102C6000781B03B0BDE8F08FB9F1000F03D00190DD +:102C70002046C847019B8BF31188ED1A1E448AF346 +:102C80001188DCE7C0E90511C160C3611144009BF4 +:102C90008260C0E90000016103627047F8B5044634 +:102CA0000D461646202383F31188A768A7B1A368B1 +:102CB000013BA36063695A1C62611D70D4E9043250 +:102CC0009A4224BFE3686361E3690BB120469847E9 +:102CD000002080F3118807E03146204600F0EAF931 +:102CE0000028E2DA87F31188F8BD0000D0E9052357 +:102CF0009A4210B501D182687AB982680132826045 +:102D00005A1C82611C7803699A4224BFC36883619C +:102D1000002100F0DFF9204610BD4FF0FF30FBE747 +:102D20002DE9F74F04460E4617469846D0F81C90FA +:102D30004FF0200A8AF311884FF0000B154665B159 +:102D40002A4631462046FFF7EFFE034660B941466A +:102D5000204600F0AFF90028F1D0002383F311885A +:102D6000781B03B0BDE8F08FB9F1000F03D00190DC +:102D70002046C847019B8BF31188ED1A1E448AF345 +:102D80001188DCE7026843681143016003B118470A +:102D9000704700001430FFF743BF00004FF0FF33CF +:102DA0001430FFF73DBF00003830FFF7B9BF000017 +:102DB0004FF0FF333830FFF7B3BF00001430FFF798 +:102DC00009BF00004FF0FF311430FFF703BF0000D0 +:102DD0003830FFF763BF00004FF0FF323830FFF7A5 +:102DE0005DBF000000207047FFF7F4BC044B036098 +:102DF0000023C0E90233436001230374704700BF1E +:102E0000F83B000838B5C36904460D461BB90421D8 +:102E10000844FFF7B7FF294604F11400FFF7BEFE90 +:102E2000002806DA201D4FF48061BDE83840FFF726 +:102E3000A9BF38BD024B0022C3E900339A60704736 +:102E400004240020002303748268054B1B689968E2 +:102E50009142FBD25A68036042601060586070472C +:102E60000424002008B5202383F31188037C032B5E +:102E700005D0042B0DD02BB983F3118808BD43690D +:102E800000221A604FF0FF334361FFF7DBFF00239E +:102E9000F2E7D0E9003213605A60F3E700230374CD +:102EA0008268054B1B6899689142FBD85A68036099 +:102EB000426010605860704704240020054B196977 +:102EC0000874186802681A6053601861012303745B +:102ED000FDF77EBB0424002030B54B1C0B4D87B0A2 +:102EE000044610D02B690A4A01A800F01BF92046BD +:102EF000FFF7E4FF049B13B101A800F02FF92B6941 +:102F0000586907B030BDFFF7D9FFF8E70424002067 +:102F1000652E000838B50C4D41612B6981689A68AF +:102F20009142044603D8BDE83840FFF78BBF1846EE +:102F3000FFF7B4FF01232C61014623742046BDE84E +:102F40003840FDF745BB00BF04240020044B1A683D +:102F50001B6990689B68984294BF002001207047CD +:102F60000424002010B5084C236820691A682260E8 +:102F70005460012223611A74FFF790FF0146206913 +:102F8000BDE81040FDF724BB0424002008B5FFF77E +:102F9000DDFF18B1BDE80840FFF7E4BF08BD000041 +:102FA000FFF7E0BFFEE7000010B50C4CFFF742FF53 +:102FB00000F0AAF80A498022204600F031F80123E7 +:102FC00044F8180C037400F0EBFA002383F3118823 +:102FD00062B60448BDE8104000F042B82C2400203E +:102FE000203C0008303C000800F0CAB8EFF3118024 +:102FF00020B9EFF30583202282F311887047000087 +:1030000010B530B9EFF30584C4F3080414B180F3AC +:10301000118810BDFFF7BAFF84F31188F9E70000AB +:1030200082600222028270478368A3F17C0243F827 +:103030000C2C026943F83C2C426943F8382C074AAF +:1030400043F81C2CC26843F8102C022203F8082C09 +:10305000002203F8072CA3F118007047E9050008C7 +:1030600010B5202383F31188FFF7DEFF002104460B +:10307000FFF750FF002383F31188204610BD0000A6 +:10308000024B1B6958610F20FFF718BF0424002072 +:10309000202383F31188FFF7F3BF000008B5014632 +:1030A000202383F311880820FFF716FF002383F302 +:1030B000118808BD49B1064B42681B6918605A6007 +:1030C000136043600420FFF707BF4FF0FF307047E5 +:1030D000042400200368984206D01A6802605060F9 +:1030E00059611846FFF7AEBE7047000038B5044678 +:1030F0000D462068844200D138BD036823605C60BF +:103100004561FFF79FFEF4E7054B03F11402C3E9A5 +:1031100005224FF0FF32DA6100221A62704700BFC9 +:103120000424002010B5C0E903230B4A136A536935 +:103130009C68A1420CD85C68816003604460206098 +:1031400058609868411A99604FF0FF33D36110BD01 +:103150001B68091BECE700BF04240020036881689A +:103160009A680A449A60426813605A600023C360F8 +:10317000024B4FF0FF32DA61704700BF0424002099 +:1031800038B50F4C236A22460133236252F8143FAC +:10319000934206D09A68013A9A60202563699A683A +:1031A00002B138BDD3E9001001604860D968DA6027 +:1031B00082F311881869884785F31188EEE700BF0C +:1031C0000424002000207047FEE700007047000044 +:1031D0004FF0FF3070470000BFF34F8F024AD368B3 +:1031E000DB07FCD4704700BF0020024008B5074B46 +:1031F0001B7853B9FFF7F0FF054B1A69120641BF60 +:10320000044A5A6002F188325A6008BD90250020B5 +:10321000002002402301674508B5054B1B7833B9F0 +:10322000FFF7DAFF034A136943F08003136108BD17 +:1032300090250020002002407F289ABF00F58030B2 +:10324000C0020020704700004FF40060704700008B +:10325000802070477F2808B50BD8FFF7EDFF00F5F9 +:1032600000630268013204D104308342F9D10120A5 +:1032700008BD0020FCE700007F2838B5044623D8AD +:10328000FFF7B4FEFFF7A8FFFFF7B0FF0F4BF322E5 +:10329000DA6002221A6105462046FFF7CDFF586129 +:1032A0001A6942F040021A614FF40061FFF794FF7F +:1032B00000F026F92846FFF7AFFFFFF7A1FE2046F2 +:1032C000BDE83840FFF7C6BF002038BD00200240EF +:1032D00012F001032DE9F04704460E46154606D0CC +:1032E000244B40F2BD221A600020BDE8F08781180F +:1032F000214A914204D91F4A40F2C2211160F3E7EA +:10330000FFF774FEFFF772FFFFF766FFDFF87890B4 +:1033100031464FF0010AA61B012D06EB0107884636 +:1033200005D8FFF779FFFFF76BFE0120DDE7B8F85E +:103330000030C9F810A03B800024FFF74DFFC9F80A +:1033400010403B8831F8022B9BB29A420FD0094BB8 +:1033500040F2D9221A60094B1F60094B1D60094BCE +:10336000C3F80080FFF758FFFFF74AFEBCE7023DB5 +:10337000D2E700BF8C250020000004088025002033 +:10338000882500208425002000200240084908B537 +:103390000B7828B11BB9FFF729FF01230B7008BD7B +:1033A000002BFCD0BDE808400870FFF735BF00BF18 +:1033B0009025002030B583B0FFF718FE0E4B0F4D5F +:1033C0001B6A2A684FF47A7101FB03F3934237BFFB +:1033D0000B4A0B49516814682B602EBFD1E900419C +:1033E000013151601C1941F100010191FFF708FE04 +:1033F0000199204603B030BD04240020942500200C +:103400009825002030B583B0FFF7F0FD114B124D29 +:103410001B6A2A684FF47A7101FB03F3934237BFAA +:103420000E4A0E49516814682B602EBFD1E9004145 +:10343000013151601C1941F100010191FFF7E0FDDC +:1034400001994FF47A7200232046FCF7A9FE03B0DD +:1034500030BD00BF042400209425002098250020C2 +:1034600010B50244064BD2B2904200D110BD441CAC +:1034700000B253F8200041F8040BE0B2F4E700BFBB +:10348000502800400F4B30B51C6A240407D41C6A36 +:1034900044F440741C621C6A44F400441C620A4CEC +:1034A000236843F4807323600244084BD2B29042F5 +:1034B00000D130BD441C00B251F8045B43F82050E9 +:1034C000E0B2F4E7001002400070004050280040D5 +:1034D00007B5012201A90020FFF7C2FF019803B040 +:1034E0005DF804FB13B50446FFF7F2FFA04205D0D8 +:1034F000012201A900200194FFF7C4FF02B010BD12 +:1035000070470000074B45F255521A6002225A607C +:1035100040F6FF729A604CF6CC421A60024B0122D0 +:103520001A70704700300040A4250020034B1B7820 +:103530001BB1034B4AF6AA221A607047A42500204B +:1035400000300040044B1A682AB902F1804202F5AB +:103550000432526A1A607047A0250020024B4FF0D7 +:1035600080725A62704700BF0010024008B5FFF732 +:10357000E9FF024B1868C0F3407008BDA025002089 +:10358000EFF3098305494A6B22F001024A6368336D +:1035900083F30988002383F31188704700EF00E06C +:1035A000202080F3118862B60C4B0D4AD96821F4B3 +:1035B000E0610904090C0A43DA60D3F8FC200949E8 +:1035C00042F08072C3F8FC200A6842F001020A60EF +:1035D0001022DA7783F82200704700BF00ED00E088 +:1035E0000003FA05001000E010B5202383F31188D2 +:1035F0000E4B5B6813F4006314D0F1EE103AEFF356 +:103600000984683C4FF08073E361094BDB6B2366F0 +:1036100084F30988FFF79AFC10B1064BA36110BD33 +:10362000054BFBE783F31188F9E700BF00ED00E0ED +:1036300000EF00E0FB050008FE05000870470000F1 +:10364000FEE700000A4B0B480B4A90420BD30B4B92 +:10365000DA1C121AC11E22F003028B4238BF00226C +:103660000021FDF7ADBE53F8041B40F8041BECE746 +:10367000183D0008282600202826002028260020A3 +:10368000704700004B6843608B688360CB68C36001 +:103690000B6943614B6903628B6943620B6803608A +:1036A0007047000008B51B4B9A6A42F4FC029A620C +:1036B0009A6A22F4FC029A629A6A5A6942F4FC02FB +:1036C0005A61154A5B6911464FF09040FFF7DAFFE7 +:1036D00002F11C0100F58060FFF7D4FF02F1380110 +:1036E00000F58060FFF7CEFF02F1540100F5806025 +:1036F000FFF7C8FF02F1700100F58060FFF7C2FF1D +:1037000002F18C0100F58060FFF7BCFFBDE80840C6 +:1037100000F05AB800100240483C000808B500F01C +:1037200093F9FFF741FCBDE80840FFF70BBF00002D +:103730007047000010B5214CA36A63F4FC03A36238 +:10374000A36A03F4FC03A3624FF0FF32A36A236968 +:1037500022612369002323612169E168E260E26854 +:10376000E360E268E269164942F08052E261E26990 +:103770000A6842F480720A60226A02F44072B2F56A +:10378000407F1EBF4FF4803222622362236A1B04F3 +:1037900007D4236A43F440732362236A43F400434B +:1037A000236200F031F9A369064A43F00103A361E3 +:1037B000A369136843F02003136010BD001002409A +:1037C00000700040000001401E4B1A6842F00102E8 +:1037D0001A601A689007FCD55A6822F003025A60F2 +:1037E0005A6812F00C02FBD1196801F0F901196056 +:1037F0005A601A6842F480321A601A689103FCD544 +:10380000114A5A604FF40452DA6230221A631A687D +:1038100042F080721A601A689201FCD50B4912229C +:103820000A600A6802F00702022AFAD15A6842F0D6 +:1038300002025A605A6802F00C02082AFAD11A6B86 +:103840001A6370470010024000241D00002002404F +:10385000084A08B5516913680B4003F0010353612E +:1038600023B1054A13680BB150689847BDE808407A +:10387000FFF7BABE00040140A8250020084A08B599 +:10388000516913680B4003F00203536123B1054AE9 +:1038900093680BB1D0689847BDE80840FFF7A4BE15 +:1038A00000040140A8250020084A08B551691368A2 +:1038B0000B4003F00403536123B1054A13690BB1B4 +:1038C00050699847BDE80840FFF78EBE00040140EC +:1038D000A8250020084A08B5516913680B4003F079 +:1038E0000803536123B1054A93690BB1D069984726 +:1038F000BDE80840FFF778BE00040140A82500207D +:10390000084A08B5516913680B4003F0100353616E +:1039100023B1054A136A0BB1506A9847BDE80840C5 +:10392000FFF762BE00040140A8250020174B10B528 +:103930005A691C68144004F478725A61A30604D5CD +:10394000134A936A0BB1D06A9847600604D5104AAF +:10395000136B0BB1506B9847210604D50C4A936B3F +:103960000BB1D06B9847E20504D5094A136C0BB133 +:10397000506C9847A30504D5054A936C0BB1D06CE5 +:103980009847BDE81040FFF72FBE00BF000401407C +:10399000A82500201A4B10B55A691C68144004F47D +:1039A0007C425A61620504D5164A136D0BB1506D05 +:1039B0009847230504D5134A936D0BB1D06D9847F2 +:1039C000E00404D50F4A136E0BB1506E9847A10462 +:1039D00004D50C4A936E0BB1D06E9847620404D59F +:1039E000084A136F0BB1506F9847230404D5054A5A +:1039F000936F0BB1D06F9847BDE81040FFF7F4BD4F +:103A000000040140A8250020062108B50846FEF75D +:103A1000CBFF06210720FEF7C7FF06210820FEF78F +:103A2000C3FF06210920FEF7BFFF06210A20FEF78B +:103A3000BBFF06211720FEF7B7FFBDE808400621AF +:103A40002820FEF7B1BF000008B5FFF773FE00F0B5 +:103A50000DF8FEF7C7FFFFF7C7F9FFF769FEBDE8EE +:103A6000084000F001B8000000F00EB80023054A3D +:103A700019460133102BC2E9001102F10802F8D1F6 +:103A8000704700BFA82500204FF0E023044A5A6188 +:103A900000229A6107221A6108210B20FEF79ABFC3 +:103AA0003F19010008B5202383F31188FFF79CFA22 +:103AB000002383F3118808BD08B5FFF7F3FFBDE8C5 +:103AC0000840FFF791BD000010B501390244904253 +:103AD00001D1002005E0037811F8014FA34201D085 +:103AE000181B10BD0130F2E72DE9F041A3B1C91A4E +:103AF00017780144044603F1FF3C8C42204601D96B +:103B0000002009E00578BD4204F10104F5D10CEB79 +:103B10000405D618A54201D1BDE8F08115F8018D44 +:103B200016F801EDF045F5D0E7E70000034611F87F +:103B3000012B03F8012B002AF9D170476F72672E11 +:103B40006172647570696C6F742E61705F706572FC +:103B50006970685F48574553430000004E6F20610D +:103B60007070207369670A00426164206677206C78 +:103B7000656E6774682025750A0042616420626F73 +:103B80006172645F69642025752073686F756C6469 +:103B90002062652025750A004261642066772064F2 +:103BA000657363726970746F72206C656E67746898 +:103BB0002025750A004261642061707020435243E1 +:103BC000203078253038783A3078253038782030F1 +:103BD00078253038783A3078253038780A00476FC1 +:103BE0006F64206669726D776172650A0040A2E4B5 +:103BF000F16468910600000000000000B12D00088B +:103C00009D2D0008D92D0008C52D0008D12D0008D4 +:103C1000BD2D0008A92D0008952D0008E52D0008F0 +:103C20006D61696E0000000069646C650000000051 +:103C3000283C0008482400208025002001000000C6 +:103C4000A52F000800000000A001A82A0000000025 +:103C5000FAAABEAA50001424EFFF0000007700006B +:103C6000709709000100000000000000AAAAAAAA9B +:103C700001000000FFFF0000000000000000000045 +:103C80000000000000000000AAAAAAAA000000008C +:103C9000FFFF000000000000000000000000000026 +:103CA00000000000AAAAAAAA00000000FFFF00006E +:103CB0000000000000000000000000000000000004 +:103CC000AAAAAAAA00000000FFFF0000000000004E +:103CD000000000000000000000000000AAAAAAAA3C +:103CE00000000000FFFF00000000000000000000D6 +:103CF000E0C4FF7F01000000EC03000000000000B2 +:103D000000980300000000006400000000000000B4 +:083D1000FE2A0100D2040000AC :00000001FF diff --git a/Tools/bootloaders/f303-M10025_bl.bin b/Tools/bootloaders/f303-M10025_bl.bin index b9f79e58c2b..0273a8c5c6a 100755 Binary files a/Tools/bootloaders/f303-M10025_bl.bin and b/Tools/bootloaders/f303-M10025_bl.bin differ diff --git a/Tools/bootloaders/f303-M10025_bl.hex b/Tools/bootloaders/f303-M10025_bl.hex index cd21867f250..e67a02b5073 100644 --- a/Tools/bootloaders/f303-M10025_bl.hex +++ b/Tools/bootloaders/f303-M10025_bl.hex @@ -1,1095 +1,980 @@ :020000040800F2 -:1000000000090020E1040008991400089D1400086C -:10001000F11400089D140008C5140008E30400084A -:10002000E3040008E3040008E30400085D37000867 -:10003000E3040008E3040008E3040008013C0008AE -:10004000E3040008E3040008E3040008E3040008F4 -:10005000E3040008E3040008E5390008113A000849 -:100060003D3A0008693A0008953A0008E3040008A0 -:10007000E3040008E3040008E3040008E3040008C4 -:10008000E3040008E3040008E3040008092600086C -:1000900075260008C92600081D270008C13A000877 -:1000A000E3040008E3040008E3040008E304000894 -:1000B000E3040008E3040008E3040008E304000884 -:1000C000E3040008E3040008E3040008E304000874 -:1000D000E3040008D92A0008ED2A0008E304000818 -:1000E000293B0008E3040008E3040008E3040008D7 -:1000F000E3040008E3040008E3040008E304000844 -:10010000E3040008E3040008E3040008E304000833 -:10011000E3040008E3040008E3040008E304000823 -:10012000E3040008E3040008E3040008E304000813 -:10013000E3040008E3040008E3040008E304000803 -:10014000E3040008E3040008E3040008E3040008F3 -:10015000E3040008E3040008E3040008E3040008E3 -:10016000E3040008E3040008E3040008E3040008D3 -:10017000E3040008E3040008E3040008E3040008C3 -:10018000E3040008E3040008E3040008E3040008B3 -:10019000E3040008E3040008E3040008E3040008A3 -:1001A000D0400B1CD1409C46203AD34018435242C9 -:1001B00063469340184370479140031C90409C460F -:1001C000203A9340194352426346D3401943704743 -:1001D00053B94AB9002908BF00281CBF4FF0FF31AE -:1001E0004FF0FF3000F07AB9ADF1080C6DE904CEA4 -:1001F00000F006F8DDF804E0DDE9022304B0704702 -:100200002DE9F0478C460D460446089E002B51D13F -:100210008A4217466DD9B2FA82FEBEF1000F0BD0AA -:10022000CEF1200C01FA0EF520FA0CFC02FA0EF7C2 -:100230004CEA050C00FA0EF44FEA174A250CBCFBF9 -:10024000FAF81FFA87F90AFB18CC45EA0C4508FBB7 -:1002500009F3AB420AD9ED1908F1FF3280F023818E -:10026000AB4240F22081A8F102083D44ED1AA4B24D -:10027000B5FBFAF00AFB105544EA054400FB09F906 -:10028000A14509D9E41900F1FF3380F00A81A145A5 -:1002900040F2078102383C44A4EB090440EA0840DC -:1002A0000021002E61D024FA0EF400233460736024 -:1002B000BDE8F0878B4207D9002E54D0002186E894 -:1002C00021000846BDE8F087B3FA83F1002940F029 -:1002D0008E80AB4202D3824200F2FA80841A65EB30 -:1002E00003050120AC46002E3FD086E81010BDE883 -:1002F000F08712B90127B7FBF2F7B7FA87FEBEF114 -:10030000000F34D1EB1B3A0C1FFA87FC0121B3FB21 -:10031000F2F8250C02FB183345EA03450CFB08F301 -:10032000AB4207D9ED1908F1FF3002D2AB4200F21F -:10033000D1808046ED1AA3B2B5FBF2F002FB105556 -:1003400043EA05440CFB00FCA44507D9E41900F17D -:10035000FF3302D2A44500F2B8801846A4EB0C0487 -:1003600040EA08409DE731463046BDE8F087CEF1CF -:10037000200405FA0EF307FA0EF720FA04F83A0CF7 -:1003800025FA04F448EA0308B4FBF2F14FEA1845F1 -:1003900002FB11441FFA87FC45EA044501FB0CF3FC -:1003A000AB4200FA0EF409D9ED1901F1FF3080F0EB -:1003B0008A80AB4240F2878002393D44EB1A1FFA33 -:1003C00088F5B3FBF2F002FB103345EA034500FB6E -:1003D0000CF3AB4207D9ED1900F1FF386FD2AB42F5 -:1003E0006DD902383D44EB1A40EA01418FE7C1F173 -:1003F000200722FA07F88B4005FA01F448EA0303C4 -:1004000020FA07FE4FEA134CFD404EEA040EB5FBFE -:10041000FCF94FEA1E440CFB19551FFA83F844EA15 -:10042000054509FB08F4AC4202FA01F200FA01FAB0 -:1004300008D9ED1809F1FF3043D2AC4241D9A9F1F6 -:1004400002091D442D1B1FFA8EFEB5FBFCF00CFBB0 -:1004500010554EEA054400FB08F8A04507D9E418FA -:1004600000F1FF3529D2A04527D902381C4440EAC3 -:100470000940A4EB0804A0FB02894C45C6464D4642 -:1004800015D312D056B1BAEB0E0364EB050404FA8F -:1004900007F7CB401F43CC40376074600021BDE8B4 -:1004A000F0871846F8E69046E0E6C245EAD2B8EB97 -:1004B000020E69EB03050138E4E72846D7E740461A -:1004C00091E78146BEE7014678E702383C4445E7BC -:1004D000084608E7A8F102083D442BE7704700BF33 -:1004E00002E000F000F8FEE772B6394880F30888B1 -:1004F000384880F3098838484EF60851CEF200019A -:10050000086040F20000CCF200004EF63471CEF2EA -:1005100000010860BFF34F8FBFF36F8F40F2000000 -:10052000C0F2F0004EF68851CEF200010860BFF331 -:100530004F8FBFF36F8F4FF00000E1EE100A4EF6C1 -:100540003C71CEF200010860062080F31488BFF3EE -:100550006F8F03F041F903F06DF94FF055301F49EB -:100560001B4A91423CBF41F8040BFAE71C49194A67 -:1005700091423CBF41F8040BFAE71A491A4A1B4B57 -:100580009A423EBF51F8040B42F8040BF8E70020F2 -:100590001749184A91423CBF41F8040BFAE703F0AF -:1005A0001FF903F089F9144C144DAC4203DA54F8E6 -:1005B000041B8847F9E700F03FF8114C114DAC429D -:1005C00003DA54F8041B8847F9E703F007B9000081 -:1005D0000009002000110020000000080001002098 -:1005E00000090020D04300080011002074110020F1 -:1005F0007811002090260020A0010008A00100082A -:10060000A0010008A00100082DE9F04F2DED108A8F -:10061000C1F80CD0C3689D46BDEC108ABDE8F08FD0 -:10062000002383F311882846A047002002F070FEC3 -:1006300002F09AFD00DFFEE7384B6FF013022DE960 -:10064000F0416FF0670100241A7003225A709C7009 -:10065000DC701C715C719C71DC711C7259729A7235 -:10066000DC7203F025F8074603F072F80546C8BBB4 -:100670002B4B9F4238D001339F4238D0294B27F073 -:10068000FF029A4237D1F8B200F052FAA84642F27D -:10069000107400F07BFC00F051FA064678B384BB7E -:1006A000464635B1204B9F4203D003F049F8002461 -:1006B0002646002003F006F81C4B1B6913F040038C -:1006C00022D00EB100F034F800F082FC00F016FEEB -:1006D00000F022FF0546CCB900F0D0FC012002F06A -:1006E0001DFEF8E78046D4E780460446D1E704467D -:1006F0004FF00108CDE780464FF47A74C9E704460D -:10070000CFE74FF47A74CCE71C46DDE700F004FF36 -:10071000401BA042E0D900F00BF8D9E77811002087 -:10072000010007B0000008B0263A09B000040048F4 -:1007300010B51C4B1C4953F8042F013200D110BDD9 -:100740008B42F8D1194C1A4B22689A4228D9194B7E -:100750009B6803F1006303F5D0439A4220D202F074 -:10076000C3FF02F0D5FF002000F0E2FD124B022093 -:10077000187000F019FE114BDA690022DA61D969AC -:1007800099699A619B6972B60D4A0E4B13601B689A -:100790002268202181F311889D4683F30888104741 -:1007A00010BD00BFFC6700081C6800080468000852 -:1007B000FF6700087811002084110020001002401B -:1007C00008ED00E00068000809490B6849F269007B -:1007D0009AB21B0C00FB0233064A0B60136844F20A -:1007E000506198B21B0C01FB0030106080B2704762 -:1007F0000C1100200811002010B500211022044621 -:1008000000F0ECFD034B03CB206061601868A06032 -:1008100010BD00BFACF7FF1FF0B51F4CBBB000F020 -:100820007BFEA368C31AF92B30D906AD2346A0601E -:1008300028220021284601F0FDFB04F10E0000F003 -:10084000C5FD0023C6B2591D5F1CDBB2B3424FEA9F -:10085000C10107DA0E3323440822284601F0EAFBDF -:100860003B46F0E7012303930823207B02930B4BC5 -:100870000193C1F3CF013023059100930146049504 -:1008800003A3D3E90023064801F0A4F93BB0F0BD6F -:1008900078F6339F93CACD8DC8210020D521002042 -:1008A000A021002070B50D4614461E4601F038F90F -:1008B00050B9022E0ED1012C0CD112A3D3E9002382 -:1008C000C5E90023012070BD052C14D003D8012CEC -:1008D00009D0002070BD282C09D0302CF9D10BA3F1 -:1008E000D3E90023ECE70BA3D3E90023E8E70BA34C -:1008F000D3E90023E4E70BA3D3E90023E0E700BF3B -:10090000AFF30080401DA12026812A0B78F6339F8B -:1009100093CACD8D9E6AC421818A46EE26417272A9 -:10092000DF25D7B7F017304A39059E5638B504464B -:100930000D46034620222846002101F07BFB227948 -:100940002346032A28BF032203F8042F2846022245 -:10095000202101F06FFB62792346072A28BF072276 -:1009600003F8052F28460322222101F063FBA27918 -:100970002346072A28BF072203F8062F284603220A -:10098000252101F057FB284604F1080310222821F5 -:1009900001F050FB382038BD2DE9F04FADF5017D59 -:1009A00021AE0EAD40F2791280460F46304600214E -:1009B00000F014FD48220021284600F00FFD00F051 -:1009C000ABFD594B4FF47A72B0FBF2F0186093E82C -:1009D0000700012385E807002B740DF15A0000235E -:1009E0006B74FFF709FF032385F82030EC2385F8AB -:1009F000213007AB18464D4903F06CF918222864E2 -:100A00003146284685F83C20FFF790FF12AB04469C -:100A100001460822304601F00DFB0822A1180DF115 -:100A20004903304601F006FB0DF14A03082204F1A8 -:100A30001001304601F0FEFA13AB202204F1180138 -:100A4000304601F0F7FA14AB402204F13801304689 -:100A500001F0F0FA16AB082204F17801304601F0FB -:100A6000E9FA0DF15903082204F18001304601F042 -:100A7000E1FA04F1880A0DF15A0904F5847B4B462A -:100A80005146082230460AF1080A01F0D3FAD3454C -:100A900009F10109F3D11BAB08225946304601F098 -:100AA000C9FA04F588744FF0000995F834304B45C5 -:100AB00010D84FF0000995F83C304B4515D92B6CF8 -:100AC00021464B440822304601F0B4FA083409F1BB -:100AD0000109F0E7AB6B21464B440822304601F098 -:100AE000A9FA083409F10109DFE7E31DC3F3CF03D5 -:100AF000F97E0593002304960393BB7E0293193776 -:100B000001230093019706A3D3E90023404601F097 -:100B100061F80DF5017DBDE8F08F00BFAFF30080F7 -:100B20009E6AC421818A46EE88110020AC3E0008EE -:100B3000014B1870704700BF94110020F0B5334B83 -:100B40001C7B85B034B1324B0E221A810024204622 -:100B500005B0F0BD2F4A1068516802AB03C30823EB -:100B60000DEB03022C492D4803F096F8054630B9E9 -:100B7000274B2B480A221A8100F084FCE6E7016922 -:100B8000B1F5663F06D9224B26480B221A8100F0A8 -:100B900079FCDCE7438BB3F57B7F09D01C4A224804 -:100BA0000C2111814FF47B72194600F06BFCCEE7EB -:100BB0001E4A024402F11003994204D2144B1C480D -:100BC00010221A81E3E710398E1A2046134900F0EB -:100BD000A7FC3246074605F11801204600F0A0FCAC -:100BE000AB689F4202D1EB6898420AD0084B0D22B5 -:100BF0001A8100903B46EA68A9680E4800F042FC62 -:100C0000A4E70D4800F03EFC0124A0E7C821002025 -:100C1000881100207C3D0008DC9703000068000874 -:100C2000843D0008903D0008A23D00080898FFF7A9 -:100C3000C03D0008DD3D0008063E00082DE9F04FEC -:100C4000ADB006AF80460C4600F06AFF05460028AE -:100C50006AD1237E022B18D1E38A012B15D100F033 -:100C60005BFC8146FFF7B0FD4FF4C873BD4EB0FB8F -:100C7000F3F209F5167902FB1300E37E19FA80F00E -:100C800030608BB9B84B00221A709C37BD46BDE866 -:100C9000F08F3B1D1D440095002308224FEAC90137 -:100CA000204601F02BF84D46A38A013BAB425FFA88 -:100CB00085F90BD905F10109B9F1110FE9D1AB4B58 -:100CC000AB4A40F23911AB4802F0B8FF07F114000B -:100CD000FFF792FD2A4607F11401381D02F0CCFF00 -:100CE00003460028CED1B9F1100F07D09E4B83F8F0 -:100CF00000903368A3F516733360C6E707F19802D6 -:100D0000014602F8950D20460092072200F0F6FFFA -:100D1000F9787F2904DD984B954A4FF4A871D2E702 -:100D2000404600F0E1FEB0E7E38A052B00F00681C3 -:100D300006D8012BA9D121464046FFF72DFEA4E796 -:100D4000282B3DD0302BA0D1637E8C4D01336A7BA4 -:100D5000DBB29342E94640F0EF80E27E2B7B9A4281 -:100D600040F0EA8007F19803002623F8846D1022F2 -:100D7000009331460123204600F0C0FFB4F81480F0 -:100D8000A8F102081FFA88F808F1030323F003030F -:100D90000A3323F00703ADEB030D0DF1180A3346B8 -:100DA0009BB2B11C98454FEAC10106F101066CDD0A -:100DB0005344009308220023204600F09FFFEEE7F3 -:100DC000A38A013B9BB2C92B3FF65FAF6B4E357BCD -:100DD0004DBB06F10C03009308222B462946204602 -:100DE00000F08CFFA38A05F10109013BEDB29D42A1 -:100DF0004FEAC90109DA0E3535440095002308226F -:100E0000204600F07BFF4D46ECE700230022C6E9B8 -:100E100000230023B36086F8D730C6F8D830337B80 -:100E20000BB9E37E3373002507F114063B1D08223E -:100E3000294630467D60BD60FD6001F0FBF83B7ADD -:100E400005F10109AB424FEAC90107D9FB68082245 -:100E50002B44304601F0EEF84D46F0E7C1F3CF01E8 -:100E60000023E07E059104960393A37E0293193438 -:100E7000282301460093019438A3D3E90023404678 -:100E800000F0A8FEFFF7C8FCFFE695F8D70000F0D9 -:100E900059FAD5F8D83006461BB995F8D70000F0B6 -:100EA00061FAD5F8D83043449E4204D295F8D70071 -:100EB000013000F057FA4FEA980B0024A0B25845D1 -:100EC00004F1010408DA2B6880000AEB000101221A -:100ED000184400F08BFAF1E7D5E90023D5F8D840A3 -:100EE00095F8D70012EB080243F100034444C5E92A -:100EF0000023C5F8D84000F025FA844209D395F8BC -:100F0000D730013385F8D730D5F8D8309E1BC5F8D7 -:100F1000D860B8F1FF0F08DC00232B7300F034FA1F -:100F2000FFF70CFE08B1FFF703FC2B68144A9B0A7D -:100F3000013313810023AB60CD46A6E6BFF34F8F8C -:100F40001049114BCA6802F4E0621343CB60BFF34F -:100F50004F8F00BFFDE700BFAFF3008026417272E4 -:100F6000DF25D7B79C21002099210020183E0008DA -:100F7000C83E0008713E0008933E0008C8210020CA -:100F80008811002000ED00E00400FA0508B54FF0DC -:100F900000530B4A196891420AD10A4A597D1170CF -:100FA00009481B7D0373C92208490E3000F004FA7A -:100FB000E02200214FF00050BDE8084000F00EBADA -:100FC0009AAD44C594110020C821002016000020CD -:100FD00030B5204C2049214885B002236371042399 -:100FE0000025ADF808300123ADF80C5007228DF82C -:100FF0000C308DF80B301A4B4B608DF80A2001F045 -:1010000003FE184B019500931749184B18484FF4ED -:10101000805200F033FD174B1978254611B1144862 -:1010200000F062FD00F078FA0446FFF7CDFB4FF4C4 -:10103000C87304F51674B0FBF3F202FB13000E4BF9 -:1010400014FA80F0186002F083FB08B10F232B81A3 -:1010500005B030BD8811002000110020E0220020E2 -:1010600003000600A5080008981100203D0C0008A8 -:10107000A0210020941100209C2100202DE9F04F98 -:1010800094A7D7E900670FF25429D9E900898D4C5C -:1010900093B0DFF850B2DFF850A2204600F0E6FD32 -:1010A0000CAD079098B310220021284600F096F965 -:1010B000079B197B4FF0000261F3030219468DF87C -:1010C000302051F8040F49680EAA03C21B680D9A1C -:1010D00063F31C029DF830300D9243F020038DF82D -:1010E000303000232A461946584601F09DFD0790EE -:1010F00030B9204600F0BEFD079B8AF80030CCE7EF -:101100009AF80030072B3EDC01338AF800301822B1 -:101110000021284600F062F9DFF8C8A10023194633 -:101120002A46504601F0A8FD014680BB102208A8BF -:1011300000F054F94FF09042536983F0100353616B -:1011400000F0ECF90B4612A9024611E903000DF17B -:10115000240E8EE803009DF83410C1F303008906C5 -:101160004CBF0E99BDF838108DF82C0046BFC1F366 -:101170001C0141F00041C1F30A010891204608A971 -:1011800000F0BEFFCAE7204600F074FDBFE720462E -:1011900000F0C6FC824600284AD1DFF850B100F0CA -:1011A000BBF9DBF80030984242D300F0B5F9079064 -:1011B000FFF70AFB079A8DF820A04FF4C87302F5D9 -:1011C0001672B0FBF3F101FB130012FA80F0CBF8BA -:1011D0000000DFF81CB19BF8001011B901238DF855 -:1011E000203028460791FFF707FB0799C1F1100A45 -:1011F0005FFA8AFABAF1060F28BF4FF0060A524684 -:1012000029440DF1210000F0D7F80AF101030493FD -:1012100008AB0393182302932B4B019301230093F4 -:1012200032463B46204600F07DFC00238BF8003020 -:1012300000F072F9254ADFF8BCA01368C31AB3F5B1 -:101240007A7F32D3106000F069F902460B462046DF -:1012500000F016FD204600F063FC30B39AF80C3025 -:10126000DFF894B0002B14BF032302238BF8053062 -:1012700000F052F94FF47A732946B0FBF3F0CBF843 -:1012800000005846FFF752FB182307300293104B1B -:101290000193C0F3CF0040F25513049000930395DF -:1012A00042464B46204600F03DFC9AF80C300BB10C -:1012B000FFF7B2FA9AF80C30002B7FF4EAAE13B0C5 -:1012C000BDE8F08FA021002098210020A822002056 -:1012D000AC220020401DA12026812A0BF1C6A7C107 -:1012E000D068080FE0220020AD2200209C210020C1 -:1012F00099210020C82100208811002070B502F03B -:10130000C3F8094C094E20700025306823788342C9 -:1013100008D902F0B5F8336805440133B5F5D04F6C -:101320003360F2D370BD00BFDC220020B022002069 -:1013300002F042B900F10060920000F5D04002F0E6 -:10134000E7B80000054B1A68054B1B789B1A8342CF -:1013500002D9104402F094B800207047B022002057 -:10136000DC22002038B5074D04462868204402F0EE -:101370008DF828B928682044BDE8384002F098B8B4 -:1013800038BD00BFB0220020064991F8243033B1A7 -:1013900000230822086A81F82430FFF7CBBF012020 -:1013A000704700BFB4220020022802BF4FF09043D4 -:1013B0004FF480129A61704710B50023934203D016 -:1013C000CC5CC4540133F9E710BD0000024603466B -:1013D000981A13F9011B0029FAD1704702440346F9 -:1013E000934202D003F8011BFAE770472DE9F0475A -:1013F000234C94F8243005468846174683BB2E4676 -:10140000DFF87C90C7B394F824302BB92022FF2159 -:1014100048462662FFF7E2FF94F82400C0F1080571 -:10142000BD4228BF3D465FFA85FAAD0041462A46D7 -:1014300004EB8000FFF7C0FF94F82430A7EB0A0705 -:101440009A445FFA8AFABAF1080F2E44A844FFB210 -:1014500084F824A0D6D1FFF797FF0028D2D108E066 -:10146000266A06EB8306B042CAD0FFF78DFF00283C -:10147000C5D10020BDE8F0870120BDE8F08700BF9E -:10148000B42200200FB4002004B070470FB44FF016 -:10149000FF3004B070470000FEE7000000B59BB0CD -:1014A000EFF3098168226846FFF786FFEFF30583B3 -:1014B000034B9A6B9A6A9A6A9A6A9A6A9B6AFEE7DF -:1014C00000ED00E000B59BB0EFF3098168226846AB -:1014D000FFF772FFEFF30583044B9A6B9A6A9A6ADF -:1014E0009A6A9A6A9A6A9B6AFEE700BF00ED00E07A -:1014F00000B59BB0EFF3098168226846FFF75CFFF7 -:10150000EFF30583034B5A6B9A6A9A6A9A6A9A6A4E -:101510009B6AFEE700ED00E002F086B802F060B8DA -:1015200030B5084D0A4491420BD011F8013B092413 -:101530005840013CF7D040F300032B4083EA5000B1 -:10154000F7E730BD2083B8ED0246006848B1036874 -:101550001360D388118901339BB29942D38038BF7D -:101560001381704770B588B00D46044620220021D3 -:101570006846FFF733FF20460495FFF7E5FF054671 -:1015800058B16B46044608AE1A4603CAB242206000 -:101590006160134604F10804F6D1284608B070BD16 -:1015A0002DE9F04130B9274B274A40F2C531274891 -:1015B00002F044FB0B7C23B9254B234A40F2C63191 -:1015C000F5E7C66986B9C161BDE8F081002B29DA6B -:1015D000930CAB4229D1B44201D10C60F3E7C8F8B7 -:1015E00000100C60BDE8F0814B6823F06047BD0C33 -:1015F0004FEAD37EC3F3807C15EA230538BF3D460E -:10160000B04634466368BEEBD37F23F06042DDD141 -:10161000974203D1C3F380739C450AD1974205E0FA -:101620001C46EFE7AA4206D013469D422CBF00237A -:101630000123002BCFD12368A046002BF0D12160DD -:10164000BDE8F0819C410008903F0008544200082A -:101650007542000808B5034A034B044840F25E3166 -:1016600002F0ECFA6C3F00081442000854420008F3 -:1016700008B503680B60C388016033B9044B054AA1 -:1016800005484FF4C76102F0D9FA013BC38008BD99 -:10169000E4410008E03F00085442000870B50C46E1 -:1016A00000F10C05616831B9E38A61F30903E38253 -:1016B0000020002170BD0E682846FFF7D9FF666044 -:1016C000F0E7000008B5426832B10B4B0B4A0C48FA -:1016D00040F22F4102F0B2FAC37DC3F3840101311D -:1016E00061F38603C375C38A62F30903C3821B0ACD -:1016F00062F3C713C37508BD304200089C3F000861 -:10170000544200082DE9F047089E32B91F4B204A89 -:10171000204840F2395102F091FA01F007054FEAF2 -:10172000D6082A4406F0070600EBD1004FF47F49A3 -:10173000954201D1BDE8F08705F0070E06F0070AD3 -:10174000D645774638BF5746C7F10807511BEC0806 -:101750008F4228BF0F46045D08EBD60104FA0EF451 -:1017600013F801C029FA07FE24FA0AF45FFA8EFE84 -:101770008CEA04044EFA0AFE04EA0E048CEA040C15 -:1017800003F801C03D443E44D2E700BFB041000829 -:10179000B43F0008544200082DE9F04106460F46C8 -:1017A00000254FF6FF7441F221082A46304639469B -:1017B000FEF7F6FCC0B284EA0024082314F4004FBC -:1017C0004FEA4404A4B203F1FF3318BF84EA0804CB -:1017D00013F0FF03F2D10835402DE6D12046BDE8D5 -:1017E000F081000010B50A4441F22104914200D179 -:1017F00010BD11F8013B80EA0320082310F4004FCC -:101800004FEA400080B203F1FF3318BF604013F08D -:10181000FF03F3D1EAE700002DE9F04F85B08A46D7 -:101820008DE80C00BDF83C40814630B9494B4A4A2E -:1018300040F26E31494802F001FA11F0604F04D0D5 -:10184000474B454A40F26F31F4E7009B002B7ED0B6 -:1018500024B10E9B002B7AD0072C28D809F10C005C -:10186000FFF772FE054628B96FF00205284605B05D -:10187000BDE8F08F14220021FFF7B0FD22460E993B -:1018800005F10800FFF798FD631C2B74009B1B7883 -:101890002C4403F01F0363F03F0323724AF000431C -:1018A0006B6029464846FFF77BFE0125DEE7019B7A -:1018B0001B0A4FF00008029300F10C034FF0800B5D -:1018C0004646454603930398FFF73EFE0746002829 -:1018D000CAD014220021FFF781FDB6BB9DF8043069 -:1018E0003B729DF808307B7202220E9B711E1944D8 -:1018F000B4420AD9B8180132D2B211F801EF80F817 -:1019000008E00136072AB6B2F2D1009B197801F03F -:101910001F01B44208BF4FF0400BB81841EA48110C -:101920004BEA0103037201324AF000437B603A74D0 -:1019300039464846FFF734FE0135B4422DB288F0EF -:1019400001084FF0000BBED190E70022CDE76FF009 -:1019500001058BE79C410008803F000854420008C5 -:10196000C04100082DE9F0471E46CB8A9146C3F3DB -:101970000902062A80460F4619D013460021B0B24C -:101980008DB25A1992B2052A09D9A84210D8FA8AFA -:10199000034463F30902FA820120BDE8F087A842FC -:1019A000F3D93A4419F8014094760131E8E700256B -:1019B000FB8A7C68C3F30900821F1C23B2FBF3FA85 -:1019C00003FB1A2A1FFA8AF27CB301212368002B39 -:1019D00039D1B31F03441C20B3FBF0F301339BB296 -:1019E00099420CD2BAF1000F09D14046FFF7ACFD85 -:1019F00008B1C0F800A0206008B304460022B6B2C7 -:101A00004FF0000AB54230D2691E49441346E0182F -:101A100001339BB211F801EF80F804E001351C2B73 -:101A2000ADB214D0AE42F2D8ECE74046FFF78CFDE1 -:101A3000044608B1002303607C60002CDED16FF007 -:101A40000200BDE8F087013189B21C46BEE7AE4214 -:101A5000D8D94046FFF778FD08B1C0F800A0206053 -:101A60000028ECD004460022CCE7FB8AC3F309022D -:101A7000164466F30903FB828EE70000F8B50E46B4 -:101A800015461F46044628B9144B154A15484F21E0 -:101A900002F0D4F824220021FFF7A0FC069B63602B -:101AA000079B23626A094FF6FF739A424FF00000CA -:101AB00028BF1A46A7602070A061E06197B204F1C8 -:101AC0000C05824205D100232B6027826382A3820A -:101AD000F8BD2E60013035462036F2E79841000807 -:101AE0000C3F00085442000808B528B9084B094AC1 -:101AF0007321094802F0A2F8037823B94BB2002BF6 -:101B000001DD017008BD054B024A7D21F1E700BFF0 -:101B10009C410008183F000854420008E0400008BB -:101B2000007870472DE9F7430D9EBDF828900B9D76 -:101B30009DF83040BDF8388007461946104616B962 -:101B4000B8F1000F43D11F2C41D83B78D3B9B8F17D -:101B5000070F39D839F0030339D1424631464FF6E1 -:101B6000FF70FFF73FFE4FEA092920F0010009F45A -:101B70004079400449EA0464400C44EA40244FF6AA -:101B8000FF730DE043EA0923B8F1070F43EA046449 -:101B9000F5D9FFF701FE42463146FFF723FE034623 -:101BA0008DE840012A4621463846FFF735FE0DB93B -:101BB000FFF750FD2B780133DBB21F2B88BF0023CA -:101BC0002B7003B0BDE8F0836FF00300F9E76FF00E -:101BD0000100F6E72DE9F7430E9F0B9D9DF8348039 -:101BE000BDF83C6081469DF8300007B9C6BB1F2890 -:101BF00036D899F800E0BEF1000F34D00C0244F062 -:101C000080049DF8281044EAC83444EA014444EAB8 -:101C10000E04072E44EA006415D919461046FFF752 -:101C2000BBFD32463946FFF7DDFD034601960097BE -:101C30002A4621464846FFF7EFFDB8F1010F0CD1C7 -:101C400025B9FFF707FD4FF6FF73EFE72B78013358 -:101C5000DBB21F2B88BF00232B7003B0BDE8F083DD -:101C60006FF00100F9E76FF00300F6E7C06900B11B -:101C700004307047C1690B68C3610C30FFF7F8BCD2 -:101C80002DE9F84FD0F818A0DFF86C80054616460D -:101C90001F4654464FF0000900F10C0B0CB9BDE88B -:101CA000F88FD4E90223B21A67EB0303994508BF02 -:101CB00090451FD2AB699C42214628460DD1FFF7C3 -:101CC000EDFCAB691B68AB6121465846FFF7D0FCC1 -:101CD000AC692346A2461C46E0E7FFF7DFFC236819 -:101CE000CAF8003021465846FFF7C2FC5446DAF8DD -:101CF0000030EFE72368EDE780841E002DE9F04F08 -:101D00008BB00D4614460793DDF8509082460028AC -:101D100000F06481B9F1000F00F06081531E3F2B89 -:101D200000F25C81012A03D1079B002B40F0568111 -:101D3000BAF81460F6000023B5420893099380F0C6 -:101D400053812B199E420AD2761B16F0FF0607D14B -:101D5000AB4BAC4A40F26751AB4801F06FFF2646EF -:101D6000DAF80C3023B9DAF81030002B00F0A58037 -:101D70002F2D31D8C5F1300846454FF000032CBF58 -:101D80005FFA88F8B0460093294608AB4246DAF875 -:101D90000800FFF7B7FCA6EB08074544FFB2BAF806 -:101DA000143003F10053063BDB000293DAF80C30E9 -:101DB00005934FF0300B059B002B51D087B9DAF813 -:101DC0001000002861D0002F5FD0AB4550D98F4B59 -:101DD0008C4A40F2A651BFE737464FF00008DEE7D5 -:101DE000029B23B98A4B874A4FF4B161B4E7029B47 -:101DF000E02B28BFE02306935B44AB4204931DD93C -:101E00005B1B9F4226BFDBB203930397AB4504D90C -:101E10007E4B7C4A40F291519EE70598CDF80080B8 -:101E200008ABA5EB0B01039A0430FFF76BFC039B97 -:101E30009844FF1A1D445FFA88F8FFB2049B9B4543 -:101E400004D3744B6F4A40F29B5185E7029B069A7C -:101E5000DDF810B09B1A0293059B1B680593AAE757 -:101E6000029BBB42ABD26C4B664A40F2A15173E776 -:101E7000CDF800803A46A5EB0B0108ABFFF742FC1A -:101E8000B8443D445FFA88F80027BAF81430B5EB3F -:101E9000C30F04D9614B5B4A40F2B1515CE7B8F122 -:101EA000400F04D95E4B574A40F2B25154E767B134 -:101EB0005C4B544A40F2B3514EE70093324608ABB4 -:101EC0002946DAF80800FFF71DFC731E3F2B35B2D8 -:101ED00001D8A64204DD544B544A40F235213BE779 -:101EE00060070AD00AAB03EBD401624211F8083C48 -:101EF00002F00702134101F8083C082C21D9102CEC -:101F000021D9202C8CBF08230423079A002A6DD0E6 -:101F1000B4EBC30F6CD0082C04F1FF3215D89DF838 -:101F2000203023FA02F2D10706D54FF0FF3202FA31 -:101F300004F423438DF820309DF8203089F80030D8 -:101F40004EE00123E1E70223DFE7102C11D8BDF8B2 -:101F5000203023FA02F2D20706D54FF0FF3202FA00 -:101F600004F42343ADF82030BDF82030A9F8003048 -:101F700036E0202C0ED8089921FA02F2D30705D5B5 -:101F80004FF0FF3303FA04F40C430894089BC9F89C -:101F9000003025E0402C1CD0DDE90867304639468A -:101FA000FEF7FEF8002100F0010050EA01030BD01B -:101FB000224601200021FEF7FFF8404261EB41017B -:101FC00006430F43CDE90867DDE90823C9E900238B -:101FD00006E0174B154A4FF42071BDE66FF001057E -:101FE00028460BB0BDE8F08F1D46F9E7012CA3D0C1 -:101FF000082CA1D9102CB7D9202CE5D8C6E700BFF2 -:10200000EC3F0008C43F0008544200080E4000089E -:10201000FB3F0008334000085B4000088240000896 -:10202000B0400008C8400008E2400008443F0008F3 -:10203000E040000830B585B030B9244B244A40F266 -:10204000B121244801F0FAFD23B9234B204A40F284 -:10205000B221F6E7402A04D9204B1D4A40F2B621AE -:10206000EFE722B91D4B1A4A4FF42F71E9E700241C -:10207000012A0294039417D11B788DF80830530776 -:102080000AD004AB03EBD203554213F8084C05F019 -:102090000705AC4003F8084C00910346002102A854 -:1020A000FFF730FB05B030BD082AE5D9102A03D868 -:1020B0001B88ADF80830E2E7202A02D81B6802939B -:1020C000DDE7D3E90045CDE90245D8E71C4100082A -:1020D000583F00085442000837410008E04000081B -:1020E00070B50C4600F10C05E16819B9A1602161D9 -:1020F000A18270BD0E682846FFF7BAFAE660F3E7E2 -:102100002DE9F04FD1F8009091B0C9F3C016044604 -:102110000D46CDE90223002E50D0C9F3C03BC9F3D0 -:102120000626B9F1000F80F29F8119F0C04F40F0F0 -:102130009B812B7B002B00F09781BBF1020F03D01A -:102140002278B24240F0938109F07F02BBF1020F86 -:10215000059236D119F07F0FC9F30F2A01D10AF089 -:10216000030A2B447606059A93F8038046EA0B4649 -:1021700046EA82465FEAD81346EA0A06069300F06A -:102180009A800022002310A961E90823059B00938F -:1021900067685B4652462046B847002800F08880B2 -:1021A000A7698FB9314604F10C00FFF7DBF9074648 -:1021B000D0B96FF0020011B0BDE8F08F4FF0020B04 -:1021C000AFE7C9F3074ACCE73B699E420DD03F68B1 -:1021D000002FF9D1314604F10C00FFF7C3F907468F -:1021E0000028E6D0A3693B60A761DDE90801FFF79D -:1021F000D3FAB882F97D08F01F06C1F38401711A81 -:1022000089B20FFA81FED7E90223BEF1000FB8BFF1 -:1022100001F1200EC9F30461B8BF0FFA8EFE0791D9 -:1022200052EA030100F02F81DDE90201801A61EB1F -:10223000030102460B469F480021994208BF904285 -:10224000C0F02181069B002B3FD0BEF1010F00F3AF -:102250001A8118F0400F38D0DDE90223C7E90223C4 -:10226000202200210DEB0200FFF7B8F8DDE9022380 -:10227000CDE908232B1D0A932B7BADF836A0013B3B -:10228000DBB2ADF834309DF81C308DF83A309DF853 -:1022900014308DF83B3020468DF838B08DF8396019 -:1022A000A36808A998473846FFF70CFA002082E790 -:1022B0006FF00B007FE7A76917B96FF00C007AE7A2 -:1022C0003B699E4296D03F68F6E7FB7DC8F340121B -:1022D000B2EBD31F40F0CE80C3F38403B34240F08F -:1022E000CC8006992B7B4FEA981279B3D2073CD465 -:1022F000032B40F2C580DDE90223C7E902232B7BD3 -:10230000AE1D033BDBB23246394604F10C00FFF749 -:1023100029FB002808DA39462046FFF7BFF938467E -:10232000FFF7D0F9032046E7AB883B832A7B033ACB -:10233000D2B2B88A3146FFF755FAFB7DB882DA434C -:10234000C2F3C01262F3C713FB75AFE76AB92E1D63 -:10235000013BDBB23246394604F10C00FFF702FBC9 -:102360000028D8DB2A7B013AE2E7FA8AC2F30902A5 -:10237000013B052AD9B250D8281D002399420AD919 -:1023800007EB020E013210F801CB8EF81AC00133B0 -:10239000062ADBB2F2D1DDE902898B4207F11A028B -:1023A000CDE908890A9238BF04337A680B9234BFAA -:1023B0005B1900230C93FB8AADF836A0C3F3090325 -:1023C00019449DF81C308DF83A309DF814308DF882 -:1023D0003B300023ADF834108DF838B08DF83960FB -:1023E0007B602A7BB88A013A291DFFF7FBF93B8BFA -:1023F000B882834203D1A36808A92046984708A958 -:102400002046FFF76DFE3846FFF75CF9B88A3B8B34 -:10241000984214BF11200020CDE6786810B34FF029 -:10242000060E03689BB9A2EB0E021B2A13D80332D7 -:10243000024405F1040E1F309942ACD91EF801CBBD -:1024400002F801CF01339042DBB2F5D1A3E70EF1E0 -:102450001C0E1846E5E7184B184A194840F2B3110C -:1024600001F0ECFB034696E76FF00900A3E66FF07E -:102470000A00A0E66FF00D009DE66FF00E009AE6F0 -:102480006FF00F0097E6FB7D68F386036FF3C713C9 -:10249000FB7539462046FFF701F9069B002B7FF4B8 -:1024A000D8AEFB7DC3F38402013262F38603FB7571 -:1024B00003E700BF80841E004C410008303F000845 -:1024C000544200082DE9F0414C4EB04240F081806A -:1024D0004B4CDFF830E1E56945F00075E561E469F2 -:1024E000846AD4F8007207EA0E0747F00107C4F8BF -:1024F0000072D4F8005205EA0E0545F0010545EAE0 -:102500000121C4F80012002A65D00021C4F81C1271 -:102510000F46C4F80412C4F80C12C4F8141204EBE9 -:10252000C10501310E29C5F84072C5F84472F6D1D3 -:102530004FF0000E4FF0010C964510D1826AD2F890 -:102540000032B04223F00103C2F8003253D12C4BC9 -:10255000DA6922F00072DA61DB69BDE8F0819F7808 -:102560001D8817F0010F18BFD4F804820CFA05F18A -:102570001CBF41EA0808C4F8048217F0020F1EBF0E -:10258000D4F80C8241EA0808C4F80C827F0742BFE5 -:10259000D4F814720F43C4F8147204EBC5055F68D5 -:1025A000C5F840729F68C5F84472D4F81C5229439C -:1025B000C4F81C120C330EF1010EBDE7846A002131 -:1025C000C4F81C12C4F80412C4F80C12C4F8141293 -:1025D000AEE7002AF2D1836A0022C3F84022C3F892 -:1025E0004422C3F80422C3F814220122C3F80C22A7 -:1025F000C3F81C22A2E7BDE8F08100BFE022002062 -:10260000001002400000FFFF184A916A08B58B686D -:102610008B6013F0010105D013F00C0F14BF4FF4C1 -:1026200080310121D80506D513F4406F14BF41F461 -:10263000003141F00201D80306D513F4402F14BF36 -:1026400041F4802141F00401D3690BB10748984758 -:10265000202383F311880021054800F087FE002322 -:1026600083F31188BDE8084001F088B8E02200201B -:10267000E822002038B5124CA36ADD68AA0712D000 -:102680005A6922F002025A61A36913B1012120465E -:102690009847202383F3118800210A4800F066FE42 -:1026A000002383F31188EB0606D5A36A1021D960B5 -:1026B000236A0BB102489847BDE8384001F05EB884 -:1026C000E0220020F022002038B5124CA36A1D69D8 -:1026D000AA0712D05A6922F010025A61A36913B1F5 -:1026E000022120469847202383F3118800210A48BD -:1026F00000F03CFE002383F31188EB0606D5A36AA5 -:1027000010211961236A0BB102489847BDE838408F -:1027100001F034B8E0220020F022002038B50F4C40 -:10272000A36A5D685D602A070AD5032222701A68D1 -:1027300022F002021A60636A13B100212046984712 -:102740006B0706D5A36A9969236A13B10904034884 -:102750009847BDE8384001F011B800BFE0220020E2 -:1027600010B50F4C204600F03DFA0E4BA3620B2132 -:10277000132000F017FA0B21142000F013FA0B219C -:10278000152000F00FFA0B21162000F00BFA0023A1 -:1027900020461A460E21BDE81040FFF793BE00BF49 -:1027A000E0220020006400400F4B984210B5044620 -:1027B00005D10E4BDA6942F00072DA61DB69A36A77 -:1027C00001221A60A36A5A68D20707D56268516865 -:1027D0001268D9611A60064A5A6110BD01210820A9 -:1027E00000F07CFCEEE700BFE02200200010024079 -:1027F0005B87010003291AD8DFE801F0020A0F14F1 -:10280000836A9B6813F0E05F14BF012000207047CB -:10281000836A9868C0F380607047836A9868C0F3E1 -:10282000C0607047836A9868C0F3007070470020EA -:102830007047000010B503291FD8DFE801F0021F20 -:102840002327816A8B68C3F30163183301EB0313F9 -:10285000107881061ED55468C0F30011490041EA82 -:10286000C40141F0040100F00F00586090689860C6 -:10287000D268DA6041F00101196010BD836A03F586 -:10288000C073E5E7836A03F5C873E1E7836A03F57C -:10289000D073DDE79488C0F30011490041EA445148 -:1028A000E1E7000001290CD003D3022910D0002059 -:1028B0007047836ADA68920701D1186903E0012042 -:1028C0007047836AD86810F0030018BF0120704772 -:1028D000836AF2E710B539B9836AD96889071BD1D1 -:1028E0001B699B0704D110BD012915D0022948D1CD -:1028F000816AD1F8C031D1F8C401D1F8C84114615E -:10290000D1F8CC41546120240C610C69A40717D183 -:102910004C6944F0100412E0816AD1F8B031D1F86A -:10292000B401D1F8B8411461D1F8BC4154612024FC -:10293000CC60CC68A40703D14C6944F002044C611C -:1029400011795C0864F304119C0864F3451111715A -:1029500089064BBF91681189DB085B0D4CBF63F39F -:102960001C0163F30A01137948BF916060F303030C -:1029700013714FEA10234FEA104058BF11811370B2 -:10298000508010BD002304491A465A50C818083315 -:10299000802B4260F9D170470C2300200268436805 -:1029A0001143016003B1184770470000024A1368E1 -:1029B00043F0C0031360704700380140024A1368B7 -:1029C00043F0C00313607047004400402DE9F04716 -:1029D000C66D3768F46934620546200719D014F0D3 -:1029E000080F0CBF00218021E20748BF41F0200101 -:1029F000A30748BF41F04001600748BF41F4807120 -:102A0000202383F31188281DFFF7C8FF002383F3D9 -:102A10001188E2050AD5202383F311884FF4007151 -:102A2000281DFFF7BBFF002383F311884FF0200917 -:102A30004FF0000A14F0200831D13B0616D54FF0B4 -:102A4000200905F1380A200610D589F3118850466F -:102A500000F04CFA00282FDA0821281DFFF79EFF0E -:102A600027F080033360002383F3118879060DD5A6 -:102A700062060BD5202383F31188EA6C2B6D9A42F2 -:102A800001D12B6CF3B9002383F31188E30621D520 -:102A9000AA6E1369F3B15069BDE8F047184789F38E -:102AA0001188B38C95F864102846194000F0AAFAF2 -:102AB0008AF31188F469BDE780B2308588F3118804 -:102AC000F469C0E71021281D27F04007FFF766FFD3 -:102AD0003760D8E7BDE8F08708B50348FFF776FF11 -:102AE000BDE8084000F04ABE8C23002008B503482A -:102AF000FFF76CFFBDE8084000F040BEF82300205F -:102B000037B51D4C1D4D204600F070FA009404F1BD -:102B10001400002320221A4900F032F920220094E8 -:102B200004F13800174B184900F0ACF9174BE36576 -:102B30002566174C0C21252000F034F8204600F0C3 -:102B400055FA04F11400009400232022114900F0EA -:102B500017F904F1380000940F4B1049202200F0BF -:102B600091F90F4BE3650C212620256603B0BDE8E3 -:102B7000304000F017B800BF8C2300200051250220 -:102B800064240020AD290008A4240020003801405E -:102B9000F823002084240020BD290008C42400203C -:102BA0000044004000F1604300F01F02400903F5BB -:102BB000614309018000C9B200F1604083F800134D -:102BC00000F5614001239340C0F8803103607047F5 -:102BD00000F16040090100F56D40C9B2017670470F -:102BE000FFF7BEBD00F108020123037082600023DD -:102BF000C26000F110024360026142618361C361FF -:102C0000036243627047000010B52023044683F33B -:102C10001188022303704160FFF7C6FD0323237070 -:102C2000002383F3118810BD2DE9F0411F460446AF -:102C30000D461646202383F3118800F108082378F7 -:102C4000042B0ED029462046FFF7D4FD48B120467C -:102C500032462946FFF7EEFD002080F31188BDE8DB -:102C6000F0813946404600F065FB0028E7D000239C -:102C700083F31188BDE8F0812DE9F0411F46044639 -:102C80000D461646202383F3118800F1100823789F -:102C9000042B0ED029462046FFF704FE48B12046FB -:102CA00032462946FFF716FE002080F31188BDE862 -:102CB000F0813946404600F03DFB0028E7D0002374 -:102CC00083F31188BDE8F081F8B51546826806697E -:102CD000AA420B46816938BF8568761AB542044618 -:102CE00007D218462A46FEF767FBA3692B44A36167 -:102CF0000DE011D932461846FEF75EFBAF1B3A468F -:102D0000E1683044FEF758FBE2683A44A261A368E8 -:102D10005B1BA3602846F8BD18462A46FEF74CFB0D -:102D2000E368E4E783682DE9F041044693421546E1 -:102D3000266938BF85684069361AB5420F4606D203 -:102D40002A46FEF739FB63692B4463610DE012D913 -:102D50003246A5EB0608FEF72FFB4246B919E0689C -:102D6000FEF72AFBE26842446261A3685B1BA36032 -:102D70002846BDE8F0812A46FEF71EFBE368E4E73B -:102D800010B50A440024C361029B00604060846067 -:102D9000C160816141610261036210BD08B5826951 -:102DA0004369934201D1826882B9826801328260AC -:102DB0005A1C42611970426903699A4201D3C3687F -:102DC0004361002100F0C6FA002008BD4FF0FF303B -:102DD00008BD000070B5202304460E4683F3118819 -:102DE000A568A5B1A368A269013BA360531CA361B8 -:102DF00015782269934224BFE368A361E3690BB1AC -:102E000020469847002383F31188284670BD314639 -:102E1000204600F08FFA0028E2DA85F3118870BDB1 -:102E20002DE9F74F05460F4690469A46D0F81C907C -:102E3000202686F311884FF0000B144664B1224619 -:102E400039462846FFF740FF034668B951462846F1 -:102E500000F070FA0028F1D0002383F31188A8EB6A -:102E6000040003B0BDE8F08FB9F1000F03D001906A -:102E70002846C847019B8BF31188E41A1F4486F348 -:102E80001188DBE7C16081614161C3611144009B2E -:102E9000006040608260016103627047F8B50446DB -:102EA0000E461746202383F31188A568A5B1A368B1 -:102EB000013BA36063695A1C62611E7023696269E9 -:102EC0009A4224BFE3686361E3690BB120469847E7 -:102ED000002080F31188F8BD3946204600F02AFA18 -:102EE0000028E2DA85F31188F8BD000083694269A1 -:102EF0009A4210B501D182687AB982680132826043 -:102F00005A1C82611C7803699A4201D3C3688361A9 -:102F1000002100F01FFA204610BD4FF0FF3010BD19 -:102F20002DE9F74F05460F4690469A46D0F81C907B -:102F3000202686F311884FF0000B144664B1224618 -:102F400039462846FFF7EEFE034668B95146284643 -:102F500000F0F0F90028F1D0002383F31188A8EBEA -:102F6000040003B0BDE8F08FB9F1000F03D0019069 -:102F70002846C847019B8BF31188E41A1F4486F347 -:102F80001188DBE7026843681143016003B1184709 -:102F9000704700001430FFF743BF00004FF0FF33CD -:102FA0001430FFF73DBF00003830FFF7B9BF000015 -:102FB0004FF0FF333830FFF7B3BF00001430FFF796 -:102FC00009BF00004FF0FF311430FFF703BF0000CE -:102FD0003830FFF763BF00004FF0FF323830FFF7A3 -:102FE0005DBF000000207047FFF78ABD044B0360FF -:102FF000002343608360C36001230374704700BFF4 -:103000009042000838B5C36904460D461BB9042137 -:103010000844FFF7B7FF294604F11400FFF7BEFE8E -:10302000002806DA201D4FF48061BDE83840FFF724 -:10303000A9BF38BD024B00221B605B609A607047DD -:10304000E4240020002303748268054B1B68996800 -:103050009142FBD25A68036042601060586070472A -:10306000E424002008B5202383F31188037C032B7C -:1030700005D0042B0DD02BB983F3118808BD43690B -:1030800000221A604FF0FF334361FFF7DBFF00239C -:10309000F2E790E80C001A6002685360F2E7000063 -:1030A000002303748268054B1B6899689142FBD822 -:1030B0005A6803604260106058607047E424002042 -:1030C000054B19690874186802681A605360186122 -:1030D00001230374FDF798BAE424002030B54B1C9B -:1030E00087B005460A4C10D023690A4A01A800F0AF -:1030F00059F92846FFF7E4FF049B13B101A800F03B -:103100006BF92369586907B030BDFFF7D9FFF8E7BD -:10311000E42400206530000838B50C4D41612B696E -:1031200081689A689142044603D8BDE83840FFF7A9 -:1031300089BF1846FFF786FF01232C6101462374DF -:103140002046BDE83840FDF75FBA00BFE424002008 -:10315000044B1A681B6990689B68984294BF0020D2 -:1031600001207047E424002010B5084C2368206932 -:103170001A6822605460012223611A74FFF790FFDD -:1031800001462069BDE81040FDF73EBAE424002066 -:1031900008B5FFF7DDFF18B1BDE80840FFF7E4BF51 -:1031A00008BD0000FEE7000010B5174CFFF742FF16 -:1031B00000F0EAF880221549204600F06FF801235C -:1031C00044F8180C0374124B124AD96821F4E061D8 -:1031D0000904090C0A431049DA60CA6842F0807297 -:1031E000CA600E490A6842F001020A601022DA77CA -:1031F000202283F82220002383F3118862B6084836 -:10320000BDE8104000F06CB80C250020B842000862 -:1032100000ED00E00003FA05F0ED00E0001000E032 -:10322000C0420008F8B50F4C226A013222622246E1 -:1032300052F8141F9142154606D08B68013B8B60F3 -:10324000202663699A6802B1F8BD1968DF68DA6000 -:103250004D60616182F311881869B84786F311885F -:10326000EFE700BFE4240020EFF3118020B9EFF373 -:103270000583202282F311887047000010B558B9E9 -:10328000EFF30584C4F3080414B180F3118810BD72 -:10329000FFF77EFF84F3118810BD000082600222D8 -:1032A00002740022427470478368A3F17C0243F8E1 -:1032B0000C2C026943F83C2C426943F8382C074A2D -:1032C00043F81C2CC26843F8102C022203F8082C87 -:1032D000002203F8072CA3F118007047210600080C -:1032E00010B5202383F31188FFF7DEFF0021044689 -:1032F000FFF712FF002383F31188204610BD000062 -:10330000024B1B6958610F20FFF7DABEE42400204E -:10331000202383F31188FFF7F3BF000008B50146AF -:10332000202383F311880820FFF7D8FE002383F3BE -:10333000118808BD49B1064B42681B6918605A6084 -:10334000136043600420FFF7C9BE4FF0FF307047A1 -:10335000E42400200368984206D01A680260506096 -:1033600059611846FFF76EBE7047000038B5044635 -:103370000D462068844200D138BD036823605C603C -:103380004561FFF75FFEF4E7054B03F114025A6154 -:103390009A614FF0FF32DA6100221A62704700BF73 -:1033A000E424002010B5C2600A4A036153699C6896 -:1033B000A1420CD85C680360446020605860816062 -:1033C0009868411A99604FF0FF33D36110BD091B13 -:1033D0001B68ECE7E4240020036881689A680A44CB -:1033E0009A604268136003685A600023C360024B0E -:1033F0004FF0FF32DA617047E4240020002070476C -:10340000FEE70000704700004FF0FF3070470000FB -:10341000BFF34F8F024AD368DB07FCD4704700BF6D -:103420000020024008B5074B1B7853B9FFF7F0FFA7 -:10343000054B1A69120641BF044A5A6002F18832EC -:103440005A6008BD70260020002002402301674515 -:1034500008B5054B1B7833B9FFF7DAFF034A136948 -:1034600043F08003136108BD702600200020024055 -:103470007F289ABF00F58030C0020020704700000E -:103480004FF4006070470000802070477F2808B527 -:103490000BD8FFF7EDFF00F500630268013204D19D -:1034A00004308342F9D1012008BD002008BD00008E -:1034B0007F2838B5044624D800F0B6F8124D2860AD -:1034C000FFF7A6FFFFF7AEFF104BF322DA600222F0 -:1034D0001A612046FFF7CCFF58611A6942F040029A -:1034E0001A61FFF795FF4FF4006100F0FBF8FFF75A -:1034F000AFFF00F099F828602046BDE83840FFF79C -:10350000C5BF002038BD00BF742600200020024047 -:103510002DE9F84312F00103144606D0204B40F287 -:103520004B221A600020BDE8F88385181D4A954299 -:1035300004D91B4A4FF414711160F3E7FFF772FFCF -:10354000FFF766FFDFF86C80451A4FF00109012C88 -:1035500005EB01060F4604D8FFF77AFF0120BDE80E -:10356000F883C8F8109031F8023B3380FFF750FF22 -:103570000020C8F8100033883A889BB29A420DD0D8 -:10358000074B40F267221A60074B1E60074B1C6016 -:10359000074B1F60FFF75CFFBDE8F883023CD6E7EE -:1035A0006C260020FFFF030860260020682600200C -:1035B0006426002000200240084908B50B7828B195 -:1035C00053B9FFF72FFF01230B7008BD23B1BDE8EE -:1035D00008400870FFF73CBF08BD00BF7026002000 -:1035E00038B5FFF741FE0D4B0D4A1C6A11684FF4C8 -:1035F0007A7303FB04F38B420A49D1E9004504D2F4 -:10360000003445F10105C1E90045E41845F1000524 -:103610001360FFF733FE2046294638BDE42400201E -:10362000782600208026002008B5FFF7D9FF4FF448 -:103630007A720023FCF7CCFD08BD00BF10B5024430 -:10364000064B0439D2B2904200D110BD441C00B2E6 -:1036500053F8200041F8040FE0B2F4E7502800408E -:10366000104B30B51C6A240407D41C6A44F440741F -:103670001C621C6A44F400441C620B4C236843F433 -:10368000807323600244094B0439D2B2904200D1C6 -:1036900030BD441C00B251F8045F43F82050E0B242 -:1036A000F4E700BF001002400070004050280040C6 -:1036B00007B5012201A90020FFF7C0FF019803B060 -:1036C0005DF804FB13B50446FFF7F2FFA04206D0F5 -:1036D00002A9012241F8044D0020FFF7C1FF02B00A -:1036E00010BD000070470000074B45F255521A60AC -:1036F00002225A6040F6FF729A604CF6CC421A6081 -:10370000024B01221A7070470030004089260020C9 -:10371000034B1B781BB1034B4AF6AA221A60704771 -:103720008926002000300040034B1B689B0042BFED -:10373000024B01221A707047241002408826002094 -:10374000024B4FF080721A60704700BF2410024095 -:10375000014B1878704700BF88260020064A53683E -:1037600023F001035360EFF30983683383F309887F -:10377000002383F31188704730EF00E010B5202359 -:1037800083F31188104B5B6813F4006318D0F1EEDB -:10379000103AEFF309844FF0807344F84C3C0B4B24 -:1037A000DB6844F8083CA4F1680383F30988FFF759 -:1037B000CFFC18B1064B44F8503C10BD054BFAE75E -:1037C00083F3118810BD00BF00ED00E030EF00E092 -:1037D000310600083406000870470000FEE70000CC -:1037E000084A094B09498B4204D3094A00219342F4 -:1037F00005D3704752F8040F43F8040BF3E743F87E -:10380000041BF4E740440008902600209026002086 -:10381000902600204B6843608B688360CB68C36050 -:103820000B6943614B6903628B6943620B680360F8 -:103830007047000008B5194B9A6A42F4FC029A627C -:103840009A6A22F4FC029A629A6A5A6942F4FC0269 -:103850005A61134A5B6911464FF09040FFF7DAFF57 -:10386000104802F11C01FFF7D5FF0F4802F13801A3 -:10387000FFF7D0FF0D4802F15401FFF7CBFF0C48D2 -:1038800002F17001FFF7C6FF0A4802F18C01FFF751 -:10389000C1FFBDE8084000F065B800BF001002405D -:1038A000E04200080004004800080048000C0048FE -:1038B000001000480014004808B500F08FF9FFF729 -:1038C00073FCBDE80840FFF72FBF00007047000001 -:1038D00010B5214CA26A62F4FC02A262A26A02F450 -:1038E000FC02A2624FF0FF31A26A226921612269C3 -:1038F000002222612069E068E160E168E260E1683D -:10390000E169164841F08051E161E169016841F4E3 -:1039100080710160216A01F44071B1F5407F1EBFE2 -:103920004FF4803323622262236A1B0407D4236A84 -:1039300043F440732362236A43F40043236200F09C -:103940002DF9A369064A43F00103A361A369136833 -:1039500043F02003136010BD0010024000700040CF -:10396000000001401C4B1A6842F001021A601A68FC -:103970009007FCD55A6822F003025A605A6812F088 -:103980000C02FBD1196801F0F90119605A601A683C -:1039900042F480321A601A689103FCD50F4A5A60CB -:1039A0004FF40452DA6230221A631A6842F08072CD -:1039B0001A601A689201FCD5094A122111605A68EE -:1039C00042F002025A605A6802F00C02082AFAD148 -:1039D0001A6B1A63704700BF0010024000241D00DC -:1039E00000200240084A08B5536911680B4003F0F3 -:1039F0000103536123B1054A13680BB1506898471E -:103A0000BDE80840FFF7BABE000401400C230020C7 -:103A1000084A08B5536911680B4003F0020353616B -:103A200023B1054A93680BB1D0689847BDE80840B8 -:103A3000FFF7A4BE000401400C230020084A08B58B -:103A4000536911680B4003F00403536123B1054A25 -:103A500013690BB150699847BDE80840FFF78EBE67 -:103A6000000401400C230020084A08B5536911687E -:103A70000B4003F00803536123B1054A93690BB16E -:103A8000D0699847BDE80840FFF778BE00040140C0 -:103A90000C230020084A08B5536911680B4003F055 -:103AA0001003536123B1054A136A0BB1506A98475A -:103AB000BDE80840FFF762BE000401400C2300206F -:103AC000174B10B55C691A68144004F478725A6197 -:103AD000A30604D5134A936A0BB1D06A98476006CF -:103AE00004D5104A136B0BB1506B9847210604D5CF -:103AF0000C4A936B0BB1D06B9847E20504D5094A89 -:103B0000136C0BB1506C9847A30504D5054A936C10 -:103B10000BB1D06C9847BDE81040FFF72FBE00BF37 -:103B2000000401400C2300201A4B10B55C691A6890 -:103B3000144004F47C425A61620504D5164A136DA0 -:103B40000BB1506D9847230504D5134A936D0BB103 -:103B5000D06D9847E00404D50F4A136E0BB1506E38 -:103B60009847A10404D50C4A936E0BB1D06E9847C8 -:103B7000620404D5084A136F0BB1506F98472304B1 -:103B800004D5054A936F0BB1D06F9847BDE810403C -:103B9000FFF7F4BD000401400C230020062108B506 -:103BA0000846FEF7FFFF06210720FEF7FBFF062170 -:103BB0000820FEF7F7FF06210920FEF7F3FF062194 -:103BC0000A20FEF7EFFF06211720FEF7EBFF062184 -:103BD0002820BDE80840FEF7E5BF000008B5FFF764 -:103BE00077FEFEF7CFFEFEF7FBFFFFF7FDF9FFF7CD -:103BF0006DFEBDE8084000F001B8000000F00EB80E -:103C000008B5202383F31188FFF70CFB002383F30F -:103C10001188BDE80840FFF7B1BD0000054B064A1A -:103C20005A6000229A6007221A6008210B20FEF7D2 -:103C3000CFBF00BF10E000E03F1901001FB51C46D8 -:103C4000094B1B680546D86852B1084B02928DE8B3 -:103C50000A0022462B460649FDF718FC00F042F800 -:103C6000044B1A46F2E700BF1011002088430008F9 -:103C700095430008143E000810B5013902449042F3 -:103C800001D1002010BD10F8013B11F8014FA342F3 -:103C9000F5D0181B10BD00002DE9F84307468846F3 -:103CA00091461E468BB10D46A8EB0500B54207EBC9 -:103CB000000402D20020BDE8F8833246494620467F -:103CC000FFF7DAFF18B1013DEEE7BDE8F8832046C3 -:103CD000BDE8F883034611F8012B03F8012B002AF5 -:103CE000F9D1704708B5062000F02CF80120FFF745 -:103CF00087FB00001F2938B504460D4604D916235A -:103D000003604FF0FF3038BD426C12B152F82130E1 -:103D10004BB9204600F030F82A4601462046BDE85F -:103D2000384000F017B8012B0AD0591C03D11623D4 -:103D30000360012038BD002442F8254028469847FA -:103D4000002038BD024B01461868FFF7D3BF00BF03 -:103D50001011002038B5074C0023054608461146CF -:103D60002360FFF751FB431C02D1236803B12B6092 -:103D700038BD00BF8C260020FFF740BB40A2E4F115 -:103D8000646891064E6F20617070207369670A0045 -:103D9000426164206677206C656E677468202575C3 -:103DA0000A0042616420626F6172645F6964202569 -:103DB000752073686F756C642062652025750A0034 -:103DC0004261642066772064657363726970746F02 -:103DD00072206C656E6774682025750A0042616404 -:103DE0002061707020435243203078253038783A73 -:103DF000307825303878203078253038783A307867 -:103E0000253038780A00476F6F64206669726D77D5 -:103E10006172650A00000000726563656976656419 -:103E20005F756E697175655F69645F6C656E203C76 -:103E30002055415643414E5F50524F544F434F4CD3 -:103E40005F44594E414D49435F4E4F44455F49449D -:103E50005F414C4C4F434154494F4E5F554E495181 -:103E600055455F49445F4D41585F4C454E47544866 -:103E7000002E2E2F2E2E2F546F6F6C732F41505FFC -:103E8000426F6F746C6F616465722F63616E2E6335 -:103E9000707000616C6C6F63617465645F6E6F64F9 -:103EA000655F6964203C3D20313237006F72672EB8 -:103EB0006172647570696C6F742E6D726F5F6D31B5 -:103EC0003030323500000000766F69642068616E22 -:103ED000646C655F616C6C6F636174696F6E5F7257 -:103EE0006573706F6E73652843616E617264496EAD -:103EF0007374616E63652A2C2043616E6172645233 -:103F0000785472616E736665722A290063616E610E -:103F10007264496E6974000063616E617264536516 -:103F2000744C6F63616C4E6F64654944000000001F -:103F300063616E61726448616E646C65527846724A -:103F4000616D650063616E6172644465636F646591 -:103F50005363616C6172000063616E617264456EEF -:103F6000636F64655363616C61720000696E6372B4 -:103F7000656D656E745472616E7366657249440056 -:103F8000656E717565756554784672616D6573000F -:103F900070757368547851756575650070726570D9 -:103FA000617265466F724E6578745472616E7366A5 -:103FB00065720000636F7079426974417272617951 -:103FC000000000006465736361747465725472610B -:103FD0006E736665725061796C6F616400000000F9 -:103FE00066726565426C6F636B0000006269745FA6 -:103FF0006C656E677468203E20300072656D616983 -:104000006E696E675F62697473203E203000696E6E -:104010007075745F6269745F6F6666736574203E65 -:104020003D20626C6F636B5F6269745F6F6666737D -:10403000657400626C6F636B5F656E645F62697468 -:104040005F6F6666736574203E20626C6F636B5FA2 -:104050006269745F6F66667365740072656D61692D -:104060006E696E675F6269745F6C656E6774682005 -:104070003C3D2072656D61696E696E675F6269744F -:104080007300696E7075745F6269745F6F666673E2 -:104090006574203C3D207472616E736665722D3EBE -:1040A0007061796C6F61645F6C656E202A203800E6 -:1040B0006F75747075745F6269745F6F666673653F -:1040C00074203C3D2036340072656D61696E696E06 -:1040D000675F6269745F6C656E677468203D3D2040 -:1040E000300028726573756C74203E2030292026BC -:1040F000262028726573756C74203C3D2036342967 -:104100002026262028726573756C74203C3D206241 -:1041100069745F6C656E6774682900006465737408 -:10412000696E6174696F6E20213D202828766F6961 -:1041300064202A2930290076616C756520213D2094 -:104140002828766F6964202A293029006F666673F3 -:1041500065745F77697468696E5F626C6F636B200A -:104160003C2028333255202D205F5F6275696C74C6 -:10417000696E5F6F66667365746F66202843616E53 -:10418000617264427566666572426C6F636B2C2067 -:1041900064617461292900006F75745F696E732012 -:1041A000213D202828766F6964202A2930290000C3 -:1041B0007372635F6C656E203E2030550000000016 -:1041C0002863616E5F696420262030783146464658 -:1041D000464646465529203D3D2063616E5F696431 -:1041E00000000000616C6C6F6361746F722D3E7330 -:1041F0007461746973746963732E63757272656E2A -:10420000745F75736167655F626C6F636B73203E8B -:10421000203000007472616E736665725F6964209D -:10422000213D202828766F6964202A293029000042 -:1042300073746174652D3E6275666665725F626C4B -:104240006F636B73203D3D202828766F6964202AB8 -:10425000293029002E2E2F2E2E2F6D6F64756C6540 -:10426000732F6C696263616E6172642F63616E614A -:1042700072642E63006974656D2D3E6672616D65B2 -:104280002E646174615F6C656E203E20300000001A -:1042900000000000B12F00089D2F0008D92F000852 -:1042A000C52F0008D12F0008BD2F0008A92F000836 -:1042B000952F0008E52F00086D61696E0000000071 -:1042C000D8420008282500206026002001000000B8 -:1042D000A53100080000000069646C650000000062 -:1042E000A001A82A00000000FAAABEAA50001400EB -:1042F000EFFF000000770000709709000100000048 -:1043000000000000AAAAAAAA01000000FFFF000006 -:10431000000000000000000000000000000000009D -:10432000AAAAAAAA00000000FFFF000000000000E7 -:10433000000000000000000000000000AAAAAAAAD5 -:1043400000000000FFFF000000000000000000006F -:104350000000000000000000AAAAAAAA00000000B5 -:10436000FFFF00000000000000000000000000004F -:1043700000000000AAAAAAAA00000000FFFF000097 -:1043800000000000000000002C2066756E63746958 -:104390006F6E3A2000617373657274696F6E2022CC -:1043A000257322206661696C65643A2066696C65D4 -:1043B00020222573222C206C696E652025642573CC -:1043C00025730A003CBEFF7F0100000000000000D2 -:1043D0006400000000000000FE2A0100D20400007A -:1043E0001411002000000000000000000000000088 -:1043F00000000000000000000000000000000000BD -:1044000000000000000000000000000000000000AC -:10441000000000000000000000000000000000009C -:10442000000000000000000000000000000000008C -:10443000000000000000000000000000000000007C -:044440000000000078 +:1000000000090020A5040008E1140008611400089C +:10001000B9140008611400088D140008A704000832 +:10002000A7040008A7040008A704000881350008F9 +:10003000A7040008A7040008A7040008B93A0008AC +:10004000A7040008A7040008A7040008A7040008E4 +:10005000A7040008A7040008513800087D380008EC +:10006000A9380008D538000801390008A70400089D +:10007000A7040008A7040008A7040008A7040008B4 +:10008000A7040008A7040008A70400082924000802 +:1000900095240008E92400083D2500082D390008B2 +:1000A000A7040008A7040008A7040008A704000884 +:1000B000A7040008A7040008A7040008A704000874 +:1000C000A7040008A7040008A7040008A704000864 +:1000D000A70400088129000895290008A704000842 +:1000E00095390008A7040008A7040008A704000821 +:1000F000A7040008A7040008A7040008A704000834 +:10010000A7040008A7040008A7040008A704000823 +:10011000A7040008A7040008A7040008A704000813 +:10012000A7040008A7040008A7040008A704000803 +:10013000A7040008A7040008A7040008A7040008F3 +:10014000A7040008A7040008A7040008A7040008E3 +:10015000A7040008A7040008A7040008A7040008D3 +:10016000A7040008A7040008A7040008A7040008C3 +:10017000A7040008A7040008A7040008A7040008B3 +:10018000A7040008A7040008A7040008A7040008A3 +:10019000A7040008A7040008A7040008A704000893 +:1001A00053B94AB9002908BF00281CBF4FF0FF31DE +:1001B0004FF0FF3000F074B9ADF1080C6DE904CEDA +:1001C00000F006F8DDF804E0DDE9022304B0704732 +:1001D0002DE9F047089D04468E46002B4DD18A42FA +:1001E000944669D9B2FA82F252B101FA02F3C2F12D +:1001F000200120FA01F10CFA02FC41EA030E9440BE +:100200004FEA1C48210CBEFBF8F61FFA8CF708FBDE +:1002100016E341EA034306FB07F199420AD91CEBB6 +:10022000030306F1FF3080F01F81994240F21C81E8 +:10023000023E63445B1AA4B2B3FBF8F008FB103330 +:1002400044EA034400FB07F7A7420AD91CEB040465 +:1002500000F1FF3380F00A81A74240F20781644435 +:10026000023840EA0640E41B00261DB1D4400023BA +:10027000C5E900433146BDE8F0878B4209D9002D1E +:1002800000F0EF800026C5E9000130463146BDE8A8 +:10029000F087B3FA83F6002E4AD18B4202D3824212 +:1002A00000F2F980841A61EB030301209E46002DC1 +:1002B000E0D0C5E9004EDDE702B9FFDEB2FA82F216 +:1002C000002A40F09280A1EB0C014FEA1C471FFA74 +:1002D0008CFE0126200CB1FBF7F307FB131140EA5B +:1002E00001410EFB03F0884208D91CEB010103F128 +:1002F000FF3802D2884200F2CB804346091AA4B2EA +:10030000B1FBF7F007FB101144EA01440EFB00FEBD +:10031000A64508D91CEB040400F1FF3102D2A64522 +:1003200000F2BB800846A4EB0E0440EA03409CE7C1 +:10033000C6F12007B34022FA07FC4CEA030C20FA6E +:1003400007F401FA06F31C43F9404FEA1C4900FA8E +:1003500006F3B1FBF9F8200C1FFA8CFE09FB18110B +:1003600040EA014108FB0EF0884202FA06F20BD97E +:100370001CEB010108F1FF3A80F08880884240F2CE +:100380008580A8F102086144091AA4B2B1FBF9F012 +:1003900009FB101144EA014100FB0EFE8E4508D90D +:1003A0001CEB010100F1FF346CD28E456AD9023892 +:1003B000614440EA0840A0FB0294A1EB0E01A14277 +:1003C000C846A64656D353D05DB1B3EB080261EBE5 +:1003D0000E0101FA07F722FA06F3F1401F43C5E9BF +:1003E000007100263146BDE8F087C2F12003D840F5 +:1003F0000CFA02FC21FA03F3914001434FEA1C4737 +:100400001FFA8CFEB3FBF7F007FB10360B0C43EA28 +:10041000064300FB0EF69E4204FA02F408D91CEBD8 +:10042000030300F1FF382FD29E422DD902386344D6 +:100430009B1B89B2B3FBF7F607FB163341EA034176 +:1004400006FB0EF38B4208D91CEB010106F1FF38C5 +:1004500016D28B4214D9023E6144C91A46EA0046BC +:1004600038E72E46284605E70646E3E61846F8E64E +:100470004B45A9D2B9EB020864EB0C0E0138A3E797 +:100480004646EAE7204694E74046D1E7D0467BE778 +:10049000023B614432E7304609E76444023842E7F0 +:1004A000704700BF02E000F000F8FEE772B63A487D +:1004B00080F30888394880F3098839484EF6085196 +:1004C000CEF20001086040F20000CCF200004EF6CF +:1004D0003471CEF200010860BFF34F8FBFF36F8F0E +:1004E00040F20000C0F2F0004EF68851CEF200015A +:1004F0000860BFF34F8FBFF36F8F4FF00000E1EE46 +:10050000100A4EF63C71CEF200010860062080F31E +:100510001488BFF36F8F03F0B3F803F08FF803F084 +:10052000C1F84FF055301F491B4A91423CBF41F87A +:10053000040BFAE71C49194A91423CBF41F8040BED +:10054000FAE71A491A4A1B4B9A423EBF51F8040B6C +:1005500042F8040BF8E700201749184A91423CBFC3 +:1005600041F8040BFAE703F06DF803F0D7F8144CE8 +:10057000144DAC4203DA54F8041B8847F9E700F045 +:1005800041F8114C114DAC4203DA54F8041B884772 +:10059000F9E703F055B80000000900200011002021 +:1005A000000000080001002000090020F83C0008BD +:1005B00000110020201100202011002028260020FA +:1005C000A0010008A0010008A0010008A001000887 +:1005D0002DE9F04F2DED108AC1F80CD0C3689D466F +:1005E000BDEC108ABDE8F08F002383F31188284604 +:1005F000A047002002F04CFDFEE702F0D1FC00DF36 +:10060000FEE700002DE9F04102F062FF074602F02C +:10061000ADFF054600283ED12B4B9F423BD0013316 +:100620009F423BD0294B27F0FF029A423AD1F8B2C1 +:1006300000F054FAA84642F2107400F059FC08B1D8 +:100640000024A04600F050FA064678B384BB464624 +:1006500035B11F4B9F4203D002F080FF0024264695 +:10066000002002F03FFF1B4B1B6913F0400322D018 +:100670000EB100F031F800F05FFC00F031FE00F048 +:1006800031FF0546CCB100F02DFF401BA04214D92C +:1006900000F022F8F3E7A8460024CEE704464FF026 +:1006A0000108CAE780464FF47A74C6E70446CFE7EC +:1006B0004FF47A74CCE71C46DDE700F0DDFC012046 +:1006C00002F0ECFCDEE700BF010007B0000008B05C +:1006D000263A09B00004004838B51D4A1D4B196878 +:1006E000013134D004339342F9D11B4C194DD4F865 +:1006F0000428AA422BD3194B9B6803F1006303F52E +:10070000D0439A4223D202F0FDFE02F00FFF0020F8 +:1007100000F000FE124B0220187000F037FE114B63 +:10072000DA690022DA61D96999699A619B6972B6BE +:100730004FF0E0232021C3F8085DD4F80038D4F846 +:10074000042881F311889D4683F30888104738BD3B +:100750002068000800680008006000080011002000 +:100760002011002000100240094A136849F2690074 +:1007700099B21B0C00FB01331360064B186844F25E +:10078000506182B2000C01FB0200186080B2704719 +:100790001C1100201811002010B500211022044661 +:1007A00000F00EFE034B03CB206061601868A06070 +:1007B00010BD00BFACF7FF1F2DE9F043224DBBB0C9 +:1007C00000F090FEAB6840F2ED22C31A934232D99A +:1007D00006AFA8602B4628220021384601F05EFBB8 +:1007E00005F10E0000F0E4FD002604465FFA80F9F2 +:1007F00005F10E08F3B2F100994501F1280107D97E +:1008000008EB06030822384601F048FB0136F1E701 +:1008100008230122CDE9023205340C4B0193A4B226 +:1008200030230093CDE9047405A3D3E90023297B89 +:10083000074801F04BF93BB0BDE8F083AFF300800F +:1008400078F6339F93CACD8D682100207521002052 +:100850003C21002070B50D4614461E4601F0CCF830 +:1008600050B9022E10D1012C0ED112A3D3E90023CE +:10087000C5E90023012007E0282C10D005D8012C61 +:1008800009D0052C0FD0002070BD302CFBD10BA35C +:10089000D3E90023ECE70BA3D3E90023E8E70BA39C +:1008A000D3E90023E4E70BA3D3E90023E0E700BF8B +:1008B000AFF30080401DA12026812A0B78F6339FDC +:1008C00093CACD8D9E6AC421818A46EE26417272FA +:1008D000DF25D7B7F017304A39059E5613B50446C1 +:1008E0002346084620220021019001F0D7FA227900 +:1008F0000198032A234628BF032203F8042F20214E +:10090000022201F0CBFA62790198072A234628BF18 +:10091000072203F8052F2221032201F0BFFAA27952 +:100920000198072A234628BF072203F8062F25210E +:10093000032201F0B3FA019804F1080310222821E0 +:1009400001F0ACFA382002B010BD00002DE9F04FE4 +:10095000ADF5017D21AD0EAE40F2751280460F4619 +:1009600022A80021296000F02BFD482200213046FA +:1009700000F026FD00F0B6FD564B4FF47A72B0FB46 +:10098000F2F0186093E80700012386E807000DF1F4 +:100990005A003382FFF700FF4EF60343338407AB60 +:1009A00018464D4903F0C2F81822306429463046F3 +:1009B00086F83C20FFF792FF12AB0446014608225E +:1009C000284601F06BFA0822A1180DF149032846C8 +:1009D00001F064FA0DF14A03082204F110012846DF +:1009E00001F05CFA13AB202204F11801284601F053 +:1009F00055FA14AB402204F13801284601F04EFAB2 +:100A000016AB082204F17801284601F047FA0DF1EF +:100A10005903082204F18001284601F03FFA04F14D +:100A2000880A0DF15A0904F5847B4B465146082289 +:100A300028460AF1080A01F031FAD34509F1010903 +:100A4000F3D11BAB08225946284601F027FA04F5DA +:100A500088744FF0000996F834304B450AD9B36BCF +:100A600021464B440822284601F018FA083409F1BF +:100A70000109F0E74FF0000996F83C304B4504EBD4 +:100A8000C90108D9336C08224B44284601F006FA04 +:100A900009F10109F0E700230393BB7E02930731BC +:100AA00007F119030193C1F3CF010123CDE90451EB +:100AB0000093F97E05A3D3E90023404601F006F830 +:100AC0000DF5017DBDE8F08FAFF300809E6AC42173 +:100AD000818A46EE241100203C3B0008014B18702F +:100AE000704700BF30110020F0B5334B1C7B85B040 +:100AF00034B1324B0E221A810024204605B0F0BDDD +:100B00002F4A1068516802AB03C308232D492E48B1 +:100B10000DEB030202F0E8FF054630B9274B2B48E6 +:100B20000A221A8100F098FCE6E70169B1F5663FF8 +:100B300006D9224B26480B221A8100F08DFCDCE7F7 +:100B4000438BB3F57B7F09D01C4A22480C211181CD +:100B50004FF47B72194600F07FFCCEE71E4A024438 +:100B600002F11003994204D2144B1C4810221A813E +:100B7000E3E710398E1A2046134900F0B7FC3246DD +:100B8000074605F11801204600F0B0FCAB689F4213 +:100B900002D1EB6898420AD0084B0D221A810090CE +:100BA000D5E902123B460E4800F056FCA4E70D487A +:100BB00000F052FC0124A0E768210020241100204D +:100BC000E93B0008DC97030000680008583B000878 +:100BD000643B0008763B00080898FFF7943B000848 +:100BE000B13B0008DA3B00082DE9F04FADB006AF8D +:100BF00080460C4600F000FF054600285AD1237EAF +:100C0000022B1BD1E38A012B18D100F06BFC0646A6 +:100C1000FFF7AAFD03464FF4C870DFF8D092B3FB8C +:100C2000F0F206F5167602FB103316FA83F3C9F8D4 +:100C30000030E37E33B9A84B00221A709C37BD46C2 +:100C4000BDE8F08FA38AEEB2013BB34205F1010586 +:100C50000BD93B1D1E44E90000960023082201F039 +:100C6000F801204600F0DEFFECE707F11400FFF783 +:100C700093FD324607F11401381D02F025FF0028CC +:100C8000D9D10F2E08D8944B1E70D9F80030A3F597 +:100C90001673C9F80030D1E7FB1CF87001460093C9 +:100CA00007220346204600F0BDFFF978404600F0D9 +:100CB0009BFEC3E7E38A282B26D010D8012B1ED039 +:100CC000052BBBD1BFF34F8F8449854BCA6802F413 +:100CD000E0621343CB60BFF34F8F00BFFDE7302BC3 +:100CE000ACD1637E7F4D01336A7BDBB29342E94630 +:100CF00003D1E27E2B7B9A4265D0CD469EE721460A +:100D00004046FFF723FE99E7A38A013B9BB2C92B1C +:100D100094D8744D2E7B26BB05F10C03009308225A +:100D200033463146204600F07DFF731CF2B2D900F5 +:100D30001E46A38A013B9A4205DA0E322A440092EB +:100D400000230822EEE700230022C5E90023002348 +:100D5000AB6085F8D730C5F8D8302B7B0BB9E37E74 +:100D60002B73002507F114093B1D0822294648462C +:100D7000C7E90155FD6001F091F83B7A05F1010AE0 +:100D8000AB424FEACA0608D9FB6808222B44314619 +:100D9000484601F083F85546EFE7C6F3CF06E17EFB +:100DA000CDE9049600230393A37E029319342823EC +:100DB0000093019446A3D3E90023404600F086FE49 +:100DC000FFF7FAFC3AE74FF0000807F11403A7F821 +:100DD00014801022009341460123204600F022FF98 +:100DE000A68A023EB6B2F31C9B109B000733DB08B9 +:100DF000A9EBC3039D460DF1180A1FFA88F34FEAC9 +:100E0000C801B34201F110010AD20AEB08030093B2 +:100E100008220023204600F005FF08F10108ECE756 +:100E200095F8D70000F080FAD5F8D83004461BB901 +:100E300095F8D70000F088FAD5F8D83033449C42B2 +:100E400004D295F8D700013000F07EFA4FEA960BF5 +:100E50004FF000081FFA88F18B45D5E9003209D917 +:100E60000AEB880103EB8800012200F0B1FA08F1D7 +:100E70000108EFE7F31842F10002C5E90032D5F8A6 +:100E8000D83095F8D70006EB0308C5F8D88000F0F5 +:100E90004BFA804509D395F8D730D5F8D8000133FF +:100EA000001B85F8D730C5F8D800FF2E08D80023DE +:100EB0002B7300F05BFAFFF717FE08B1FFF70CFC8D +:100EC0002B68094A9B0A013313810023AB6014E7A6 +:100ED00026417272DF25D7B73521002000ED00E0F2 +:100EE0000400FA0568210020241100203821002088 +:100EF00010B54FF000540C4B22689A4211D10B4BA5 +:100F0000627D1A700A48237D03730A49C9220E3094 +:100F100000F044FAE0220021204600F051FA0120BE +:100F200010BD0020FCE700BF9AAD44C53011002081 +:100F300068210020160000202DE9FF41434C0223C8 +:100F400063710023029324250A23581EB5FBF3F690 +:100F50007343D3F12402C1B23ED002280346F4D138 +:100F60009DF80B303A493B485A1E9DF80A30013B28 +:100F70001B0443EA0253BDF80820013A13434B60B7 +:100F800001F044FD00230193334B3449009334486E +:100F9000344B4FF4805200F001FD334B197811B1FE +:100FA0002F4800F021FD00F09DFA0546FFF7DCFB1D +:100FB0004FF4C873B0FBF3F202FB130305F5167090 +:100FC00010FA83F0294B186002F0D0FA08B10F2311 +:100FD000238104B0BDE8F081C1EBC107FB1C4FEADF +:100FE000E30EC3F3C703A1EB030C0EF101084FF4AA +:100FF0007A705FFA8CF50EFB000058FA8CFCB0FB9F +:10100000FCF0B0F5617F07D97B1EC3F3C703C91A93 +:10101000CDB2591E0F2916D86A1E072A8CBF00228E +:101020000122591901FB06601149B1FBF0F1114889 +:10103000814295D1002A93D0ADF808608DF80A302E +:101040008DF80B508CE71346EBE700BF241100200E +:1010500010110020802200205508000834110020C3 +:101060003C210020E90B000830110020382100202D +:101070000051250240420F002DE9F04F90A7D7E91B +:1010800000670FF24429D9E90089874D93B0DFF852 +:1010900040B2864C284600F07DFD0DF1300A0790E5 +:1010A00070B310220021504600F08AF9079B197B8B +:1010B0004FF0000261F303028DF830205868996800 +:1010C0000EAA03C21B680D9A63F31C029DF8303010 +:1010D0000D9243F020038DF830300023524619461C +:1010E000584601F0A3FC079028B9284600F056FDA9 +:1010F000079B2370CEE72378072B3CD8013323705E +:1011000018220021504600F05BF9DFF8C4B100233B +:1011100019465246584601F0B1FC014678BB1022F0 +:1011200008A800F04DF94FF0904209AC536983F0E4 +:101130001003536100F0D8F90B4612A9024611E9D9 +:10114000030084E803009DF83410C1F3030089060E +:101150004CBF0E9CBDF838408DF82C0046BFC4F340 +:101160001C0444F00044C4F30A0408A92846089467 +:1011700000F0DCFECBE7284600F010FDC0E7284673 +:1011800000F03AFC0446002848D1DFF848B100F0EE +:10119000A9F9DBF80030984240D300F0A3F907909A +:1011A000FFF7E2FA079A8DF8204003464FF4C87023 +:1011B00002F51672B3FBF0F101FB103312FA83F360 +:1011C000CBF80030DFF810B19BF8001011B9012303 +:1011D0008DF8203050460791FFF7DEFA0799C1F1EC +:1011E0001004E4B2062C28BF0624224651440DF117 +:1011F000210000F0D3F808AB0393182302930134C5 +:101200002B4B0193E4B20123009304943B463246F6 +:10121000284600F0F3FB00238BF8003000F062F961 +:10122000244A254C1368C31AB3F57A7F31D3106072 +:1012300000F05AF902460B46284600F0B9FC284651 +:1012400000F0DAFB28B3237BDFF890B0002B14BF4B +:10125000032302238BF8053000F044F94FF47A732E +:101260005146B0FBF3F0CBF800005846FFF736FBD1 +:10127000182307300293114B0193C0F3CF0040F2C3 +:101280005513CDE903A0009342464B46284600F093 +:10129000B5FB237B2BB1FFF78FFA237B002B7FF469 +:1012A000F6AE13B0BDE8F08F3C2100204D220020A7 +:1012B0003421002048220020682100204C220020F8 +:1012C000401DA12026812A0BF1C6A7C1D068080FB6 +:1012D0008022002038210020352100202411002008 +:1012E00070B501F0B5FF094E094D30800024286823 +:1012F0003388834208D901F0A7FF2B6804440133E7 +:10130000B4F5D04F2B60F2D370BD00BF7C2200201B +:101310005022002002F03AB800F10060920000F57F +:10132000D04001F0D5BF0000054B1A68054B1B8863 +:101330009B1A834202D9104401F086BF00207047F7 +:10134000502200207C22002038B5074D0446286832 +:10135000204401F07FFF28B928682044BDE83840C8 +:1013600001F08ABF38BD00BF50220020064991F825 +:10137000243033B10023086A81F824300822FFF7B3 +:10138000CBBF0120704700BF54220020022802BFBB +:101390004FF090434FF480129A61704710B50023CC +:1013A000934203D0CC5CC4540133F9E710BD000074 +:1013B00003460246D01A12F9011B0029FAD17047E0 +:1013C00002440346934202D003F8011BFAE7704738 +:1013D0002DE9F8431F4D144695F82420074688460A +:1013E00052BBDFF870909CB395F824302BB92022C3 +:1013F000FF2148462F62FFF7E3FF95F82400C0F174 +:101400000802A24228BF2246D6B24146920005EB0E +:101410008000FFF7C3FF95F82430A41B1E44F6B2EA +:10142000082E17449044E4B285F82460DBD1FFF71E +:101430009DFF0028D7D108E02B6A03EB820383428B +:10144000CFD0FFF793FF0028CBD10020BDE8F88371 +:101450000120FBE7542200200FB4002004B07047A5 +:1014600000B59BB0EFF3098168226846FFF796FF4D +:10147000EFF30583044B9A6BDA6A9A6A9A6A9A6A5E +:101480009A6A9A6A9B6AFEE700ED00E000B59BB09D +:10149000EFF3098168226846FFF780FFEFF30583C9 +:1014A000044B9A6B9A6A9A6A9A6A9A6A9A6A9B6ACF +:1014B000FEE700BF00ED00E000B59BB0EFF309814F +:1014C00068226846FFF76AFFEFF30583034B5A6B08 +:1014D0009A6A9A6A9A6A9A6A9B6AFEE700ED00E045 +:1014E000FEE7000001F08EBF01F064BF30B5094D8A +:1014F0000A4491420DD011F8013B5840082340F3B3 +:101500000004013B2C4013F0FF0384EA5000F6D1A5 +:10151000EFE730BD2083B8ED2DE9F041C56915B97D +:10152000C161BDE8F0814B6823F06047C3F38A4690 +:101530004FEAD37EC3F3807816EA230638BF3E46CF +:10154000AC462B465A68BEEBD27F22F060440AD0EC +:10155000002A18DAA40CB44217D19D420FD10D60B5 +:10156000DEE71346EEE7A74207D102F08044C2F35C +:10157000807242450BD054B1EFE708D2EDE7CCF8CA +:1015800000100B60CDE7B44201D0B442E5D81A6830 +:101590009C46002AE5D11960C3E700002DE9F04719 +:1015A000089D01F007044FEAD508224405F007051D +:1015B00000EBD1004FF47F49944201D1BDE8F087A0 +:1015C00004F0070705F0070A57453E4638BF564660 +:1015D000C6F10806111B8E4228BF0E46E10808EB33 +:1015E000D50E415C13F80EC0B94029FA06F721FA6E +:1015F0000AF1FFB28CEA010147FA0AF739408CEA96 +:10160000010C03F80EC034443544D5E780EA0120CC +:10161000082341F2210201B24000002980B203F107 +:10162000FF33B8BF504013F0FF03F4D17047000000 +:1016300038B50C468D18A54200D138BD14F8011BF1 +:10164000FFF7E4FFF7E7000002684AB113680360A0 +:10165000C388018901339BB29942C38038BF03819B +:101660001046704770B588B0202204460D46684683 +:101670000021FFF7A5FE20460495FFF7E5FF02468F +:1016800058B16B46054608AE1C4603CCB4422860F0 +:101690006960234605F10805F6D1104608B070BD13 +:1016A000082817D909280CD00A280CD00B280CD0F0 +:1016B0000C280CD00D280CD00E2814BF4020302050 +:1016C00070470C2070471020704714207047182076 +:1016D0007047202070470000082817D90C280CD923 +:1016E00010280CD914280CD918280CD920280CD96A +:1016F00030288CBF0F200E207047092070470A2029 +:1017000070470B2070470C2070470D207047000079 +:1017100010B54B6823B9CA8A63F30902CA8210BDA7 +:10172000C4681A681C60C360438A013B43824A60F4 +:10173000EFE700002DE9F84F1D46CB8A0F46C3F3B3 +:1017400009010629814692460B4630D00020AAB2F4 +:1017500007F119049EB2052E1FFA80F80FD89045A4 +:1017600003F1010306D3FB8A0A4462F30903FB82F7 +:1017700001201AE01AF80060E6540130EAE79045CB +:10178000F1D2A1F1060B1C237C68BBFBF3F203FB37 +:1017900012BB1FFA8BF6002C45D14846FFF754FFC9 +:1017A000044638B978606FF00200BDE8F88F4FF05A +:1017B0000008E6E7002606607860ADB24FF0000B47 +:1017C000454510D90AEB0803221D13F8011B91555A +:1017D000B1B208F101081B291FFA88F82BD0454542 +:1017E00006F10106F1D8FB8AC3F30902154465F33B +:1017F0000903BCE7013292B21C462368002BF9D1E1 +:10180000AB1F0B441C21B3FBF1F301339BB29A4293 +:10181000D3D2BBF1000FD0D14846FFF715FF20B956 +:10182000C4F800B0BFE70122E7E7C0F800B05E46A9 +:1018300020600446C1E74545D5D94846FFF704FF77 +:1018400008B92060AFE7C0F800B000262060044669 +:10185000B6E700002DE9F04F2DED028B83B0CDE906 +:101860000013BDF83C5007469146002A00F09280D4 +:101870002DB10E9B002B00F08D80072D32D807F183 +:101880000C00FFF7E1FE044638B96FF00204204671 +:1018900003B0BDEC028BBDE8F08F14220021FFF7EE +:1018A0008FFD0E992A4604F10800FFF777FD681CAA +:1018B000C0B2FFF711FFFFF7F3FE207499F8003074 +:1018C000013814FA80F003F01F0363F03F03037242 +:1018D000009B43F00041616038462146FFF71CFE43 +:1018E0000124D4E700F10C034FF0000808EE103A91 +:1018F0004FF0800A4646444618EE100AFFF7A4FE51 +:1019000083460028C1D014220021FFF759FDC6BB31 +:10191000019BABF8083002200E9B00F108029919D8 +:101920005BFA82F20130C0B2082801D0AE422AD35D +:10193000FFF7D2FEFFF7B4FE99F80020009B411E8E +:1019400002F01F0242EA4812AE4208BF4FF0400ABE +:101950005BFA81F14AEA020A43F0004281F808A0EA +:101960008BF81000CBF8042059463846FFF7D4FD19 +:101970000134AE4224B288F001084FF0000ABBD116 +:1019800085E70020C8E711F801CB02F801CB01364A +:10199000B6B2C7E76FF0010479E70000F8B5154665 +:1019A0000E462822002104461F46FFF709FD069B2C +:1019B0006360B5F5001F079BA76034BF6A094FF647 +:1019C000FF72236204F10C0097B200239A4205D8FB +:1019D0000023036027826382A382F8BD066001337F +:1019E00030462036F2E7000003781BB94BB2002BDB +:1019F000C8BF017070470000007870472DE9F74FAD +:101A0000DDF83C90BDF830500D9E9DF83840BDF893 +:101A10004070804692469B46B9F1000F01D1002FDD +:101A200051D11F2C4FD898F80000B0B9072F47D8D4 +:101A300035F0030347D13A4649464FF6FF70FFF7AA +:101A4000F7FD20F001002D02400445EA0464400C3B +:101A500044EA40244FF6FF7321E040EA0520072FB7 +:101A600040EA0464F6D900254FF6FF73C5F1200063 +:101A7000A5F120022AFA05F10BFA00F001432BFA36 +:101A800002F211431846C9B2FFF7C0FD0835402DD8 +:101A90000346EBD13A464946FFF7CAFD0346CDE976 +:101AA0000097324621464046FFF7D4FE3378013393 +:101AB000DBB21F2B88BF0023337003B0BDE8F08F6B +:101AC0006FF00300F9E76FF00100F6E72DE9F04F42 +:101AD00085B09246DDF848800F9D9DF840209DF826 +:101AE0004490BDF84C7006469B46B8F1000F01D1FA +:101AF000002F48D11F2A46D83378002B46D00C023D +:101B000044EA02649DF8381044EAC93444EA0144C6 +:101B10001C43072F44F0800432D900234FF6FF7294 +:101B2000C3F1200CA3F120002AFA03F10BFA0CFCFC +:101B300041EA0C012BFA00F00143C9B210460393AD +:101B4000FFF764FD039B0833402B0246E8D13A4679 +:101B50004146FFF76DFD0346CDE900872A46214641 +:101B60003046FFF777FEB9F1010F06D12B7801332C +:101B7000DBB21F2B88BF00232B7005B0BDE8F08FB0 +:101B80004FF6FF73E8E76FF00100F6E76FF0030030 +:101B9000F3E70000C06900B104307047C3691A68F8 +:101BA000C261C2681A60C360438A013B43827047C6 +:101BB0002DE9F041D0F81880194E14461D464146D3 +:101BC000002709B9BDE8F081D1E90223A21A65EB2B +:101BD0000303964277EB03031ED283698B420DD138 +:101BE000FFF796FD83691B688361C3680B60438AB6 +:101BF000C1608169013B43828846E2E7FFF788FDC7 +:101C00000B68C8F80030C3680B60438AC160013BB1 +:101C10004382D8F80010D4E788460968D1E700BFAE +:101C200080841E002DE9F04F8BB00D46DDF85090FA +:101C300014469B468046002800F01981B9F1000F38 +:101C400000F01581531E3F2B00F21181012A03D1B0 +:101C5000BBF1000F40F00B810023CDE90833B8F849 +:101C60001430B5EBC30F4FEAC30703D300200BB00A +:101C7000BDE8F08F2B199F42D8F80C303ABF7F1B7C +:101C8000FFB227461BB9D8F81030002B7AD02F2D81 +:101C90004ED8C5F13006B7424FF000032CBFF6B264 +:101CA0003E4600932946D8F8080008AB3246FFF7B5 +:101CB00075FCA7EB060A35445FFA8AFAB8F81430C7 +:101CC00003F10053063BDB000493D8F80C30039378 +:101CD0003021039B13B1BAF1000F2CD1D8F81000BA +:101CE00040B1BAF1000F05D0009608AB5246691A10 +:101CF000FFF754FC38B2002FB8D066070AD00AAB01 +:101D000003EBD401624211F8083C02F007021341D0 +:101D100001F8083C082C3CD9102C40F2B580202C4E +:101D200040F2B780BBF1000F00F09C80082334E044 +:101D3000BA460026C2E7049BE02B28BFE0230693A7 +:101D40000B44AB42059314D95A1B03980096924555 +:101D500034BF5246D2B2691A08AB04300792FFF77B +:101D60001DFC079A1644AAEB020A1544F6B25FFA64 +:101D70008AFA049B069A05999B1A0493039B1B6895 +:101D80000393A6E70093D8F8080008AB3A46294623 +:101D9000AEE7BBF1000F13D00123B4EBC30F6CD03F +:101DA000082C12D89DF82030621E23FA02F2D507C3 +:101DB00006D54FF0FF3202FA04F423438DF82030A9 +:101DC0009DF8203089F8003051E7102C12D8BDF86A +:101DD0002030621E23FA02F2D10706D54FF0FF32FF +:101DE00002FA04F42343ADF82030BDF82030A9F8FE +:101DF00000303CE7202C0FD80899631E21FA03F32A +:101E0000DA0705D54FF0FF3202FA04F40C430894C8 +:101E1000089BC9F800302AE7402C2BD0DDE9086583 +:101E2000611EC4F12102A4F1210326FA01F105FA91 +:101E300002F225FA03F311431943CB0712D501220D +:101E4000A4F12003C4F1200102FA03F322FA01F104 +:101E5000A240524243EA010363EB430332432B4364 +:101E6000CDE90823DDE90823C9E90023FFE66FF087 +:101E70000100FCE66FF00800F9E6082CA0D9102C50 +:101E8000B3D9202CEED8C3E7BBF1000FADD00223AD +:101E900083E7BBF1000FBBD004237EE730B5012AF6 +:101EA000144638BF0124402C85B028BF40240025AB +:101EB000012ACDE9025518D81B788DF80830630740 +:101EC0000AD004AB03EBD405624215F8083C02F0DB +:101ED0000702934005F8083C009103462246002182 +:101EE00002A8FFF75BFB05B030BD082AE4D9102A31 +:101EF00003D81B88ADF80830E1E7202A8DBFD3E96D +:101F000000231B680293CDE90223D8E710B5CB6804 +:101F10001BB98B600B618B8210BDC4681A681C6092 +:101F2000C360438A013B4382CA60F0E72DE9F04F6A +:101F3000D1F8008093B018F0800FCDE90323C8F3E7 +:101F4000C01219BFC8F3C03BC8F306264FF0020BFE +:101F50001646B8F1000F04460D4680F2D18118F004 +:101F6000C043059340F0CC810B7B002B00F0C8816F +:101F7000BBF1020F03D00178B14240F0C48108F0F8 +:101F80007F0106916AB3C8F3074A2B44069A93F877 +:101F90000390760646EA0B4646EA82465FEAD91384 +:101FA00046EA0A06079300F0908000220023CDE95C +:101FB0000A23069B009367685B4652460AA920469F +:101FC000B84700287ED0A7699FB9314604F10C00BC +:101FD000FFF748FB0746E0B96FF0020013B0BDE819 +:101FE000F08FC8F30F2A18F07F0F08BF0AF0030A1A +:101FF000CBE73B699E420DD03F68002FF9D13146B7 +:1020000004F10C00FFF72EFB07460028E4D0A3697B +:102010003B60A761DDE90A2300264FF6FF70C6F199 +:10202000200E22FA06F103FA0EFEA6F1200C23FA86 +:102030000CFC41EA0E0141EA0C01C9B208360992D2 +:102040000893FFF7E3FA402EDDE90832E7D1B882C2 +:10205000FB7D09F01F06C3F384039B1BD7E9022114 +:1020600098B2002BBCBF00F120031BB252EA010062 +:10207000C8F304680FD00398821A049860EB01013A +:10208000A74890424FF000028A4104D3079A002AE1 +:102090005BD0012B23DDFA7D4FEA890302F00302B6 +:1020A00003F07C031343FB7539462046FFF730FBF2 +:1020B000079BA3B9FB7DC3F38402013262F386035D +:1020C000FB7504E06FF00B0088E7A76917B96FF0A4 +:1020D0000C0083E73B699E42BAD03F68F6E719F0EF +:1020E000400F32D0039BBB60049BFB601422002195 +:1020F0000DA8FFF765F9039B0A93049B0B932B1D17 +:102100000C932B7BADF83EA0013BDBB2ADF83C302D +:10211000069B8DF8433094F824308DF840B083F05E +:1021200001038DF844308DF84160A3688DF842803A +:102130000AA920469847FB7DC3F38403013303F0CB +:102140001F039B02FB82002048E7FB7DC9F340127E +:10215000B2EBD31F40F0DA80C3F38403B34240F004 +:10216000D88007992B7B4FEA9912002934D0D207E7 +:1021700041D4032B40F2D080039BBB60049BFB60E7 +:102180002B7BAE1D033BDBB23246394604F10C001B +:10219000FFF7D0FA00280DDA20463946FFF7B8FAE3 +:1021A000FB7DC3F38403013303F01F039B02FB8217 +:1021B000032013E7AB883B832A7B033AB88AD2B269 +:1021C0003146FFF735FAFB7DB882DA43C2F3C0121D +:1021D00062F3C713FB75B6E76AB92E1D013BDBB28C +:1021E0003246394604F10C00FFF7A4FA0028D3DB8D +:1021F0002A7B013AE2E7F98AC1F30901013B05298B +:10220000DAB259D8281D002307F11A0C9A4208D9CE +:1022100010F801EB0CF801E0013101330629DBB2C3 +:10222000F4D103990A9104990B91934207F11A0191 +:102230000C9138BF043379680D9134BF55FA83F39C +:1022400000230E93FB8AADF83EA0C3F309031A44A2 +:10225000069B8DF8433094F82430ADF83C2083F091 +:1022600001038DF8443000238DF840B08DF84160B3 +:102270008DF842807B602A7BB88A013A291DFFF7DE +:10228000D7F93B8BB882834203D1A3680AA92046C1 +:10229000984720460AA9FFF739FEFB7DB88AC3F3A9 +:1022A0008403013303F01F039B02FB823B8B9842A4 +:1022B00014BF1120002091E67B68002BB1D00620CE +:1022C00001E01C306346D3F800C0BCF1000FF8D128 +:1022D000091A081D05F1040C00EB030905989DF887 +:1022E000143001EB000EBEF11B0F9AD89A4298D918 +:1022F0001CF8013B09F8013B059B01330593EDE711 +:102300006FF009006AE66FF00A0067E66FF00D00F3 +:1023100064E66FF00E0061E66FF00F005EE600BF4E +:1023200080841E00F0B53D4D3D4FEB6943F00073D6 +:10233000EB61EB693B4B9B6AD3F800623E4046F091 +:102340000106C3F80062D3F800423C4044EA002092 +:1023500040F00100C3F80002002951D00020C3F86A +:102360001C020646C3F80402C3F80C02C3F81402A8 +:1023700003EBC00401300E28C4F84062C4F8446284 +:10238000F6D100274FF0010C9678148816F0010F53 +:1023900018BFD3F804E20CFA04F01CBF40EA0E0E9A +:1023A000C3F804E216F0020F1EBFD3F80CE240EAB5 +:1023B0000E0EC3F80CE2760742BFD3F81462064350 +:1023C000C3F8146203EBC4045668C4F8406296680C +:1023D000C4F84462D3F81C4201372043B942C3F821 +:1023E0001C0202F10C02CFD1D3F8002222F001022C +:1023F000C3F80022EB6923F00073EB61EB69F0BDD9 +:102400000122C3F84012C3F84412C3F80412C3F8FF +:102410001412C3F80C22C3F81C22E5E70010024096 +:102420000000FFFF80220020184A916A08B58B68DF +:102430008B6013F0010104D013F00C0F18BF4FF4A0 +:102440008031D80506D513F4406F14BF41F4003134 +:1024500041F00201D80306D513F4402F14BF41F414 +:10246000802141F00401D3690BB10848984720232B +:1024700083F311880648002100F038FE002383F31F +:102480001188BDE8084001F0AFB800BF80220020ED +:102490008822002038B5124CA36ADD68AA0712D042 +:1024A0005A6922F002025A61A36913B10121204640 +:1024B0009847202383F311880A48002100F016FE74 +:1024C000002383F31188EB0606D5A36A1021D96097 +:1024D000236A0BB102489847BDE8384001F084B840 +:1024E000802200209022002038B5124CA36A1D697A +:1024F000AA0712D05A6922F010025A61A36913B1D7 +:10250000022120469847202383F311880A4800219E +:1025100000F0ECFD002383F31188EB0606D5A36AD7 +:1025200010211961236A0BB102489847BDE8384071 +:1025300001F05AB8802200209022002038B50F4CBC +:10254000A36A5D685D602A070AD5042222701A68B2 +:1025500022F002021A60636A13B1002120469847F4 +:102560006B0706D5A36A9969236A13B10348090466 +:102570009847BDE8384001F037B800BF80220020FE +:1025800010B50E4C204600F02FFA0D4BA3620B2124 +:10259000132000F009FA0B21142000F005FA0B219A +:1025A000152000F001FA0B21162000F0FDF90022A1 +:1025B000BDE8104011460E20FFF7B4BE8022002077 +:1025C000006400400F4B984210B5044605D10E4BF5 +:1025D000DA6942F00072DA61DB69A36A01221A60EB +:1025E000A36A5A68D20707D5626851681268D96130 +:1025F0001A60064A5A6110BD0121082000F06CFCE7 +:10260000EEE700BF80220020001002405B8701003F +:1026100003291AD8DFE801F0020A0F14836A9B68C5 +:1026200013F0E05F14BF012000207047836A9868B0 +:10263000C0F380607047836A9868C0F3C0607047D9 +:10264000836A9868C0F300707047002070470000EC +:1026500010B5032925D8DFE801F00225292D836A6A +:102660009968C1F30161183103EB011310788406F6 +:102670004CBF54689488C0F300114FEA410148BF31 +:1026800041EAC40100F00F004CBF41F0040141EAEF +:102690004451586041F001019068D2689860DA6056 +:1026A000196010BD836A03F5C073DFE7836A03F521 +:1026B000C873DBE7836A03F5D073D7E701290AD033 +:1026C00002290FD081B9836ADA68920701D11869AB +:1026D00003E001207047836AD86810F0030018BF38 +:1026E00001207047836AF2E70020704710B539B9BE +:1026F000836AD96889071BD11B699C0704D110BD67 +:10270000012915D00229FAD1816AD1F8C031D1F856 +:10271000C441D1F8C8011061D1F8CC01506120202A +:1027200008610869800717D1486940F0100012E07D +:10273000816AD1F8B031D1F8B441D1F8B801106153 +:10274000D1F8BC0150612020C860C868800703D15F +:10275000486940F002004861C3F34000C3F38001C0 +:10276000000140EA4111107920F03000014311715D +:1027700089064BBF91681189DB085B0D4CBF63F381 +:102780001C0163F30A01137948BF916064F30303EA +:1027900013714FEA14234FEA144458BF1181137088 +:1027A0005480ACE7026843681143016003B11847E5 +:1027B00070470000024A136843F0C003136070477B +:1027C00000380140024A136843F0C00313607047A9 +:1027D0000044004037B51D4C1D4D204600F006FB5F +:1027E000009404F114001B490023202200F0C8F9D2 +:1027F0002022009404F13800174B184900F042FAE7 +:10280000174BC4E91735174C0C21252000F0CCF8E4 +:10281000204600F0EBFA04F1140013490094002361 +:10282000202200F0ADF904F13800104B104900945B +:10283000202200F027FA0F4B0C212620C4E917357F +:1028400003B0BDE8304000F0AFB800BFAC220020BC +:102850000051250284230020B5270008C42300204E +:102860000038014018230020A4230020C5270008B9 +:10287000E4230020004400402DE9F047C66D37688E +:10288000F46934622107054618D014F0080118BF16 +:102890008021E20748BF41F02001A30748BF41F073 +:1028A0004001600748BF41F48071202383F3118801 +:1028B000281DFFF777FF002383F31188E2050AD56F +:1028C000202383F311884FF40071281DFFF76AFF5E +:1028D000002383F311884FF020094FF0000A14F011 +:1028E000200838D13B0616D54FF0200905F1380AEB +:1028F000200610D589F31188504600F0F7F900281A +:1029000036DA0821281DFFF74DFF27F080033360DA +:10291000002383F31188790614D5620612D520238B +:1029200083F31188D5E913239A4208D12B6C33B174 +:102930001021281D27F04007FFF734FF37600023E0 +:1029400083F31188E30619D5AA6E1369B3B1BDE804 +:10295000F0475069184789F31188B38C95F86410D3 +:102960002846194000F04EFA8AF31188F469B6E758 +:1029700080B2308588F31188F469B9E7BDE8F08743 +:1029800008B50348FFF778FFBDE8084000F02CBE0B +:10299000AC22002008B50348FFF76EFFBDE80840F1 +:1029A00000F022BE1823002000F1604303F56143CC +:1029B0000901C9B283F80013012200F01F039A40F5 +:1029C00043099B0003F1604303F56143C3F8802191 +:1029D0001A60704700F16040090100F56D40C9B20E +:1029E00001767047FFF7CCBD012300F10802C0E972 +:1029F0000222037000F110020023C0E90422C0E9A2 +:102A00000633C0E9083343607047000010B5202347 +:102A1000044683F31188022303704160FFF7D2FD5F +:102A200004232370002383F3118810BD2DE9F041A6 +:102A30001F4604460D461646202383F3118800F1F5 +:102A400008082378052B0DD029462046FFF7E0FD26 +:102A500040B1204632462946FFF7FAFD002080F3B8 +:102A6000118808E03946404600F024FB0028E8D0F1 +:102A7000002383F31188BDE8F08100002DE9F041C7 +:102A80001F4604460D461646202383F3118800F1A5 +:102A900010082378052B0DD029462046FFF70EFE9F +:102AA00040B1204632462946FFF720FE002080F341 +:102AB000118808E03946404600F0FCFA0028E8D0CA +:102AC000002383F31188BDE8F0810000F8B51546B6 +:102AD00082680669AA420B46816938BF8568761A02 +:102AE000B54204460BD218462A46FEF757FCA369A6 +:102AF0002B44A361A3685B1BA3602846F8BD0CD9D7 +:102B000018463246FEF74AFCAF1BE1683A463044AD +:102B1000FEF744FCE3683B44EBE718462A46FEF721 +:102B20003DFCE368E5E7000083689342F7B515468E +:102B3000044638BF8568D0E90460361AB5420BD226 +:102B40002A46FEF72BFC63692B446361A368284681 +:102B50005B1BA36003B0F0BD0DD932460191FEF7B7 +:102B60001DFC0199E068AF1B3A463144FEF716FCA4 +:102B7000E3683B44E9E72A46FEF710FCE368E4E734 +:102B800010B50A440024C361029B8460C0E90000C0 +:102B9000C0E90511C1600261036210BD08B5D0E94A +:102BA0000532934201D1826882B982680132826023 +:102BB0005A1C42611970D0E904329A4224BFC3689A +:102BC0004361002100F086FA002008BD4FF0FF307D +:102BD000FBE7000070B5202304460E4683F31188FE +:102BE000A568A5B1A368A269013BA360531CA361BA +:102BF00015782269934224BFE368A361E3690BB1AE +:102C000020469847002383F31188284607E0314681 +:102C1000204600F04FFA0028E2DA85F3118870BDF3 +:102C20002DE9F74F04460E4617469846D0F81C90FB +:102C30004FF0200A8AF311884FF0000B154665B15A +:102C40002A4631462046FFF741FF034660B9414618 +:102C5000204600F02FFA0028F1D0002383F31188DA +:102C6000781B03B0BDE8F08FB9F1000F03D00190DD +:102C70002046C847019B8BF31188ED1A1E448AF346 +:102C80001188DCE7C0E90511C160C3611144009BF4 +:102C90008260C0E90000016103627047F8B5044634 +:102CA0000D461646202383F31188A768A7B1A368B1 +:102CB000013BA36063695A1C62611D70D4E9043250 +:102CC0009A4224BFE3686361E3690BB120469847E9 +:102CD000002080F3118807E03146204600F0EAF931 +:102CE0000028E2DA87F31188F8BD0000D0E9052357 +:102CF0009A4210B501D182687AB982680132826045 +:102D00005A1C82611C7803699A4224BFC36883619C +:102D1000002100F0DFF9204610BD4FF0FF30FBE747 +:102D20002DE9F74F04460E4617469846D0F81C90FA +:102D30004FF0200A8AF311884FF0000B154665B159 +:102D40002A4631462046FFF7EFFE034660B941466A +:102D5000204600F0AFF90028F1D0002383F311885A +:102D6000781B03B0BDE8F08FB9F1000F03D00190DC +:102D70002046C847019B8BF31188ED1A1E448AF345 +:102D80001188DCE7026843681143016003B118470A +:102D9000704700001430FFF743BF00004FF0FF33CF +:102DA0001430FFF73DBF00003830FFF7B9BF000017 +:102DB0004FF0FF333830FFF7B3BF00001430FFF798 +:102DC00009BF00004FF0FF311430FFF703BF0000D0 +:102DD0003830FFF763BF00004FF0FF323830FFF7A5 +:102DE0005DBF000000207047FFF7F4BC044B036098 +:102DF0000023C0E90233436001230374704700BF1E +:102E0000F43B000838B5C36904460D461BB90421DC +:102E10000844FFF7B7FF294604F11400FFF7BEFE90 +:102E2000002806DA201D4FF48061BDE83840FFF726 +:102E3000A9BF38BD024B0022C3E900339A60704736 +:102E400004240020002303748268054B1B689968E2 +:102E50009142FBD25A68036042601060586070472C +:102E60000424002008B5202383F31188037C032B5E +:102E700005D0042B0DD02BB983F3118808BD43690D +:102E800000221A604FF0FF334361FFF7DBFF00239E +:102E9000F2E7D0E9003213605A60F3E700230374CD +:102EA0008268054B1B6899689142FBD85A68036099 +:102EB000426010605860704704240020054B196977 +:102EC0000874186802681A6053601861012303745B +:102ED000FDF77EBB0424002030B54B1C0B4D87B0A2 +:102EE000044610D02B690A4A01A800F01BF92046BD +:102EF000FFF7E4FF049B13B101A800F02FF92B6941 +:102F0000586907B030BDFFF7D9FFF8E70424002067 +:102F1000652E000838B50C4D41612B6981689A68AF +:102F20009142044603D8BDE83840FFF78BBF1846EE +:102F3000FFF7B4FF01232C61014623742046BDE84E +:102F40003840FDF745BB00BF04240020044B1A683D +:102F50001B6990689B68984294BF002001207047CD +:102F60000424002010B5084C236820691A682260E8 +:102F70005460012223611A74FFF790FF0146206913 +:102F8000BDE81040FDF724BB0424002008B5FFF77E +:102F9000DDFF18B1BDE80840FFF7E4BF08BD000041 +:102FA000FFF7E0BFFEE7000010B50C4CFFF742FF53 +:102FB00000F0AAF80A498022204600F031F80123E7 +:102FC00044F8180C037400F0EBFA002383F3118823 +:102FD00062B60448BDE8104000F042B82C2400203E +:102FE0001C3C00082C3C000800F0CAB8EFF311802C +:102FF00020B9EFF30583202282F311887047000087 +:1030000010B530B9EFF30584C4F3080414B180F3AC +:10301000118810BDFFF7BAFF84F31188F9E70000AB +:1030200082600222028270478368A3F17C0243F827 +:103030000C2C026943F83C2C426943F8382C074AAF +:1030400043F81C2CC26843F8102C022203F8082C09 +:10305000002203F8072CA3F118007047E9050008C7 +:1030600010B5202383F31188FFF7DEFF002104460B +:10307000FFF750FF002383F31188204610BD0000A6 +:10308000024B1B6958610F20FFF718BF0424002072 +:10309000202383F31188FFF7F3BF000008B5014632 +:1030A000202383F311880820FFF716FF002383F302 +:1030B000118808BD49B1064B42681B6918605A6007 +:1030C000136043600420FFF707BF4FF0FF307047E5 +:1030D000042400200368984206D01A6802605060F9 +:1030E00059611846FFF7AEBE7047000038B5044678 +:1030F0000D462068844200D138BD036823605C60BF +:103100004561FFF79FFEF4E7054B03F11402C3E9A5 +:1031100005224FF0FF32DA6100221A62704700BFC9 +:103120000424002010B5C0E903230B4A136A536935 +:103130009C68A1420CD85C68816003604460206098 +:1031400058609868411A99604FF0FF33D36110BD01 +:103150001B68091BECE700BF04240020036881689A +:103160009A680A449A60426813605A600023C360F8 +:10317000024B4FF0FF32DA61704700BF0424002099 +:1031800038B50F4C236A22460133236252F8143FAC +:10319000934206D09A68013A9A60202563699A683A +:1031A00002B138BDD3E9001001604860D968DA6027 +:1031B00082F311881869884785F31188EEE700BF0C +:1031C0000424002000207047FEE700007047000044 +:1031D0004FF0FF3070470000BFF34F8F024AD368B3 +:1031E000DB07FCD4704700BF0020024008B5074B46 +:1031F0001B7853B9FFF7F0FF054B1A69120641BF60 +:10320000044A5A6002F188325A6008BD90250020B5 +:10321000002002402301674508B5054B1B7833B9F0 +:10322000FFF7DAFF034A136943F08003136108BD17 +:1032300090250020002002407F289ABF00F58030B2 +:10324000C0020020704700004FF40060704700008B +:10325000802070477F2808B50BD8FFF7EDFF00F5F9 +:1032600000630268013204D104308342F9D10120A5 +:1032700008BD0020FCE700007F2838B5044623D8AD +:10328000FFF7B4FEFFF7A8FFFFF7B0FF0F4BF322E5 +:10329000DA6002221A6105462046FFF7CDFF586129 +:1032A0001A6942F040021A614FF40061FFF794FF7F +:1032B00000F026F92846FFF7AFFFFFF7A1FE2046F2 +:1032C000BDE83840FFF7C6BF002038BD00200240EF +:1032D00012F001032DE9F04704460E46154606D0CC +:1032E000244B40F2BD221A600020BDE8F08781180F +:1032F000214A914204D91F4A40F2C2211160F3E7EA +:10330000FFF774FEFFF772FFFFF766FFDFF87890B4 +:1033100031464FF0010AA61B012D06EB0107884636 +:1033200005D8FFF779FFFFF76BFE0120DDE7B8F85E +:103330000030C9F810A03B800024FFF74DFFC9F80A +:1033400010403B8831F8022B9BB29A420FD0094BB8 +:1033500040F2D9221A60094B1F60094B1D60094BCE +:10336000C3F80080FFF758FFFFF74AFEBCE7023DB5 +:10337000D2E700BF8C250020000004088025002033 +:10338000882500208425002000200240084908B537 +:103390000B7828B11BB9FFF729FF01230B7008BD7B +:1033A000002BFCD0BDE808400870FFF735BF00BF18 +:1033B0009025002030B583B0FFF718FE0E4B0F4D5F +:1033C0001B6A2A684FF47A7101FB03F3934237BFFB +:1033D0000B4A0B49516814682B602EBFD1E900419C +:1033E000013151601C1941F100010191FFF708FE04 +:1033F0000199204603B030BD04240020942500200C +:103400009825002030B583B0FFF7F0FD114B124D29 +:103410001B6A2A684FF47A7101FB03F3934237BFAA +:103420000E4A0E49516814682B602EBFD1E9004145 +:10343000013151601C1941F100010191FFF7E0FDDC +:1034400001994FF47A7200232046FCF7A9FE03B0DD +:1034500030BD00BF042400209425002098250020C2 +:1034600010B50244064BD2B2904200D110BD441CAC +:1034700000B253F8200041F8040BE0B2F4E700BFBB +:10348000502800400F4B30B51C6A240407D41C6A36 +:1034900044F440741C621C6A44F400441C620A4CEC +:1034A000236843F4807323600244084BD2B29042F5 +:1034B00000D130BD441C00B251F8045B43F82050E9 +:1034C000E0B2F4E7001002400070004050280040D5 +:1034D00007B5012201A90020FFF7C2FF019803B040 +:1034E0005DF804FB13B50446FFF7F2FFA04205D0D8 +:1034F000012201A900200194FFF7C4FF02B010BD12 +:1035000070470000074B45F255521A6002225A607C +:1035100040F6FF729A604CF6CC421A60024B0122D0 +:103520001A70704700300040A4250020034B1B7820 +:103530001BB1034B4AF6AA221A607047A42500204B +:1035400000300040044B1A682AB902F1804202F5AB +:103550000432526A1A607047A0250020024B4FF0D7 +:1035600080725A62704700BF0010024008B5FFF732 +:10357000E9FF024B1868C0F3407008BDA025002089 +:10358000EFF3098305494A6B22F001024A6368336D +:1035900083F30988002383F31188704700EF00E06C +:1035A000202080F3118862B60C4B0D4AD96821F4B3 +:1035B000E0610904090C0A43DA60D3F8FC200949E8 +:1035C00042F08072C3F8FC200A6842F001020A60EF +:1035D0001022DA7783F82200704700BF00ED00E088 +:1035E0000003FA05001000E010B5202383F31188D2 +:1035F0000E4B5B6813F4006314D0F1EE103AEFF356 +:103600000984683C4FF08073E361094BDB6B2366F0 +:1036100084F30988FFF79AFC10B1064BA36110BD33 +:10362000054BFBE783F31188F9E700BF00ED00E0ED +:1036300000EF00E0FB050008FE05000870470000F1 +:10364000FEE700000A4B0B480B4A90420BD30B4B92 +:10365000DA1C121AC11E22F003028B4238BF00226C +:103660000021FDF7ADBE53F8041B40F8041BECE746 +:10367000183D0008282600202826002028260020A3 +:10368000704700004B6843608B688360CB68C36001 +:103690000B6943614B6903628B6943620B6803608A +:1036A0007047000008B51B4B9A6A42F4FC029A620C +:1036B0009A6A22F4FC029A629A6A5A6942F4FC02FB +:1036C0005A61154A5B6911464FF09040FFF7DAFFE7 +:1036D00002F11C0100F58060FFF7D4FF02F1380110 +:1036E00000F58060FFF7CEFF02F1540100F5806025 +:1036F000FFF7C8FF02F1700100F58060FFF7C2FF1D +:1037000002F18C0100F58060FFF7BCFFBDE80840C6 +:1037100000F05AB800100240443C000808B500F020 +:1037200093F9FFF741FCBDE80840FFF70BBF00002D +:103730007047000010B5214CA36A63F4FC03A36238 +:10374000A36A03F4FC03A3624FF0FF32A36A236968 +:1037500022612369002323612169E168E260E26854 +:10376000E360E268E269164942F08052E261E26990 +:103770000A6842F480720A60226A02F44072B2F56A +:10378000407F1EBF4FF4803222622362236A1B04F3 +:1037900007D4236A43F440732362236A43F400434B +:1037A000236200F031F9A369064A43F00103A361E3 +:1037B000A369136843F02003136010BD001002409A +:1037C00000700040000001401E4B1A6842F00102E8 +:1037D0001A601A689007FCD55A6822F003025A60F2 +:1037E0005A6812F00C02FBD1196801F0F901196056 +:1037F0005A601A6842F480321A601A689103FCD544 +:10380000114A5A604FF40452DA6230221A631A687D +:1038100042F080721A601A689201FCD50B4912229C +:103820000A600A6802F00702022AFAD15A6842F0D6 +:1038300002025A605A6802F00C02082AFAD11A6B86 +:103840001A6370470010024000241D00002002404F +:10385000084A08B5516913680B4003F0010353612E +:1038600023B1054A13680BB150689847BDE808407A +:10387000FFF7BABE00040140A8250020084A08B599 +:10388000516913680B4003F00203536123B1054AE9 +:1038900093680BB1D0689847BDE80840FFF7A4BE15 +:1038A00000040140A8250020084A08B551691368A2 +:1038B0000B4003F00403536123B1054A13690BB1B4 +:1038C00050699847BDE80840FFF78EBE00040140EC +:1038D000A8250020084A08B5516913680B4003F079 +:1038E0000803536123B1054A93690BB1D069984726 +:1038F000BDE80840FFF778BE00040140A82500207D +:10390000084A08B5516913680B4003F0100353616E +:1039100023B1054A136A0BB1506A9847BDE80840C5 +:10392000FFF762BE00040140A8250020174B10B528 +:103930005A691C68144004F478725A61A30604D5CD +:10394000134A936A0BB1D06A9847600604D5104AAF +:10395000136B0BB1506B9847210604D50C4A936B3F +:103960000BB1D06B9847E20504D5094A136C0BB133 +:10397000506C9847A30504D5054A936C0BB1D06CE5 +:103980009847BDE81040FFF72FBE00BF000401407C +:10399000A82500201A4B10B55A691C68144004F47D +:1039A0007C425A61620504D5164A136D0BB1506D05 +:1039B0009847230504D5134A936D0BB1D06D9847F2 +:1039C000E00404D50F4A136E0BB1506E9847A10462 +:1039D00004D50C4A936E0BB1D06E9847620404D59F +:1039E000084A136F0BB1506F9847230404D5054A5A +:1039F000936F0BB1D06F9847BDE81040FFF7F4BD4F +:103A000000040140A8250020062108B50846FEF75D +:103A1000CBFF06210720FEF7C7FF06210820FEF78F +:103A2000C3FF06210920FEF7BFFF06210A20FEF78B +:103A3000BBFF06211720FEF7B7FFBDE808400621AF +:103A40002820FEF7B1BF000008B5FFF773FE00F0B5 +:103A50000DF8FEF7C7FFFFF7C7F9FFF769FEBDE8EE +:103A6000084000F001B8000000F00EB80023054A3D +:103A700019460133102BC2E9001102F10802F8D1F6 +:103A8000704700BFA82500204FF0E023044A5A6188 +:103A900000229A6107221A6108210B20FEF79ABFC3 +:103AA0003F19010008B5202383F31188FFF79CFA22 +:103AB000002383F3118808BD08B5FFF7F3FFBDE8C5 +:103AC0000840FFF791BD000010B501390244904253 +:103AD00001D1002005E0037811F8014FA34201D085 +:103AE000181B10BD0130F2E72DE9F041A3B1C91A4E +:103AF00017780144044603F1FF3C8C42204601D96B +:103B0000002009E00578BD4204F10104F5D10CEB79 +:103B10000405D618A54201D1BDE8F08115F8018D44 +:103B200016F801EDF045F5D0E7E70000034611F87F +:103B3000012B03F8012B002AF9D170476F72672E11 +:103B40006172647570696C6F742E6D726F5F6D3128 +:103B500030303235000000004E6F206170702073ED +:103B600069670A00426164206677206C656E67743D +:103B7000682025750A0042616420626F6172645F8B +:103B800069642025752073686F756C6420626520F8 +:103B900025750A004261642066772064657363724C +:103BA0006970746F72206C656E6774682025750A81 +:103BB00000426164206170702043524320307825B8 +:103BC0003038783A307825303878203078253038D9 +:103BD000783A3078253038780A00476F6F6420666D +:103BE00069726D776172650A0040A2E4F1646891C0 +:103BF0000600000000000000B12D00089D2D000807 +:103C0000D92D0008C52D0008D12D0008BD2D0008B4 +:103C1000A92D0008952D0008E52D00086D61696E3D +:103C20000000000069646C6500000000243C00088E +:103C3000482400208025002001000000A52F000856 +:103C400000000000A001A82A00000000FAAABEAAF5 +:103C500050001424EFFF0000007700007097090067 +:103C60000100000000000000AAAAAAAA01000000AA +:103C7000FFFF000000000000000000000000000046 +:103C800000000000AAAAAAAA00000000FFFF00008E +:103C90000000000000000000000000000000000024 +:103CA000AAAAAAAA00000000FFFF0000000000006E +:103CB000000000000000000000000000AAAAAAAA5C +:103CC00000000000FFFF00000000000000000000F6 +:103CD0000000000000000000AAAAAAAA000000003C +:103CE000FFFF00000000000000000000E4C4FF7FB0 +:103CF0000100000000000000EC03000000000000D4 +:103D000000980300000000006400000000000000B4 +:083D1000FE2A0100D2040000AC :00000001FF diff --git a/Tools/bootloaders/f303-M10070_bl.bin b/Tools/bootloaders/f303-M10070_bl.bin index 95343487617..ea2f3b654da 100755 Binary files a/Tools/bootloaders/f303-M10070_bl.bin and b/Tools/bootloaders/f303-M10070_bl.bin differ diff --git a/Tools/bootloaders/f303-M10070_bl.elf b/Tools/bootloaders/f303-M10070_bl.elf index a0cf1dd91be..cd8dd84fe75 100755 Binary files a/Tools/bootloaders/f303-M10070_bl.elf and b/Tools/bootloaders/f303-M10070_bl.elf differ diff --git a/Tools/bootloaders/f303-M10070_bl.hex b/Tools/bootloaders/f303-M10070_bl.hex index fdbd526031e..18f1da6c868 100644 --- a/Tools/bootloaders/f303-M10070_bl.hex +++ b/Tools/bootloaders/f303-M10070_bl.hex @@ -1,1095 +1,980 @@ :020000040800F2 -:1000000000090020E1040008991400089D1400086C -:10001000F11400089D140008C5140008E30400084A -:10002000E3040008E3040008E30400085D37000867 -:10003000E3040008E3040008E3040008013C0008AE -:10004000E3040008E3040008E3040008E3040008F4 -:10005000E3040008E3040008E5390008113A000849 -:100060003D3A0008693A0008953A0008E3040008A0 -:10007000E3040008E3040008E3040008E3040008C4 -:10008000E3040008E3040008E3040008092600086C -:1000900075260008C92600081D270008C13A000877 -:1000A000E3040008E3040008E3040008E304000894 -:1000B000E3040008E3040008E3040008E304000884 -:1000C000E3040008E3040008E3040008E304000874 -:1000D000E3040008D92A0008ED2A0008E304000818 -:1000E000293B0008E3040008E3040008E3040008D7 -:1000F000E3040008E3040008E3040008E304000844 -:10010000E3040008E3040008E3040008E304000833 -:10011000E3040008E3040008E3040008E304000823 -:10012000E3040008E3040008E3040008E304000813 -:10013000E3040008E3040008E3040008E304000803 -:10014000E3040008E3040008E3040008E3040008F3 -:10015000E3040008E3040008E3040008E3040008E3 -:10016000E3040008E3040008E3040008E3040008D3 -:10017000E3040008E3040008E3040008E3040008C3 -:10018000E3040008E3040008E3040008E3040008B3 -:10019000E3040008E3040008E3040008E3040008A3 -:1001A000D0400B1CD1409C46203AD34018435242C9 -:1001B00063469340184370479140031C90409C460F -:1001C000203A9340194352426346D3401943704743 -:1001D00053B94AB9002908BF00281CBF4FF0FF31AE -:1001E0004FF0FF3000F07AB9ADF1080C6DE904CEA4 -:1001F00000F006F8DDF804E0DDE9022304B0704702 -:100200002DE9F0478C460D460446089E002B51D13F -:100210008A4217466DD9B2FA82FEBEF1000F0BD0AA -:10022000CEF1200C01FA0EF520FA0CFC02FA0EF7C2 -:100230004CEA050C00FA0EF44FEA174A250CBCFBF9 -:10024000FAF81FFA87F90AFB18CC45EA0C4508FBB7 -:1002500009F3AB420AD9ED1908F1FF3280F023818E -:10026000AB4240F22081A8F102083D44ED1AA4B24D -:10027000B5FBFAF00AFB105544EA054400FB09F906 -:10028000A14509D9E41900F1FF3380F00A81A145A5 -:1002900040F2078102383C44A4EB090440EA0840DC -:1002A0000021002E61D024FA0EF400233460736024 -:1002B000BDE8F0878B4207D9002E54D0002186E894 -:1002C00021000846BDE8F087B3FA83F1002940F029 -:1002D0008E80AB4202D3824200F2FA80841A65EB30 -:1002E00003050120AC46002E3FD086E81010BDE883 -:1002F000F08712B90127B7FBF2F7B7FA87FEBEF114 -:10030000000F34D1EB1B3A0C1FFA87FC0121B3FB21 -:10031000F2F8250C02FB183345EA03450CFB08F301 -:10032000AB4207D9ED1908F1FF3002D2AB4200F21F -:10033000D1808046ED1AA3B2B5FBF2F002FB105556 -:1003400043EA05440CFB00FCA44507D9E41900F17D -:10035000FF3302D2A44500F2B8801846A4EB0C0487 -:1003600040EA08409DE731463046BDE8F087CEF1CF -:10037000200405FA0EF307FA0EF720FA04F83A0CF7 -:1003800025FA04F448EA0308B4FBF2F14FEA1845F1 -:1003900002FB11441FFA87FC45EA044501FB0CF3FC -:1003A000AB4200FA0EF409D9ED1901F1FF3080F0EB -:1003B0008A80AB4240F2878002393D44EB1A1FFA33 -:1003C00088F5B3FBF2F002FB103345EA034500FB6E -:1003D0000CF3AB4207D9ED1900F1FF386FD2AB42F5 -:1003E0006DD902383D44EB1A40EA01418FE7C1F173 -:1003F000200722FA07F88B4005FA01F448EA0303C4 -:1004000020FA07FE4FEA134CFD404EEA040EB5FBFE -:10041000FCF94FEA1E440CFB19551FFA83F844EA15 -:10042000054509FB08F4AC4202FA01F200FA01FAB0 -:1004300008D9ED1809F1FF3043D2AC4241D9A9F1F6 -:1004400002091D442D1B1FFA8EFEB5FBFCF00CFBB0 -:1004500010554EEA054400FB08F8A04507D9E418FA -:1004600000F1FF3529D2A04527D902381C4440EAC3 -:100470000940A4EB0804A0FB02894C45C6464D4642 -:1004800015D312D056B1BAEB0E0364EB050404FA8F -:1004900007F7CB401F43CC40376074600021BDE8B4 -:1004A000F0871846F8E69046E0E6C245EAD2B8EB97 -:1004B000020E69EB03050138E4E72846D7E740461A -:1004C00091E78146BEE7014678E702383C4445E7BC -:1004D000084608E7A8F102083D442BE7704700BF33 -:1004E00002E000F000F8FEE772B6394880F30888B1 -:1004F000384880F3098838484EF60851CEF200019A -:10050000086040F20000CCF200004EF63471CEF2EA -:1005100000010860BFF34F8FBFF36F8F40F2000000 -:10052000C0F2F0004EF68851CEF200010860BFF331 -:100530004F8FBFF36F8F4FF00000E1EE100A4EF6C1 -:100540003C71CEF200010860062080F31488BFF3EE -:100550006F8F03F041F903F06DF94FF055301F49EB -:100560001B4A91423CBF41F8040BFAE71C49194A67 -:1005700091423CBF41F8040BFAE71A491A4A1B4B57 -:100580009A423EBF51F8040B42F8040BF8E70020F2 -:100590001749184A91423CBF41F8040BFAE703F0AF -:1005A0001FF903F089F9144C144DAC4203DA54F8E6 -:1005B000041B8847F9E700F03FF8114C114DAC429D -:1005C00003DA54F8041B8847F9E703F007B9000081 -:1005D0000009002000110020000000080001002098 -:1005E00000090020D04300080011002074110020F1 -:1005F0007811002090260020A0010008A00100082A -:10060000A0010008A00100082DE9F04F2DED108A8F -:10061000C1F80CD0C3689D46BDEC108ABDE8F08FD0 -:10062000002383F311882846A047002002F070FEC3 -:1006300002F09AFD00DFFEE7384B6FF013022DE960 -:10064000F0416FF0670100241A7003225A709C7009 -:10065000DC701C715C719C71DC711C7259729A7235 -:10066000DC7203F025F8074603F072F80546C8BBB4 -:100670002B4B9F4238D001339F4238D0294B27F073 -:10068000FF029A4237D1F8B200F052FAA84642F27D -:10069000107400F07BFC00F051FA064678B384BB7E -:1006A000464635B1204B9F4203D003F049F8002461 -:1006B0002646002003F006F81C4B1B6913F040038C -:1006C00022D00EB100F034F800F082FC00F016FEEB -:1006D00000F022FF0546CCB900F0D0FC012002F06A -:1006E0001DFEF8E78046D4E780460446D1E704467D -:1006F0004FF00108CDE780464FF47A74C9E704460D -:10070000CFE74FF47A74CCE71C46DDE700F004FF36 -:10071000401BA042E0D900F00BF8D9E77811002087 -:10072000010007B0000008B0263A09B000040048F4 -:1007300010B51C4B1C4953F8042F013200D110BDD9 -:100740008B42F8D1194C1A4B22689A4228D9194B7E -:100750009B6803F1006303F5D0439A4220D202F074 -:10076000C3FF02F0D5FF002000F0E2FD124B022093 -:10077000187000F019FE114BDA690022DA61D969AC -:1007800099699A619B6972B60D4A0E4B13601B689A -:100790002268202181F311889D4683F30888104741 -:1007A00010BD00BFFC6700081C6800080468000852 -:1007B000FF6700087811002084110020001002401B -:1007C00008ED00E00068000809490B6849F269007B -:1007D0009AB21B0C00FB0233064A0B60136844F20A -:1007E000506198B21B0C01FB0030106080B2704762 -:1007F0000C1100200811002010B500211022044621 -:1008000000F0ECFD034B03CB206061601868A06032 -:1008100010BD00BFACF7FF1FF0B51F4CBBB000F020 -:100820007BFEA368C31AF92B30D906AD2346A0601E -:1008300028220021284601F0FDFB04F10E0000F003 -:10084000C5FD0023C6B2591D5F1CDBB2B3424FEA9F -:10085000C10107DA0E3323440822284601F0EAFBDF -:100860003B46F0E7012303930823207B02930B4BC5 -:100870000193C1F3CF013023059100930146049504 -:1008800003A3D3E90023064801F0A4F93BB0F0BD6F -:1008900078F6339F93CACD8DC8210020D521002042 -:1008A000A021002070B50D4614461E4601F038F90F -:1008B00050B9022E0ED1012C0CD112A3D3E9002382 -:1008C000C5E90023012070BD052C14D003D8012CEC -:1008D00009D0002070BD282C09D0302CF9D10BA3F1 -:1008E000D3E90023ECE70BA3D3E90023E8E70BA34C -:1008F000D3E90023E4E70BA3D3E90023E0E700BF3B -:10090000AFF30080401DA12026812A0B78F6339F8B -:1009100093CACD8D9E6AC421818A46EE26417272A9 -:10092000DF25D7B7F017304A39059E5638B504464B -:100930000D46034620222846002101F07BFB227948 -:100940002346032A28BF032203F8042F2846022245 -:10095000202101F06FFB62792346072A28BF072276 -:1009600003F8052F28460322222101F063FBA27918 -:100970002346072A28BF072203F8062F284603220A -:10098000252101F057FB284604F1080310222821F5 -:1009900001F050FB382038BD2DE9F04FADF5017D59 -:1009A00021AE0EAD40F2791280460F46304600214E -:1009B00000F014FD48220021284600F00FFD00F051 -:1009C000ABFD594B4FF47A72B0FBF2F0186093E82C -:1009D0000700012385E807002B740DF15A0000235E -:1009E0006B74FFF709FF032385F82030EC2385F8AB -:1009F000213007AB18464D4903F06CF91B222864DF -:100A00003146284685F83C20FFF790FF12AB04469C -:100A100001460822304601F00DFB0822A1180DF115 -:100A20004903304601F006FB0DF14A03082204F1A8 -:100A30001001304601F0FEFA13AB202204F1180138 -:100A4000304601F0F7FA14AB402204F13801304689 -:100A500001F0F0FA16AB082204F17801304601F0FB -:100A6000E9FA0DF15903082204F18001304601F042 -:100A7000E1FA04F1880A0DF15A0904F5847B4B462A -:100A80005146082230460AF1080A01F0D3FAD3454C -:100A900009F10109F3D11BAB08225946304601F098 -:100AA000C9FA04F588744FF0000995F834304B45C5 -:100AB00010D84FF0000995F83C304B4515D92B6CF8 -:100AC00021464B440822304601F0B4FA083409F1BB -:100AD0000109F0E7AB6B21464B440822304601F098 -:100AE000A9FA083409F10109DFE7E31DC3F3CF03D5 -:100AF000F97E0593002304960393BB7E0293193776 -:100B000001230093019706A3D3E90023404601F097 -:100B100061F80DF5017DBDE8F08F00BFAFF30080F7 -:100B20009E6AC421818A46EE88110020AC3E0008EE -:100B3000014B1870704700BF94110020F0B5334B83 -:100B40001C7B85B034B1324B0E221A810024204622 -:100B500005B0F0BD2F4A1068516802AB03C30823EB -:100B60000DEB03022C492D4803F096F8054630B9E9 -:100B7000274B2B480A221A8100F084FCE6E7016922 -:100B8000B1F5663F06D9224B26480B221A8100F0A8 -:100B900079FCDCE7438BB3F57B7F09D01C4A224804 -:100BA0000C2111814FF47B72194600F06BFCCEE7EB -:100BB0001E4A024402F11003994204D2144B1C480D -:100BC00010221A81E3E710398E1A2046134900F0EB -:100BD000A7FC3246074605F11801204600F0A0FCAC -:100BE000AB689F4202D1EB6898420AD0084B0D22B5 -:100BF0001A8100903B46EA68A9680E4800F042FC62 -:100C0000A4E70D4800F03EFC0124A0E7C821002025 -:100C1000881100207C3D0008DC9703000068000874 -:100C2000843D0008903D0008A23D00080898FFF7A9 -:100C3000C03D0008DD3D0008063E00082DE9F04FEC -:100C4000ADB006AF80460C4600F06AFF05460028AE -:100C50006AD1237E022B18D1E38A012B15D100F033 -:100C60005BFC8146FFF7B0FD4FF4C873BD4EB0FB8F -:100C7000F3F209F5167902FB1300E37E19FA80F00E -:100C800030608BB9B84B00221A709C37BD46BDE866 -:100C9000F08F3B1D1D440095002308224FEAC90137 -:100CA000204601F02BF84D46A38A013BAB425FFA88 -:100CB00085F90BD905F10109B9F1110FE9D1AB4B58 -:100CC000AB4A40F23911AB4802F0B8FF07F114000B -:100CD000FFF792FD2A4607F11401381D02F0CCFF00 -:100CE00003460028CED1B9F1100F07D09E4B83F8F0 -:100CF00000903368A3F516733360C6E707F19802D6 -:100D0000014602F8950D20460092072200F0F6FFFA -:100D1000F9787F2904DD984B954A4FF4A871D2E702 -:100D2000404600F0E1FEB0E7E38A052B00F00681C3 -:100D300006D8012BA9D121464046FFF72DFEA4E796 -:100D4000282B3DD0302BA0D1637E8C4D01336A7BA4 -:100D5000DBB29342E94640F0EF80E27E2B7B9A4281 -:100D600040F0EA8007F19803002623F8846D1022F2 -:100D7000009331460123204600F0C0FFB4F81480F0 -:100D8000A8F102081FFA88F808F1030323F003030F -:100D90000A3323F00703ADEB030D0DF1180A3346B8 -:100DA0009BB2B11C98454FEAC10106F101066CDD0A -:100DB0005344009308220023204600F09FFFEEE7F3 -:100DC000A38A013B9BB2C92B3FF65FAF6B4E357BCD -:100DD0004DBB06F10C03009308222B462946204602 -:100DE00000F08CFFA38A05F10109013BEDB29D42A1 -:100DF0004FEAC90109DA0E3535440095002308226F -:100E0000204600F07BFF4D46ECE700230022C6E9B8 -:100E100000230023B36086F8D730C6F8D830337B80 -:100E20000BB9E37E3373002507F114063B1D08223E -:100E3000294630467D60BD60FD6001F0FBF83B7ADD -:100E400005F10109AB424FEAC90107D9FB68082245 -:100E50002B44304601F0EEF84D46F0E7C1F3CF01E8 -:100E60000023E07E059104960393A37E0293193438 -:100E7000282301460093019438A3D3E90023404678 -:100E800000F0A8FEFFF7C8FCFFE695F8D70000F0D9 -:100E900059FAD5F8D83006461BB995F8D70000F0B6 -:100EA00061FAD5F8D83043449E4204D295F8D70071 -:100EB000013000F057FA4FEA980B0024A0B25845D1 -:100EC00004F1010408DA2B6880000AEB000101221A -:100ED000184400F08BFAF1E7D5E90023D5F8D840A3 -:100EE00095F8D70012EB080243F100034444C5E92A -:100EF0000023C5F8D84000F025FA844209D395F8BC -:100F0000D730013385F8D730D5F8D8309E1BC5F8D7 -:100F1000D860B8F1FF0F08DC00232B7300F034FA1F -:100F2000FFF70CFE08B1FFF703FC2B68144A9B0A7D -:100F3000013313810023AB60CD46A6E6BFF34F8F8C -:100F40001049114BCA6802F4E0621343CB60BFF34F -:100F50004F8F00BFFDE700BFAFF3008026417272E4 -:100F6000DF25D7B79C21002099210020183E0008DA -:100F7000C83E0008713E0008933E0008C8210020CA -:100F80008811002000ED00E00400FA0508B54FF0DC -:100F900000530B4A196891420AD10A4A597D1170CF -:100FA00009481B7D0373C92208490E3000F004FA7A -:100FB000E02200214FF00050BDE8084000F00EBADA -:100FC0009AAD44C594110020C821002016000020CD -:100FD00030B5204C2049214885B002236371042399 -:100FE0000025ADF808300123ADF80C5007228DF82C -:100FF0000C308DF80B301A4B4B608DF80A2001F045 -:1010000003FE184B019500931749184B18484FF4ED -:10101000805200F033FD174B1978254611B1144862 -:1010200000F062FD00F078FA0446FFF7CDFB4FF4C4 -:10103000C87304F51674B0FBF3F202FB13000E4BF9 -:1010400014FA80F0186002F083FB08B10F232B81A3 -:1010500005B030BD8811002000110020E0220020E2 -:1010600003000600A5080008981100203D0C0008A8 -:10107000A0210020941100209C2100202DE9F04F98 -:1010800094A7D7E900670FF25429D9E900898D4C5C -:1010900093B0DFF850B2DFF850A2204600F0E6FD32 -:1010A0000CAD079098B310220021284600F096F965 -:1010B000079B197B4FF0000261F3030219468DF87C -:1010C000302051F8040F49680EAA03C21B680D9A1C -:1010D00063F31C029DF830300D9243F020038DF82D -:1010E000303000232A461946584601F09DFD0790EE -:1010F00030B9204600F0BEFD079B8AF80030CCE7EF -:101100009AF80030072B3EDC01338AF800301822B1 -:101110000021284600F062F9DFF8C8A10023194633 -:101120002A46504601F0A8FD014680BB102208A8BF -:1011300000F054F94FF09042536983F0100353616B -:1011400000F0ECF90B4612A9024611E903000DF17B -:10115000240E8EE803009DF83410C1F303008906C5 -:101160004CBF0E99BDF838108DF82C0046BFC1F366 -:101170001C0141F00041C1F30A010891204608A971 -:1011800000F0BEFFCAE7204600F074FDBFE720462E -:1011900000F0C6FC824600284AD1DFF850B100F0CA -:1011A000BBF9DBF80030984242D300F0B5F9079064 -:1011B000FFF70AFB079A8DF820A04FF4C87302F5D9 -:1011C0001672B0FBF3F101FB130012FA80F0CBF8BA -:1011D0000000DFF81CB19BF8001011B901238DF855 -:1011E000203028460791FFF707FB0799C1F1100A45 -:1011F0005FFA8AFABAF1060F28BF4FF0060A524684 -:1012000029440DF1210000F0D7F80AF101030493FD -:1012100008AB0393182302932B4B019301230093F4 -:1012200032463B46204600F07DFC00238BF8003020 -:1012300000F072F9254ADFF8BCA01368C31AB3F5B1 -:101240007A7F32D3106000F069F902460B462046DF -:1012500000F016FD204600F063FC30B39AF80C3025 -:10126000DFF894B0002B14BF032302238BF8053062 -:1012700000F052F94FF47A732946B0FBF3F0CBF843 -:1012800000005846FFF752FB182307300293104B1B -:101290000193C0F3CF0040F25513049000930395DF -:1012A00042464B46204600F03DFC9AF80C300BB10C -:1012B000FFF7B2FA9AF80C30002B7FF4EAAE13B0C5 -:1012C000BDE8F08FA021002098210020A822002056 -:1012D000AC220020401DA12026812A0BF1C6A7C107 -:1012E000D068080FE0220020AD2200209C210020C1 -:1012F00099210020C82100208811002070B502F03B -:10130000C3F8094C094E20700025306823788342C9 -:1013100008D902F0B5F8336805440133B5F5D04F6C -:101320003360F2D370BD00BFDC220020B022002069 -:1013300002F042B900F10060920000F5D04002F0E6 -:10134000E7B80000054B1A68054B1B789B1A8342CF -:1013500002D9104402F094B800207047B022002057 -:10136000DC22002038B5074D04462868204402F0EE -:101370008DF828B928682044BDE8384002F098B8B4 -:1013800038BD00BFB0220020064991F8243033B1A7 -:1013900000230822086A81F82430FFF7CBBF012020 -:1013A000704700BFB4220020022802BF4FF09043D4 -:1013B0004FF480129A61704710B50023934203D016 -:1013C000CC5CC4540133F9E710BD0000024603466B -:1013D000981A13F9011B0029FAD1704702440346F9 -:1013E000934202D003F8011BFAE770472DE9F0475A -:1013F000234C94F8243005468846174683BB2E4676 -:10140000DFF87C90C7B394F824302BB92022FF2159 -:1014100048462662FFF7E2FF94F82400C0F1080571 -:10142000BD4228BF3D465FFA85FAAD0041462A46D7 -:1014300004EB8000FFF7C0FF94F82430A7EB0A0705 -:101440009A445FFA8AFABAF1080F2E44A844FFB210 -:1014500084F824A0D6D1FFF797FF0028D2D108E066 -:10146000266A06EB8306B042CAD0FFF78DFF00283C -:10147000C5D10020BDE8F0870120BDE8F08700BF9E -:10148000B42200200FB4002004B070470FB44FF016 -:10149000FF3004B070470000FEE7000000B59BB0CD -:1014A000EFF3098168226846FFF786FFEFF30583B3 -:1014B000034B9A6B9A6A9A6A9A6A9A6A9B6AFEE7DF -:1014C00000ED00E000B59BB0EFF3098168226846AB -:1014D000FFF772FFEFF30583044B9A6B9A6A9A6ADF -:1014E0009A6A9A6A9A6A9B6AFEE700BF00ED00E07A -:1014F00000B59BB0EFF3098168226846FFF75CFFF7 -:10150000EFF30583034B5A6B9A6A9A6A9A6A9A6A4E -:101510009B6AFEE700ED00E002F086B802F060B8DA -:1015200030B5084D0A4491420BD011F8013B092413 -:101530005840013CF7D040F300032B4083EA5000B1 -:10154000F7E730BD2083B8ED0246006848B1036874 -:101550001360D388118901339BB29942D38038BF7D -:101560001381704770B588B00D46044620220021D3 -:101570006846FFF733FF20460495FFF7E5FF054671 -:1015800058B16B46044608AE1A4603CAB242206000 -:101590006160134604F10804F6D1284608B070BD16 -:1015A0002DE9F04130B9274B274A40F2C531274891 -:1015B00002F044FB0B7C23B9254B234A40F2C63191 -:1015C000F5E7C66986B9C161BDE8F081002B29DA6B -:1015D000930CAB4229D1B44201D10C60F3E7C8F8B7 -:1015E00000100C60BDE8F0814B6823F06047BD0C33 -:1015F0004FEAD37EC3F3807C15EA230538BF3D460E -:10160000B04634466368BEEBD37F23F06042DDD141 -:10161000974203D1C3F380739C450AD1974205E0FA -:101620001C46EFE7AA4206D013469D422CBF00237A -:101630000123002BCFD12368A046002BF0D12160DD -:10164000BDE8F0819C410008903F0008544200082A -:101650007542000808B5034A034B044840F25E3166 -:1016600002F0ECFA6C3F00081442000854420008F3 -:1016700008B503680B60C388016033B9044B054AA1 -:1016800005484FF4C76102F0D9FA013BC38008BD99 -:10169000E4410008E03F00085442000870B50C46E1 -:1016A00000F10C05616831B9E38A61F30903E38253 -:1016B0000020002170BD0E682846FFF7D9FF666044 -:1016C000F0E7000008B5426832B10B4B0B4A0C48FA -:1016D00040F22F4102F0B2FAC37DC3F3840101311D -:1016E00061F38603C375C38A62F30903C3821B0ACD -:1016F00062F3C713C37508BD304200089C3F000861 -:10170000544200082DE9F047089E32B91F4B204A89 -:10171000204840F2395102F091FA01F007054FEAF2 -:10172000D6082A4406F0070600EBD1004FF47F49A3 -:10173000954201D1BDE8F08705F0070E06F0070AD3 -:10174000D645774638BF5746C7F10807511BEC0806 -:101750008F4228BF0F46045D08EBD60104FA0EF451 -:1017600013F801C029FA07FE24FA0AF45FFA8EFE84 -:101770008CEA04044EFA0AFE04EA0E048CEA040C15 -:1017800003F801C03D443E44D2E700BFB041000829 -:10179000B43F0008544200082DE9F04106460F46C8 -:1017A00000254FF6FF7441F221082A46304639469B -:1017B000FEF7F6FCC0B284EA0024082314F4004FBC -:1017C0004FEA4404A4B203F1FF3318BF84EA0804CB -:1017D00013F0FF03F2D10835402DE6D12046BDE8D5 -:1017E000F081000010B50A4441F22104914200D179 -:1017F00010BD11F8013B80EA0320082310F4004FCC -:101800004FEA400080B203F1FF3318BF604013F08D -:10181000FF03F3D1EAE700002DE9F04F85B08A46D7 -:101820008DE80C00BDF83C40814630B9494B4A4A2E -:1018300040F26E31494802F001FA11F0604F04D0D5 -:10184000474B454A40F26F31F4E7009B002B7ED0B6 -:1018500024B10E9B002B7AD0072C28D809F10C005C -:10186000FFF772FE054628B96FF00205284605B05D -:10187000BDE8F08F14220021FFF7B0FD22460E993B -:1018800005F10800FFF798FD631C2B74009B1B7883 -:101890002C4403F01F0363F03F0323724AF000431C -:1018A0006B6029464846FFF77BFE0125DEE7019B7A -:1018B0001B0A4FF00008029300F10C034FF0800B5D -:1018C0004646454603930398FFF73EFE0746002829 -:1018D000CAD014220021FFF781FDB6BB9DF8043069 -:1018E0003B729DF808307B7202220E9B711E1944D8 -:1018F000B4420AD9B8180132D2B211F801EF80F817 -:1019000008E00136072AB6B2F2D1009B197801F03F -:101910001F01B44208BF4FF0400BB81841EA48110C -:101920004BEA0103037201324AF000437B603A74D0 -:1019300039464846FFF734FE0135B4422DB288F0EF -:1019400001084FF0000BBED190E70022CDE76FF009 -:1019500001058BE79C410008803F000854420008C5 -:10196000C04100082DE9F0471E46CB8A9146C3F3DB -:101970000902062A80460F4619D013460021B0B24C -:101980008DB25A1992B2052A09D9A84210D8FA8AFA -:10199000034463F30902FA820120BDE8F087A842FC -:1019A000F3D93A4419F8014094760131E8E700256B -:1019B000FB8A7C68C3F30900821F1C23B2FBF3FA85 -:1019C00003FB1A2A1FFA8AF27CB301212368002B39 -:1019D00039D1B31F03441C20B3FBF0F301339BB296 -:1019E00099420CD2BAF1000F09D14046FFF7ACFD85 -:1019F00008B1C0F800A0206008B304460022B6B2C7 -:101A00004FF0000AB54230D2691E49441346E0182F -:101A100001339BB211F801EF80F804E001351C2B73 -:101A2000ADB214D0AE42F2D8ECE74046FFF78CFDE1 -:101A3000044608B1002303607C60002CDED16FF007 -:101A40000200BDE8F087013189B21C46BEE7AE4214 -:101A5000D8D94046FFF778FD08B1C0F800A0206053 -:101A60000028ECD004460022CCE7FB8AC3F309022D -:101A7000164466F30903FB828EE70000F8B50E46B4 -:101A800015461F46044628B9144B154A15484F21E0 -:101A900002F0D4F824220021FFF7A0FC069B63602B -:101AA000079B23626A094FF6FF739A424FF00000CA -:101AB00028BF1A46A7602070A061E06197B204F1C8 -:101AC0000C05824205D100232B6027826382A3820A -:101AD000F8BD2E60013035462036F2E79841000807 -:101AE0000C3F00085442000808B528B9084B094AC1 -:101AF0007321094802F0A2F8037823B94BB2002BF6 -:101B000001DD017008BD054B024A7D21F1E700BFF0 -:101B10009C410008183F000854420008E0400008BB -:101B2000007870472DE9F7430D9EBDF828900B9D76 -:101B30009DF83040BDF8388007461946104616B962 -:101B4000B8F1000F43D11F2C41D83B78D3B9B8F17D -:101B5000070F39D839F0030339D1424631464FF6E1 -:101B6000FF70FFF73FFE4FEA092920F0010009F45A -:101B70004079400449EA0464400C44EA40244FF6AA -:101B8000FF730DE043EA0923B8F1070F43EA046449 -:101B9000F5D9FFF701FE42463146FFF723FE034623 -:101BA0008DE840012A4621463846FFF735FE0DB93B -:101BB000FFF750FD2B780133DBB21F2B88BF0023CA -:101BC0002B7003B0BDE8F0836FF00300F9E76FF00E -:101BD0000100F6E72DE9F7430E9F0B9D9DF8348039 -:101BE000BDF83C6081469DF8300007B9C6BB1F2890 -:101BF00036D899F800E0BEF1000F34D00C0244F062 -:101C000080049DF8281044EAC83444EA014444EAB8 -:101C10000E04072E44EA006415D919461046FFF752 -:101C2000BBFD32463946FFF7DDFD034601960097BE -:101C30002A4621464846FFF7EFFDB8F1010F0CD1C7 -:101C400025B9FFF707FD4FF6FF73EFE72B78013358 -:101C5000DBB21F2B88BF00232B7003B0BDE8F083DD -:101C60006FF00100F9E76FF00300F6E7C06900B11B -:101C700004307047C1690B68C3610C30FFF7F8BCD2 -:101C80002DE9F84FD0F818A0DFF86C80054616460D -:101C90001F4654464FF0000900F10C0B0CB9BDE88B -:101CA000F88FD4E90223B21A67EB0303994508BF02 -:101CB00090451FD2AB699C42214628460DD1FFF7C3 -:101CC000EDFCAB691B68AB6121465846FFF7D0FCC1 -:101CD000AC692346A2461C46E0E7FFF7DFFC236819 -:101CE000CAF8003021465846FFF7C2FC5446DAF8DD -:101CF0000030EFE72368EDE780841E002DE9F04F08 -:101D00008BB00D4614460793DDF8509082460028AC -:101D100000F06481B9F1000F00F06081531E3F2B89 -:101D200000F25C81012A03D1079B002B40F0568111 -:101D3000BAF81460F6000023B5420893099380F0C6 -:101D400053812B199E420AD2761B16F0FF0607D14B -:101D5000AB4BAC4A40F26751AB4801F06FFF2646EF -:101D6000DAF80C3023B9DAF81030002B00F0A58037 -:101D70002F2D31D8C5F1300846454FF000032CBF58 -:101D80005FFA88F8B0460093294608AB4246DAF875 -:101D90000800FFF7B7FCA6EB08074544FFB2BAF806 -:101DA000143003F10053063BDB000293DAF80C30E9 -:101DB00005934FF0300B059B002B51D087B9DAF813 -:101DC0001000002861D0002F5FD0AB4550D98F4B59 -:101DD0008C4A40F2A651BFE737464FF00008DEE7D5 -:101DE000029B23B98A4B874A4FF4B161B4E7029B47 -:101DF000E02B28BFE02306935B44AB4204931DD93C -:101E00005B1B9F4226BFDBB203930397AB4504D90C -:101E10007E4B7C4A40F291519EE70598CDF80080B8 -:101E200008ABA5EB0B01039A0430FFF76BFC039B97 -:101E30009844FF1A1D445FFA88F8FFB2049B9B4543 -:101E400004D3744B6F4A40F29B5185E7029B069A7C -:101E5000DDF810B09B1A0293059B1B680593AAE757 -:101E6000029BBB42ABD26C4B664A40F2A15173E776 -:101E7000CDF800803A46A5EB0B0108ABFFF742FC1A -:101E8000B8443D445FFA88F80027BAF81430B5EB3F -:101E9000C30F04D9614B5B4A40F2B1515CE7B8F122 -:101EA000400F04D95E4B574A40F2B25154E767B134 -:101EB0005C4B544A40F2B3514EE70093324608ABB4 -:101EC0002946DAF80800FFF71DFC731E3F2B35B2D8 -:101ED00001D8A64204DD544B544A40F235213BE779 -:101EE00060070AD00AAB03EBD401624211F8083C48 -:101EF00002F00702134101F8083C082C21D9102CEC -:101F000021D9202C8CBF08230423079A002A6DD0E6 -:101F1000B4EBC30F6CD0082C04F1FF3215D89DF838 -:101F2000203023FA02F2D10706D54FF0FF3202FA31 -:101F300004F423438DF820309DF8203089F80030D8 -:101F40004EE00123E1E70223DFE7102C11D8BDF8B2 -:101F5000203023FA02F2D20706D54FF0FF3202FA00 -:101F600004F42343ADF82030BDF82030A9F8003048 -:101F700036E0202C0ED8089921FA02F2D30705D5B5 -:101F80004FF0FF3303FA04F40C430894089BC9F89C -:101F9000003025E0402C1CD0DDE90867304639468A -:101FA000FEF7FEF8002100F0010050EA01030BD01B -:101FB000224601200021FEF7FFF8404261EB41017B -:101FC00006430F43CDE90867DDE90823C9E900238B -:101FD00006E0174B154A4FF42071BDE66FF001057E -:101FE00028460BB0BDE8F08F1D46F9E7012CA3D0C1 -:101FF000082CA1D9102CB7D9202CE5D8C6E700BFF2 -:10200000EC3F0008C43F0008544200080E4000089E -:10201000FB3F0008334000085B4000088240000896 -:10202000B0400008C8400008E2400008443F0008F3 -:10203000E040000830B585B030B9244B244A40F266 -:10204000B121244801F0FAFD23B9234B204A40F284 -:10205000B221F6E7402A04D9204B1D4A40F2B621AE -:10206000EFE722B91D4B1A4A4FF42F71E9E700241C -:10207000012A0294039417D11B788DF80830530776 -:102080000AD004AB03EBD203554213F8084C05F019 -:102090000705AC4003F8084C00910346002102A854 -:1020A000FFF730FB05B030BD082AE5D9102A03D868 -:1020B0001B88ADF80830E2E7202A02D81B6802939B -:1020C000DDE7D3E90045CDE90245D8E71C4100082A -:1020D000583F00085442000837410008E04000081B -:1020E00070B50C4600F10C05E16819B9A1602161D9 -:1020F000A18270BD0E682846FFF7BAFAE660F3E7E2 -:102100002DE9F04FD1F8009091B0C9F3C016044604 -:102110000D46CDE90223002E50D0C9F3C03BC9F3D0 -:102120000626B9F1000F80F29F8119F0C04F40F0F0 -:102130009B812B7B002B00F09781BBF1020F03D01A -:102140002278B24240F0938109F07F02BBF1020F86 -:10215000059236D119F07F0FC9F30F2A01D10AF089 -:10216000030A2B447606059A93F8038046EA0B4649 -:1021700046EA82465FEAD81346EA0A06069300F06A -:102180009A800022002310A961E90823059B00938F -:1021900067685B4652462046B847002800F08880B2 -:1021A000A7698FB9314604F10C00FFF7DBF9074648 -:1021B000D0B96FF0020011B0BDE8F08F4FF0020B04 -:1021C000AFE7C9F3074ACCE73B699E420DD03F68B1 -:1021D000002FF9D1314604F10C00FFF7C3F907468F -:1021E0000028E6D0A3693B60A761DDE90801FFF79D -:1021F000D3FAB882F97D08F01F06C1F38401711A81 -:1022000089B20FFA81FED7E90223BEF1000FB8BFF1 -:1022100001F1200EC9F30461B8BF0FFA8EFE0791D9 -:1022200052EA030100F02F81DDE90201801A61EB1F -:10223000030102460B469F480021994208BF904285 -:10224000C0F02181069B002B3FD0BEF1010F00F3AF -:102250001A8118F0400F38D0DDE90223C7E90223C4 -:10226000202200210DEB0200FFF7B8F8DDE9022380 -:10227000CDE908232B1D0A932B7BADF836A0013B3B -:10228000DBB2ADF834309DF81C308DF83A309DF853 -:1022900014308DF83B3020468DF838B08DF8396019 -:1022A000A36808A998473846FFF70CFA002082E790 -:1022B0006FF00B007FE7A76917B96FF00C007AE7A2 -:1022C0003B699E4296D03F68F6E7FB7DC8F340121B -:1022D000B2EBD31F40F0CE80C3F38403B34240F08F -:1022E000CC8006992B7B4FEA981279B3D2073CD465 -:1022F000032B40F2C580DDE90223C7E902232B7BD3 -:10230000AE1D033BDBB23246394604F10C00FFF749 -:1023100029FB002808DA39462046FFF7BFF938467E -:10232000FFF7D0F9032046E7AB883B832A7B033ACB -:10233000D2B2B88A3146FFF755FAFB7DB882DA434C -:10234000C2F3C01262F3C713FB75AFE76AB92E1D63 -:10235000013BDBB23246394604F10C00FFF702FBC9 -:102360000028D8DB2A7B013AE2E7FA8AC2F30902A5 -:10237000013B052AD9B250D8281D002399420AD919 -:1023800007EB020E013210F801CB8EF81AC00133B0 -:10239000062ADBB2F2D1DDE902898B4207F11A028B -:1023A000CDE908890A9238BF04337A680B9234BFAA -:1023B0005B1900230C93FB8AADF836A0C3F3090325 -:1023C00019449DF81C308DF83A309DF814308DF882 -:1023D0003B300023ADF834108DF838B08DF83960FB -:1023E0007B602A7BB88A013A291DFFF7FBF93B8BFA -:1023F000B882834203D1A36808A92046984708A958 -:102400002046FFF76DFE3846FFF75CF9B88A3B8B34 -:10241000984214BF11200020CDE6786810B34FF029 -:10242000060E03689BB9A2EB0E021B2A13D80332D7 -:10243000024405F1040E1F309942ACD91EF801CBBD -:1024400002F801CF01339042DBB2F5D1A3E70EF1E0 -:102450001C0E1846E5E7184B184A194840F2B3110C -:1024600001F0ECFB034696E76FF00900A3E66FF07E -:102470000A00A0E66FF00D009DE66FF00E009AE6F0 -:102480006FF00F0097E6FB7D68F386036FF3C713C9 -:10249000FB7539462046FFF701F9069B002B7FF4B8 -:1024A000D8AEFB7DC3F38402013262F38603FB7571 -:1024B00003E700BF80841E004C410008303F000845 -:1024C000544200082DE9F0414C4EB04240F081806A -:1024D0004B4CDFF830E1E56945F00075E561E469F2 -:1024E000846AD4F8007207EA0E0747F00107C4F8BF -:1024F0000072D4F8005205EA0E0545F0010545EAE0 -:102500000121C4F80012002A65D00021C4F81C1271 -:102510000F46C4F80412C4F80C12C4F8141204EBE9 -:10252000C10501310E29C5F84072C5F84472F6D1D3 -:102530004FF0000E4FF0010C964510D1826AD2F890 -:102540000032B04223F00103C2F8003253D12C4BC9 -:10255000DA6922F00072DA61DB69BDE8F0819F7808 -:102560001D8817F0010F18BFD4F804820CFA05F18A -:102570001CBF41EA0808C4F8048217F0020F1EBF0E -:10258000D4F80C8241EA0808C4F80C827F0742BFE5 -:10259000D4F814720F43C4F8147204EBC5055F68D5 -:1025A000C5F840729F68C5F84472D4F81C5229439C -:1025B000C4F81C120C330EF1010EBDE7846A002131 -:1025C000C4F81C12C4F80412C4F80C12C4F8141293 -:1025D000AEE7002AF2D1836A0022C3F84022C3F892 -:1025E0004422C3F80422C3F814220122C3F80C22A7 -:1025F000C3F81C22A2E7BDE8F08100BFE022002062 -:10260000001002400000FFFF184A916A08B58B686D -:102610008B6013F0010105D013F00C0F14BF4FF4C1 -:1026200080310121D80506D513F4406F14BF41F461 -:10263000003141F00201D80306D513F4402F14BF36 -:1026400041F4802141F00401D3690BB10748984758 -:10265000202383F311880021054800F087FE002322 -:1026600083F31188BDE8084001F088B8E02200201B -:10267000E822002038B5124CA36ADD68AA0712D000 -:102680005A6922F002025A61A36913B1012120465E -:102690009847202383F3118800210A4800F066FE42 -:1026A000002383F31188EB0606D5A36A1021D960B5 -:1026B000236A0BB102489847BDE8384001F05EB884 -:1026C000E0220020F022002038B5124CA36A1D69D8 -:1026D000AA0712D05A6922F010025A61A36913B1F5 -:1026E000022120469847202383F3118800210A48BD -:1026F00000F03CFE002383F31188EB0606D5A36AA5 -:1027000010211961236A0BB102489847BDE838408F -:1027100001F034B8E0220020F022002038B50F4C40 -:10272000A36A5D685D602A070AD5032222701A68D1 -:1027300022F002021A60636A13B100212046984712 -:102740006B0706D5A36A9969236A13B10904034884 -:102750009847BDE8384001F011B800BFE0220020E2 -:1027600010B50F4C204600F03DFA0E4BA3620B2132 -:10277000132000F017FA0B21142000F013FA0B219C -:10278000152000F00FFA0B21162000F00BFA0023A1 -:1027900020461A460E21BDE81040FFF793BE00BF49 -:1027A000E0220020006400400F4B984210B5044620 -:1027B00005D10E4BDA6942F00072DA61DB69A36A77 -:1027C00001221A60A36A5A68D20707D56268516865 -:1027D0001268D9611A60064A5A6110BD01210820A9 -:1027E00000F07CFCEEE700BFE02200200010024079 -:1027F0005B87010003291AD8DFE801F0020A0F14F1 -:10280000836A9B6813F0E05F14BF012000207047CB -:10281000836A9868C0F380607047836A9868C0F3E1 -:10282000C0607047836A9868C0F3007070470020EA -:102830007047000010B503291FD8DFE801F0021F20 -:102840002327816A8B68C3F30163183301EB0313F9 -:10285000107881061ED55468C0F30011490041EA82 -:10286000C40141F0040100F00F00586090689860C6 -:10287000D268DA6041F00101196010BD836A03F586 -:10288000C073E5E7836A03F5C873E1E7836A03F57C -:10289000D073DDE79488C0F30011490041EA445148 -:1028A000E1E7000001290CD003D3022910D0002059 -:1028B0007047836ADA68920701D1186903E0012042 -:1028C0007047836AD86810F0030018BF0120704772 -:1028D000836AF2E710B539B9836AD96889071BD1D1 -:1028E0001B699B0704D110BD012915D0022948D1CD -:1028F000816AD1F8C031D1F8C401D1F8C84114615E -:10290000D1F8CC41546120240C610C69A40717D183 -:102910004C6944F0100412E0816AD1F8B031D1F86A -:10292000B401D1F8B8411461D1F8BC4154612024FC -:10293000CC60CC68A40703D14C6944F002044C611C -:1029400011795C0864F304119C0864F3451111715A -:1029500089064BBF91681189DB085B0D4CBF63F39F -:102960001C0163F30A01137948BF916060F303030C -:1029700013714FEA10234FEA104058BF11811370B2 -:10298000508010BD002304491A465A50C818083315 -:10299000802B4260F9D170470C2300200268436805 -:1029A0001143016003B1184770470000024A1368E1 -:1029B00043F0C0031360704700380140024A1368B7 -:1029C00043F0C00313607047004400402DE9F04716 -:1029D000C66D3768F46934620546200719D014F0D3 -:1029E000080F0CBF00218021E20748BF41F0200101 -:1029F000A30748BF41F04001600748BF41F4807120 -:102A0000202383F31188281DFFF7C8FF002383F3D9 -:102A10001188E2050AD5202383F311884FF4007151 -:102A2000281DFFF7BBFF002383F311884FF0200917 -:102A30004FF0000A14F0200831D13B0616D54FF0B4 -:102A4000200905F1380A200610D589F3118850466F -:102A500000F04CFA00282FDA0821281DFFF79EFF0E -:102A600027F080033360002383F3118879060DD5A6 -:102A700062060BD5202383F31188EA6C2B6D9A42F2 -:102A800001D12B6CF3B9002383F31188E30621D520 -:102A9000AA6E1369F3B15069BDE8F047184789F38E -:102AA0001188B38C95F864102846194000F0AAFAF2 -:102AB0008AF31188F469BDE780B2308588F3118804 -:102AC000F469C0E71021281D27F04007FFF766FFD3 -:102AD0003760D8E7BDE8F08708B50348FFF776FF11 -:102AE000BDE8084000F04ABE8C23002008B503482A -:102AF000FFF76CFFBDE8084000F040BEF82300205F -:102B000037B51D4C1D4D204600F070FA009404F1BD -:102B10001400002320221A4900F032F920220094E8 -:102B200004F13800174B184900F0ACF9174BE36576 -:102B30002566174C0C21252000F034F8204600F0C3 -:102B400055FA04F11400009400232022114900F0EA -:102B500017F904F1380000940F4B1049202200F0BF -:102B600091F90F4BE3650C212620256603B0BDE8E3 -:102B7000304000F017B800BF8C2300200051250220 -:102B800064240020AD290008A4240020003801405E -:102B9000F823002084240020BD290008C42400203C -:102BA0000044004000F1604300F01F02400903F5BB -:102BB000614309018000C9B200F1604083F800134D -:102BC00000F5614001239340C0F8803103607047F5 -:102BD00000F16040090100F56D40C9B2017670470F -:102BE000FFF7BEBD00F108020123037082600023DD -:102BF000C26000F110024360026142618361C361FF -:102C0000036243627047000010B52023044683F33B -:102C10001188022303704160FFF7C6FD0323237070 -:102C2000002383F3118810BD2DE9F0411F460446AF -:102C30000D461646202383F3118800F108082378F7 -:102C4000042B0ED029462046FFF7D4FD48B120467C -:102C500032462946FFF7EEFD002080F31188BDE8DB -:102C6000F0813946404600F065FB0028E7D000239C -:102C700083F31188BDE8F0812DE9F0411F46044639 -:102C80000D461646202383F3118800F1100823789F -:102C9000042B0ED029462046FFF704FE48B12046FB -:102CA00032462946FFF716FE002080F31188BDE862 -:102CB000F0813946404600F03DFB0028E7D0002374 -:102CC00083F31188BDE8F081F8B51546826806697E -:102CD000AA420B46816938BF8568761AB542044618 -:102CE00007D218462A46FEF767FBA3692B44A36167 -:102CF0000DE011D932461846FEF75EFBAF1B3A468F -:102D0000E1683044FEF758FBE2683A44A261A368E8 -:102D10005B1BA3602846F8BD18462A46FEF74CFB0D -:102D2000E368E4E783682DE9F041044693421546E1 -:102D3000266938BF85684069361AB5420F4606D203 -:102D40002A46FEF739FB63692B4463610DE012D913 -:102D50003246A5EB0608FEF72FFB4246B919E0689C -:102D6000FEF72AFBE26842446261A3685B1BA36032 -:102D70002846BDE8F0812A46FEF71EFBE368E4E73B -:102D800010B50A440024C361029B00604060846067 -:102D9000C160816141610261036210BD08B5826951 -:102DA0004369934201D1826882B9826801328260AC -:102DB0005A1C42611970426903699A4201D3C3687F -:102DC0004361002100F0C6FA002008BD4FF0FF303B -:102DD00008BD000070B5202304460E4683F3118819 -:102DE000A568A5B1A368A269013BA360531CA361B8 -:102DF00015782269934224BFE368A361E3690BB1AC -:102E000020469847002383F31188284670BD314639 -:102E1000204600F08FFA0028E2DA85F3118870BDB1 -:102E20002DE9F74F05460F4690469A46D0F81C907C -:102E3000202686F311884FF0000B144664B1224619 -:102E400039462846FFF740FF034668B951462846F1 -:102E500000F070FA0028F1D0002383F31188A8EB6A -:102E6000040003B0BDE8F08FB9F1000F03D001906A -:102E70002846C847019B8BF31188E41A1F4486F348 -:102E80001188DBE7C16081614161C3611144009B2E -:102E9000006040608260016103627047F8B50446DB -:102EA0000E461746202383F31188A568A5B1A368B1 -:102EB000013BA36063695A1C62611E7023696269E9 -:102EC0009A4224BFE3686361E3690BB120469847E7 -:102ED000002080F31188F8BD3946204600F02AFA18 -:102EE0000028E2DA85F31188F8BD000083694269A1 -:102EF0009A4210B501D182687AB982680132826043 -:102F00005A1C82611C7803699A4201D3C3688361A9 -:102F1000002100F01FFA204610BD4FF0FF3010BD19 -:102F20002DE9F74F05460F4690469A46D0F81C907B -:102F3000202686F311884FF0000B144664B1224618 -:102F400039462846FFF7EEFE034668B95146284643 -:102F500000F0F0F90028F1D0002383F31188A8EBEA -:102F6000040003B0BDE8F08FB9F1000F03D0019069 -:102F70002846C847019B8BF31188E41A1F4486F347 -:102F80001188DBE7026843681143016003B1184709 -:102F9000704700001430FFF743BF00004FF0FF33CD -:102FA0001430FFF73DBF00003830FFF7B9BF000015 -:102FB0004FF0FF333830FFF7B3BF00001430FFF796 -:102FC00009BF00004FF0FF311430FFF703BF0000CE -:102FD0003830FFF763BF00004FF0FF323830FFF7A3 -:102FE0005DBF000000207047FFF78ABD044B0360FF -:102FF000002343608360C36001230374704700BFF4 -:103000009042000838B5C36904460D461BB9042137 -:103010000844FFF7B7FF294604F11400FFF7BEFE8E -:10302000002806DA201D4FF48061BDE83840FFF724 -:10303000A9BF38BD024B00221B605B609A607047DD -:10304000E4240020002303748268054B1B68996800 -:103050009142FBD25A68036042601060586070472A -:10306000E424002008B5202383F31188037C032B7C -:1030700005D0042B0DD02BB983F3118808BD43690B -:1030800000221A604FF0FF334361FFF7DBFF00239C -:10309000F2E790E80C001A6002685360F2E7000063 -:1030A000002303748268054B1B6899689142FBD822 -:1030B0005A6803604260106058607047E424002042 -:1030C000054B19690874186802681A605360186122 -:1030D00001230374FDF798BAE424002030B54B1C9B -:1030E00087B005460A4C10D023690A4A01A800F0AF -:1030F00059F92846FFF7E4FF049B13B101A800F03B -:103100006BF92369586907B030BDFFF7D9FFF8E7BD -:10311000E42400206530000838B50C4D41612B696E -:1031200081689A689142044603D8BDE83840FFF7A9 -:1031300089BF1846FFF786FF01232C6101462374DF -:103140002046BDE83840FDF75FBA00BFE424002008 -:10315000044B1A681B6990689B68984294BF0020D2 -:1031600001207047E424002010B5084C2368206932 -:103170001A6822605460012223611A74FFF790FFDD -:1031800001462069BDE81040FDF73EBAE424002066 -:1031900008B5FFF7DDFF18B1BDE80840FFF7E4BF51 -:1031A00008BD0000FEE7000010B5174CFFF742FF16 -:1031B00000F0EAF880221549204600F06FF801235C -:1031C00044F8180C0374124B124AD96821F4E061D8 -:1031D0000904090C0A431049DA60CA6842F0807297 -:1031E000CA600E490A6842F001020A601022DA77CA -:1031F000202283F82220002383F3118862B6084836 -:10320000BDE8104000F06CB80C250020B842000862 -:1032100000ED00E00003FA05F0ED00E0001000E032 -:10322000C0420008F8B50F4C226A013222622246E1 -:1032300052F8141F9142154606D08B68013B8B60F3 -:10324000202663699A6802B1F8BD1968DF68DA6000 -:103250004D60616182F311881869B84786F311885F -:10326000EFE700BFE4240020EFF3118020B9EFF373 -:103270000583202282F311887047000010B558B9E9 -:10328000EFF30584C4F3080414B180F3118810BD72 -:10329000FFF77EFF84F3118810BD000082600222D8 -:1032A00002740022427470478368A3F17C0243F8E1 -:1032B0000C2C026943F83C2C426943F8382C074A2D -:1032C00043F81C2CC26843F8102C022203F8082C87 -:1032D000002203F8072CA3F118007047210600080C -:1032E00010B5202383F31188FFF7DEFF0021044689 -:1032F000FFF712FF002383F31188204610BD000062 -:10330000024B1B6958610F20FFF7DABEE42400204E -:10331000202383F31188FFF7F3BF000008B50146AF -:10332000202383F311880820FFF7D8FE002383F3BE -:10333000118808BD49B1064B42681B6918605A6084 -:10334000136043600420FFF7C9BE4FF0FF307047A1 -:10335000E42400200368984206D01A680260506096 -:1033600059611846FFF76EBE7047000038B5044635 -:103370000D462068844200D138BD036823605C603C -:103380004561FFF75FFEF4E7054B03F114025A6154 -:103390009A614FF0FF32DA6100221A62704700BF73 -:1033A000E424002010B5C2600A4A036153699C6896 -:1033B000A1420CD85C680360446020605860816062 -:1033C0009868411A99604FF0FF33D36110BD091B13 -:1033D0001B68ECE7E4240020036881689A680A44CB -:1033E0009A604268136003685A600023C360024B0E -:1033F0004FF0FF32DA617047E4240020002070476C -:10340000FEE70000704700004FF0FF3070470000FB -:10341000BFF34F8F024AD368DB07FCD4704700BF6D -:103420000020024008B5074B1B7853B9FFF7F0FFA7 -:10343000054B1A69120641BF044A5A6002F18832EC -:103440005A6008BD70260020002002402301674515 -:1034500008B5054B1B7833B9FFF7DAFF034A136948 -:1034600043F08003136108BD702600200020024055 -:103470007F289ABF00F58030C0020020704700000E -:103480004FF4006070470000802070477F2808B527 -:103490000BD8FFF7EDFF00F500630268013204D19D -:1034A00004308342F9D1012008BD002008BD00008E -:1034B0007F2838B5044624D800F0B6F8124D2860AD -:1034C000FFF7A6FFFFF7AEFF104BF322DA600222F0 -:1034D0001A612046FFF7CCFF58611A6942F040029A -:1034E0001A61FFF795FF4FF4006100F0FBF8FFF75A -:1034F000AFFF00F099F828602046BDE83840FFF79C -:10350000C5BF002038BD00BF742600200020024047 -:103510002DE9F84312F00103144606D0204B40F287 -:103520004B221A600020BDE8F88385181D4A954299 -:1035300004D91B4A4FF414711160F3E7FFF772FFCF -:10354000FFF766FFDFF86C80451A4FF00109012C88 -:1035500005EB01060F4604D8FFF77AFF0120BDE80E -:10356000F883C8F8109031F8023B3380FFF750FF22 -:103570000020C8F8100033883A889BB29A420DD0D8 -:10358000074B40F267221A60074B1E60074B1C6016 -:10359000074B1F60FFF75CFFBDE8F883023CD6E7EE -:1035A0006C260020FFFF030860260020682600200C -:1035B0006426002000200240084908B50B7828B195 -:1035C00053B9FFF72FFF01230B7008BD23B1BDE8EE -:1035D00008400870FFF73CBF08BD00BF7026002000 -:1035E00038B5FFF741FE0D4B0D4A1C6A11684FF4C8 -:1035F0007A7303FB04F38B420A49D1E9004504D2F4 -:10360000003445F10105C1E90045E41845F1000524 -:103610001360FFF733FE2046294638BDE42400201E -:10362000782600208026002008B5FFF7D9FF4FF448 -:103630007A720023FCF7CCFD08BD00BF10B5024430 -:10364000064B0439D2B2904200D110BD441C00B2E6 -:1036500053F8200041F8040FE0B2F4E7502800408E -:10366000104B30B51C6A240407D41C6A44F440741F -:103670001C621C6A44F400441C620B4C236843F433 -:10368000807323600244094B0439D2B2904200D1C6 -:1036900030BD441C00B251F8045F43F82050E0B242 -:1036A000F4E700BF001002400070004050280040C6 -:1036B00007B5012201A90020FFF7C0FF019803B060 -:1036C0005DF804FB13B50446FFF7F2FFA04206D0F5 -:1036D00002A9012241F8044D0020FFF7C1FF02B00A -:1036E00010BD000070470000074B45F255521A60AC -:1036F00002225A6040F6FF729A604CF6CC421A6081 -:10370000024B01221A7070470030004089260020C9 -:10371000034B1B781BB1034B4AF6AA221A60704771 -:103720008926002000300040034B1B689B0042BFED -:10373000024B01221A707047241002408826002094 -:10374000024B4FF080721A60704700BF2410024095 -:10375000014B1878704700BF88260020064A53683E -:1037600023F001035360EFF30983683383F309887F -:10377000002383F31188704730EF00E010B5202359 -:1037800083F31188104B5B6813F4006318D0F1EEDB -:10379000103AEFF309844FF0807344F84C3C0B4B24 -:1037A000DB6844F8083CA4F1680383F30988FFF759 -:1037B000CFFC18B1064B44F8503C10BD054BFAE75E -:1037C00083F3118810BD00BF00ED00E030EF00E092 -:1037D000310600083406000870470000FEE70000CC -:1037E000084A094B09498B4204D3094A00219342F4 -:1037F00005D3704752F8040F43F8040BF3E743F87E -:10380000041BF4E740440008902600209026002086 -:10381000902600204B6843608B688360CB68C36050 -:103820000B6943614B6903628B6943620B680360F8 -:103830007047000008B5194B9A6A42F4FC029A627C -:103840009A6A22F4FC029A629A6A5A6942F4FC0269 -:103850005A61134A5B6911464FF09040FFF7DAFF57 -:10386000104802F11C01FFF7D5FF0F4802F13801A3 -:10387000FFF7D0FF0D4802F15401FFF7CBFF0C48D2 -:1038800002F17001FFF7C6FF0A4802F18C01FFF751 -:10389000C1FFBDE8084000F065B800BF001002405D -:1038A000E04200080004004800080048000C0048FE -:1038B000001000480014004808B500F08FF9FFF729 -:1038C00073FCBDE80840FFF72FBF00007047000001 -:1038D00010B5214CA26A62F4FC02A262A26A02F450 -:1038E000FC02A2624FF0FF31A26A226921612269C3 -:1038F000002222612069E068E160E168E260E1683D -:10390000E169164841F08051E161E169016841F4E3 -:1039100080710160216A01F44071B1F5407F1EBFE2 -:103920004FF4803323622262236A1B0407D4236A84 -:1039300043F440732362236A43F40043236200F09C -:103940002DF9A369064A43F00103A361A369136833 -:1039500043F02003136010BD0010024000700040CF -:10396000000001401C4B1A6842F001021A601A68FC -:103970009007FCD55A6822F003025A605A6812F088 -:103980000C02FBD1196801F0F90119605A601A683C -:1039900042F480321A601A689103FCD50F4A5A60CB -:1039A0004FF40452DA6230221A631A6842F08072CD -:1039B0001A601A689201FCD5094A122111605A68EE -:1039C00042F002025A605A6802F00C02082AFAD148 -:1039D0001A6B1A63704700BF0010024000241D00DC -:1039E00000200240084A08B5536911680B4003F0F3 -:1039F0000103536123B1054A13680BB1506898471E -:103A0000BDE80840FFF7BABE000401400C230020C7 -:103A1000084A08B5536911680B4003F0020353616B -:103A200023B1054A93680BB1D0689847BDE80840B8 -:103A3000FFF7A4BE000401400C230020084A08B58B -:103A4000536911680B4003F00403536123B1054A25 -:103A500013690BB150699847BDE80840FFF78EBE67 -:103A6000000401400C230020084A08B5536911687E -:103A70000B4003F00803536123B1054A93690BB16E -:103A8000D0699847BDE80840FFF778BE00040140C0 -:103A90000C230020084A08B5536911680B4003F055 -:103AA0001003536123B1054A136A0BB1506A98475A -:103AB000BDE80840FFF762BE000401400C2300206F -:103AC000174B10B55C691A68144004F478725A6197 -:103AD000A30604D5134A936A0BB1D06A98476006CF -:103AE00004D5104A136B0BB1506B9847210604D5CF -:103AF0000C4A936B0BB1D06B9847E20504D5094A89 -:103B0000136C0BB1506C9847A30504D5054A936C10 -:103B10000BB1D06C9847BDE81040FFF72FBE00BF37 -:103B2000000401400C2300201A4B10B55C691A6890 -:103B3000144004F47C425A61620504D5164A136DA0 -:103B40000BB1506D9847230504D5134A936D0BB103 -:103B5000D06D9847E00404D50F4A136E0BB1506E38 -:103B60009847A10404D50C4A936E0BB1D06E9847C8 -:103B7000620404D5084A136F0BB1506F98472304B1 -:103B800004D5054A936F0BB1D06F9847BDE810403C -:103B9000FFF7F4BD000401400C230020062108B506 -:103BA0000846FEF7FFFF06210720FEF7FBFF062170 -:103BB0000820FEF7F7FF06210920FEF7F3FF062194 -:103BC0000A20FEF7EFFF06211720FEF7EBFF062184 -:103BD0002820BDE80840FEF7E5BF000008B5FFF764 -:103BE00077FEFEF7CFFEFEF7FBFFFFF7FDF9FFF7CD -:103BF0006DFEBDE8084000F001B8000000F00EB80E -:103C000008B5202383F31188FFF70CFB002383F30F -:103C10001188BDE80840FFF7B1BD0000054B064A1A -:103C20005A6000229A6007221A6008210B20FEF7D2 -:103C3000CFBF00BF10E000E03F1901001FB51C46D8 -:103C4000094B1B680546D86852B1084B02928DE8B3 -:103C50000A0022462B460649FDF718FC00F042F800 -:103C6000044B1A46F2E700BF1011002088430008F9 -:103C700095430008143E000810B5013902449042F3 -:103C800001D1002010BD10F8013B11F8014FA342F3 -:103C9000F5D0181B10BD00002DE9F84307468846F3 -:103CA00091461E468BB10D46A8EB0500B54207EBC9 -:103CB000000402D20020BDE8F8833246494620467F -:103CC000FFF7DAFF18B1013DEEE7BDE8F8832046C3 -:103CD000BDE8F883034611F8012B03F8012B002AF5 -:103CE000F9D1704708B5062000F02CF80120FFF745 -:103CF00087FB00001F2938B504460D4604D916235A -:103D000003604FF0FF3038BD426C12B152F82130E1 -:103D10004BB9204600F030F82A4601462046BDE85F -:103D2000384000F017B8012B0AD0591C03D11623D4 -:103D30000360012038BD002442F8254028469847FA -:103D4000002038BD024B01461868FFF7D3BF00BF03 -:103D50001011002038B5074C0023054608461146CF -:103D60002360FFF751FB431C02D1236803B12B6092 -:103D700038BD00BF8C260020FFF740BB40A2E4F115 -:103D8000646891064E6F20617070207369670A0045 -:103D9000426164206677206C656E677468202575C3 -:103DA0000A0042616420626F6172645F6964202569 -:103DB000752073686F756C642062652025750A0034 -:103DC0004261642066772064657363726970746F02 -:103DD00072206C656E6774682025750A0042616404 -:103DE0002061707020435243203078253038783A73 -:103DF000307825303878203078253038783A307867 -:103E0000253038780A00476F6F64206669726D77D5 -:103E10006172650A00000000726563656976656419 -:103E20005F756E697175655F69645F6C656E203C76 -:103E30002055415643414E5F50524F544F434F4CD3 -:103E40005F44594E414D49435F4E4F44455F49449D -:103E50005F414C4C4F434154494F4E5F554E495181 -:103E600055455F49445F4D41585F4C454E47544866 -:103E7000002E2E2F2E2E2F546F6F6C732F41505FFC -:103E8000426F6F746C6F616465722F63616E2E6335 -:103E9000707000616C6C6F63617465645F6E6F64F9 -:103EA000655F6964203C3D2031323700696F2E6DBB -:103EB000726F626F746963732E6D31303037305FAB -:103EC0006C6F63315F424C00766F69642068616E8D -:103ED000646C655F616C6C6F636174696F6E5F7257 -:103EE0006573706F6E73652843616E617264496EAD -:103EF0007374616E63652A2C2043616E6172645233 -:103F0000785472616E736665722A290063616E610E -:103F10007264496E6974000063616E617264536516 -:103F2000744C6F63616C4E6F64654944000000001F -:103F300063616E61726448616E646C65527846724A -:103F4000616D650063616E6172644465636F646591 -:103F50005363616C6172000063616E617264456EEF -:103F6000636F64655363616C61720000696E6372B4 -:103F7000656D656E745472616E7366657249440056 -:103F8000656E717565756554784672616D6573000F -:103F900070757368547851756575650070726570D9 -:103FA000617265466F724E6578745472616E7366A5 -:103FB00065720000636F7079426974417272617951 -:103FC000000000006465736361747465725472610B -:103FD0006E736665725061796C6F616400000000F9 -:103FE00066726565426C6F636B0000006269745FA6 -:103FF0006C656E677468203E20300072656D616983 -:104000006E696E675F62697473203E203000696E6E -:104010007075745F6269745F6F6666736574203E65 -:104020003D20626C6F636B5F6269745F6F6666737D -:10403000657400626C6F636B5F656E645F62697468 -:104040005F6F6666736574203E20626C6F636B5FA2 -:104050006269745F6F66667365740072656D61692D -:104060006E696E675F6269745F6C656E6774682005 -:104070003C3D2072656D61696E696E675F6269744F -:104080007300696E7075745F6269745F6F666673E2 -:104090006574203C3D207472616E736665722D3EBE -:1040A0007061796C6F61645F6C656E202A203800E6 -:1040B0006F75747075745F6269745F6F666673653F -:1040C00074203C3D2036340072656D61696E696E06 -:1040D000675F6269745F6C656E677468203D3D2040 -:1040E000300028726573756C74203E2030292026BC -:1040F000262028726573756C74203C3D2036342967 -:104100002026262028726573756C74203C3D206241 -:1041100069745F6C656E6774682900006465737408 -:10412000696E6174696F6E20213D202828766F6961 -:1041300064202A2930290076616C756520213D2094 -:104140002828766F6964202A293029006F666673F3 -:1041500065745F77697468696E5F626C6F636B200A -:104160003C2028333255202D205F5F6275696C74C6 -:10417000696E5F6F66667365746F66202843616E53 -:10418000617264427566666572426C6F636B2C2067 -:1041900064617461292900006F75745F696E732012 -:1041A000213D202828766F6964202A2930290000C3 -:1041B0007372635F6C656E203E2030550000000016 -:1041C0002863616E5F696420262030783146464658 -:1041D000464646465529203D3D2063616E5F696431 -:1041E00000000000616C6C6F6361746F722D3E7330 -:1041F0007461746973746963732E63757272656E2A -:10420000745F75736167655F626C6F636B73203E8B -:10421000203000007472616E736665725F6964209D -:10422000213D202828766F6964202A293029000042 -:1042300073746174652D3E6275666665725F626C4B -:104240006F636B73203D3D202828766F6964202AB8 -:10425000293029002E2E2F2E2E2F6D6F64756C6540 -:10426000732F6C696263616E6172642F63616E614A -:1042700072642E63006974656D2D3E6672616D65B2 -:104280002E646174615F6C656E203E20300000001A -:1042900000000000B12F00089D2F0008D92F000852 -:1042A000C52F0008D12F0008BD2F0008A92F000836 -:1042B000952F0008E52F00086D61696E0000000071 -:1042C000D8420008282500206026002001000000B8 -:1042D000A53100080000000069646C650000000062 -:1042E000A001A82A00000000FAAABEAA50001400EB -:1042F000EFFF000000770000709709000100000048 -:1043000000000000AAAAAAAA01000000FFFF000006 -:10431000000000000000000000000000000000009D -:10432000AAAAAAAA00000000FFFF000000000000E7 -:10433000000000000000000000000000AAAAAAAAD5 -:1043400000000000FFFF000000000000000000006F -:104350000000000000000000AAAAAAAA00000000B5 -:10436000FFFF00000000000000000000000000004F -:1043700000000000AAAAAAAA00000000FFFF000097 -:1043800000000000000000002C2066756E63746958 -:104390006F6E3A2000617373657274696F6E2022CC -:1043A000257322206661696C65643A2066696C65D4 -:1043B00020222573222C206C696E652025642573CC -:1043C00025730A003CBEFF7F0100000000000000D2 -:1043D0006400000000000000FE2A0100D20400007A -:1043E0001411002000000000000000000000000088 -:1043F00000000000000000000000000000000000BD -:1044000000000000000000000000000000000000AC -:10441000000000000000000000000000000000009C -:10442000000000000000000000000000000000008C -:10443000000000000000000000000000000000007C -:044440000000000078 +:1000000000090020A5040008E1140008611400089C +:10001000B9140008611400088D140008A704000832 +:10002000A7040008A7040008A704000881350008F9 +:10003000A7040008A7040008A7040008B93A0008AC +:10004000A7040008A7040008A7040008A7040008E4 +:10005000A7040008A7040008513800087D380008EC +:10006000A9380008D538000801390008A70400089D +:10007000A7040008A7040008A7040008A7040008B4 +:10008000A7040008A7040008A70400082924000802 +:1000900095240008E92400083D2500082D390008B2 +:1000A000A7040008A7040008A7040008A704000884 +:1000B000A7040008A7040008A7040008A704000874 +:1000C000A7040008A7040008A7040008A704000864 +:1000D000A70400088129000895290008A704000842 +:1000E00095390008A7040008A7040008A704000821 +:1000F000A7040008A7040008A7040008A704000834 +:10010000A7040008A7040008A7040008A704000823 +:10011000A7040008A7040008A7040008A704000813 +:10012000A7040008A7040008A7040008A704000803 +:10013000A7040008A7040008A7040008A7040008F3 +:10014000A7040008A7040008A7040008A7040008E3 +:10015000A7040008A7040008A7040008A7040008D3 +:10016000A7040008A7040008A7040008A7040008C3 +:10017000A7040008A7040008A7040008A7040008B3 +:10018000A7040008A7040008A7040008A7040008A3 +:10019000A7040008A7040008A7040008A704000893 +:1001A00053B94AB9002908BF00281CBF4FF0FF31DE +:1001B0004FF0FF3000F074B9ADF1080C6DE904CEDA +:1001C00000F006F8DDF804E0DDE9022304B0704732 +:1001D0002DE9F047089D04468E46002B4DD18A42FA +:1001E000944669D9B2FA82F252B101FA02F3C2F12D +:1001F000200120FA01F10CFA02FC41EA030E9440BE +:100200004FEA1C48210CBEFBF8F61FFA8CF708FBDE +:1002100016E341EA034306FB07F199420AD91CEBB6 +:10022000030306F1FF3080F01F81994240F21C81E8 +:10023000023E63445B1AA4B2B3FBF8F008FB103330 +:1002400044EA034400FB07F7A7420AD91CEB040465 +:1002500000F1FF3380F00A81A74240F20781644435 +:10026000023840EA0640E41B00261DB1D4400023BA +:10027000C5E900433146BDE8F0878B4209D9002D1E +:1002800000F0EF800026C5E9000130463146BDE8A8 +:10029000F087B3FA83F6002E4AD18B4202D3824212 +:1002A00000F2F980841A61EB030301209E46002DC1 +:1002B000E0D0C5E9004EDDE702B9FFDEB2FA82F216 +:1002C000002A40F09280A1EB0C014FEA1C471FFA74 +:1002D0008CFE0126200CB1FBF7F307FB131140EA5B +:1002E00001410EFB03F0884208D91CEB010103F128 +:1002F000FF3802D2884200F2CB804346091AA4B2EA +:10030000B1FBF7F007FB101144EA01440EFB00FEBD +:10031000A64508D91CEB040400F1FF3102D2A64522 +:1003200000F2BB800846A4EB0E0440EA03409CE7C1 +:10033000C6F12007B34022FA07FC4CEA030C20FA6E +:1003400007F401FA06F31C43F9404FEA1C4900FA8E +:1003500006F3B1FBF9F8200C1FFA8CFE09FB18110B +:1003600040EA014108FB0EF0884202FA06F20BD97E +:100370001CEB010108F1FF3A80F08880884240F2CE +:100380008580A8F102086144091AA4B2B1FBF9F012 +:1003900009FB101144EA014100FB0EFE8E4508D90D +:1003A0001CEB010100F1FF346CD28E456AD9023892 +:1003B000614440EA0840A0FB0294A1EB0E01A14277 +:1003C000C846A64656D353D05DB1B3EB080261EBE5 +:1003D0000E0101FA07F722FA06F3F1401F43C5E9BF +:1003E000007100263146BDE8F087C2F12003D840F5 +:1003F0000CFA02FC21FA03F3914001434FEA1C4737 +:100400001FFA8CFEB3FBF7F007FB10360B0C43EA28 +:10041000064300FB0EF69E4204FA02F408D91CEBD8 +:10042000030300F1FF382FD29E422DD902386344D6 +:100430009B1B89B2B3FBF7F607FB163341EA034176 +:1004400006FB0EF38B4208D91CEB010106F1FF38C5 +:1004500016D28B4214D9023E6144C91A46EA0046BC +:1004600038E72E46284605E70646E3E61846F8E64E +:100470004B45A9D2B9EB020864EB0C0E0138A3E797 +:100480004646EAE7204694E74046D1E7D0467BE778 +:10049000023B614432E7304609E76444023842E7F0 +:1004A000704700BF02E000F000F8FEE772B63A487D +:1004B00080F30888394880F3098839484EF6085196 +:1004C000CEF20001086040F20000CCF200004EF6CF +:1004D0003471CEF200010860BFF34F8FBFF36F8F0E +:1004E00040F20000C0F2F0004EF68851CEF200015A +:1004F0000860BFF34F8FBFF36F8F4FF00000E1EE46 +:10050000100A4EF63C71CEF200010860062080F31E +:100510001488BFF36F8F03F0B3F803F08FF803F084 +:10052000C1F84FF055301F491B4A91423CBF41F87A +:10053000040BFAE71C49194A91423CBF41F8040BED +:10054000FAE71A491A4A1B4B9A423EBF51F8040B6C +:1005500042F8040BF8E700201749184A91423CBFC3 +:1005600041F8040BFAE703F06DF803F0D7F8144CE8 +:10057000144DAC4203DA54F8041B8847F9E700F045 +:1005800041F8114C114DAC4203DA54F8041B884772 +:10059000F9E703F055B80000000900200011002021 +:1005A000000000080001002000090020F83C0008BD +:1005B00000110020201100202011002028260020FA +:1005C000A0010008A0010008A0010008A001000887 +:1005D0002DE9F04F2DED108AC1F80CD0C3689D466F +:1005E000BDEC108ABDE8F08F002383F31188284604 +:1005F000A047002002F04CFDFEE702F0D1FC00DF36 +:10060000FEE700002DE9F04102F062FF074602F02C +:10061000ADFF054600283ED12B4B9F423BD0013316 +:100620009F423BD0294B27F0FF029A423AD1F8B2C1 +:1006300000F054FAA84642F2107400F059FC08B1D8 +:100640000024A04600F050FA064678B384BB464624 +:1006500035B11F4B9F4203D002F080FF0024264695 +:10066000002002F03FFF1B4B1B6913F0400322D018 +:100670000EB100F031F800F05FFC00F031FE00F048 +:1006800031FF0546CCB100F02DFF401BA04214D92C +:1006900000F022F8F3E7A8460024CEE704464FF026 +:1006A0000108CAE780464FF47A74C6E70446CFE7EC +:1006B0004FF47A74CCE71C46DDE700F0DDFC012046 +:1006C00002F0ECFCDEE700BF010007B0000008B05C +:1006D000263A09B00004004838B51D4A1D4B196878 +:1006E000013134D004339342F9D11B4C194DD4F865 +:1006F0000428AA422BD3194B9B6803F1006303F52E +:10070000D0439A4223D202F0FDFE02F00FFF0020F8 +:1007100000F000FE124B0220187000F037FE114B63 +:10072000DA690022DA61D96999699A619B6972B6BE +:100730004FF0E0232021C3F8085DD4F80038D4F846 +:10074000042881F311889D4683F30888104738BD3B +:100750002068000800680008006000080011002000 +:100760002011002000100240094A136849F2690074 +:1007700099B21B0C00FB01331360064B186844F25E +:10078000506182B2000C01FB0200186080B2704719 +:100790001C1100201811002010B500211022044661 +:1007A00000F00EFE034B03CB206061601868A06070 +:1007B00010BD00BFACF7FF1F2DE9F043224DBBB0C9 +:1007C00000F090FEAB6840F2ED22C31A934232D99A +:1007D00006AFA8602B4628220021384601F05EFBB8 +:1007E00005F10E0000F0E4FD002604465FFA80F9F2 +:1007F00005F10E08F3B2F100994501F1280107D97E +:1008000008EB06030822384601F048FB0136F1E701 +:1008100008230122CDE9023205340C4B0193A4B226 +:1008200030230093CDE9047405A3D3E90023297B89 +:10083000074801F04BF93BB0BDE8F083AFF300800F +:1008400078F6339F93CACD8D682100207521002052 +:100850003C21002070B50D4614461E4601F0CCF830 +:1008600050B9022E10D1012C0ED112A3D3E90023CE +:10087000C5E90023012007E0282C10D005D8012C61 +:1008800009D0052C0FD0002070BD302CFBD10BA35C +:10089000D3E90023ECE70BA3D3E90023E8E70BA39C +:1008A000D3E90023E4E70BA3D3E90023E0E700BF8B +:1008B000AFF30080401DA12026812A0B78F6339FDC +:1008C00093CACD8D9E6AC421818A46EE26417272FA +:1008D000DF25D7B7F017304A39059E5613B50446C1 +:1008E0002346084620220021019001F0D7FA227900 +:1008F0000198032A234628BF032203F8042F20214E +:10090000022201F0CBFA62790198072A234628BF18 +:10091000072203F8052F2221032201F0BFFAA27952 +:100920000198072A234628BF072203F8062F25210E +:10093000032201F0B3FA019804F1080310222821E0 +:1009400001F0ACFA382002B010BD00002DE9F04FE4 +:10095000ADF5017D21AD0EAE40F2751280460F4619 +:1009600022A80021296000F02BFD482200213046FA +:1009700000F026FD00F0B6FD564B4FF47A72B0FB46 +:10098000F2F0186093E80700012386E807000DF1F4 +:100990005A003382FFF700FF4EF60343338407AB60 +:1009A00018464D4903F0C2F81B22306429463046F0 +:1009B00086F83C20FFF792FF12AB0446014608225E +:1009C000284601F06BFA0822A1180DF149032846C8 +:1009D00001F064FA0DF14A03082204F110012846DF +:1009E00001F05CFA13AB202204F11801284601F053 +:1009F00055FA14AB402204F13801284601F04EFAB2 +:100A000016AB082204F17801284601F047FA0DF1EF +:100A10005903082204F18001284601F03FFA04F14D +:100A2000880A0DF15A0904F5847B4B465146082289 +:100A300028460AF1080A01F031FAD34509F1010903 +:100A4000F3D11BAB08225946284601F027FA04F5DA +:100A500088744FF0000996F834304B450AD9B36BCF +:100A600021464B440822284601F018FA083409F1BF +:100A70000109F0E74FF0000996F83C304B4504EBD4 +:100A8000C90108D9336C08224B44284601F006FA04 +:100A900009F10109F0E700230393BB7E02930731BC +:100AA00007F119030193C1F3CF010123CDE90451EB +:100AB0000093F97E05A3D3E90023404601F006F830 +:100AC0000DF5017DBDE8F08FAFF300809E6AC42173 +:100AD000818A46EE241100203C3B0008014B18702F +:100AE000704700BF30110020F0B5334B1C7B85B040 +:100AF00034B1324B0E221A810024204605B0F0BDDD +:100B00002F4A1068516802AB03C308232D492E48B1 +:100B10000DEB030202F0E8FF054630B9274B2B48E6 +:100B20000A221A8100F098FCE6E70169B1F5663FF8 +:100B300006D9224B26480B221A8100F08DFCDCE7F7 +:100B4000438BB3F57B7F09D01C4A22480C211181CD +:100B50004FF47B72194600F07FFCCEE71E4A024438 +:100B600002F11003994204D2144B1C4810221A813E +:100B7000E3E710398E1A2046134900F0B7FC3246DD +:100B8000074605F11801204600F0B0FCAB689F4213 +:100B900002D1EB6898420AD0084B0D221A810090CE +:100BA000D5E902123B460E4800F056FCA4E70D487A +:100BB00000F052FC0124A0E768210020241100204D +:100BC000E93B0008DC97030000680008583B000878 +:100BD000643B0008763B00080898FFF7943B000848 +:100BE000B13B0008DA3B00082DE9F04FADB006AF8D +:100BF00080460C4600F000FF054600285AD1237EAF +:100C0000022B1BD1E38A012B18D100F06BFC0646A6 +:100C1000FFF7AAFD03464FF4C870DFF8D092B3FB8C +:100C2000F0F206F5167602FB103316FA83F3C9F8D4 +:100C30000030E37E33B9A84B00221A709C37BD46C2 +:100C4000BDE8F08FA38AEEB2013BB34205F1010586 +:100C50000BD93B1D1E44E90000960023082201F039 +:100C6000F801204600F0DEFFECE707F11400FFF783 +:100C700093FD324607F11401381D02F025FF0028CC +:100C8000D9D10F2E08D8944B1E70D9F80030A3F597 +:100C90001673C9F80030D1E7FB1CF87001460093C9 +:100CA00007220346204600F0BDFFF978404600F0D9 +:100CB0009BFEC3E7E38A282B26D010D8012B1ED039 +:100CC000052BBBD1BFF34F8F8449854BCA6802F413 +:100CD000E0621343CB60BFF34F8F00BFFDE7302BC3 +:100CE000ACD1637E7F4D01336A7BDBB29342E94630 +:100CF00003D1E27E2B7B9A4265D0CD469EE721460A +:100D00004046FFF723FE99E7A38A013B9BB2C92B1C +:100D100094D8744D2E7B26BB05F10C03009308225A +:100D200033463146204600F07DFF731CF2B2D900F5 +:100D30001E46A38A013B9A4205DA0E322A440092EB +:100D400000230822EEE700230022C5E90023002348 +:100D5000AB6085F8D730C5F8D8302B7B0BB9E37E74 +:100D60002B73002507F114093B1D0822294648462C +:100D7000C7E90155FD6001F091F83B7A05F1010AE0 +:100D8000AB424FEACA0608D9FB6808222B44314619 +:100D9000484601F083F85546EFE7C6F3CF06E17EFB +:100DA000CDE9049600230393A37E029319342823EC +:100DB0000093019446A3D3E90023404600F086FE49 +:100DC000FFF7FAFC3AE74FF0000807F11403A7F821 +:100DD00014801022009341460123204600F022FF98 +:100DE000A68A023EB6B2F31C9B109B000733DB08B9 +:100DF000A9EBC3039D460DF1180A1FFA88F34FEAC9 +:100E0000C801B34201F110010AD20AEB08030093B2 +:100E100008220023204600F005FF08F10108ECE756 +:100E200095F8D70000F080FAD5F8D83004461BB901 +:100E300095F8D70000F088FAD5F8D83033449C42B2 +:100E400004D295F8D700013000F07EFA4FEA960BF5 +:100E50004FF000081FFA88F18B45D5E9003209D917 +:100E60000AEB880103EB8800012200F0B1FA08F1D7 +:100E70000108EFE7F31842F10002C5E90032D5F8A6 +:100E8000D83095F8D70006EB0308C5F8D88000F0F5 +:100E90004BFA804509D395F8D730D5F8D8000133FF +:100EA000001B85F8D730C5F8D800FF2E08D80023DE +:100EB0002B7300F05BFAFFF717FE08B1FFF70CFC8D +:100EC0002B68094A9B0A013313810023AB6014E7A6 +:100ED00026417272DF25D7B73521002000ED00E0F2 +:100EE0000400FA0568210020241100203821002088 +:100EF00010B54FF000540C4B22689A4211D10B4BA5 +:100F0000627D1A700A48237D03730A49C9220E3094 +:100F100000F044FAE0220021204600F051FA0120BE +:100F200010BD0020FCE700BF9AAD44C53011002081 +:100F300068210020160000202DE9FF41434C0223C8 +:100F400063710023029324250A23581EB5FBF3F690 +:100F50007343D3F12402C1B23ED002280346F4D138 +:100F60009DF80B303A493B485A1E9DF80A30013B28 +:100F70001B0443EA0253BDF80820013A13434B60B7 +:100F800001F044FD00230193334B3449009334486E +:100F9000344B4FF4805200F001FD334B197811B1FE +:100FA0002F4800F021FD00F09DFA0546FFF7DCFB1D +:100FB0004FF4C873B0FBF3F202FB130305F5167090 +:100FC00010FA83F0294B186002F0D0FA08B10F2311 +:100FD000238104B0BDE8F081C1EBC107FB1C4FEADF +:100FE000E30EC3F3C703A1EB030C0EF101084FF4AA +:100FF0007A705FFA8CF50EFB000058FA8CFCB0FB9F +:10100000FCF0B0F5617F07D97B1EC3F3C703C91A93 +:10101000CDB2591E0F2916D86A1E072A8CBF00228E +:101020000122591901FB06601149B1FBF0F1114889 +:10103000814295D1002A93D0ADF808608DF80A302E +:101040008DF80B508CE71346EBE700BF241100200E +:1010500010110020802200205508000834110020C3 +:101060003C210020E90B000830110020382100202D +:101070000051250240420F002DE9F04F90A7D7E91B +:1010800000670FF24429D9E90089874D93B0DFF852 +:1010900040B2864C284600F07DFD0DF1300A0790E5 +:1010A00070B310220021504600F08AF9079B197B8B +:1010B0004FF0000261F303028DF830205868996800 +:1010C0000EAA03C21B680D9A63F31C029DF8303010 +:1010D0000D9243F020038DF830300023524619461C +:1010E000584601F0A3FC079028B9284600F056FDA9 +:1010F000079B2370CEE72378072B3CD8013323705E +:1011000018220021504600F05BF9DFF8C4B100233B +:1011100019465246584601F0B1FC014678BB1022F0 +:1011200008A800F04DF94FF0904209AC536983F0E4 +:101130001003536100F0D8F90B4612A9024611E9D9 +:10114000030084E803009DF83410C1F3030089060E +:101150004CBF0E9CBDF838408DF82C0046BFC4F340 +:101160001C0444F00044C4F30A0408A92846089467 +:1011700000F0DCFECBE7284600F010FDC0E7284673 +:1011800000F03AFC0446002848D1DFF848B100F0EE +:10119000A9F9DBF80030984240D300F0A3F907909A +:1011A000FFF7E2FA079A8DF8204003464FF4C87023 +:1011B00002F51672B3FBF0F101FB103312FA83F360 +:1011C000CBF80030DFF810B19BF8001011B9012303 +:1011D0008DF8203050460791FFF7DEFA0799C1F1EC +:1011E0001004E4B2062C28BF0624224651440DF117 +:1011F000210000F0D3F808AB0393182302930134C5 +:101200002B4B0193E4B20123009304943B463246F6 +:10121000284600F0F3FB00238BF8003000F062F961 +:10122000244A254C1368C31AB3F57A7F31D3106072 +:1012300000F05AF902460B46284600F0B9FC284651 +:1012400000F0DAFB28B3237BDFF890B0002B14BF4B +:10125000032302238BF8053000F044F94FF47A732E +:101260005146B0FBF3F0CBF800005846FFF736FBD1 +:10127000182307300293114B0193C0F3CF0040F2C3 +:101280005513CDE903A0009342464B46284600F093 +:10129000B5FB237B2BB1FFF78FFA237B002B7FF469 +:1012A000F6AE13B0BDE8F08F3C2100204D220020A7 +:1012B0003421002048220020682100204C220020F8 +:1012C000401DA12026812A0BF1C6A7C1D068080FB6 +:1012D0008022002038210020352100202411002008 +:1012E00070B501F0B5FF094E094D30800024286823 +:1012F0003388834208D901F0A7FF2B6804440133E7 +:10130000B4F5D04F2B60F2D370BD00BF7C2200201B +:101310005022002002F03AB800F10060920000F57F +:10132000D04001F0D5BF0000054B1A68054B1B8863 +:101330009B1A834202D9104401F086BF00207047F7 +:10134000502200207C22002038B5074D0446286832 +:10135000204401F07FFF28B928682044BDE83840C8 +:1013600001F08ABF38BD00BF50220020064991F825 +:10137000243033B10023086A81F824300822FFF7B3 +:10138000CBBF0120704700BF54220020022802BFBB +:101390004FF090434FF480129A61704710B50023CC +:1013A000934203D0CC5CC4540133F9E710BD000074 +:1013B00003460246D01A12F9011B0029FAD17047E0 +:1013C00002440346934202D003F8011BFAE7704738 +:1013D0002DE9F8431F4D144695F82420074688460A +:1013E00052BBDFF870909CB395F824302BB92022C3 +:1013F000FF2148462F62FFF7E3FF95F82400C0F174 +:101400000802A24228BF2246D6B24146920005EB0E +:101410008000FFF7C3FF95F82430A41B1E44F6B2EA +:10142000082E17449044E4B285F82460DBD1FFF71E +:101430009DFF0028D7D108E02B6A03EB820383428B +:10144000CFD0FFF793FF0028CBD10020BDE8F88371 +:101450000120FBE7542200200FB4002004B07047A5 +:1014600000B59BB0EFF3098168226846FFF796FF4D +:10147000EFF30583044B9A6BDA6A9A6A9A6A9A6A5E +:101480009A6A9A6A9B6AFEE700ED00E000B59BB09D +:10149000EFF3098168226846FFF780FFEFF30583C9 +:1014A000044B9A6B9A6A9A6A9A6A9A6A9A6A9B6ACF +:1014B000FEE700BF00ED00E000B59BB0EFF309814F +:1014C00068226846FFF76AFFEFF30583034B5A6B08 +:1014D0009A6A9A6A9A6A9A6A9B6AFEE700ED00E045 +:1014E000FEE7000001F08EBF01F064BF30B5094D8A +:1014F0000A4491420DD011F8013B5840082340F3B3 +:101500000004013B2C4013F0FF0384EA5000F6D1A5 +:10151000EFE730BD2083B8ED2DE9F041C56915B97D +:10152000C161BDE8F0814B6823F06047C3F38A4690 +:101530004FEAD37EC3F3807816EA230638BF3E46CF +:10154000AC462B465A68BEEBD27F22F060440AD0EC +:10155000002A18DAA40CB44217D19D420FD10D60B5 +:10156000DEE71346EEE7A74207D102F08044C2F35C +:10157000807242450BD054B1EFE708D2EDE7CCF8CA +:1015800000100B60CDE7B44201D0B442E5D81A6830 +:101590009C46002AE5D11960C3E700002DE9F04719 +:1015A000089D01F007044FEAD508224405F007051D +:1015B00000EBD1004FF47F49944201D1BDE8F087A0 +:1015C00004F0070705F0070A57453E4638BF564660 +:1015D000C6F10806111B8E4228BF0E46E10808EB33 +:1015E000D50E415C13F80EC0B94029FA06F721FA6E +:1015F0000AF1FFB28CEA010147FA0AF739408CEA96 +:10160000010C03F80EC034443544D5E780EA0120CC +:10161000082341F2210201B24000002980B203F107 +:10162000FF33B8BF504013F0FF03F4D17047000000 +:1016300038B50C468D18A54200D138BD14F8011BF1 +:10164000FFF7E4FFF7E7000002684AB113680360A0 +:10165000C388018901339BB29942C38038BF03819B +:101660001046704770B588B0202204460D46684683 +:101670000021FFF7A5FE20460495FFF7E5FF02468F +:1016800058B16B46054608AE1C4603CCB4422860F0 +:101690006960234605F10805F6D1104608B070BD13 +:1016A000082817D909280CD00A280CD00B280CD0F0 +:1016B0000C280CD00D280CD00E2814BF4020302050 +:1016C00070470C2070471020704714207047182076 +:1016D0007047202070470000082817D90C280CD923 +:1016E00010280CD914280CD918280CD920280CD96A +:1016F00030288CBF0F200E207047092070470A2029 +:1017000070470B2070470C2070470D207047000079 +:1017100010B54B6823B9CA8A63F30902CA8210BDA7 +:10172000C4681A681C60C360438A013B43824A60F4 +:10173000EFE700002DE9F84F1D46CB8A0F46C3F3B3 +:1017400009010629814692460B4630D00020AAB2F4 +:1017500007F119049EB2052E1FFA80F80FD89045A4 +:1017600003F1010306D3FB8A0A4462F30903FB82F7 +:1017700001201AE01AF80060E6540130EAE79045CB +:10178000F1D2A1F1060B1C237C68BBFBF3F203FB37 +:1017900012BB1FFA8BF6002C45D14846FFF754FFC9 +:1017A000044638B978606FF00200BDE8F88F4FF05A +:1017B0000008E6E7002606607860ADB24FF0000B47 +:1017C000454510D90AEB0803221D13F8011B91555A +:1017D000B1B208F101081B291FFA88F82BD0454542 +:1017E00006F10106F1D8FB8AC3F30902154465F33B +:1017F0000903BCE7013292B21C462368002BF9D1E1 +:10180000AB1F0B441C21B3FBF1F301339BB29A4293 +:10181000D3D2BBF1000FD0D14846FFF715FF20B956 +:10182000C4F800B0BFE70122E7E7C0F800B05E46A9 +:1018300020600446C1E74545D5D94846FFF704FF77 +:1018400008B92060AFE7C0F800B000262060044669 +:10185000B6E700002DE9F04F2DED028B83B0CDE906 +:101860000013BDF83C5007469146002A00F09280D4 +:101870002DB10E9B002B00F08D80072D32D807F183 +:101880000C00FFF7E1FE044638B96FF00204204671 +:1018900003B0BDEC028BBDE8F08F14220021FFF7EE +:1018A0008FFD0E992A4604F10800FFF777FD681CAA +:1018B000C0B2FFF711FFFFF7F3FE207499F8003074 +:1018C000013814FA80F003F01F0363F03F03037242 +:1018D000009B43F00041616038462146FFF71CFE43 +:1018E0000124D4E700F10C034FF0000808EE103A91 +:1018F0004FF0800A4646444618EE100AFFF7A4FE51 +:1019000083460028C1D014220021FFF759FDC6BB31 +:10191000019BABF8083002200E9B00F108029919D8 +:101920005BFA82F20130C0B2082801D0AE422AD35D +:10193000FFF7D2FEFFF7B4FE99F80020009B411E8E +:1019400002F01F0242EA4812AE4208BF4FF0400ABE +:101950005BFA81F14AEA020A43F0004281F808A0EA +:101960008BF81000CBF8042059463846FFF7D4FD19 +:101970000134AE4224B288F001084FF0000ABBD116 +:1019800085E70020C8E711F801CB02F801CB01364A +:10199000B6B2C7E76FF0010479E70000F8B5154665 +:1019A0000E462822002104461F46FFF709FD069B2C +:1019B0006360B5F5001F079BA76034BF6A094FF647 +:1019C000FF72236204F10C0097B200239A4205D8FB +:1019D0000023036027826382A382F8BD066001337F +:1019E00030462036F2E7000003781BB94BB2002BDB +:1019F000C8BF017070470000007870472DE9F74FAD +:101A0000DDF83C90BDF830500D9E9DF83840BDF893 +:101A10004070804692469B46B9F1000F01D1002FDD +:101A200051D11F2C4FD898F80000B0B9072F47D8D4 +:101A300035F0030347D13A4649464FF6FF70FFF7AA +:101A4000F7FD20F001002D02400445EA0464400C3B +:101A500044EA40244FF6FF7321E040EA0520072FB7 +:101A600040EA0464F6D900254FF6FF73C5F1200063 +:101A7000A5F120022AFA05F10BFA00F001432BFA36 +:101A800002F211431846C9B2FFF7C0FD0835402DD8 +:101A90000346EBD13A464946FFF7CAFD0346CDE976 +:101AA0000097324621464046FFF7D4FE3378013393 +:101AB000DBB21F2B88BF0023337003B0BDE8F08F6B +:101AC0006FF00300F9E76FF00100F6E72DE9F04F42 +:101AD00085B09246DDF848800F9D9DF840209DF826 +:101AE0004490BDF84C7006469B46B8F1000F01D1FA +:101AF000002F48D11F2A46D83378002B46D00C023D +:101B000044EA02649DF8381044EAC93444EA0144C6 +:101B10001C43072F44F0800432D900234FF6FF7294 +:101B2000C3F1200CA3F120002AFA03F10BFA0CFCFC +:101B300041EA0C012BFA00F00143C9B210460393AD +:101B4000FFF764FD039B0833402B0246E8D13A4679 +:101B50004146FFF76DFD0346CDE900872A46214641 +:101B60003046FFF777FEB9F1010F06D12B7801332C +:101B7000DBB21F2B88BF00232B7005B0BDE8F08FB0 +:101B80004FF6FF73E8E76FF00100F6E76FF0030030 +:101B9000F3E70000C06900B104307047C3691A68F8 +:101BA000C261C2681A60C360438A013B43827047C6 +:101BB0002DE9F041D0F81880194E14461D464146D3 +:101BC000002709B9BDE8F081D1E90223A21A65EB2B +:101BD0000303964277EB03031ED283698B420DD138 +:101BE000FFF796FD83691B688361C3680B60438AB6 +:101BF000C1608169013B43828846E2E7FFF788FDC7 +:101C00000B68C8F80030C3680B60438AC160013BB1 +:101C10004382D8F80010D4E788460968D1E700BFAE +:101C200080841E002DE9F04F8BB00D46DDF85090FA +:101C300014469B468046002800F01981B9F1000F38 +:101C400000F01581531E3F2B00F21181012A03D1B0 +:101C5000BBF1000F40F00B810023CDE90833B8F849 +:101C60001430B5EBC30F4FEAC30703D300200BB00A +:101C7000BDE8F08F2B199F42D8F80C303ABF7F1B7C +:101C8000FFB227461BB9D8F81030002B7AD02F2D81 +:101C90004ED8C5F13006B7424FF000032CBFF6B264 +:101CA0003E4600932946D8F8080008AB3246FFF7B5 +:101CB00075FCA7EB060A35445FFA8AFAB8F81430C7 +:101CC00003F10053063BDB000493D8F80C30039378 +:101CD0003021039B13B1BAF1000F2CD1D8F81000BA +:101CE00040B1BAF1000F05D0009608AB5246691A10 +:101CF000FFF754FC38B2002FB8D066070AD00AAB01 +:101D000003EBD401624211F8083C02F007021341D0 +:101D100001F8083C082C3CD9102C40F2B580202C4E +:101D200040F2B780BBF1000F00F09C80082334E044 +:101D3000BA460026C2E7049BE02B28BFE0230693A7 +:101D40000B44AB42059314D95A1B03980096924555 +:101D500034BF5246D2B2691A08AB04300792FFF77B +:101D60001DFC079A1644AAEB020A1544F6B25FFA64 +:101D70008AFA049B069A05999B1A0493039B1B6895 +:101D80000393A6E70093D8F8080008AB3A46294623 +:101D9000AEE7BBF1000F13D00123B4EBC30F6CD03F +:101DA000082C12D89DF82030621E23FA02F2D507C3 +:101DB00006D54FF0FF3202FA04F423438DF82030A9 +:101DC0009DF8203089F8003051E7102C12D8BDF86A +:101DD0002030621E23FA02F2D10706D54FF0FF32FF +:101DE00002FA04F42343ADF82030BDF82030A9F8FE +:101DF00000303CE7202C0FD80899631E21FA03F32A +:101E0000DA0705D54FF0FF3202FA04F40C430894C8 +:101E1000089BC9F800302AE7402C2BD0DDE9086583 +:101E2000611EC4F12102A4F1210326FA01F105FA91 +:101E300002F225FA03F311431943CB0712D501220D +:101E4000A4F12003C4F1200102FA03F322FA01F104 +:101E5000A240524243EA010363EB430332432B4364 +:101E6000CDE90823DDE90823C9E90023FFE66FF087 +:101E70000100FCE66FF00800F9E6082CA0D9102C50 +:101E8000B3D9202CEED8C3E7BBF1000FADD00223AD +:101E900083E7BBF1000FBBD004237EE730B5012AF6 +:101EA000144638BF0124402C85B028BF40240025AB +:101EB000012ACDE9025518D81B788DF80830630740 +:101EC0000AD004AB03EBD405624215F8083C02F0DB +:101ED0000702934005F8083C009103462246002182 +:101EE00002A8FFF75BFB05B030BD082AE4D9102A31 +:101EF00003D81B88ADF80830E1E7202A8DBFD3E96D +:101F000000231B680293CDE90223D8E710B5CB6804 +:101F10001BB98B600B618B8210BDC4681A681C6092 +:101F2000C360438A013B4382CA60F0E72DE9F04F6A +:101F3000D1F8008093B018F0800FCDE90323C8F3E7 +:101F4000C01219BFC8F3C03BC8F306264FF0020BFE +:101F50001646B8F1000F04460D4680F2D18118F004 +:101F6000C043059340F0CC810B7B002B00F0C8816F +:101F7000BBF1020F03D00178B14240F0C48108F0F8 +:101F80007F0106916AB3C8F3074A2B44069A93F877 +:101F90000390760646EA0B4646EA82465FEAD91384 +:101FA00046EA0A06079300F0908000220023CDE95C +:101FB0000A23069B009367685B4652460AA920469F +:101FC000B84700287ED0A7699FB9314604F10C00BC +:101FD000FFF748FB0746E0B96FF0020013B0BDE819 +:101FE000F08FC8F30F2A18F07F0F08BF0AF0030A1A +:101FF000CBE73B699E420DD03F68002FF9D13146B7 +:1020000004F10C00FFF72EFB07460028E4D0A3697B +:102010003B60A761DDE90A2300264FF6FF70C6F199 +:10202000200E22FA06F103FA0EFEA6F1200C23FA86 +:102030000CFC41EA0E0141EA0C01C9B208360992D2 +:102040000893FFF7E3FA402EDDE90832E7D1B882C2 +:10205000FB7D09F01F06C3F384039B1BD7E9022114 +:1020600098B2002BBCBF00F120031BB252EA010062 +:10207000C8F304680FD00398821A049860EB01013A +:10208000A74890424FF000028A4104D3079A002AE1 +:102090005BD0012B23DDFA7D4FEA890302F00302B6 +:1020A00003F07C031343FB7539462046FFF730FBF2 +:1020B000079BA3B9FB7DC3F38402013262F386035D +:1020C000FB7504E06FF00B0088E7A76917B96FF0A4 +:1020D0000C0083E73B699E42BAD03F68F6E719F0EF +:1020E000400F32D0039BBB60049BFB601422002195 +:1020F0000DA8FFF765F9039B0A93049B0B932B1D17 +:102100000C932B7BADF83EA0013BDBB2ADF83C302D +:10211000069B8DF8433094F824308DF840B083F05E +:1021200001038DF844308DF84160A3688DF842803A +:102130000AA920469847FB7DC3F38403013303F0CB +:102140001F039B02FB82002048E7FB7DC9F340127E +:10215000B2EBD31F40F0DA80C3F38403B34240F004 +:10216000D88007992B7B4FEA9912002934D0D207E7 +:1021700041D4032B40F2D080039BBB60049BFB60E7 +:102180002B7BAE1D033BDBB23246394604F10C001B +:10219000FFF7D0FA00280DDA20463946FFF7B8FAE3 +:1021A000FB7DC3F38403013303F01F039B02FB8217 +:1021B000032013E7AB883B832A7B033AB88AD2B269 +:1021C0003146FFF735FAFB7DB882DA43C2F3C0121D +:1021D00062F3C713FB75B6E76AB92E1D013BDBB28C +:1021E0003246394604F10C00FFF7A4FA0028D3DB8D +:1021F0002A7B013AE2E7F98AC1F30901013B05298B +:10220000DAB259D8281D002307F11A0C9A4208D9CE +:1022100010F801EB0CF801E0013101330629DBB2C3 +:10222000F4D103990A9104990B91934207F11A0191 +:102230000C9138BF043379680D9134BF55FA83F39C +:1022400000230E93FB8AADF83EA0C3F309031A44A2 +:10225000069B8DF8433094F82430ADF83C2083F091 +:1022600001038DF8443000238DF840B08DF84160B3 +:102270008DF842807B602A7BB88A013A291DFFF7DE +:10228000D7F93B8BB882834203D1A3680AA92046C1 +:10229000984720460AA9FFF739FEFB7DB88AC3F3A9 +:1022A0008403013303F01F039B02FB823B8B9842A4 +:1022B00014BF1120002091E67B68002BB1D00620CE +:1022C00001E01C306346D3F800C0BCF1000FF8D128 +:1022D000091A081D05F1040C00EB030905989DF887 +:1022E000143001EB000EBEF11B0F9AD89A4298D918 +:1022F0001CF8013B09F8013B059B01330593EDE711 +:102300006FF009006AE66FF00A0067E66FF00D00F3 +:1023100064E66FF00E0061E66FF00F005EE600BF4E +:1023200080841E00F0B53D4D3D4FEB6943F00073D6 +:10233000EB61EB693B4B9B6AD3F800623E4046F091 +:102340000106C3F80062D3F800423C4044EA002092 +:1023500040F00100C3F80002002951D00020C3F86A +:102360001C020646C3F80402C3F80C02C3F81402A8 +:1023700003EBC00401300E28C4F84062C4F8446284 +:10238000F6D100274FF0010C9678148816F0010F53 +:1023900018BFD3F804E20CFA04F01CBF40EA0E0E9A +:1023A000C3F804E216F0020F1EBFD3F80CE240EAB5 +:1023B0000E0EC3F80CE2760742BFD3F81462064350 +:1023C000C3F8146203EBC4045668C4F8406296680C +:1023D000C4F84462D3F81C4201372043B942C3F821 +:1023E0001C0202F10C02CFD1D3F8002222F001022C +:1023F000C3F80022EB6923F00073EB61EB69F0BDD9 +:102400000122C3F84012C3F84412C3F80412C3F8FF +:102410001412C3F80C22C3F81C22E5E70010024096 +:102420000000FFFF80220020184A916A08B58B68DF +:102430008B6013F0010104D013F00C0F18BF4FF4A0 +:102440008031D80506D513F4406F14BF41F4003134 +:1024500041F00201D80306D513F4402F14BF41F414 +:10246000802141F00401D3690BB10848984720232B +:1024700083F311880648002100F038FE002383F31F +:102480001188BDE8084001F0AFB800BF80220020ED +:102490008822002038B5124CA36ADD68AA0712D042 +:1024A0005A6922F002025A61A36913B10121204640 +:1024B0009847202383F311880A48002100F016FE74 +:1024C000002383F31188EB0606D5A36A1021D96097 +:1024D000236A0BB102489847BDE8384001F084B840 +:1024E000802200209022002038B5124CA36A1D697A +:1024F000AA0712D05A6922F010025A61A36913B1D7 +:10250000022120469847202383F311880A4800219E +:1025100000F0ECFD002383F31188EB0606D5A36AD7 +:1025200010211961236A0BB102489847BDE8384071 +:1025300001F05AB8802200209022002038B50F4CBC +:10254000A36A5D685D602A070AD5042222701A68B2 +:1025500022F002021A60636A13B1002120469847F4 +:102560006B0706D5A36A9969236A13B10348090466 +:102570009847BDE8384001F037B800BF80220020FE +:1025800010B50E4C204600F02FFA0D4BA3620B2124 +:10259000132000F009FA0B21142000F005FA0B219A +:1025A000152000F001FA0B21162000F0FDF90022A1 +:1025B000BDE8104011460E20FFF7B4BE8022002077 +:1025C000006400400F4B984210B5044605D10E4BF5 +:1025D000DA6942F00072DA61DB69A36A01221A60EB +:1025E000A36A5A68D20707D5626851681268D96130 +:1025F0001A60064A5A6110BD0121082000F06CFCE7 +:10260000EEE700BF80220020001002405B8701003F +:1026100003291AD8DFE801F0020A0F14836A9B68C5 +:1026200013F0E05F14BF012000207047836A9868B0 +:10263000C0F380607047836A9868C0F3C0607047D9 +:10264000836A9868C0F300707047002070470000EC +:1026500010B5032925D8DFE801F00225292D836A6A +:102660009968C1F30161183103EB011310788406F6 +:102670004CBF54689488C0F300114FEA410148BF31 +:1026800041EAC40100F00F004CBF41F0040141EAEF +:102690004451586041F001019068D2689860DA6056 +:1026A000196010BD836A03F5C073DFE7836A03F521 +:1026B000C873DBE7836A03F5D073D7E701290AD033 +:1026C00002290FD081B9836ADA68920701D11869AB +:1026D00003E001207047836AD86810F0030018BF38 +:1026E00001207047836AF2E70020704710B539B9BE +:1026F000836AD96889071BD11B699C0704D110BD67 +:10270000012915D00229FAD1816AD1F8C031D1F856 +:10271000C441D1F8C8011061D1F8CC01506120202A +:1027200008610869800717D1486940F0100012E07D +:10273000816AD1F8B031D1F8B441D1F8B801106153 +:10274000D1F8BC0150612020C860C868800703D15F +:10275000486940F002004861C3F34000C3F38001C0 +:10276000000140EA4111107920F03000014311715D +:1027700089064BBF91681189DB085B0D4CBF63F381 +:102780001C0163F30A01137948BF916064F30303EA +:1027900013714FEA14234FEA144458BF1181137088 +:1027A0005480ACE7026843681143016003B11847E5 +:1027B00070470000024A136843F0C003136070477B +:1027C00000380140024A136843F0C00313607047A9 +:1027D0000044004037B51D4C1D4D204600F006FB5F +:1027E000009404F114001B490023202200F0C8F9D2 +:1027F0002022009404F13800174B184900F042FAE7 +:10280000174BC4E91735174C0C21252000F0CCF8E4 +:10281000204600F0EBFA04F1140013490094002361 +:10282000202200F0ADF904F13800104B104900945B +:10283000202200F027FA0F4B0C212620C4E917357F +:1028400003B0BDE8304000F0AFB800BFAC220020BC +:102850000051250284230020B5270008C42300204E +:102860000038014018230020A4230020C5270008B9 +:10287000E4230020004400402DE9F047C66D37688E +:10288000F46934622107054618D014F0080118BF16 +:102890008021E20748BF41F02001A30748BF41F073 +:1028A0004001600748BF41F48071202383F3118801 +:1028B000281DFFF777FF002383F31188E2050AD56F +:1028C000202383F311884FF40071281DFFF76AFF5E +:1028D000002383F311884FF020094FF0000A14F011 +:1028E000200838D13B0616D54FF0200905F1380AEB +:1028F000200610D589F31188504600F0F7F900281A +:1029000036DA0821281DFFF74DFF27F080033360DA +:10291000002383F31188790614D5620612D520238B +:1029200083F31188D5E913239A4208D12B6C33B174 +:102930001021281D27F04007FFF734FF37600023E0 +:1029400083F31188E30619D5AA6E1369B3B1BDE804 +:10295000F0475069184789F31188B38C95F86410D3 +:102960002846194000F04EFA8AF31188F469B6E758 +:1029700080B2308588F31188F469B9E7BDE8F08743 +:1029800008B50348FFF778FFBDE8084000F02CBE0B +:10299000AC22002008B50348FFF76EFFBDE80840F1 +:1029A00000F022BE1823002000F1604303F56143CC +:1029B0000901C9B283F80013012200F01F039A40F5 +:1029C00043099B0003F1604303F56143C3F8802191 +:1029D0001A60704700F16040090100F56D40C9B20E +:1029E00001767047FFF7CCBD012300F10802C0E972 +:1029F0000222037000F110020023C0E90422C0E9A2 +:102A00000633C0E9083343607047000010B5202347 +:102A1000044683F31188022303704160FFF7D2FD5F +:102A200004232370002383F3118810BD2DE9F041A6 +:102A30001F4604460D461646202383F3118800F1F5 +:102A400008082378052B0DD029462046FFF7E0FD26 +:102A500040B1204632462946FFF7FAFD002080F3B8 +:102A6000118808E03946404600F024FB0028E8D0F1 +:102A7000002383F31188BDE8F08100002DE9F041C7 +:102A80001F4604460D461646202383F3118800F1A5 +:102A900010082378052B0DD029462046FFF70EFE9F +:102AA00040B1204632462946FFF720FE002080F341 +:102AB000118808E03946404600F0FCFA0028E8D0CA +:102AC000002383F31188BDE8F0810000F8B51546B6 +:102AD00082680669AA420B46816938BF8568761A02 +:102AE000B54204460BD218462A46FEF757FCA369A6 +:102AF0002B44A361A3685B1BA3602846F8BD0CD9D7 +:102B000018463246FEF74AFCAF1BE1683A463044AD +:102B1000FEF744FCE3683B44EBE718462A46FEF721 +:102B20003DFCE368E5E7000083689342F7B515468E +:102B3000044638BF8568D0E90460361AB5420BD226 +:102B40002A46FEF72BFC63692B446361A368284681 +:102B50005B1BA36003B0F0BD0DD932460191FEF7B7 +:102B60001DFC0199E068AF1B3A463144FEF716FCA4 +:102B7000E3683B44E9E72A46FEF710FCE368E4E734 +:102B800010B50A440024C361029B8460C0E90000C0 +:102B9000C0E90511C1600261036210BD08B5D0E94A +:102BA0000532934201D1826882B982680132826023 +:102BB0005A1C42611970D0E904329A4224BFC3689A +:102BC0004361002100F086FA002008BD4FF0FF307D +:102BD000FBE7000070B5202304460E4683F31188FE +:102BE000A568A5B1A368A269013BA360531CA361BA +:102BF00015782269934224BFE368A361E3690BB1AE +:102C000020469847002383F31188284607E0314681 +:102C1000204600F04FFA0028E2DA85F3118870BDF3 +:102C20002DE9F74F04460E4617469846D0F81C90FB +:102C30004FF0200A8AF311884FF0000B154665B15A +:102C40002A4631462046FFF741FF034660B9414618 +:102C5000204600F02FFA0028F1D0002383F31188DA +:102C6000781B03B0BDE8F08FB9F1000F03D00190DD +:102C70002046C847019B8BF31188ED1A1E448AF346 +:102C80001188DCE7C0E90511C160C3611144009BF4 +:102C90008260C0E90000016103627047F8B5044634 +:102CA0000D461646202383F31188A768A7B1A368B1 +:102CB000013BA36063695A1C62611D70D4E9043250 +:102CC0009A4224BFE3686361E3690BB120469847E9 +:102CD000002080F3118807E03146204600F0EAF931 +:102CE0000028E2DA87F31188F8BD0000D0E9052357 +:102CF0009A4210B501D182687AB982680132826045 +:102D00005A1C82611C7803699A4224BFC36883619C +:102D1000002100F0DFF9204610BD4FF0FF30FBE747 +:102D20002DE9F74F04460E4617469846D0F81C90FA +:102D30004FF0200A8AF311884FF0000B154665B159 +:102D40002A4631462046FFF7EFFE034660B941466A +:102D5000204600F0AFF90028F1D0002383F311885A +:102D6000781B03B0BDE8F08FB9F1000F03D00190DC +:102D70002046C847019B8BF31188ED1A1E448AF345 +:102D80001188DCE7026843681143016003B118470A +:102D9000704700001430FFF743BF00004FF0FF33CF +:102DA0001430FFF73DBF00003830FFF7B9BF000017 +:102DB0004FF0FF333830FFF7B3BF00001430FFF798 +:102DC00009BF00004FF0FF311430FFF703BF0000D0 +:102DD0003830FFF763BF00004FF0FF323830FFF7A5 +:102DE0005DBF000000207047FFF7F4BC044B036098 +:102DF0000023C0E90233436001230374704700BF1E +:102E0000F43B000838B5C36904460D461BB90421DC +:102E10000844FFF7B7FF294604F11400FFF7BEFE90 +:102E2000002806DA201D4FF48061BDE83840FFF726 +:102E3000A9BF38BD024B0022C3E900339A60704736 +:102E400004240020002303748268054B1B689968E2 +:102E50009142FBD25A68036042601060586070472C +:102E60000424002008B5202383F31188037C032B5E +:102E700005D0042B0DD02BB983F3118808BD43690D +:102E800000221A604FF0FF334361FFF7DBFF00239E +:102E9000F2E7D0E9003213605A60F3E700230374CD +:102EA0008268054B1B6899689142FBD85A68036099 +:102EB000426010605860704704240020054B196977 +:102EC0000874186802681A6053601861012303745B +:102ED000FDF77EBB0424002030B54B1C0B4D87B0A2 +:102EE000044610D02B690A4A01A800F01BF92046BD +:102EF000FFF7E4FF049B13B101A800F02FF92B6941 +:102F0000586907B030BDFFF7D9FFF8E70424002067 +:102F1000652E000838B50C4D41612B6981689A68AF +:102F20009142044603D8BDE83840FFF78BBF1846EE +:102F3000FFF7B4FF01232C61014623742046BDE84E +:102F40003840FDF745BB00BF04240020044B1A683D +:102F50001B6990689B68984294BF002001207047CD +:102F60000424002010B5084C236820691A682260E8 +:102F70005460012223611A74FFF790FF0146206913 +:102F8000BDE81040FDF724BB0424002008B5FFF77E +:102F9000DDFF18B1BDE80840FFF7E4BF08BD000041 +:102FA000FFF7E0BFFEE7000010B50C4CFFF742FF53 +:102FB00000F0AAF80A498022204600F031F80123E7 +:102FC00044F8180C037400F0EBFA002383F3118823 +:102FD00062B60448BDE8104000F042B82C2400203E +:102FE0001C3C00082C3C000800F0CAB8EFF311802C +:102FF00020B9EFF30583202282F311887047000087 +:1030000010B530B9EFF30584C4F3080414B180F3AC +:10301000118810BDFFF7BAFF84F31188F9E70000AB +:1030200082600222028270478368A3F17C0243F827 +:103030000C2C026943F83C2C426943F8382C074AAF +:1030400043F81C2CC26843F8102C022203F8082C09 +:10305000002203F8072CA3F118007047E9050008C7 +:1030600010B5202383F31188FFF7DEFF002104460B +:10307000FFF750FF002383F31188204610BD0000A6 +:10308000024B1B6958610F20FFF718BF0424002072 +:10309000202383F31188FFF7F3BF000008B5014632 +:1030A000202383F311880820FFF716FF002383F302 +:1030B000118808BD49B1064B42681B6918605A6007 +:1030C000136043600420FFF707BF4FF0FF307047E5 +:1030D000042400200368984206D01A6802605060F9 +:1030E00059611846FFF7AEBE7047000038B5044678 +:1030F0000D462068844200D138BD036823605C60BF +:103100004561FFF79FFEF4E7054B03F11402C3E9A5 +:1031100005224FF0FF32DA6100221A62704700BFC9 +:103120000424002010B5C0E903230B4A136A536935 +:103130009C68A1420CD85C68816003604460206098 +:1031400058609868411A99604FF0FF33D36110BD01 +:103150001B68091BECE700BF04240020036881689A +:103160009A680A449A60426813605A600023C360F8 +:10317000024B4FF0FF32DA61704700BF0424002099 +:1031800038B50F4C236A22460133236252F8143FAC +:10319000934206D09A68013A9A60202563699A683A +:1031A00002B138BDD3E9001001604860D968DA6027 +:1031B00082F311881869884785F31188EEE700BF0C +:1031C0000424002000207047FEE700007047000044 +:1031D0004FF0FF3070470000BFF34F8F024AD368B3 +:1031E000DB07FCD4704700BF0020024008B5074B46 +:1031F0001B7853B9FFF7F0FF054B1A69120641BF60 +:10320000044A5A6002F188325A6008BD90250020B5 +:10321000002002402301674508B5054B1B7833B9F0 +:10322000FFF7DAFF034A136943F08003136108BD17 +:1032300090250020002002407F289ABF00F58030B2 +:10324000C0020020704700004FF40060704700008B +:10325000802070477F2808B50BD8FFF7EDFF00F5F9 +:1032600000630268013204D104308342F9D10120A5 +:1032700008BD0020FCE700007F2838B5044623D8AD +:10328000FFF7B4FEFFF7A8FFFFF7B0FF0F4BF322E5 +:10329000DA6002221A6105462046FFF7CDFF586129 +:1032A0001A6942F040021A614FF40061FFF794FF7F +:1032B00000F026F92846FFF7AFFFFFF7A1FE2046F2 +:1032C000BDE83840FFF7C6BF002038BD00200240EF +:1032D00012F001032DE9F04704460E46154606D0CC +:1032E000244B40F2BD221A600020BDE8F08781180F +:1032F000214A914204D91F4A40F2C2211160F3E7EA +:10330000FFF774FEFFF772FFFFF766FFDFF87890B4 +:1033100031464FF0010AA61B012D06EB0107884636 +:1033200005D8FFF779FFFFF76BFE0120DDE7B8F85E +:103330000030C9F810A03B800024FFF74DFFC9F80A +:1033400010403B8831F8022B9BB29A420FD0094BB8 +:1033500040F2D9221A60094B1F60094B1D60094BCE +:10336000C3F80080FFF758FFFFF74AFEBCE7023DB5 +:10337000D2E700BF8C250020000004088025002033 +:10338000882500208425002000200240084908B537 +:103390000B7828B11BB9FFF729FF01230B7008BD7B +:1033A000002BFCD0BDE808400870FFF735BF00BF18 +:1033B0009025002030B583B0FFF718FE0E4B0F4D5F +:1033C0001B6A2A684FF47A7101FB03F3934237BFFB +:1033D0000B4A0B49516814682B602EBFD1E900419C +:1033E000013151601C1941F100010191FFF708FE04 +:1033F0000199204603B030BD04240020942500200C +:103400009825002030B583B0FFF7F0FD114B124D29 +:103410001B6A2A684FF47A7101FB03F3934237BFAA +:103420000E4A0E49516814682B602EBFD1E9004145 +:10343000013151601C1941F100010191FFF7E0FDDC +:1034400001994FF47A7200232046FCF7A9FE03B0DD +:1034500030BD00BF042400209425002098250020C2 +:1034600010B50244064BD2B2904200D110BD441CAC +:1034700000B253F8200041F8040BE0B2F4E700BFBB +:10348000502800400F4B30B51C6A240407D41C6A36 +:1034900044F440741C621C6A44F400441C620A4CEC +:1034A000236843F4807323600244084BD2B29042F5 +:1034B00000D130BD441C00B251F8045B43F82050E9 +:1034C000E0B2F4E7001002400070004050280040D5 +:1034D00007B5012201A90020FFF7C2FF019803B040 +:1034E0005DF804FB13B50446FFF7F2FFA04205D0D8 +:1034F000012201A900200194FFF7C4FF02B010BD12 +:1035000070470000074B45F255521A6002225A607C +:1035100040F6FF729A604CF6CC421A60024B0122D0 +:103520001A70704700300040A4250020034B1B7820 +:103530001BB1034B4AF6AA221A607047A42500204B +:1035400000300040044B1A682AB902F1804202F5AB +:103550000432526A1A607047A0250020024B4FF0D7 +:1035600080725A62704700BF0010024008B5FFF732 +:10357000E9FF024B1868C0F3407008BDA025002089 +:10358000EFF3098305494A6B22F001024A6368336D +:1035900083F30988002383F31188704700EF00E06C +:1035A000202080F3118862B60C4B0D4AD96821F4B3 +:1035B000E0610904090C0A43DA60D3F8FC200949E8 +:1035C00042F08072C3F8FC200A6842F001020A60EF +:1035D0001022DA7783F82200704700BF00ED00E088 +:1035E0000003FA05001000E010B5202383F31188D2 +:1035F0000E4B5B6813F4006314D0F1EE103AEFF356 +:103600000984683C4FF08073E361094BDB6B2366F0 +:1036100084F30988FFF79AFC10B1064BA36110BD33 +:10362000054BFBE783F31188F9E700BF00ED00E0ED +:1036300000EF00E0FB050008FE05000870470000F1 +:10364000FEE700000A4B0B480B4A90420BD30B4B92 +:10365000DA1C121AC11E22F003028B4238BF00226C +:103660000021FDF7ADBE53F8041B40F8041BECE746 +:10367000183D0008282600202826002028260020A3 +:10368000704700004B6843608B688360CB68C36001 +:103690000B6943614B6903628B6943620B6803608A +:1036A0007047000008B51B4B9A6A42F4FC029A620C +:1036B0009A6A22F4FC029A629A6A5A6942F4FC02FB +:1036C0005A61154A5B6911464FF09040FFF7DAFFE7 +:1036D00002F11C0100F58060FFF7D4FF02F1380110 +:1036E00000F58060FFF7CEFF02F1540100F5806025 +:1036F000FFF7C8FF02F1700100F58060FFF7C2FF1D +:1037000002F18C0100F58060FFF7BCFFBDE80840C6 +:1037100000F05AB800100240443C000808B500F020 +:1037200093F9FFF741FCBDE80840FFF70BBF00002D +:103730007047000010B5214CA36A63F4FC03A36238 +:10374000A36A03F4FC03A3624FF0FF32A36A236968 +:1037500022612369002323612169E168E260E26854 +:10376000E360E268E269164942F08052E261E26990 +:103770000A6842F480720A60226A02F44072B2F56A +:10378000407F1EBF4FF4803222622362236A1B04F3 +:1037900007D4236A43F440732362236A43F400434B +:1037A000236200F031F9A369064A43F00103A361E3 +:1037B000A369136843F02003136010BD001002409A +:1037C00000700040000001401E4B1A6842F00102E8 +:1037D0001A601A689007FCD55A6822F003025A60F2 +:1037E0005A6812F00C02FBD1196801F0F901196056 +:1037F0005A601A6842F480321A601A689103FCD544 +:10380000114A5A604FF40452DA6230221A631A687D +:1038100042F080721A601A689201FCD50B4912229C +:103820000A600A6802F00702022AFAD15A6842F0D6 +:1038300002025A605A6802F00C02082AFAD11A6B86 +:103840001A6370470010024000241D00002002404F +:10385000084A08B5516913680B4003F0010353612E +:1038600023B1054A13680BB150689847BDE808407A +:10387000FFF7BABE00040140A8250020084A08B599 +:10388000516913680B4003F00203536123B1054AE9 +:1038900093680BB1D0689847BDE80840FFF7A4BE15 +:1038A00000040140A8250020084A08B551691368A2 +:1038B0000B4003F00403536123B1054A13690BB1B4 +:1038C00050699847BDE80840FFF78EBE00040140EC +:1038D000A8250020084A08B5516913680B4003F079 +:1038E0000803536123B1054A93690BB1D069984726 +:1038F000BDE80840FFF778BE00040140A82500207D +:10390000084A08B5516913680B4003F0100353616E +:1039100023B1054A136A0BB1506A9847BDE80840C5 +:10392000FFF762BE00040140A8250020174B10B528 +:103930005A691C68144004F478725A61A30604D5CD +:10394000134A936A0BB1D06A9847600604D5104AAF +:10395000136B0BB1506B9847210604D50C4A936B3F +:103960000BB1D06B9847E20504D5094A136C0BB133 +:10397000506C9847A30504D5054A936C0BB1D06CE5 +:103980009847BDE81040FFF72FBE00BF000401407C +:10399000A82500201A4B10B55A691C68144004F47D +:1039A0007C425A61620504D5164A136D0BB1506D05 +:1039B0009847230504D5134A936D0BB1D06D9847F2 +:1039C000E00404D50F4A136E0BB1506E9847A10462 +:1039D00004D50C4A936E0BB1D06E9847620404D59F +:1039E000084A136F0BB1506F9847230404D5054A5A +:1039F000936F0BB1D06F9847BDE81040FFF7F4BD4F +:103A000000040140A8250020062108B50846FEF75D +:103A1000CBFF06210720FEF7C7FF06210820FEF78F +:103A2000C3FF06210920FEF7BFFF06210A20FEF78B +:103A3000BBFF06211720FEF7B7FFBDE808400621AF +:103A40002820FEF7B1BF000008B5FFF773FE00F0B5 +:103A50000DF8FEF7C7FFFFF7C7F9FFF769FEBDE8EE +:103A6000084000F001B8000000F00EB80023054A3D +:103A700019460133102BC2E9001102F10802F8D1F6 +:103A8000704700BFA82500204FF0E023044A5A6188 +:103A900000229A6107221A6108210B20FEF79ABFC3 +:103AA0003F19010008B5202383F31188FFF79CFA22 +:103AB000002383F3118808BD08B5FFF7F3FFBDE8C5 +:103AC0000840FFF791BD000010B501390244904253 +:103AD00001D1002005E0037811F8014FA34201D085 +:103AE000181B10BD0130F2E72DE9F041A3B1C91A4E +:103AF00017780144044603F1FF3C8C42204601D96B +:103B0000002009E00578BD4204F10104F5D10CEB79 +:103B10000405D618A54201D1BDE8F08115F8018D44 +:103B200016F801EDF045F5D0E7E70000034611F87F +:103B3000012B03F8012B002AF9D17047696F2E6D14 +:103B4000726F626F746963732E6D31303037305F1E +:103B50006C6F63315F424C004E6F20617070207358 +:103B600069670A00426164206677206C656E67743D +:103B7000682025750A0042616420626F6172645F8B +:103B800069642025752073686F756C6420626520F8 +:103B900025750A004261642066772064657363724C +:103BA0006970746F72206C656E6774682025750A81 +:103BB00000426164206170702043524320307825B8 +:103BC0003038783A307825303878203078253038D9 +:103BD000783A3078253038780A00476F6F6420666D +:103BE00069726D776172650A0040A2E4F1646891C0 +:103BF0000600000000000000B12D00089D2D000807 +:103C0000D92D0008C52D0008D12D0008BD2D0008B4 +:103C1000A92D0008952D0008E52D00086D61696E3D +:103C20000000000069646C6500000000243C00088E +:103C3000482400208025002001000000A52F000856 +:103C400000000000A001A82A00000000FAAABEAAF5 +:103C500050001424EFFF0000007700007097090067 +:103C60000100000000000000AAAAAAAA01000000AA +:103C7000FFFF000000000000000000000000000046 +:103C800000000000AAAAAAAA00000000FFFF00008E +:103C90000000000000000000000000000000000024 +:103CA000AAAAAAAA00000000FFFF0000000000006E +:103CB000000000000000000000000000AAAAAAAA5C +:103CC00000000000FFFF00000000000000000000F6 +:103CD0000000000000000000AAAAAAAA000000003C +:103CE000FFFF00000000000000000000E4C4FF7FB0 +:103CF0000100000000000000EC03000000000000D4 +:103D000000980300000000006400000000000000B4 +:083D1000FE2A0100D2040000AC :00000001FF diff --git a/Tools/bootloaders/f303-MatekGPS_bl.bin b/Tools/bootloaders/f303-MatekGPS_bl.bin index ce846237d88..1af00725c6c 100755 Binary files a/Tools/bootloaders/f303-MatekGPS_bl.bin and b/Tools/bootloaders/f303-MatekGPS_bl.bin differ diff --git a/Tools/bootloaders/f303-MatekGPS_bl.elf b/Tools/bootloaders/f303-MatekGPS_bl.elf index 930ece65580..299e90cccb1 100755 Binary files a/Tools/bootloaders/f303-MatekGPS_bl.elf and b/Tools/bootloaders/f303-MatekGPS_bl.elf differ diff --git a/Tools/bootloaders/f303-MatekGPS_bl.hex b/Tools/bootloaders/f303-MatekGPS_bl.hex index e2cfbdb6bf5..50f32ca71bc 100644 --- a/Tools/bootloaders/f303-MatekGPS_bl.hex +++ b/Tools/bootloaders/f303-MatekGPS_bl.hex @@ -1,1095 +1,980 @@ :020000040800F2 -:1000000000090020E1040008991400089D1400086C -:10001000F11400089D140008C5140008E30400084A -:10002000E3040008E3040008E30400085D37000867 -:10003000E3040008E3040008E3040008013C0008AE -:10004000E3040008E3040008E3040008E3040008F4 -:10005000E3040008E3040008E5390008113A000849 -:100060003D3A0008693A0008953A0008E3040008A0 -:10007000E3040008E3040008E3040008E3040008C4 -:10008000E3040008E3040008E3040008092600086C -:1000900075260008C92600081D270008C13A000877 -:1000A000E3040008E3040008E3040008E304000894 -:1000B000E3040008E3040008E3040008E304000884 -:1000C000E3040008E3040008E3040008E304000874 -:1000D000E3040008D92A0008ED2A0008E304000818 -:1000E000293B0008E3040008E3040008E3040008D7 -:1000F000E3040008E3040008E3040008E304000844 -:10010000E3040008E3040008E3040008E304000833 -:10011000E3040008E3040008E3040008E304000823 -:10012000E3040008E3040008E3040008E304000813 -:10013000E3040008E3040008E3040008E304000803 -:10014000E3040008E3040008E3040008E3040008F3 -:10015000E3040008E3040008E3040008E3040008E3 -:10016000E3040008E3040008E3040008E3040008D3 -:10017000E3040008E3040008E3040008E3040008C3 -:10018000E3040008E3040008E3040008E3040008B3 -:10019000E3040008E3040008E3040008E3040008A3 -:1001A000D0400B1CD1409C46203AD34018435242C9 -:1001B00063469340184370479140031C90409C460F -:1001C000203A9340194352426346D3401943704743 -:1001D00053B94AB9002908BF00281CBF4FF0FF31AE -:1001E0004FF0FF3000F07AB9ADF1080C6DE904CEA4 -:1001F00000F006F8DDF804E0DDE9022304B0704702 -:100200002DE9F0478C460D460446089E002B51D13F -:100210008A4217466DD9B2FA82FEBEF1000F0BD0AA -:10022000CEF1200C01FA0EF520FA0CFC02FA0EF7C2 -:100230004CEA050C00FA0EF44FEA174A250CBCFBF9 -:10024000FAF81FFA87F90AFB18CC45EA0C4508FBB7 -:1002500009F3AB420AD9ED1908F1FF3280F023818E -:10026000AB4240F22081A8F102083D44ED1AA4B24D -:10027000B5FBFAF00AFB105544EA054400FB09F906 -:10028000A14509D9E41900F1FF3380F00A81A145A5 -:1002900040F2078102383C44A4EB090440EA0840DC -:1002A0000021002E61D024FA0EF400233460736024 -:1002B000BDE8F0878B4207D9002E54D0002186E894 -:1002C00021000846BDE8F087B3FA83F1002940F029 -:1002D0008E80AB4202D3824200F2FA80841A65EB30 -:1002E00003050120AC46002E3FD086E81010BDE883 -:1002F000F08712B90127B7FBF2F7B7FA87FEBEF114 -:10030000000F34D1EB1B3A0C1FFA87FC0121B3FB21 -:10031000F2F8250C02FB183345EA03450CFB08F301 -:10032000AB4207D9ED1908F1FF3002D2AB4200F21F -:10033000D1808046ED1AA3B2B5FBF2F002FB105556 -:1003400043EA05440CFB00FCA44507D9E41900F17D -:10035000FF3302D2A44500F2B8801846A4EB0C0487 -:1003600040EA08409DE731463046BDE8F087CEF1CF -:10037000200405FA0EF307FA0EF720FA04F83A0CF7 -:1003800025FA04F448EA0308B4FBF2F14FEA1845F1 -:1003900002FB11441FFA87FC45EA044501FB0CF3FC -:1003A000AB4200FA0EF409D9ED1901F1FF3080F0EB -:1003B0008A80AB4240F2878002393D44EB1A1FFA33 -:1003C00088F5B3FBF2F002FB103345EA034500FB6E -:1003D0000CF3AB4207D9ED1900F1FF386FD2AB42F5 -:1003E0006DD902383D44EB1A40EA01418FE7C1F173 -:1003F000200722FA07F88B4005FA01F448EA0303C4 -:1004000020FA07FE4FEA134CFD404EEA040EB5FBFE -:10041000FCF94FEA1E440CFB19551FFA83F844EA15 -:10042000054509FB08F4AC4202FA01F200FA01FAB0 -:1004300008D9ED1809F1FF3043D2AC4241D9A9F1F6 -:1004400002091D442D1B1FFA8EFEB5FBFCF00CFBB0 -:1004500010554EEA054400FB08F8A04507D9E418FA -:1004600000F1FF3529D2A04527D902381C4440EAC3 -:100470000940A4EB0804A0FB02894C45C6464D4642 -:1004800015D312D056B1BAEB0E0364EB050404FA8F -:1004900007F7CB401F43CC40376074600021BDE8B4 -:1004A000F0871846F8E69046E0E6C245EAD2B8EB97 -:1004B000020E69EB03050138E4E72846D7E740461A -:1004C00091E78146BEE7014678E702383C4445E7BC -:1004D000084608E7A8F102083D442BE7704700BF33 -:1004E00002E000F000F8FEE772B6394880F30888B1 -:1004F000384880F3098838484EF60851CEF200019A -:10050000086040F20000CCF200004EF63471CEF2EA -:1005100000010860BFF34F8FBFF36F8F40F2000000 -:10052000C0F2F0004EF68851CEF200010860BFF331 -:100530004F8FBFF36F8F4FF00000E1EE100A4EF6C1 -:100540003C71CEF200010860062080F31488BFF3EE -:100550006F8F03F041F903F06DF94FF055301F49EB -:100560001B4A91423CBF41F8040BFAE71C49194A67 -:1005700091423CBF41F8040BFAE71A491A4A1B4B57 -:100580009A423EBF51F8040B42F8040BF8E70020F2 -:100590001749184A91423CBF41F8040BFAE703F0AF -:1005A0001FF903F089F9144C144DAC4203DA54F8E6 -:1005B000041B8847F9E700F03FF8114C114DAC429D -:1005C00003DA54F8041B8847F9E703F007B9000081 -:1005D0000009002000110020000000080001002098 -:1005E00000090020D04300080011002074110020F1 -:1005F0007811002090260020A0010008A00100082A -:10060000A0010008A00100082DE9F04F2DED108A8F -:10061000C1F80CD0C3689D46BDEC108ABDE8F08FD0 -:10062000002383F311882846A047002002F070FEC3 -:1006300002F09AFD00DFFEE7384B6FF013022DE960 -:10064000F0416FF0670100241A7003225A709C7009 -:10065000DC701C715C719C71DC711C7259729A7235 -:10066000DC7203F025F8074603F072F80546C8BBB4 -:100670002B4B9F4238D001339F4238D0294B27F073 -:10068000FF029A4237D1F8B200F052FAA84642F27D -:10069000107400F07BFC00F051FA064678B384BB7E -:1006A000464635B1204B9F4203D003F049F8002461 -:1006B0002646002003F006F81C4B1B6913F040038C -:1006C00022D00EB100F034F800F082FC00F016FEEB -:1006D00000F022FF0546CCB900F0D0FC012002F06A -:1006E0001DFEF8E78046D4E780460446D1E704467D -:1006F0004FF00108CDE780464FF47A74C9E704460D -:10070000CFE74FF47A74CCE71C46DDE700F004FF36 -:10071000401BA042E0D900F00BF8D9E77811002087 -:10072000010007B0000008B0263A09B000040048F4 -:1007300010B51C4B1C4953F8042F013200D110BDD9 -:100740008B42F8D1194C1A4B22689A4228D9194B7E -:100750009B6803F1006303F5D0439A4220D202F074 -:10076000C3FF02F0D5FF002000F0E2FD124B022093 -:10077000187000F019FE114BDA690022DA61D969AC -:1007800099699A619B6972B60D4A0E4B13601B689A -:100790002268202181F311889D4683F30888104741 -:1007A00010BD00BFFC6700081C6800080468000852 -:1007B000FF6700087811002084110020001002401B -:1007C00008ED00E00068000809490B6849F269007B -:1007D0009AB21B0C00FB0233064A0B60136844F20A -:1007E000506198B21B0C01FB0030106080B2704762 -:1007F0000C1100200811002010B500211022044621 -:1008000000F0ECFD034B03CB206061601868A06032 -:1008100010BD00BFACF7FF1FF0B51F4CBBB000F020 -:100820007BFEA368C31AF92B30D906AD2346A0601E -:1008300028220021284601F0FDFB04F10E0000F003 -:10084000C5FD0023C6B2591D5F1CDBB2B3424FEA9F -:10085000C10107DA0E3323440822284601F0EAFBDF -:100860003B46F0E7012303930823207B02930B4BC5 -:100870000193C1F3CF013023059100930146049504 -:1008800003A3D3E90023064801F0A4F93BB0F0BD6F -:1008900078F6339F93CACD8DC8210020D521002042 -:1008A000A021002070B50D4614461E4601F038F90F -:1008B00050B9022E0ED1012C0CD112A3D3E9002382 -:1008C000C5E90023012070BD052C14D003D8012CEC -:1008D00009D0002070BD282C09D0302CF9D10BA3F1 -:1008E000D3E90023ECE70BA3D3E90023E8E70BA34C -:1008F000D3E90023E4E70BA3D3E90023E0E700BF3B -:10090000AFF30080401DA12026812A0B78F6339F8B -:1009100093CACD8D9E6AC421818A46EE26417272A9 -:10092000DF25D7B7F017304A39059E5638B504464B -:100930000D46034620222846002101F07BFB227948 -:100940002346032A28BF032203F8042F2846022245 -:10095000202101F06FFB62792346072A28BF072276 -:1009600003F8052F28460322222101F063FBA27918 -:100970002346072A28BF072203F8062F284603220A -:10098000252101F057FB284604F1080310222821F5 -:1009900001F050FB382038BD2DE9F04FADF5017D59 -:1009A00021AE0EAD40F2791280460F46304600214E -:1009B00000F014FD48220021284600F00FFD00F051 -:1009C000ABFD594B4FF47A72B0FBF2F0186093E82C -:1009D0000700012385E807002B740DF15A0000235E -:1009E0006B74FFF709FF032385F82030EC2385F8AB -:1009F000213007AB18464D4903F06CF91B222864DF -:100A00003146284685F83C20FFF790FF12AB04469C -:100A100001460822304601F00DFB0822A1180DF115 -:100A20004903304601F006FB0DF14A03082204F1A8 -:100A30001001304601F0FEFA13AB202204F1180138 -:100A4000304601F0F7FA14AB402204F13801304689 -:100A500001F0F0FA16AB082204F17801304601F0FB -:100A6000E9FA0DF15903082204F18001304601F042 -:100A7000E1FA04F1880A0DF15A0904F5847B4B462A -:100A80005146082230460AF1080A01F0D3FAD3454C -:100A900009F10109F3D11BAB08225946304601F098 -:100AA000C9FA04F588744FF0000995F834304B45C5 -:100AB00010D84FF0000995F83C304B4515D92B6CF8 -:100AC00021464B440822304601F0B4FA083409F1BB -:100AD0000109F0E7AB6B21464B440822304601F098 -:100AE000A9FA083409F10109DFE7E31DC3F3CF03D5 -:100AF000F97E0593002304960393BB7E0293193776 -:100B000001230093019706A3D3E90023404601F097 -:100B100061F80DF5017DBDE8F08F00BFAFF30080F7 -:100B20009E6AC421818A46EE88110020AC3E0008EE -:100B3000014B1870704700BF94110020F0B5334B83 -:100B40001C7B85B034B1324B0E221A810024204622 -:100B500005B0F0BD2F4A1068516802AB03C30823EB -:100B60000DEB03022C492D4803F096F8054630B9E9 -:100B7000274B2B480A221A8100F084FCE6E7016922 -:100B8000B1F5663F06D9224B26480B221A8100F0A8 -:100B900079FCDCE7438BB3F57B7F09D01C4A224804 -:100BA0000C2111814FF47B72194600F06BFCCEE7EB -:100BB0001E4A024402F11003994204D2144B1C480D -:100BC00010221A81E3E710398E1A2046134900F0EB -:100BD000A7FC3246074605F11801204600F0A0FCAC -:100BE000AB689F4202D1EB6898420AD0084B0D22B5 -:100BF0001A8100903B46EA68A9680E4800F042FC62 -:100C0000A4E70D4800F03EFC0124A0E7C821002025 -:100C1000881100207C3D0008DC9703000068000874 -:100C2000843D0008903D0008A23D00080898FFF7A9 -:100C3000C03D0008DD3D0008063E00082DE9F04FEC -:100C4000ADB006AF80460C4600F06AFF05460028AE -:100C50006AD1237E022B18D1E38A012B15D100F033 -:100C60005BFC8146FFF7B0FD4FF4C873BD4EB0FB8F -:100C7000F3F209F5167902FB1300E37E19FA80F00E -:100C800030608BB9B84B00221A709C37BD46BDE866 -:100C9000F08F3B1D1D440095002308224FEAC90137 -:100CA000204601F02BF84D46A38A013BAB425FFA88 -:100CB00085F90BD905F10109B9F1110FE9D1AB4B58 -:100CC000AB4A40F23911AB4802F0B8FF07F114000B -:100CD000FFF792FD2A4607F11401381D02F0CCFF00 -:100CE00003460028CED1B9F1100F07D09E4B83F8F0 -:100CF00000903368A3F516733360C6E707F19802D6 -:100D0000014602F8950D20460092072200F0F6FFFA -:100D1000F9787F2904DD984B954A4FF4A871D2E702 -:100D2000404600F0E1FEB0E7E38A052B00F00681C3 -:100D300006D8012BA9D121464046FFF72DFEA4E796 -:100D4000282B3DD0302BA0D1637E8C4D01336A7BA4 -:100D5000DBB29342E94640F0EF80E27E2B7B9A4281 -:100D600040F0EA8007F19803002623F8846D1022F2 -:100D7000009331460123204600F0C0FFB4F81480F0 -:100D8000A8F102081FFA88F808F1030323F003030F -:100D90000A3323F00703ADEB030D0DF1180A3346B8 -:100DA0009BB2B11C98454FEAC10106F101066CDD0A -:100DB0005344009308220023204600F09FFFEEE7F3 -:100DC000A38A013B9BB2C92B3FF65FAF6B4E357BCD -:100DD0004DBB06F10C03009308222B462946204602 -:100DE00000F08CFFA38A05F10109013BEDB29D42A1 -:100DF0004FEAC90109DA0E3535440095002308226F -:100E0000204600F07BFF4D46ECE700230022C6E9B8 -:100E100000230023B36086F8D730C6F8D830337B80 -:100E20000BB9E37E3373002507F114063B1D08223E -:100E3000294630467D60BD60FD6001F0FBF83B7ADD -:100E400005F10109AB424FEAC90107D9FB68082245 -:100E50002B44304601F0EEF84D46F0E7C1F3CF01E8 -:100E60000023E07E059104960393A37E0293193438 -:100E7000282301460093019438A3D3E90023404678 -:100E800000F0A8FEFFF7C8FCFFE695F8D70000F0D9 -:100E900059FAD5F8D83006461BB995F8D70000F0B6 -:100EA00061FAD5F8D83043449E4204D295F8D70071 -:100EB000013000F057FA4FEA980B0024A0B25845D1 -:100EC00004F1010408DA2B6880000AEB000101221A -:100ED000184400F08BFAF1E7D5E90023D5F8D840A3 -:100EE00095F8D70012EB080243F100034444C5E92A -:100EF0000023C5F8D84000F025FA844209D395F8BC -:100F0000D730013385F8D730D5F8D8309E1BC5F8D7 -:100F1000D860B8F1FF0F08DC00232B7300F034FA1F -:100F2000FFF70CFE08B1FFF703FC2B68144A9B0A7D -:100F3000013313810023AB60CD46A6E6BFF34F8F8C -:100F40001049114BCA6802F4E0621343CB60BFF34F -:100F50004F8F00BFFDE700BFAFF3008026417272E4 -:100F6000DF25D7B79C21002099210020183E0008DA -:100F7000C83E0008713E0008933E0008C8210020CA -:100F80008811002000ED00E00400FA0508B54FF0DC -:100F900000530B4A196891420AD10A4A597D1170CF -:100FA00009481B7D0373C92208490E3000F004FA7A -:100FB000E02200214FF00050BDE8084000F00EBADA -:100FC0009AAD44C594110020C821002016000020CD -:100FD00030B5204C2049214885B002236371042399 -:100FE0000025ADF808300123ADF80C5007228DF82C -:100FF0000C308DF80B301A4B4B608DF80A2001F045 -:1010000003FE184B019500931749184B18484FF4ED -:10101000805200F033FD174B1978254611B1144862 -:1010200000F062FD00F078FA0446FFF7CDFB4FF4C4 -:10103000C87304F51674B0FBF3F202FB13000E4BF9 -:1010400014FA80F0186002F083FB08B10F232B81A3 -:1010500005B030BD8811002000110020E0220020E2 -:1010600003000600A5080008981100203D0C0008A8 -:10107000A0210020941100209C2100202DE9F04F98 -:1010800094A7D7E900670FF25429D9E900898D4C5C -:1010900093B0DFF850B2DFF850A2204600F0E6FD32 -:1010A0000CAD079098B310220021284600F096F965 -:1010B000079B197B4FF0000261F3030219468DF87C -:1010C000302051F8040F49680EAA03C21B680D9A1C -:1010D00063F31C029DF830300D9243F020038DF82D -:1010E000303000232A461946584601F09DFD0790EE -:1010F00030B9204600F0BEFD079B8AF80030CCE7EF -:101100009AF80030072B3EDC01338AF800301822B1 -:101110000021284600F062F9DFF8C8A10023194633 -:101120002A46504601F0A8FD014680BB102208A8BF -:1011300000F054F94FF09042536983F0100353616B -:1011400000F0ECF90B4612A9024611E903000DF17B -:10115000240E8EE803009DF83410C1F303008906C5 -:101160004CBF0E99BDF838108DF82C0046BFC1F366 -:101170001C0141F00041C1F30A010891204608A971 -:1011800000F0BEFFCAE7204600F074FDBFE720462E -:1011900000F0C6FC824600284AD1DFF850B100F0CA -:1011A000BBF9DBF80030984242D300F0B5F9079064 -:1011B000FFF70AFB079A8DF820A04FF4C87302F5D9 -:1011C0001672B0FBF3F101FB130012FA80F0CBF8BA -:1011D0000000DFF81CB19BF8001011B901238DF855 -:1011E000203028460791FFF707FB0799C1F1100A45 -:1011F0005FFA8AFABAF1060F28BF4FF0060A524684 -:1012000029440DF1210000F0D7F80AF101030493FD -:1012100008AB0393182302932B4B019301230093F4 -:1012200032463B46204600F07DFC00238BF8003020 -:1012300000F072F9254ADFF8BCA01368C31AB3F5B1 -:101240007A7F32D3106000F069F902460B462046DF -:1012500000F016FD204600F063FC30B39AF80C3025 -:10126000DFF894B0002B14BF032302238BF8053062 -:1012700000F052F94FF47A732946B0FBF3F0CBF843 -:1012800000005846FFF752FB182307300293104B1B -:101290000193C0F3CF0040F25513049000930395DF -:1012A00042464B46204600F03DFC9AF80C300BB10C -:1012B000FFF7B2FA9AF80C30002B7FF4EAAE13B0C5 -:1012C000BDE8F08FA021002098210020A822002056 -:1012D000AC220020401DA12026812A0BF1C6A7C107 -:1012E000D068080FE0220020AD2200209C210020C1 -:1012F00099210020C82100208811002070B502F03B -:10130000C3F8094C094E20700025306823788342C9 -:1013100008D902F0B5F8336805440133B5F5D04F6C -:101320003360F2D370BD00BFDC220020B022002069 -:1013300002F042B900F10060920000F5D04002F0E6 -:10134000E7B80000054B1A68054B1B789B1A8342CF -:1013500002D9104402F094B800207047B022002057 -:10136000DC22002038B5074D04462868204402F0EE -:101370008DF828B928682044BDE8384002F098B8B4 -:1013800038BD00BFB0220020064991F8243033B1A7 -:1013900000230822086A81F82430FFF7CBBF012020 -:1013A000704700BFB4220020022802BF4FF09043D4 -:1013B0004FF480129A61704710B50023934203D016 -:1013C000CC5CC4540133F9E710BD0000024603466B -:1013D000981A13F9011B0029FAD1704702440346F9 -:1013E000934202D003F8011BFAE770472DE9F0475A -:1013F000234C94F8243005468846174683BB2E4676 -:10140000DFF87C90C7B394F824302BB92022FF2159 -:1014100048462662FFF7E2FF94F82400C0F1080571 -:10142000BD4228BF3D465FFA85FAAD0041462A46D7 -:1014300004EB8000FFF7C0FF94F82430A7EB0A0705 -:101440009A445FFA8AFABAF1080F2E44A844FFB210 -:1014500084F824A0D6D1FFF797FF0028D2D108E066 -:10146000266A06EB8306B042CAD0FFF78DFF00283C -:10147000C5D10020BDE8F0870120BDE8F08700BF9E -:10148000B42200200FB4002004B070470FB44FF016 -:10149000FF3004B070470000FEE7000000B59BB0CD -:1014A000EFF3098168226846FFF786FFEFF30583B3 -:1014B000034B9A6B9A6A9A6A9A6A9A6A9B6AFEE7DF -:1014C00000ED00E000B59BB0EFF3098168226846AB -:1014D000FFF772FFEFF30583044B9A6B9A6A9A6ADF -:1014E0009A6A9A6A9A6A9B6AFEE700BF00ED00E07A -:1014F00000B59BB0EFF3098168226846FFF75CFFF7 -:10150000EFF30583034B5A6B9A6A9A6A9A6A9A6A4E -:101510009B6AFEE700ED00E002F086B802F060B8DA -:1015200030B5084D0A4491420BD011F8013B092413 -:101530005840013CF7D040F300032B4083EA5000B1 -:10154000F7E730BD2083B8ED0246006848B1036874 -:101550001360D388118901339BB29942D38038BF7D -:101560001381704770B588B00D46044620220021D3 -:101570006846FFF733FF20460495FFF7E5FF054671 -:1015800058B16B46044608AE1A4603CAB242206000 -:101590006160134604F10804F6D1284608B070BD16 -:1015A0002DE9F04130B9274B274A40F2C531274891 -:1015B00002F044FB0B7C23B9254B234A40F2C63191 -:1015C000F5E7C66986B9C161BDE8F081002B29DA6B -:1015D000930CAB4229D1B44201D10C60F3E7C8F8B7 -:1015E00000100C60BDE8F0814B6823F06047BD0C33 -:1015F0004FEAD37EC3F3807C15EA230538BF3D460E -:10160000B04634466368BEEBD37F23F06042DDD141 -:10161000974203D1C3F380739C450AD1974205E0FA -:101620001C46EFE7AA4206D013469D422CBF00237A -:101630000123002BCFD12368A046002BF0D12160DD -:10164000BDE8F0819C410008903F0008544200082A -:101650007542000808B5034A034B044840F25E3166 -:1016600002F0ECFA6C3F00081442000854420008F3 -:1016700008B503680B60C388016033B9044B054AA1 -:1016800005484FF4C76102F0D9FA013BC38008BD99 -:10169000E4410008E03F00085442000870B50C46E1 -:1016A00000F10C05616831B9E38A61F30903E38253 -:1016B0000020002170BD0E682846FFF7D9FF666044 -:1016C000F0E7000008B5426832B10B4B0B4A0C48FA -:1016D00040F22F4102F0B2FAC37DC3F3840101311D -:1016E00061F38603C375C38A62F30903C3821B0ACD -:1016F00062F3C713C37508BD304200089C3F000861 -:10170000544200082DE9F047089E32B91F4B204A89 -:10171000204840F2395102F091FA01F007054FEAF2 -:10172000D6082A4406F0070600EBD1004FF47F49A3 -:10173000954201D1BDE8F08705F0070E06F0070AD3 -:10174000D645774638BF5746C7F10807511BEC0806 -:101750008F4228BF0F46045D08EBD60104FA0EF451 -:1017600013F801C029FA07FE24FA0AF45FFA8EFE84 -:101770008CEA04044EFA0AFE04EA0E048CEA040C15 -:1017800003F801C03D443E44D2E700BFB041000829 -:10179000B43F0008544200082DE9F04106460F46C8 -:1017A00000254FF6FF7441F221082A46304639469B -:1017B000FEF7F6FCC0B284EA0024082314F4004FBC -:1017C0004FEA4404A4B203F1FF3318BF84EA0804CB -:1017D00013F0FF03F2D10835402DE6D12046BDE8D5 -:1017E000F081000010B50A4441F22104914200D179 -:1017F00010BD11F8013B80EA0320082310F4004FCC -:101800004FEA400080B203F1FF3318BF604013F08D -:10181000FF03F3D1EAE700002DE9F04F85B08A46D7 -:101820008DE80C00BDF83C40814630B9494B4A4A2E -:1018300040F26E31494802F001FA11F0604F04D0D5 -:10184000474B454A40F26F31F4E7009B002B7ED0B6 -:1018500024B10E9B002B7AD0072C28D809F10C005C -:10186000FFF772FE054628B96FF00205284605B05D -:10187000BDE8F08F14220021FFF7B0FD22460E993B -:1018800005F10800FFF798FD631C2B74009B1B7883 -:101890002C4403F01F0363F03F0323724AF000431C -:1018A0006B6029464846FFF77BFE0125DEE7019B7A -:1018B0001B0A4FF00008029300F10C034FF0800B5D -:1018C0004646454603930398FFF73EFE0746002829 -:1018D000CAD014220021FFF781FDB6BB9DF8043069 -:1018E0003B729DF808307B7202220E9B711E1944D8 -:1018F000B4420AD9B8180132D2B211F801EF80F817 -:1019000008E00136072AB6B2F2D1009B197801F03F -:101910001F01B44208BF4FF0400BB81841EA48110C -:101920004BEA0103037201324AF000437B603A74D0 -:1019300039464846FFF734FE0135B4422DB288F0EF -:1019400001084FF0000BBED190E70022CDE76FF009 -:1019500001058BE79C410008803F000854420008C5 -:10196000C04100082DE9F0471E46CB8A9146C3F3DB -:101970000902062A80460F4619D013460021B0B24C -:101980008DB25A1992B2052A09D9A84210D8FA8AFA -:10199000034463F30902FA820120BDE8F087A842FC -:1019A000F3D93A4419F8014094760131E8E700256B -:1019B000FB8A7C68C3F30900821F1C23B2FBF3FA85 -:1019C00003FB1A2A1FFA8AF27CB301212368002B39 -:1019D00039D1B31F03441C20B3FBF0F301339BB296 -:1019E00099420CD2BAF1000F09D14046FFF7ACFD85 -:1019F00008B1C0F800A0206008B304460022B6B2C7 -:101A00004FF0000AB54230D2691E49441346E0182F -:101A100001339BB211F801EF80F804E001351C2B73 -:101A2000ADB214D0AE42F2D8ECE74046FFF78CFDE1 -:101A3000044608B1002303607C60002CDED16FF007 -:101A40000200BDE8F087013189B21C46BEE7AE4214 -:101A5000D8D94046FFF778FD08B1C0F800A0206053 -:101A60000028ECD004460022CCE7FB8AC3F309022D -:101A7000164466F30903FB828EE70000F8B50E46B4 -:101A800015461F46044628B9144B154A15484F21E0 -:101A900002F0D4F824220021FFF7A0FC069B63602B -:101AA000079B23626A094FF6FF739A424FF00000CA -:101AB00028BF1A46A7602070A061E06197B204F1C8 -:101AC0000C05824205D100232B6027826382A3820A -:101AD000F8BD2E60013035462036F2E79841000807 -:101AE0000C3F00085442000808B528B9084B094AC1 -:101AF0007321094802F0A2F8037823B94BB2002BF6 -:101B000001DD017008BD054B024A7D21F1E700BFF0 -:101B10009C410008183F000854420008E0400008BB -:101B2000007870472DE9F7430D9EBDF828900B9D76 -:101B30009DF83040BDF8388007461946104616B962 -:101B4000B8F1000F43D11F2C41D83B78D3B9B8F17D -:101B5000070F39D839F0030339D1424631464FF6E1 -:101B6000FF70FFF73FFE4FEA092920F0010009F45A -:101B70004079400449EA0464400C44EA40244FF6AA -:101B8000FF730DE043EA0923B8F1070F43EA046449 -:101B9000F5D9FFF701FE42463146FFF723FE034623 -:101BA0008DE840012A4621463846FFF735FE0DB93B -:101BB000FFF750FD2B780133DBB21F2B88BF0023CA -:101BC0002B7003B0BDE8F0836FF00300F9E76FF00E -:101BD0000100F6E72DE9F7430E9F0B9D9DF8348039 -:101BE000BDF83C6081469DF8300007B9C6BB1F2890 -:101BF00036D899F800E0BEF1000F34D00C0244F062 -:101C000080049DF8281044EAC83444EA014444EAB8 -:101C10000E04072E44EA006415D919461046FFF752 -:101C2000BBFD32463946FFF7DDFD034601960097BE -:101C30002A4621464846FFF7EFFDB8F1010F0CD1C7 -:101C400025B9FFF707FD4FF6FF73EFE72B78013358 -:101C5000DBB21F2B88BF00232B7003B0BDE8F083DD -:101C60006FF00100F9E76FF00300F6E7C06900B11B -:101C700004307047C1690B68C3610C30FFF7F8BCD2 -:101C80002DE9F84FD0F818A0DFF86C80054616460D -:101C90001F4654464FF0000900F10C0B0CB9BDE88B -:101CA000F88FD4E90223B21A67EB0303994508BF02 -:101CB00090451FD2AB699C42214628460DD1FFF7C3 -:101CC000EDFCAB691B68AB6121465846FFF7D0FCC1 -:101CD000AC692346A2461C46E0E7FFF7DFFC236819 -:101CE000CAF8003021465846FFF7C2FC5446DAF8DD -:101CF0000030EFE72368EDE780841E002DE9F04F08 -:101D00008BB00D4614460793DDF8509082460028AC -:101D100000F06481B9F1000F00F06081531E3F2B89 -:101D200000F25C81012A03D1079B002B40F0568111 -:101D3000BAF81460F6000023B5420893099380F0C6 -:101D400053812B199E420AD2761B16F0FF0607D14B -:101D5000AB4BAC4A40F26751AB4801F06FFF2646EF -:101D6000DAF80C3023B9DAF81030002B00F0A58037 -:101D70002F2D31D8C5F1300846454FF000032CBF58 -:101D80005FFA88F8B0460093294608AB4246DAF875 -:101D90000800FFF7B7FCA6EB08074544FFB2BAF806 -:101DA000143003F10053063BDB000293DAF80C30E9 -:101DB00005934FF0300B059B002B51D087B9DAF813 -:101DC0001000002861D0002F5FD0AB4550D98F4B59 -:101DD0008C4A40F2A651BFE737464FF00008DEE7D5 -:101DE000029B23B98A4B874A4FF4B161B4E7029B47 -:101DF000E02B28BFE02306935B44AB4204931DD93C -:101E00005B1B9F4226BFDBB203930397AB4504D90C -:101E10007E4B7C4A40F291519EE70598CDF80080B8 -:101E200008ABA5EB0B01039A0430FFF76BFC039B97 -:101E30009844FF1A1D445FFA88F8FFB2049B9B4543 -:101E400004D3744B6F4A40F29B5185E7029B069A7C -:101E5000DDF810B09B1A0293059B1B680593AAE757 -:101E6000029BBB42ABD26C4B664A40F2A15173E776 -:101E7000CDF800803A46A5EB0B0108ABFFF742FC1A -:101E8000B8443D445FFA88F80027BAF81430B5EB3F -:101E9000C30F04D9614B5B4A40F2B1515CE7B8F122 -:101EA000400F04D95E4B574A40F2B25154E767B134 -:101EB0005C4B544A40F2B3514EE70093324608ABB4 -:101EC0002946DAF80800FFF71DFC731E3F2B35B2D8 -:101ED00001D8A64204DD544B544A40F235213BE779 -:101EE00060070AD00AAB03EBD401624211F8083C48 -:101EF00002F00702134101F8083C082C21D9102CEC -:101F000021D9202C8CBF08230423079A002A6DD0E6 -:101F1000B4EBC30F6CD0082C04F1FF3215D89DF838 -:101F2000203023FA02F2D10706D54FF0FF3202FA31 -:101F300004F423438DF820309DF8203089F80030D8 -:101F40004EE00123E1E70223DFE7102C11D8BDF8B2 -:101F5000203023FA02F2D20706D54FF0FF3202FA00 -:101F600004F42343ADF82030BDF82030A9F8003048 -:101F700036E0202C0ED8089921FA02F2D30705D5B5 -:101F80004FF0FF3303FA04F40C430894089BC9F89C -:101F9000003025E0402C1CD0DDE90867304639468A -:101FA000FEF7FEF8002100F0010050EA01030BD01B -:101FB000224601200021FEF7FFF8404261EB41017B -:101FC00006430F43CDE90867DDE90823C9E900238B -:101FD00006E0174B154A4FF42071BDE66FF001057E -:101FE00028460BB0BDE8F08F1D46F9E7012CA3D0C1 -:101FF000082CA1D9102CB7D9202CE5D8C6E700BFF2 -:10200000EC3F0008C43F0008544200080E4000089E -:10201000FB3F0008334000085B4000088240000896 -:10202000B0400008C8400008E2400008443F0008F3 -:10203000E040000830B585B030B9244B244A40F266 -:10204000B121244801F0FAFD23B9234B204A40F284 -:10205000B221F6E7402A04D9204B1D4A40F2B621AE -:10206000EFE722B91D4B1A4A4FF42F71E9E700241C -:10207000012A0294039417D11B788DF80830530776 -:102080000AD004AB03EBD203554213F8084C05F019 -:102090000705AC4003F8084C00910346002102A854 -:1020A000FFF730FB05B030BD082AE5D9102A03D868 -:1020B0001B88ADF80830E2E7202A02D81B6802939B -:1020C000DDE7D3E90045CDE90245D8E71C4100082A -:1020D000583F00085442000837410008E04000081B -:1020E00070B50C4600F10C05E16819B9A1602161D9 -:1020F000A18270BD0E682846FFF7BAFAE660F3E7E2 -:102100002DE9F04FD1F8009091B0C9F3C016044604 -:102110000D46CDE90223002E50D0C9F3C03BC9F3D0 -:102120000626B9F1000F80F29F8119F0C04F40F0F0 -:102130009B812B7B002B00F09781BBF1020F03D01A -:102140002278B24240F0938109F07F02BBF1020F86 -:10215000059236D119F07F0FC9F30F2A01D10AF089 -:10216000030A2B447606059A93F8038046EA0B4649 -:1021700046EA82465FEAD81346EA0A06069300F06A -:102180009A800022002310A961E90823059B00938F -:1021900067685B4652462046B847002800F08880B2 -:1021A000A7698FB9314604F10C00FFF7DBF9074648 -:1021B000D0B96FF0020011B0BDE8F08F4FF0020B04 -:1021C000AFE7C9F3074ACCE73B699E420DD03F68B1 -:1021D000002FF9D1314604F10C00FFF7C3F907468F -:1021E0000028E6D0A3693B60A761DDE90801FFF79D -:1021F000D3FAB882F97D08F01F06C1F38401711A81 -:1022000089B20FFA81FED7E90223BEF1000FB8BFF1 -:1022100001F1200EC9F30461B8BF0FFA8EFE0791D9 -:1022200052EA030100F02F81DDE90201801A61EB1F -:10223000030102460B469F480021994208BF904285 -:10224000C0F02181069B002B3FD0BEF1010F00F3AF -:102250001A8118F0400F38D0DDE90223C7E90223C4 -:10226000202200210DEB0200FFF7B8F8DDE9022380 -:10227000CDE908232B1D0A932B7BADF836A0013B3B -:10228000DBB2ADF834309DF81C308DF83A309DF853 -:1022900014308DF83B3020468DF838B08DF8396019 -:1022A000A36808A998473846FFF70CFA002082E790 -:1022B0006FF00B007FE7A76917B96FF00C007AE7A2 -:1022C0003B699E4296D03F68F6E7FB7DC8F340121B -:1022D000B2EBD31F40F0CE80C3F38403B34240F08F -:1022E000CC8006992B7B4FEA981279B3D2073CD465 -:1022F000032B40F2C580DDE90223C7E902232B7BD3 -:10230000AE1D033BDBB23246394604F10C00FFF749 -:1023100029FB002808DA39462046FFF7BFF938467E -:10232000FFF7D0F9032046E7AB883B832A7B033ACB -:10233000D2B2B88A3146FFF755FAFB7DB882DA434C -:10234000C2F3C01262F3C713FB75AFE76AB92E1D63 -:10235000013BDBB23246394604F10C00FFF702FBC9 -:102360000028D8DB2A7B013AE2E7FA8AC2F30902A5 -:10237000013B052AD9B250D8281D002399420AD919 -:1023800007EB020E013210F801CB8EF81AC00133B0 -:10239000062ADBB2F2D1DDE902898B4207F11A028B -:1023A000CDE908890A9238BF04337A680B9234BFAA -:1023B0005B1900230C93FB8AADF836A0C3F3090325 -:1023C00019449DF81C308DF83A309DF814308DF882 -:1023D0003B300023ADF834108DF838B08DF83960FB -:1023E0007B602A7BB88A013A291DFFF7FBF93B8BFA -:1023F000B882834203D1A36808A92046984708A958 -:102400002046FFF76DFE3846FFF75CF9B88A3B8B34 -:10241000984214BF11200020CDE6786810B34FF029 -:10242000060E03689BB9A2EB0E021B2A13D80332D7 -:10243000024405F1040E1F309942ACD91EF801CBBD -:1024400002F801CF01339042DBB2F5D1A3E70EF1E0 -:102450001C0E1846E5E7184B184A194840F2B3110C -:1024600001F0ECFB034696E76FF00900A3E66FF07E -:102470000A00A0E66FF00D009DE66FF00E009AE6F0 -:102480006FF00F0097E6FB7D68F386036FF3C713C9 -:10249000FB7539462046FFF701F9069B002B7FF4B8 -:1024A000D8AEFB7DC3F38402013262F38603FB7571 -:1024B00003E700BF80841E004C410008303F000845 -:1024C000544200082DE9F0414C4EB04240F081806A -:1024D0004B4CDFF830E1E56945F00075E561E469F2 -:1024E000846AD4F8007207EA0E0747F00107C4F8BF -:1024F0000072D4F8005205EA0E0545F0010545EAE0 -:102500000121C4F80012002A65D00021C4F81C1271 -:102510000F46C4F80412C4F80C12C4F8141204EBE9 -:10252000C10501310E29C5F84072C5F84472F6D1D3 -:102530004FF0000E4FF0010C964510D1826AD2F890 -:102540000032B04223F00103C2F8003253D12C4BC9 -:10255000DA6922F00072DA61DB69BDE8F0819F7808 -:102560001D8817F0010F18BFD4F804820CFA05F18A -:102570001CBF41EA0808C4F8048217F0020F1EBF0E -:10258000D4F80C8241EA0808C4F80C827F0742BFE5 -:10259000D4F814720F43C4F8147204EBC5055F68D5 -:1025A000C5F840729F68C5F84472D4F81C5229439C -:1025B000C4F81C120C330EF1010EBDE7846A002131 -:1025C000C4F81C12C4F80412C4F80C12C4F8141293 -:1025D000AEE7002AF2D1836A0022C3F84022C3F892 -:1025E0004422C3F80422C3F814220122C3F80C22A7 -:1025F000C3F81C22A2E7BDE8F08100BFE022002062 -:10260000001002400000FFFF184A916A08B58B686D -:102610008B6013F0010105D013F00C0F14BF4FF4C1 -:1026200080310121D80506D513F4406F14BF41F461 -:10263000003141F00201D80306D513F4402F14BF36 -:1026400041F4802141F00401D3690BB10748984758 -:10265000202383F311880021054800F087FE002322 -:1026600083F31188BDE8084001F088B8E02200201B -:10267000E822002038B5124CA36ADD68AA0712D000 -:102680005A6922F002025A61A36913B1012120465E -:102690009847202383F3118800210A4800F066FE42 -:1026A000002383F31188EB0606D5A36A1021D960B5 -:1026B000236A0BB102489847BDE8384001F05EB884 -:1026C000E0220020F022002038B5124CA36A1D69D8 -:1026D000AA0712D05A6922F010025A61A36913B1F5 -:1026E000022120469847202383F3118800210A48BD -:1026F00000F03CFE002383F31188EB0606D5A36AA5 -:1027000010211961236A0BB102489847BDE838408F -:1027100001F034B8E0220020F022002038B50F4C40 -:10272000A36A5D685D602A070AD5032222701A68D1 -:1027300022F002021A60636A13B100212046984712 -:102740006B0706D5A36A9969236A13B10904034884 -:102750009847BDE8384001F011B800BFE0220020E2 -:1027600010B50F4C204600F03DFA0E4BA3620B2132 -:10277000132000F017FA0B21142000F013FA0B219C -:10278000152000F00FFA0B21162000F00BFA0023A1 -:1027900020461A460E21BDE81040FFF793BE00BF49 -:1027A000E0220020006400400F4B984210B5044620 -:1027B00005D10E4BDA6942F00072DA61DB69A36A77 -:1027C00001221A60A36A5A68D20707D56268516865 -:1027D0001268D9611A60064A5A6110BD01210820A9 -:1027E00000F07CFCEEE700BFE02200200010024079 -:1027F0005B87010003291AD8DFE801F0020A0F14F1 -:10280000836A9B6813F0E05F14BF012000207047CB -:10281000836A9868C0F380607047836A9868C0F3E1 -:10282000C0607047836A9868C0F3007070470020EA -:102830007047000010B503291FD8DFE801F0021F20 -:102840002327816A8B68C3F30163183301EB0313F9 -:10285000107881061ED55468C0F30011490041EA82 -:10286000C40141F0040100F00F00586090689860C6 -:10287000D268DA6041F00101196010BD836A03F586 -:10288000C073E5E7836A03F5C873E1E7836A03F57C -:10289000D073DDE79488C0F30011490041EA445148 -:1028A000E1E7000001290CD003D3022910D0002059 -:1028B0007047836ADA68920701D1186903E0012042 -:1028C0007047836AD86810F0030018BF0120704772 -:1028D000836AF2E710B539B9836AD96889071BD1D1 -:1028E0001B699B0704D110BD012915D0022948D1CD -:1028F000816AD1F8C031D1F8C401D1F8C84114615E -:10290000D1F8CC41546120240C610C69A40717D183 -:102910004C6944F0100412E0816AD1F8B031D1F86A -:10292000B401D1F8B8411461D1F8BC4154612024FC -:10293000CC60CC68A40703D14C6944F002044C611C -:1029400011795C0864F304119C0864F3451111715A -:1029500089064BBF91681189DB085B0D4CBF63F39F -:102960001C0163F30A01137948BF916060F303030C -:1029700013714FEA10234FEA104058BF11811370B2 -:10298000508010BD002304491A465A50C818083315 -:10299000802B4260F9D170470C2300200268436805 -:1029A0001143016003B1184770470000024A1368E1 -:1029B00043F0C0031360704700380140024A1368B7 -:1029C00043F0C00313607047004400402DE9F04716 -:1029D000C66D3768F46934620546200719D014F0D3 -:1029E000080F0CBF00218021E20748BF41F0200101 -:1029F000A30748BF41F04001600748BF41F4807120 -:102A0000202383F31188281DFFF7C8FF002383F3D9 -:102A10001188E2050AD5202383F311884FF4007151 -:102A2000281DFFF7BBFF002383F311884FF0200917 -:102A30004FF0000A14F0200831D13B0616D54FF0B4 -:102A4000200905F1380A200610D589F3118850466F -:102A500000F04CFA00282FDA0821281DFFF79EFF0E -:102A600027F080033360002383F3118879060DD5A6 -:102A700062060BD5202383F31188EA6C2B6D9A42F2 -:102A800001D12B6CF3B9002383F31188E30621D520 -:102A9000AA6E1369F3B15069BDE8F047184789F38E -:102AA0001188B38C95F864102846194000F0AAFAF2 -:102AB0008AF31188F469BDE780B2308588F3118804 -:102AC000F469C0E71021281D27F04007FFF766FFD3 -:102AD0003760D8E7BDE8F08708B50348FFF776FF11 -:102AE000BDE8084000F04ABE8C23002008B503482A -:102AF000FFF76CFFBDE8084000F040BEF82300205F -:102B000037B51D4C1D4D204600F070FA009404F1BD -:102B10001400002320221A4900F032F920220094E8 -:102B200004F13800174B184900F0ACF9174BE36576 -:102B30002566174C0C21252000F034F8204600F0C3 -:102B400055FA04F11400009400232022114900F0EA -:102B500017F904F1380000940F4B1049202200F0BF -:102B600091F90F4BE3650C212620256603B0BDE8E3 -:102B7000304000F017B800BF8C2300200051250220 -:102B800064240020AD290008A4240020003801405E -:102B9000F823002084240020BD290008C42400203C -:102BA0000044004000F1604300F01F02400903F5BB -:102BB000614309018000C9B200F1604083F800134D -:102BC00000F5614001239340C0F8803103607047F5 -:102BD00000F16040090100F56D40C9B2017670470F -:102BE000FFF7BEBD00F108020123037082600023DD -:102BF000C26000F110024360026142618361C361FF -:102C0000036243627047000010B52023044683F33B -:102C10001188022303704160FFF7C6FD0323237070 -:102C2000002383F3118810BD2DE9F0411F460446AF -:102C30000D461646202383F3118800F108082378F7 -:102C4000042B0ED029462046FFF7D4FD48B120467C -:102C500032462946FFF7EEFD002080F31188BDE8DB -:102C6000F0813946404600F065FB0028E7D000239C -:102C700083F31188BDE8F0812DE9F0411F46044639 -:102C80000D461646202383F3118800F1100823789F -:102C9000042B0ED029462046FFF704FE48B12046FB -:102CA00032462946FFF716FE002080F31188BDE862 -:102CB000F0813946404600F03DFB0028E7D0002374 -:102CC00083F31188BDE8F081F8B51546826806697E -:102CD000AA420B46816938BF8568761AB542044618 -:102CE00007D218462A46FEF767FBA3692B44A36167 -:102CF0000DE011D932461846FEF75EFBAF1B3A468F -:102D0000E1683044FEF758FBE2683A44A261A368E8 -:102D10005B1BA3602846F8BD18462A46FEF74CFB0D -:102D2000E368E4E783682DE9F041044693421546E1 -:102D3000266938BF85684069361AB5420F4606D203 -:102D40002A46FEF739FB63692B4463610DE012D913 -:102D50003246A5EB0608FEF72FFB4246B919E0689C -:102D6000FEF72AFBE26842446261A3685B1BA36032 -:102D70002846BDE8F0812A46FEF71EFBE368E4E73B -:102D800010B50A440024C361029B00604060846067 -:102D9000C160816141610261036210BD08B5826951 -:102DA0004369934201D1826882B9826801328260AC -:102DB0005A1C42611970426903699A4201D3C3687F -:102DC0004361002100F0C6FA002008BD4FF0FF303B -:102DD00008BD000070B5202304460E4683F3118819 -:102DE000A568A5B1A368A269013BA360531CA361B8 -:102DF00015782269934224BFE368A361E3690BB1AC -:102E000020469847002383F31188284670BD314639 -:102E1000204600F08FFA0028E2DA85F3118870BDB1 -:102E20002DE9F74F05460F4690469A46D0F81C907C -:102E3000202686F311884FF0000B144664B1224619 -:102E400039462846FFF740FF034668B951462846F1 -:102E500000F070FA0028F1D0002383F31188A8EB6A -:102E6000040003B0BDE8F08FB9F1000F03D001906A -:102E70002846C847019B8BF31188E41A1F4486F348 -:102E80001188DBE7C16081614161C3611144009B2E -:102E9000006040608260016103627047F8B50446DB -:102EA0000E461746202383F31188A568A5B1A368B1 -:102EB000013BA36063695A1C62611E7023696269E9 -:102EC0009A4224BFE3686361E3690BB120469847E7 -:102ED000002080F31188F8BD3946204600F02AFA18 -:102EE0000028E2DA85F31188F8BD000083694269A1 -:102EF0009A4210B501D182687AB982680132826043 -:102F00005A1C82611C7803699A4201D3C3688361A9 -:102F1000002100F01FFA204610BD4FF0FF3010BD19 -:102F20002DE9F74F05460F4690469A46D0F81C907B -:102F3000202686F311884FF0000B144664B1224618 -:102F400039462846FFF7EEFE034668B95146284643 -:102F500000F0F0F90028F1D0002383F31188A8EBEA -:102F6000040003B0BDE8F08FB9F1000F03D0019069 -:102F70002846C847019B8BF31188E41A1F4486F347 -:102F80001188DBE7026843681143016003B1184709 -:102F9000704700001430FFF743BF00004FF0FF33CD -:102FA0001430FFF73DBF00003830FFF7B9BF000015 -:102FB0004FF0FF333830FFF7B3BF00001430FFF796 -:102FC00009BF00004FF0FF311430FFF703BF0000CE -:102FD0003830FFF763BF00004FF0FF323830FFF7A3 -:102FE0005DBF000000207047FFF78ABD044B0360FF -:102FF000002343608360C36001230374704700BFF4 -:103000009042000838B5C36904460D461BB9042137 -:103010000844FFF7B7FF294604F11400FFF7BEFE8E -:10302000002806DA201D4FF48061BDE83840FFF724 -:10303000A9BF38BD024B00221B605B609A607047DD -:10304000E4240020002303748268054B1B68996800 -:103050009142FBD25A68036042601060586070472A -:10306000E424002008B5202383F31188037C032B7C -:1030700005D0042B0DD02BB983F3118808BD43690B -:1030800000221A604FF0FF334361FFF7DBFF00239C -:10309000F2E790E80C001A6002685360F2E7000063 -:1030A000002303748268054B1B6899689142FBD822 -:1030B0005A6803604260106058607047E424002042 -:1030C000054B19690874186802681A605360186122 -:1030D00001230374FDF798BAE424002030B54B1C9B -:1030E00087B005460A4C10D023690A4A01A800F0AF -:1030F00059F92846FFF7E4FF049B13B101A800F03B -:103100006BF92369586907B030BDFFF7D9FFF8E7BD -:10311000E42400206530000838B50C4D41612B696E -:1031200081689A689142044603D8BDE83840FFF7A9 -:1031300089BF1846FFF786FF01232C6101462374DF -:103140002046BDE83840FDF75FBA00BFE424002008 -:10315000044B1A681B6990689B68984294BF0020D2 -:1031600001207047E424002010B5084C2368206932 -:103170001A6822605460012223611A74FFF790FFDD -:1031800001462069BDE81040FDF73EBAE424002066 -:1031900008B5FFF7DDFF18B1BDE80840FFF7E4BF51 -:1031A00008BD0000FEE7000010B5174CFFF742FF16 -:1031B00000F0EAF880221549204600F06FF801235C -:1031C00044F8180C0374124B124AD96821F4E061D8 -:1031D0000904090C0A431049DA60CA6842F0807297 -:1031E000CA600E490A6842F001020A601022DA77CA -:1031F000202283F82220002383F3118862B6084836 -:10320000BDE8104000F06CB80C250020B842000862 -:1032100000ED00E00003FA05F0ED00E0001000E032 -:10322000C0420008F8B50F4C226A013222622246E1 -:1032300052F8141F9142154606D08B68013B8B60F3 -:10324000202663699A6802B1F8BD1968DF68DA6000 -:103250004D60616182F311881869B84786F311885F -:10326000EFE700BFE4240020EFF3118020B9EFF373 -:103270000583202282F311887047000010B558B9E9 -:10328000EFF30584C4F3080414B180F3118810BD72 -:10329000FFF77EFF84F3118810BD000082600222D8 -:1032A00002740022427470478368A3F17C0243F8E1 -:1032B0000C2C026943F83C2C426943F8382C074A2D -:1032C00043F81C2CC26843F8102C022203F8082C87 -:1032D000002203F8072CA3F118007047210600080C -:1032E00010B5202383F31188FFF7DEFF0021044689 -:1032F000FFF712FF002383F31188204610BD000062 -:10330000024B1B6958610F20FFF7DABEE42400204E -:10331000202383F31188FFF7F3BF000008B50146AF -:10332000202383F311880820FFF7D8FE002383F3BE -:10333000118808BD49B1064B42681B6918605A6084 -:10334000136043600420FFF7C9BE4FF0FF307047A1 -:10335000E42400200368984206D01A680260506096 -:1033600059611846FFF76EBE7047000038B5044635 -:103370000D462068844200D138BD036823605C603C -:103380004561FFF75FFEF4E7054B03F114025A6154 -:103390009A614FF0FF32DA6100221A62704700BF73 -:1033A000E424002010B5C2600A4A036153699C6896 -:1033B000A1420CD85C680360446020605860816062 -:1033C0009868411A99604FF0FF33D36110BD091B13 -:1033D0001B68ECE7E4240020036881689A680A44CB -:1033E0009A604268136003685A600023C360024B0E -:1033F0004FF0FF32DA617047E4240020002070476C -:10340000FEE70000704700004FF0FF3070470000FB -:10341000BFF34F8F024AD368DB07FCD4704700BF6D -:103420000020024008B5074B1B7853B9FFF7F0FFA7 -:10343000054B1A69120641BF044A5A6002F18832EC -:103440005A6008BD70260020002002402301674515 -:1034500008B5054B1B7833B9FFF7DAFF034A136948 -:1034600043F08003136108BD702600200020024055 -:103470007F289ABF00F58030C0020020704700000E -:103480004FF4006070470000802070477F2808B527 -:103490000BD8FFF7EDFF00F500630268013204D19D -:1034A00004308342F9D1012008BD002008BD00008E -:1034B0007F2838B5044624D800F0B6F8124D2860AD -:1034C000FFF7A6FFFFF7AEFF104BF322DA600222F0 -:1034D0001A612046FFF7CCFF58611A6942F040029A -:1034E0001A61FFF795FF4FF4006100F0FBF8FFF75A -:1034F000AFFF00F099F828602046BDE83840FFF79C -:10350000C5BF002038BD00BF742600200020024047 -:103510002DE9F84312F00103144606D0204B40F287 -:103520004B221A600020BDE8F88385181D4A954299 -:1035300004D91B4A4FF414711160F3E7FFF772FFCF -:10354000FFF766FFDFF86C80451A4FF00109012C88 -:1035500005EB01060F4604D8FFF77AFF0120BDE80E -:10356000F883C8F8109031F8023B3380FFF750FF22 -:103570000020C8F8100033883A889BB29A420DD0D8 -:10358000074B40F267221A60074B1E60074B1C6016 -:10359000074B1F60FFF75CFFBDE8F883023CD6E7EE -:1035A0006C260020FFFF030860260020682600200C -:1035B0006426002000200240084908B50B7828B195 -:1035C00053B9FFF72FFF01230B7008BD23B1BDE8EE -:1035D00008400870FFF73CBF08BD00BF7026002000 -:1035E00038B5FFF741FE0D4B0D4A1C6A11684FF4C8 -:1035F0007A7303FB04F38B420A49D1E9004504D2F4 -:10360000003445F10105C1E90045E41845F1000524 -:103610001360FFF733FE2046294638BDE42400201E -:10362000782600208026002008B5FFF7D9FF4FF448 -:103630007A720023FCF7CCFD08BD00BF10B5024430 -:10364000064B0439D2B2904200D110BD441C00B2E6 -:1036500053F8200041F8040FE0B2F4E7502800408E -:10366000104B30B51C6A240407D41C6A44F440741F -:103670001C621C6A44F400441C620B4C236843F433 -:10368000807323600244094B0439D2B2904200D1C6 -:1036900030BD441C00B251F8045F43F82050E0B242 -:1036A000F4E700BF001002400070004050280040C6 -:1036B00007B5012201A90020FFF7C0FF019803B060 -:1036C0005DF804FB13B50446FFF7F2FFA04206D0F5 -:1036D00002A9012241F8044D0020FFF7C1FF02B00A -:1036E00010BD000070470000074B45F255521A60AC -:1036F00002225A6040F6FF729A604CF6CC421A6081 -:10370000024B01221A7070470030004089260020C9 -:10371000034B1B781BB1034B4AF6AA221A60704771 -:103720008926002000300040034B1B689B0042BFED -:10373000024B01221A707047241002408826002094 -:10374000024B4FF080721A60704700BF2410024095 -:10375000014B1878704700BF88260020064A53683E -:1037600023F001035360EFF30983683383F309887F -:10377000002383F31188704730EF00E010B5202359 -:1037800083F31188104B5B6813F4006318D0F1EEDB -:10379000103AEFF309844FF0807344F84C3C0B4B24 -:1037A000DB6844F8083CA4F1680383F30988FFF759 -:1037B000CFFC18B1064B44F8503C10BD054BFAE75E -:1037C00083F3118810BD00BF00ED00E030EF00E092 -:1037D000310600083406000870470000FEE70000CC -:1037E000084A094B09498B4204D3094A00219342F4 -:1037F00005D3704752F8040F43F8040BF3E743F87E -:10380000041BF4E740440008902600209026002086 -:10381000902600204B6843608B688360CB68C36050 -:103820000B6943614B6903628B6943620B680360F8 -:103830007047000008B5194B9A6A42F4FC029A627C -:103840009A6A22F4FC029A629A6A5A6942F4FC0269 -:103850005A61134A5B6911464FF09040FFF7DAFF57 -:10386000104802F11C01FFF7D5FF0F4802F13801A3 -:10387000FFF7D0FF0D4802F15401FFF7CBFF0C48D2 -:1038800002F17001FFF7C6FF0A4802F18C01FFF751 -:10389000C1FFBDE8084000F065B800BF001002405D -:1038A000E04200080004004800080048000C0048FE -:1038B000001000480014004808B500F08FF9FFF729 -:1038C00073FCBDE80840FFF72FBF00007047000001 -:1038D00010B5214CA26A62F4FC02A262A26A02F450 -:1038E000FC02A2624FF0FF31A26A226921612269C3 -:1038F000002222612069E068E160E168E260E1683D -:10390000E169164841F08051E161E169016841F4E3 -:1039100080710160216A01F44071B1F5407F1EBFE2 -:103920004FF4803323622262236A1B0407D4236A84 -:1039300043F440732362236A43F40043236200F09C -:103940002DF9A369064A43F00103A361A369136833 -:1039500043F02003136010BD0010024000700040CF -:10396000000001401C4B1A6842F001021A601A68FC -:103970009007FCD55A6822F003025A605A6812F088 -:103980000C02FBD1196801F0F90119605A601A683C -:1039900042F480321A601A689103FCD50F4A5A60CB -:1039A0004FF40452DA6230221A631A6842F08072CD -:1039B0001A601A689201FCD5094A122111605A68EE -:1039C00042F002025A605A6802F00C02082AFAD148 -:1039D0001A6B1A63704700BF0010024000241D00DC -:1039E00000200240084A08B5536911680B4003F0F3 -:1039F0000103536123B1054A13680BB1506898471E -:103A0000BDE80840FFF7BABE000401400C230020C7 -:103A1000084A08B5536911680B4003F0020353616B -:103A200023B1054A93680BB1D0689847BDE80840B8 -:103A3000FFF7A4BE000401400C230020084A08B58B -:103A4000536911680B4003F00403536123B1054A25 -:103A500013690BB150699847BDE80840FFF78EBE67 -:103A6000000401400C230020084A08B5536911687E -:103A70000B4003F00803536123B1054A93690BB16E -:103A8000D0699847BDE80840FFF778BE00040140C0 -:103A90000C230020084A08B5536911680B4003F055 -:103AA0001003536123B1054A136A0BB1506A98475A -:103AB000BDE80840FFF762BE000401400C2300206F -:103AC000174B10B55C691A68144004F478725A6197 -:103AD000A30604D5134A936A0BB1D06A98476006CF -:103AE00004D5104A136B0BB1506B9847210604D5CF -:103AF0000C4A936B0BB1D06B9847E20504D5094A89 -:103B0000136C0BB1506C9847A30504D5054A936C10 -:103B10000BB1D06C9847BDE81040FFF72FBE00BF37 -:103B2000000401400C2300201A4B10B55C691A6890 -:103B3000144004F47C425A61620504D5164A136DA0 -:103B40000BB1506D9847230504D5134A936D0BB103 -:103B5000D06D9847E00404D50F4A136E0BB1506E38 -:103B60009847A10404D50C4A936E0BB1D06E9847C8 -:103B7000620404D5084A136F0BB1506F98472304B1 -:103B800004D5054A936F0BB1D06F9847BDE810403C -:103B9000FFF7F4BD000401400C230020062108B506 -:103BA0000846FEF7FFFF06210720FEF7FBFF062170 -:103BB0000820FEF7F7FF06210920FEF7F3FF062194 -:103BC0000A20FEF7EFFF06211720FEF7EBFF062184 -:103BD0002820BDE80840FEF7E5BF000008B5FFF764 -:103BE00077FEFEF7CFFEFEF7FBFFFFF7FDF9FFF7CD -:103BF0006DFEBDE8084000F001B8000000F00EB80E -:103C000008B5202383F31188FFF70CFB002383F30F -:103C10001188BDE80840FFF7B1BD0000054B064A1A -:103C20005A6000229A6007221A6008210B20FEF7D2 -:103C3000CFBF00BF10E000E03F1901001FB51C46D8 -:103C4000094B1B680546D86852B1084B02928DE8B3 -:103C50000A0022462B460649FDF718FC00F042F800 -:103C6000044B1A46F2E700BF1011002088430008F9 -:103C700095430008143E000810B5013902449042F3 -:103C800001D1002010BD10F8013B11F8014FA342F3 -:103C9000F5D0181B10BD00002DE9F84307468846F3 -:103CA00091461E468BB10D46A8EB0500B54207EBC9 -:103CB000000402D20020BDE8F8833246494620467F -:103CC000FFF7DAFF18B1013DEEE7BDE8F8832046C3 -:103CD000BDE8F883034611F8012B03F8012B002AF5 -:103CE000F9D1704708B5062000F02CF80120FFF745 -:103CF00087FB00001F2938B504460D4604D916235A -:103D000003604FF0FF3038BD426C12B152F82130E1 -:103D10004BB9204600F030F82A4601462046BDE85F -:103D2000384000F017B8012B0AD0591C03D11623D4 -:103D30000360012038BD002442F8254028469847FA -:103D4000002038BD024B01461868FFF7D3BF00BF03 -:103D50001011002038B5074C0023054608461146CF -:103D60002360FFF751FB431C02D1236803B12B6092 -:103D700038BD00BF8C260020FFF740BB40A2E4F115 -:103D8000646891064E6F20617070207369670A0045 -:103D9000426164206677206C656E677468202575C3 -:103DA0000A0042616420626F6172645F6964202569 -:103DB000752073686F756C642062652025750A0034 -:103DC0004261642066772064657363726970746F02 -:103DD00072206C656E6774682025750A0042616404 -:103DE0002061707020435243203078253038783A73 -:103DF000307825303878203078253038783A307867 -:103E0000253038780A00476F6F64206669726D77D5 -:103E10006172650A00000000726563656976656419 -:103E20005F756E697175655F69645F6C656E203C76 -:103E30002055415643414E5F50524F544F434F4CD3 -:103E40005F44594E414D49435F4E4F44455F49449D -:103E50005F414C4C4F434154494F4E5F554E495181 -:103E600055455F49445F4D41585F4C454E47544866 -:103E7000002E2E2F2E2E2F546F6F6C732F41505FFC -:103E8000426F6F746C6F616465722F63616E2E6335 -:103E9000707000616C6C6F63617465645F6E6F64F9 -:103EA000655F6964203C3D20313237006F72672EB8 -:103EB0006172647570696C6F742E663330335F4D58 -:103EC0006174656B47505300766F69642068616E5A -:103ED000646C655F616C6C6F636174696F6E5F7257 -:103EE0006573706F6E73652843616E617264496EAD -:103EF0007374616E63652A2C2043616E6172645233 -:103F0000785472616E736665722A290063616E610E -:103F10007264496E6974000063616E617264536516 -:103F2000744C6F63616C4E6F64654944000000001F -:103F300063616E61726448616E646C65527846724A -:103F4000616D650063616E6172644465636F646591 -:103F50005363616C6172000063616E617264456EEF -:103F6000636F64655363616C61720000696E6372B4 -:103F7000656D656E745472616E7366657249440056 -:103F8000656E717565756554784672616D6573000F -:103F900070757368547851756575650070726570D9 -:103FA000617265466F724E6578745472616E7366A5 -:103FB00065720000636F7079426974417272617951 -:103FC000000000006465736361747465725472610B -:103FD0006E736665725061796C6F616400000000F9 -:103FE00066726565426C6F636B0000006269745FA6 -:103FF0006C656E677468203E20300072656D616983 -:104000006E696E675F62697473203E203000696E6E -:104010007075745F6269745F6F6666736574203E65 -:104020003D20626C6F636B5F6269745F6F6666737D -:10403000657400626C6F636B5F656E645F62697468 -:104040005F6F6666736574203E20626C6F636B5FA2 -:104050006269745F6F66667365740072656D61692D -:104060006E696E675F6269745F6C656E6774682005 -:104070003C3D2072656D61696E696E675F6269744F -:104080007300696E7075745F6269745F6F666673E2 -:104090006574203C3D207472616E736665722D3EBE -:1040A0007061796C6F61645F6C656E202A203800E6 -:1040B0006F75747075745F6269745F6F666673653F -:1040C00074203C3D2036340072656D61696E696E06 -:1040D000675F6269745F6C656E677468203D3D2040 -:1040E000300028726573756C74203E2030292026BC -:1040F000262028726573756C74203C3D2036342967 -:104100002026262028726573756C74203C3D206241 -:1041100069745F6C656E6774682900006465737408 -:10412000696E6174696F6E20213D202828766F6961 -:1041300064202A2930290076616C756520213D2094 -:104140002828766F6964202A293029006F666673F3 -:1041500065745F77697468696E5F626C6F636B200A -:104160003C2028333255202D205F5F6275696C74C6 -:10417000696E5F6F66667365746F66202843616E53 -:10418000617264427566666572426C6F636B2C2067 -:1041900064617461292900006F75745F696E732012 -:1041A000213D202828766F6964202A2930290000C3 -:1041B0007372635F6C656E203E2030550000000016 -:1041C0002863616E5F696420262030783146464658 -:1041D000464646465529203D3D2063616E5F696431 -:1041E00000000000616C6C6F6361746F722D3E7330 -:1041F0007461746973746963732E63757272656E2A -:10420000745F75736167655F626C6F636B73203E8B -:10421000203000007472616E736665725F6964209D -:10422000213D202828766F6964202A293029000042 -:1042300073746174652D3E6275666665725F626C4B -:104240006F636B73203D3D202828766F6964202AB8 -:10425000293029002E2E2F2E2E2F6D6F64756C6540 -:10426000732F6C696263616E6172642F63616E614A -:1042700072642E63006974656D2D3E6672616D65B2 -:104280002E646174615F6C656E203E20300000001A -:1042900000000000B12F00089D2F0008D92F000852 -:1042A000C52F0008D12F0008BD2F0008A92F000836 -:1042B000952F0008E52F00086D61696E0000000071 -:1042C000D8420008282500206026002001000000B8 -:1042D000A53100080000000069646C650000000062 -:1042E000A001A80200000000FAAABEAA5000140013 -:1042F000EFFF000000770000709709000000A000A9 -:1043000000000000AAAAFAAA00005000FFFF000067 -:104310000000000000770000000000000000000026 -:10432000AAAAAAAA00000000FFFF000000000000E7 -:10433000000000000000000000000000AAAAAAAAD5 -:1043400000000000FFFF000000000000000000006F -:104350000000000000000000AAAAAAAA00000000B5 -:10436000FFFF00000000000000000000000000004F -:1043700000000000AAAAAAAA00000000FFFF000097 -:1043800000000000000000002C2066756E63746958 -:104390006F6E3A2000617373657274696F6E2022CC -:1043A000257322206661696C65643A2066696C65D4 -:1043B00020222573222C206C696E652025642573CC -:1043C00025730A003CBEFF7F0100000000000000D2 -:1043D0006400000000000000FE2A0100D20400007A -:1043E0001411002000000000000000000000000088 -:1043F00000000000000000000000000000000000BD -:1044000000000000000000000000000000000000AC -:10441000000000000000000000000000000000009C -:10442000000000000000000000000000000000008C -:10443000000000000000000000000000000000007C -:044440000000000078 +:1000000000090020A5040008E1140008611400089C +:10001000B9140008611400088D140008A704000832 +:10002000A7040008A7040008A704000881350008F9 +:10003000A7040008A7040008A7040008B93A0008AC +:10004000A7040008A7040008A7040008A7040008E4 +:10005000A7040008A7040008513800087D380008EC +:10006000A9380008D538000801390008A70400089D +:10007000A7040008A7040008A7040008A7040008B4 +:10008000A7040008A7040008A70400082924000802 +:1000900095240008E92400083D2500082D390008B2 +:1000A000A7040008A7040008A7040008A704000884 +:1000B000A7040008A7040008A7040008A704000874 +:1000C000A7040008A7040008A7040008A704000864 +:1000D000A70400088129000895290008A704000842 +:1000E00095390008A7040008A7040008A704000821 +:1000F000A7040008A7040008A7040008A704000834 +:10010000A7040008A7040008A7040008A704000823 +:10011000A7040008A7040008A7040008A704000813 +:10012000A7040008A7040008A7040008A704000803 +:10013000A7040008A7040008A7040008A7040008F3 +:10014000A7040008A7040008A7040008A7040008E3 +:10015000A7040008A7040008A7040008A7040008D3 +:10016000A7040008A7040008A7040008A7040008C3 +:10017000A7040008A7040008A7040008A7040008B3 +:10018000A7040008A7040008A7040008A7040008A3 +:10019000A7040008A7040008A7040008A704000893 +:1001A00053B94AB9002908BF00281CBF4FF0FF31DE +:1001B0004FF0FF3000F074B9ADF1080C6DE904CEDA +:1001C00000F006F8DDF804E0DDE9022304B0704732 +:1001D0002DE9F047089D04468E46002B4DD18A42FA +:1001E000944669D9B2FA82F252B101FA02F3C2F12D +:1001F000200120FA01F10CFA02FC41EA030E9440BE +:100200004FEA1C48210CBEFBF8F61FFA8CF708FBDE +:1002100016E341EA034306FB07F199420AD91CEBB6 +:10022000030306F1FF3080F01F81994240F21C81E8 +:10023000023E63445B1AA4B2B3FBF8F008FB103330 +:1002400044EA034400FB07F7A7420AD91CEB040465 +:1002500000F1FF3380F00A81A74240F20781644435 +:10026000023840EA0640E41B00261DB1D4400023BA +:10027000C5E900433146BDE8F0878B4209D9002D1E +:1002800000F0EF800026C5E9000130463146BDE8A8 +:10029000F087B3FA83F6002E4AD18B4202D3824212 +:1002A00000F2F980841A61EB030301209E46002DC1 +:1002B000E0D0C5E9004EDDE702B9FFDEB2FA82F216 +:1002C000002A40F09280A1EB0C014FEA1C471FFA74 +:1002D0008CFE0126200CB1FBF7F307FB131140EA5B +:1002E00001410EFB03F0884208D91CEB010103F128 +:1002F000FF3802D2884200F2CB804346091AA4B2EA +:10030000B1FBF7F007FB101144EA01440EFB00FEBD +:10031000A64508D91CEB040400F1FF3102D2A64522 +:1003200000F2BB800846A4EB0E0440EA03409CE7C1 +:10033000C6F12007B34022FA07FC4CEA030C20FA6E +:1003400007F401FA06F31C43F9404FEA1C4900FA8E +:1003500006F3B1FBF9F8200C1FFA8CFE09FB18110B +:1003600040EA014108FB0EF0884202FA06F20BD97E +:100370001CEB010108F1FF3A80F08880884240F2CE +:100380008580A8F102086144091AA4B2B1FBF9F012 +:1003900009FB101144EA014100FB0EFE8E4508D90D +:1003A0001CEB010100F1FF346CD28E456AD9023892 +:1003B000614440EA0840A0FB0294A1EB0E01A14277 +:1003C000C846A64656D353D05DB1B3EB080261EBE5 +:1003D0000E0101FA07F722FA06F3F1401F43C5E9BF +:1003E000007100263146BDE8F087C2F12003D840F5 +:1003F0000CFA02FC21FA03F3914001434FEA1C4737 +:100400001FFA8CFEB3FBF7F007FB10360B0C43EA28 +:10041000064300FB0EF69E4204FA02F408D91CEBD8 +:10042000030300F1FF382FD29E422DD902386344D6 +:100430009B1B89B2B3FBF7F607FB163341EA034176 +:1004400006FB0EF38B4208D91CEB010106F1FF38C5 +:1004500016D28B4214D9023E6144C91A46EA0046BC +:1004600038E72E46284605E70646E3E61846F8E64E +:100470004B45A9D2B9EB020864EB0C0E0138A3E797 +:100480004646EAE7204694E74046D1E7D0467BE778 +:10049000023B614432E7304609E76444023842E7F0 +:1004A000704700BF02E000F000F8FEE772B63A487D +:1004B00080F30888394880F3098839484EF6085196 +:1004C000CEF20001086040F20000CCF200004EF6CF +:1004D0003471CEF200010860BFF34F8FBFF36F8F0E +:1004E00040F20000C0F2F0004EF68851CEF200015A +:1004F0000860BFF34F8FBFF36F8F4FF00000E1EE46 +:10050000100A4EF63C71CEF200010860062080F31E +:100510001488BFF36F8F03F0B3F803F08FF803F084 +:10052000C1F84FF055301F491B4A91423CBF41F87A +:10053000040BFAE71C49194A91423CBF41F8040BED +:10054000FAE71A491A4A1B4B9A423EBF51F8040B6C +:1005500042F8040BF8E700201749184A91423CBFC3 +:1005600041F8040BFAE703F06DF803F0D7F8144CE8 +:10057000144DAC4203DA54F8041B8847F9E700F045 +:1005800041F8114C114DAC4203DA54F8041B884772 +:10059000F9E703F055B80000000900200011002021 +:1005A000000000080001002000090020F83C0008BD +:1005B00000110020201100202011002028260020FA +:1005C000A0010008A0010008A0010008A001000887 +:1005D0002DE9F04F2DED108AC1F80CD0C3689D466F +:1005E000BDEC108ABDE8F08F002383F31188284604 +:1005F000A047002002F04CFDFEE702F0D1FC00DF36 +:10060000FEE700002DE9F04102F062FF074602F02C +:10061000ADFF054600283ED12B4B9F423BD0013316 +:100620009F423BD0294B27F0FF029A423AD1F8B2C1 +:1006300000F054FAA84642F2107400F059FC08B1D8 +:100640000024A04600F050FA064678B384BB464624 +:1006500035B11F4B9F4203D002F080FF0024264695 +:10066000002002F03FFF1B4B1B6913F0400322D018 +:100670000EB100F031F800F05FFC00F031FE00F048 +:1006800031FF0546CCB100F02DFF401BA04214D92C +:1006900000F022F8F3E7A8460024CEE704464FF026 +:1006A0000108CAE780464FF47A74C6E70446CFE7EC +:1006B0004FF47A74CCE71C46DDE700F0DDFC012046 +:1006C00002F0ECFCDEE700BF010007B0000008B05C +:1006D000263A09B00004004838B51D4A1D4B196878 +:1006E000013134D004339342F9D11B4C194DD4F865 +:1006F0000428AA422BD3194B9B6803F1006303F52E +:10070000D0439A4223D202F0FDFE02F00FFF0020F8 +:1007100000F000FE124B0220187000F037FE114B63 +:10072000DA690022DA61D96999699A619B6972B6BE +:100730004FF0E0232021C3F8085DD4F80038D4F846 +:10074000042881F311889D4683F30888104738BD3B +:100750002068000800680008006000080011002000 +:100760002011002000100240094A136849F2690074 +:1007700099B21B0C00FB01331360064B186844F25E +:10078000506182B2000C01FB0200186080B2704719 +:100790001C1100201811002010B500211022044661 +:1007A00000F00EFE034B03CB206061601868A06070 +:1007B00010BD00BFACF7FF1F2DE9F043224DBBB0C9 +:1007C00000F090FEAB6840F2ED22C31A934232D99A +:1007D00006AFA8602B4628220021384601F05EFBB8 +:1007E00005F10E0000F0E4FD002604465FFA80F9F2 +:1007F00005F10E08F3B2F100994501F1280107D97E +:1008000008EB06030822384601F048FB0136F1E701 +:1008100008230122CDE9023205340C4B0193A4B226 +:1008200030230093CDE9047405A3D3E90023297B89 +:10083000074801F04BF93BB0BDE8F083AFF300800F +:1008400078F6339F93CACD8D682100207521002052 +:100850003C21002070B50D4614461E4601F0CCF830 +:1008600050B9022E10D1012C0ED112A3D3E90023CE +:10087000C5E90023012007E0282C10D005D8012C61 +:1008800009D0052C0FD0002070BD302CFBD10BA35C +:10089000D3E90023ECE70BA3D3E90023E8E70BA39C +:1008A000D3E90023E4E70BA3D3E90023E0E700BF8B +:1008B000AFF30080401DA12026812A0B78F6339FDC +:1008C00093CACD8D9E6AC421818A46EE26417272FA +:1008D000DF25D7B7F017304A39059E5613B50446C1 +:1008E0002346084620220021019001F0D7FA227900 +:1008F0000198032A234628BF032203F8042F20214E +:10090000022201F0CBFA62790198072A234628BF18 +:10091000072203F8052F2221032201F0BFFAA27952 +:100920000198072A234628BF072203F8062F25210E +:10093000032201F0B3FA019804F1080310222821E0 +:1009400001F0ACFA382002B010BD00002DE9F04FE4 +:10095000ADF5017D21AD0EAE40F2751280460F4619 +:1009600022A80021296000F02BFD482200213046FA +:1009700000F026FD00F0B6FD564B4FF47A72B0FB46 +:10098000F2F0186093E80700012386E807000DF1F4 +:100990005A003382FFF700FF4EF60343338407AB60 +:1009A00018464D4903F0C2F81B22306429463046F0 +:1009B00086F83C20FFF792FF12AB0446014608225E +:1009C000284601F06BFA0822A1180DF149032846C8 +:1009D00001F064FA0DF14A03082204F110012846DF +:1009E00001F05CFA13AB202204F11801284601F053 +:1009F00055FA14AB402204F13801284601F04EFAB2 +:100A000016AB082204F17801284601F047FA0DF1EF +:100A10005903082204F18001284601F03FFA04F14D +:100A2000880A0DF15A0904F5847B4B465146082289 +:100A300028460AF1080A01F031FAD34509F1010903 +:100A4000F3D11BAB08225946284601F027FA04F5DA +:100A500088744FF0000996F834304B450AD9B36BCF +:100A600021464B440822284601F018FA083409F1BF +:100A70000109F0E74FF0000996F83C304B4504EBD4 +:100A8000C90108D9336C08224B44284601F006FA04 +:100A900009F10109F0E700230393BB7E02930731BC +:100AA00007F119030193C1F3CF010123CDE90451EB +:100AB0000093F97E05A3D3E90023404601F006F830 +:100AC0000DF5017DBDE8F08FAFF300809E6AC42173 +:100AD000818A46EE241100203C3B0008014B18702F +:100AE000704700BF30110020F0B5334B1C7B85B040 +:100AF00034B1324B0E221A810024204605B0F0BDDD +:100B00002F4A1068516802AB03C308232D492E48B1 +:100B10000DEB030202F0E8FF054630B9274B2B48E6 +:100B20000A221A8100F098FCE6E70169B1F5663FF8 +:100B300006D9224B26480B221A8100F08DFCDCE7F7 +:100B4000438BB3F57B7F09D01C4A22480C211181CD +:100B50004FF47B72194600F07FFCCEE71E4A024438 +:100B600002F11003994204D2144B1C4810221A813E +:100B7000E3E710398E1A2046134900F0B7FC3246DD +:100B8000074605F11801204600F0B0FCAB689F4213 +:100B900002D1EB6898420AD0084B0D221A810090CE +:100BA000D5E902123B460E4800F056FCA4E70D487A +:100BB00000F052FC0124A0E768210020241100204D +:100BC000E93B0008DC97030000680008583B000878 +:100BD000643B0008763B00080898FFF7943B000848 +:100BE000B13B0008DA3B00082DE9F04FADB006AF8D +:100BF00080460C4600F000FF054600285AD1237EAF +:100C0000022B1BD1E38A012B18D100F06BFC0646A6 +:100C1000FFF7AAFD03464FF4C870DFF8D092B3FB8C +:100C2000F0F206F5167602FB103316FA83F3C9F8D4 +:100C30000030E37E33B9A84B00221A709C37BD46C2 +:100C4000BDE8F08FA38AEEB2013BB34205F1010586 +:100C50000BD93B1D1E44E90000960023082201F039 +:100C6000F801204600F0DEFFECE707F11400FFF783 +:100C700093FD324607F11401381D02F025FF0028CC +:100C8000D9D10F2E08D8944B1E70D9F80030A3F597 +:100C90001673C9F80030D1E7FB1CF87001460093C9 +:100CA00007220346204600F0BDFFF978404600F0D9 +:100CB0009BFEC3E7E38A282B26D010D8012B1ED039 +:100CC000052BBBD1BFF34F8F8449854BCA6802F413 +:100CD000E0621343CB60BFF34F8F00BFFDE7302BC3 +:100CE000ACD1637E7F4D01336A7BDBB29342E94630 +:100CF00003D1E27E2B7B9A4265D0CD469EE721460A +:100D00004046FFF723FE99E7A38A013B9BB2C92B1C +:100D100094D8744D2E7B26BB05F10C03009308225A +:100D200033463146204600F07DFF731CF2B2D900F5 +:100D30001E46A38A013B9A4205DA0E322A440092EB +:100D400000230822EEE700230022C5E90023002348 +:100D5000AB6085F8D730C5F8D8302B7B0BB9E37E74 +:100D60002B73002507F114093B1D0822294648462C +:100D7000C7E90155FD6001F091F83B7A05F1010AE0 +:100D8000AB424FEACA0608D9FB6808222B44314619 +:100D9000484601F083F85546EFE7C6F3CF06E17EFB +:100DA000CDE9049600230393A37E029319342823EC +:100DB0000093019446A3D3E90023404600F086FE49 +:100DC000FFF7FAFC3AE74FF0000807F11403A7F821 +:100DD00014801022009341460123204600F022FF98 +:100DE000A68A023EB6B2F31C9B109B000733DB08B9 +:100DF000A9EBC3039D460DF1180A1FFA88F34FEAC9 +:100E0000C801B34201F110010AD20AEB08030093B2 +:100E100008220023204600F005FF08F10108ECE756 +:100E200095F8D70000F080FAD5F8D83004461BB901 +:100E300095F8D70000F088FAD5F8D83033449C42B2 +:100E400004D295F8D700013000F07EFA4FEA960BF5 +:100E50004FF000081FFA88F18B45D5E9003209D917 +:100E60000AEB880103EB8800012200F0B1FA08F1D7 +:100E70000108EFE7F31842F10002C5E90032D5F8A6 +:100E8000D83095F8D70006EB0308C5F8D88000F0F5 +:100E90004BFA804509D395F8D730D5F8D8000133FF +:100EA000001B85F8D730C5F8D800FF2E08D80023DE +:100EB0002B7300F05BFAFFF717FE08B1FFF70CFC8D +:100EC0002B68094A9B0A013313810023AB6014E7A6 +:100ED00026417272DF25D7B73521002000ED00E0F2 +:100EE0000400FA0568210020241100203821002088 +:100EF00010B54FF000540C4B22689A4211D10B4BA5 +:100F0000627D1A700A48237D03730A49C9220E3094 +:100F100000F044FAE0220021204600F051FA0120BE +:100F200010BD0020FCE700BF9AAD44C53011002081 +:100F300068210020160000202DE9FF41434C0223C8 +:100F400063710023029324250A23581EB5FBF3F690 +:100F50007343D3F12402C1B23ED002280346F4D138 +:100F60009DF80B303A493B485A1E9DF80A30013B28 +:100F70001B0443EA0253BDF80820013A13434B60B7 +:100F800001F044FD00230193334B3449009334486E +:100F9000344B4FF4805200F001FD334B197811B1FE +:100FA0002F4800F021FD00F09DFA0546FFF7DCFB1D +:100FB0004FF4C873B0FBF3F202FB130305F5167090 +:100FC00010FA83F0294B186002F0D0FA08B10F2311 +:100FD000238104B0BDE8F081C1EBC107FB1C4FEADF +:100FE000E30EC3F3C703A1EB030C0EF101084FF4AA +:100FF0007A705FFA8CF50EFB000058FA8CFCB0FB9F +:10100000FCF0B0F5617F07D97B1EC3F3C703C91A93 +:10101000CDB2591E0F2916D86A1E072A8CBF00228E +:101020000122591901FB06601149B1FBF0F1114889 +:10103000814295D1002A93D0ADF808608DF80A302E +:101040008DF80B508CE71346EBE700BF241100200E +:1010500010110020802200205508000834110020C3 +:101060003C210020E90B000830110020382100202D +:101070000051250240420F002DE9F04F90A7D7E91B +:1010800000670FF24429D9E90089874D93B0DFF852 +:1010900040B2864C284600F07DFD0DF1300A0790E5 +:1010A00070B310220021504600F08AF9079B197B8B +:1010B0004FF0000261F303028DF830205868996800 +:1010C0000EAA03C21B680D9A63F31C029DF8303010 +:1010D0000D9243F020038DF830300023524619461C +:1010E000584601F0A3FC079028B9284600F056FDA9 +:1010F000079B2370CEE72378072B3CD8013323705E +:1011000018220021504600F05BF9DFF8C4B100233B +:1011100019465246584601F0B1FC014678BB1022F0 +:1011200008A800F04DF94FF0904209AC536983F0E4 +:101130001003536100F0D8F90B4612A9024611E9D9 +:10114000030084E803009DF83410C1F3030089060E +:101150004CBF0E9CBDF838408DF82C0046BFC4F340 +:101160001C0444F00044C4F30A0408A92846089467 +:1011700000F0DCFECBE7284600F010FDC0E7284673 +:1011800000F03AFC0446002848D1DFF848B100F0EE +:10119000A9F9DBF80030984240D300F0A3F907909A +:1011A000FFF7E2FA079A8DF8204003464FF4C87023 +:1011B00002F51672B3FBF0F101FB103312FA83F360 +:1011C000CBF80030DFF810B19BF8001011B9012303 +:1011D0008DF8203050460791FFF7DEFA0799C1F1EC +:1011E0001004E4B2062C28BF0624224651440DF117 +:1011F000210000F0D3F808AB0393182302930134C5 +:101200002B4B0193E4B20123009304943B463246F6 +:10121000284600F0F3FB00238BF8003000F062F961 +:10122000244A254C1368C31AB3F57A7F31D3106072 +:1012300000F05AF902460B46284600F0B9FC284651 +:1012400000F0DAFB28B3237BDFF890B0002B14BF4B +:10125000032302238BF8053000F044F94FF47A732E +:101260005146B0FBF3F0CBF800005846FFF736FBD1 +:10127000182307300293114B0193C0F3CF0040F2C3 +:101280005513CDE903A0009342464B46284600F093 +:10129000B5FB237B2BB1FFF78FFA237B002B7FF469 +:1012A000F6AE13B0BDE8F08F3C2100204D220020A7 +:1012B0003421002048220020682100204C220020F8 +:1012C000401DA12026812A0BF1C6A7C1D068080FB6 +:1012D0008022002038210020352100202411002008 +:1012E00070B501F0B5FF094E094D30800024286823 +:1012F0003388834208D901F0A7FF2B6804440133E7 +:10130000B4F5D04F2B60F2D370BD00BF7C2200201B +:101310005022002002F03AB800F10060920000F57F +:10132000D04001F0D5BF0000054B1A68054B1B8863 +:101330009B1A834202D9104401F086BF00207047F7 +:10134000502200207C22002038B5074D0446286832 +:10135000204401F07FFF28B928682044BDE83840C8 +:1013600001F08ABF38BD00BF50220020064991F825 +:10137000243033B10023086A81F824300822FFF7B3 +:10138000CBBF0120704700BF54220020022802BFBB +:101390004FF090434FF480129A61704710B50023CC +:1013A000934203D0CC5CC4540133F9E710BD000074 +:1013B00003460246D01A12F9011B0029FAD17047E0 +:1013C00002440346934202D003F8011BFAE7704738 +:1013D0002DE9F8431F4D144695F82420074688460A +:1013E00052BBDFF870909CB395F824302BB92022C3 +:1013F000FF2148462F62FFF7E3FF95F82400C0F174 +:101400000802A24228BF2246D6B24146920005EB0E +:101410008000FFF7C3FF95F82430A41B1E44F6B2EA +:10142000082E17449044E4B285F82460DBD1FFF71E +:101430009DFF0028D7D108E02B6A03EB820383428B +:10144000CFD0FFF793FF0028CBD10020BDE8F88371 +:101450000120FBE7542200200FB4002004B07047A5 +:1014600000B59BB0EFF3098168226846FFF796FF4D +:10147000EFF30583044B9A6BDA6A9A6A9A6A9A6A5E +:101480009A6A9A6A9B6AFEE700ED00E000B59BB09D +:10149000EFF3098168226846FFF780FFEFF30583C9 +:1014A000044B9A6B9A6A9A6A9A6A9A6A9A6A9B6ACF +:1014B000FEE700BF00ED00E000B59BB0EFF309814F +:1014C00068226846FFF76AFFEFF30583034B5A6B08 +:1014D0009A6A9A6A9A6A9A6A9B6AFEE700ED00E045 +:1014E000FEE7000001F08EBF01F064BF30B5094D8A +:1014F0000A4491420DD011F8013B5840082340F3B3 +:101500000004013B2C4013F0FF0384EA5000F6D1A5 +:10151000EFE730BD2083B8ED2DE9F041C56915B97D +:10152000C161BDE8F0814B6823F06047C3F38A4690 +:101530004FEAD37EC3F3807816EA230638BF3E46CF +:10154000AC462B465A68BEEBD27F22F060440AD0EC +:10155000002A18DAA40CB44217D19D420FD10D60B5 +:10156000DEE71346EEE7A74207D102F08044C2F35C +:10157000807242450BD054B1EFE708D2EDE7CCF8CA +:1015800000100B60CDE7B44201D0B442E5D81A6830 +:101590009C46002AE5D11960C3E700002DE9F04719 +:1015A000089D01F007044FEAD508224405F007051D +:1015B00000EBD1004FF47F49944201D1BDE8F087A0 +:1015C00004F0070705F0070A57453E4638BF564660 +:1015D000C6F10806111B8E4228BF0E46E10808EB33 +:1015E000D50E415C13F80EC0B94029FA06F721FA6E +:1015F0000AF1FFB28CEA010147FA0AF739408CEA96 +:10160000010C03F80EC034443544D5E780EA0120CC +:10161000082341F2210201B24000002980B203F107 +:10162000FF33B8BF504013F0FF03F4D17047000000 +:1016300038B50C468D18A54200D138BD14F8011BF1 +:10164000FFF7E4FFF7E7000002684AB113680360A0 +:10165000C388018901339BB29942C38038BF03819B +:101660001046704770B588B0202204460D46684683 +:101670000021FFF7A5FE20460495FFF7E5FF02468F +:1016800058B16B46054608AE1C4603CCB4422860F0 +:101690006960234605F10805F6D1104608B070BD13 +:1016A000082817D909280CD00A280CD00B280CD0F0 +:1016B0000C280CD00D280CD00E2814BF4020302050 +:1016C00070470C2070471020704714207047182076 +:1016D0007047202070470000082817D90C280CD923 +:1016E00010280CD914280CD918280CD920280CD96A +:1016F00030288CBF0F200E207047092070470A2029 +:1017000070470B2070470C2070470D207047000079 +:1017100010B54B6823B9CA8A63F30902CA8210BDA7 +:10172000C4681A681C60C360438A013B43824A60F4 +:10173000EFE700002DE9F84F1D46CB8A0F46C3F3B3 +:1017400009010629814692460B4630D00020AAB2F4 +:1017500007F119049EB2052E1FFA80F80FD89045A4 +:1017600003F1010306D3FB8A0A4462F30903FB82F7 +:1017700001201AE01AF80060E6540130EAE79045CB +:10178000F1D2A1F1060B1C237C68BBFBF3F203FB37 +:1017900012BB1FFA8BF6002C45D14846FFF754FFC9 +:1017A000044638B978606FF00200BDE8F88F4FF05A +:1017B0000008E6E7002606607860ADB24FF0000B47 +:1017C000454510D90AEB0803221D13F8011B91555A +:1017D000B1B208F101081B291FFA88F82BD0454542 +:1017E00006F10106F1D8FB8AC3F30902154465F33B +:1017F0000903BCE7013292B21C462368002BF9D1E1 +:10180000AB1F0B441C21B3FBF1F301339BB29A4293 +:10181000D3D2BBF1000FD0D14846FFF715FF20B956 +:10182000C4F800B0BFE70122E7E7C0F800B05E46A9 +:1018300020600446C1E74545D5D94846FFF704FF77 +:1018400008B92060AFE7C0F800B000262060044669 +:10185000B6E700002DE9F04F2DED028B83B0CDE906 +:101860000013BDF83C5007469146002A00F09280D4 +:101870002DB10E9B002B00F08D80072D32D807F183 +:101880000C00FFF7E1FE044638B96FF00204204671 +:1018900003B0BDEC028BBDE8F08F14220021FFF7EE +:1018A0008FFD0E992A4604F10800FFF777FD681CAA +:1018B000C0B2FFF711FFFFF7F3FE207499F8003074 +:1018C000013814FA80F003F01F0363F03F03037242 +:1018D000009B43F00041616038462146FFF71CFE43 +:1018E0000124D4E700F10C034FF0000808EE103A91 +:1018F0004FF0800A4646444618EE100AFFF7A4FE51 +:1019000083460028C1D014220021FFF759FDC6BB31 +:10191000019BABF8083002200E9B00F108029919D8 +:101920005BFA82F20130C0B2082801D0AE422AD35D +:10193000FFF7D2FEFFF7B4FE99F80020009B411E8E +:1019400002F01F0242EA4812AE4208BF4FF0400ABE +:101950005BFA81F14AEA020A43F0004281F808A0EA +:101960008BF81000CBF8042059463846FFF7D4FD19 +:101970000134AE4224B288F001084FF0000ABBD116 +:1019800085E70020C8E711F801CB02F801CB01364A +:10199000B6B2C7E76FF0010479E70000F8B5154665 +:1019A0000E462822002104461F46FFF709FD069B2C +:1019B0006360B5F5001F079BA76034BF6A094FF647 +:1019C000FF72236204F10C0097B200239A4205D8FB +:1019D0000023036027826382A382F8BD066001337F +:1019E00030462036F2E7000003781BB94BB2002BDB +:1019F000C8BF017070470000007870472DE9F74FAD +:101A0000DDF83C90BDF830500D9E9DF83840BDF893 +:101A10004070804692469B46B9F1000F01D1002FDD +:101A200051D11F2C4FD898F80000B0B9072F47D8D4 +:101A300035F0030347D13A4649464FF6FF70FFF7AA +:101A4000F7FD20F001002D02400445EA0464400C3B +:101A500044EA40244FF6FF7321E040EA0520072FB7 +:101A600040EA0464F6D900254FF6FF73C5F1200063 +:101A7000A5F120022AFA05F10BFA00F001432BFA36 +:101A800002F211431846C9B2FFF7C0FD0835402DD8 +:101A90000346EBD13A464946FFF7CAFD0346CDE976 +:101AA0000097324621464046FFF7D4FE3378013393 +:101AB000DBB21F2B88BF0023337003B0BDE8F08F6B +:101AC0006FF00300F9E76FF00100F6E72DE9F04F42 +:101AD00085B09246DDF848800F9D9DF840209DF826 +:101AE0004490BDF84C7006469B46B8F1000F01D1FA +:101AF000002F48D11F2A46D83378002B46D00C023D +:101B000044EA02649DF8381044EAC93444EA0144C6 +:101B10001C43072F44F0800432D900234FF6FF7294 +:101B2000C3F1200CA3F120002AFA03F10BFA0CFCFC +:101B300041EA0C012BFA00F00143C9B210460393AD +:101B4000FFF764FD039B0833402B0246E8D13A4679 +:101B50004146FFF76DFD0346CDE900872A46214641 +:101B60003046FFF777FEB9F1010F06D12B7801332C +:101B7000DBB21F2B88BF00232B7005B0BDE8F08FB0 +:101B80004FF6FF73E8E76FF00100F6E76FF0030030 +:101B9000F3E70000C06900B104307047C3691A68F8 +:101BA000C261C2681A60C360438A013B43827047C6 +:101BB0002DE9F041D0F81880194E14461D464146D3 +:101BC000002709B9BDE8F081D1E90223A21A65EB2B +:101BD0000303964277EB03031ED283698B420DD138 +:101BE000FFF796FD83691B688361C3680B60438AB6 +:101BF000C1608169013B43828846E2E7FFF788FDC7 +:101C00000B68C8F80030C3680B60438AC160013BB1 +:101C10004382D8F80010D4E788460968D1E700BFAE +:101C200080841E002DE9F04F8BB00D46DDF85090FA +:101C300014469B468046002800F01981B9F1000F38 +:101C400000F01581531E3F2B00F21181012A03D1B0 +:101C5000BBF1000F40F00B810023CDE90833B8F849 +:101C60001430B5EBC30F4FEAC30703D300200BB00A +:101C7000BDE8F08F2B199F42D8F80C303ABF7F1B7C +:101C8000FFB227461BB9D8F81030002B7AD02F2D81 +:101C90004ED8C5F13006B7424FF000032CBFF6B264 +:101CA0003E4600932946D8F8080008AB3246FFF7B5 +:101CB00075FCA7EB060A35445FFA8AFAB8F81430C7 +:101CC00003F10053063BDB000493D8F80C30039378 +:101CD0003021039B13B1BAF1000F2CD1D8F81000BA +:101CE00040B1BAF1000F05D0009608AB5246691A10 +:101CF000FFF754FC38B2002FB8D066070AD00AAB01 +:101D000003EBD401624211F8083C02F007021341D0 +:101D100001F8083C082C3CD9102C40F2B580202C4E +:101D200040F2B780BBF1000F00F09C80082334E044 +:101D3000BA460026C2E7049BE02B28BFE0230693A7 +:101D40000B44AB42059314D95A1B03980096924555 +:101D500034BF5246D2B2691A08AB04300792FFF77B +:101D60001DFC079A1644AAEB020A1544F6B25FFA64 +:101D70008AFA049B069A05999B1A0493039B1B6895 +:101D80000393A6E70093D8F8080008AB3A46294623 +:101D9000AEE7BBF1000F13D00123B4EBC30F6CD03F +:101DA000082C12D89DF82030621E23FA02F2D507C3 +:101DB00006D54FF0FF3202FA04F423438DF82030A9 +:101DC0009DF8203089F8003051E7102C12D8BDF86A +:101DD0002030621E23FA02F2D10706D54FF0FF32FF +:101DE00002FA04F42343ADF82030BDF82030A9F8FE +:101DF00000303CE7202C0FD80899631E21FA03F32A +:101E0000DA0705D54FF0FF3202FA04F40C430894C8 +:101E1000089BC9F800302AE7402C2BD0DDE9086583 +:101E2000611EC4F12102A4F1210326FA01F105FA91 +:101E300002F225FA03F311431943CB0712D501220D +:101E4000A4F12003C4F1200102FA03F322FA01F104 +:101E5000A240524243EA010363EB430332432B4364 +:101E6000CDE90823DDE90823C9E90023FFE66FF087 +:101E70000100FCE66FF00800F9E6082CA0D9102C50 +:101E8000B3D9202CEED8C3E7BBF1000FADD00223AD +:101E900083E7BBF1000FBBD004237EE730B5012AF6 +:101EA000144638BF0124402C85B028BF40240025AB +:101EB000012ACDE9025518D81B788DF80830630740 +:101EC0000AD004AB03EBD405624215F8083C02F0DB +:101ED0000702934005F8083C009103462246002182 +:101EE00002A8FFF75BFB05B030BD082AE4D9102A31 +:101EF00003D81B88ADF80830E1E7202A8DBFD3E96D +:101F000000231B680293CDE90223D8E710B5CB6804 +:101F10001BB98B600B618B8210BDC4681A681C6092 +:101F2000C360438A013B4382CA60F0E72DE9F04F6A +:101F3000D1F8008093B018F0800FCDE90323C8F3E7 +:101F4000C01219BFC8F3C03BC8F306264FF0020BFE +:101F50001646B8F1000F04460D4680F2D18118F004 +:101F6000C043059340F0CC810B7B002B00F0C8816F +:101F7000BBF1020F03D00178B14240F0C48108F0F8 +:101F80007F0106916AB3C8F3074A2B44069A93F877 +:101F90000390760646EA0B4646EA82465FEAD91384 +:101FA00046EA0A06079300F0908000220023CDE95C +:101FB0000A23069B009367685B4652460AA920469F +:101FC000B84700287ED0A7699FB9314604F10C00BC +:101FD000FFF748FB0746E0B96FF0020013B0BDE819 +:101FE000F08FC8F30F2A18F07F0F08BF0AF0030A1A +:101FF000CBE73B699E420DD03F68002FF9D13146B7 +:1020000004F10C00FFF72EFB07460028E4D0A3697B +:102010003B60A761DDE90A2300264FF6FF70C6F199 +:10202000200E22FA06F103FA0EFEA6F1200C23FA86 +:102030000CFC41EA0E0141EA0C01C9B208360992D2 +:102040000893FFF7E3FA402EDDE90832E7D1B882C2 +:10205000FB7D09F01F06C3F384039B1BD7E9022114 +:1020600098B2002BBCBF00F120031BB252EA010062 +:10207000C8F304680FD00398821A049860EB01013A +:10208000A74890424FF000028A4104D3079A002AE1 +:102090005BD0012B23DDFA7D4FEA890302F00302B6 +:1020A00003F07C031343FB7539462046FFF730FBF2 +:1020B000079BA3B9FB7DC3F38402013262F386035D +:1020C000FB7504E06FF00B0088E7A76917B96FF0A4 +:1020D0000C0083E73B699E42BAD03F68F6E719F0EF +:1020E000400F32D0039BBB60049BFB601422002195 +:1020F0000DA8FFF765F9039B0A93049B0B932B1D17 +:102100000C932B7BADF83EA0013BDBB2ADF83C302D +:10211000069B8DF8433094F824308DF840B083F05E +:1021200001038DF844308DF84160A3688DF842803A +:102130000AA920469847FB7DC3F38403013303F0CB +:102140001F039B02FB82002048E7FB7DC9F340127E +:10215000B2EBD31F40F0DA80C3F38403B34240F004 +:10216000D88007992B7B4FEA9912002934D0D207E7 +:1021700041D4032B40F2D080039BBB60049BFB60E7 +:102180002B7BAE1D033BDBB23246394604F10C001B +:10219000FFF7D0FA00280DDA20463946FFF7B8FAE3 +:1021A000FB7DC3F38403013303F01F039B02FB8217 +:1021B000032013E7AB883B832A7B033AB88AD2B269 +:1021C0003146FFF735FAFB7DB882DA43C2F3C0121D +:1021D00062F3C713FB75B6E76AB92E1D013BDBB28C +:1021E0003246394604F10C00FFF7A4FA0028D3DB8D +:1021F0002A7B013AE2E7F98AC1F30901013B05298B +:10220000DAB259D8281D002307F11A0C9A4208D9CE +:1022100010F801EB0CF801E0013101330629DBB2C3 +:10222000F4D103990A9104990B91934207F11A0191 +:102230000C9138BF043379680D9134BF55FA83F39C +:1022400000230E93FB8AADF83EA0C3F309031A44A2 +:10225000069B8DF8433094F82430ADF83C2083F091 +:1022600001038DF8443000238DF840B08DF84160B3 +:102270008DF842807B602A7BB88A013A291DFFF7DE +:10228000D7F93B8BB882834203D1A3680AA92046C1 +:10229000984720460AA9FFF739FEFB7DB88AC3F3A9 +:1022A0008403013303F01F039B02FB823B8B9842A4 +:1022B00014BF1120002091E67B68002BB1D00620CE +:1022C00001E01C306346D3F800C0BCF1000FF8D128 +:1022D000091A081D05F1040C00EB030905989DF887 +:1022E000143001EB000EBEF11B0F9AD89A4298D918 +:1022F0001CF8013B09F8013B059B01330593EDE711 +:102300006FF009006AE66FF00A0067E66FF00D00F3 +:1023100064E66FF00E0061E66FF00F005EE600BF4E +:1023200080841E00F0B53D4D3D4FEB6943F00073D6 +:10233000EB61EB693B4B9B6AD3F800623E4046F091 +:102340000106C3F80062D3F800423C4044EA002092 +:1023500040F00100C3F80002002951D00020C3F86A +:102360001C020646C3F80402C3F80C02C3F81402A8 +:1023700003EBC00401300E28C4F84062C4F8446284 +:10238000F6D100274FF0010C9678148816F0010F53 +:1023900018BFD3F804E20CFA04F01CBF40EA0E0E9A +:1023A000C3F804E216F0020F1EBFD3F80CE240EAB5 +:1023B0000E0EC3F80CE2760742BFD3F81462064350 +:1023C000C3F8146203EBC4045668C4F8406296680C +:1023D000C4F84462D3F81C4201372043B942C3F821 +:1023E0001C0202F10C02CFD1D3F8002222F001022C +:1023F000C3F80022EB6923F00073EB61EB69F0BDD9 +:102400000122C3F84012C3F84412C3F80412C3F8FF +:102410001412C3F80C22C3F81C22E5E70010024096 +:102420000000FFFF80220020184A916A08B58B68DF +:102430008B6013F0010104D013F00C0F18BF4FF4A0 +:102440008031D80506D513F4406F14BF41F4003134 +:1024500041F00201D80306D513F4402F14BF41F414 +:10246000802141F00401D3690BB10848984720232B +:1024700083F311880648002100F038FE002383F31F +:102480001188BDE8084001F0AFB800BF80220020ED +:102490008822002038B5124CA36ADD68AA0712D042 +:1024A0005A6922F002025A61A36913B10121204640 +:1024B0009847202383F311880A48002100F016FE74 +:1024C000002383F31188EB0606D5A36A1021D96097 +:1024D000236A0BB102489847BDE8384001F084B840 +:1024E000802200209022002038B5124CA36A1D697A +:1024F000AA0712D05A6922F010025A61A36913B1D7 +:10250000022120469847202383F311880A4800219E +:1025100000F0ECFD002383F31188EB0606D5A36AD7 +:1025200010211961236A0BB102489847BDE8384071 +:1025300001F05AB8802200209022002038B50F4CBC +:10254000A36A5D685D602A070AD5042222701A68B2 +:1025500022F002021A60636A13B1002120469847F4 +:102560006B0706D5A36A9969236A13B10348090466 +:102570009847BDE8384001F037B800BF80220020FE +:1025800010B50E4C204600F02FFA0D4BA3620B2124 +:10259000132000F009FA0B21142000F005FA0B219A +:1025A000152000F001FA0B21162000F0FDF90022A1 +:1025B000BDE8104011460E20FFF7B4BE8022002077 +:1025C000006400400F4B984210B5044605D10E4BF5 +:1025D000DA6942F00072DA61DB69A36A01221A60EB +:1025E000A36A5A68D20707D5626851681268D96130 +:1025F0001A60064A5A6110BD0121082000F06CFCE7 +:10260000EEE700BF80220020001002405B8701003F +:1026100003291AD8DFE801F0020A0F14836A9B68C5 +:1026200013F0E05F14BF012000207047836A9868B0 +:10263000C0F380607047836A9868C0F3C0607047D9 +:10264000836A9868C0F300707047002070470000EC +:1026500010B5032925D8DFE801F00225292D836A6A +:102660009968C1F30161183103EB011310788406F6 +:102670004CBF54689488C0F300114FEA410148BF31 +:1026800041EAC40100F00F004CBF41F0040141EAEF +:102690004451586041F001019068D2689860DA6056 +:1026A000196010BD836A03F5C073DFE7836A03F521 +:1026B000C873DBE7836A03F5D073D7E701290AD033 +:1026C00002290FD081B9836ADA68920701D11869AB +:1026D00003E001207047836AD86810F0030018BF38 +:1026E00001207047836AF2E70020704710B539B9BE +:1026F000836AD96889071BD11B699C0704D110BD67 +:10270000012915D00229FAD1816AD1F8C031D1F856 +:10271000C441D1F8C8011061D1F8CC01506120202A +:1027200008610869800717D1486940F0100012E07D +:10273000816AD1F8B031D1F8B441D1F8B801106153 +:10274000D1F8BC0150612020C860C868800703D15F +:10275000486940F002004861C3F34000C3F38001C0 +:10276000000140EA4111107920F03000014311715D +:1027700089064BBF91681189DB085B0D4CBF63F381 +:102780001C0163F30A01137948BF916064F30303EA +:1027900013714FEA14234FEA144458BF1181137088 +:1027A0005480ACE7026843681143016003B11847E5 +:1027B00070470000024A136843F0C003136070477B +:1027C00000380140024A136843F0C00313607047A9 +:1027D0000044004037B51D4C1D4D204600F006FB5F +:1027E000009404F114001B490023202200F0C8F9D2 +:1027F0002022009404F13800174B184900F042FAE7 +:10280000174BC4E91735174C0C21252000F0CCF8E4 +:10281000204600F0EBFA04F1140013490094002361 +:10282000202200F0ADF904F13800104B104900945B +:10283000202200F027FA0F4B0C212620C4E917357F +:1028400003B0BDE8304000F0AFB800BFAC220020BC +:102850000051250284230020B5270008C42300204E +:102860000038014018230020A4230020C5270008B9 +:10287000E4230020004400402DE9F047C66D37688E +:10288000F46934622107054618D014F0080118BF16 +:102890008021E20748BF41F02001A30748BF41F073 +:1028A0004001600748BF41F48071202383F3118801 +:1028B000281DFFF777FF002383F31188E2050AD56F +:1028C000202383F311884FF40071281DFFF76AFF5E +:1028D000002383F311884FF020094FF0000A14F011 +:1028E000200838D13B0616D54FF0200905F1380AEB +:1028F000200610D589F31188504600F0F7F900281A +:1029000036DA0821281DFFF74DFF27F080033360DA +:10291000002383F31188790614D5620612D520238B +:1029200083F31188D5E913239A4208D12B6C33B174 +:102930001021281D27F04007FFF734FF37600023E0 +:1029400083F31188E30619D5AA6E1369B3B1BDE804 +:10295000F0475069184789F31188B38C95F86410D3 +:102960002846194000F04EFA8AF31188F469B6E758 +:1029700080B2308588F31188F469B9E7BDE8F08743 +:1029800008B50348FFF778FFBDE8084000F02CBE0B +:10299000AC22002008B50348FFF76EFFBDE80840F1 +:1029A00000F022BE1823002000F1604303F56143CC +:1029B0000901C9B283F80013012200F01F039A40F5 +:1029C00043099B0003F1604303F56143C3F8802191 +:1029D0001A60704700F16040090100F56D40C9B20E +:1029E00001767047FFF7CCBD012300F10802C0E972 +:1029F0000222037000F110020023C0E90422C0E9A2 +:102A00000633C0E9083343607047000010B5202347 +:102A1000044683F31188022303704160FFF7D2FD5F +:102A200004232370002383F3118810BD2DE9F041A6 +:102A30001F4604460D461646202383F3118800F1F5 +:102A400008082378052B0DD029462046FFF7E0FD26 +:102A500040B1204632462946FFF7FAFD002080F3B8 +:102A6000118808E03946404600F024FB0028E8D0F1 +:102A7000002383F31188BDE8F08100002DE9F041C7 +:102A80001F4604460D461646202383F3118800F1A5 +:102A900010082378052B0DD029462046FFF70EFE9F +:102AA00040B1204632462946FFF720FE002080F341 +:102AB000118808E03946404600F0FCFA0028E8D0CA +:102AC000002383F31188BDE8F0810000F8B51546B6 +:102AD00082680669AA420B46816938BF8568761A02 +:102AE000B54204460BD218462A46FEF757FCA369A6 +:102AF0002B44A361A3685B1BA3602846F8BD0CD9D7 +:102B000018463246FEF74AFCAF1BE1683A463044AD +:102B1000FEF744FCE3683B44EBE718462A46FEF721 +:102B20003DFCE368E5E7000083689342F7B515468E +:102B3000044638BF8568D0E90460361AB5420BD226 +:102B40002A46FEF72BFC63692B446361A368284681 +:102B50005B1BA36003B0F0BD0DD932460191FEF7B7 +:102B60001DFC0199E068AF1B3A463144FEF716FCA4 +:102B7000E3683B44E9E72A46FEF710FCE368E4E734 +:102B800010B50A440024C361029B8460C0E90000C0 +:102B9000C0E90511C1600261036210BD08B5D0E94A +:102BA0000532934201D1826882B982680132826023 +:102BB0005A1C42611970D0E904329A4224BFC3689A +:102BC0004361002100F086FA002008BD4FF0FF307D +:102BD000FBE7000070B5202304460E4683F31188FE +:102BE000A568A5B1A368A269013BA360531CA361BA +:102BF00015782269934224BFE368A361E3690BB1AE +:102C000020469847002383F31188284607E0314681 +:102C1000204600F04FFA0028E2DA85F3118870BDF3 +:102C20002DE9F74F04460E4617469846D0F81C90FB +:102C30004FF0200A8AF311884FF0000B154665B15A +:102C40002A4631462046FFF741FF034660B9414618 +:102C5000204600F02FFA0028F1D0002383F31188DA +:102C6000781B03B0BDE8F08FB9F1000F03D00190DD +:102C70002046C847019B8BF31188ED1A1E448AF346 +:102C80001188DCE7C0E90511C160C3611144009BF4 +:102C90008260C0E90000016103627047F8B5044634 +:102CA0000D461646202383F31188A768A7B1A368B1 +:102CB000013BA36063695A1C62611D70D4E9043250 +:102CC0009A4224BFE3686361E3690BB120469847E9 +:102CD000002080F3118807E03146204600F0EAF931 +:102CE0000028E2DA87F31188F8BD0000D0E9052357 +:102CF0009A4210B501D182687AB982680132826045 +:102D00005A1C82611C7803699A4224BFC36883619C +:102D1000002100F0DFF9204610BD4FF0FF30FBE747 +:102D20002DE9F74F04460E4617469846D0F81C90FA +:102D30004FF0200A8AF311884FF0000B154665B159 +:102D40002A4631462046FFF7EFFE034660B941466A +:102D5000204600F0AFF90028F1D0002383F311885A +:102D6000781B03B0BDE8F08FB9F1000F03D00190DC +:102D70002046C847019B8BF31188ED1A1E448AF345 +:102D80001188DCE7026843681143016003B118470A +:102D9000704700001430FFF743BF00004FF0FF33CF +:102DA0001430FFF73DBF00003830FFF7B9BF000017 +:102DB0004FF0FF333830FFF7B3BF00001430FFF798 +:102DC00009BF00004FF0FF311430FFF703BF0000D0 +:102DD0003830FFF763BF00004FF0FF323830FFF7A5 +:102DE0005DBF000000207047FFF7F4BC044B036098 +:102DF0000023C0E90233436001230374704700BF1E +:102E0000F43B000838B5C36904460D461BB90421DC +:102E10000844FFF7B7FF294604F11400FFF7BEFE90 +:102E2000002806DA201D4FF48061BDE83840FFF726 +:102E3000A9BF38BD024B0022C3E900339A60704736 +:102E400004240020002303748268054B1B689968E2 +:102E50009142FBD25A68036042601060586070472C +:102E60000424002008B5202383F31188037C032B5E +:102E700005D0042B0DD02BB983F3118808BD43690D +:102E800000221A604FF0FF334361FFF7DBFF00239E +:102E9000F2E7D0E9003213605A60F3E700230374CD +:102EA0008268054B1B6899689142FBD85A68036099 +:102EB000426010605860704704240020054B196977 +:102EC0000874186802681A6053601861012303745B +:102ED000FDF77EBB0424002030B54B1C0B4D87B0A2 +:102EE000044610D02B690A4A01A800F01BF92046BD +:102EF000FFF7E4FF049B13B101A800F02FF92B6941 +:102F0000586907B030BDFFF7D9FFF8E70424002067 +:102F1000652E000838B50C4D41612B6981689A68AF +:102F20009142044603D8BDE83840FFF78BBF1846EE +:102F3000FFF7B4FF01232C61014623742046BDE84E +:102F40003840FDF745BB00BF04240020044B1A683D +:102F50001B6990689B68984294BF002001207047CD +:102F60000424002010B5084C236820691A682260E8 +:102F70005460012223611A74FFF790FF0146206913 +:102F8000BDE81040FDF724BB0424002008B5FFF77E +:102F9000DDFF18B1BDE80840FFF7E4BF08BD000041 +:102FA000FFF7E0BFFEE7000010B50C4CFFF742FF53 +:102FB00000F0AAF80A498022204600F031F80123E7 +:102FC00044F8180C037400F0EBFA002383F3118823 +:102FD00062B60448BDE8104000F042B82C2400203E +:102FE0001C3C00082C3C000800F0CAB8EFF311802C +:102FF00020B9EFF30583202282F311887047000087 +:1030000010B530B9EFF30584C4F3080414B180F3AC +:10301000118810BDFFF7BAFF84F31188F9E70000AB +:1030200082600222028270478368A3F17C0243F827 +:103030000C2C026943F83C2C426943F8382C074AAF +:1030400043F81C2CC26843F8102C022203F8082C09 +:10305000002203F8072CA3F118007047E9050008C7 +:1030600010B5202383F31188FFF7DEFF002104460B +:10307000FFF750FF002383F31188204610BD0000A6 +:10308000024B1B6958610F20FFF718BF0424002072 +:10309000202383F31188FFF7F3BF000008B5014632 +:1030A000202383F311880820FFF716FF002383F302 +:1030B000118808BD49B1064B42681B6918605A6007 +:1030C000136043600420FFF707BF4FF0FF307047E5 +:1030D000042400200368984206D01A6802605060F9 +:1030E00059611846FFF7AEBE7047000038B5044678 +:1030F0000D462068844200D138BD036823605C60BF +:103100004561FFF79FFEF4E7054B03F11402C3E9A5 +:1031100005224FF0FF32DA6100221A62704700BFC9 +:103120000424002010B5C0E903230B4A136A536935 +:103130009C68A1420CD85C68816003604460206098 +:1031400058609868411A99604FF0FF33D36110BD01 +:103150001B68091BECE700BF04240020036881689A +:103160009A680A449A60426813605A600023C360F8 +:10317000024B4FF0FF32DA61704700BF0424002099 +:1031800038B50F4C236A22460133236252F8143FAC +:10319000934206D09A68013A9A60202563699A683A +:1031A00002B138BDD3E9001001604860D968DA6027 +:1031B00082F311881869884785F31188EEE700BF0C +:1031C0000424002000207047FEE700007047000044 +:1031D0004FF0FF3070470000BFF34F8F024AD368B3 +:1031E000DB07FCD4704700BF0020024008B5074B46 +:1031F0001B7853B9FFF7F0FF054B1A69120641BF60 +:10320000044A5A6002F188325A6008BD90250020B5 +:10321000002002402301674508B5054B1B7833B9F0 +:10322000FFF7DAFF034A136943F08003136108BD17 +:1032300090250020002002407F289ABF00F58030B2 +:10324000C0020020704700004FF40060704700008B +:10325000802070477F2808B50BD8FFF7EDFF00F5F9 +:1032600000630268013204D104308342F9D10120A5 +:1032700008BD0020FCE700007F2838B5044623D8AD +:10328000FFF7B4FEFFF7A8FFFFF7B0FF0F4BF322E5 +:10329000DA6002221A6105462046FFF7CDFF586129 +:1032A0001A6942F040021A614FF40061FFF794FF7F +:1032B00000F026F92846FFF7AFFFFFF7A1FE2046F2 +:1032C000BDE83840FFF7C6BF002038BD00200240EF +:1032D00012F001032DE9F04704460E46154606D0CC +:1032E000244B40F2BD221A600020BDE8F08781180F +:1032F000214A914204D91F4A40F2C2211160F3E7EA +:10330000FFF774FEFFF772FFFFF766FFDFF87890B4 +:1033100031464FF0010AA61B012D06EB0107884636 +:1033200005D8FFF779FFFFF76BFE0120DDE7B8F85E +:103330000030C9F810A03B800024FFF74DFFC9F80A +:1033400010403B8831F8022B9BB29A420FD0094BB8 +:1033500040F2D9221A60094B1F60094B1D60094BCE +:10336000C3F80080FFF758FFFFF74AFEBCE7023DB5 +:10337000D2E700BF8C250020000004088025002033 +:10338000882500208425002000200240084908B537 +:103390000B7828B11BB9FFF729FF01230B7008BD7B +:1033A000002BFCD0BDE808400870FFF735BF00BF18 +:1033B0009025002030B583B0FFF718FE0E4B0F4D5F +:1033C0001B6A2A684FF47A7101FB03F3934237BFFB +:1033D0000B4A0B49516814682B602EBFD1E900419C +:1033E000013151601C1941F100010191FFF708FE04 +:1033F0000199204603B030BD04240020942500200C +:103400009825002030B583B0FFF7F0FD114B124D29 +:103410001B6A2A684FF47A7101FB03F3934237BFAA +:103420000E4A0E49516814682B602EBFD1E9004145 +:10343000013151601C1941F100010191FFF7E0FDDC +:1034400001994FF47A7200232046FCF7A9FE03B0DD +:1034500030BD00BF042400209425002098250020C2 +:1034600010B50244064BD2B2904200D110BD441CAC +:1034700000B253F8200041F8040BE0B2F4E700BFBB +:10348000502800400F4B30B51C6A240407D41C6A36 +:1034900044F440741C621C6A44F400441C620A4CEC +:1034A000236843F4807323600244084BD2B29042F5 +:1034B00000D130BD441C00B251F8045B43F82050E9 +:1034C000E0B2F4E7001002400070004050280040D5 +:1034D00007B5012201A90020FFF7C2FF019803B040 +:1034E0005DF804FB13B50446FFF7F2FFA04205D0D8 +:1034F000012201A900200194FFF7C4FF02B010BD12 +:1035000070470000074B45F255521A6002225A607C +:1035100040F6FF729A604CF6CC421A60024B0122D0 +:103520001A70704700300040A4250020034B1B7820 +:103530001BB1034B4AF6AA221A607047A42500204B +:1035400000300040044B1A682AB902F1804202F5AB +:103550000432526A1A607047A0250020024B4FF0D7 +:1035600080725A62704700BF0010024008B5FFF732 +:10357000E9FF024B1868C0F3407008BDA025002089 +:10358000EFF3098305494A6B22F001024A6368336D +:1035900083F30988002383F31188704700EF00E06C +:1035A000202080F3118862B60C4B0D4AD96821F4B3 +:1035B000E0610904090C0A43DA60D3F8FC200949E8 +:1035C00042F08072C3F8FC200A6842F001020A60EF +:1035D0001022DA7783F82200704700BF00ED00E088 +:1035E0000003FA05001000E010B5202383F31188D2 +:1035F0000E4B5B6813F4006314D0F1EE103AEFF356 +:103600000984683C4FF08073E361094BDB6B2366F0 +:1036100084F30988FFF79AFC10B1064BA36110BD33 +:10362000054BFBE783F31188F9E700BF00ED00E0ED +:1036300000EF00E0FB050008FE05000870470000F1 +:10364000FEE700000A4B0B480B4A90420BD30B4B92 +:10365000DA1C121AC11E22F003028B4238BF00226C +:103660000021FDF7ADBE53F8041B40F8041BECE746 +:10367000183D0008282600202826002028260020A3 +:10368000704700004B6843608B688360CB68C36001 +:103690000B6943614B6903628B6943620B6803608A +:1036A0007047000008B51B4B9A6A42F4FC029A620C +:1036B0009A6A22F4FC029A629A6A5A6942F4FC02FB +:1036C0005A61154A5B6911464FF09040FFF7DAFFE7 +:1036D00002F11C0100F58060FFF7D4FF02F1380110 +:1036E00000F58060FFF7CEFF02F1540100F5806025 +:1036F000FFF7C8FF02F1700100F58060FFF7C2FF1D +:1037000002F18C0100F58060FFF7BCFFBDE80840C6 +:1037100000F05AB800100240443C000808B500F020 +:1037200093F9FFF741FCBDE80840FFF70BBF00002D +:103730007047000010B5214CA36A63F4FC03A36238 +:10374000A36A03F4FC03A3624FF0FF32A36A236968 +:1037500022612369002323612169E168E260E26854 +:10376000E360E268E269164942F08052E261E26990 +:103770000A6842F480720A60226A02F44072B2F56A +:10378000407F1EBF4FF4803222622362236A1B04F3 +:1037900007D4236A43F440732362236A43F400434B +:1037A000236200F031F9A369064A43F00103A361E3 +:1037B000A369136843F02003136010BD001002409A +:1037C00000700040000001401E4B1A6842F00102E8 +:1037D0001A601A689007FCD55A6822F003025A60F2 +:1037E0005A6812F00C02FBD1196801F0F901196056 +:1037F0005A601A6842F480321A601A689103FCD544 +:10380000114A5A604FF40452DA6230221A631A687D +:1038100042F080721A601A689201FCD50B4912229C +:103820000A600A6802F00702022AFAD15A6842F0D6 +:1038300002025A605A6802F00C02082AFAD11A6B86 +:103840001A6370470010024000241D00002002404F +:10385000084A08B5516913680B4003F0010353612E +:1038600023B1054A13680BB150689847BDE808407A +:10387000FFF7BABE00040140A8250020084A08B599 +:10388000516913680B4003F00203536123B1054AE9 +:1038900093680BB1D0689847BDE80840FFF7A4BE15 +:1038A00000040140A8250020084A08B551691368A2 +:1038B0000B4003F00403536123B1054A13690BB1B4 +:1038C00050699847BDE80840FFF78EBE00040140EC +:1038D000A8250020084A08B5516913680B4003F079 +:1038E0000803536123B1054A93690BB1D069984726 +:1038F000BDE80840FFF778BE00040140A82500207D +:10390000084A08B5516913680B4003F0100353616E +:1039100023B1054A136A0BB1506A9847BDE80840C5 +:10392000FFF762BE00040140A8250020174B10B528 +:103930005A691C68144004F478725A61A30604D5CD +:10394000134A936A0BB1D06A9847600604D5104AAF +:10395000136B0BB1506B9847210604D50C4A936B3F +:103960000BB1D06B9847E20504D5094A136C0BB133 +:10397000506C9847A30504D5054A936C0BB1D06CE5 +:103980009847BDE81040FFF72FBE00BF000401407C +:10399000A82500201A4B10B55A691C68144004F47D +:1039A0007C425A61620504D5164A136D0BB1506D05 +:1039B0009847230504D5134A936D0BB1D06D9847F2 +:1039C000E00404D50F4A136E0BB1506E9847A10462 +:1039D00004D50C4A936E0BB1D06E9847620404D59F +:1039E000084A136F0BB1506F9847230404D5054A5A +:1039F000936F0BB1D06F9847BDE81040FFF7F4BD4F +:103A000000040140A8250020062108B50846FEF75D +:103A1000CBFF06210720FEF7C7FF06210820FEF78F +:103A2000C3FF06210920FEF7BFFF06210A20FEF78B +:103A3000BBFF06211720FEF7B7FFBDE808400621AF +:103A40002820FEF7B1BF000008B5FFF773FE00F0B5 +:103A50000DF8FEF7C7FFFFF7C7F9FFF769FEBDE8EE +:103A6000084000F001B8000000F00EB80023054A3D +:103A700019460133102BC2E9001102F10802F8D1F6 +:103A8000704700BFA82500204FF0E023044A5A6188 +:103A900000229A6107221A6108210B20FEF79ABFC3 +:103AA0003F19010008B5202383F31188FFF79CFA22 +:103AB000002383F3118808BD08B5FFF7F3FFBDE8C5 +:103AC0000840FFF791BD000010B501390244904253 +:103AD00001D1002005E0037811F8014FA34201D085 +:103AE000181B10BD0130F2E72DE9F041A3B1C91A4E +:103AF00017780144044603F1FF3C8C42204601D96B +:103B0000002009E00578BD4204F10104F5D10CEB79 +:103B10000405D618A54201D1BDE8F08115F8018D44 +:103B200016F801EDF045F5D0E7E70000034611F87F +:103B3000012B03F8012B002AF9D170476F72672E11 +:103B40006172647570696C6F742E663330335F4DCB +:103B50006174656B475053004E6F20617070207325 +:103B600069670A00426164206677206C656E67743D +:103B7000682025750A0042616420626F6172645F8B +:103B800069642025752073686F756C6420626520F8 +:103B900025750A004261642066772064657363724C +:103BA0006970746F72206C656E6774682025750A81 +:103BB00000426164206170702043524320307825B8 +:103BC0003038783A307825303878203078253038D9 +:103BD000783A3078253038780A00476F6F6420666D +:103BE00069726D776172650A0040A2E4F1646891C0 +:103BF0000600000000000000B12D00089D2D000807 +:103C0000D92D0008C52D0008D12D0008BD2D0008B4 +:103C1000A92D0008952D0008E52D00086D61696E3D +:103C20000000000069646C6500000000243C00088E +:103C3000482400208025002001000000A52F000856 +:103C400000000000A001A82A00000000FAAABEAAF5 +:103C500050001424EFFF0000007700007097090067 +:103C60000000A00000000000AAAAFAAA000050006C +:103C7000FFFF0000000000000077000000000000CF +:103C800000000000AAAAAAAA00000000FFFF00008E +:103C90000000000000000000000000000000000024 +:103CA000AAAAAAAA00000000FFFF0000000000006E +:103CB000000000000000000000000000AAAAAAAA5C +:103CC00000000000FFFF00000000000000000000F6 +:103CD0000000000000000000AAAAAAAA000000003C +:103CE000FFFF00000000000000000000E4C4FF7FB0 +:103CF0000100000000000000EC03000000000000D4 +:103D000000980300000000006400000000000000B4 +:083D1000FE2A0100D2040000AC :00000001FF diff --git a/Tools/bootloaders/f303-Universal_bl.bin b/Tools/bootloaders/f303-Universal_bl.bin index aad60ca2f45..2f1a162da54 100755 Binary files a/Tools/bootloaders/f303-Universal_bl.bin and b/Tools/bootloaders/f303-Universal_bl.bin differ diff --git a/Tools/bootloaders/f303-Universal_bl.elf b/Tools/bootloaders/f303-Universal_bl.elf index 7b41fe3a065..eaf00e309fd 100755 Binary files a/Tools/bootloaders/f303-Universal_bl.elf and b/Tools/bootloaders/f303-Universal_bl.elf differ diff --git a/Tools/bootloaders/f303-Universal_bl.hex b/Tools/bootloaders/f303-Universal_bl.hex index 1a01db00dc7..0d4ea718064 100644 --- a/Tools/bootloaders/f303-Universal_bl.hex +++ b/Tools/bootloaders/f303-Universal_bl.hex @@ -1,1095 +1,980 @@ :020000040800F2 -:1000000000090020E1040008991400089D1400086C -:10001000F11400089D140008C5140008E30400084A -:10002000E3040008E3040008E30400085D37000867 -:10003000E3040008E3040008E3040008013C0008AE -:10004000E3040008E3040008E3040008E3040008F4 -:10005000E3040008E3040008E5390008113A000849 -:100060003D3A0008693A0008953A0008E3040008A0 -:10007000E3040008E3040008E3040008E3040008C4 -:10008000E3040008E3040008E3040008092600086C -:1000900075260008C92600081D270008C13A000877 -:1000A000E3040008E3040008E3040008E304000894 -:1000B000E3040008E3040008E3040008E304000884 -:1000C000E3040008E3040008E3040008E304000874 -:1000D000E3040008D92A0008ED2A0008E304000818 -:1000E000293B0008E3040008E3040008E3040008D7 -:1000F000E3040008E3040008E3040008E304000844 -:10010000E3040008E3040008E3040008E304000833 -:10011000E3040008E3040008E3040008E304000823 -:10012000E3040008E3040008E3040008E304000813 -:10013000E3040008E3040008E3040008E304000803 -:10014000E3040008E3040008E3040008E3040008F3 -:10015000E3040008E3040008E3040008E3040008E3 -:10016000E3040008E3040008E3040008E3040008D3 -:10017000E3040008E3040008E3040008E3040008C3 -:10018000E3040008E3040008E3040008E3040008B3 -:10019000E3040008E3040008E3040008E3040008A3 -:1001A000D0400B1CD1409C46203AD34018435242C9 -:1001B00063469340184370479140031C90409C460F -:1001C000203A9340194352426346D3401943704743 -:1001D00053B94AB9002908BF00281CBF4FF0FF31AE -:1001E0004FF0FF3000F07AB9ADF1080C6DE904CEA4 -:1001F00000F006F8DDF804E0DDE9022304B0704702 -:100200002DE9F0478C460D460446089E002B51D13F -:100210008A4217466DD9B2FA82FEBEF1000F0BD0AA -:10022000CEF1200C01FA0EF520FA0CFC02FA0EF7C2 -:100230004CEA050C00FA0EF44FEA174A250CBCFBF9 -:10024000FAF81FFA87F90AFB18CC45EA0C4508FBB7 -:1002500009F3AB420AD9ED1908F1FF3280F023818E -:10026000AB4240F22081A8F102083D44ED1AA4B24D -:10027000B5FBFAF00AFB105544EA054400FB09F906 -:10028000A14509D9E41900F1FF3380F00A81A145A5 -:1002900040F2078102383C44A4EB090440EA0840DC -:1002A0000021002E61D024FA0EF400233460736024 -:1002B000BDE8F0878B4207D9002E54D0002186E894 -:1002C00021000846BDE8F087B3FA83F1002940F029 -:1002D0008E80AB4202D3824200F2FA80841A65EB30 -:1002E00003050120AC46002E3FD086E81010BDE883 -:1002F000F08712B90127B7FBF2F7B7FA87FEBEF114 -:10030000000F34D1EB1B3A0C1FFA87FC0121B3FB21 -:10031000F2F8250C02FB183345EA03450CFB08F301 -:10032000AB4207D9ED1908F1FF3002D2AB4200F21F -:10033000D1808046ED1AA3B2B5FBF2F002FB105556 -:1003400043EA05440CFB00FCA44507D9E41900F17D -:10035000FF3302D2A44500F2B8801846A4EB0C0487 -:1003600040EA08409DE731463046BDE8F087CEF1CF -:10037000200405FA0EF307FA0EF720FA04F83A0CF7 -:1003800025FA04F448EA0308B4FBF2F14FEA1845F1 -:1003900002FB11441FFA87FC45EA044501FB0CF3FC -:1003A000AB4200FA0EF409D9ED1901F1FF3080F0EB -:1003B0008A80AB4240F2878002393D44EB1A1FFA33 -:1003C00088F5B3FBF2F002FB103345EA034500FB6E -:1003D0000CF3AB4207D9ED1900F1FF386FD2AB42F5 -:1003E0006DD902383D44EB1A40EA01418FE7C1F173 -:1003F000200722FA07F88B4005FA01F448EA0303C4 -:1004000020FA07FE4FEA134CFD404EEA040EB5FBFE -:10041000FCF94FEA1E440CFB19551FFA83F844EA15 -:10042000054509FB08F4AC4202FA01F200FA01FAB0 -:1004300008D9ED1809F1FF3043D2AC4241D9A9F1F6 -:1004400002091D442D1B1FFA8EFEB5FBFCF00CFBB0 -:1004500010554EEA054400FB08F8A04507D9E418FA -:1004600000F1FF3529D2A04527D902381C4440EAC3 -:100470000940A4EB0804A0FB02894C45C6464D4642 -:1004800015D312D056B1BAEB0E0364EB050404FA8F -:1004900007F7CB401F43CC40376074600021BDE8B4 -:1004A000F0871846F8E69046E0E6C245EAD2B8EB97 -:1004B000020E69EB03050138E4E72846D7E740461A -:1004C00091E78146BEE7014678E702383C4445E7BC -:1004D000084608E7A8F102083D442BE7704700BF33 -:1004E00002E000F000F8FEE772B6394880F30888B1 -:1004F000384880F3098838484EF60851CEF200019A -:10050000086040F20000CCF200004EF63471CEF2EA -:1005100000010860BFF34F8FBFF36F8F40F2000000 -:10052000C0F2F0004EF68851CEF200010860BFF331 -:100530004F8FBFF36F8F4FF00000E1EE100A4EF6C1 -:100540003C71CEF200010860062080F31488BFF3EE -:100550006F8F03F041F903F06DF94FF055301F49EB -:100560001B4A91423CBF41F8040BFAE71C49194A67 -:1005700091423CBF41F8040BFAE71A491A4A1B4B57 -:100580009A423EBF51F8040B42F8040BF8E70020F2 -:100590001749184A91423CBF41F8040BFAE703F0AF -:1005A0001FF903F089F9144C144DAC4203DA54F8E6 -:1005B000041B8847F9E700F03FF8114C114DAC429D -:1005C00003DA54F8041B8847F9E703F007B9000081 -:1005D0000009002000110020000000080001002098 -:1005E00000090020D84300080011002074110020E9 -:1005F0007811002090260020A0010008A00100082A -:10060000A0010008A00100082DE9F04F2DED108A8F -:10061000C1F80CD0C3689D46BDEC108ABDE8F08FD0 -:10062000002383F311882846A047002002F070FEC3 -:1006300002F09AFD00DFFEE7384B6FF013022DE960 -:10064000F0416FF0670100241A7003225A709C7009 -:10065000DC701C715C719C71DC711C7259729A7235 -:10066000DC7203F025F8074603F072F80546C8BBB4 -:100670002B4B9F4238D001339F4238D0294B27F073 -:10068000FF029A4237D1F8B200F052FAA84642F27D -:10069000107400F07BFC00F051FA064678B384BB7E -:1006A000464635B1204B9F4203D003F049F8002461 -:1006B0002646002003F006F81C4B1B6913F040038C -:1006C00022D00EB100F034F800F082FC00F016FEEB -:1006D00000F022FF0546CCB900F0D0FC012002F06A -:1006E0001DFEF8E78046D4E780460446D1E704467D -:1006F0004FF00108CDE780464FF47A74C9E704460D -:10070000CFE74FF47A74CCE71C46DDE700F004FF36 -:10071000401BA042E0D900F00BF8D9E77811002087 -:10072000010007B0000008B0263A09B000040048F4 -:1007300010B51C4B1C4953F8042F013200D110BDD9 -:100740008B42F8D1194C1A4B22689A4228D9194B7E -:100750009B6803F1006303F5D0439A4220D202F074 -:10076000C3FF02F0D5FF002000F0E2FD124B022093 -:10077000187000F019FE114BDA690022DA61D969AC -:1007800099699A619B6972B60D4A0E4B13601B689A -:100790002268202181F311889D4683F30888104741 -:1007A00010BD00BFFC6700081C6800080468000852 -:1007B000FF6700087811002084110020001002401B -:1007C00008ED00E00068000809490B6849F269007B -:1007D0009AB21B0C00FB0233064A0B60136844F20A -:1007E000506198B21B0C01FB0030106080B2704762 -:1007F0000C1100200811002010B500211022044621 -:1008000000F0ECFD034B03CB206061601868A06032 -:1008100010BD00BFACF7FF1FF0B51F4CBBB000F020 -:100820007BFEA368C31AF92B30D906AD2346A0601E -:1008300028220021284601F0FDFB04F10E0000F003 -:10084000C5FD0023C6B2591D5F1CDBB2B3424FEA9F -:10085000C10107DA0E3323440822284601F0EAFBDF -:100860003B46F0E7012303930823207B02930B4BC5 -:100870000193C1F3CF013023059100930146049504 -:1008800003A3D3E90023064801F0A4F93BB0F0BD6F -:1008900078F6339F93CACD8DC8210020D521002042 -:1008A000A021002070B50D4614461E4601F038F90F -:1008B00050B9022E0ED1012C0CD112A3D3E9002382 -:1008C000C5E90023012070BD052C14D003D8012CEC -:1008D00009D0002070BD282C09D0302CF9D10BA3F1 -:1008E000D3E90023ECE70BA3D3E90023E8E70BA34C -:1008F000D3E90023E4E70BA3D3E90023E0E700BF3B -:10090000AFF30080401DA12026812A0B78F6339F8B -:1009100093CACD8D9E6AC421818A46EE26417272A9 -:10092000DF25D7B7F017304A39059E5638B504464B -:100930000D46034620222846002101F07BFB227948 -:100940002346032A28BF032203F8042F2846022245 -:10095000202101F06FFB62792346072A28BF072276 -:1009600003F8052F28460322222101F063FBA27918 -:100970002346072A28BF072203F8062F284603220A -:10098000252101F057FB284604F1080310222821F5 -:1009900001F050FB382038BD2DE9F04FADF5037D57 -:1009A00023AE10AD40F2791280460F46304600214A -:1009B00000F014FD48220021284600F00FFD00F051 -:1009C000ABFD594B4FF47A72B0FBF2F0186093E82C -:1009D0000700012385E807002B740DF16200002356 -:1009E0006B74FFF709FF032385F82030EC2385F8AB -:1009F000213007AB18464D4903F06CF921222864D9 -:100A00003146284685F83C20FFF790FF14AB04469A -:100A100001460822304601F00DFB0822A1180DF115 -:100A20005103304601F006FB0DF15203082204F198 -:100A30001001304601F0FEFA15AB202204F1180136 -:100A4000304601F0F7FA16AB402204F13801304687 -:100A500001F0F0FA18AB082204F17801304601F0F9 -:100A6000E9FA0DF16103082204F18001304601F03A -:100A7000E1FA04F1880A0DF1620904F5847B4B4622 -:100A80005146082230460AF1080A01F0D3FAD3454C -:100A900009F10109F3D11DAB08225946304601F096 -:100AA000C9FA04F588744FF0000995F834304B45C5 -:100AB00010D84FF0000995F83C304B4515D92B6CF8 -:100AC00021464B440822304601F0B4FA083409F1BB -:100AD0000109F0E7AB6B21464B440822304601F098 -:100AE000A9FA083409F10109DFE7E31DC3F3CF03D5 -:100AF000F97E0593002304960393BB7E0293193776 -:100B000001230093019706A3D3E90023404601F097 -:100B100061F80DF5037DBDE8F08F00BFAFF30080F5 -:100B20009E6AC421818A46EE88110020AC3E0008EE -:100B3000014B1870704700BF94110020F0B5334B83 -:100B40001C7B85B034B1324B0E221A810024204622 -:100B500005B0F0BD2F4A1068516802AB03C30823EB -:100B60000DEB03022C492D4803F096F8054630B9E9 -:100B7000274B2B480A221A8100F084FCE6E7016922 -:100B8000B1F5663F06D9224B26480B221A8100F0A8 -:100B900079FCDCE7438BB3F57B7F09D01C4A224804 -:100BA0000C2111814FF47B72194600F06BFCCEE7EB -:100BB0001E4A024402F11003994204D2144B1C480D -:100BC00010221A81E3E710398E1A2046134900F0EB -:100BD000A7FC3246074605F11801204600F0A0FCAC -:100BE000AB689F4202D1EB6898420AD0084B0D22B5 -:100BF0001A8100903B46EA68A9680E4800F042FC62 -:100C0000A4E70D4800F03EFC0124A0E7C821002025 -:100C1000881100207C3D0008DC9703000068000874 -:100C2000843D0008903D0008A23D00080898FFF7A9 -:100C3000C03D0008DD3D0008063E00082DE9F04FEC -:100C4000ADB006AF80460C4600F06AFF05460028AE -:100C50006AD1237E022B18D1E38A012B15D100F033 -:100C60005BFC8146FFF7B0FD4FF4C873BD4EB0FB8F -:100C7000F3F209F5167902FB1300E37E19FA80F00E -:100C800030608BB9B84B00221A709C37BD46BDE866 -:100C9000F08F3B1D1D440095002308224FEAC90137 -:100CA000204601F02BF84D46A38A013BAB425FFA88 -:100CB00085F90BD905F10109B9F1110FE9D1AB4B58 -:100CC000AB4A40F23911AB4802F0B8FF07F114000B -:100CD000FFF792FD2A4607F11401381D02F0CCFF00 -:100CE00003460028CED1B9F1100F07D09E4B83F8F0 -:100CF00000903368A3F516733360C6E707F19802D6 -:100D0000014602F8950D20460092072200F0F6FFFA -:100D1000F9787F2904DD984B954A4FF4A871D2E702 -:100D2000404600F0E1FEB0E7E38A052B00F00681C3 -:100D300006D8012BA9D121464046FFF72DFEA4E796 -:100D4000282B3DD0302BA0D1637E8C4D01336A7BA4 -:100D5000DBB29342E94640F0EF80E27E2B7B9A4281 -:100D600040F0EA8007F19803002623F8846D1022F2 -:100D7000009331460123204600F0C0FFB4F81480F0 -:100D8000A8F102081FFA88F808F1030323F003030F -:100D90000A3323F00703ADEB030D0DF1180A3346B8 -:100DA0009BB2B11C98454FEAC10106F101066CDD0A -:100DB0005344009308220023204600F09FFFEEE7F3 -:100DC000A38A013B9BB2C92B3FF65FAF6B4E357BCD -:100DD0004DBB06F10C03009308222B462946204602 -:100DE00000F08CFFA38A05F10109013BEDB29D42A1 -:100DF0004FEAC90109DA0E3535440095002308226F -:100E0000204600F07BFF4D46ECE700230022C6E9B8 -:100E100000230023B36086F8D730C6F8D830337B80 -:100E20000BB9E37E3373002507F114063B1D08223E -:100E3000294630467D60BD60FD6001F0FBF83B7ADD -:100E400005F10109AB424FEAC90107D9FB68082245 -:100E50002B44304601F0EEF84D46F0E7C1F3CF01E8 -:100E60000023E07E059104960393A37E0293193438 -:100E7000282301460093019438A3D3E90023404678 -:100E800000F0A8FEFFF7C8FCFFE695F8D70000F0D9 -:100E900059FAD5F8D83006461BB995F8D70000F0B6 -:100EA00061FAD5F8D83043449E4204D295F8D70071 -:100EB000013000F057FA4FEA980B0024A0B25845D1 -:100EC00004F1010408DA2B6880000AEB000101221A -:100ED000184400F08BFAF1E7D5E90023D5F8D840A3 -:100EE00095F8D70012EB080243F100034444C5E92A -:100EF0000023C5F8D84000F025FA844209D395F8BC -:100F0000D730013385F8D730D5F8D8309E1BC5F8D7 -:100F1000D860B8F1FF0F08DC00232B7300F034FA1F -:100F2000FFF70CFE08B1FFF703FC2B68144A9B0A7D -:100F3000013313810023AB60CD46A6E6BFF34F8F8C -:100F40001049114BCA6802F4E0621343CB60BFF34F -:100F50004F8F00BFFDE700BFAFF3008026417272E4 -:100F6000DF25D7B79C21002099210020183E0008DA -:100F7000D03E0008713E0008933E0008C8210020C2 -:100F80008811002000ED00E00400FA0508B54FF0DC -:100F900000530B4A196891420AD10A4A597D1170CF -:100FA00009481B7D0373C92208490E3000F004FA7A -:100FB000E02200214FF00050BDE8084000F00EBADA -:100FC0009AAD44C594110020C821002016000020CD -:100FD00030B5204C2049214885B002236371042399 -:100FE0000025ADF808300123ADF80C5007228DF82C -:100FF0000C308DF80B301A4B4B608DF80A2001F045 -:1010000003FE184B019500931749184B18484FF4ED -:10101000805200F033FD174B1978254611B1144862 -:1010200000F062FD00F078FA0446FFF7CDFB4FF4C4 -:10103000C87304F51674B0FBF3F202FB13000E4BF9 -:1010400014FA80F0186002F083FB08B10F232B81A3 -:1010500005B030BD8811002000110020E0220020E2 -:1010600003000600A5080008981100203D0C0008A8 -:10107000A0210020941100209C2100202DE9F04F98 -:1010800094A7D7E900670FF25429D9E900898D4C5C -:1010900093B0DFF850B2DFF850A2204600F0E6FD32 -:1010A0000CAD079098B310220021284600F096F965 -:1010B000079B197B4FF0000261F3030219468DF87C -:1010C000302051F8040F49680EAA03C21B680D9A1C -:1010D00063F31C029DF830300D9243F020038DF82D -:1010E000303000232A461946584601F09DFD0790EE -:1010F00030B9204600F0BEFD079B8AF80030CCE7EF -:101100009AF80030072B3EDC01338AF800301822B1 -:101110000021284600F062F9DFF8C8A10023194633 -:101120002A46504601F0A8FD014680BB102208A8BF -:1011300000F054F94FF09042536983F0100353616B -:1011400000F0ECF90B4612A9024611E903000DF17B -:10115000240E8EE803009DF83410C1F303008906C5 -:101160004CBF0E99BDF838108DF82C0046BFC1F366 -:101170001C0141F00041C1F30A010891204608A971 -:1011800000F0BEFFCAE7204600F074FDBFE720462E -:1011900000F0C6FC824600284AD1DFF850B100F0CA -:1011A000BBF9DBF80030984242D300F0B5F9079064 -:1011B000FFF70AFB079A8DF820A04FF4C87302F5D9 -:1011C0001672B0FBF3F101FB130012FA80F0CBF8BA -:1011D0000000DFF81CB19BF8001011B901238DF855 -:1011E000203028460791FFF707FB0799C1F1100A45 -:1011F0005FFA8AFABAF1060F28BF4FF0060A524684 -:1012000029440DF1210000F0D7F80AF101030493FD -:1012100008AB0393182302932B4B019301230093F4 -:1012200032463B46204600F07DFC00238BF8003020 -:1012300000F072F9254ADFF8BCA01368C31AB3F5B1 -:101240007A7F32D3106000F069F902460B462046DF -:1012500000F016FD204600F063FC30B39AF80C3025 -:10126000DFF894B0002B14BF032302238BF8053062 -:1012700000F052F94FF47A732946B0FBF3F0CBF843 -:1012800000005846FFF752FB182307300293104B1B -:101290000193C0F3CF0040F25513049000930395DF -:1012A00042464B46204600F03DFC9AF80C300BB10C -:1012B000FFF7B2FA9AF80C30002B7FF4EAAE13B0C5 -:1012C000BDE8F08FA021002098210020A822002056 -:1012D000AC220020401DA12026812A0BF1C6A7C107 -:1012E000D068080FE0220020AD2200209C210020C1 -:1012F00099210020C82100208811002070B502F03B -:10130000C3F8094C094E20700025306823788342C9 -:1013100008D902F0B5F8336805440133B5F5D04F6C -:101320003360F2D370BD00BFDC220020B022002069 -:1013300002F042B900F10060920000F5D04002F0E6 -:10134000E7B80000054B1A68054B1B789B1A8342CF -:1013500002D9104402F094B800207047B022002057 -:10136000DC22002038B5074D04462868204402F0EE -:101370008DF828B928682044BDE8384002F098B8B4 -:1013800038BD00BFB0220020064991F8243033B1A7 -:1013900000230822086A81F82430FFF7CBBF012020 -:1013A000704700BFB4220020022802BF4FF09043D4 -:1013B0004FF480129A61704710B50023934203D016 -:1013C000CC5CC4540133F9E710BD0000024603466B -:1013D000981A13F9011B0029FAD1704702440346F9 -:1013E000934202D003F8011BFAE770472DE9F0475A -:1013F000234C94F8243005468846174683BB2E4676 -:10140000DFF87C90C7B394F824302BB92022FF2159 -:1014100048462662FFF7E2FF94F82400C0F1080571 -:10142000BD4228BF3D465FFA85FAAD0041462A46D7 -:1014300004EB8000FFF7C0FF94F82430A7EB0A0705 -:101440009A445FFA8AFABAF1080F2E44A844FFB210 -:1014500084F824A0D6D1FFF797FF0028D2D108E066 -:10146000266A06EB8306B042CAD0FFF78DFF00283C -:10147000C5D10020BDE8F0870120BDE8F08700BF9E -:10148000B42200200FB4002004B070470FB44FF016 -:10149000FF3004B070470000FEE7000000B59BB0CD -:1014A000EFF3098168226846FFF786FFEFF30583B3 -:1014B000034B9A6B9A6A9A6A9A6A9A6A9B6AFEE7DF -:1014C00000ED00E000B59BB0EFF3098168226846AB -:1014D000FFF772FFEFF30583044B9A6B9A6A9A6ADF -:1014E0009A6A9A6A9A6A9B6AFEE700BF00ED00E07A -:1014F00000B59BB0EFF3098168226846FFF75CFFF7 -:10150000EFF30583034B5A6B9A6A9A6A9A6A9A6A4E -:101510009B6AFEE700ED00E002F086B802F060B8DA -:1015200030B5084D0A4491420BD011F8013B092413 -:101530005840013CF7D040F300032B4083EA5000B1 -:10154000F7E730BD2083B8ED0246006848B1036874 -:101550001360D388118901339BB29942D38038BF7D -:101560001381704770B588B00D46044620220021D3 -:101570006846FFF733FF20460495FFF7E5FF054671 -:1015800058B16B46044608AE1A4603CAB242206000 -:101590006160134604F10804F6D1284608B070BD16 -:1015A0002DE9F04130B9274B274A40F2C531274891 -:1015B00002F044FB0B7C23B9254B234A40F2C63191 -:1015C000F5E7C66986B9C161BDE8F081002B29DA6B -:1015D000930CAB4229D1B44201D10C60F3E7C8F8B7 -:1015E00000100C60BDE8F0814B6823F06047BD0C33 -:1015F0004FEAD37EC3F3807C15EA230538BF3D460E -:10160000B04634466368BEEBD37F23F06042DDD141 -:10161000974203D1C3F380739C450AD1974205E0FA -:101620001C46EFE7AA4206D013469D422CBF00237A -:101630000123002BCFD12368A046002BF0D12160DD -:10164000BDE8F081A4410008983F00085C42000812 -:101650007D42000808B5034A034B044840F25E315E -:1016600002F0ECFA743F00081C4200085C420008DB -:1016700008B503680B60C388016033B9044B054AA1 -:1016800005484FF4C76102F0D9FA013BC38008BD99 -:10169000EC410008E83F00085C42000870B50C46C9 -:1016A00000F10C05616831B9E38A61F30903E38253 -:1016B0000020002170BD0E682846FFF7D9FF666044 -:1016C000F0E7000008B5426832B10B4B0B4A0C48FA -:1016D00040F22F4102F0B2FAC37DC3F3840101311D -:1016E00061F38603C375C38A62F30903C3821B0ACD -:1016F00062F3C713C37508BD38420008A43F000851 -:101700005C4200082DE9F047089E32B91F4B204A81 -:10171000204840F2395102F091FA01F007054FEAF2 -:10172000D6082A4406F0070600EBD1004FF47F49A3 -:10173000954201D1BDE8F08705F0070E06F0070AD3 -:10174000D645774638BF5746C7F10807511BEC0806 -:101750008F4228BF0F46045D08EBD60104FA0EF451 -:1017600013F801C029FA07FE24FA0AF45FFA8EFE84 -:101770008CEA04044EFA0AFE04EA0E048CEA040C15 -:1017800003F801C03D443E44D2E700BFB841000821 -:10179000BC3F00085C4200082DE9F04106460F46B8 -:1017A00000254FF6FF7441F221082A46304639469B -:1017B000FEF7F6FCC0B284EA0024082314F4004FBC -:1017C0004FEA4404A4B203F1FF3318BF84EA0804CB -:1017D00013F0FF03F2D10835402DE6D12046BDE8D5 -:1017E000F081000010B50A4441F22104914200D179 -:1017F00010BD11F8013B80EA0320082310F4004FCC -:101800004FEA400080B203F1FF3318BF604013F08D -:10181000FF03F3D1EAE700002DE9F04F85B08A46D7 -:101820008DE80C00BDF83C40814630B9494B4A4A2E -:1018300040F26E31494802F001FA11F0604F04D0D5 -:10184000474B454A40F26F31F4E7009B002B7ED0B6 -:1018500024B10E9B002B7AD0072C28D809F10C005C -:10186000FFF772FE054628B96FF00205284605B05D -:10187000BDE8F08F14220021FFF7B0FD22460E993B -:1018800005F10800FFF798FD631C2B74009B1B7883 -:101890002C4403F01F0363F03F0323724AF000431C -:1018A0006B6029464846FFF77BFE0125DEE7019B7A -:1018B0001B0A4FF00008029300F10C034FF0800B5D -:1018C0004646454603930398FFF73EFE0746002829 -:1018D000CAD014220021FFF781FDB6BB9DF8043069 -:1018E0003B729DF808307B7202220E9B711E1944D8 -:1018F000B4420AD9B8180132D2B211F801EF80F817 -:1019000008E00136072AB6B2F2D1009B197801F03F -:101910001F01B44208BF4FF0400BB81841EA48110C -:101920004BEA0103037201324AF000437B603A74D0 -:1019300039464846FFF734FE0135B4422DB288F0EF -:1019400001084FF0000BBED190E70022CDE76FF009 -:1019500001058BE7A4410008883F00085C420008AD -:10196000C84100082DE9F0471E46CB8A9146C3F3D3 -:101970000902062A80460F4619D013460021B0B24C -:101980008DB25A1992B2052A09D9A84210D8FA8AFA -:10199000034463F30902FA820120BDE8F087A842FC -:1019A000F3D93A4419F8014094760131E8E700256B -:1019B000FB8A7C68C3F30900821F1C23B2FBF3FA85 -:1019C00003FB1A2A1FFA8AF27CB301212368002B39 -:1019D00039D1B31F03441C20B3FBF0F301339BB296 -:1019E00099420CD2BAF1000F09D14046FFF7ACFD85 -:1019F00008B1C0F800A0206008B304460022B6B2C7 -:101A00004FF0000AB54230D2691E49441346E0182F -:101A100001339BB211F801EF80F804E001351C2B73 -:101A2000ADB214D0AE42F2D8ECE74046FFF78CFDE1 -:101A3000044608B1002303607C60002CDED16FF007 -:101A40000200BDE8F087013189B21C46BEE7AE4214 -:101A5000D8D94046FFF778FD08B1C0F800A0206053 -:101A60000028ECD004460022CCE7FB8AC3F309022D -:101A7000164466F30903FB828EE70000F8B50E46B4 -:101A800015461F46044628B9144B154A15484F21E0 -:101A900002F0D4F824220021FFF7A0FC069B63602B -:101AA000079B23626A094FF6FF739A424FF00000CA -:101AB00028BF1A46A7602070A061E06197B204F1C8 -:101AC0000C05824205D100232B6027826382A3820A -:101AD000F8BD2E60013035462036F2E7A0410008FF -:101AE000143F00085C42000808B528B9084B094AB1 -:101AF0007321094802F0A2F8037823B94BB2002BF6 -:101B000001DD017008BD054B024A7D21F1E700BFF0 -:101B1000A4410008203F00085C420008E84000089B -:101B2000007870472DE9F7430D9EBDF828900B9D76 -:101B30009DF83040BDF8388007461946104616B962 -:101B4000B8F1000F43D11F2C41D83B78D3B9B8F17D -:101B5000070F39D839F0030339D1424631464FF6E1 -:101B6000FF70FFF73FFE4FEA092920F0010009F45A -:101B70004079400449EA0464400C44EA40244FF6AA -:101B8000FF730DE043EA0923B8F1070F43EA046449 -:101B9000F5D9FFF701FE42463146FFF723FE034623 -:101BA0008DE840012A4621463846FFF735FE0DB93B -:101BB000FFF750FD2B780133DBB21F2B88BF0023CA -:101BC0002B7003B0BDE8F0836FF00300F9E76FF00E -:101BD0000100F6E72DE9F7430E9F0B9D9DF8348039 -:101BE000BDF83C6081469DF8300007B9C6BB1F2890 -:101BF00036D899F800E0BEF1000F34D00C0244F062 -:101C000080049DF8281044EAC83444EA014444EAB8 -:101C10000E04072E44EA006415D919461046FFF752 -:101C2000BBFD32463946FFF7DDFD034601960097BE -:101C30002A4621464846FFF7EFFDB8F1010F0CD1C7 -:101C400025B9FFF707FD4FF6FF73EFE72B78013358 -:101C5000DBB21F2B88BF00232B7003B0BDE8F083DD -:101C60006FF00100F9E76FF00300F6E7C06900B11B -:101C700004307047C1690B68C3610C30FFF7F8BCD2 -:101C80002DE9F84FD0F818A0DFF86C80054616460D -:101C90001F4654464FF0000900F10C0B0CB9BDE88B -:101CA000F88FD4E90223B21A67EB0303994508BF02 -:101CB00090451FD2AB699C42214628460DD1FFF7C3 -:101CC000EDFCAB691B68AB6121465846FFF7D0FCC1 -:101CD000AC692346A2461C46E0E7FFF7DFFC236819 -:101CE000CAF8003021465846FFF7C2FC5446DAF8DD -:101CF0000030EFE72368EDE780841E002DE9F04F08 -:101D00008BB00D4614460793DDF8509082460028AC -:101D100000F06481B9F1000F00F06081531E3F2B89 -:101D200000F25C81012A03D1079B002B40F0568111 -:101D3000BAF81460F6000023B5420893099380F0C6 -:101D400053812B199E420AD2761B16F0FF0607D14B -:101D5000AB4BAC4A40F26751AB4801F06FFF2646EF -:101D6000DAF80C3023B9DAF81030002B00F0A58037 -:101D70002F2D31D8C5F1300846454FF000032CBF58 -:101D80005FFA88F8B0460093294608AB4246DAF875 -:101D90000800FFF7B7FCA6EB08074544FFB2BAF806 -:101DA000143003F10053063BDB000293DAF80C30E9 -:101DB00005934FF0300B059B002B51D087B9DAF813 -:101DC0001000002861D0002F5FD0AB4550D98F4B59 -:101DD0008C4A40F2A651BFE737464FF00008DEE7D5 -:101DE000029B23B98A4B874A4FF4B161B4E7029B47 -:101DF000E02B28BFE02306935B44AB4204931DD93C -:101E00005B1B9F4226BFDBB203930397AB4504D90C -:101E10007E4B7C4A40F291519EE70598CDF80080B8 -:101E200008ABA5EB0B01039A0430FFF76BFC039B97 -:101E30009844FF1A1D445FFA88F8FFB2049B9B4543 -:101E400004D3744B6F4A40F29B5185E7029B069A7C -:101E5000DDF810B09B1A0293059B1B680593AAE757 -:101E6000029BBB42ABD26C4B664A40F2A15173E776 -:101E7000CDF800803A46A5EB0B0108ABFFF742FC1A -:101E8000B8443D445FFA88F80027BAF81430B5EB3F -:101E9000C30F04D9614B5B4A40F2B1515CE7B8F122 -:101EA000400F04D95E4B574A40F2B25154E767B134 -:101EB0005C4B544A40F2B3514EE70093324608ABB4 -:101EC0002946DAF80800FFF71DFC731E3F2B35B2D8 -:101ED00001D8A64204DD544B544A40F235213BE779 -:101EE00060070AD00AAB03EBD401624211F8083C48 -:101EF00002F00702134101F8083C082C21D9102CEC -:101F000021D9202C8CBF08230423079A002A6DD0E6 -:101F1000B4EBC30F6CD0082C04F1FF3215D89DF838 -:101F2000203023FA02F2D10706D54FF0FF3202FA31 -:101F300004F423438DF820309DF8203089F80030D8 -:101F40004EE00123E1E70223DFE7102C11D8BDF8B2 -:101F5000203023FA02F2D20706D54FF0FF3202FA00 -:101F600004F42343ADF82030BDF82030A9F8003048 -:101F700036E0202C0ED8089921FA02F2D30705D5B5 -:101F80004FF0FF3303FA04F40C430894089BC9F89C -:101F9000003025E0402C1CD0DDE90867304639468A -:101FA000FEF7FEF8002100F0010050EA01030BD01B -:101FB000224601200021FEF7FFF8404261EB41017B -:101FC00006430F43CDE90867DDE90823C9E900238B -:101FD00006E0174B154A4FF42071BDE66FF001057E -:101FE00028460BB0BDE8F08F1D46F9E7012CA3D0C1 -:101FF000082CA1D9102CB7D9202CE5D8C6E700BFF2 -:10200000F43F0008CC3F00085C420008164000087E -:10201000034000083B400008634000088A40000875 -:10202000B8400008D0400008EA4000084C3F0008D3 -:10203000E840000830B585B030B9244B244A40F25E -:10204000B121244801F0FAFD23B9234B204A40F284 -:10205000B221F6E7402A04D9204B1D4A40F2B621AE -:10206000EFE722B91D4B1A4A4FF42F71E9E700241C -:10207000012A0294039417D11B788DF80830530776 -:102080000AD004AB03EBD203554213F8084C05F019 -:102090000705AC4003F8084C00910346002102A854 -:1020A000FFF730FB05B030BD082AE5D9102A03D868 -:1020B0001B88ADF80830E2E7202A02D81B6802939B -:1020C000DDE7D3E90045CDE90245D8E72441000822 -:1020D000603F00085C4200083F410008E8400008FB -:1020E00070B50C4600F10C05E16819B9A1602161D9 -:1020F000A18270BD0E682846FFF7BAFAE660F3E7E2 -:102100002DE9F04FD1F8009091B0C9F3C016044604 -:102110000D46CDE90223002E50D0C9F3C03BC9F3D0 -:102120000626B9F1000F80F29F8119F0C04F40F0F0 -:102130009B812B7B002B00F09781BBF1020F03D01A -:102140002278B24240F0938109F07F02BBF1020F86 -:10215000059236D119F07F0FC9F30F2A01D10AF089 -:10216000030A2B447606059A93F8038046EA0B4649 -:1021700046EA82465FEAD81346EA0A06069300F06A -:102180009A800022002310A961E90823059B00938F -:1021900067685B4652462046B847002800F08880B2 -:1021A000A7698FB9314604F10C00FFF7DBF9074648 -:1021B000D0B96FF0020011B0BDE8F08F4FF0020B04 -:1021C000AFE7C9F3074ACCE73B699E420DD03F68B1 -:1021D000002FF9D1314604F10C00FFF7C3F907468F -:1021E0000028E6D0A3693B60A761DDE90801FFF79D -:1021F000D3FAB882F97D08F01F06C1F38401711A81 -:1022000089B20FFA81FED7E90223BEF1000FB8BFF1 -:1022100001F1200EC9F30461B8BF0FFA8EFE0791D9 -:1022200052EA030100F02F81DDE90201801A61EB1F -:10223000030102460B469F480021994208BF904285 -:10224000C0F02181069B002B3FD0BEF1010F00F3AF -:102250001A8118F0400F38D0DDE90223C7E90223C4 -:10226000202200210DEB0200FFF7B8F8DDE9022380 -:10227000CDE908232B1D0A932B7BADF836A0013B3B -:10228000DBB2ADF834309DF81C308DF83A309DF853 -:1022900014308DF83B3020468DF838B08DF8396019 -:1022A000A36808A998473846FFF70CFA002082E790 -:1022B0006FF00B007FE7A76917B96FF00C007AE7A2 -:1022C0003B699E4296D03F68F6E7FB7DC8F340121B -:1022D000B2EBD31F40F0CE80C3F38403B34240F08F -:1022E000CC8006992B7B4FEA981279B3D2073CD465 -:1022F000032B40F2C580DDE90223C7E902232B7BD3 -:10230000AE1D033BDBB23246394604F10C00FFF749 -:1023100029FB002808DA39462046FFF7BFF938467E -:10232000FFF7D0F9032046E7AB883B832A7B033ACB -:10233000D2B2B88A3146FFF755FAFB7DB882DA434C -:10234000C2F3C01262F3C713FB75AFE76AB92E1D63 -:10235000013BDBB23246394604F10C00FFF702FBC9 -:102360000028D8DB2A7B013AE2E7FA8AC2F30902A5 -:10237000013B052AD9B250D8281D002399420AD919 -:1023800007EB020E013210F801CB8EF81AC00133B0 -:10239000062ADBB2F2D1DDE902898B4207F11A028B -:1023A000CDE908890A9238BF04337A680B9234BFAA -:1023B0005B1900230C93FB8AADF836A0C3F3090325 -:1023C00019449DF81C308DF83A309DF814308DF882 -:1023D0003B300023ADF834108DF838B08DF83960FB -:1023E0007B602A7BB88A013A291DFFF7FBF93B8BFA -:1023F000B882834203D1A36808A92046984708A958 -:102400002046FFF76DFE3846FFF75CF9B88A3B8B34 -:10241000984214BF11200020CDE6786810B34FF029 -:10242000060E03689BB9A2EB0E021B2A13D80332D7 -:10243000024405F1040E1F309942ACD91EF801CBBD -:1024400002F801CF01339042DBB2F5D1A3E70EF1E0 -:102450001C0E1846E5E7184B184A194840F2B3110C -:1024600001F0ECFB034696E76FF00900A3E66FF07E -:102470000A00A0E66FF00D009DE66FF00E009AE6F0 -:102480006FF00F0097E6FB7D68F386036FF3C713C9 -:10249000FB7539462046FFF701F9069B002B7FF4B8 -:1024A000D8AEFB7DC3F38402013262F38603FB7571 -:1024B00003E700BF80841E0054410008383F000835 -:1024C0005C4200082DE9F0414C4EB04240F0818062 -:1024D0004B4CDFF830E1E56945F00075E561E469F2 -:1024E000846AD4F8007207EA0E0747F00107C4F8BF -:1024F0000072D4F8005205EA0E0545F0010545EAE0 -:102500000121C4F80012002A65D00021C4F81C1271 -:102510000F46C4F80412C4F80C12C4F8141204EBE9 -:10252000C10501310E29C5F84072C5F84472F6D1D3 -:102530004FF0000E4FF0010C964510D1826AD2F890 -:102540000032B04223F00103C2F8003253D12C4BC9 -:10255000DA6922F00072DA61DB69BDE8F0819F7808 -:102560001D8817F0010F18BFD4F804820CFA05F18A -:102570001CBF41EA0808C4F8048217F0020F1EBF0E -:10258000D4F80C8241EA0808C4F80C827F0742BFE5 -:10259000D4F814720F43C4F8147204EBC5055F68D5 -:1025A000C5F840729F68C5F84472D4F81C5229439C -:1025B000C4F81C120C330EF1010EBDE7846A002131 -:1025C000C4F81C12C4F80412C4F80C12C4F8141293 -:1025D000AEE7002AF2D1836A0022C3F84022C3F892 -:1025E0004422C3F80422C3F814220122C3F80C22A7 -:1025F000C3F81C22A2E7BDE8F08100BFE022002062 -:10260000001002400000FFFF184A916A08B58B686D -:102610008B6013F0010105D013F00C0F14BF4FF4C1 -:1026200080310121D80506D513F4406F14BF41F461 -:10263000003141F00201D80306D513F4402F14BF36 -:1026400041F4802141F00401D3690BB10748984758 -:10265000202383F311880021054800F087FE002322 -:1026600083F31188BDE8084001F088B8E02200201B -:10267000E822002038B5124CA36ADD68AA0712D000 -:102680005A6922F002025A61A36913B1012120465E -:102690009847202383F3118800210A4800F066FE42 -:1026A000002383F31188EB0606D5A36A1021D960B5 -:1026B000236A0BB102489847BDE8384001F05EB884 -:1026C000E0220020F022002038B5124CA36A1D69D8 -:1026D000AA0712D05A6922F010025A61A36913B1F5 -:1026E000022120469847202383F3118800210A48BD -:1026F00000F03CFE002383F31188EB0606D5A36AA5 -:1027000010211961236A0BB102489847BDE838408F -:1027100001F034B8E0220020F022002038B50F4C40 -:10272000A36A5D685D602A070AD5032222701A68D1 -:1027300022F002021A60636A13B100212046984712 -:102740006B0706D5A36A9969236A13B10904034884 -:102750009847BDE8384001F011B800BFE0220020E2 -:1027600010B50F4C204600F03DFA0E4BA3620B2132 -:10277000132000F017FA0B21142000F013FA0B219C -:10278000152000F00FFA0B21162000F00BFA0023A1 -:1027900020461A460E21BDE81040FFF793BE00BF49 -:1027A000E0220020006400400F4B984210B5044620 -:1027B00005D10E4BDA6942F00072DA61DB69A36A77 -:1027C00001221A60A36A5A68D20707D56268516865 -:1027D0001268D9611A60064A5A6110BD01210820A9 -:1027E00000F07CFCEEE700BFE02200200010024079 -:1027F0005B87010003291AD8DFE801F0020A0F14F1 -:10280000836A9B6813F0E05F14BF012000207047CB -:10281000836A9868C0F380607047836A9868C0F3E1 -:10282000C0607047836A9868C0F3007070470020EA -:102830007047000010B503291FD8DFE801F0021F20 -:102840002327816A8B68C3F30163183301EB0313F9 -:10285000107881061ED55468C0F30011490041EA82 -:10286000C40141F0040100F00F00586090689860C6 -:10287000D268DA6041F00101196010BD836A03F586 -:10288000C073E5E7836A03F5C873E1E7836A03F57C -:10289000D073DDE79488C0F30011490041EA445148 -:1028A000E1E7000001290CD003D3022910D0002059 -:1028B0007047836ADA68920701D1186903E0012042 -:1028C0007047836AD86810F0030018BF0120704772 -:1028D000836AF2E710B539B9836AD96889071BD1D1 -:1028E0001B699B0704D110BD012915D0022948D1CD -:1028F000816AD1F8C031D1F8C401D1F8C84114615E -:10290000D1F8CC41546120240C610C69A40717D183 -:102910004C6944F0100412E0816AD1F8B031D1F86A -:10292000B401D1F8B8411461D1F8BC4154612024FC -:10293000CC60CC68A40703D14C6944F002044C611C -:1029400011795C0864F304119C0864F3451111715A -:1029500089064BBF91681189DB085B0D4CBF63F39F -:102960001C0163F30A01137948BF916060F303030C -:1029700013714FEA10234FEA104058BF11811370B2 -:10298000508010BD002304491A465A50C818083315 -:10299000802B4260F9D170470C2300200268436805 -:1029A0001143016003B1184770470000024A1368E1 -:1029B00043F0C0031360704700380140024A1368B7 -:1029C00043F0C00313607047004400402DE9F04716 -:1029D000C66D3768F46934620546200719D014F0D3 -:1029E000080F0CBF00218021E20748BF41F0200101 -:1029F000A30748BF41F04001600748BF41F4807120 -:102A0000202383F31188281DFFF7C8FF002383F3D9 -:102A10001188E2050AD5202383F311884FF4007151 -:102A2000281DFFF7BBFF002383F311884FF0200917 -:102A30004FF0000A14F0200831D13B0616D54FF0B4 -:102A4000200905F1380A200610D589F3118850466F -:102A500000F04CFA00282FDA0821281DFFF79EFF0E -:102A600027F080033360002383F3118879060DD5A6 -:102A700062060BD5202383F31188EA6C2B6D9A42F2 -:102A800001D12B6CF3B9002383F31188E30621D520 -:102A9000AA6E1369F3B15069BDE8F047184789F38E -:102AA0001188B38C95F864102846194000F0AAFAF2 -:102AB0008AF31188F469BDE780B2308588F3118804 -:102AC000F469C0E71021281D27F04007FFF766FFD3 -:102AD0003760D8E7BDE8F08708B50348FFF776FF11 -:102AE000BDE8084000F04ABE8C23002008B503482A -:102AF000FFF76CFFBDE8084000F040BEF82300205F -:102B000037B51D4C1D4D204600F070FA009404F1BD -:102B10001400002320221A4900F032F920220094E8 -:102B200004F13800174B184900F0ACF9174BE36576 -:102B30002566174C0C21252000F034F8204600F0C3 -:102B400055FA04F11400009400232022114900F0EA -:102B500017F904F1380000940F4B1049202200F0BF -:102B600091F90F4BE3650C212620256603B0BDE8E3 -:102B7000304000F017B800BF8C2300200051250220 -:102B800064240020AD290008A4240020003801405E -:102B9000F823002084240020BD290008C42400203C -:102BA0000044004000F1604300F01F02400903F5BB -:102BB000614309018000C9B200F1604083F800134D -:102BC00000F5614001239340C0F8803103607047F5 -:102BD00000F16040090100F56D40C9B2017670470F -:102BE000FFF7BEBD00F108020123037082600023DD -:102BF000C26000F110024360026142618361C361FF -:102C0000036243627047000010B52023044683F33B -:102C10001188022303704160FFF7C6FD0323237070 -:102C2000002383F3118810BD2DE9F0411F460446AF -:102C30000D461646202383F3118800F108082378F7 -:102C4000042B0ED029462046FFF7D4FD48B120467C -:102C500032462946FFF7EEFD002080F31188BDE8DB -:102C6000F0813946404600F065FB0028E7D000239C -:102C700083F31188BDE8F0812DE9F0411F46044639 -:102C80000D461646202383F3118800F1100823789F -:102C9000042B0ED029462046FFF704FE48B12046FB -:102CA00032462946FFF716FE002080F31188BDE862 -:102CB000F0813946404600F03DFB0028E7D0002374 -:102CC00083F31188BDE8F081F8B51546826806697E -:102CD000AA420B46816938BF8568761AB542044618 -:102CE00007D218462A46FEF767FBA3692B44A36167 -:102CF0000DE011D932461846FEF75EFBAF1B3A468F -:102D0000E1683044FEF758FBE2683A44A261A368E8 -:102D10005B1BA3602846F8BD18462A46FEF74CFB0D -:102D2000E368E4E783682DE9F041044693421546E1 -:102D3000266938BF85684069361AB5420F4606D203 -:102D40002A46FEF739FB63692B4463610DE012D913 -:102D50003246A5EB0608FEF72FFB4246B919E0689C -:102D6000FEF72AFBE26842446261A3685B1BA36032 -:102D70002846BDE8F0812A46FEF71EFBE368E4E73B -:102D800010B50A440024C361029B00604060846067 -:102D9000C160816141610261036210BD08B5826951 -:102DA0004369934201D1826882B9826801328260AC -:102DB0005A1C42611970426903699A4201D3C3687F -:102DC0004361002100F0C6FA002008BD4FF0FF303B -:102DD00008BD000070B5202304460E4683F3118819 -:102DE000A568A5B1A368A269013BA360531CA361B8 -:102DF00015782269934224BFE368A361E3690BB1AC -:102E000020469847002383F31188284670BD314639 -:102E1000204600F08FFA0028E2DA85F3118870BDB1 -:102E20002DE9F74F05460F4690469A46D0F81C907C -:102E3000202686F311884FF0000B144664B1224619 -:102E400039462846FFF740FF034668B951462846F1 -:102E500000F070FA0028F1D0002383F31188A8EB6A -:102E6000040003B0BDE8F08FB9F1000F03D001906A -:102E70002846C847019B8BF31188E41A1F4486F348 -:102E80001188DBE7C16081614161C3611144009B2E -:102E9000006040608260016103627047F8B50446DB -:102EA0000E461746202383F31188A568A5B1A368B1 -:102EB000013BA36063695A1C62611E7023696269E9 -:102EC0009A4224BFE3686361E3690BB120469847E7 -:102ED000002080F31188F8BD3946204600F02AFA18 -:102EE0000028E2DA85F31188F8BD000083694269A1 -:102EF0009A4210B501D182687AB982680132826043 -:102F00005A1C82611C7803699A4201D3C3688361A9 -:102F1000002100F01FFA204610BD4FF0FF3010BD19 -:102F20002DE9F74F05460F4690469A46D0F81C907B -:102F3000202686F311884FF0000B144664B1224618 -:102F400039462846FFF7EEFE034668B95146284643 -:102F500000F0F0F90028F1D0002383F31188A8EBEA -:102F6000040003B0BDE8F08FB9F1000F03D0019069 -:102F70002846C847019B8BF31188E41A1F4486F347 -:102F80001188DBE7026843681143016003B1184709 -:102F9000704700001430FFF743BF00004FF0FF33CD -:102FA0001430FFF73DBF00003830FFF7B9BF000015 -:102FB0004FF0FF333830FFF7B3BF00001430FFF796 -:102FC00009BF00004FF0FF311430FFF703BF0000CE -:102FD0003830FFF763BF00004FF0FF323830FFF7A3 -:102FE0005DBF000000207047FFF78ABD044B0360FF -:102FF000002343608360C36001230374704700BFF4 -:103000009842000838B5C36904460D461BB904212F -:103010000844FFF7B7FF294604F11400FFF7BEFE8E -:10302000002806DA201D4FF48061BDE83840FFF724 -:10303000A9BF38BD024B00221B605B609A607047DD -:10304000E4240020002303748268054B1B68996800 -:103050009142FBD25A68036042601060586070472A -:10306000E424002008B5202383F31188037C032B7C -:1030700005D0042B0DD02BB983F3118808BD43690B -:1030800000221A604FF0FF334361FFF7DBFF00239C -:10309000F2E790E80C001A6002685360F2E7000063 -:1030A000002303748268054B1B6899689142FBD822 -:1030B0005A6803604260106058607047E424002042 -:1030C000054B19690874186802681A605360186122 -:1030D00001230374FDF798BAE424002030B54B1C9B -:1030E00087B005460A4C10D023690A4A01A800F0AF -:1030F00059F92846FFF7E4FF049B13B101A800F03B -:103100006BF92369586907B030BDFFF7D9FFF8E7BD -:10311000E42400206530000838B50C4D41612B696E -:1031200081689A689142044603D8BDE83840FFF7A9 -:1031300089BF1846FFF786FF01232C6101462374DF -:103140002046BDE83840FDF75FBA00BFE424002008 -:10315000044B1A681B6990689B68984294BF0020D2 -:1031600001207047E424002010B5084C2368206932 -:103170001A6822605460012223611A74FFF790FFDD -:1031800001462069BDE81040FDF73EBAE424002066 -:1031900008B5FFF7DDFF18B1BDE80840FFF7E4BF51 -:1031A00008BD0000FEE7000010B5174CFFF742FF16 -:1031B00000F0EAF880221549204600F06FF801235C -:1031C00044F8180C0374124B124AD96821F4E061D8 -:1031D0000904090C0A431049DA60CA6842F0807297 -:1031E000CA600E490A6842F001020A601022DA77CA -:1031F000202283F82220002383F3118862B6084836 -:10320000BDE8104000F06CB80C250020C04200085A -:1032100000ED00E00003FA05F0ED00E0001000E032 -:10322000C8420008F8B50F4C226A013222622246D9 -:1032300052F8141F9142154606D08B68013B8B60F3 -:10324000202663699A6802B1F8BD1968DF68DA6000 -:103250004D60616182F311881869B84786F311885F -:10326000EFE700BFE4240020EFF3118020B9EFF373 -:103270000583202282F311887047000010B558B9E9 -:10328000EFF30584C4F3080414B180F3118810BD72 -:10329000FFF77EFF84F3118810BD000082600222D8 -:1032A00002740022427470478368A3F17C0243F8E1 -:1032B0000C2C026943F83C2C426943F8382C074A2D -:1032C00043F81C2CC26843F8102C022203F8082C87 -:1032D000002203F8072CA3F118007047210600080C -:1032E00010B5202383F31188FFF7DEFF0021044689 -:1032F000FFF712FF002383F31188204610BD000062 -:10330000024B1B6958610F20FFF7DABEE42400204E -:10331000202383F31188FFF7F3BF000008B50146AF -:10332000202383F311880820FFF7D8FE002383F3BE -:10333000118808BD49B1064B42681B6918605A6084 -:10334000136043600420FFF7C9BE4FF0FF307047A1 -:10335000E42400200368984206D01A680260506096 -:1033600059611846FFF76EBE7047000038B5044635 -:103370000D462068844200D138BD036823605C603C -:103380004561FFF75FFEF4E7054B03F114025A6154 -:103390009A614FF0FF32DA6100221A62704700BF73 -:1033A000E424002010B5C2600A4A036153699C6896 -:1033B000A1420CD85C680360446020605860816062 -:1033C0009868411A99604FF0FF33D36110BD091B13 -:1033D0001B68ECE7E4240020036881689A680A44CB -:1033E0009A604268136003685A600023C360024B0E -:1033F0004FF0FF32DA617047E4240020002070476C -:10340000FEE70000704700004FF0FF3070470000FB -:10341000BFF34F8F024AD368DB07FCD4704700BF6D -:103420000020024008B5074B1B7853B9FFF7F0FFA7 -:10343000054B1A69120641BF044A5A6002F18832EC -:103440005A6008BD70260020002002402301674515 -:1034500008B5054B1B7833B9FFF7DAFF034A136948 -:1034600043F08003136108BD702600200020024055 -:103470007F289ABF00F58030C0020020704700000E -:103480004FF4006070470000802070477F2808B527 -:103490000BD8FFF7EDFF00F500630268013204D19D -:1034A00004308342F9D1012008BD002008BD00008E -:1034B0007F2838B5044624D800F0B6F8124D2860AD -:1034C000FFF7A6FFFFF7AEFF104BF322DA600222F0 -:1034D0001A612046FFF7CCFF58611A6942F040029A -:1034E0001A61FFF795FF4FF4006100F0FBF8FFF75A -:1034F000AFFF00F099F828602046BDE83840FFF79C -:10350000C5BF002038BD00BF742600200020024047 -:103510002DE9F84312F00103144606D0204B40F287 -:103520004B221A600020BDE8F88385181D4A954299 -:1035300004D91B4A4FF414711160F3E7FFF772FFCF -:10354000FFF766FFDFF86C80451A4FF00109012C88 -:1035500005EB01060F4604D8FFF77AFF0120BDE80E -:10356000F883C8F8109031F8023B3380FFF750FF22 -:103570000020C8F8100033883A889BB29A420DD0D8 -:10358000074B40F267221A60074B1E60074B1C6016 -:10359000074B1F60FFF75CFFBDE8F883023CD6E7EE -:1035A0006C260020FFFF030860260020682600200C -:1035B0006426002000200240084908B50B7828B195 -:1035C00053B9FFF72FFF01230B7008BD23B1BDE8EE -:1035D00008400870FFF73CBF08BD00BF7026002000 -:1035E00038B5FFF741FE0D4B0D4A1C6A11684FF4C8 -:1035F0007A7303FB04F38B420A49D1E9004504D2F4 -:10360000003445F10105C1E90045E41845F1000524 -:103610001360FFF733FE2046294638BDE42400201E -:10362000782600208026002008B5FFF7D9FF4FF448 -:103630007A720023FCF7CCFD08BD00BF10B5024430 -:10364000064B0439D2B2904200D110BD441C00B2E6 -:1036500053F8200041F8040FE0B2F4E7502800408E -:10366000104B30B51C6A240407D41C6A44F440741F -:103670001C621C6A44F400441C620B4C236843F433 -:10368000807323600244094B0439D2B2904200D1C6 -:1036900030BD441C00B251F8045F43F82050E0B242 -:1036A000F4E700BF001002400070004050280040C6 -:1036B00007B5012201A90020FFF7C0FF019803B060 -:1036C0005DF804FB13B50446FFF7F2FFA04206D0F5 -:1036D00002A9012241F8044D0020FFF7C1FF02B00A -:1036E00010BD000070470000074B45F255521A60AC -:1036F00002225A6040F6FF729A604CF6CC421A6081 -:10370000024B01221A7070470030004089260020C9 -:10371000034B1B781BB1034B4AF6AA221A60704771 -:103720008926002000300040034B1B689B0042BFED -:10373000024B01221A707047241002408826002094 -:10374000024B4FF080721A60704700BF2410024095 -:10375000014B1878704700BF88260020064A53683E -:1037600023F001035360EFF30983683383F309887F -:10377000002383F31188704730EF00E010B5202359 -:1037800083F31188104B5B6813F4006318D0F1EEDB -:10379000103AEFF309844FF0807344F84C3C0B4B24 -:1037A000DB6844F8083CA4F1680383F30988FFF759 -:1037B000CFFC18B1064B44F8503C10BD054BFAE75E -:1037C00083F3118810BD00BF00ED00E030EF00E092 -:1037D000310600083406000870470000FEE70000CC -:1037E000084A094B09498B4204D3094A00219342F4 -:1037F00005D3704752F8040F43F8040BF3E743F87E -:10380000041BF4E74844000890260020902600207E -:10381000902600204B6843608B688360CB68C36050 -:103820000B6943614B6903628B6943620B680360F8 -:103830007047000008B5194B9A6A42F4FC029A627C -:103840009A6A22F4FC029A629A6A5A6942F4FC0269 -:103850005A61134A5B6911464FF09040FFF7DAFF57 -:10386000104802F11C01FFF7D5FF0F4802F13801A3 -:10387000FFF7D0FF0D4802F15401FFF7CBFF0C48D2 -:1038800002F17001FFF7C6FF0A4802F18C01FFF751 -:10389000C1FFBDE8084000F065B800BF001002405D -:1038A000E84200080004004800080048000C0048F6 -:1038B000001000480014004808B500F08FF9FFF729 -:1038C00073FCBDE80840FFF72FBF00007047000001 -:1038D00010B5214CA26A62F4FC02A262A26A02F450 -:1038E000FC02A2624FF0FF31A26A226921612269C3 -:1038F000002222612069E068E160E168E260E1683D -:10390000E169164841F08051E161E169016841F4E3 -:1039100080710160216A01F44071B1F5407F1EBFE2 -:103920004FF4803323622262236A1B0407D4236A84 -:1039300043F440732362236A43F40043236200F09C -:103940002DF9A369064A43F00103A361A369136833 -:1039500043F02003136010BD0010024000700040CF -:10396000000001401C4B1A6842F001021A601A68FC -:103970009007FCD55A6822F003025A605A6812F088 -:103980000C02FBD1196801F0F90119605A601A683C -:1039900042F480321A601A689103FCD50F4A5A60CB -:1039A0004FF40452DA6230221A631A6842F08072CD -:1039B0001A601A689201FCD5094A122111605A68EE -:1039C00042F002025A605A6802F00C02082AFAD148 -:1039D0001A6B1A63704700BF0010024000241D00DC -:1039E00000200240084A08B5536911680B4003F0F3 -:1039F0000103536123B1054A13680BB1506898471E -:103A0000BDE80840FFF7BABE000401400C230020C7 -:103A1000084A08B5536911680B4003F0020353616B -:103A200023B1054A93680BB1D0689847BDE80840B8 -:103A3000FFF7A4BE000401400C230020084A08B58B -:103A4000536911680B4003F00403536123B1054A25 -:103A500013690BB150699847BDE80840FFF78EBE67 -:103A6000000401400C230020084A08B5536911687E -:103A70000B4003F00803536123B1054A93690BB16E -:103A8000D0699847BDE80840FFF778BE00040140C0 -:103A90000C230020084A08B5536911680B4003F055 -:103AA0001003536123B1054A136A0BB1506A98475A -:103AB000BDE80840FFF762BE000401400C2300206F -:103AC000174B10B55C691A68144004F478725A6197 -:103AD000A30604D5134A936A0BB1D06A98476006CF -:103AE00004D5104A136B0BB1506B9847210604D5CF -:103AF0000C4A936B0BB1D06B9847E20504D5094A89 -:103B0000136C0BB1506C9847A30504D5054A936C10 -:103B10000BB1D06C9847BDE81040FFF72FBE00BF37 -:103B2000000401400C2300201A4B10B55C691A6890 -:103B3000144004F47C425A61620504D5164A136DA0 -:103B40000BB1506D9847230504D5134A936D0BB103 -:103B5000D06D9847E00404D50F4A136E0BB1506E38 -:103B60009847A10404D50C4A936E0BB1D06E9847C8 -:103B7000620404D5084A136F0BB1506F98472304B1 -:103B800004D5054A936F0BB1D06F9847BDE810403C -:103B9000FFF7F4BD000401400C230020062108B506 -:103BA0000846FEF7FFFF06210720FEF7FBFF062170 -:103BB0000820FEF7F7FF06210920FEF7F3FF062194 -:103BC0000A20FEF7EFFF06211720FEF7EBFF062184 -:103BD0002820BDE80840FEF7E5BF000008B5FFF764 -:103BE00077FEFEF7CFFEFEF7FBFFFFF7FDF9FFF7CD -:103BF0006DFEBDE8084000F001B8000000F00EB80E -:103C000008B5202383F31188FFF70CFB002383F30F -:103C10001188BDE80840FFF7B1BD0000054B064A1A -:103C20005A6000229A6007221A6008210B20FEF7D2 -:103C3000CFBF00BF10E000E03F1901001FB51C46D8 -:103C4000094B1B680546D86852B1084B02928DE8B3 -:103C50000A0022462B460649FDF718FC00F042F800 -:103C6000044B1A46F2E700BF1011002090430008F1 -:103C70009D430008143E000810B5013902449042EB -:103C800001D1002010BD10F8013B11F8014FA342F3 -:103C9000F5D0181B10BD00002DE9F84307468846F3 -:103CA00091461E468BB10D46A8EB0500B54207EBC9 -:103CB000000402D20020BDE8F8833246494620467F -:103CC000FFF7DAFF18B1013DEEE7BDE8F8832046C3 -:103CD000BDE8F883034611F8012B03F8012B002AF5 -:103CE000F9D1704708B5062000F02CF80120FFF745 -:103CF00087FB00001F2938B504460D4604D916235A -:103D000003604FF0FF3038BD426C12B152F82130E1 -:103D10004BB9204600F030F82A4601462046BDE85F -:103D2000384000F017B8012B0AD0591C03D11623D4 -:103D30000360012038BD002442F8254028469847FA -:103D4000002038BD024B01461868FFF7D3BF00BF03 -:103D50001011002038B5074C0023054608461146CF -:103D60002360FFF751FB431C02D1236803B12B6092 -:103D700038BD00BF8C260020FFF740BB40A2E4F115 -:103D8000646891064E6F20617070207369670A0045 -:103D9000426164206677206C656E677468202575C3 -:103DA0000A0042616420626F6172645F6964202569 -:103DB000752073686F756C642062652025750A0034 -:103DC0004261642066772064657363726970746F02 -:103DD00072206C656E6774682025750A0042616404 -:103DE0002061707020435243203078253038783A73 -:103DF000307825303878203078253038783A307867 -:103E0000253038780A00476F6F64206669726D77D5 -:103E10006172650A00000000726563656976656419 -:103E20005F756E697175655F69645F6C656E203C76 -:103E30002055415643414E5F50524F544F434F4CD3 -:103E40005F44594E414D49435F4E4F44455F49449D -:103E50005F414C4C4F434154494F4E5F554E495181 -:103E600055455F49445F4D41585F4C454E47544866 -:103E7000002E2E2F2E2E2F546F6F6C732F41505FFC -:103E8000426F6F746C6F616465722F63616E2E6335 -:103E9000707000616C6C6F63617465645F6E6F64F9 -:103EA000655F6964203C3D20313237006F72672EB8 -:103EB0006172647570696C6F742E61705F70657289 -:103EC0006970685F756E6976657273616C00000079 -:103ED000766F69642068616E646C655F616C6C6F9D -:103EE000636174696F6E5F726573706F6E7365285E -:103EF00043616E617264496E7374616E63652A2CEE -:103F00002043616E61726452785472616E736665AB -:103F1000722A290063616E617264496E69740000DF -:103F200063616E6172645365744C6F63616C4E6F54 -:103F3000646549440000000063616E617264486119 -:103F40006E646C6552784672616D650063616E6186 -:103F500072644465636F64655363616C61720000F1 -:103F600063616E617264456E636F64655363616C17 -:103F700061720000696E6372656D656E7454726182 -:103F80006E73666572494400656E7175657565543A -:103F9000784672616D6573007075736854785175F9 -:103FA0006575650070726570617265466F724E6509 -:103FB00078745472616E736665720000636F707915 -:103FC0004269744172726179000000006465736334 -:103FD00061747465725472616E7366657250617952 -:103FE0006C6F61640000000066726565426C6F630F -:103FF0006B0000006269745F6C656E677468203ED8 -:1040000020300072656D61696E696E675F62697408 -:1040100073203E203000696E7075745F6269745F52 -:104020006F6666736574203E3D20626C6F636B5FE4 -:104030006269745F6F666673657400626C6F636B50 -:104040005F656E645F6269745F6F66667365742036 -:104050003E20626C6F636B5F6269745F6F6666734C -:1040600065740072656D61696E696E675F6269741F -:104070005F6C656E677468203C3D2072656D616998 -:104080006E696E675F6269747300696E7075745FE4 -:104090006269745F6F6666736574203C3D2074725C -:1040A000616E736665722D3E7061796C6F61645FDD -:1040B0006C656E202A2038006F75747075745F62AD -:1040C00069745F6F6666736574203C3D203634000A -:1040D00072656D61696E696E675F6269745F6C6558 -:1040E0006E677468203D3D20300028726573756CE2 -:1040F00074203E2030292026262028726573756C96 -:1041000074203C3D203634292026262028726573F1 -:10411000756C74203C3D206269745F6C656E6774D9 -:104120006829000064657374696E6174696F6E203C -:10413000213D202828766F6964202A2930290076BD -:10414000616C756520213D202828766F6964202ADE -:10415000293029006F66667365745F7769746869D2 -:104160006E5F626C6F636B203C2028333255202DCC -:10417000205F5F6275696C74696E5F6F66667365F8 -:10418000746F66202843616E61726442756666656D -:1041900072426C6F636B2C2064617461292900008A -:1041A0006F75745F696E7320213D202828766F69D2 -:1041B00064202A29302900007372635F6C656E20C9 -:1041C0003E203055000000002863616E5F69642066 -:1041D0002620307831464646464646465529203DFB -:1041E0003D2063616E5F696400000000616C6C6F6C -:1041F0006361746F722D3E73746174697374696363 -:10420000732E63757272656E745F75736167655F37 -:10421000626C6F636B73203E203000007472616EBD -:10422000736665725F696420213D202828766F6976 -:1042300064202A293029000073746174652D3E6260 -:1042400075666665725F626C6F636B73203D3D20BF -:104250002828766F6964202A293029002E2E2F2ED7 -:104260002E2F6D6F64756C65732F6C696263616E60 -:104270006172642F63616E6172642E63006974659C -:104280006D2D3E6672616D652E646174615F6C6553 -:104290006E203E203000000000000000B12F00081A -:1042A0009D2F0008D92F0008C52F0008D12F000826 -:1042B000BD2F0008A92F0008952F0008E52F000842 -:1042C0006D61696E00000000E042000828250020B2 -:1042D0006026002001000000A53100080000000059 -:1042E00069646C6500000000A001A82A00000000BD -:1042F000FAAABEAA50001400EFFF000000770000E9 -:10430000709709000100000000000000AAAAAAAAF4 -:1043100001000000FFFF000000000000000000009E -:104320000000000000000000AAAAAAAA00000000E5 -:10433000FFFF00000000000000000000000000007F -:1043400000000000AAAAAAAA00000000FFFF0000C7 -:10435000000000000000000000000000000000005D -:10436000AAAAAAAA00000000FFFF000000000000A7 -:10437000000000000000000000000000AAAAAAAA95 -:1043800000000000FFFF000000000000000000002F -:104390002C2066756E6374696F6E3A2000617373CA -:1043A000657274696F6E2022257322206661696CC4 -:1043B00065643A2066696C6520222573222C206C86 -:1043C000696E65202564257325730A0034BEFF7F5E -:1043D0000100000000000000640000000000000078 -:1043E000FE2A0100D2040000141100200000000089 -:1043F00000000000000000000000000000000000BD -:1044000000000000000000000000000000000000AC -:10441000000000000000000000000000000000009C -:10442000000000000000000000000000000000008C -:10443000000000000000000000000000000000007C -:0C44400000000000000000000000000070 +:1000000000090020A5040008E1140008611400089C +:10001000B9140008611400088D140008A704000832 +:10002000A7040008A7040008A704000881350008F9 +:10003000A7040008A7040008A7040008B93A0008AC +:10004000A7040008A7040008A7040008A7040008E4 +:10005000A7040008A7040008513800087D380008EC +:10006000A9380008D538000801390008A70400089D +:10007000A7040008A7040008A7040008A7040008B4 +:10008000A7040008A7040008A70400082924000802 +:1000900095240008E92400083D2500082D390008B2 +:1000A000A7040008A7040008A7040008A704000884 +:1000B000A7040008A7040008A7040008A704000874 +:1000C000A7040008A7040008A7040008A704000864 +:1000D000A70400088129000895290008A704000842 +:1000E00095390008A7040008A7040008A704000821 +:1000F000A7040008A7040008A7040008A704000834 +:10010000A7040008A7040008A7040008A704000823 +:10011000A7040008A7040008A7040008A704000813 +:10012000A7040008A7040008A7040008A704000803 +:10013000A7040008A7040008A7040008A7040008F3 +:10014000A7040008A7040008A7040008A7040008E3 +:10015000A7040008A7040008A7040008A7040008D3 +:10016000A7040008A7040008A7040008A7040008C3 +:10017000A7040008A7040008A7040008A7040008B3 +:10018000A7040008A7040008A7040008A7040008A3 +:10019000A7040008A7040008A7040008A704000893 +:1001A00053B94AB9002908BF00281CBF4FF0FF31DE +:1001B0004FF0FF3000F074B9ADF1080C6DE904CEDA +:1001C00000F006F8DDF804E0DDE9022304B0704732 +:1001D0002DE9F047089D04468E46002B4DD18A42FA +:1001E000944669D9B2FA82F252B101FA02F3C2F12D +:1001F000200120FA01F10CFA02FC41EA030E9440BE +:100200004FEA1C48210CBEFBF8F61FFA8CF708FBDE +:1002100016E341EA034306FB07F199420AD91CEBB6 +:10022000030306F1FF3080F01F81994240F21C81E8 +:10023000023E63445B1AA4B2B3FBF8F008FB103330 +:1002400044EA034400FB07F7A7420AD91CEB040465 +:1002500000F1FF3380F00A81A74240F20781644435 +:10026000023840EA0640E41B00261DB1D4400023BA +:10027000C5E900433146BDE8F0878B4209D9002D1E +:1002800000F0EF800026C5E9000130463146BDE8A8 +:10029000F087B3FA83F6002E4AD18B4202D3824212 +:1002A00000F2F980841A61EB030301209E46002DC1 +:1002B000E0D0C5E9004EDDE702B9FFDEB2FA82F216 +:1002C000002A40F09280A1EB0C014FEA1C471FFA74 +:1002D0008CFE0126200CB1FBF7F307FB131140EA5B +:1002E00001410EFB03F0884208D91CEB010103F128 +:1002F000FF3802D2884200F2CB804346091AA4B2EA +:10030000B1FBF7F007FB101144EA01440EFB00FEBD +:10031000A64508D91CEB040400F1FF3102D2A64522 +:1003200000F2BB800846A4EB0E0440EA03409CE7C1 +:10033000C6F12007B34022FA07FC4CEA030C20FA6E +:1003400007F401FA06F31C43F9404FEA1C4900FA8E +:1003500006F3B1FBF9F8200C1FFA8CFE09FB18110B +:1003600040EA014108FB0EF0884202FA06F20BD97E +:100370001CEB010108F1FF3A80F08880884240F2CE +:100380008580A8F102086144091AA4B2B1FBF9F012 +:1003900009FB101144EA014100FB0EFE8E4508D90D +:1003A0001CEB010100F1FF346CD28E456AD9023892 +:1003B000614440EA0840A0FB0294A1EB0E01A14277 +:1003C000C846A64656D353D05DB1B3EB080261EBE5 +:1003D0000E0101FA07F722FA06F3F1401F43C5E9BF +:1003E000007100263146BDE8F087C2F12003D840F5 +:1003F0000CFA02FC21FA03F3914001434FEA1C4737 +:100400001FFA8CFEB3FBF7F007FB10360B0C43EA28 +:10041000064300FB0EF69E4204FA02F408D91CEBD8 +:10042000030300F1FF382FD29E422DD902386344D6 +:100430009B1B89B2B3FBF7F607FB163341EA034176 +:1004400006FB0EF38B4208D91CEB010106F1FF38C5 +:1004500016D28B4214D9023E6144C91A46EA0046BC +:1004600038E72E46284605E70646E3E61846F8E64E +:100470004B45A9D2B9EB020864EB0C0E0138A3E797 +:100480004646EAE7204694E74046D1E7D0467BE778 +:10049000023B614432E7304609E76444023842E7F0 +:1004A000704700BF02E000F000F8FEE772B63A487D +:1004B00080F30888394880F3098839484EF6085196 +:1004C000CEF20001086040F20000CCF200004EF6CF +:1004D0003471CEF200010860BFF34F8FBFF36F8F0E +:1004E00040F20000C0F2F0004EF68851CEF200015A +:1004F0000860BFF34F8FBFF36F8F4FF00000E1EE46 +:10050000100A4EF63C71CEF200010860062080F31E +:100510001488BFF36F8F03F0B3F803F08FF803F084 +:10052000C1F84FF055301F491B4A91423CBF41F87A +:10053000040BFAE71C49194A91423CBF41F8040BED +:10054000FAE71A491A4A1B4B9A423EBF51F8040B6C +:1005500042F8040BF8E700201749184A91423CBFC3 +:1005600041F8040BFAE703F06DF803F0D7F8144CE8 +:10057000144DAC4203DA54F8041B8847F9E700F045 +:1005800041F8114C114DAC4203DA54F8041B884772 +:10059000F9E703F055B80000000900200011002021 +:1005A000000000080001002000090020003D0008B4 +:1005B00000110020201100202011002028260020FA +:1005C000A0010008A0010008A0010008A001000887 +:1005D0002DE9F04F2DED108AC1F80CD0C3689D466F +:1005E000BDEC108ABDE8F08F002383F31188284604 +:1005F000A047002002F04CFDFEE702F0D1FC00DF36 +:10060000FEE700002DE9F04102F062FF074602F02C +:10061000ADFF054600283ED12B4B9F423BD0013316 +:100620009F423BD0294B27F0FF029A423AD1F8B2C1 +:1006300000F054FAA84642F2107400F059FC08B1D8 +:100640000024A04600F050FA064678B384BB464624 +:1006500035B11F4B9F4203D002F080FF0024264695 +:10066000002002F03FFF1B4B1B6913F0400322D018 +:100670000EB100F031F800F05FFC00F031FE00F048 +:1006800031FF0546CCB100F02DFF401BA04214D92C +:1006900000F022F8F3E7A8460024CEE704464FF026 +:1006A0000108CAE780464FF47A74C6E70446CFE7EC +:1006B0004FF47A74CCE71C46DDE700F0DDFC012046 +:1006C00002F0ECFCDEE700BF010007B0000008B05C +:1006D000263A09B00004004838B51D4A1D4B196878 +:1006E000013134D004339342F9D11B4C194DD4F865 +:1006F0000428AA422BD3194B9B6803F1006303F52E +:10070000D0439A4223D202F0FDFE02F00FFF0020F8 +:1007100000F000FE124B0220187000F037FE114B63 +:10072000DA690022DA61D96999699A619B6972B6BE +:100730004FF0E0232021C3F8085DD4F80038D4F846 +:10074000042881F311889D4683F30888104738BD3B +:100750002068000800680008006000080011002000 +:100760002011002000100240094A136849F2690074 +:1007700099B21B0C00FB01331360064B186844F25E +:10078000506182B2000C01FB0200186080B2704719 +:100790001C1100201811002010B500211022044661 +:1007A00000F00EFE034B03CB206061601868A06070 +:1007B00010BD00BFACF7FF1F2DE9F043224DBBB0C9 +:1007C00000F090FEAB6840F2ED22C31A934232D99A +:1007D00006AFA8602B4628220021384601F05EFBB8 +:1007E00005F10E0000F0E4FD002604465FFA80F9F2 +:1007F00005F10E08F3B2F100994501F1280107D97E +:1008000008EB06030822384601F048FB0136F1E701 +:1008100008230122CDE9023205340C4B0193A4B226 +:1008200030230093CDE9047405A3D3E90023297B89 +:10083000074801F04BF93BB0BDE8F083AFF300800F +:1008400078F6339F93CACD8D682100207521002052 +:100850003C21002070B50D4614461E4601F0CCF830 +:1008600050B9022E10D1012C0ED112A3D3E90023CE +:10087000C5E90023012007E0282C10D005D8012C61 +:1008800009D0052C0FD0002070BD302CFBD10BA35C +:10089000D3E90023ECE70BA3D3E90023E8E70BA39C +:1008A000D3E90023E4E70BA3D3E90023E0E700BF8B +:1008B000AFF30080401DA12026812A0B78F6339FDC +:1008C00093CACD8D9E6AC421818A46EE26417272FA +:1008D000DF25D7B7F017304A39059E5613B50446C1 +:1008E0002346084620220021019001F0D7FA227900 +:1008F0000198032A234628BF032203F8042F20214E +:10090000022201F0CBFA62790198072A234628BF18 +:10091000072203F8052F2221032201F0BFFAA27952 +:100920000198072A234628BF072203F8062F25210E +:10093000032201F0B3FA019804F1080310222821E0 +:1009400001F0ACFA382002B010BD00002DE9F04FE4 +:10095000ADF5037D23AD10AE40F2751280460F4613 +:1009600024A80021296000F02BFD482200213046F8 +:1009700000F026FD00F0B6FD564B4FF47A72B0FB46 +:10098000F2F0186093E80700012386E807000DF1F4 +:1009900062003382FFF700FF4EF60343338407AB58 +:1009A00018464D4903F0C2F82122306429463046EA +:1009B00086F83C20FFF792FF14AB0446014608225C +:1009C000284601F06BFA0822A1180DF151032846C0 +:1009D00001F064FA0DF15203082204F110012846D7 +:1009E00001F05CFA15AB202204F11801284601F051 +:1009F00055FA16AB402204F13801284601F04EFAB0 +:100A000018AB082204F17801284601F047FA0DF1ED +:100A10006103082204F18001284601F03FFA04F145 +:100A2000880A0DF1620904F5847B4B465146082281 +:100A300028460AF1080A01F031FAD34509F1010903 +:100A4000F3D11DAB08225946284601F027FA04F5D8 +:100A500088744FF0000996F834304B450AD9B36BCF +:100A600021464B440822284601F018FA083409F1BF +:100A70000109F0E74FF0000996F83C304B4504EBD4 +:100A8000C90108D9336C08224B44284601F006FA04 +:100A900009F10109F0E700230393BB7E02930731BC +:100AA00007F119030193C1F3CF010123CDE90451EB +:100AB0000093F97E05A3D3E90023404601F006F830 +:100AC0000DF5037DBDE8F08FAFF300809E6AC42171 +:100AD000818A46EE241100203C3B0008014B18702F +:100AE000704700BF30110020F0B5334B1C7B85B040 +:100AF00034B1324B0E221A810024204605B0F0BDDD +:100B00002F4A1068516802AB03C308232D492E48B1 +:100B10000DEB030202F0E8FF054630B9274B2B48E6 +:100B20000A221A8100F098FCE6E70169B1F5663FF8 +:100B300006D9224B26480B221A8100F08DFCDCE7F7 +:100B4000438BB3F57B7F09D01C4A22480C211181CD +:100B50004FF47B72194600F07FFCCEE71E4A024438 +:100B600002F11003994204D2144B1C4810221A813E +:100B7000E3E710398E1A2046134900F0B7FC3246DD +:100B8000074605F11801204600F0B0FCAB689F4213 +:100B900002D1EB6898420AD0084B0D221A810090CE +:100BA000D5E902123B460E4800F056FCA4E70D487A +:100BB00000F052FC0124A0E768210020241100204D +:100BC000F13B0008DC97030000680008603B000868 +:100BD0006C3B00087E3B00080898FFF79C3B000830 +:100BE000B93B0008E23B00082DE9F04FADB006AF7D +:100BF00080460C4600F000FF054600285AD1237EAF +:100C0000022B1BD1E38A012B18D100F06BFC0646A6 +:100C1000FFF7AAFD03464FF4C870DFF8D092B3FB8C +:100C2000F0F206F5167602FB103316FA83F3C9F8D4 +:100C30000030E37E33B9A84B00221A709C37BD46C2 +:100C4000BDE8F08FA38AEEB2013BB34205F1010586 +:100C50000BD93B1D1E44E90000960023082201F039 +:100C6000F801204600F0DEFFECE707F11400FFF783 +:100C700093FD324607F11401381D02F025FF0028CC +:100C8000D9D10F2E08D8944B1E70D9F80030A3F597 +:100C90001673C9F80030D1E7FB1CF87001460093C9 +:100CA00007220346204600F0BDFFF978404600F0D9 +:100CB0009BFEC3E7E38A282B26D010D8012B1ED039 +:100CC000052BBBD1BFF34F8F8449854BCA6802F413 +:100CD000E0621343CB60BFF34F8F00BFFDE7302BC3 +:100CE000ACD1637E7F4D01336A7BDBB29342E94630 +:100CF00003D1E27E2B7B9A4265D0CD469EE721460A +:100D00004046FFF723FE99E7A38A013B9BB2C92B1C +:100D100094D8744D2E7B26BB05F10C03009308225A +:100D200033463146204600F07DFF731CF2B2D900F5 +:100D30001E46A38A013B9A4205DA0E322A440092EB +:100D400000230822EEE700230022C5E90023002348 +:100D5000AB6085F8D730C5F8D8302B7B0BB9E37E74 +:100D60002B73002507F114093B1D0822294648462C +:100D7000C7E90155FD6001F091F83B7A05F1010AE0 +:100D8000AB424FEACA0608D9FB6808222B44314619 +:100D9000484601F083F85546EFE7C6F3CF06E17EFB +:100DA000CDE9049600230393A37E029319342823EC +:100DB0000093019446A3D3E90023404600F086FE49 +:100DC000FFF7FAFC3AE74FF0000807F11403A7F821 +:100DD00014801022009341460123204600F022FF98 +:100DE000A68A023EB6B2F31C9B109B000733DB08B9 +:100DF000A9EBC3039D460DF1180A1FFA88F34FEAC9 +:100E0000C801B34201F110010AD20AEB08030093B2 +:100E100008220023204600F005FF08F10108ECE756 +:100E200095F8D70000F080FAD5F8D83004461BB901 +:100E300095F8D70000F088FAD5F8D83033449C42B2 +:100E400004D295F8D700013000F07EFA4FEA960BF5 +:100E50004FF000081FFA88F18B45D5E9003209D917 +:100E60000AEB880103EB8800012200F0B1FA08F1D7 +:100E70000108EFE7F31842F10002C5E90032D5F8A6 +:100E8000D83095F8D70006EB0308C5F8D88000F0F5 +:100E90004BFA804509D395F8D730D5F8D8000133FF +:100EA000001B85F8D730C5F8D800FF2E08D80023DE +:100EB0002B7300F05BFAFFF717FE08B1FFF70CFC8D +:100EC0002B68094A9B0A013313810023AB6014E7A6 +:100ED00026417272DF25D7B73521002000ED00E0F2 +:100EE0000400FA0568210020241100203821002088 +:100EF00010B54FF000540C4B22689A4211D10B4BA5 +:100F0000627D1A700A48237D03730A49C9220E3094 +:100F100000F044FAE0220021204600F051FA0120BE +:100F200010BD0020FCE700BF9AAD44C53011002081 +:100F300068210020160000202DE9FF41434C0223C8 +:100F400063710023029324250A23581EB5FBF3F690 +:100F50007343D3F12402C1B23ED002280346F4D138 +:100F60009DF80B303A493B485A1E9DF80A30013B28 +:100F70001B0443EA0253BDF80820013A13434B60B7 +:100F800001F044FD00230193334B3449009334486E +:100F9000344B4FF4805200F001FD334B197811B1FE +:100FA0002F4800F021FD00F09DFA0546FFF7DCFB1D +:100FB0004FF4C873B0FBF3F202FB130305F5167090 +:100FC00010FA83F0294B186002F0D0FA08B10F2311 +:100FD000238104B0BDE8F081C1EBC107FB1C4FEADF +:100FE000E30EC3F3C703A1EB030C0EF101084FF4AA +:100FF0007A705FFA8CF50EFB000058FA8CFCB0FB9F +:10100000FCF0B0F5617F07D97B1EC3F3C703C91A93 +:10101000CDB2591E0F2916D86A1E072A8CBF00228E +:101020000122591901FB06601149B1FBF0F1114889 +:10103000814295D1002A93D0ADF808608DF80A302E +:101040008DF80B508CE71346EBE700BF241100200E +:1010500010110020802200205508000834110020C3 +:101060003C210020E90B000830110020382100202D +:101070000051250240420F002DE9F04F90A7D7E91B +:1010800000670FF24429D9E90089874D93B0DFF852 +:1010900040B2864C284600F07DFD0DF1300A0790E5 +:1010A00070B310220021504600F08AF9079B197B8B +:1010B0004FF0000261F303028DF830205868996800 +:1010C0000EAA03C21B680D9A63F31C029DF8303010 +:1010D0000D9243F020038DF830300023524619461C +:1010E000584601F0A3FC079028B9284600F056FDA9 +:1010F000079B2370CEE72378072B3CD8013323705E +:1011000018220021504600F05BF9DFF8C4B100233B +:1011100019465246584601F0B1FC014678BB1022F0 +:1011200008A800F04DF94FF0904209AC536983F0E4 +:101130001003536100F0D8F90B4612A9024611E9D9 +:10114000030084E803009DF83410C1F3030089060E +:101150004CBF0E9CBDF838408DF82C0046BFC4F340 +:101160001C0444F00044C4F30A0408A92846089467 +:1011700000F0DCFECBE7284600F010FDC0E7284673 +:1011800000F03AFC0446002848D1DFF848B100F0EE +:10119000A9F9DBF80030984240D300F0A3F907909A +:1011A000FFF7E2FA079A8DF8204003464FF4C87023 +:1011B00002F51672B3FBF0F101FB103312FA83F360 +:1011C000CBF80030DFF810B19BF8001011B9012303 +:1011D0008DF8203050460791FFF7DEFA0799C1F1EC +:1011E0001004E4B2062C28BF0624224651440DF117 +:1011F000210000F0D3F808AB0393182302930134C5 +:101200002B4B0193E4B20123009304943B463246F6 +:10121000284600F0F3FB00238BF8003000F062F961 +:10122000244A254C1368C31AB3F57A7F31D3106072 +:1012300000F05AF902460B46284600F0B9FC284651 +:1012400000F0DAFB28B3237BDFF890B0002B14BF4B +:10125000032302238BF8053000F044F94FF47A732E +:101260005146B0FBF3F0CBF800005846FFF736FBD1 +:10127000182307300293114B0193C0F3CF0040F2C3 +:101280005513CDE903A0009342464B46284600F093 +:10129000B5FB237B2BB1FFF78FFA237B002B7FF469 +:1012A000F6AE13B0BDE8F08F3C2100204D220020A7 +:1012B0003421002048220020682100204C220020F8 +:1012C000401DA12026812A0BF1C6A7C1D068080FB6 +:1012D0008022002038210020352100202411002008 +:1012E00070B501F0B5FF094E094D30800024286823 +:1012F0003388834208D901F0A7FF2B6804440133E7 +:10130000B4F5D04F2B60F2D370BD00BF7C2200201B +:101310005022002002F03AB800F10060920000F57F +:10132000D04001F0D5BF0000054B1A68054B1B8863 +:101330009B1A834202D9104401F086BF00207047F7 +:10134000502200207C22002038B5074D0446286832 +:10135000204401F07FFF28B928682044BDE83840C8 +:1013600001F08ABF38BD00BF50220020064991F825 +:10137000243033B10023086A81F824300822FFF7B3 +:10138000CBBF0120704700BF54220020022802BFBB +:101390004FF090434FF480129A61704710B50023CC +:1013A000934203D0CC5CC4540133F9E710BD000074 +:1013B00003460246D01A12F9011B0029FAD17047E0 +:1013C00002440346934202D003F8011BFAE7704738 +:1013D0002DE9F8431F4D144695F82420074688460A +:1013E00052BBDFF870909CB395F824302BB92022C3 +:1013F000FF2148462F62FFF7E3FF95F82400C0F174 +:101400000802A24228BF2246D6B24146920005EB0E +:101410008000FFF7C3FF95F82430A41B1E44F6B2EA +:10142000082E17449044E4B285F82460DBD1FFF71E +:101430009DFF0028D7D108E02B6A03EB820383428B +:10144000CFD0FFF793FF0028CBD10020BDE8F88371 +:101450000120FBE7542200200FB4002004B07047A5 +:1014600000B59BB0EFF3098168226846FFF796FF4D +:10147000EFF30583044B9A6BDA6A9A6A9A6A9A6A5E +:101480009A6A9A6A9B6AFEE700ED00E000B59BB09D +:10149000EFF3098168226846FFF780FFEFF30583C9 +:1014A000044B9A6B9A6A9A6A9A6A9A6A9A6A9B6ACF +:1014B000FEE700BF00ED00E000B59BB0EFF309814F +:1014C00068226846FFF76AFFEFF30583034B5A6B08 +:1014D0009A6A9A6A9A6A9A6A9B6AFEE700ED00E045 +:1014E000FEE7000001F08EBF01F064BF30B5094D8A +:1014F0000A4491420DD011F8013B5840082340F3B3 +:101500000004013B2C4013F0FF0384EA5000F6D1A5 +:10151000EFE730BD2083B8ED2DE9F041C56915B97D +:10152000C161BDE8F0814B6823F06047C3F38A4690 +:101530004FEAD37EC3F3807816EA230638BF3E46CF +:10154000AC462B465A68BEEBD27F22F060440AD0EC +:10155000002A18DAA40CB44217D19D420FD10D60B5 +:10156000DEE71346EEE7A74207D102F08044C2F35C +:10157000807242450BD054B1EFE708D2EDE7CCF8CA +:1015800000100B60CDE7B44201D0B442E5D81A6830 +:101590009C46002AE5D11960C3E700002DE9F04719 +:1015A000089D01F007044FEAD508224405F007051D +:1015B00000EBD1004FF47F49944201D1BDE8F087A0 +:1015C00004F0070705F0070A57453E4638BF564660 +:1015D000C6F10806111B8E4228BF0E46E10808EB33 +:1015E000D50E415C13F80EC0B94029FA06F721FA6E +:1015F0000AF1FFB28CEA010147FA0AF739408CEA96 +:10160000010C03F80EC034443544D5E780EA0120CC +:10161000082341F2210201B24000002980B203F107 +:10162000FF33B8BF504013F0FF03F4D17047000000 +:1016300038B50C468D18A54200D138BD14F8011BF1 +:10164000FFF7E4FFF7E7000002684AB113680360A0 +:10165000C388018901339BB29942C38038BF03819B +:101660001046704770B588B0202204460D46684683 +:101670000021FFF7A5FE20460495FFF7E5FF02468F +:1016800058B16B46054608AE1C4603CCB4422860F0 +:101690006960234605F10805F6D1104608B070BD13 +:1016A000082817D909280CD00A280CD00B280CD0F0 +:1016B0000C280CD00D280CD00E2814BF4020302050 +:1016C00070470C2070471020704714207047182076 +:1016D0007047202070470000082817D90C280CD923 +:1016E00010280CD914280CD918280CD920280CD96A +:1016F00030288CBF0F200E207047092070470A2029 +:1017000070470B2070470C2070470D207047000079 +:1017100010B54B6823B9CA8A63F30902CA8210BDA7 +:10172000C4681A681C60C360438A013B43824A60F4 +:10173000EFE700002DE9F84F1D46CB8A0F46C3F3B3 +:1017400009010629814692460B4630D00020AAB2F4 +:1017500007F119049EB2052E1FFA80F80FD89045A4 +:1017600003F1010306D3FB8A0A4462F30903FB82F7 +:1017700001201AE01AF80060E6540130EAE79045CB +:10178000F1D2A1F1060B1C237C68BBFBF3F203FB37 +:1017900012BB1FFA8BF6002C45D14846FFF754FFC9 +:1017A000044638B978606FF00200BDE8F88F4FF05A +:1017B0000008E6E7002606607860ADB24FF0000B47 +:1017C000454510D90AEB0803221D13F8011B91555A +:1017D000B1B208F101081B291FFA88F82BD0454542 +:1017E00006F10106F1D8FB8AC3F30902154465F33B +:1017F0000903BCE7013292B21C462368002BF9D1E1 +:10180000AB1F0B441C21B3FBF1F301339BB29A4293 +:10181000D3D2BBF1000FD0D14846FFF715FF20B956 +:10182000C4F800B0BFE70122E7E7C0F800B05E46A9 +:1018300020600446C1E74545D5D94846FFF704FF77 +:1018400008B92060AFE7C0F800B000262060044669 +:10185000B6E700002DE9F04F2DED028B83B0CDE906 +:101860000013BDF83C5007469146002A00F09280D4 +:101870002DB10E9B002B00F08D80072D32D807F183 +:101880000C00FFF7E1FE044638B96FF00204204671 +:1018900003B0BDEC028BBDE8F08F14220021FFF7EE +:1018A0008FFD0E992A4604F10800FFF777FD681CAA +:1018B000C0B2FFF711FFFFF7F3FE207499F8003074 +:1018C000013814FA80F003F01F0363F03F03037242 +:1018D000009B43F00041616038462146FFF71CFE43 +:1018E0000124D4E700F10C034FF0000808EE103A91 +:1018F0004FF0800A4646444618EE100AFFF7A4FE51 +:1019000083460028C1D014220021FFF759FDC6BB31 +:10191000019BABF8083002200E9B00F108029919D8 +:101920005BFA82F20130C0B2082801D0AE422AD35D +:10193000FFF7D2FEFFF7B4FE99F80020009B411E8E +:1019400002F01F0242EA4812AE4208BF4FF0400ABE +:101950005BFA81F14AEA020A43F0004281F808A0EA +:101960008BF81000CBF8042059463846FFF7D4FD19 +:101970000134AE4224B288F001084FF0000ABBD116 +:1019800085E70020C8E711F801CB02F801CB01364A +:10199000B6B2C7E76FF0010479E70000F8B5154665 +:1019A0000E462822002104461F46FFF709FD069B2C +:1019B0006360B5F5001F079BA76034BF6A094FF647 +:1019C000FF72236204F10C0097B200239A4205D8FB +:1019D0000023036027826382A382F8BD066001337F +:1019E00030462036F2E7000003781BB94BB2002BDB +:1019F000C8BF017070470000007870472DE9F74FAD +:101A0000DDF83C90BDF830500D9E9DF83840BDF893 +:101A10004070804692469B46B9F1000F01D1002FDD +:101A200051D11F2C4FD898F80000B0B9072F47D8D4 +:101A300035F0030347D13A4649464FF6FF70FFF7AA +:101A4000F7FD20F001002D02400445EA0464400C3B +:101A500044EA40244FF6FF7321E040EA0520072FB7 +:101A600040EA0464F6D900254FF6FF73C5F1200063 +:101A7000A5F120022AFA05F10BFA00F001432BFA36 +:101A800002F211431846C9B2FFF7C0FD0835402DD8 +:101A90000346EBD13A464946FFF7CAFD0346CDE976 +:101AA0000097324621464046FFF7D4FE3378013393 +:101AB000DBB21F2B88BF0023337003B0BDE8F08F6B +:101AC0006FF00300F9E76FF00100F6E72DE9F04F42 +:101AD00085B09246DDF848800F9D9DF840209DF826 +:101AE0004490BDF84C7006469B46B8F1000F01D1FA +:101AF000002F48D11F2A46D83378002B46D00C023D +:101B000044EA02649DF8381044EAC93444EA0144C6 +:101B10001C43072F44F0800432D900234FF6FF7294 +:101B2000C3F1200CA3F120002AFA03F10BFA0CFCFC +:101B300041EA0C012BFA00F00143C9B210460393AD +:101B4000FFF764FD039B0833402B0246E8D13A4679 +:101B50004146FFF76DFD0346CDE900872A46214641 +:101B60003046FFF777FEB9F1010F06D12B7801332C +:101B7000DBB21F2B88BF00232B7005B0BDE8F08FB0 +:101B80004FF6FF73E8E76FF00100F6E76FF0030030 +:101B9000F3E70000C06900B104307047C3691A68F8 +:101BA000C261C2681A60C360438A013B43827047C6 +:101BB0002DE9F041D0F81880194E14461D464146D3 +:101BC000002709B9BDE8F081D1E90223A21A65EB2B +:101BD0000303964277EB03031ED283698B420DD138 +:101BE000FFF796FD83691B688361C3680B60438AB6 +:101BF000C1608169013B43828846E2E7FFF788FDC7 +:101C00000B68C8F80030C3680B60438AC160013BB1 +:101C10004382D8F80010D4E788460968D1E700BFAE +:101C200080841E002DE9F04F8BB00D46DDF85090FA +:101C300014469B468046002800F01981B9F1000F38 +:101C400000F01581531E3F2B00F21181012A03D1B0 +:101C5000BBF1000F40F00B810023CDE90833B8F849 +:101C60001430B5EBC30F4FEAC30703D300200BB00A +:101C7000BDE8F08F2B199F42D8F80C303ABF7F1B7C +:101C8000FFB227461BB9D8F81030002B7AD02F2D81 +:101C90004ED8C5F13006B7424FF000032CBFF6B264 +:101CA0003E4600932946D8F8080008AB3246FFF7B5 +:101CB00075FCA7EB060A35445FFA8AFAB8F81430C7 +:101CC00003F10053063BDB000493D8F80C30039378 +:101CD0003021039B13B1BAF1000F2CD1D8F81000BA +:101CE00040B1BAF1000F05D0009608AB5246691A10 +:101CF000FFF754FC38B2002FB8D066070AD00AAB01 +:101D000003EBD401624211F8083C02F007021341D0 +:101D100001F8083C082C3CD9102C40F2B580202C4E +:101D200040F2B780BBF1000F00F09C80082334E044 +:101D3000BA460026C2E7049BE02B28BFE0230693A7 +:101D40000B44AB42059314D95A1B03980096924555 +:101D500034BF5246D2B2691A08AB04300792FFF77B +:101D60001DFC079A1644AAEB020A1544F6B25FFA64 +:101D70008AFA049B069A05999B1A0493039B1B6895 +:101D80000393A6E70093D8F8080008AB3A46294623 +:101D9000AEE7BBF1000F13D00123B4EBC30F6CD03F +:101DA000082C12D89DF82030621E23FA02F2D507C3 +:101DB00006D54FF0FF3202FA04F423438DF82030A9 +:101DC0009DF8203089F8003051E7102C12D8BDF86A +:101DD0002030621E23FA02F2D10706D54FF0FF32FF +:101DE00002FA04F42343ADF82030BDF82030A9F8FE +:101DF00000303CE7202C0FD80899631E21FA03F32A +:101E0000DA0705D54FF0FF3202FA04F40C430894C8 +:101E1000089BC9F800302AE7402C2BD0DDE9086583 +:101E2000611EC4F12102A4F1210326FA01F105FA91 +:101E300002F225FA03F311431943CB0712D501220D +:101E4000A4F12003C4F1200102FA03F322FA01F104 +:101E5000A240524243EA010363EB430332432B4364 +:101E6000CDE90823DDE90823C9E90023FFE66FF087 +:101E70000100FCE66FF00800F9E6082CA0D9102C50 +:101E8000B3D9202CEED8C3E7BBF1000FADD00223AD +:101E900083E7BBF1000FBBD004237EE730B5012AF6 +:101EA000144638BF0124402C85B028BF40240025AB +:101EB000012ACDE9025518D81B788DF80830630740 +:101EC0000AD004AB03EBD405624215F8083C02F0DB +:101ED0000702934005F8083C009103462246002182 +:101EE00002A8FFF75BFB05B030BD082AE4D9102A31 +:101EF00003D81B88ADF80830E1E7202A8DBFD3E96D +:101F000000231B680293CDE90223D8E710B5CB6804 +:101F10001BB98B600B618B8210BDC4681A681C6092 +:101F2000C360438A013B4382CA60F0E72DE9F04F6A +:101F3000D1F8008093B018F0800FCDE90323C8F3E7 +:101F4000C01219BFC8F3C03BC8F306264FF0020BFE +:101F50001646B8F1000F04460D4680F2D18118F004 +:101F6000C043059340F0CC810B7B002B00F0C8816F +:101F7000BBF1020F03D00178B14240F0C48108F0F8 +:101F80007F0106916AB3C8F3074A2B44069A93F877 +:101F90000390760646EA0B4646EA82465FEAD91384 +:101FA00046EA0A06079300F0908000220023CDE95C +:101FB0000A23069B009367685B4652460AA920469F +:101FC000B84700287ED0A7699FB9314604F10C00BC +:101FD000FFF748FB0746E0B96FF0020013B0BDE819 +:101FE000F08FC8F30F2A18F07F0F08BF0AF0030A1A +:101FF000CBE73B699E420DD03F68002FF9D13146B7 +:1020000004F10C00FFF72EFB07460028E4D0A3697B +:102010003B60A761DDE90A2300264FF6FF70C6F199 +:10202000200E22FA06F103FA0EFEA6F1200C23FA86 +:102030000CFC41EA0E0141EA0C01C9B208360992D2 +:102040000893FFF7E3FA402EDDE90832E7D1B882C2 +:10205000FB7D09F01F06C3F384039B1BD7E9022114 +:1020600098B2002BBCBF00F120031BB252EA010062 +:10207000C8F304680FD00398821A049860EB01013A +:10208000A74890424FF000028A4104D3079A002AE1 +:102090005BD0012B23DDFA7D4FEA890302F00302B6 +:1020A00003F07C031343FB7539462046FFF730FBF2 +:1020B000079BA3B9FB7DC3F38402013262F386035D +:1020C000FB7504E06FF00B0088E7A76917B96FF0A4 +:1020D0000C0083E73B699E42BAD03F68F6E719F0EF +:1020E000400F32D0039BBB60049BFB601422002195 +:1020F0000DA8FFF765F9039B0A93049B0B932B1D17 +:102100000C932B7BADF83EA0013BDBB2ADF83C302D +:10211000069B8DF8433094F824308DF840B083F05E +:1021200001038DF844308DF84160A3688DF842803A +:102130000AA920469847FB7DC3F38403013303F0CB +:102140001F039B02FB82002048E7FB7DC9F340127E +:10215000B2EBD31F40F0DA80C3F38403B34240F004 +:10216000D88007992B7B4FEA9912002934D0D207E7 +:1021700041D4032B40F2D080039BBB60049BFB60E7 +:102180002B7BAE1D033BDBB23246394604F10C001B +:10219000FFF7D0FA00280DDA20463946FFF7B8FAE3 +:1021A000FB7DC3F38403013303F01F039B02FB8217 +:1021B000032013E7AB883B832A7B033AB88AD2B269 +:1021C0003146FFF735FAFB7DB882DA43C2F3C0121D +:1021D00062F3C713FB75B6E76AB92E1D013BDBB28C +:1021E0003246394604F10C00FFF7A4FA0028D3DB8D +:1021F0002A7B013AE2E7F98AC1F30901013B05298B +:10220000DAB259D8281D002307F11A0C9A4208D9CE +:1022100010F801EB0CF801E0013101330629DBB2C3 +:10222000F4D103990A9104990B91934207F11A0191 +:102230000C9138BF043379680D9134BF55FA83F39C +:1022400000230E93FB8AADF83EA0C3F309031A44A2 +:10225000069B8DF8433094F82430ADF83C2083F091 +:1022600001038DF8443000238DF840B08DF84160B3 +:102270008DF842807B602A7BB88A013A291DFFF7DE +:10228000D7F93B8BB882834203D1A3680AA92046C1 +:10229000984720460AA9FFF739FEFB7DB88AC3F3A9 +:1022A0008403013303F01F039B02FB823B8B9842A4 +:1022B00014BF1120002091E67B68002BB1D00620CE +:1022C00001E01C306346D3F800C0BCF1000FF8D128 +:1022D000091A081D05F1040C00EB030905989DF887 +:1022E000143001EB000EBEF11B0F9AD89A4298D918 +:1022F0001CF8013B09F8013B059B01330593EDE711 +:102300006FF009006AE66FF00A0067E66FF00D00F3 +:1023100064E66FF00E0061E66FF00F005EE600BF4E +:1023200080841E00F0B53D4D3D4FEB6943F00073D6 +:10233000EB61EB693B4B9B6AD3F800623E4046F091 +:102340000106C3F80062D3F800423C4044EA002092 +:1023500040F00100C3F80002002951D00020C3F86A +:102360001C020646C3F80402C3F80C02C3F81402A8 +:1023700003EBC00401300E28C4F84062C4F8446284 +:10238000F6D100274FF0010C9678148816F0010F53 +:1023900018BFD3F804E20CFA04F01CBF40EA0E0E9A +:1023A000C3F804E216F0020F1EBFD3F80CE240EAB5 +:1023B0000E0EC3F80CE2760742BFD3F81462064350 +:1023C000C3F8146203EBC4045668C4F8406296680C +:1023D000C4F84462D3F81C4201372043B942C3F821 +:1023E0001C0202F10C02CFD1D3F8002222F001022C +:1023F000C3F80022EB6923F00073EB61EB69F0BDD9 +:102400000122C3F84012C3F84412C3F80412C3F8FF +:102410001412C3F80C22C3F81C22E5E70010024096 +:102420000000FFFF80220020184A916A08B58B68DF +:102430008B6013F0010104D013F00C0F18BF4FF4A0 +:102440008031D80506D513F4406F14BF41F4003134 +:1024500041F00201D80306D513F4402F14BF41F414 +:10246000802141F00401D3690BB10848984720232B +:1024700083F311880648002100F038FE002383F31F +:102480001188BDE8084001F0AFB800BF80220020ED +:102490008822002038B5124CA36ADD68AA0712D042 +:1024A0005A6922F002025A61A36913B10121204640 +:1024B0009847202383F311880A48002100F016FE74 +:1024C000002383F31188EB0606D5A36A1021D96097 +:1024D000236A0BB102489847BDE8384001F084B840 +:1024E000802200209022002038B5124CA36A1D697A +:1024F000AA0712D05A6922F010025A61A36913B1D7 +:10250000022120469847202383F311880A4800219E +:1025100000F0ECFD002383F31188EB0606D5A36AD7 +:1025200010211961236A0BB102489847BDE8384071 +:1025300001F05AB8802200209022002038B50F4CBC +:10254000A36A5D685D602A070AD5042222701A68B2 +:1025500022F002021A60636A13B1002120469847F4 +:102560006B0706D5A36A9969236A13B10348090466 +:102570009847BDE8384001F037B800BF80220020FE +:1025800010B50E4C204600F02FFA0D4BA3620B2124 +:10259000132000F009FA0B21142000F005FA0B219A +:1025A000152000F001FA0B21162000F0FDF90022A1 +:1025B000BDE8104011460E20FFF7B4BE8022002077 +:1025C000006400400F4B984210B5044605D10E4BF5 +:1025D000DA6942F00072DA61DB69A36A01221A60EB +:1025E000A36A5A68D20707D5626851681268D96130 +:1025F0001A60064A5A6110BD0121082000F06CFCE7 +:10260000EEE700BF80220020001002405B8701003F +:1026100003291AD8DFE801F0020A0F14836A9B68C5 +:1026200013F0E05F14BF012000207047836A9868B0 +:10263000C0F380607047836A9868C0F3C0607047D9 +:10264000836A9868C0F300707047002070470000EC +:1026500010B5032925D8DFE801F00225292D836A6A +:102660009968C1F30161183103EB011310788406F6 +:102670004CBF54689488C0F300114FEA410148BF31 +:1026800041EAC40100F00F004CBF41F0040141EAEF +:102690004451586041F001019068D2689860DA6056 +:1026A000196010BD836A03F5C073DFE7836A03F521 +:1026B000C873DBE7836A03F5D073D7E701290AD033 +:1026C00002290FD081B9836ADA68920701D11869AB +:1026D00003E001207047836AD86810F0030018BF38 +:1026E00001207047836AF2E70020704710B539B9BE +:1026F000836AD96889071BD11B699C0704D110BD67 +:10270000012915D00229FAD1816AD1F8C031D1F856 +:10271000C441D1F8C8011061D1F8CC01506120202A +:1027200008610869800717D1486940F0100012E07D +:10273000816AD1F8B031D1F8B441D1F8B801106153 +:10274000D1F8BC0150612020C860C868800703D15F +:10275000486940F002004861C3F34000C3F38001C0 +:10276000000140EA4111107920F03000014311715D +:1027700089064BBF91681189DB085B0D4CBF63F381 +:102780001C0163F30A01137948BF916064F30303EA +:1027900013714FEA14234FEA144458BF1181137088 +:1027A0005480ACE7026843681143016003B11847E5 +:1027B00070470000024A136843F0C003136070477B +:1027C00000380140024A136843F0C00313607047A9 +:1027D0000044004037B51D4C1D4D204600F006FB5F +:1027E000009404F114001B490023202200F0C8F9D2 +:1027F0002022009404F13800174B184900F042FAE7 +:10280000174BC4E91735174C0C21252000F0CCF8E4 +:10281000204600F0EBFA04F1140013490094002361 +:10282000202200F0ADF904F13800104B104900945B +:10283000202200F027FA0F4B0C212620C4E917357F +:1028400003B0BDE8304000F0AFB800BFAC220020BC +:102850000051250284230020B5270008C42300204E +:102860000038014018230020A4230020C5270008B9 +:10287000E4230020004400402DE9F047C66D37688E +:10288000F46934622107054618D014F0080118BF16 +:102890008021E20748BF41F02001A30748BF41F073 +:1028A0004001600748BF41F48071202383F3118801 +:1028B000281DFFF777FF002383F31188E2050AD56F +:1028C000202383F311884FF40071281DFFF76AFF5E +:1028D000002383F311884FF020094FF0000A14F011 +:1028E000200838D13B0616D54FF0200905F1380AEB +:1028F000200610D589F31188504600F0F7F900281A +:1029000036DA0821281DFFF74DFF27F080033360DA +:10291000002383F31188790614D5620612D520238B +:1029200083F31188D5E913239A4208D12B6C33B174 +:102930001021281D27F04007FFF734FF37600023E0 +:1029400083F31188E30619D5AA6E1369B3B1BDE804 +:10295000F0475069184789F31188B38C95F86410D3 +:102960002846194000F04EFA8AF31188F469B6E758 +:1029700080B2308588F31188F469B9E7BDE8F08743 +:1029800008B50348FFF778FFBDE8084000F02CBE0B +:10299000AC22002008B50348FFF76EFFBDE80840F1 +:1029A00000F022BE1823002000F1604303F56143CC +:1029B0000901C9B283F80013012200F01F039A40F5 +:1029C00043099B0003F1604303F56143C3F8802191 +:1029D0001A60704700F16040090100F56D40C9B20E +:1029E00001767047FFF7CCBD012300F10802C0E972 +:1029F0000222037000F110020023C0E90422C0E9A2 +:102A00000633C0E9083343607047000010B5202347 +:102A1000044683F31188022303704160FFF7D2FD5F +:102A200004232370002383F3118810BD2DE9F041A6 +:102A30001F4604460D461646202383F3118800F1F5 +:102A400008082378052B0DD029462046FFF7E0FD26 +:102A500040B1204632462946FFF7FAFD002080F3B8 +:102A6000118808E03946404600F024FB0028E8D0F1 +:102A7000002383F31188BDE8F08100002DE9F041C7 +:102A80001F4604460D461646202383F3118800F1A5 +:102A900010082378052B0DD029462046FFF70EFE9F +:102AA00040B1204632462946FFF720FE002080F341 +:102AB000118808E03946404600F0FCFA0028E8D0CA +:102AC000002383F31188BDE8F0810000F8B51546B6 +:102AD00082680669AA420B46816938BF8568761A02 +:102AE000B54204460BD218462A46FEF757FCA369A6 +:102AF0002B44A361A3685B1BA3602846F8BD0CD9D7 +:102B000018463246FEF74AFCAF1BE1683A463044AD +:102B1000FEF744FCE3683B44EBE718462A46FEF721 +:102B20003DFCE368E5E7000083689342F7B515468E +:102B3000044638BF8568D0E90460361AB5420BD226 +:102B40002A46FEF72BFC63692B446361A368284681 +:102B50005B1BA36003B0F0BD0DD932460191FEF7B7 +:102B60001DFC0199E068AF1B3A463144FEF716FCA4 +:102B7000E3683B44E9E72A46FEF710FCE368E4E734 +:102B800010B50A440024C361029B8460C0E90000C0 +:102B9000C0E90511C1600261036210BD08B5D0E94A +:102BA0000532934201D1826882B982680132826023 +:102BB0005A1C42611970D0E904329A4224BFC3689A +:102BC0004361002100F086FA002008BD4FF0FF307D +:102BD000FBE7000070B5202304460E4683F31188FE +:102BE000A568A5B1A368A269013BA360531CA361BA +:102BF00015782269934224BFE368A361E3690BB1AE +:102C000020469847002383F31188284607E0314681 +:102C1000204600F04FFA0028E2DA85F3118870BDF3 +:102C20002DE9F74F04460E4617469846D0F81C90FB +:102C30004FF0200A8AF311884FF0000B154665B15A +:102C40002A4631462046FFF741FF034660B9414618 +:102C5000204600F02FFA0028F1D0002383F31188DA +:102C6000781B03B0BDE8F08FB9F1000F03D00190DD +:102C70002046C847019B8BF31188ED1A1E448AF346 +:102C80001188DCE7C0E90511C160C3611144009BF4 +:102C90008260C0E90000016103627047F8B5044634 +:102CA0000D461646202383F31188A768A7B1A368B1 +:102CB000013BA36063695A1C62611D70D4E9043250 +:102CC0009A4224BFE3686361E3690BB120469847E9 +:102CD000002080F3118807E03146204600F0EAF931 +:102CE0000028E2DA87F31188F8BD0000D0E9052357 +:102CF0009A4210B501D182687AB982680132826045 +:102D00005A1C82611C7803699A4224BFC36883619C +:102D1000002100F0DFF9204610BD4FF0FF30FBE747 +:102D20002DE9F74F04460E4617469846D0F81C90FA +:102D30004FF0200A8AF311884FF0000B154665B159 +:102D40002A4631462046FFF7EFFE034660B941466A +:102D5000204600F0AFF90028F1D0002383F311885A +:102D6000781B03B0BDE8F08FB9F1000F03D00190DC +:102D70002046C847019B8BF31188ED1A1E448AF345 +:102D80001188DCE7026843681143016003B118470A +:102D9000704700001430FFF743BF00004FF0FF33CF +:102DA0001430FFF73DBF00003830FFF7B9BF000017 +:102DB0004FF0FF333830FFF7B3BF00001430FFF798 +:102DC00009BF00004FF0FF311430FFF703BF0000D0 +:102DD0003830FFF763BF00004FF0FF323830FFF7A5 +:102DE0005DBF000000207047FFF7F4BC044B036098 +:102DF0000023C0E90233436001230374704700BF1E +:102E0000FC3B000838B5C36904460D461BB90421D4 +:102E10000844FFF7B7FF294604F11400FFF7BEFE90 +:102E2000002806DA201D4FF48061BDE83840FFF726 +:102E3000A9BF38BD024B0022C3E900339A60704736 +:102E400004240020002303748268054B1B689968E2 +:102E50009142FBD25A68036042601060586070472C +:102E60000424002008B5202383F31188037C032B5E +:102E700005D0042B0DD02BB983F3118808BD43690D +:102E800000221A604FF0FF334361FFF7DBFF00239E +:102E9000F2E7D0E9003213605A60F3E700230374CD +:102EA0008268054B1B6899689142FBD85A68036099 +:102EB000426010605860704704240020054B196977 +:102EC0000874186802681A6053601861012303745B +:102ED000FDF77EBB0424002030B54B1C0B4D87B0A2 +:102EE000044610D02B690A4A01A800F01BF92046BD +:102EF000FFF7E4FF049B13B101A800F02FF92B6941 +:102F0000586907B030BDFFF7D9FFF8E70424002067 +:102F1000652E000838B50C4D41612B6981689A68AF +:102F20009142044603D8BDE83840FFF78BBF1846EE +:102F3000FFF7B4FF01232C61014623742046BDE84E +:102F40003840FDF745BB00BF04240020044B1A683D +:102F50001B6990689B68984294BF002001207047CD +:102F60000424002010B5084C236820691A682260E8 +:102F70005460012223611A74FFF790FF0146206913 +:102F8000BDE81040FDF724BB0424002008B5FFF77E +:102F9000DDFF18B1BDE80840FFF7E4BF08BD000041 +:102FA000FFF7E0BFFEE7000010B50C4CFFF742FF53 +:102FB00000F0AAF80A498022204600F031F80123E7 +:102FC00044F8180C037400F0EBFA002383F3118823 +:102FD00062B60448BDE8104000F042B82C2400203E +:102FE000243C0008343C000800F0CAB8EFF311801C +:102FF00020B9EFF30583202282F311887047000087 +:1030000010B530B9EFF30584C4F3080414B180F3AC +:10301000118810BDFFF7BAFF84F31188F9E70000AB +:1030200082600222028270478368A3F17C0243F827 +:103030000C2C026943F83C2C426943F8382C074AAF +:1030400043F81C2CC26843F8102C022203F8082C09 +:10305000002203F8072CA3F118007047E9050008C7 +:1030600010B5202383F31188FFF7DEFF002104460B +:10307000FFF750FF002383F31188204610BD0000A6 +:10308000024B1B6958610F20FFF718BF0424002072 +:10309000202383F31188FFF7F3BF000008B5014632 +:1030A000202383F311880820FFF716FF002383F302 +:1030B000118808BD49B1064B42681B6918605A6007 +:1030C000136043600420FFF707BF4FF0FF307047E5 +:1030D000042400200368984206D01A6802605060F9 +:1030E00059611846FFF7AEBE7047000038B5044678 +:1030F0000D462068844200D138BD036823605C60BF +:103100004561FFF79FFEF4E7054B03F11402C3E9A5 +:1031100005224FF0FF32DA6100221A62704700BFC9 +:103120000424002010B5C0E903230B4A136A536935 +:103130009C68A1420CD85C68816003604460206098 +:1031400058609868411A99604FF0FF33D36110BD01 +:103150001B68091BECE700BF04240020036881689A +:103160009A680A449A60426813605A600023C360F8 +:10317000024B4FF0FF32DA61704700BF0424002099 +:1031800038B50F4C236A22460133236252F8143FAC +:10319000934206D09A68013A9A60202563699A683A +:1031A00002B138BDD3E9001001604860D968DA6027 +:1031B00082F311881869884785F31188EEE700BF0C +:1031C0000424002000207047FEE700007047000044 +:1031D0004FF0FF3070470000BFF34F8F024AD368B3 +:1031E000DB07FCD4704700BF0020024008B5074B46 +:1031F0001B7853B9FFF7F0FF054B1A69120641BF60 +:10320000044A5A6002F188325A6008BD90250020B5 +:10321000002002402301674508B5054B1B7833B9F0 +:10322000FFF7DAFF034A136943F08003136108BD17 +:1032300090250020002002407F289ABF00F58030B2 +:10324000C0020020704700004FF40060704700008B +:10325000802070477F2808B50BD8FFF7EDFF00F5F9 +:1032600000630268013204D104308342F9D10120A5 +:1032700008BD0020FCE700007F2838B5044623D8AD +:10328000FFF7B4FEFFF7A8FFFFF7B0FF0F4BF322E5 +:10329000DA6002221A6105462046FFF7CDFF586129 +:1032A0001A6942F040021A614FF40061FFF794FF7F +:1032B00000F026F92846FFF7AFFFFFF7A1FE2046F2 +:1032C000BDE83840FFF7C6BF002038BD00200240EF +:1032D00012F001032DE9F04704460E46154606D0CC +:1032E000244B40F2BD221A600020BDE8F08781180F +:1032F000214A914204D91F4A40F2C2211160F3E7EA +:10330000FFF774FEFFF772FFFFF766FFDFF87890B4 +:1033100031464FF0010AA61B012D06EB0107884636 +:1033200005D8FFF779FFFFF76BFE0120DDE7B8F85E +:103330000030C9F810A03B800024FFF74DFFC9F80A +:1033400010403B8831F8022B9BB29A420FD0094BB8 +:1033500040F2D9221A60094B1F60094B1D60094BCE +:10336000C3F80080FFF758FFFFF74AFEBCE7023DB5 +:10337000D2E700BF8C250020000004088025002033 +:10338000882500208425002000200240084908B537 +:103390000B7828B11BB9FFF729FF01230B7008BD7B +:1033A000002BFCD0BDE808400870FFF735BF00BF18 +:1033B0009025002030B583B0FFF718FE0E4B0F4D5F +:1033C0001B6A2A684FF47A7101FB03F3934237BFFB +:1033D0000B4A0B49516814682B602EBFD1E900419C +:1033E000013151601C1941F100010191FFF708FE04 +:1033F0000199204603B030BD04240020942500200C +:103400009825002030B583B0FFF7F0FD114B124D29 +:103410001B6A2A684FF47A7101FB03F3934237BFAA +:103420000E4A0E49516814682B602EBFD1E9004145 +:10343000013151601C1941F100010191FFF7E0FDDC +:1034400001994FF47A7200232046FCF7A9FE03B0DD +:1034500030BD00BF042400209425002098250020C2 +:1034600010B50244064BD2B2904200D110BD441CAC +:1034700000B253F8200041F8040BE0B2F4E700BFBB +:10348000502800400F4B30B51C6A240407D41C6A36 +:1034900044F440741C621C6A44F400441C620A4CEC +:1034A000236843F4807323600244084BD2B29042F5 +:1034B00000D130BD441C00B251F8045B43F82050E9 +:1034C000E0B2F4E7001002400070004050280040D5 +:1034D00007B5012201A90020FFF7C2FF019803B040 +:1034E0005DF804FB13B50446FFF7F2FFA04205D0D8 +:1034F000012201A900200194FFF7C4FF02B010BD12 +:1035000070470000074B45F255521A6002225A607C +:1035100040F6FF729A604CF6CC421A60024B0122D0 +:103520001A70704700300040A4250020034B1B7820 +:103530001BB1034B4AF6AA221A607047A42500204B +:1035400000300040044B1A682AB902F1804202F5AB +:103550000432526A1A607047A0250020024B4FF0D7 +:1035600080725A62704700BF0010024008B5FFF732 +:10357000E9FF024B1868C0F3407008BDA025002089 +:10358000EFF3098305494A6B22F001024A6368336D +:1035900083F30988002383F31188704700EF00E06C +:1035A000202080F3118862B60C4B0D4AD96821F4B3 +:1035B000E0610904090C0A43DA60D3F8FC200949E8 +:1035C00042F08072C3F8FC200A6842F001020A60EF +:1035D0001022DA7783F82200704700BF00ED00E088 +:1035E0000003FA05001000E010B5202383F31188D2 +:1035F0000E4B5B6813F4006314D0F1EE103AEFF356 +:103600000984683C4FF08073E361094BDB6B2366F0 +:1036100084F30988FFF79AFC10B1064BA36110BD33 +:10362000054BFBE783F31188F9E700BF00ED00E0ED +:1036300000EF00E0FB050008FE05000870470000F1 +:10364000FEE700000A4B0B480B4A90420BD30B4B92 +:10365000DA1C121AC11E22F003028B4238BF00226C +:103660000021FDF7ADBE53F8041B40F8041BECE746 +:10367000203D00082826002028260020282600209B +:10368000704700004B6843608B688360CB68C36001 +:103690000B6943614B6903628B6943620B6803608A +:1036A0007047000008B51B4B9A6A42F4FC029A620C +:1036B0009A6A22F4FC029A629A6A5A6942F4FC02FB +:1036C0005A61154A5B6911464FF09040FFF7DAFFE7 +:1036D00002F11C0100F58060FFF7D4FF02F1380110 +:1036E00000F58060FFF7CEFF02F1540100F5806025 +:1036F000FFF7C8FF02F1700100F58060FFF7C2FF1D +:1037000002F18C0100F58060FFF7BCFFBDE80840C6 +:1037100000F05AB8001002404C3C000808B500F018 +:1037200093F9FFF741FCBDE80840FFF70BBF00002D +:103730007047000010B5214CA36A63F4FC03A36238 +:10374000A36A03F4FC03A3624FF0FF32A36A236968 +:1037500022612369002323612169E168E260E26854 +:10376000E360E268E269164942F08052E261E26990 +:103770000A6842F480720A60226A02F44072B2F56A +:10378000407F1EBF4FF4803222622362236A1B04F3 +:1037900007D4236A43F440732362236A43F400434B +:1037A000236200F031F9A369064A43F00103A361E3 +:1037B000A369136843F02003136010BD001002409A +:1037C00000700040000001401E4B1A6842F00102E8 +:1037D0001A601A689007FCD55A6822F003025A60F2 +:1037E0005A6812F00C02FBD1196801F0F901196056 +:1037F0005A601A6842F480321A601A689103FCD544 +:10380000114A5A604FF40452DA6230221A631A687D +:1038100042F080721A601A689201FCD50B4912229C +:103820000A600A6802F00702022AFAD15A6842F0D6 +:1038300002025A605A6802F00C02082AFAD11A6B86 +:103840001A6370470010024000241D00002002404F +:10385000084A08B5516913680B4003F0010353612E +:1038600023B1054A13680BB150689847BDE808407A +:10387000FFF7BABE00040140A8250020084A08B599 +:10388000516913680B4003F00203536123B1054AE9 +:1038900093680BB1D0689847BDE80840FFF7A4BE15 +:1038A00000040140A8250020084A08B551691368A2 +:1038B0000B4003F00403536123B1054A13690BB1B4 +:1038C00050699847BDE80840FFF78EBE00040140EC +:1038D000A8250020084A08B5516913680B4003F079 +:1038E0000803536123B1054A93690BB1D069984726 +:1038F000BDE80840FFF778BE00040140A82500207D +:10390000084A08B5516913680B4003F0100353616E +:1039100023B1054A136A0BB1506A9847BDE80840C5 +:10392000FFF762BE00040140A8250020174B10B528 +:103930005A691C68144004F478725A61A30604D5CD +:10394000134A936A0BB1D06A9847600604D5104AAF +:10395000136B0BB1506B9847210604D50C4A936B3F +:103960000BB1D06B9847E20504D5094A136C0BB133 +:10397000506C9847A30504D5054A936C0BB1D06CE5 +:103980009847BDE81040FFF72FBE00BF000401407C +:10399000A82500201A4B10B55A691C68144004F47D +:1039A0007C425A61620504D5164A136D0BB1506D05 +:1039B0009847230504D5134A936D0BB1D06D9847F2 +:1039C000E00404D50F4A136E0BB1506E9847A10462 +:1039D00004D50C4A936E0BB1D06E9847620404D59F +:1039E000084A136F0BB1506F9847230404D5054A5A +:1039F000936F0BB1D06F9847BDE81040FFF7F4BD4F +:103A000000040140A8250020062108B50846FEF75D +:103A1000CBFF06210720FEF7C7FF06210820FEF78F +:103A2000C3FF06210920FEF7BFFF06210A20FEF78B +:103A3000BBFF06211720FEF7B7FFBDE808400621AF +:103A40002820FEF7B1BF000008B5FFF773FE00F0B5 +:103A50000DF8FEF7C7FFFFF7C7F9FFF769FEBDE8EE +:103A6000084000F001B8000000F00EB80023054A3D +:103A700019460133102BC2E9001102F10802F8D1F6 +:103A8000704700BFA82500204FF0E023044A5A6188 +:103A900000229A6107221A6108210B20FEF79ABFC3 +:103AA0003F19010008B5202383F31188FFF79CFA22 +:103AB000002383F3118808BD08B5FFF7F3FFBDE8C5 +:103AC0000840FFF791BD000010B501390244904253 +:103AD00001D1002005E0037811F8014FA34201D085 +:103AE000181B10BD0130F2E72DE9F041A3B1C91A4E +:103AF00017780144044603F1FF3C8C42204601D96B +:103B0000002009E00578BD4204F10104F5D10CEB79 +:103B10000405D618A54201D1BDE8F08115F8018D44 +:103B200016F801EDF045F5D0E7E70000034611F87F +:103B3000012B03F8012B002AF9D170476F72672E11 +:103B40006172647570696C6F742E61705F706572FC +:103B50006970685F756E6976657273616C000000EC +:103B60004E6F20617070207369670A0042616420A3 +:103B70006677206C656E6774682025750A0042615F +:103B80006420626F6172645F6964202575207368C8 +:103B90006F756C642062652025750A00426164209F +:103BA00066772064657363726970746F72206C65E8 +:103BB0006E6774682025750A004261642061707028 +:103BC00020435243203078253038783A30782530F9 +:103BD0003878203078253038783A30782530387881 +:103BE0000A00476F6F64206669726D776172650ABB +:103BF0000040A2E4F16468910600000000000000AB +:103C0000B12D00089D2D0008D92D0008C52D0008F4 +:103C1000D12D0008BD2D0008A92D0008952D000804 +:103C2000E52D00086D61696E0000000069646C6537 +:103C3000000000002C3C00084824002080250020C3 +:103C400001000000A52F000800000000A001A82A24 +:103C500000000000FAAABEAA50001424EFFF0000E2 +:103C600000770000709709000100000000000000CC +:103C7000AAAAAAAA01000000FFFF0000000000009D +:103C8000000000000000000000000000AAAAAAAA8C +:103C900000000000FFFF0000000000000000000026 +:103CA0000000000000000000AAAAAAAA000000006C +:103CB000FFFF000000000000000000000000000006 +:103CC00000000000AAAAAAAA00000000FFFF00004E +:103CD00000000000000000000000000000000000E4 +:103CE000AAAAAAAA00000000FFFF0000000000002E +:103CF00000000000DCC4FF7F0100000000000000A5 +:103D0000EC03000000000000009803000000000029 +:103D10006400000000000000FE2A0100D204000040 :00000001FF diff --git a/Tools/bootloaders/f405-MatekAirspeed_bl.bin b/Tools/bootloaders/f405-MatekAirspeed_bl.bin old mode 100644 new mode 100755 index f7b6e102c15..3a2276329c3 Binary files a/Tools/bootloaders/f405-MatekAirspeed_bl.bin and b/Tools/bootloaders/f405-MatekAirspeed_bl.bin differ diff --git a/Tools/bootloaders/f405-MatekAirspeed_bl.hex b/Tools/bootloaders/f405-MatekAirspeed_bl.hex index 0b5c70440fe..2b5ee851433 100644 --- a/Tools/bootloaders/f405-MatekAirspeed_bl.hex +++ b/Tools/bootloaders/f405-MatekAirspeed_bl.hex @@ -1,25 +1,25 @@ :020000040800F2 -:1000000000070020E50400080D1D00088D1C0008F5 -:10001000E51C00088D1C0008B91C0008E704000856 -:10002000E7040008E7040008E7040008C1430008EB +:1000000000070020E5040008E11B0008611B000850 +:10001000B91B0008611B00088D1B0008E7040008DD +:10002000E7040008E7040008E70400082547000883 :10003000E7040008E7040008E7040008E7040008F4 :10004000E7040008E7040008E7040008E7040008E4 -:10005000E7040008E70400085D540008895400081C -:10006000B5540008E15400080D550008E7040008E5 +:10005000E7040008E7040008C1570008ED5700084E +:10006000195800084558000871580008E7040008AE :10007000E7040008E7040008E7040008E7040008B4 -:10008000E7040008E7040008E7040008C12B0008A3 -:100090002D2C0008812C0008D52C000839550008AB +:10008000E7040008E7040008E7040008E52E00087C +:10009000512F0008A52F0008F92F00089D580008CF :1000A000E7040008E7040008E7040008E704000884 -:1000B000D1520008E7040008E7040008E70400083C +:1000B00035560008E7040008E7040008E7040008D4 :1000C000E7040008E7040008E7040008E704000864 :1000D000E7040008E7040008E7040008E704000854 -:1000E000A1550008E7040008E7040008E704000839 +:1000E00005590008E7040008E7040008E7040008D1 :1000F000E7040008E7040008E7040008E704000834 :10010000E7040008E7040008E7040008E704000823 :10011000E7040008E7040008E7040008E704000813 :10012000E7040008E7040008E7040008E704000803 :10013000E7040008E7040008E7040008E7040008F3 -:10014000E7040008E7040008E7040008F94A00088B +:10014000E7040008E7040008E70400085D4E000823 :10015000E7040008E7040008E7040008E7040008D3 :10016000E7040008E7040008E7040008E7040008C3 :10017000E7040008E7040008E7040008E7040008B3 @@ -84,1380 +84,1426 @@ :1005200040F20000C0F2F0004EF68851CEF2000119 :100530000860BFF34F8FBFF36F8F4FF00000E1EE05 :10054000100A4EF63C71CEF200010860062080F3DE -:100550001488BFF36F8F03F0B3FF03F08FFF04F035 -:100560001BFE4FF055301F491B4A91423CBF41F8DA +:100550001488BFF36F8F04F065F904F041F904F0DB +:10056000CDFF4FF055301F491B4A91423CBF41F827 :10057000040BFAE71C49194A91423CBF41F8040BAD :10058000FAE71A491A4A1B4B9A423EBF51F8040B2C :1005900042F8040BF8E700201749184A91423CBF83 -:1005A00041F8040BFAE703F06DFF04F049FE144C28 +:1005A00041F8040BFAE704F01FF904F0FBFF144CC8 :1005B000144DAC4203DA54F8041B8847F9E700F005 :1005C00041F8114C114DAC4203DA54F8041B884732 -:1005D000F9E703F055BF00000007002000230020CA -:1005E000000000080001002000070020005B000858 -:1005F000002300205023002050230020144000201E +:1005D000F9E704F007B9000000070020002300201D +:1005E000000000080001002000070020D85D00087E +:1005F00000230020542300205823002028400020FE :10060000E0010008E0010008E0010008E001000846 :100610002DE9F04F2DED108AC1F80CD0C3689D462E :10062000BDEC108ABDE8F08F002383F311882846C3 -:10063000A047002003F06EFAFEE703F0E9F900DFBF -:10064000FEE70000F8B503F065FE074603F0B2FED2 -:10065000044688BB1D4B9F422ED001339F422ED0B3 -:100660001B4B27F0FF029A422CD1F8B200F01AFD82 -:10067000264642F2107500F01FFF00F019FD08B980 -:100680000646054634B1134B9F4203D003F08AFE61 -:1006900000252E46002003F047FE0EB100F062F860 -:1006A00001F0C6FA00F02AFF01F052F9284600F0E6 -:1006B000B5F800F057F8F9E726460025DBE70546D0 -:1006C0000126D8E7064641F28835D4E7010007B095 -:1006D000000008B0263A09B008B501F00BF9A0F106 -:1006E00020035842584108BD07B541F212030221C8 -:1006F00001A8ADF8043001F01BF903B05DF804FB6C -:1007000010B5202383F311881248C3680BB103F09E -:1007100087FA114A0F4800234FF47A7103F044FA24 -:10072000002383F311880D4C236813B12368013B28 -:100730002360636813B16368013B6360084B1B78F7 -:1007400033B9636823B9022001F0ECF93223636006 -:1007500010BD00BF50230020010700086C240020BA -:1007600064230020274B284A10B51C461968013124 -:1007700046D004339342F9D16268244B9A423FD960 -:10078000234B9B6803F1006303F580339A4237D211 -:1007900003F0DAFD03F0ECFD002001F0F3F81D4B4F -:1007A0000220187001F0B4F91B4B1A6C00221A6475 -:1007B000196E1A66196E596C5A64596E5A665A6ED9 -:1007C0005A6942F080025A615A6922F080025A61E5 -:1007D0005A691A6942F000521A611A6922F00052ED -:1007E0001A611B6972B64FF0E0232021C3F8084D4F -:1007F000D4E9003281F311889D4683F308881047BD -:1008000010BD00BF0000010820000108FFFF000824 -:100810000023002064230020003802402DE9F04F1F -:1008200093B0AC4B00902022FF210AA89D6801F0F4 -:10083000A9F9A94A1378A3B9A8480121C360117086 -:10084000202383F31188C3680BB103F0E9F9A44AAC -:10085000A24800234FF47A7103F0A6F9002383F332 -:100860001188009B9F4A03B113609F49009C00239D -:100870000B70536098469B461E469A46012001F035 -:1008800047F924B1974B1B68002B00F01C82002015 -:1008900001F030F80390039B002B01DA00F0CEFE4C -:1008A000039B002BEDDB012001F028F9039B213B8A -:1008B000162BE3D801A252F823F000BF1909000853 -:1008C00041090008D50900087D0800087D080008D6 -:1008D0007D080008690A00083B0C0008550B000859 -:1008E000B70B0008DF0B0008050C00087D080008A6 -:1008F000170C00087D080008890C0008B9090008D9 -:100900007D080008CD0C000825090008B909000879 -:100910007D080008B70B00080220FFF7DDFE002865 -:1009200040F0FB81009B0221B8F1000F08BF1C467C -:1009300005A841F21233ADF8143000F0F9FF9DE73D -:100940004FF47A7000F0D6FF071EEBDB0220FFF7B2 -:10095000C3FE0028E6D0013F052F00F2E081DFE86A -:1009600007F0030A0D10133605230593042105A88B -:1009700000F0DEFF17E057480421F9E75B48042147 -:10098000F6E75B480421F3E74FF01C09484600F006 -:10099000FBFF09F104090590042105A800F0C8FF38 -:1009A000B9F12C0FF2D1012000FA07F747EA0B0B3F -:1009B0005FFA8BFB4FF0000A01F030F926B10BF023 -:1009C0000B030B2B08BF0024FFF78EFE56E74948A8 -:1009D0000421CDE7002EA5D00BF00B030B2BA1D1EA -:1009E0000220FFF779FE074600289BD001203E4EEB -:1009F00000F0C8FF0220307001F08AF84FF00008C4 -:100A00005FFA88F9484600F0CDFF044690B14846A9 -:100A100000F0D8FF08F101080028F1D1B8460446DB -:100A200041F21213022105A8ADF814303E4600F041 -:100A30007FFF23E701230220337001F05FF8254692 -:100A4000244B9B68AB4207D9284600F09DFF01303C -:100A500040F068810435F3E7234B00251D70214BDE -:100A6000B8465D603E46A7E7002E3FF45BAF0BF053 -:100A70000B030B2B7FF456AF1B4B0220187001F0B9 -:100A800047F8322000F036FFB0F10009FFF64AAF18 -:100A900019F003077FF446AF0E4A926809EB05038D -:100AA00093423FF63FAFB9F5807F3FF73BAF124B24 -:100AB0000193B94522DD4FF47A7000F01BFF0390DB -:100AC000039A002AFFF62EAF019B039A03F8012B2D -:100AD0000137EDE700230020682400205023002088 -:100AE000010700086C240020642300200423002058 -:100AF000082300200C23002068230020C820FFF7D3 -:100B0000EBFD074600283FF40DAF1F2D11D8C5F1AE -:100B100020024A450AAB25F0030028BF4A46834914 -:100B20000192184401F008F8019A8048FF2101F071 -:100B300029F84FEAA9037D490193C9F387022846A2 -:100B400001F028F8064600283FF46AAF019B05EB48 -:100B5000830531E70220FFF7BFFD00283FF4E2AE36 -:100B600000F05AFF00283FF4DDAE0027B946704B75 -:100B70009B68BB4218D91F2F11D80A9B01330ED096 -:100B800027F0030312AA134453F8203C0593484668 -:100B9000042205A901F0C0F804378146E7E738468A -:100BA00000F0F2FE0590F2E7CDF81490042105A8BC -:100BB00000F0BEFE00E70023642104A8049300F0C7 -:100BC000ADFE00287FF4AEAE0220FFF785FD0028C1 -:100BD0003FF4A8AE049800F007FF0590E6E7002375 -:100BE000642104A8049300F099FE00287FF49AAED3 -:100BF0000220FFF771FD00283FF494AE049800F046 -:100C000003FFEAE70220FFF767FD00283FF48AAE02 -:100C100000F012FFE1E70220FFF75EFD00283FF43D -:100C200081AE05A9142000F00DFF042107460490B1 -:100C300004A800F07DFE3946B9E7322000F05AFEE4 -:100C4000071EFFF66FAEBB077FF46CAE384A9268A2 -:100C500007EB0A0393423FF665AE0220FFF73CFD27 -:100C600000283FF45FAE27F003075744BA453FF42E -:100C7000A3AE504600F088FE0421059005A800F0C0 -:100C800057FE0AF1040AF1E74FF47A70FFF724FDEA -:100C900000283FF447AE00F0BFFE002844D00A9B76 -:100CA00001330BD008220AA9002000F073FF0028AE -:100CB0003AD02022FF210AA800F064FFFFF714FDBC -:100CC0001C4802F02DFF13B0BDE8F08F002E3FF45A -:100CD00029AE0BF00B030B2B7FF424AE0023642111 -:100CE00005A8059300F01AFE074600287FF41AAE07 -:100CF0000220FFF7F1FC814600283FF413AEFFF716 -:100D0000F3FC41F2883002F00BFF059800F0B8FFC9 -:100D10004E4600F083FF3C46B0E506464CE64FF0F9 -:100D2000000AFFE5B8467BE6374679E668230020EF -:100D300000230020A0860100094A136849F26900D7 -:100D400099B21B0C00FB01331360064B186844F288 -:100D5000506182B2000C01FB0200186080B2704743 -:100D60001C2300201823002010B500211022044667 -:100D700000F008FF034B03CB206061601868A0609F -:100D800010BD00BF107AFF1F2DE9F043204DBBB00E -:100D900000F0BEFFAB68C31AF92B32D906AFA860CA -:100DA0002B4628220021384601F04AFC05F10E00AE -:100DB00000F0E0FE002604465FFA80F905F10E0817 -:100DC000F3B2F100994501F1280107D908EB0603B8 -:100DD0000822384601F034FC0136F1E708230122ED -:100DE000CDE9023205340B4B0193A4B230230093BA -:100DF000CDE9047404A3D3E90023297B064801F05C -:100E000037FA3BB0BDE8F08378F6339F93CACD8DB7 -:100E1000B0340020BD3400208C34002070B50D4665 -:100E200014461E4601F0BAF950B9022E10D1012C19 -:100E30000ED112A3D3E90023C5E90023012007E066 -:100E4000282C10D005D8012C09D0052C0FD000205B -:100E500070BD302CFBD10BA3D3E90023ECE70BA32F -:100E6000D3E90023E8E70BA3D3E90023E4E70BA3CE -:100E7000D3E90023E0E700BFAFF30080401DA120CD -:100E800026812A0B78F6339F93CACD8D9E6AC421A2 -:100E9000818A46EE26417272DF25D7B7F017304AB5 -:100EA00039059E5613B504462346084620220021E4 -:100EB000019001F0C5FB22790198032A234628BF3F -:100EC000032203F8042F2021022201F0B9FB6279EA -:100ED0000198072A234628BF072203F8052F22215D -:100EE000032201F0ADFBA2790198072A234628BF0F -:100EF000072203F8062F2521032201F0A1FB019808 -:100F000004F108031022282101F09AFB382002B0D6 -:100F100010BD00002DE9F04FADF5037D23AD10AEFF -:100F200040F2751280460F4624A80021296000F087 -:100F300029FE48220021304600F024FE00F0E8FEA1 -:100F4000564B4FF47A72B0FBF2F0186093E807004A -:100F5000012386E807000DF162003382FFF704FFEA -:100F60004FF20363338407AB18464D4904F0C4FBCA -:100F70004FF0200930642946304686F83C90FFF750 -:100F800091FF14AB044601460822284601F058FBA5 -:100F90000822A1180DF15103284601F051FB0DF173 -:100FA0005203082204F11001284601F049FB4A4689 -:100FB00015AB04F11801284601F042FB16AB4022A4 -:100FC00004F13801284601F03BFB18AB082204F17C -:100FD0007801284601F034FB0DF16103082204F189 -:100FE0008001284601F02CFB04F1880A0DF162090A -:100FF00004F5847B4B465146082228460AF1080A2C -:1010000001F01EFBD34509F10109F3D11DAB082204 -:101010005946284601F014FB04F588744FF0000986 -:1010200096F834304B450AD9B36B21464B4408221D -:10103000284601F005FB083409F10109F0E74FF0FB -:10104000000996F83C304B4504EBC90108D9336CD4 -:1010500008224B44284601F0F3FA09F10109F0E7B0 -:10106000CB1DC3F3CF03CDE9045300230393BB7E11 -:10107000029307F11903019301230093F97E05A35D -:10108000D3E90023404601F0F3F80DF5037DBDE8F8 -:10109000F08F00BF9E6AC421818A46EE742400202E -:1010A00008570008014B1870704700BF80240020CB -:1010B000F0B5334B1C7B85B034B1324B0E221A8114 -:1010C0000024204605B0F0BD2F4A1068516802ABDD -:1010D00003C308232D492E480DEB030204F0EAFA5E -:1010E000054630B9274B2B480A221A8100F0CAFD69 -:1010F000E6E70169B1F5702F06D9224B26480B228D -:101100001A8100F0BFFDDCE7438B40F2F6329342D8 -:1011100007D01C490C2008811946204800F0B2FD78 -:10112000CFE71F4A024402F11003994204D2154B43 -:101130001C4810221A81E4E710398E1A20461449FF -:1011400000F0EAFD3246074605F11801204600F09E -:10115000E3FDAB689F4202D1EB6898420AD0094B8D -:101160000D221A810090D5E902123B460E4800F08C -:1011700089FDA5E70D4800F085FD0124A1E700BF2A -:10118000B034002074240020BD570008DCFF0E009E -:10119000000001082C570008385700084A5700087B -:1011A0000800FFF76857000885570008AE57000889 -:1011B0002DE9F04FADB006AF80460C4600F0EEFFD3 -:1011C000054600285AD1237E022B1BD1E38A012B2E -:1011D00018D100F09DFD0646FFF7AEFD03464FF423 -:1011E000C870DFF8D092B3FBF0F206F5167602FB7A -:1011F000103316FA83F3C9F80030E37E33B9A84BF5 -:1012000000221A709C37BD46BDE8F08FA38AEEB26B -:10121000013BB34205F101050BD93B1D1E44E9001A -:1012200000960023082201F0F801204601F0CCF8D6 -:10123000ECE707F11400FFF797FD324607F11401C0 -:10124000381D04F027FA0028D9D10F2E08D8944B66 -:101250001E70D9F80030A3F51673C9F80030D1E735 -:10126000FB1CF8700146009307220346204601F05C -:10127000ABF8F978404600F089FFC3E7E38A282BF2 -:1012800026D010D8012B1ED0052BBBD1BFF34F8F1A -:101290008449854BCA6802F4E0621343CB60BFF314 -:1012A0004F8F00BFFDE7302BACD1637E7F4D013304 -:1012B0006A7BDBB29342E94603D1E27E2B7B9A4202 -:1012C00065D0CD469EE721464046FFF723FE99E7CD -:1012D000A38A013B9BB2C92B94D8744D2E7B26BBAD -:1012E00005F10C030093082233463146204601F0F5 -:1012F0006BF8731CF2B2D9001E46A38A013B9A42D6 -:1013000005DA0E322A44009200230822EEE7002379 -:101310000022C5E900230023AB6085F8D730C5F86B -:10132000D8302B7B0BB9E37E2B73002507F1140912 -:101330003B1D082229464846C7E90155FD6001F0DA -:101340007FF93B7A05F1010AAB424FEACA0608D998 -:10135000FB6808222B443146484601F071F9554696 -:10136000EFE7C6F3CF06E17ECDE9049600230393B1 -:10137000A37E0293193428230093019446A3D3E952 -:101380000023404600F074FFFFF7FEFC3AE74FF001 -:10139000000807F11403A7F81480102200934146B7 -:1013A0000123204601F010F8A68A023EB6B2F31CD3 -:1013B0009B109B000733DB08A9EBC3039D460DF18F -:1013C000180A1FFA88F34FEAC801B34201F110016D -:1013D0000AD20AEB0803009308220023204600F0FB -:1013E000F3FF08F10108ECE795F8D70000F0DAFA0E -:1013F000D5F8D83004461BB995F8D70000F0E2FACA -:10140000D5F8D83033449C4204D295F8D700013047 -:1014100000F0D8FA4FEA960B4FF000081FFA88F157 -:101420008B45D5E9003209D90AEB880103EB880026 -:10143000012200F0AFFB08F10108EFE7F31842F1D9 -:101440000002C5E90032D5F8D83095F8D70006EB90 -:101450000308C5F8D88000F0A5FA804509D395F8AF -:10146000D730D5F8D8000133001B85F8D730C5F840 -:10147000D800FF2E08D800232B7300F0CDFAFFF719 -:1014800017FE08B1FFF76EF92B68094A9B0A013372 -:1014900013810023AB6014E726417272DF25D7B7B2 -:1014A0008534002000ED00E00400FA05B03400208F -:1014B000742400208834002008B54FF000530B4AF4 -:1014C000196891420AD10A4A597D117009481B7D59 -:1014D00003730949C9220E3000F02EFBBDE8084015 -:1014E000E02200214FF0005000F04CBB9AAD44C503 -:1014F00080240020B0340020160000202DE9FF4198 -:10150000434C02236371002302932A250A23581EA9 -:10151000B5FBF3F67343D3F12A02C1B23ED00228E1 -:101520000346F4D19DF80B303A493B485A1E9DF8CA -:101530000A30013B1B0443EA0253BDF80820013A7C -:1015400013434B6001F028FD00230193334B3449D2 -:1015500000933448344B4FF4805200F0F1FD334B8C -:10156000197811B12F4800F011FE00F0D1FB0546AB -:10157000FFF7E2FB4FF4C873B0FBF3F202FB130377 -:1015800005F5167010FA83F0294B186002F012FF6F -:1015900008B10F23238104B0BDE8F081C1EBC1077E -:1015A000FB1C4FEAE30EC3F3C703A1EB030C0EF1E0 -:1015B00001084FF47A705FFA8CF50EFB000058FAC0 -:1015C0008CFCB0FBFCF0B0F5617F07D97B1EC3F348 -:1015D000C703C91ACDB2591E0F2916D86A1E072A89 -:1015E0008CBF00220122591901FB06601149B1FB91 -:1015F000F0F11148814295D1002A93D0ADF80860EE -:101600008DF80A308DF80B508CE71346EBE700BFDE -:101610007424002010230020C83500201D0E00086F -:10162000842400208C340020B11100088024002084 -:101630008834002080DE800240420F002DE9F04F08 -:1016400091A7D7E900670FF24829D9E90089874DAA -:1016500093B0DFF844B2864C284600F06DFE0DF1E1 -:10166000300A079070B310220021504600F08AFA29 -:10167000079B197B4FF0000261F303028DF83020C5 -:10168000586899680EAA03C21B680D9A63F31C027E -:101690009DF830300D9243F020038DF83030002358 -:1016A00052461946584601F087FC079028B928464B -:1016B00000F046FE079B2370CEE72378072B3CD82B -:1016C0000133237018220021504600F05BFADFF846 -:1016D000C8B1684C002319465246584601F094FCA4 -:1016E000014670BB102208A800F04CFA636983F42D -:1016F0008043636100F00EFB0B4612A9024611E91C -:1017000003000DF1240C8CE803009DF83410C1F3A4 -:10171000030089064CBF0E99BDF838C08DF82C0027 -:1017200046BFC1F31C0C4CF00041CCF30A010891F8 -:10173000284608A900F0CCFFCCE7284600F000FEC0 -:10174000C0E7284600F02AFD0446002848D1DFF80B -:101750004CB100F0DDFADBF80030984240D300F0E5 -:10176000D7FA0790FFF7E8FA079A8DF8204003466A -:101770004FF4C87002F51672B3FBF0F101FB1033A1 -:1017800012FA83F3CBF80030DFF814B19BF80010A5 -:1017900011B901238DF8203050460791FFF7E4FA84 -:1017A0000799C1F11004E4B2062C28BF0624224692 -:1017B00051440DF1210000F0BFF908AB0393182349 -:1017C000029301342C4B0193E4B20123009304945F -:1017D0003B463246284600F0E3FC00238BF80030FD -:1017E00000F096FA254A264C1368C31AB3F57A7F9F -:1017F00031D3106000F08EFA02460B46284600F006 -:10180000A9FD284600F0CAFC28B3237BDFF894B07A -:10181000002B14BF032302238BF8053000F078FA65 -:101820004FF47A735146B0FBF3F0CBF80000584602 -:10183000FFF738FB182307300293124B0193C0F3D4 -:10184000CF0040F25513CDE903A0009342464B462A -:10185000284600F0A5FC237B2BB1FFF795FA237BEC -:10186000002B7FF4F6AE13B0BDE8F08F8C3400206F -:10187000953500200000024084340020903500207F -:10188000B034002094350020401DA12026812A0B71 -:10189000F1C6A7C1D068080FC835002088340020E1 -:1018A000853400207424002070B50F4B1B78013361 -:1018B000DBB2012B0C4611D80C4D29684FF47A731A -:1018C0000E6AA2FB0332014622462846B0478442F4 -:1018D00004D1074B00221A70012070BD4FF4FA703A -:1018E00002F01EF90020F8E720230020B037002086 -:1018F000C435002007B50023024601210DF1070081 -:101900008DF80730FFF7D0FF20B19DF8070003B036 -:101910005DF804FB4FF0FF30F9E700000A4608B518 -:101920000421FFF7C1FF80F00100C0B2404208BDB2 -:1019300030B4054C2368DD69044B0A46AC460146C9 -:10194000204630BC604700BFB0370020A0860100B1 -:1019500070B502F095FB094E094D308000242868CF -:101960003388834208D902F085FB2B680444013395 -:10197000B4F5803F2B60F2D370BD00BFC6350020A8 -:101980009835002002F02ABC00F1006000F580309C -:101990000068704700F10060920000F5803002F0AE -:1019A000B5BB0000054B1A68054B1B889B1A834288 -:1019B00002D9104402F05EBB002070479835002029 -:1019C000C635002038B5074D04462868204402F08B -:1019D00059FB28B928682044BDE8384002F06ABBAA -:1019E00038BD00BF9835002010F003030AD1B0F5D0 -:1019F000047F05D200F10050A0F51040D0F8003867 -:101A0000184670470023FBE700F10050A0F5104096 -:101A1000D0F8100A70470000064991F8243033B11D -:101A20000023086A81F824300822FFF7B3BF0120A1 -:101A3000704700BF9C350020014B1868704700BFFD -:101A4000002004E070B52A4B1B68C3F30B02044668 -:101A50001B0C62B140F21340824230D040F2194078 -:101A600082422ED040F2214082422CD10322214DCD -:101A70000C2000FB0252556842F20102934224D02E -:101A8000B3F5805F23D041F20102934221D041F2AD -:101A9000030293421FD041F20702934214BF3F2337 -:101AA0003123013C0C44013D0A46A24215D215F9EE -:101AB000016F501C9EB100F8016C0246F5E701224F -:101AC000D5E70222D3E70C4DD6E73323E9E74123DC -:101AD000E7E75A23E5E75923E3E7104605E02C251D -:101AE0008442157001D9901C5370401A70BD00BF1C -:101AF000002004E0F4570008C8570008022802BF7D -:101B0000024B4FF080429A61704700BF00000240D4 -:101B1000022802BF024B4FF480429A61704700BF17 -:101B200000000240022801BF024A536983F4804347 -:101B3000536170470000024010B50023934203D068 -:101B4000CC5CC4540133F9E710BD000010B5013876 -:101B500010F9013F3BB191F900409C4203D11AB109 -:101B60000131013AF4E71AB191F90020981A10BD39 -:101B70001046FCE703460246D01A12F9011B002961 -:101B8000FAD1704702440346934202D003F8011B86 -:101B9000FAE770472DE9F8431F4D144695F82420C5 -:101BA0000746884652BBDFF870909CB395F8243006 -:101BB0002BB92022FF2148462F62FFF7E3FF95F85B -:101BC0002400C0F10802A24228BF2246D6B24146F4 -:101BD000920005EB8000FFF7AFFF95F82430A41BBF -:101BE0001E44F6B2082E17449044E4B285F82460EF -:101BF000DBD1FFF711FF0028D7D108E02B6A03EBF8 -:101C000082038342CFD0FFF707FF0028CBD100200B -:101C1000BDE8F8830120FBE79C350020024B1A78D1 -:101C2000024B1A70704700BFC435002020230020EB -:101C300010B50F4C0F4801F089FA21460D4801F00C -:101C4000B1FA24680C48626DD2F8043843F00203FC -:101C5000C2F8043801F064FF0849204601F0A8FBEF -:101C6000626DD2F8043823F00203C2F8043810BDC4 -:101C7000E8580008B037002040420F00F058000834 -:101C8000704700000FB4002004B0704700B59BB04F -:101C9000EFF3098168226846FFF74EFFEFF30583F3 -:101CA000044B9A6BDA6A9A6A9A6A9A6A9A6A9A6A88 -:101CB0009B6AFEE700ED00E000B59BB0EFF3098101 -:101CC00068226846FFF738FFEFF30583044B9A6BF1 -:101CD0009A6A9A6A9A6A9A6A9A6A9B6AFEE700BF47 -:101CE00000ED00E000B59BB0EFF309816822684683 -:101CF000FFF722FFEFF30583034B5A6B9A6A9A6A48 -:101D00009A6A9A6A9B6AFEE700ED00E0FEE700002F -:101D100002F09EBA02F076BA30B5094D0A449142FB -:101D20000DD011F8013B5840082340F30004013B5B -:101D30002C4013F0FF0384EA5000F6D1EFE730BDEA -:101D40002083B8ED2DE9F041C56915B9C161BDE841 -:101D5000F0814B6823F06047C3F38A464FEAD37E95 -:101D6000C3F3807816EA230638BF3E46AC462B46BE -:101D70005A68BEEBD27F22F060440AD0002A18DAFB -:101D8000A40CB44217D19D420FD10D60DEE713467B -:101D9000EEE7A74207D102F08044C2F380724245C9 -:101DA0000BD054B1EFE708D2EDE7CCF800100B6090 -:101DB000CDE7B44201D0B442E5D81A689C46002A67 -:101DC000E5D11960C3E700002DE9F047089D01F057 -:101DD00007044FEAD508224405F0070500EBD100BF -:101DE0004FF47F49944201D1BDE8F08704F0070722 -:101DF00005F0070A57453E4638BF5646C6F1080665 -:101E0000111B8E4228BF0E46E10808EBD50E415C3F -:101E100013F80EC0B94029FA06F721FA0AF1FFB209 -:101E20008CEA010147FA0AF739408CEA010C03F801 -:101E30000EC034443544D5E780EA0120082341F23E -:101E4000210201B24000002980B203F1FF33B8BF84 -:101E5000504013F0FF03F4D17047000038B50C4632 -:101E60008D18A54200D138BD14F8011BFFF7E4FF1F -:101E7000F7E7000002684AB113680360C38801896C -:101E800001339BB29942C38038BF0381104670472B -:101E900070B588B0202204460D4668460021FFF741 -:101EA00071FE20460495FFF7E5FF024658B16B46E8 -:101EB000054608AE1C4603CCB44228606960234640 -:101EC00005F10805F6D1104608B070BD10B54B6895 -:101ED00023B9CA8A63F30902CA8210BDC4681A68AA -:101EE0001C60C360438A013B43824A60EFE7000005 -:101EF0002DE9F84F1D46CB8A0F46C3F30901062989 -:101F0000814692460B4630D00020AAB207F1190450 -:101F10009EB2052E1FFA80F80FD8904503F10103F9 -:101F200006D3FB8A0A4462F30903FB8201201AE00C -:101F30001AF80060E6540130EAE79045F1D2A1F1C9 -:101F4000060B1C237C68BBFBF3F203FB12BB1FFADE -:101F50008BF6002C45D14846FFF78CFF044638B974 -:101F600078606FF00200BDE8F88F4FF00008E6E7F8 -:101F7000002606607860ADB24FF0000B454510D9E1 -:101F80000AEB0803221D13F8011B9155B1B208F1A9 -:101F900001081B291FFA88F82BD0454506F10106D8 -:101FA000F1D8FB8AC3F30902154465F30903BCE7C2 -:101FB000013292B21C462368002BF9D1AB1F0B44AF -:101FC0001C21B3FBF1F301339BB29A42D3D2BBF194 -:101FD000000FD0D14846FFF74DFF20B9C4F800B03C -:101FE000BFE70122E7E7C0F800B05E462060044684 -:101FF000C1E74545D5D94846FFF73CFF08B9206001 -:10200000AFE7C0F800B0002620600446B6E7000045 -:102010002DE9F04F2DED028B83B0CDE90013BDF813 -:102020003C4080469246002A00F087802CB10E9BEF -:10203000002B00F08280072C2BD808F10C00FFF752 -:1020400019FF054638B96FF00205284603B0BDEC0C -:10205000028BBDE8F08F14220021FFF793FD22468A -:102060000E9905F10800FFF767FD631C2B749AF8C1 -:1020700000302C4403F01F0363F03F032372009BE6 -:1020800043F00041696040462946FFF75BFE0125A9 -:10209000DBE700F10C034FF0000908EE103A4FF0B7 -:1020A000800B4E464D4618EE100AFFF7E3FE07463A -:1020B0000028C8D014220021FFF764FD002E3AD179 -:1020C000019B3B8102220E9B02F1080103EB060CEF -:1020D00057FA81F11046B44202F10102D2B201D89E -:1020E000024607E01CF8010B01F8010B0136062A35 -:1020F000B6B2EFD99AF8001001F01F01B44208BF40 -:102100004FF0400BB81841EA49114BEA0103037242 -:10211000009B013243F000437B603A7439464046ED -:10212000FFF710FE0135B4422DB289F001094FF0DE -:10213000000BB8D189E70022C5E76FF0010584E7FD -:10214000F8B515460E462422002104461F46FFF727 -:1021500019FD069B6360B5F5001F079BA76034BFA0 -:102160006A094FF6FF72236204F10C0097B2002354 -:102170009A4205D80023036027826382A382F8BDB8 -:102180000660013330462036F2E7000003781BB9C1 -:102190004BB2002BC8BF0170704700000078704739 -:1021A0002DE9F74FDDF83C90BDF830500D9E9DF8BD -:1021B0003840BDF84070804692469B46B9F1000F0A -:1021C00001D1002F51D11F2C4FD898F80000B0B981 -:1021D000072F47D835F0030347D13A4649464FF613 -:1021E000FF70FFF73BFE20F001002D02400445EA9E -:1021F0000464400C44EA40244FF6FF7321E040EAB7 -:102200000520072F40EA0464F6D900254FF6FF7336 -:10221000C5F12000A5F120022AFA05F10BFA00F021 -:1022200001432BFA02F211431846C9B2FFF704FE2C -:102230000835402D0346EBD13A464946FFF70EFEDE -:102240000346CDE90097324621464046FFF7E0FEBF -:1022500033780133DBB21F2B88BF0023337003B008 -:10226000BDE8F08F6FF00300F9E76FF00100F6E7CB -:102270002DE9F04F85B09246DDF848800F9D9DF81E -:1022800040209DF84490BDF84C7006469B46B8F13E -:10229000000F01D1002F48D11F2A46D83378002BD8 -:1022A00046D00C0244EA02649DF8381044EAC9346E -:1022B00044EA01441C43072F44F0800432D9002330 -:1022C0004FF6FF72C3F1200CA3F120002AFA03F1AC -:1022D0000BFA0CFC41EA0C012BFA00F00143C9B2E5 -:1022E00010460393FFF7A8FD039B0833402B0246DB -:1022F000E8D13A464146FFF7B1FD0346CDE90087F4 -:102300002A4621463046FFF783FEB9F1010F06D178 -:102310002B780133DBB21F2B88BF00232B7005B055 -:10232000BDE8F08F4FF6FF73E8E76FF00100F6E7C6 -:102330006FF00300F3E70000C06900B1043070479C -:10234000C3691A68C261C2681A60C360438A013BEC -:10235000438270472DE9F041D0F81880194E144699 -:102360001D464146002709B9BDE8F081D1E90223A5 -:10237000A21A65EB0303964277EB03031ED283692F -:102380008B420DD1FFF7A2FD83691B688361C3688F -:102390000B60438AC1608169013B43828846E2E762 -:1023A000FFF794FD0B68C8F80030C3680B60438AE0 -:1023B000C160013B4382D8F80010D4E78846096821 -:1023C000D1E700BF80841E002DE9F04F8BB00D4691 -:1023D000DDF8509014469B468046002800F0198195 -:1023E000B9F1000F00F01581531E3F2B00F211814F -:1023F000012A03D1BBF1000F40F00B810023CDE98E -:102400000833B8F81430B5EBC30F4FEAC30703D352 -:1024100000200BB0BDE8F08F2B199F42D8F80C308C -:102420003ABF7F1BFFB227461BB9D8F81030002BEC -:102430007AD02F2D4ED8C5F13006B7424FF00003A9 -:102440002CBFF6B23E4600932946D8F8080008ABE8 -:102450003246FFF7B9FCA7EB060A35445FFA8AFA61 -:10246000B8F8143003F10053063BDB000493D8F8AE -:102470000C3003933021039B13B1BAF1000F2CD120 -:10248000D8F8100040B1BAF1000F05D0009608ABA3 -:102490005246691AFFF798FC38B2002FB8D0660789 -:1024A0000AD00AAB03EBD401624211F8083C02F0F7 -:1024B0000702134101F8083C082C3CD9102C40F2CB -:1024C000B580202C40F2B780BBF1000F00F09C805B -:1024D000082334E0BA460026C2E7049BE02B28BF5D -:1024E000E02306930B44AB42059314D95A1B03987F -:1024F0000096924534BF5246D2B2691A08AB0430F6 -:102500000792FFF761FC079A1644AAEB020A1544EA -:10251000F6B25FFA8AFA049B069A05999B1A04930D -:10252000039B1B680393A6E70093D8F8080008AB49 -:102530003A462946AEE7BBF1000F13D00123B4EBB6 -:10254000C30F6CD0082C12D89DF82030621E23FADD -:1025500002F2D50706D54FF0FF3202FA04F4234306 -:102560008DF820309DF8203089F8003051E7102C8C -:1025700012D8BDF82030621E23FA02F2D10706D528 -:102580004FF0FF3202FA04F42343ADF82030BDF8D7 -:102590002030A9F800303CE7202C0FD80899631EA2 -:1025A00021FA03F3DA0705D54FF0FF3202FA04F4FB -:1025B0000C430894089BC9F800302AE7402C2BD024 -:1025C000DDE90865611EC4F12102A4F1210326FAA8 -:1025D00001F105FA02F225FA03F311431943CB077F -:1025E00012D50122A4F12003C4F1200102FA03F361 -:1025F00022FA01F1A240524243EA010363EB430392 -:1026000032432B43CDE90823DDE90823C9E9002340 -:10261000FFE66FF00100FCE66FF00800F9E6082C19 -:10262000A0D9102CB3D9202CEED8C3E7BBF1000FF2 -:10263000ADD0022383E7BBF1000FBBD004237EE7BC -:1026400030B5012A144638BF0124402C85B028BF7C -:1026500040240025012ACDE9025518D81B788DF8B1 -:10266000083063070AD004AB03EBD405624215F8C7 -:10267000083C02F00702934005F8083C009103462D -:102680002246002102A8FFF79FFB05B030BD082AB3 -:10269000E4D9102A03D81B88ADF80830E1E7202AD6 -:1026A0008DBFD3E900231B680293CDE90223D8E74D -:1026B00010B5CB681BB98B600B618B8210BDC468F1 -:1026C0001A681C60C360438A013B4382CA60F0E71A -:1026D0002DE9F04FD1F8008093B018F0800FCDE9CC -:1026E0000323C8F3C01219BFC8F3C03BC8F30626C2 -:1026F0004FF0020B1646B8F1000F04460D4680F26B -:10270000C58118F0C043059340F0C0810B7B002BBE -:1027100000F0BC81BBF1020F03D00178B14240F060 -:10272000B88108F07F0106916AB3C8F3074A2B44C9 -:10273000069A93F80390760646EA0B4646EA8246E6 -:102740005FEAD91346EA0A06079300F09080002258 -:102750000023CDE90A23069B009367685B46524637 -:102760000AA92046B84700287ED0A7699FB93146FC -:1027700004F10C00FFF78CFB0746E0B96FF0020094 -:1027800013B0BDE8F08FC8F30F2A18F07F0F08BF11 -:102790000AF0030ACBE73B699E420DD03F68002F49 -:1027A000F9D1314604F10C00FFF772FB074600280F -:1027B000E4D0A3693B60A761DDE90A2300264FF658 -:1027C000FF70C6F1200E22FA06F103FA0EFEA6F102 -:1027D000200C23FA0CFC41EA0E0141EA0C01C9B2BB -:1027E000083609920893FFF727FB402EDDE90832EF -:1027F000E7D1B882FB7D09F01F06C3F38403F31A07 -:10280000D7E9022198B2002BBCBF00F120031BB214 -:1028100052EA0100C8F304680FD00398821A0498A2 -:1028200060EB0101A14890424FF000028A4104D3BD -:10283000079A002A55D0012B23DDFA7D4FEA890340 -:1028400002F0030203F07C031343FB753946204674 -:10285000FFF73CFB079BA3B9FB7DC3F38402013266 -:1028600062F38603FB7504E06FF00B0088E7A7694D -:1028700017B96FF00C0083E73B699E42BAD03F68FE -:10288000F6E719F0400F2CD0039BBB60049BFB6064 -:10289000142200210DA8FFF775F9039B0A93049BEE -:1028A0000B932B1D0C932B7BADF83EA0013BDBB2B1 -:1028B000ADF83C30069B8DF843308DF840B0A368EE -:1028C0008DF841608DF842800AA920469847FB7D2B -:1028D000C3F38403013303F01F039B02FB82002038 -:1028E0004EE7FB7DC9F34012B2EBD31F40F0D4801A -:1028F000C3F38403B34240F0D28007992B7B4FEAA5 -:102900009912002934D0D20741D4032B40F2CA8057 -:10291000039BBB60049BFB602B7BAE1D033BDBB2C8 -:102920003246394604F10C00FFF7E2FA00280DDACE -:1029300020463946FFF7CAFAFB7DC3F3840301330F -:1029400003F01F039B02FB82032019E7AB883B8344 -:102950002A7B033AB88AD2B23146FFF77FFAFB7D71 -:10296000B882DA43C2F3C01262F3C713FB75B6E74D -:102970006AB92E1D013BDBB23246394604F10C0028 -:10298000FFF7B6FA0028D3DB2A7B013AE2E7F98A9F -:10299000C1F30901013B0529DAB253D8281D0023F0 -:1029A00007F11A0C9A4208D910F801EB0CF801E073 -:1029B000013101330629DBB2F4D103990A9104995C -:1029C0000B91934207F11A010C9138BF04337968D7 -:1029D0000D9134BF55FA83F300230E93FB8AADF8B3 -:1029E0003EA0C3F309031A44069B8DF8433000232D -:1029F000ADF83C208DF840B08DF841608DF84280F4 -:102A00007B602A7BB88A013A291DFFF727FA3B8BA6 -:102A1000B882834203D1A3680AA92046984720467A -:102A20000AA9FFF745FEFB7DB88AC3F3840301338F -:102A300003F01F039B02FB823B8B984214BF1120C3 -:102A400000209DE67B68002BB7D0062001E01C30FB -:102A50006346D3F800C0BCF1000FF8D1091A081D75 -:102A600005F1040C00EB030905989DF8143001EB07 -:102A7000000EBEF11B0FA0D89A429ED91CF8013B54 -:102A800009F8013B059B01330593EDE76FF0090061 -:102A900076E66FF00A0073E66FF00D0070E66FF0F7 -:102AA0000E006DE66FF00F006AE600BF80841E0026 -:102AB000404BF0B51C6C404E44F000741C641D6E1D -:102AC00045F000751D661B6E3C4B9B6AD3F80052A7 -:102AD000354045F00105C3F80052D3F800423440B8 -:102AE00044EA002040F00100C3F80002002952D05F -:102AF0000020C3F81C020546C3F80402C3F80C0208 -:102B0000C3F8140203EBC00401301C28C4F840527F -:102B1000C4F84452F6D100254FF0010C9678148881 -:102B2000F70748BFD3F804720CFA04F044BF074318 -:102B3000C3F80472B70742BFD3F80C720743C3F857 -:102B40000C72760742BFD3F814620643C3F81462CE -:102B500003EBC4045668C4F840629668C4F8446243 -:102B6000D3F81C4201352043A942C3F81C0202F1EC -:102B70000C02D3D1D3F8002222F00102C3F80022C4 -:102B80000C4B1A6C22F000721A641A6E22F000725A -:102B90001A661B6EF0BD0122C3F84012C3F844123E -:102BA000C3F80412C3F81412C3F80C22C3F81C2291 -:102BB000E0E700BF003802400000FFFFC8350020FA -:102BC000184A916A08B58B688B6013F0010104D034 -:102BD00013F00C0F18BF4FF48031D80506D513F44D -:102BE000406F14BF41F4003141F00201D80306D513 -:102BF00013F4402F14BF41F4802141F00401D36944 -:102C00000BB108489847202383F311880648002118 -:102C100000F0AEFF002383F31188BDE8084001F007 -:102C200003BC00BFC8350020D035002038B5124C99 -:102C3000A36ADD68AA0712D05A6922F002025A611B -:102C4000A36913B1012120469847202383F31188FB -:102C50000A48002100F08CFF002383F31188EB0663 -:102C600006D5A36A1021D960236A0BB102489847A0 -:102C7000BDE8384001F0D8BBC8350020D835002069 -:102C800038B5124CA36A1D69AA0712D05A6922F0FE -:102C900010025A61A36913B10221204698472023EC -:102CA00083F311880A48002100F062FF002383F3B8 -:102CB0001188EB0606D5A36A10211961236A0BB1AE -:102CC00002489847BDE8384001F0AEBBC835002047 -:102CD000D835002038B50F4CA36A5D685D602A07BF -:102CE0000AD5042222701A6822F002021A60636A6E -:102CF00013B10021204698476B0706D5A36A99694E -:102D0000236A13B1034809049847BDE8384001F02D -:102D10008BBB00BFC835002010B50E4C204600F01C -:102D200029F90D4BA3620B21132000F00BF90B21A5 -:102D3000142000F007F90B21152000F003F90B21F6 -:102D4000162000F0FFF80022BDE8104011460E20CA -:102D5000FFF7AEBEC835002000640040114B98421A -:102D600010B5044609D1104B1A6C42F000721A6477 -:102D70001A6E42F000721A661B6EA36A01221A6074 -:102D8000A36A5A68D20707D5626851681268D96188 -:102D90001A60064A5A6110BD0121082000F0D4FDD6 -:102DA000EEE700BFC8350020003802405B87010015 -:102DB00003291AD8DFE801F0020A0F14836A9B681E -:102DC00013F0E05F14BF012000207047836A986809 -:102DD000C0F380607047836A9868C0F3C060704732 -:102DE000836A9868C0F30070704700207047000045 -:102DF00010B5032925D8DFE801F00225292D836AC3 -:102E00009968C1F30161183103EB0113107884064E -:102E10004CBF54689488C0F300114FEA410148BF89 -:102E200041EAC40100F00F004CBF41F0040141EA47 -:102E30004451586041F001019068D2689860DA60AE -:102E4000196010BD836A03F5C073DFE7836A03F579 -:102E5000C873DBE7836A03F5D073D7E701290AD08B -:102E600002290FD081B9836ADA68920701D1186903 -:102E700003E001207047836AD86810F0030018BF90 -:102E800001207047836AF2E70020704710B539B916 -:102E9000836AD96889071BD11B699C0704D110BDBF -:102EA000012915D00229FAD1816AD1F8C031D1F8AF -:102EB000C441D1F8C8011061D1F8CC015061202083 -:102EC00008610869800717D1486940F0100012E0D6 -:102ED000816AD1F8B031D1F8B441D1F8B8011061AC -:102EE000D1F8BC0150612020C860C868800703D1B8 -:102EF000486940F002004861C3F34000C3F3800119 -:102F0000000140EA4111107920F0300001431171B5 -:102F100089064BBF91681189DB085B0D4CBF63F3D9 -:102F20001C0163F30A01137948BF916064F3030342 -:102F300013714FEA14234FEA144458BF11811370E0 -:102F40005480ACE700F1604303F561430901C9B265 -:102F500083F80013012200F01F039A4043099B00ED -:102F600003F1604303F56143C3F880211A607047A1 -:102F7000FFF7D2BE012300F10802C0E9022203706C -:102F800000F110020023C0E90422C0E90633C0E9C1 -:102F9000083343607047000010B52023044683F3D4 -:102FA0001188022303704160FFF7D8FE04232370C9 -:102FB000002383F3118810BD2DE9F0411F4604461C -:102FC0000D461646202383F3118800F10808237864 -:102FD000052B0DD029462046FFF7EAFE40B12046DA -:102FE00032462946FFF704FF002080F3118808E0ED -:102FF0003946404600F0A0FD0028E8D0002383F3C6 -:103000001188BDE8F08100002DE9F0411F4604461B -:103010000D461646202383F3118800F1100823780B -:10302000052B0DD029462046FFF718FF40B120465A -:1030300032462946FFF72AFF002080F3118808E076 -:103040003946404600F078FD0028E8D0002383F39D -:103050001188BDE8F08100000268436811430160F7 -:1030600003B118477047000013B5446BD4F894348B -:103070001A681178042915D1217C022912D11979F5 -:10308000128901238B4013420CD101A904F14C0099 -:1030900001F088FFD4F89444019B2179024620680E -:1030A00000F0CEF902B010BD143001F00BBF0000EB -:1030B0004FF0FF33143001F005BF00004C3001F039 -:1030C000DDBF00004FF0FF334C3001F0D7BF0000F0 -:1030D000143001F0D9BE00004FF0FF31143001F080 -:1030E000D3BE00004C3001F0A9BF00004FF0FF320A -:1030F0004C3001F0A3BF00000020704710B5D0F89D -:1031000094341A6811780429044617D1017C0229E5 -:1031100014D15979528901238B4013420ED11430B6 -:1031200001F06CFE024648B1D4F894444FF4807329 -:1031300061792068BDE8104000F070B910BD000052 -:10314000406BFFF7DBBF0000704700007FB5124BFC -:10315000036000234360C0E90233012502260F4BC0 -:10316000057404460290019300F1840229460096FA -:103170004FF48073143001F01DFE094B0294CDE929 -:10318000006304F523724FF48073294604F14C0068 -:1031900001F0E4FE04B070BD24580008413100087D -:1031A000693000080B68202282F311880A7903EB4A -:1031B000820290614A79093243F822008A7912B179 -:1031C00003EB8203986102230374C0F89414002374 -:1031D00083F311887047000038B5037F044613B1AC -:1031E00090F85430ABB9201D01250221FFF734FFC0 -:1031F00004F1140025776FF0010100F0B9FC84F8A8 -:10320000545004F14C006FF00101BDE8384000F06B -:10321000AFBC38BD10B5012104460430FFF71CFFD8 -:103220000023237784F8543010BD000038B50446DD -:103230000025143001F0D6FD04F14C00257701F093 -:10324000A5FE201D84F854500121FFF705FF2046FC -:10325000BDE83840FFF752BF90F8443003F06003F8 -:10326000202B07D190F84520212A4FF0000303D8E6 -:103270001F2A06D800207047222AFBD1C0E90E334E -:1032800003E0034A82630722C2630364012070479C -:103290002123002037B5D0F894341A681178042916 -:1032A00004461AD1017C022917D119791289012308 -:1032B0008B40134211D100F14C05284601F026FF46 -:1032C00058B101A9284601F06DFED4F89444019B41 -:1032D00021790246206800F0B3F803B030BD000049 -:1032E000F0B500EB810385B09E6904460D46FEB142 -:1032F000202383F3118804EB8507301D0821FFF795 -:10330000ABFEFB685B691B6806F14C001BB10190CA -:1033100001F056FE019803A901F044FE024648B1AF -:10332000039B2946204600F08BF8002383F3118885 -:1033300005B0F0BDFB685A691268002AF5D01B8AF7 -:10334000013B1340F1D104F14402EAE7093138B5F9 -:1033500050F82140DCB1202383F31188D4F8942461 -:103360001368527903EB8203DB689B695D6845B1A2 -:1033700004216018FFF770FE294604F1140001F0E3 -:1033800047FD2046FFF7BAFE002383F3118838BDBE -:103390007047000001F00AB9012303700023C0E95F -:1033A0000133C36183620362C36243620363704794 -:1033B00038B50446202383F311880025C0E903555E -:1033C000C0E90555416001F001F90223237085F33E -:1033D000118838BD70B500EB810305465069DA608D -:1033E0000E46144618B110220021FEF7CBFBA0694F -:1033F00018B110220021FEF7C5FB31462846BDE872 -:10340000704001F0ADB90000826802F001128260E4 -:103410000022C0E90422826101F02EBAF0B400EB70 -:1034200081044789E4680125A4698D403D434581B5 -:1034300023600023A2606360F0BC01F049BA000081 -:10344000F0B400EB81040789E468012564698D40CC -:103450003D43058123600023A2606360F0BC01F05E -:10346000C3BA000070B50223002504460370C0E90A -:103470000255C0E90455C564856180F8345001F0F7 -:103480000BF963681B6823B129462046BDE87040EC -:10349000184770BD037880F85030052303704368E7 -:1034A0001B6810B504460BB1042198470023A360A4 -:1034B00010BD000090F85020436802701B680BB1EB -:1034C000052118477047000070B590F83430044665 -:1034D00013B1002380F8343004F14402204601F097 -:1034E000EDF963689B68B3B994F8443013F0600554 -:1034F00035D00021204601F03FFC0021204601F09C -:1035000031FC63681B6813B10621204698470623E7 -:1035100084F8343070BD204698470028E4D0B4F8D1 -:103520004A30E26B9A4288BFE36394F94430E56B1A -:10353000002B4FF0200380F20381002D00F0F28079 -:10354000092284F8342083F311880021D4E90E2362 -:103550002046FFF775FF002383F31188DAE794F81C -:10356000452003F07F0343EA022340F202329342F4 -:1035700000F0C58021D8B3F5807F48D00DD8012B4D -:103580003FD0022B00F09380002BB2D104F14C020B -:10359000A2630222E2632364C1E7B3F5817F00F0F6 -:1035A0009B80B3F5407FA4D194F84630012BA0D185 -:1035B000B4F84C3043F0020332E0B3F5006F4DD065 -:1035C00017D8B3F5A06F31D0A3F5C063012B90D805 -:1035D000636894F846205E6894F84710B4F8483061 -:1035E0002046B047002884D04368A3630368E363A0 -:1035F0001AE0B3F5106F36D040F6024293427FF4E2 -:1036000078AF5C4BA3630223E3630023C3E794F822 -:103610004630012B7FF46DAFB4F84C3023F0020339 -:10362000C4E90E55A4F84C30256478E7B4F844306A -:10363000B3F5A06F0ED194F8463084F84E30204692 -:1036400001F082F863681B6813B101212046984796 -:10365000032323700023C4E90E339CE704F14F03D6 -:10366000A3630123C3E72378042B10D1202383F322 -:1036700011882046FFF7C8FE85F31188032163688F -:1036800084F84F5021701B680BB12046984794F87E -:103690004630002BDED084F84F300423237063685B -:1036A0001B68002BD6D0022120469847D2E794F819 -:1036B00048301D0603F00F0120460AD501F0F0F84E -:1036C000012804D002287FF414AF2B4B9AE72B4B30 -:1036D00098E701F0D7F8F3E794F84630002B7FF431 -:1036E00008AF94F8483013F00F01B3D01A06204603 -:1036F00002D501F055FBADE701F048FBAAE794F8CD -:103700004630002B7FF4F5AE94F8483013F00F01EB -:10371000A0D01B06204602D501F02EFB9AE701F04F -:1037200021FB97E7142284F8342083F311882B4679 -:103730002A4629462046FFF771FE85F31188E9E6FF -:103740005DB1152284F8342083F311880021D4E977 -:103750000E232046FFF762FEFDE60B2284F834209C -:1037600083F311882B462A4629462046FFF768FE38 -:10377000E3E700BF545800084C58000850580008B0 -:1037800038B590F834300446002B3ED0063BDAB210 -:103790000F2A34D80F2B32D8DFE803F03731310845 -:1037A000223231313131313131313737C56BB0F8F7 -:1037B0004A309D4214D2C3681B8AB5FBF3F203FB67 -:1037C00012556DB9202383F311882B462A462946CA -:1037D000FFF736FE85F311880A2384F834300EE0B3 -:1037E000142384F83430202383F3118800231A46ED -:1037F00019462046FFF712FE002383F3118838BDD7 -:10380000036C03B198470023E7E70021204601F04D -:10381000B3FA0021204601F0A5FA63681B6813B1D2 -:103820000621204698470623D7E7000010B590F8F8 -:103830003430142B044629D017D8062B05D001D8D4 -:103840001BB110BD093B022BFBD80021204601F023 -:1038500093FA0021204601F085FA63681B6813B1D2 -:10386000062120469847062319E0152BE9D10B23A2 -:1038700080F83430202383F3118800231A46194638 -:10388000FFF7DEFD002383F31188DAE7C3689B6945 -:103890005B68002BD5D1036C03B19847002384F8F3 -:1038A0003430CEE7024B0022C3E900339A60704700 -:1038B000F4350020002303748268054B1B68996867 -:1038C0009142FBD25A6803604260106058607047B2 -:1038D000F435002008B5202383F31188037C032BE3 -:1038E00005D0042B0DD02BB983F3118808BD436993 -:1038F00000221A604FF0FF334361FFF7DBFF002324 -:10390000F2E7D0E9003213605A60F3E70023037452 -:103910008268054B1B6899689142FBD85A6803601E -:103920004260106058607047F4350020054B1969FB -:103930000874186802681A605360186101230374E0 -:10394000FCF766BEF435002030B54B1C0B4D87B03C -:10395000044610D02B690A4A01A800F025F9204638 -:10396000FFF7E4FF049B13B101A800F059F92B699C -:10397000586907B030BDFFF7D9FFF8E7F4350020EC -:10398000D538000838B50C4D41612B6981689A68BB -:103990009142044603D8BDE83840FFF78BBF184674 -:1039A000FFF7B4FF01232C61014623742046BDE8D4 -:1039B0003840FCF72DBE00BFF4350020044B1A68D8 -:1039C0001B6990689B68984294BF00200120704753 -:1039D000F435002010B5084C236820691A6822606D -:1039E0005460012223611A74FFF790FF0146206999 -:1039F000BDE81040FCF70CBEF435002008B5FFF719 -:103A0000DDFF18B1BDE80840FFF7E4BF08BD0000C6 -:103A1000FFF7E0BFFEE7000010B50C4CFFF742FFD8 -:103A200000F0B4F80A498022204600F03BF8012358 -:103A300044F8180C037400F0D3FC002383F31188BE -:103A400062B60448BDE8104000F04CB81C360020B7 -:103A5000585800086858000800F01CB9EFF31180AE -:103A600020B9EFF30583202282F31188704700000C -:103A700010B530B9EFF30584C4F3080414B180F332 -:103A8000118810BDFFF7BAFF84F31188F9E7000031 -:103A9000034A516853685B1A9842FBD8704700BFCD -:103AA000001000E082600222028270478368A3F166 -:103AB0007C0243F80C2C026943F83C2C426943F821 -:103AC000382C074A43F81C2CC26843F8102C0222F9 -:103AD00003F8082C002203F8072CA3F11800704704 -:103AE0002906000810B5202383F31188FFF7DEFFB5 -:103AF00000210446FFF746FF002383F31188204688 -:103B000010BD0000024B1B6958610F20FFF70EBF6C -:103B1000F4350020202383F31188FFF7F3BF000062 -:103B200008B50146202383F311880820FFF70CFF16 -:103B3000002383F3118808BD49B1064B42681B6915 -:103B400018605A60136043600420FFF7FDBE4FF019 -:103B5000FF307047F43500200368984206D01A6899 -:103B60000260506059611846FFF7A4BE704700001C -:103B700038B504460D462068844200D138BD03683C -:103B800023605C604561FFF795FEF4E7054B03F1A8 -:103B90001402C3E905224FF0FF310022C3E90712E6 -:103BA000704700BFF435002070B51C4EC0E90323F8 -:103BB00005460C4601F0DCFA334653F8142F9A42BE -:103BC0000DD13062C5E901242A600A2C2CBF0019EE -:103BD0000A30C6E90555BDE8704001F0B7BA316A50 -:103BE000431AE31838BF1C469368A34202D9081948 -:103BF00001F0BAFA73699A6894420CD85A68AC60BA -:103C00002B606A6015609A685D60121B9A604FF0C5 -:103C1000FF33F36170BD1B68A41AECE7F435002094 -:103C200038B51B4C636998420DD0D0E9003213605F -:103C30005A6000228168C2609A680A449A604FF014 -:103C4000FF33E36138BD2246036842F8143F002188 -:103C500093425A60C16003D1BDE8384001F07EBA9A -:103C60009A688168256A0A449A6001F081FA63695A -:103C70009A68411B8A42E5D9AB181D1A092D206AA2 -:103C800098BF01F10A02BDE83840104401F06CBA57 -:103C9000F43500202DE9F041184C002704F11406FA -:103CA000656901F065FA236AAA68C11A8A4215D8C3 -:103CB00013442362D5E9003213605A606369D5F872 -:103CC0000C80EF60B34201D101F048FA87F311880C -:103CD0002869C047202383F31188E1E76169B14275 -:103CE00009D013441B1ABDE8F0410A2B2CBFC018A1 -:103CF0000A3001F039BABDE8F08100BFF435002088 -:103D000000207047FEE70000704700004FF0FF30D2 -:103D10007047000002290CD0032904D0012907486C -:103D200018BF00207047032A05D8054800EBC200E1 -:103D30007047044870470020704700BF4C59000886 -:103D4000302300200059000870B59AB00546084697 -:103D500001A9144600F0C2F801A8FDF70BFF431CAF -:103D60005B00C5E900340022237003236370C6B2F0 -:103D700001AB02341046D1B28E4204F1020401D8E4 -:103D80001AB070BD13F8011B04F8021C04F8010CF2 -:103D90000132F0E708B5202383F311880348FFF7C9 -:103DA00079FA002383F3118808BD00BFB0370020E3 -:103DB00090F8443003F01F02012A07D190F8452003 -:103DC0000B2A03D10023C0E90E3315E003F0600392 -:103DD000202B08D1B0F848302BB990F84520212A83 -:103DE00003D81F2A04D8FFF737BA222AEBD0FAE704 -:103DF000034A82630722C26303640120704700BF45 -:103E00002823002007B5052917D8DFE801F0191687 -:103E100003191920202383F31188104A01900121EE -:103E2000FFF7D8FA01980E4A0221FFF7D3FA0D489E -:103E3000FFF7FCF9002383F3118803B05DF804FB5E -:103E4000202383F311880748FFF7C6F9F2E7202300 -:103E500083F311880348FFF7DDF9EBE7A05800086A -:103E6000C4580008B037002038B50C4D0C4C0D4933 -:103E70002A4604F10800FFF767FF05F1CA0204F1C2 -:103E800010000949FFF760FF05F5CA7204F1180038 -:103E90000649BDE83840FFF757BF00BF783C002017 -:103EA00030230020805800088A58000895580008E0 -:103EB00070B5044608460D46FDF75CFEC6B22046C6 -:103EC000013403780BB9184670BD32462946FDF718 -:103ED0003DFE0028F3D10120F6E700002DE9F04770 -:103EE00005460C46FDF746FE2B49C6B22846FFF7AD -:103EF000DFFF08B10B36F6B228492846FFF7D8FF96 -:103F000008B11036F6B2632E0BD8DFF88C80DFF8DC -:103F10008C90234FDFF894A02E7846B92670BDE828 -:103F2000F08729462046BDE8F04701F0E5BB252E85 -:103F30002ED1072241462846FDF708FE70B9194BDD -:103F4000224603F1100153F8040B42F8040B8B4294 -:103F5000F9D11B88138007351234DDE70822494662 -:103F60002846FDF7F3FD98B90F4BA21C19780909F3 -:103F70000232C95D02F8041C13F8011B01F00F01A5 -:103F80005345C95D02F8031CF0D118340835C3E766 -:103F900004F8016B0135BFE76C590008955800081B -:103FA0008759000874590008107AFF1F1C7AFF1FF8 -:103FB000BFF34F8F024AD368DB03FCD4704700BFC6 -:103FC000003C024008B5094B1B7873B9FFF7F0FFBE -:103FD000074B1A69002ABFBF064A5A6002F18832AD -:103FE0005A601A6822F480621A6008BDD63E00202A -:103FF000003C02402301674508B50B4B1B7893B981 -:10400000FFF7D6FF094B1A6942F000421A611A689D -:1040100042F480521A601A6822F480521A601A68B8 -:1040200042F480621A6008BDD63E0020003C024087 -:104030000B28F0B516D80C4C0C4923787BB90C4DE5 -:104040000E460C234FF0006255F8047B46F8042B13 -:10405000013B13F0FF033A44F6D10123237051F8DA -:104060002000F0BD0020FCE7083F0020D83E0020E3 -:1040700098590008014B53F82000704798590008E0 -:104080000C2070470B2810B5044601D9002010BD44 -:10409000FFF7CEFF064B53F824301844C21A0BB971 -:1040A0000120F4E712680132F0D1043BF6E700BFCB -:1040B000985900080B2810B5044621D8FFF778FF5F -:1040C000FFF780FF0F4AF323D360C300DBB243F452 -:1040D000007343F002031361136943F480331361E7 -:1040E000FFF766FFFFF7A4FF074B53F8241000F01B -:1040F00029F9FFF781FF2046BDE81040FFF7C2BF56 -:10410000002010BD003C024098590008F8B512F09C -:104110000103144642D18218B2F1016F57D82D4BDA -:104120001B6813F0010352D02B4DFFF74BFFF32315 -:10413000EB60FFF73DFF40F20127032C15D824F078 -:1041400001046618244C401A40F20117B142236959 -:1041500000EB010524D123F001032361FFF74CFF9D -:104160000120F8BD043C0430E7E78307E7D12B6961 -:1041700023F440732B612B693B432B6151F8046B93 -:104180000660BFF34F8FFFF713FF03689E42E9D02D -:104190002B6923F001032B61FFF72EFF0020E0E7DE -:1041A00023F44073236123693B4323610B882B80F5 -:1041B000BFF34F8FFFF7FCFE2D8831F8023BADB205 -:1041C000AB42C3D0236923F001032361E4E718461F -:1041D000C7E700BF00380240003C0240084908B56C -:1041E0000B7828B11BB9FFF7EDFE01230B7008BD5A -:1041F000002BFCD0BDE808400870FFF7FDBE00BFF3 -:10420000D63E002070B582B0FFF728FC0E4E054662 -:1042100000F0AEFF3268904237BF0C4A0B4951683C -:1042200014682EBFD1E900410131516004190346E1 -:1042300041F10001284601913360FFF719FC019913 -:10424000204602B070BD00BF0C3F0020103F002090 -:1042500070B582B0FFF702FC104E054600F088FFF3 -:104260003268904237BF0E4A0D49516814682EBF1C -:10427000D1E9004101315160041941F100010346C7 -:10428000284601913360FFF7F3FB01994FF47A72EE -:1042900000232046FBF7A4FF02B070BD0C3F0020B6 -:1042A000103F002010B50244064BD2B2904200D11C -:1042B00010BD441C00B253F8200041F8040BE0B2DA -:1042C000F4E700BF502800400F4B30B51C6F2404AA -:1042D00007D41C6F44F400741C671C6F44F4004442 -:1042E0001C670A4C236843F4807323600244084B24 -:1042F000D2B2904200D130BD441C00B251F8045BF0 -:1043000043F82050E0B2F4E700380240007000406B -:104310005028004007B5012201A90020FFF7C2FF85 -:10432000019803B05DF804FB13B50446FFF7F2FFF4 -:10433000A04205D0012201A900200194FFF7C4FF8B -:1043400002B010BD70470000074B45F255521A608D -:1043500002225A6040F6FF729A604CF6CC421A6014 -:10436000024B01221A70704700300040193F0020B4 -:10437000034B1B781BB1034B4AF6AA221A60704705 -:10438000193F002000300040044BD3F874389B00E4 -:1043900042BF034B01221A70704700BF0030024039 -:1043A000183F0020024B4FF08072C3F8742870470A -:1043B00000300240014B1878704700BF183F0020C2 -:1043C000EFF3098305494A6B22F001024A6368331F -:1043D00083F30988002383F31188704700EF00E01E -:1043E000202080F3118862B60C4B0D4AD96821F465 -:1043F000E0610904090C0A43DA60D3F8FC2009499A -:1044000042F08072C3F8FC200A6842F001020A60A0 -:104410001022DA7783F82200704700BF00ED00E039 -:104420000003FA05001000E010B5202383F3118883 -:104430000E4B5B6813F4006314D0F1EE103AEFF307 -:104440000984683C4FF08073E361094BDB6B2366A2 -:1044500084F30988FFF7B2FA10B1064BA36110BDCF -:10446000054BFBE783F31188F9E700BF00ED00E09F -:1044700000EF00E03B0600083E0600087047000021 -:10448000FEE700000A4B0B480B4A90420BD30B4B44 -:10449000DA1C121AC11E22F003028B4238BF00221E -:1044A0000021FDF76FBB53F8041B40F8041BECE739 -:1044B000505B0008144000201440002014400020ED -:1044C0007047000070B5D0E915439E6800224FF098 -:1044D000FF3504EB42135101D3F800090028BEBF99 -:1044E000D3F8000940F08040C3F80009D3F8000B6E -:1044F0000028BEBFD3F8000B40F08040C3F8000B8B -:10450000013263189642C3F80859C3F8085BE0D239 -:104510004FF00113C4F81C3870BD00001D4B03EBB5 -:1045200080022DE9F043D2F80CC05D6DDCF8142058 -:10453000461CD2F800E005EB063605EB4018516842 -:1045400071450AD3D5F83438012202FA00F023EA83 -:104550000000C5F83408BDE8F083BCF81040AEEBAD -:104560000103A34228BF2346D8F81849A4B2B3EBED -:10457000840FF0D89468A4F1040959F8047F3760D7 -:10458000A4EB09071F44042FF7D81C440B44946084 -:104590005360D4E71C3F0020890141F020010161F4 -:1045A00003699B06FCD41220FFF772BA10B5054CC4 -:1045B0002046FEF7F1FE4FF0A0436365024BA36572 -:1045C00010BD00BF1C3F0020EC59000870B50378F7 -:1045D000012B054650D12A4B446D98421BD1294BE3 -:1045E0005A6B42F080025A635A6D42F080025A655B -:1045F0005A6D5A6942F080025A615A6922F080026B -:104600005A610E2143205B69FEF79CFC1E4BE36060 -:104610001E4BC4F800380023C4F8003EC0232360BA -:104620006E6D4FF40413A3633369002BFCDA01238E -:1046300033610C20FFF72CFA3369DB07FCD412201E -:10464000FFF726FA3369002BFCDA0026A66028461D -:10465000FFF738FF6B68C4F81068DB68C4F81468AB -:10466000C4F81C684BB90A4BA3614FF0FF33636178 -:10467000A36843F00103A36070BD064BF4E700BFDD -:104680001C3F00200038024040140040030020027C -:10469000003C30C0083C30C0F8B5446D05460021F0 -:1046A0002046FFF779FFA96D00234FF001128F68B4 -:1046B000C4F834384FF00066C4F81C284FF0FF30BF -:1046C00004EB431201339F42C2F80069C2F8006B49 -:1046D000C2F80809C2F8080BF2D20B686A6DEB65E4 -:1046E000636210231361166916F01006FBD11220C5 -:1046F000FFF7CEF9D4F8003823F4FE63C4F800388D -:10470000A36943F4402343F01003A3610923C4F8D1 -:104710001038C4F814380A4BEB604FF0C043C4F8AB -:10472000103B084BC4F8003BC4F81069C4F80039CA -:10473000EB6D03F1100243F48013EA65A362F8BD48 -:10474000C859000840800010426D90F84E10D2F811 -:10475000003823F4FE6343EA0113C2F800387047BF -:104760002DE9F84300EB8103456DDA68166806F021 -:104770000306731E022B05EB41130C4680460FFA0D -:1047800081F94FEA41104FF00001C3F8101B4FF0C0 -:10479000010104F1100398BFB60401FA03F3916913 -:1047A0008EBF334E06F1805606F5004600293AD0FA -:1047B000578A04F15801490137436F50D5F81C1846 -:1047C0000B43C5F81C382B180021C3F81019536986 -:1047D0000127611EA7409BB3138A928B9B08012A75 -:1047E00088BF5343D8F85C20981842EA034301F18C -:1047F000400205EB8202C8F85C002146536028465F -:10480000FFF7CAFE08EB8900C3681B8A43EA84539A -:10481000483464011E432E51D5F81C381F43C5F897 -:104820001C78BDE8F88305EB4917D7F8001B21F485 -:104830000041C7F8001BD5F81C1821EA0303C0E7A4 -:1048400004F13F0305EB83030A4A5A6028462146D8 -:10485000FFF7A2FE05EB4910D0F8003923F400431E -:10486000C0F80039D5F81C3823EA0707D7E700BF9E -:104870000080001000040002826D1268C265FFF71C -:1048800021BE00005831436D49015B5813F40040CC -:1048900004D013F4001F0CBF022001207047000059 -:1048A0004831436D49015B5813F4004004D013F4C0 -:1048B000001F0CBF022001207047000000EB8101A7 -:1048C000CB68196A0B6813604B685360704700002F -:1048D00000EB810330B5DD68AA691368D36019B9AC -:1048E000402B84BF402313606B8A1468426D1C44C4 -:1048F000013CB4FBF3F46343033323F0030302EB03 -:10490000411043EAC44343F0C043C0F8103B2B6856 -:1049100003F00303012B09B20ED1D2F8083802EBE1 -:10492000411013F4807FD0F8003B14BF43F0805354 -:1049300043F00053C0F8003B02EB4112D2F8003BB9 -:1049400043F00443C2F8003B30BD00002DE9F041C4 -:10495000244D6E6D06EB40130446D3F8087BC3F874 -:10496000087B38070AD5D6F81438190706D505EBA1 -:1049700084032146DB6828465B689847FA071FD501 -:10498000D6F81438DB071BD505EB8403D968CCB9FE -:104990008B69488A5A68B2FBF0F600FB16228AB986 -:1049A0001868DA6890420DD2121AC3E90024202355 -:1049B00083F311880B482146FFF78AFF84F311889F -:1049C000BDE8F081012303FA04F26B8923EA0203B4 -:1049D0006B81CB68002BF3D021460248BDE8F04143 -:1049E000184700BF1C3F002000EB810370B5DD6855 -:1049F000436D6C692668E6604A0156BB1A444FF461 -:104A00000020C2F810092A6802F00302012A0AB243 -:104A10000ED1D3F8080803EB421410F4807FD4F8C9 -:104A2000000914BF40F0805040F00050C4F8000965 -:104A300003EB4212D2F8000940F00440C2F800092A -:104A4000D3F83408012202FA01F10143C3F8341803 -:104A500070BD19B9402E84BF4020206020682E8A86 -:104A60008419013CB4FBF6F440EAC44040F0005025 -:104A70001A44C6E7F8B504461E48456D05EB4413D5 -:104A8000D3F80869C3F80869F10717D5D5F81038C5 -:104A9000DA0713D500EB8403D9684B691F68DA681D -:104AA000974218D2D21B00271A605F60202383F33D -:104AB00011882146FFF798FF87F31188330617D531 -:104AC000D5F834280123A340134211D02046BDE875 -:104AD000F840FFF723BD012303FA04F2038923EA18 -:104AE000020303818B68002BE8D021469847E5E755 -:104AF000F8BD00BF1C3F00202DE9F74F984C666DB4 -:104B00007569B3691D4015F48058756107D020465A -:104B1000FEF7A8FC03B0BDE8F04FFFF785BC002D01 -:104B200012DAD6F8003E8E489F071EBFD6F8003E28 -:104B300023F00303C6F8003ED6F8043823F001033F -:104B4000C6F80438FEF7B6FC280505D58448FFF7FB -:104B5000B9FC8348FEF79EFCA9040CD5D6F80838AA -:104B600013F0060FF36823F470530CBF43F4105393 -:104B700043F4A053F3602A0704D56368DB680BB1E4 -:104B800077489847EB0274D4AF0227D5D4F85490F5 -:104B9000DFF8CCB100274FF0010A09EB4712D2F839 -:104BA000003B03F44023B3F5802F11D1D2F8003B32 -:104BB000002B0DDA62890AFA07F322EA0303638104 -:104BC00004EB8703DB68DB6813B139465846984726 -:104BD000A36D01379B68FFB29F42DED9E80617D567 -:104BE000676D3A6AC2F30A1002F00F0302F4F01282 -:104BF000B2F5802F00F08880B2F5402F08D104EB89 -:104C000083030022DB681B6A07F5805790426DD151 -:104C10002903D6F8184813D5E20302D50020FFF780 -:104C200095FEA30302D50120FFF790FE670302D58E -:104C30000220FFF78BFE260302D50320FFF786FE36 -:104C40006D037FF567AFE00702D50020FFF712FF85 -:104C5000A10702D50120FFF70DFF620702D5022050 -:104C6000FFF708FF23077FF555AF0320FFF702FF8B -:104C700050E7636DDFF8E8B0019300274FF0010AB9 -:104C8000A36D9B685FFA87F999453FF67DAF019B5D -:104C900003EB4913D3F8002902F44022B2F5802F28 -:104CA00022D1D3F80029002A1EDAD3F8002942F0D5 -:104CB0009042C3F80029D3F80029002AFBDB606D7D -:104CC0004946FFF769FC22890AFA09F322EA03033D -:104CD000238104EB8903DB689B6813B1494658467E -:104CE00098474846FFF71AFC0137C9E7910708BF04 -:104CF000D7F80080072A98BF03F8018B02F1010260 -:104D000098BF4FEA182881E7023304EB830207F5C6 -:104D100080575268D2F818C0DCF80820DCE9001C83 -:104D2000A1EB0C0C002188420AD104EB83046368D8 -:104D30009B699A6802449A605A6802445A6067E71D -:104D400011F0030F08BFD7F800808C4588BF02F828 -:104D5000018B01F1010188BF4FEA1828E3E700BF8A -:104D60001C3F0020436D03EB4111D1F8003B43F49D -:104D70000013C1F8003B7047436D03EB4111D1F8BC -:104D8000003943F40013C1F800397047436D03EB59 -:104D90004111D1F8003B23F40013C1F8003B7047E8 -:104DA000436D03EB4111D1F8003923F40013C1F82E -:104DB0000039704730B5039C0172043304FB0325AE -:104DC000C0E90653049B03630021059BC160C0E951 -:104DD0000000C0E90422C0E90842C0E90A114363A7 -:104DE00030BD0000416A0022C0E90411C0E90A2276 -:104DF000C2606FF00101FEF7BBBE0000D0E90432D3 -:104E0000934201D1C2680AB9181D7047002070474B -:104E100003691960C2680132C260C26913448269C1 -:104E20000361934224BF436A03610021FEF794BEED -:104E300038B504460D46E3683BB16269131D12683C -:104E4000A3621344E362002007E0237A33B92946C2 -:104E50002046FEF771FE0028EDDA38BD6FF0010044 -:104E6000FBE70000C368C269013BC36043691344A8 -:104E700082694361934224BF436A43610023836292 -:104E8000036B03B11847704770B52023044683F3C2 -:104E90001188866A3EB9FFF7CBFF054618B186F345 -:104EA0001188284670BDA36AE26A13F8015BA36209 -:104EB000934202D32046FFF7D5FF002383F31188E6 -:104EC000EFE700002DE9F84F04460E4617469846D6 -:104ED0004FF0200989F311880025AA46D4F828B09C -:104EE000BBF1000F09D141462046FFF7A1FF20B1D9 -:104EF0008BF311882846BDE8F88FD4E90A12A7EB96 -:104F0000050B521A934528BF9346BBF1400F1BD99E -:104F1000334601F1400251F8040B43F8040B91426F -:104F2000F9D1A36A40334036A3624035D4E90A235D -:104F30009A4202D32046FFF795FF8AF31188BD42BB -:104F4000D8D289F31188C9E730465A46FCF7F4FDF8 -:104F5000A36A5B445E44A3625D44E7E710B5029C2C -:104F60000172043304FB0321C0E906130023C0E9E6 -:104F70000A33039B0363049BC460C0E90000C0E9DB -:104F80000422C0E90842436310BD0000026AC26007 -:104F9000426AC0E904220022C0E90A226FF001013E -:104FA000FEF7E6BDD0E904239A4201D1C26822B9D6 -:104FB000184650F8043B0B60704700207047000013 -:104FC000C368C2690133C3604369134482694361A2 -:104FD000934224BF436A43610021FEF7BDBD000038 -:104FE00038B504460D46E3683BB123691A1DA26239 -:104FF000E2691344E362002007E0237A33B92946CB -:105000002046FEF799FD0028EDDA38BD6FF001006B -:10501000FBE7000003691960C268013AC260C26917 -:10502000134482690361934224BF436A03610023EE -:105030008362036B03B118477047000070B52023EB -:105040000D460446114683F31188866A2EB9FFF790 -:10505000C7FF10B186F3118870BDA36A1D70A36AE3 -:10506000E26A01339342A36204D3E1692046043922 -:10507000FFF7D0FF002080F31188EDE72DE9F84F0E -:1050800004460D46904699464FF0200A8AF311884F -:105090000026B346A76A4FB949462046FFF7A0FF4E -:1050A00020B187F311883046BDE8F88FD4E90A07AC -:1050B0003A1AA8EB0607974228BF1746402F1BD97C -:1050C00005F1400355F8042B40F8042B9D42F9D11B -:1050D000A36A4033A3624036D4E90A239A4204D338 -:1050E000E16920460439FFF795FF8BF311884645A7 -:1050F000D9D28AF31188CDE729463A46FCF71CFD40 -:10510000A36A3B443D44A3623E44E5E7D0E904235F -:105110009A4217D1C3689BB1836A8BB1043B9B1A37 -:105120000ED01360C368013BC360C3691A4483692E -:1051300002619A4224BF436A036100238362012310 -:10514000184670470023FBE700F088B84FF0804313 -:10515000002258631A610222DA6070474FF08043E0 -:105160000022DA60704700004FF0804358637047B8 -:105170004FF08043586A70474B6843608B68836088 -:10518000CB68C3600B6943614B6903628B694362FF -:105190000B6803607047000008B5264B26481A6963 -:1051A00040F2FF110A431A611A6922F4FF7222F0D9 -:1051B00001021A611A691A6B0A431A631A6D0A43CB -:1051C0001A651E4A1B6D1146FFF7D6FF02F11C013E -:1051D00000F58060FFF7D0FF02F1380100F5806034 -:1051E000FFF7CAFF02F1540100F58060FFF7C4FF2A -:1051F00002F1700100F58060FFF7BEFF02F18C0143 -:1052000000F58060FFF7B8FF02F1A80100F58060AB -:10521000FFF7B2FF02F1C40100F58060FFF7ACFFB9 -:1052200002F1E00100F58060FFF7A6FFBDE808404D -:1052300000F09AB80038024000000240F859000817 -:1052400008B500F007FAFEF7E7FBFFF79DF8BDE8A9 -:105250000840FEF709BE000070470000104B1A6CB2 -:1052600042F001021A641A6E42F001021A660D4AF7 -:105270001B6E936843F0010393604FF08043532209 -:105280009A624FF0FF32DA6200229A615A63DA6062 -:105290005A6001225A6108211A601C20FDF752BE93 -:1052A00000380240002004E04FF0804208B5116948 -:1052B000D3680B40D9B2C9439B07116107D520239E -:1052C00083F31188FEF7C8FB002383F3118808BD20 -:1052D00008B5FFF7E9FFBDE80840FFF7A5B80000F3 -:1052E0001F4B1A696FEAC2526FEAD2521A611A69E9 -:1052F000C2F308021A614FF0FF301A695A69586107 -:1053000000215A6959615A691A6A62F080521A6218 -:105310001A6A02F080521A621A6A5A6A58625A6A03 -:1053200059625A6A1A6C42F080521A641A6E42F03C -:1053300080521A661A6E0B4A106840F48070106032 -:10534000186F00F44070B0F5007F1EBF4FF480303E -:1053500018671967536823F40073536000F05AB953 -:105360000038024000700040334B4FF080521A6406 -:10537000324A4FF4404111601A6842F001021A604B -:105380001A689107FCD59A6822F003029A602A4BAA -:105390009A6812F00C02FBD1196801F0F90119604A -:1053A0009A601A6842F480321A601A689203FCD537 -:1053B0005A6F42F001025A671F4B5A6F9007FCD593 -:1053C0001F4A5A601A6842F080721A601B4A53687A -:1053D0005904FCD5184B1A689201FCD5194A9A60F9 -:1053E000194B1A68194B9A42194B21D1194A116865 -:1053F000194A91421CD140F205121A60144A1368EE -:1054000003F00F03052BFAD10B4B9A6842F002020E -:105410009A609A6802F00C02082AFAD15A6C42F497 -:1054200080425A645A6E42F480425A665B6E7047FC -:1054300040F20572E1E700BF003802400070004012 -:105440000854400700948838002004E011640020CC -:10545000003C024000ED00E041C20F41084A08B59F -:10546000516913680B4003F00103536123B1054AEE -:1054700013680BB150689847BDE80840FEF7D4BFE9 -:10548000003C0140943F0020084A08B55169136868 -:105490000B4003F00203536123B1054A93680BB13B -:1054A000D0689847BDE80840FEF7BEBF003C014009 -:1054B000943F0020084A08B5516913680B4003F077 -:1054C0000403536123B1054A13690BB1506998472E -:1054D000BDE80840FEF7A8BF003C0140943F002013 -:1054E000084A08B5516913680B4003F0080353617B -:1054F00023B1054A93690BB1D0699847BDE80840CC -:10550000FEF792BF003C0140943F0020084A08B5D6 -:10551000516913680B4003F01003536123B1054A2E -:10552000136A0BB1506A9847BDE80840FEF77CBF8C -:10553000003C0140943F0020174B10B55A691C688D -:10554000144004F478725A61A30604D5134A936A8E -:105550000BB1D06A9847600604D5104A136B0BB1A3 -:10556000506B9847210604D50C4A936B0BB1D06B56 -:105570009847E20504D5094A136C0BB1506C984763 -:10558000A30504D5054A936C0BB1D06C9847BDE8D0 -:105590001040FEF749BF00BF003C0140943F00208F -:1055A0001A4B10B55A691C68144004F47C425A61C5 -:1055B000620504D5164A136D0BB1506D984723054B -:1055C00004D5134A936D0BB1D06D9847E00404D510 -:1055D0000F4A136E0BB1506E9847A10404D50C4AC4 -:1055E000936E0BB1D06E9847620404D5084A136FCE -:1055F0000BB1506F9847230404D5054A936F0BB144 -:10560000D06F9847BDE81040FEF70EBF003C014048 -:10561000943F0020062108B50846FDF793FC0621BB -:105620000720FDF78FFC06210820FDF78BFC0621E3 -:105630000920FDF787FC06210A20FDF783FC0621DF -:105640001720FDF77FFCBDE8084006212820FDF764 -:1056500079BC000008B5FFF743FE00F00DF8FDF738 -:1056600087FCFDF797FEFDF76FFDFFF7F5FDBDE841 -:105670000840FFF769BD00000023054A19460133C1 -:10568000102BC2E9001102F10802F8D1704700BFE7 -:10569000943F002010B501390244904201D100200E -:1056A00005E0037811F8014FA34201D0181B10BD8B -:1056B0000130F2E72DE9F041A3B1C91A177801448E -:1056C000044603F1FF3C8C42204601D9002009E04A -:1056D0000578BD4204F10104F5D10CEB0405D618A0 -:1056E000A54201D1BDE8F08115F8018D16F801ED54 -:1056F000F045F5D0E7E70000034611F8012B03F869 -:10570000012B002AF9D170476F72672E61726475A0 -:1057100070696C6F742E663430355F4D6174656BE3 -:105720004169727370656564000000004E6F20610E -:105730007070207369670A00426164206677206C8C -:10574000656E6774682025750A0042616420626F87 -:105750006172645F69642025752073686F756C647D -:105760002062652025750A00426164206677206406 -:10577000657363726970746F72206C656E677468AC -:105780002025750A004261642061707020435243F5 -:10579000203078253038783A307825303878203005 -:1057A00078253038783A3078253038780A00476FD5 -:1057B0006F64206669726D776172650A0040A2E4C9 -:1057C000F16468910600000053544D3332463F3F68 -:1057D0003F00000053544D33324634307800535468 -:1057E0004D3332463432780053544D3332463434DC -:1057F0003658580000000000C85700083F0000005D -:1058000013040000D45700083F00000019040000F2 -:10581000DE5700083F00000021040000E8570008A0 -:105820003F00000000000000C5300008B130000853 -:10583000ED300008D9300008E5300008D13000080C -:10584000BD300008A9300008F93000080000000051 -:1058500001000000000000006D61696E00000000A2 -:1058600069646C650000000060580008383600204C -:10587000B037002001000000153A000800000000C9 -:105880004172647550696C6F740025424F415244F7 -:10589000252D424C002553455249414C250000001E -:1058A0000200000000000000E13200084D33000853 -:1058B00040004000483C0020583C0020020000000E -:1058C0000000000003000000000000009133000809 -:1058D0000000000010000000683C002000000000F4 -:1058E00001000000000000001C3F00200101020038 -:1058F000053E0008153D0008B13D0008953D000833 -:10590000430000000859000809024300020100C0DA -:105910003209040000010202010005240010010503 -:105920002401000104240202052406000107058267 -:10593000030800FF09040100020A00000007050136 -:105940000240000007058102400000001200000034 -:105950005459000812011001020000400912415779 -:1059600000020102030100000403090425424F4123 -:1059700052442500663430352D4D6174656B4169A4 -:1059800072737065656400303132333435363738C0 -:1059900039414243444546000040000000400000B9 -:1059A0000040000000400000000001000000020074 -:1059B00000000200000002000000020000000200DF -:1059C000000002000000020000000000C9340008CE -:1059D000813700082D380008400040007C3F00203F -:1059E0007C3F0020010000008C3F00208000000070 -:1059F0004001000003000000AA01A81200000000FE -:105A0000AAAAAAAA55011400FFBF000088770000C7 -:105A100070A70A0000000A0100000000AAAAAAAAB2 -:105A200000000001FFFF00000000000099000000DE -:105A30000000A01600000000AAAAAAA600005011AB -:105A4000FFDF0000000000000077080020000000D9 -:105A500000000000AAAAAAAA10000000FFFF000090 -:105A6000000800000000000000000000000000002E -:105A7000AAAAAAAA00000000FFFF00000000000080 -:105A8000000000000000000000000000AAAAAAAA6E -:105A900000000000FFFF0000000000000000000008 -:105AA0000000000000000000AAAAAAAA000000004E -:105AB000FFFF0000000000000000000000000000E8 -:105AC000000000000A0000000000000003000000C9 -:105AD00000000000000000000000000000000000C6 -:105AE00000000000000000000000000000000000B6 -:105AF000000000001CA7FF7F010000000000000064 -:105B0000F60300000000000000000F00000000008D -:105B10006400000000000000FE2A0100D204000022 -:105B2000FF0096000000000800960000000008003A -:105B30000400000068590008000000000000000098 -:105B40000000000000000000000000000000000055 +:10063000A047002003F000FCFEE703F07BFB00DF97 +:10064000FEE70000F8B504F00BF8074604F056F892 +:100650000546B8BB204B9F4234D001339F4234D073 +:100660001E4B27F0FF029A4232D1F8B200F03AFE58 +:100670002E4642F2107400F03BFE08B100242646DC +:1006800001F0F6FB20B1032000F07CF800242646A0 +:1006900035B1134B9F4203D004F028F800242646BE +:1006A000002003F0E7FF0EB100F082F801F02EFA0F +:1006B00000F07CFE01F0B8F8204600F0DFF800F012 +:1006C00077F8F9E72E460024D5E704460126D2E75D +:1006D000064641F28834CEE7010007B0000008B0BA +:1006E000263A09B008B501F071F8A0F1200358428C +:1006F000584108BD07B541F21203022101A8ADF827 +:10070000043001F081F803B05DF804FB38B5202314 +:1007100083F311881748C3680BB103F013FC164A22 +:10072000144800234FF47A7103F0D0FB002383F3C5 +:100730001188124C236813B12368013B236063685E +:1007400013B16368013B63600D4D2B7833B9636867 +:100750007BB9022001F054F9322363602B78032B1C +:1007600007D163682BB9022001F04AF94FF47A737C +:10077000636038BD582300200D0700087424002052 +:100780006C230020084B187003280CD8DFE800F019 +:1007900008050208022001F029B9022001F01CB965 +:1007A000024B00225A6070476C2300207424002002 +:1007B00010B501F05DFB30B1294B03221A70294BB3 +:1007C00000225A6010BD284B284A1C461968013186 +:1007D000F8D004339342F9D16268254B9A42F1D99B +:1007E000244B9B6803F1006303F580339A42E9D2FE +:1007F00003F050FF03F062FF002001F02FF8022009 +:10080000FFF7C0FF1C4B1A6C00221A64196E1A669F +:10081000196E596C5A64596E5A665A6E5A6942F08A +:1008200080025A615A6922F080025A615A691A6933 +:1008300042F000521A611A6922F000521A611B69D3 +:1008400072B64FF0E0232021C3F8084DD4E90032FE +:1008500081F311889D4683F308881047B2E700BFF3 +:100860006C230020742400200000010820000108EF +:10087000FFFF000800230020003802402DE9F04F60 +:1008800093B0AC4B00902022FF210AA89D6801F094 +:10089000E7F8A94A1378A3B9A8480121C3601170E9 +:1008A000202383F31188C3680BB103F04BFBA44AE8 +:1008B000A24800234FF47A7103F008FB002383F36E +:1008C0001188009B13B19F4B009A1A609E4A009CAE +:1008D0001378032B1EBF002313709A4A4FF0000AAF +:1008E00018BF5360D3465646D146012001F07EF82A +:1008F00024B1944B1B68002B00F01582002000F0FF +:1009000065FF0390039B002B01DA00F003FE039BBD +:10091000002BEDDB012001F05FF8039B213B162B40 +:10092000E3D801A252F823F085090008AD090008B8 +:10093000410A0008EB080008EB080008EB08000873 +:10094000CB0A00089B0C0008B50B0008170C000828 +:100950003F0C0008650C0008EB080008770C000845 +:10096000EB080008E90C0008250A0008EB0800085D +:100970002D0D000891090008250A0008EB08000861 +:10098000170C00080220FFF7ADFE002840F0F581AB +:10099000009B0221BAF1000F08BF1C4605A841F2D6 +:1009A0001233ADF8143000F02FFF9EE74FF47A7049 +:1009B00000F00CFF071EEBDB0220FFF793FE002880 +:1009C000E6D0013F052F00F2DA81DFE807F0030AE5 +:1009D0000D10133605230593042105A800F014FF1C +:1009E00017E054480421F9E758480421F6E758482D +:1009F0000421F3E74FF01C08404600F031FF08F1F6 +:100A000004080590042105A800F0FEFEB8F12C0FA3 +:100A1000F2D1012000FA07F747EA0B0B5FFA8BFBD4 +:100A20004FF0000901F068F826B10BF00B030B2B17 +:100A300008BF0024FFF75EFE57E746480421CDE7D4 +:100A4000002EA5D00BF00B030B2BA1D10220FFF73A +:100A500049FE074600289BD0012000F0FFFE02203F +:100A6000FFF790FE00265FFA86F8404600F006FF8A +:100A7000044690B10021404600F010FF01360028E6 +:100A8000F1D1BA46044641F21213022105A8ADF88D +:100A900014303E4600F0B8FE27E70120FFF772FE53 +:100AA0002546244B9B68AB4207D9284600F0D8FE68 +:100AB000013040F067810435F3E7234B00251D70BA +:100AC000204BBA465D603E46ACE7002E3FF460AF77 +:100AD0000BF00B030B2B7FF45BAF0220FFF752FEF2 +:100AE000322000F073FEB0F10008FFF651AF18F0AD +:100AF00003077FF44DAF0F4A926808EB050393425A +:100B00003FF646AFB8F5807F3FF742AF124B0193F7 +:100B1000B84523DD4FF47A7000F058FE0390039A35 +:100B2000002AFFF635AF019B039A03F8012B01372A +:100B3000EDE700BF00230020702400205823002090 +:100B40000D070008742400206C23002004230020DB +:100B5000082300200C23002070230020C820FFF76A +:100B6000C1FD074600283FF413AF1F2D11D8C5F172 +:100B7000200242450AAB25F0030028BF42468349C4 +:100B80000192184400F046FF019A8048FF2100F0CE +:100B900067FF4FEAA8037D490193C8F387022846FF +:100BA00000F066FF064600283FF46DAF019B05EBA1 +:100BB000830537E70220FFF795FD00283FF4E8AEF4 +:100BC00000F098FE00283FF4E3AE0027B846704BD3 +:100BD0009B68BB4218D91F2F11D80A9B01330ED036 +:100BE00027F0030312AA134453F8203C0593404610 +:100BF000042205A901F0F4F804378046E7E73846F7 +:100C000000F02EFE0590F2E7CDF81480042105A82F +:100C100000F0FAFD06E70023642104A8049300F025 +:100C2000E9FD00287FF4B4AE0220FFF75BFD002849 +:100C30003FF4AEAE049800F045FE0590E6E70023D1 +:100C4000642104A8049300F0D5FD00287FF4A0AE31 +:100C50000220FFF747FD00283FF49AAE049800F009 +:100C600041FEEAE70220FFF73DFD00283FF490AE89 +:100C700000F050FEE1E70220FFF734FD00283FF4CA +:100C800087AE05A9142000F04BFE0421074604900E +:100C900004A800F0B9FD3946B9E7322000F096FD0E +:100CA000071EFFF675AEBB077FF472AE384A926836 +:100CB00007EB090393423FF66BAE0220FFF712FDEC +:100CC00000283FF465AE27F003074F44B9453FF4D1 +:100CD000A9AE484600F0C4FD0421059005A800F027 +:100CE00093FD09F10409F1E74FF47A70FFF7FAFC7C +:100CF00000283FF44DAE00F0FDFD002844D00A9BD3 +:100D000001330BD008220AA9002000F0B1FE002810 +:100D10003AD02022FF210AA800F0A2FEFFF7EAFC49 +:100D20001C4803F08FF813B0BDE8F08F002E3FF49D +:100D30002FAE0BF00B030B2B7FF42AAE00236421A4 +:100D400005A8059300F056FD074600287FF420AE65 +:100D50000220FFF7C7FC804600283FF419AEFFF7DA +:100D6000C9FC41F2883003F06DF8059800F0F6FEFA +:100D7000464600F0C1FE3C46B7E5064652E64FF057 +:100D8000000905E6BA467EE637467CE67023002079 +:100D900000230020A0860100094A136849F2690077 +:100DA00099B21B0C00FB01331360064B186844F228 +:100DB000506182B2000C01FB0200186080B27047E3 +:100DC000202300201C23002010B5002110220446FF +:100DD00000F046FE034B03CB206061601868A06002 +:100DE00010BD00BF107AFF1F2DE9F041ADF5507D19 +:100DF0000DF13C086EAC40F2751207460D4610A886 +:100E00000021C8F8001000F02BFE4FF4C47200213E +:100E1000204600F025FE00F0E5FE254B4FF47A72E7 +:100E2000B0FBF2F0186093E80700012384E80700A4 +:100E30000DF5ED702382FFF7C7FF4FF203631D49E5 +:100E4000238406A804F00AFE202384F832310DF230 +:100E5000EB2606AB0DF1380C1A4603CA624530602A +:100E60007160134606F10806F6D14146012220467C +:100E700000F0BCFE00230393AB7E029305F119033F +:100E8000019380B20123CDE904800093E97E06A39B +:100E9000D3E90023384601F043FB0DF5507DBDE852 +:100EA000F08100BFAFF300809E6AC421818A46EEC4 +:100EB0007C2400206C5A00082DE9F043224DBBB081 +:100EC00000F090FEAB6840F2ED22C31A934232D993 +:100ED00006AFA8602B4628220021384601F008FD05 +:100EE00005F10E0000F0B4FD002604465FFA80F91B +:100EF00005F10E08F3B2F100994501F1280107D977 +:100F000008EB06030822384601F0F2FC0136F1E74F +:100F100008230122CDE9023205340C4B0193A4B21F +:100F200030230093CDE9047405A3D3E90023297B82 +:100F3000074801F0F5FA3BB0BDE8F083AFF300805D +:100F400078F6339F93CACD8DC0340020CD34002075 +:100F500094340020F0B58B8A013B9BB2C92BC9B0F9 +:100F600006460C4647D8274D2F7B27BB05F10C03BF +:100F7000009308223B463946204601F07DFB7B1C4E +:100F8000FAB2D9001F46A38A013B9A4205DA0E3213 +:100F90002A44009200230822EEE700230022C5E93C +:100FA00000230023AB6085F8D730C5F8D8302B7B01 +:100FB0000BB9E37E2B738122002106AD27A800F038 +:100FC0004FFD0122294627A800F0DEFE00230393EF +:100FD000A37E029304F1190380B201932823CDE983 +:100FE0000450E17E0093304604A3D3E9002301F0CE +:100FF00097FAFFF761FF49B0F0BD00BF264172725A +:10100000DF25D7B7C034002070B50D4614461E4604 +:1010100001F01CFA50B9022E10D1012C0ED112A3EE +:10102000D3E90023C5E90023012007E0282C10D0D4 +:1010300005D8012C09D0052C0FD0002070BD302C14 +:10104000FBD10BA3D3E90023ECE70BA3D3E90023E7 +:10105000E8E70BA3D3E90023E4E70BA3D3E90023DC +:10106000E0E700BFAFF30080401DA12026812A0BDE +:1010700078F6339F93CACD8D9E6AC421818A46EE4D +:1010800026417272DF25D7B7F017304A39059E56D0 +:101090002DE9F04F8DB002AF80460D4601F0D6F934 +:1010A000044600285CD12B7E022B1BD1EB8A012B3E +:1010B00018D100F097FD0646FFF76EFE03464FF489 +:1010C000C870DFF81C92B3FBF0F206F5167602FB4F +:1010D000103316FA83F3C9F80030EB7E33B97B4B3B +:1010E00000221A702C37BD46BDE8F08FAB8AE6B2FD +:1010F000013BB34204F101040CD907F108031E447B +:10110000E10000960023082201F0F801284601F0D2 +:10111000B3FAEBE707F11800FFF756FE324607F186 +:10112000180107F1080004F067FC0028D7D10F2E42 +:1011300008D8664B1E70D9F80030A3F51673C9F8AD +:101140000030CFE7FB1DF8710146009307220346EC +:10115000284601F091FAF979404601F06FF9C1E7AC +:10116000EB8A282B26D010D8012B1ED0052BB9D105 +:10117000BFF34F8F5649574BCA6802F4E0621343DE +:10118000CB60BFF34F8F00BFFDE7302BAAD16B7E42 +:10119000514C0133627BDBB29342E94603D1EA7ED4 +:1011A000237B9A420BD0CD469CE729464046FFF769 +:1011B0001BFE97E729464046FFF7CCFE92E74FF02B +:1011C000000807F11803A7F8188010220093414681 +:1011D0000123284601F050FAAE8A023EB6B2F31C53 +:1011E0009B109B000733DB08A9EBC3039D460DF161 +:1011F000080A1FFA88F34FEAC8019E4201F1100164 +:101200000AD90AEB0803009308220023284601F0BC +:1012100033FA08F10108ECE794F8D70000F02EFB50 +:10122000D4F8D810054619B994F8D70000F036FB69 +:10123000D4F8D83033449D4205D294F8D700002129 +:10124000013000F02BFB4FEA960B4FF000081FFA1D +:1012500088F18B45D4E9003209D90AEB880103EB08 +:101260008800012200F004FC08F10108EFE7F31800 +:1012700042F10002C4E90032D4F8D83094F8D70023 +:1012800006EB0308C4F8D88000F0F8FA804509D3CB +:1012900094F8D730D4F8D8000133401B84F8D73005 +:1012A000C4F8D800FF2E0D4D09D80023237300F099 +:1012B00021FB00F0DDFD288108B9FFF779FA2368EA +:1012C0009B0A01332B810023A3606CE78D3400203F +:1012D00000ED00E00400FA05C03400207C2400206A +:1012E00090340020014B1870704700BF8824002004 +:1012F00030B54FF00054244B22689A4285B007D095 +:1013000003F006FA0446A8B90024204605B030BD13 +:101310001E4B627D1A701E48237D03731D49C9222E +:101320000E3000F077FB2046E022002100F098FB11 +:101330000124EAE7184A194D136C43F00073136453 +:10134000AA6D174B9A42DFD12B6E013B7E2BDBD867 +:10135000144A07CA01AB83E807001846032100F0CE +:1013600055FD6B6D83424FF00003CDD12A6D8A424B +:1013700001BFAB65054B2A6E1A7003BF0A4BEA6DBD +:101380001A601C46C1E700BF9AAD44C588240020FE +:10139000C0340020160000200038024000660040E3 +:1013A0005041A0B058660040182300202DE9FF47A7 +:1013B0004C4C00F05DFD02236371002302934A4B05 +:1013C0002081D3F800C0BCF57A7F12D3474B484F39 +:1013D000B7FBFCF69C458CBF0A231123581EB6FBB5 +:1013E000F3F503FB1562C1B2002A3ED00228034682 +:1013F000F4D89DF80B303F493F485A1E9DF80A30FB +:10140000013B1B0443EA0253BDF80820013A134391 +:101410004B6001F053FF00230193384B3849009390 +:101420003848394B4FF4805200F0E2FF374B1978BF +:1014300011B1344801F002F800F0D4FB0546FFF783 +:10144000ABFC4FF4C873B0FBF3F202FB130305F5DA +:10145000167010FA83F02E4B186003F04FF908B1A4 +:101460000F23238104B0BDE8F0876B1EB3F5806FB6 +:10147000BFD2C1EBC10E0EF103034FEAE309C3F380 +:10148000C703A1EB030809F1010A4FF47A705FFA70 +:1014900088F609FB00005AFA88F8B0FBF8F0B0F5BE +:1014A000617F08D90EF1FF33C3F3C703C91ACEB267 +:1014B000591E0F2914D8721E072A8CBF0022012240 +:1014C000991901FB0551B7FBF1F7BC4591D1002AF1 +:1014D0008FD0ADF808508DF80A308DF80B6088E792 +:1014E0001346EDE77C240020182300203F420F0024 +:1014F00080DE800210230020D8350020091000086B +:101500008C240020943400209110000888240020AE +:10151000903400202DE9F04F91A7D7E900670FF232 +:101520004829D9E90089874D93B0DFF844B2864C49 +:10153000284601F059F80DF1300A079070B31022D7 +:101540000021504600F08CFA079B197B4FF00002F7 +:1015500061F303028DF83020586899680EAA03C21F +:101560001B680D9A63F31C029DF830300D9243F016 +:1015700020038DF83030002352461946584601F0BA +:10158000ADFE079028B9284601F032F8079B23707A +:10159000CEE72378072B3CD8013323701822002193 +:1015A000504600F05DFADFF8C8B1684C00231946D8 +:1015B0005246584601F0BAFE014670BB102208A8F8 +:1015C00000F04EFA636983F48043636100F00CFB22 +:1015D0000B4612A9024611E903000DF1240C8CE818 +:1015E00003009DF83410C1F3030089064CBF0E9927 +:1015F000BDF838C08DF82C0046BFC1F31C0C4CF070 +:101600000041CCF30A010891284608A901F0B8F975 +:10161000CCE7284600F0ECFFC0E7284600F016FFB4 +:101620000446002848D1DFF84CB100F0DBFADBF8C3 +:101630000030984240D300F0D5FA0790FFF7ACFB9A +:10164000079A8DF8204003464FF4C87002F51672D1 +:10165000B3FBF0F101FB103312FA83F3CBF8003047 +:10166000DFF814B19BF8001011B901238DF8203078 +:1016700050460791FFF7A8FB0799C1F11004E4B2A7 +:10168000062C28BF0624224651440DF1210000F00B +:10169000C1F908AB03931823029301342C4B019337 +:1016A000E4B20123009304943B463246284600F0FE +:1016B000CFFE00238BF8003000F094FA254A264C28 +:1016C0001368C31AB3F57A7F30D3106000F08CFA38 +:1016D00002460B46284600F095FF284600F0B6FE6D +:1016E00020B3237BDFF894B0002B14BF0323022325 +:1016F0008BF8053000F076FA4FF47A730122B0FBD4 +:10170000F3F05146CBF80000584600F015FB1823C3 +:101710000293124B019380B240F25513CDE903A01E +:10172000009342464B46284600F092FE237B2BB1A5 +:10173000FFF7C2FB237B002B7FF4F7AE13B0BDE8AD +:10174000F08F00BF94340020A53500200000024037 +:101750008C340020A0350020C0340020A4350020A7 +:10176000401DA12026812A0BF1C6A7C1D068080F11 +:10177000D8350020903400208D3400207C240020B7 +:1017800070B50F4B1B780133DBB2012B0C4611D81F +:101790000C4D29684FF47A730E6AA2FB033201469E +:1017A00022462846B047844204D1074B00221A70D3 +:1017B000012070BD4FF4FA7002F044FB0020F8E7FE +:1017C00024230020C0370020D435002007B5002393 +:1017D000024601210DF107008DF80730FFF7D0FF19 +:1017E00020B19DF8070003B05DF804FB4FF0FF3017 +:1017F000F9E700000A4608B50421FFF7C1FF80F0B1 +:101800000100C0B2404208BD30B4054C2368DD6918 +:10181000044B0A46AC460146204630BC604700BF38 +:10182000C0370020A086010070B502F0BBFD094E54 +:10183000094D3080002428683388834208D902F09B +:10184000ABFD2B6804440133B4F5803F2B60F2D329 +:1018500070BD00BFD6350020A835002002F064BE60 +:1018600000F1006000F580300068704700F1006012 +:10187000920000F5803002F0E3BD0000054B1A68CD +:10188000054B1B889B1A834202D9104402F084BD89 +:1018900000207047A8350020D635002038B5084D07 +:1018A000044629B128682044BDE8384002F094BDC0 +:1018B0002868204402F078FD0028F3D038BD00BF2E +:1018C000A835002010F003030AD1B0F5047F05D23B +:1018D00000F10050A0F51040D0F8003818467047CD +:1018E0000023FBE700F10050A0F51040D0F8100AEB +:1018F00070470000064991F8243033B10023086A8C +:1019000081F824300822FFF7B1BF0120704700BFE3 +:10191000AC350020014B1868704700BF002004E080 +:1019200070B52A4B1B68C3F30B0204461B0C62B153 +:1019300040F21340824230D040F2194082422ED011 +:1019400040F2214082422CD10322214D0C2000FB89 +:101950000252556842F20102934224D0B3F5805FEF +:1019600023D041F20102934221D041F2030293427B +:101970001FD041F20702934214BF3F233123013CA1 +:101980000C44013D0A46A24215D215F9016F501CC4 +:101990009EB100F8016C0246F5E70122D5E702226C +:1019A000D3E70C4DD6E73323E9E74123E7E75A2392 +:1019B000E5E75923E3E7104605E02C25844215703E +:1019C00001D9901C5370401A70BD00BF002004E084 +:1019D000BC5A0008905A0008022802BF024B4FF080 +:1019E00080429A61704700BF00000240022802BF97 +:1019F000024B4FF480429A61704700BF00000240E2 +:101A0000022801BF024A536983F48043536170473F +:101A10000000024010B50023934203D0CC5CC454B4 +:101A20000133F9E710BD000010B5013810F9013F8E +:101A30003BB191F900409C4203D11AB10131013A06 +:101A4000F4E71AB191F90020981A10BD1046FCE78E +:101A500003460246D01A12F9011B0029FAD1704739 +:101A600002440346934202D003F8011BFAE7704791 +:101A70002DE9F8431F4D144695F824200746884663 +:101A800052BBDFF870909CB395F824302BB920221C +:101A9000FF2148462F62FFF7E3FF95F82400C0F1CD +:101AA0000802A24228BF2246D6B24146920005EB68 +:101AB0008000FFF7AFFF95F82430A41B1E44F6B258 +:101AC000082E17449044E4B285F82460DBD1FFF778 +:101AD00011FF0028D7D108E02B6A03EB8203834271 +:101AE000CFD0FFF707FF0028CBD10020BDE8F88357 +:101AF0000120FBE7AC350020024B1A78024B1A702C +:101B0000704700BFD43500202423002010B50F4CAF +:101B10000F4801F0ADFC21460D4801F0D5FC2468CA +:101B20000C48626DD2F8043843F00203C2F804385E +:101B300002F088F90849204601F0CCFD626DD2F828 +:101B4000043823F00203C2F8043810BDC45B000857 +:101B5000C037002040420F00CC5B000870470000F7 +:101B600000B59BB0EFF3098168226846FFF752FF8A +:101B7000EFF30583044B9A6BDA6A9A6A9A6A9A6A57 +:101B80009A6A9A6A9B6AFEE700ED00E000B59BB096 +:101B9000EFF3098168226846FFF73CFFEFF3058306 +:101BA000044B9A6B9A6A9A6A9A6A9A6A9A6A9B6AC8 +:101BB000FEE700BF00ED00E000B59BB0EFF3098148 +:101BC00068226846FFF726FFEFF30583034B5A6B45 +:101BD0009A6A9A6A9A6A9A6A9B6AFEE700ED00E03E +:101BE000FEE7000002F0DABC02F0B2BC2DE9F047DB +:101BF0000D46044600219046284640F27912FFF730 +:101C00002FFF234620220021284600F071FE231DCD +:101C100002222021284600F06BFE631D03222221B0 +:101C2000284600F065FEA31D03222521284600F06A +:101C30005FFE04F1080310222821284600F058FE18 +:101C400004F1100308223821284600F051FE04F167 +:101C5000110308224021284600F04AFE04F1120335 +:101C600008224821284600F043FE04F114032022F4 +:101C70005021284600F03CFE04F118034022702158 +:101C8000284600F035FE04F120030822B021284642 +:101C900000F02EFE04F121030822B821284600F0AE +:101CA00027FE04F12207C0263B463146082228467B +:101CB000083600F01DFEB6F5A07F07F10107F3D14D +:101CC00004F1320308223146284600F011FE0027B5 +:101CD00004F1330A94F832304FEAC7099F4209F5FC +:101CE000A47615D3B8F1000F08D1314604F59973E5 +:101CF0000722284600F0FCFD09F24F16274694F80B +:101D000032213B1B93420CD3F01DC008BDE8F08785 +:101D10000AEB070308223146284600F0E9FD0137A7 +:101D2000D8E707F2331331460822284600F0E0FDD9 +:101D300008360137E3E7000013B5044608460021E2 +:101D400001602346C0F803102022019000F0D0FD6E +:101D50000198231D0222202100F0CAFD0198631D75 +:101D60000322222100F0C4FD0198A31D0322252196 +:101D700000F0BEFD019804F108031022282100F0B4 +:101D8000B7FD072002B010BDF8B50E460546144653 +:101D9000002181223046FFF763FE2B4608220021F6 +:101DA000304600F0A5FD7CB96B1C072208213046A7 +:101DB00000F09EFD0F2401236A785F1C013B9342D3 +:101DC00004D3E01DC008F8BD0824F4E7EB19214650 +:101DD0000822304600F08CFD08343B46ECE700005A +:101DE00030B5094D0A4491420DD011F8013B5840DD +:101DF000082340F30004013B2C4013F0FF0384EA66 +:101E00005000F6D1EFE730BD2083B8EDF7B54FF0C5 +:101E1000FF33DFF854C0DFF854E000EB81011A46CD +:101E200088421CD050F8044B019401AF042417F8E9 +:101E3000015B82EA05620825DB18164605F1FF35CD +:101E40005241002EBCBF83EA0C0382EA0E0215F059 +:101E5000FF05F1D1013C14F0FF04E8D1E0E7D843DD +:101E6000D14303B0F0BD00BF9336EAA9EBE1F042E5 +:101E700073B5384A106851686B4603C36A463649E1 +:101E80003648082303F0C8FD044670B9344A106888 +:101E900051686B4603C36A4632493048082303F051 +:101EA000BBFD044630BB0A2022E00369B3F5702F66 +:101EB000ECD8418B40F2F6329142E7D12A4A0244F3 +:101EC00002F110018B42E1D3103B244900209D1AFE +:101ED000FFF786FF2A46064604F118010020FFF7A7 +:101EE0007FFFA3689E42D1D1E3689842CED1002003 +:101EF00002B070BD0369B3F5702F22D8B0F8661038 +:101F000040F2F63291421ED1174A024402F15C01BE +:101F10008B421AD35C3B114900209D1AFFF760FFEA +:101F20002A46064604F164010020FFF759FFA26823 +:101F3000964203460BD1E068834214BF0D20002077 +:101F4000D6E70B20D4E70C20D2E71020D0E70D20F5 +:101F5000CEE700BFEC5A0008DCFF0E0000000108CD +:101F6000F55A000890FF0E000800FFF72DE9F04138 +:101F7000C56915B9C161BDE8F0814B6823F06047C0 +:101F8000C3F38A464FEAD37EC3F3807816EA23066A +:101F900038BF3E46AC462B465A68BEEBD27F22F095 +:101FA00060440AD0002A18DAA40CB44217D19D422A +:101FB0000FD10D60DEE71346EEE7A74207D102F02E +:101FC0008044C2F3807242450BD054B1EFE708D28F +:101FD000EDE7CCF800100B60CDE7B44201D0B4427D +:101FE000E5D81A689C46002AE5D11960C3E70000CD +:101FF0002DE9F047089D01F007044FEAD508224477 +:1020000005F0070500EBD1004FF47F49944201D160 +:10201000BDE8F08704F0070705F0070A57453E467C +:1020200038BF5646C6F10806111B8E4228BF0E4621 +:10203000E10808EBD50E415C13F80EC0B94029FA4F +:1020400006F721FA0AF1FFB28CEA010147FA0AF712 +:1020500039408CEA010C03F80EC034443544D5E70E +:1020600080EA0120082341F2210201B24000002948 +:1020700080B203F1FF33B8BF504013F0FF03F4D137 +:102080007047000038B50C468D18A54200D138BD08 +:1020900014F8011BFFF7E4FFF7E7000002684AB1FC +:1020A00013680360C388018901339BB29942C380DE +:1020B00038BF03811046704770B588B020220446AF +:1020C0000D4668460021FFF7CBFC20460495FFF73C +:1020D000E5FF024658B16B46054608AE1C4603CCE8 +:1020E000B44228606960234605F10805F6D1104620 +:1020F00008B070BD082817D909280CD00A280CD0C0 +:102100000B280CD00C280CD00D280CD00E2814BF96 +:102110004020302070470C2070471020704714205A +:10212000704718207047202070470000082817D9F2 +:102130000C280CD910280CD914280CD918280CD923 +:1021400020280CD930288CBF0F200E207047092082 +:1021500070470A2070470B2070470C2070470D20F5 +:102160007047000010B54B6823B9CA8A63F30902AF +:10217000CA8210BDC4681A681C60C360438A013BF0 +:1021800043824A60EFE700002DE9F84F1D46CB8AF5 +:102190000F46C3F309010529814692460B4630D00C +:1021A0000020AAB207F11A049EB2042E1FFA80F88A +:1021B0000FD8904503F1010306D3FB8A0A4462F36A +:1021C0000903FB8201201AE01AF80060E65401308E +:1021D000EAE79045F1D2A1F1050B1C237C68BBFB1B +:1021E000F3F203FB12BB1FFA8BF6002C45D14846D5 +:1021F000FFF754FF044638B978606FF00200BDE87D +:10220000F88F4FF00008E6E7002606607860ADB270 +:102210004FF0000B454510D90AEB0803221D13F8B7 +:10222000011B9155B1B208F101081B291FFA88F86A +:102230002BD0454506F10106F1D8FB8AC3F309020C +:10224000154465F30903BCE7013292B21C462368CA +:10225000002BF9D16B1F0B441C21B3FBF1F30133AD +:102260009BB29A42D3D2BBF1000FD0D14846FFF7C0 +:1022700015FF20B9C4F800B0BFE70122E7E7C0F8B6 +:1022800000B05E4620600446C1E74545D5D94846C2 +:10229000FFF704FF08B92060AFE7C0F800B00026E0 +:1022A00020600446B6E700002DE9F04F2DED028BCB +:1022B00083B0CDE90013BDF83C5007469146002A93 +:1022C00000F092802DB10E9B002B00F08D80072D29 +:1022D00032D807F10C00FFF7E1FE044638B96FF081 +:1022E0000204204603B0BDEC028BBDE8F08F14223F +:1022F0000021FFF7B5FB0E992A4604F10800FFF70D +:1023000089FB681CC0B2FFF711FFFFF7F3FE2074D2 +:1023100099F80030013814FA80F003F01F0363F0DD +:102320003F030372009B43F0004161603846214641 +:10233000FFF71CFE0124D4E700F10C034FF0000866 +:1023400008EE103A4FF0800A4646444618EE100A4E +:10235000FFF7A4FE83460028C1D014220021FFF716 +:102360007FFBC6BB019BABF8083002200E9B00F13F +:10237000080299195BFA82F20130C0B2082801D034 +:10238000AE422AD3FFF7D2FEFFF7B4FE99F8002041 +:10239000009B411E02F01F0242EA4812AE4208BFF3 +:1023A0004FF0400A5BFA81F14AEA020A43F0004228 +:1023B00081F808A08BF81000CBF804205946384665 +:1023C000FFF7D4FD0134AE4224B288F001084FF08B +:1023D000000ABBD185E70020C8E711F801CB02F85D +:1023E00001CB0136B6B2C7E76FF0010479E7000010 +:1023F000F8B515460E462822002104461F46FFF771 +:102400002FFB069B6360B5F5001F079BA76034BFD9 +:102410006A094FF6FF72236204F10C0097B20023A1 +:102420009A4205D80023036027826382A382F8BD05 +:102430000660013330462036F2E7000003781BB90E +:102440004BB2002BC8BF0170704700000078704786 +:102450002DE9F74FDDF83C90BDF830500D9E9DF80A +:102460003840BDF84070804692469B46B9F1000F57 +:1024700001D1002F51D11F2C4FD898F80000B0B9CE +:10248000072F47D835F0030347D13A4649464FF660 +:10249000FF70FFF7F7FD20F001002D02400445EA30 +:1024A0000464400C44EA40244FF6FF7321E040EA04 +:1024B0000520072F40EA0464F6D900254FF6FF7384 +:1024C000C5F12000A5F120022AFA05F10BFA00F06F +:1024D00001432BFA02F211431846C9B2FFF7C0FDBF +:1024E0000835402D0346EBD13A464946FFF7CAFD71 +:1024F0000346CDE90097324621464046FFF7D4FE19 +:1025000033780133DBB21F2B88BF0023337003B055 +:10251000BDE8F08F6FF00300F9E76FF00100F6E718 +:102520002DE9F04F85B09246DDF848800F9D9DF86B +:1025300040209DF84490BDF84C7006469B46B8F18B +:10254000000F01D1002F48D11F2A46D83378002B25 +:1025500046D00C0244EA02649DF8381044EAC934BB +:1025600044EA01441C43072F44F0800432D900237D +:102570004FF6FF72C3F1200CA3F120002AFA03F1F9 +:102580000BFA0CFC41EA0C012BFA00F00143C9B232 +:1025900010460393FFF764FD039B0833402B02466C +:1025A000E8D13A464146FFF76DFD0346CDE9008785 +:1025B0002A4621463046FFF777FEB9F1010F06D1D2 +:1025C0002B780133DBB21F2B88BF00232B7005B0A3 +:1025D000BDE8F08F4FF6FF73E8E76FF00100F6E714 +:1025E0006FF00300F3E70000C06900B104307047EA +:1025F000C3691A68C261C2681A60C360438A013B3A +:10260000438270472DE9F041D0F81880194E1446E6 +:102610001D464146002709B9BDE8F081D1E90223F2 +:10262000A21A65EB0303964277EB03031ED283697C +:102630008B420DD1FFF796FD83691B688361C368E8 +:102640000B60438AC1608169013B43828846E2E7AF +:10265000FFF788FD0B68C8F80030C3680B60438A39 +:10266000C160013B4382D8F80010D4E7884609686E +:10267000D1E700BF80841E002DE9F04F8BB00D46DE +:10268000DDF8509014469B468046002800F01981E2 +:10269000B9F1000F00F01581531E3F2B00F211819C +:1026A000012A03D1BBF1000F40F00B810023CDE9DB +:1026B0000833B8F81430B5EBC30F4FEAC30703D3A0 +:1026C00000200BB0BDE8F08F2B199F42D8F80C30DA +:1026D0003ABF7F1BFFB227461BB9D8F81030002B3A +:1026E0007AD0272D4ED8C5F12806B7424FF0000307 +:1026F0002CBFF6B23E4600932946D8F8080008AB36 +:102700003246FFF775FCA7EB060A35445FFA8AFAF2 +:10271000B8F8143003F10053053BDB000493D8F8FC +:102720000C3003932821039B13B1BAF1000F2CD175 +:10273000D8F8100040B1BAF1000F05D0009608ABF0 +:102740005246691AFFF754FC38B2002FB8D066071A +:102750000AD00AAB03EBD401624211F8083C02F044 +:102760000702134101F8083C082C3CD9102C40F218 +:10277000B580202C40F2B780BBF1000F00F09C80A8 +:10278000082334E0BA460026C2E7049BE02B28BFAA +:10279000E02306930B44AB42059314D95A1B0398CC +:1027A0000096924534BF5246D2B2691A08AB043043 +:1027B0000792FFF71DFC079A1644AAEB020A15447C +:1027C000F6B25FFA8AFA049B069A05999B1A04935B +:1027D000039B1B680393A6E70093D8F8080008AB97 +:1027E0003A462946AEE7BBF1000F13D00123B4EB04 +:1027F000C30F6CD0082C12D89DF82030621E23FA2B +:1028000002F2D50706D54FF0FF3202FA04F4234353 +:102810008DF820309DF8203089F8003051E7102CD9 +:1028200012D8BDF82030621E23FA02F2D10706D575 +:102830004FF0FF3202FA04F42343ADF82030BDF824 +:102840002030A9F800303CE7202C0FD80899631EEF +:1028500021FA03F3DA0705D54FF0FF3202FA04F448 +:102860000C430894089BC9F800302AE7402C2BD071 +:10287000DDE90865611EC4F12102A4F1210326FAF5 +:1028800001F105FA02F225FA03F311431943CB07CC +:1028900012D50122A4F12003C4F1200102FA03F3AE +:1028A00022FA01F1A240524243EA010363EB4303DF +:1028B00032432B43CDE90823DDE90823C9E900238E +:1028C000FFE66FF00100FCE66FF00800F9E6082C67 +:1028D000A0D9102CB3D9202CEED8C3E7BBF1000F40 +:1028E000ADD0022383E7BBF1000FBBD004237EE70A +:1028F00030B5012A144638BF0124402C85B028BFCA +:1029000040240025012ACDE9025518D81B788DF8FE +:10291000083063070AD004AB03EBD405624215F814 +:10292000083C02F00702934005F8083C009103467A +:102930002246002102A8FFF75BFB05B030BD082A44 +:10294000E4D9102A03D81B88ADF80830E1E7202A23 +:102950008DBFD3E900231B680293CDE90223D8E79A +:1029600010B5CB681BB98B600B618B8210BDC4683E +:102970001A681C60C360438A013B4382CA60F0E767 +:102980002DE9F04F95B0CDE904230B6804460D46C0 +:102990001806C3F3C01147BFC3F3C03BC3F30626F9 +:1029A0004FF0020B0E46002B80F2018213F0C0495B +:1029B00040F0FD812A7B002A00F0F981BBF1020F73 +:1029C00003D02078B04240F0F581C3F30460089052 +:1029D00003F07F00069069B3C3F3074A2A44069BBD +:1029E00092F80380760646EA0B4646EA83460022C2 +:1029F0000023CDE90A235FEAD81346EA0A060393C7 +:102A00006CD0069B009367685B4652460AA9204635 +:102A1000B847002800F0D181A76997B9314604F181 +:102A20000C00FFF749FB0746D8B96FF0020015B05C +:102A3000BDE8F08FC3F30F2A590608BF0AF0030A56 +:102A4000CCE73B699E420DD03F68002FF9D131465B +:102A500004F10C00FFF730FB07460028E5D0A3691E +:102A60003B60A761FE7D08F01F03C6F38406F01AE1 +:102A70001FFA80FC0028B8BF0CF120000793A3EBDD +:102A800006031FFA83FCD7E90221B8BF00B2002B6E +:102A90000993BEBF0CF120031BB2099352EA010354 +:102AA00033D0049EDFF8D0C2B21A059E66EB010156 +:102AB0000026944576EB010327D395F80DE097F8AF +:102AC0001AC0E64514D1039B002B76D001281CDCEC +:102AD000A848904276EB010314D336E0A76917B9F2 +:102AE0006FF00C00A3E73B699E42BBD03F68F6E75E +:102AF000A048904276EB010301D3002097E7039BA7 +:102B0000002BFAD0099B0F2B18DCFA7D4FEA8803C3 +:102B100002F0030203F07C031343FB7539462046A1 +:102B2000FFF720FB6B7BBB76039B3BB9FB7DC3F3BD +:102B30008402013262F38603FB75D1E76A7BBB7EB8 +:102B40009A42DAD1039B002B37D04FEA9813022B1D +:102B500033D0049BBB60059BFB60142200210FA8AF +:102B6000FEF77EFF049B0C93059B0D932B1D0E938C +:102B70002B7BADF846A0013BDBB2ADF84430079BA0 +:102B80008DF84930089B8DF84A30069B8DF84B3004 +:102B900094F824308DF848B083F001038DF84C3060 +:102BA0000CA9A36820469847FB7DC3F38403013337 +:102BB00003F01F039B02FB829FE7FB7DC8F34012DB +:102BC000B2EBD31F40F0FC80079AC3F38403934217 +:102BD00040F0F98003992B7B4FEA981200294ED0E0 +:102BE000D2075ED4032B40F2F180049BBB60059BAF +:102BF000FB602B7BAE1D033BDBB23246394604F152 +:102C00000C00FFF7C1FA00280DDA20463946FFF71D +:102C1000A9FAFB7DC3F38403013303F01F039B0276 +:102C2000FB82032003E7DDE90A84AB883B834FF690 +:102C3000FF73C9F12000A9F1200228FA09F104FA72 +:102C400000F0014324FA02F211431846C9B2FFF71B +:102C500007FA09F10809B9F1400F0346E9D1B88232 +:102C60002A7B033AD2B23146FFF70CFAFB7DB882D9 +:102C7000DA43C2F3C01262F3C713FB753DE782B9B2 +:102C80002E1D013BDBB23246394604F10C00FFF742 +:102C90007BFA0028B9DB2A7BB88A013AD2B23146E6 +:102CA000E2E7F98AC1F30901013B0429DAB25BD8F2 +:102CB000281D002307F11B069A4208D910F801CB02 +:102CC00006F801C0013101330529DBB2F4D10499C2 +:102CD0000C9105990D91934207F11B010E9138BF9C +:102CE000043379680F9134BF55FA83F300231093AE +:102CF000FB8AADF846A0C3F309031A44079B8DF87D +:102D00004930089B8DF84A30069B8DF84B3094F87B +:102D10002430ADF8442083F001038DF84C300023BB +:102D20008DF848B07B602A7BB88A013A291DFFF7ED +:102D3000A9F93B8BB882834203D1A3680CA9204632 +:102D4000984720460CA9FFF70BFEFB7DB88AC3F31A +:102D50008403013303F01F039B02FB823B8B9842E9 +:102D600014BF1120002062E67B68002BAFD0052045 +:102D700006E000BF40420F0080841E001C30334636 +:102D80001E68002EFAD1091A081D2E1D184401EBE9 +:102D9000090CBCF11B0F5FFA89F398D89A4296D9B7 +:102DA00016F8013B00F8013B09F10109EFE76FF06C +:102DB00009003CE66FF00A0039E66FF00B0036E6DA +:102DC0006FF00D0033E66FF00E0030E66FF00F008D +:102DD0002DE600BF404BF0B51C6C404E44F0007433 +:102DE0001C641D6E45F000751D661B6E3C4B9B6A96 +:102DF000D3F80052354045F00105C3F80052D3F82E +:102E00000042344044EA002040F00100C3F80002D0 +:102E1000002952D00020C3F81C020546C3F8040262 +:102E2000C3F80C02C3F8140203EBC00401301C28E1 +:102E3000C4F84052C4F84452F6D100254FF0010CBA +:102E400096781488F70748BFD3F804720CFA04F098 +:102E500044BF0743C3F80472B70742BFD3F80C72EC +:102E60000743C3F80C72760742BFD3F814620643D7 +:102E7000C3F8146203EBC4045668C4F84062966851 +:102E8000C4F84462D3F81C4201352043A942C3F878 +:102E90001C0202F10C02D3D1D3F8002222F001026D +:102EA000C3F800220C4B1A6C22F000721A641A6EDE +:102EB00022F000721A661B6EF0BD0122C3F84012A8 +:102EC000C3F84412C3F80412C3F81412C3F80C2256 +:102ED000C3F81C22E0E700BF003802400000FFFFFB +:102EE000D8350020184A916A08B58B688B6013F0BA +:102EF000010104D013F00C0F18BF4FF48031D80536 +:102F000006D513F4406F14BF41F4003141F00201C3 +:102F1000D80306D513F4402F14BF41F4802141F0AB +:102F20000401D3690BB108489847202383F3118823 +:102F30000648002100F0AEFF002383F31188BDE8AE +:102F4000084001F023BC00BFD8350020E035002048 +:102F500038B5124CA36ADD68AA0712D05A6922F06C +:102F600002025A61A36913B1012120469847202328 +:102F700083F311880A48002100F08CFF002383F3BB +:102F80001188EB0606D5A36A1021D960236A0BB11C +:102F900002489847BDE8384001F0F8BBD83500201A +:102FA000E835002038B5124CA36A1D69AA0712D073 +:102FB0005A6922F010025A61A36913B10221204616 +:102FC0009847202383F311880A48002100F062FF0C +:102FD000002383F31188EB0606D5A36A102119613B +:102FE000236A0BB102489847BDE8384001F0CEBBD8 +:102FF000D8350020E835002038B50F4CA36A5D684D +:103000005D602A070AD5042222701A6822F00202A3 +:103010001A60636A13B10021204698476B0706D5F2 +:10302000A36A9969236A13B1034809049847BDE864 +:10303000384001F0ABBB00BFD835002010B50E4CB6 +:10304000204600F029F90D4BA3620B21132000F05C +:103050000BF90B21142000F007F90B21152000F0CB +:1030600003F90B21162000F0FFF80022BDE8104004 +:1030700011460E20FFF7AEBED83500200064004098 +:10308000114B984210B5044609D1104B1A6C42F00E +:1030900000721A641A6E42F000721A661B6EA36AFE +:1030A00001221A60A36A5A68D20707D5626851687C +:1030B0001268D9611A60064A5A6110BD01210820C0 +:1030C00000F0D4FDEEE700BFD83500200038024004 +:1030D0005B87010003291AD8DFE801F0020A0F1408 +:1030E000836A9B6813F0E05F14BF012000207047E3 +:1030F000836A9868C0F380607047836A9868C0F3F9 +:10310000C0607047836A9868C0F300707047002001 +:103110007047000010B5032925D8DFE801F002252B +:10312000292D836A9968C1F30161183103EB0113FA +:10313000107884064CBF54689488C0F300114FEA9D +:10314000410148BF41EAC40100F00F004CBF41F00B +:10315000040141EA4451586041F001019068D2688D +:103160009860DA60196010BD836A03F5C073DFE709 +:10317000836A03F5C873DBE7836A03F5D073D7E787 +:1031800001290AD002290FD081B9836ADA6892072F +:1031900001D1186903E001207047836AD86810F0F4 +:1031A000030018BF01207047836AF2E700207047D0 +:1031B00010B539B9836AD96889071BD11B699C0787 +:1031C00004D110BD012915D00229FAD1816AD1F8A4 +:1031D000C031D1F8C441D1F8C8011061D1F8CC0197 +:1031E0005061202008610869800717D1486940F0C4 +:1031F000100012E0816AD1F8B031D1F8B441D1F8B1 +:10320000B8011061D1F8BC0150612020C860C868C5 +:10321000800703D1486940F002004861C3F34000D1 +:10322000C3F38001000140EA4111107920F0300021 +:103230000143117189064BBF91681189DB085B0D51 +:103240004CBF63F31C0163F30A01137948BF91601B +:1032500064F3030313714FEA14234FEA144458BF75 +:10326000118113705480ACE700F1604303F56143B2 +:103270000901C9B283F80013012200F01F039A402C +:1032800043099B0003F1604303F56143C3F88021C8 +:103290001A607047FFF7D2BE012300F10802C0E9AF +:1032A0000222037000F110020023C0E90422C0E9E9 +:1032B0000633C0E9083343607047000010B520238F +:1032C000044683F31188022303704160FFF7D8FEA0 +:1032D00004232370002383F3118810BD2DE9F041EE +:1032E0001F4604460D461646202383F3118800F13D +:1032F00008082378052B0DD029462046FFF7EAFE63 +:1033000040B1204632462946FFF704FF002080F3F3 +:10331000118808E03946404600F0A0FD0028E8D0BA +:10332000002383F31188BDE8F08100002DE9F0410E +:103330001F4604460D461646202383F3118800F1EC +:1033400010082378052B0DD029462046FFF718FFDB +:1033500040B1204632462946FFF72AFF002080F37D +:10336000118808E03946404600F078FD0028E8D092 +:10337000002383F31188BDE8F081000002684368F0 +:103380001143016003B118477047000013B5446B47 +:10339000D4F894341A681178042915D1217C0229B3 +:1033A00012D11979128901238B4013420CD101A942 +:1033B00004F14C0001F0A8FFD4F89444019B21795A +:1033C0000246206800F0CEF902B010BD143001F0C2 +:1033D0002BBF00004FF0FF33143001F025BF000079 +:1033E0004C3001F0FDBF00004FF0FF334C3001F0D6 +:1033F000F7BF0000143001F0F9BE00004FF0FF31BC +:10340000143001F0F3BE00004C3001F0C9BF0000E1 +:103410004FF0FF324C3001F0C3BF00000020704776 +:1034200010B5D0F894341A6811780429044617D1DD +:10343000017C022914D15979528901238B4013420E +:103440000ED1143001F08CFE024648B1D4F89444F9 +:103450004FF4807361792068BDE8104000F070B9C6 +:1034600010BD0000406BFFF7DBBF0000704700009D +:103470007FB5124B036000234360C0E9023301258E +:1034800002260F4B057404460290019300F184025A +:10349000294600964FF48073143001F03DFE094B2D +:1034A0000294CDE9006304F523724FF4807329463A +:1034B00004F14C0001F004FF04B070BD005B000893 +:1034C000653400088D3300080B68202282F31188D0 +:1034D0000A7903EB820290614A79093243F82200AB +:1034E0008A7912B103EB8203986102230374C0F856 +:1034F0009414002383F311887047000038B5037FCC +:10350000044613B190F85430ABB9201D01250221B7 +:10351000FFF734FF04F1140025776FF0010100F08C +:10352000B9FC84F8545004F14C006FF00101BDE87F +:10353000384000F0AFBC38BD10B50121044604305E +:10354000FFF71CFF0023237784F8543010BD0000E0 +:1035500038B504460025143001F0F6FD04F14C00A6 +:10356000257701F0C5FE201D84F854500121FFF796 +:1035700005FF2046BDE83840FFF752BF90F84430C1 +:1035800003F06003202B07D190F84520212A4FF04B +:10359000000303D81F2A06D800207047222AFBD137 +:1035A000C0E90E3303E0034A82630722C263036467 +:1035B000012070472523002037B5D0F894341A68CD +:1035C0001178042904461AD1017C022917D11979EE +:1035D000128901238B40134211D100F14C0528467A +:1035E00001F046FF58B101A9284601F08DFED4F83C +:1035F0009444019B21790246206800F0B3F803B09F +:1036000030BD0000F0B500EB810385B09E69044633 +:103610000D46FEB1202383F3118804EB8507301D8E +:103620000821FFF7ABFEFB685B691B6806F14C00E5 +:103630001BB1019001F076FE019803A901F064FE30 +:10364000024648B1039B2946204600F08BF8002330 +:1036500083F3118805B0F0BDFB685A691268002A2F +:10366000F5D01B8A013B1340F1D104F14402EAE793 +:10367000093138B550F82140DCB1202383F311889B +:10368000D4F894241368527903EB8203DB689B69B6 +:103690005D6845B104216018FFF770FE294604F10A +:1036A000140001F067FD2046FFF7BAFE002383F304 +:1036B000118838BD7047000001F02AB9012303705A +:1036C0000023C0E90133C36183620362C3624362C2 +:1036D0000363704738B50446202383F3118800251F +:1036E000C0E90355C0E90555416001F021F9022305 +:1036F000237085F3118838BD70B500EB8103054652 +:103700005069DA600E46144618B110220021FEF707 +:10371000A7F9A06918B110220021FEF7A1F93146DE +:103720002846BDE8704001F0CDB90000826802F083 +:10373000011282600022C0E90422826101F04EBAC7 +:10374000F0B400EB81044789E4680125A4698D4049 +:103750003D43458123600023A2606360F0BC01F01B +:1037600069BA0000F0B400EB81040789E468012520 +:1037700064698D403D43058123600023A26063603E +:10378000F0BC01F0E3BA000070B502230025044646 +:103790000370C0E90255C0E90455C564856180F82D +:1037A000345001F02BF963681B6823B12946204689 +:1037B000BDE87040184770BD037880F8503005238D +:1037C000037043681B6810B504460BB10421984789 +:1037D0000023A36010BD000090F8502043680270E1 +:1037E0001B680BB1052118477047000070B590F8B1 +:1037F0003430044613B1002380F8343004F144021D +:10380000204601F00DFA63689B68B3B994F8443020 +:1038100013F0600535D00021204601F05FFC002147 +:10382000204601F051FC63681B6813B10621204655 +:103830009847062384F8343070BD20469847002806 +:10384000E4D0B4F84A30E26B9A4288BFE36394F95B +:103850004430E56B002B4FF0200380F20381002DF4 +:1038600000F0F280092284F8342083F311880021CB +:10387000D4E90E232046FFF775FF002383F3118858 +:10388000DAE794F8452003F07F0343EA022340F28D +:103890000232934200F0C58021D8B3F5807F48D032 +:1038A0000DD8012B3FD0022B00F09380002BB2D11A +:1038B00004F14C02A2630222E2632364C1E7B3F580 +:1038C000817F00F09B80B3F5407FA4D194F846300F +:1038D000012BA0D1B4F84C3043F0020332E0B3F531 +:1038E000006F4DD017D8B3F5A06F31D0A3F5C063EA +:1038F000012B90D8636894F846205E6894F84710CE +:10390000B4F848302046B047002884D04368A36309 +:103910000368E3631AE0B3F5106F36D040F6024255 +:1039200093427FF478AF5C4BA3630223E3630023ED +:10393000C3E794F84630012B7FF46DAFB4F84C30F8 +:1039400023F00203C4E90E55A4F84C30256478E74F +:10395000B4F84430B3F5A06F0ED194F8463084F833 +:103960004E30204601F0A2F863681B6813B10121B4 +:1039700020469847032323700023C4E90E339CE7B5 +:1039800004F14F03A3630123C3E72378042B10D171 +:10399000202383F311882046FFF7C8FE85F31188A2 +:1039A0000321636884F84F5021701B680BB12046D7 +:1039B000984794F84630002BDED084F84F3004232B +:1039C000237063681B68002BD6D0022120469847DD +:1039D000D2E794F848301D0603F00F0120460AD5BF +:1039E00001F010F9012804D002287FF414AF2B4B0A +:1039F0009AE72B4B98E701F0F7F8F3E794F8463095 +:103A0000002B7FF408AF94F8483013F00F01B3D0C7 +:103A10001A06204602D501F075FBADE701F068FB00 +:103A2000AAE794F84630002B7FF4F5AE94F84830BE +:103A300013F00F01A0D01B06204602D501F04EFB6B +:103A40009AE701F041FB97E7142284F8342083F3CE +:103A500011882B462A4629462046FFF771FE85F33A +:103A60001188E9E65DB1152284F8342083F31188CA +:103A70000021D4E90E232046FFF762FEFDE60B226B +:103A800084F8342083F311882B462A4629462046A1 +:103A9000FFF768FEE3E700BF305B0008285B000823 +:103AA0002C5B000838B590F834300446002B3ED02B +:103AB000063BDAB20F2A34D80F2B32D8DFE803F0F6 +:103AC000373131082232313131313131313137370B +:103AD000C56BB0F84A309D4214D2C3681B8AB5FB4F +:103AE000F3F203FB12556DB9202383F311882B46A3 +:103AF0002A462946FFF736FE85F311880A2384F803 +:103B000034300EE0142384F83430202383F31188FA +:103B100000231A4619462046FFF712FE002383F3BE +:103B2000118838BD036C03B198470023E7E70021F3 +:103B3000204601F0D3FA0021204601F0C5FA63685F +:103B40001B6813B10621204698470623D7E70000DB +:103B500010B590F83430142B044629D017D8062B12 +:103B600005D001D81BB110BD093B022BFBD80021A9 +:103B7000204601F0B3FA0021204601F0A5FA63685F +:103B80001B6813B1062120469847062319E0152B20 +:103B9000E9D10B2380F83430202383F311880023EC +:103BA0001A461946FFF7DEFD002383F31188DAE792 +:103BB000C3689B695B68002BD5D1036C03B1984740 +:103BC000002384F83430CEE7024B0022C3E90033EF +:103BD0009A60704704360020002303748268054B06 +:103BE0001B6899689142FBD25A680360426010607A +:103BF000586070470436002008B5202383F31188ED +:103C0000037C032B05D0042B0DD02BB983F3118833 +:103C100008BD436900221A604FF0FF334361FFF78C +:103C2000DBFF0023F2E7D0E9003213605A60F3E7CC +:103C3000002303748268054B1B6899689142FBD886 +:103C40005A68036042601060586070470436002074 +:103C5000054B19690874186802681A605360186186 +:103C600001230374FCF7D4BC0436002030B54B1C90 +:103C70000B4D87B0044610D02B690A4A01A800F00A +:103C800025F92046FFF7E4FF049B13B101A800F0DB +:103C900059F92B69586907B030BDFFF7D9FFF8E72C +:103CA00004360020F93B000838B50C4D41612B6902 +:103CB00081689A689142044603D8BDE83840FFF70E +:103CC0008BBF1846FFF7B4FF01232C610146237414 +:103CD0002046BDE83840FCF79BBC00BF04360020FE +:103CE000044B1A681B6990689B68984294BF002037 +:103CF000012070470436002010B5084C2368206965 +:103D00001A6822605460012223611A74FFF790FF41 +:103D100001462069BDE81040FCF77ABC043600205B +:103D200008B5FFF7DDFF18B1BDE80840FFF7E4BFB5 +:103D300008BD0000FFF7E0BFFEE7000010B50C4C27 +:103D4000FFF742FF00F0B4F80A498022204600F055 +:103D50003BF8012344F8180C037400F0F3FC002333 +:103D600083F3118862B60448BDE8104000F04CB8F7 +:103D70002C360020345B0008445B000800F01CB9BE +:103D8000EFF3118020B9EFF30583202282F311882D +:103D90007047000010B530B9EFF30584C4F3080490 +:103DA00014B180F3118810BDFFF7BAFF84F31188B6 +:103DB000F9E70000034A516853685B1A9842FBD840 +:103DC000704700BF001000E082600222028270474C +:103DD0008368A3F17C0243F80C2C026943F83C2C65 +:103DE000426943F8382C074A43F81C2CC26843F850 +:103DF000102C022203F8082C002203F8072CA3F150 +:103E0000180070472906000810B5202383F3118895 +:103E1000FFF7DEFF00210446FFF746FF002383F390 +:103E20001188204610BD0000024B1B6958610F200D +:103E3000FFF70EBF04360020202383F31188FFF71D +:103E4000F3BF000008B50146202383F31188082042 +:103E5000FFF70CFF002383F3118808BD49B1064B1F +:103E600042681B6918605A60136043600420FFF7C2 +:103E7000FDBE4FF0FF3070470436002003689842C3 +:103E800006D01A680260506059611846FFF7A4BE58 +:103E90007047000038B504460D462068844200D1C2 +:103EA00038BD036823605C604561FFF795FEF4E769 +:103EB000054B03F11402C3E905224FF0FF31002244 +:103EC000C3E90712704700BF0436002070B51C4ECE +:103ED000C0E9032305460C4601F0FCFA334653F8CB +:103EE000142F9A420DD13062C5E901242A600A2CB0 +:103EF0002CBF00190A30C6E90555BDE8704001F035 +:103F0000D7BA316A431AE31838BF1C469368A342F4 +:103F100002D9081901F0DAFA73699A6894420CD848 +:103F20005A68AC602B606A6015609A685D60121B0D +:103F30009A604FF0FF33F36170BD1B68A41AECE781 +:103F40000436002038B51B4C636998420DD0D0E987 +:103F5000003213605A6000228168C2609A680A4485 +:103F60009A604FF0FF33E36138BD2246036842F8A0 +:103F7000143F002193425A60C16003D1BDE838402C +:103F800001F09EBA9A688168256A0A449A6001F035 +:103F9000A1FA63699A68411B8A42E5D9AB181D1AD8 +:103FA000092D206A98BF01F10A02BDE8384010448B +:103FB00001F08CBA043600202DE9F041184C00279E +:103FC00004F11406656901F085FA236AAA68C11A2A +:103FD0008A4215D813442362D5E9003213605A602F +:103FE0006369D5F80C80EF60B34201D101F068FA43 +:103FF00087F311882869C047202383F31188E1E7FC +:104000006169B14209D013441B1ABDE8F0410A2B83 +:104010002CBFC0180A3001F059BABDE8F08100BFCA +:104020000436002000207047FEE7000070470000C3 +:104030004FF0FF307047000002290CD0032904D054 +:104040000129074818BF00207047032A05D80548F2 +:1040500000EBC2007047044870470020704700BF63 +:10406000285C000834230020DC5B000870B59AB09F +:104070000546084601A9144600F0C2F801A8FDF75C +:10408000E7FC431C5B00C5E90034002223700323D6 +:104090006370C6B201AB02341046D1B28E4204F155 +:1040A000020401D81AB070BD13F8011B04F8021CF9 +:1040B00004F8010C0132F0E708B5202383F31188DE +:1040C0000348FFF779FA002383F3118808BD00BF86 +:1040D000C037002090F8443003F01F02012A07D1B6 +:1040E00090F845200B2A03D10023C0E90E3315E0D8 +:1040F00003F06003202B08D1B0F848302BB990F8BA +:104100004520212A03D81F2A04D8FFF737BA222ACC +:10411000EBD0FAE7034A82630722C26303640120FB +:10412000704700BF2C23002007B5052917D8DFE80A +:1041300001F0191603191920202383F31188104A5E +:1041400001900121FFF7D8FA01980E4A0221FFF7EA +:10415000D3FA0D48FFF7FCF9002383F3118803B06D +:104160005DF804FB202383F311880748FFF7C6F9A5 +:10417000F2E7202383F311880348FFF7DDF9EBE72B +:104180007C5B0008A05B0008C037002038B50C4DF0 +:104190000C4C0D492A4604F10800FFF767FF05F1B2 +:1041A000CA0204F110000949FFF760FF05F5CA7261 +:1041B00004F118000649BDE83840FFF757BF00BFBB +:1041C000883C0020342300205C5B0008665B00080C +:1041D000715B000870B5044608460D46FDF738FCD3 +:1041E000C6B22046013403780BB9184670BD32467A +:1041F0002946FDF719FC0028F3D10120F6E700005D +:104200002DE9F04705460C46FDF722FC2B49C6B2C6 +:104210002846FFF7DFFF08B10B36F6B228492846DB +:10422000FFF7D8FF08B11036F6B2632E0BD8DFF8CF +:104230008C80DFF88C90234FDFF894A02E7846B95D +:104240002670BDE8F08729462046BDE8F04701F01A +:1042500005BC252E2ED1072241462846FDF7E4FB5A +:1042600070B9194B224603F1100153F8040B42F8C0 +:10427000040B8B42F9D11B88138007351234DDE71C +:10428000082249462846FDF7CFFB98B90F4BA21CE0 +:10429000197809090232C95D02F8041C13F8011BE0 +:1042A00001F00F015345C95D02F8031CF0D1183429 +:1042B0000835C3E704F8016B0135BFE7485C000827 +:1042C000715B0008635C0008505C0008107AFF1FF7 +:1042D0001C7AFF1FBFF34F8F024AD368DB03FCD465 +:1042E000704700BF003C024008B5094B1B7873B90A +:1042F000FFF7F0FF074B1A69002ABFBF064A5A6052 +:1043000002F188325A601A6822F480621A6008BD8D +:10431000E63E0020003C02402301674508B50B4BF8 +:104320001B7893B9FFF7D6FF094B1A6942F0004298 +:104330001A611A6842F480521A601A6822F4805294 +:104340001A601A6842F480621A6008BDE63E0020D6 +:10435000003C02400B28F0B516D80C4C0C492378D1 +:104360007BB90C4D0E460C234FF0006255F8047BD0 +:1043700046F8042B013B13F0FF033A44F6D1012326 +:10438000237051F82000F0BD0020FCE7183F00200A +:10439000E83E0020745C0008014B53F82000704791 +:1043A000745C00080C2070470B2810B5044601D936 +:1043B000002010BDFFF7CEFF064B53F82430184401 +:1043C000C21A0BB90120F4E712680132F0D1043BA4 +:1043D000F6E700BF745C00080B2838B5044628D8FF +:1043E000FFF7CEFCFFF776FFFFF77EFF124AF323BD +:1043F000D360E300DBB243F4007343F002031361C4 +:10440000136943F48033136105462046FFF762FFCA +:10441000FFF7A0FF094B53F8241000F039F92846A4 +:10442000FFF77CFFFFF7B6FC2046BDE83840FFF7FA +:10443000BBBF002038BD00BF003C0240745C0008D8 +:1044400012F001032DE9F04105460E4614464BD10A +:104450008218B2F1016F61D8314B1B6813F0010370 +:104460005CD0304FFFF78CFCFFF73EFFF323FB607F +:10447000FFF730FF314640F20128032C18D824F012 +:104480000104284E0C446D1A40F20118A142336910 +:1044900005EB01072AD123F001033361FFF73EFF4B +:1044A000FFF778FC0120BDE8F081043C0435E4E727 +:1044B000AB07E4D13B6923F440733B613B6943EABA +:1044C00008033B6151F8046B2E60BFF34F8FFFF779 +:1044D00001FF2B689E42E8D03B6923F001033B615A +:1044E000FFF71CFFFFF756FC0020DCE723F44073C6 +:1044F0003361336943EA080333610B883B80BFF3C0 +:104500004F8FFFF7E7FE3F8831F8023BBFB2BB4257 +:10451000BCD0336923F001033361E1E71846C2E7F9 +:1045200000380240003C0240084908B50B7828B129 +:104530001BB9FFF7D9FE01230B7008BD002BFCD07F +:10454000BDE808400870FFF7E9BE00BFE63E002066 +:1045500070B582B0FFF714FC0E4E054600F0BAFFAE +:104560003268904237BF0C4A0B49516814682EBF1D +:10457000D1E90041013151600419034641F10001C4 +:10458000284601913360FFF705FC0199204602B0EF +:1045900070BD00BF1C3F0020203F002070B582B0DE +:1045A000FFF7EEFB104E054600F094FF3268904294 +:1045B00037BF0E4A0D49516814682EBFD1E900413A +:1045C00001315160041941F100010346284601916F +:1045D0003360FFF7DFFB01994FF47A720023204626 +:1045E000FBF7FEFD02B070BD1C3F0020203F002005 +:1045F00010B50244064BD2B2904200D110BD441C0B +:1046000000B253F8200041F8040BE0B2F4E700BF19 +:10461000502800400F4B30B51C6F240407D41C6F8A +:1046200044F400741C671C6F44F400441C670A4C7B +:10463000236843F4807323600244084BD2B2904253 +:1046400000D130BD441C00B251F8045B43F8205047 +:10465000E0B2F4E70038024000700040502800400B +:1046600007B5012201A90020FFF7C2FF019803B09E +:104670005DF804FB13B50446FFF7F2FFA04205D036 +:10468000012201A900200194FFF7C4FF02B010BD70 +:1046900070470000074B45F255521A6002225A60DB +:1046A00040F6FF729A604CF6CC421A60024B01222F +:1046B0001A707047003000402C3F0020034B1B78DD +:1046C0001BB1034B4AF6AA221A6070472C3F002008 +:1046D00000300040034B1A681AB9034AD2F8742814 +:1046E0001A607047283F002000300240024B4FF014 +:1046F0008072C3F8742870470030024008B5FFF795 +:10470000E9FF024B1868C0F3407008BD283F002045 +:1047100008B5FFF7DFFF024B1868C0F3007008BD53 +:10472000283F0020EFF3098305494A6B22F001027C +:104730004A63683383F30988002383F31188704741 +:1047400000EF00E0202080F3118862B60C4B0D4A88 +:10475000D96821F4E0610904090C0A43DA60D3F84E +:10476000FC20094942F08072C3F8FC200A6842F03C +:1047700001020A601022DA7783F82200704700BF36 +:1047800000ED00E00003FA05001000E010B5202362 +:1047900083F311880E4B5B6813F4006314D0F1EEC1 +:1047A000103AEFF30984683C4FF08073E361094BE2 +:1047B000DB6B236684F30988FFF792FA10B1064B8E +:1047C000A36110BD054BFBE783F31188F9E700BF38 +:1047D00000ED00E000EF00E03B0600083E060008A8 +:1047E00070470000FEE700000A4B0B480B4A90425E +:1047F0000BD30B4BDA1C121AC11E22F003028B42A0 +:1048000038BF00220021FDF72BB953F8041B40F8F4 +:10481000041BECE72C5E0008284000202840002004 +:10482000284000207047000070B5D0E915439E680D +:1048300000224FF0FF3504EB42135101D3F8000979 +:104840000028BEBFD3F8000940F08040C3F800093B +:10485000D3F8000B0028BEBFD3F8000B40F0804017 +:10486000C3F8000B013263189642C3F80859C3F825 +:10487000085BE0D24FF00113C4F81C3870BD000093 +:104880001D4B03EB80022DE9F043D2F80CC05D6DA7 +:10489000DCF81420461CD2F800E005EB063605EBE8 +:1048A0004018516871450AD3D5F83438012202FA0C +:1048B00000F023EA0000C5F83408BDE8F083BCF836 +:1048C0001040AEEB0103A34228BF2346D8F8184995 +:1048D000A4B2B3EB840FF0D89468A4F1040959F89A +:1048E000047F3760A4EB09071F44042FF7D81C444A +:1048F0000B4494605360D4E7303F0020890141F0BD +:104900002001016103699B06FCD41220FFF752BA13 +:1049100010B5054C2046FEF7D1FE4FF0A04363656D +:10492000024BA36510BD00BF303F0020C85C0008EB +:1049300070B50378012B054650D12A4B446D98423F +:104940001BD1294B5A6B42F080025A635A6D42F0D8 +:1049500080025A655A6D5A6942F080025A615A695A +:1049600022F080025A610E2143205B69FEF77CFC35 +:104970001E4BE3601E4BC4F800380023C4F8003E11 +:10498000C02323606E6D4FF40413A3633369002BBF +:10499000FCDA012333610C20FFF70CFA3369DB07E3 +:1049A000FCD41220FFF706FA3369002BFCDA00264C +:1049B000A6602846FFF738FF6B68C4F81068DB680C +:1049C000C4F81468C4F81C684BB90A4BA3614FF0D3 +:1049D000FF336361A36843F00103A36070BD064B1E +:1049E000F4E700BF303F0020003802404014004090 +:1049F00003002002003C30C0083C30C0F8B5446DD4 +:104A0000054600212046FFF779FFA96D00234FF0EE +:104A100001128F68C4F834384FF00066C4F81C28BF +:104A20004FF0FF3004EB431201339F42C2F800699C +:104A3000C2F8006BC2F80809C2F8080BF2D20B6882 +:104A40006A6DEB65636210231361166916F0100638 +:104A5000FBD11220FFF7AEF9D4F8003823F4FE633F +:104A6000C4F80038A36943F4402343F01003A36162 +:104A70000923C4F81038C4F814380A4BEB604FF01F +:104A8000C043C4F8103B084BC4F8003BC4F810699D +:104A9000C4F80039EB6D03F1100243F48013EA65AA +:104AA000A362F8BDA45C000840800010426D90F83D +:104AB0004E10D2F8003823F4FE6343EA0113C2F823 +:104AC000003870472DE9F84300EB8103456DDA6843 +:104AD000166806F00306731E022B05EB41130C4605 +:104AE00080460FFA81F94FEA41104FF00001C3F8F8 +:104AF000101B4FF0010104F1100398BFB60401FA36 +:104B000003F391698EBF334E06F1805606F50046D9 +:104B100000293AD0578A04F15801490137436F50B0 +:104B2000D5F81C180B43C5F81C382B180021C3F806 +:104B3000101953690127611EA7409BB3138A928BFA +:104B40009B08012A88BF5343D8F85C20981842EA92 +:104B5000034301F1400205EB8202C8F85C002146E4 +:104B600053602846FFF7CAFE08EB8900C3681B8A1A +:104B700043EA8453483464011E432E51D5F81C384F +:104B80001F43C5F81C78BDE8F88305EB4917D7F833 +:104B9000001B21F40041C7F8001BD5F81C1821EABE +:104BA0000303C0E704F13F0305EB83030A4A5A609D +:104BB00028462146FFF7A2FE05EB4910D0F8003940 +:104BC00023F40043C0F80039D5F81C3823EA07075E +:104BD000D7E700BF0080001000040002826D126859 +:104BE000C265FFF721BE00005831436D49015B5893 +:104BF00013F4004004D013F4001F0CBF0220012066 +:104C0000704700004831436D49015B5813F4004080 +:104C100004D013F4001F0CBF0220012070470000D5 +:104C200000EB8101CB68196A0B6813604B68536015 +:104C30007047000000EB810330B5DD68AA69136896 +:104C4000D36019B9402B84BF402313606B8A14686A +:104C5000426D1C44013CB4FBF3F46343033323F083 +:104C6000030302EB411043EAC44343F0C043C0F8DE +:104C7000103B2B6803F00303012B09B20ED1D2F8CD +:104C8000083802EB411013F4807FD0F8003B14BFCA +:104C900043F0805343F00053C0F8003B02EB411255 +:104CA000D2F8003B43F00443C2F8003B30BD0000A3 +:104CB0002DE9F041244D6E6D06EB40130446D3F808 +:104CC000087BC3F8087B38070AD5D6F814381907CB +:104CD00006D505EB84032146DB6828465B689847C8 +:104CE000FA071FD5D6F81438DB071BD505EB84036C +:104CF000D968CCB98B69488A5A68B2FBF0F600FBD8 +:104D000016228AB91868DA6890420DD2121AC3E9DD +:104D10000024202383F311880B482146FFF78AFFE4 +:104D200084F31188BDE8F081012303FA04F26B8952 +:104D300023EA02036B81CB68002BF3D021460248A3 +:104D4000BDE8F041184700BF303F002000EB810371 +:104D500070B5DD68436D6C692668E6604A0156BB34 +:104D60001A444FF40020C2F810092A6802F0030226 +:104D7000012A0AB20ED1D3F8080803EB421410F44A +:104D8000807FD4F8000914BF40F0805040F00050FC +:104D9000C4F8000903EB4212D2F8000940F00440C5 +:104DA000C2F80009D3F83408012202FA01F10143E4 +:104DB000C3F8341870BD19B9402E84BF402020605C +:104DC00020682E8A8419013CB4FBF6F440EAC44002 +:104DD00040F000501A44C6E7F8B504461E48456D39 +:104DE00005EB4413D3F80869C3F80869F10717D530 +:104DF000D5F81038DA0713D500EB8403D9684B696E +:104E00001F68DA68974218D2D21B00271A605F60C9 +:104E1000202383F311882146FFF798FF87F3118839 +:104E2000330617D5D5F834280123A340134211D0F7 +:104E30002046BDE8F840FFF723BD012303FA04F242 +:104E4000038923EA020303818B68002BE8D0214603 +:104E50009847E5E7F8BD00BF303F00202DE9F74F48 +:104E6000984C666D7569B3691D4015F4805875617D +:104E700007D02046FEF788FC03B0BDE8F04FFFF7EF +:104E800085BC002D12DAD6F8003E8E489F071EBF63 +:104E9000D6F8003E23F00303C6F8003ED6F80438E7 +:104EA00023F00103C6F80438FEF796FC280505D563 +:104EB0008448FFF7B9FC8348FEF77EFCA9040CD5B3 +:104EC000D6F8083813F0060FF36823F470530CBFBC +:104ED00043F4105343F4A053F3602A0704D56368E6 +:104EE000DB680BB177489847EB0274D4AF0227D543 +:104EF000D4F85490DFF8CCB100274FF0010A09EB49 +:104F00004712D2F8003B03F44023B3F5802F11D1B0 +:104F1000D2F8003B002B0DDA62890AFA07F322EA85 +:104F20000303638104EB8703DB68DB6813B1394655 +:104F300058469847A36D01379B68FFB29F42DED960 +:104F4000E80617D5676D3A6AC2F30A1002F00F033C +:104F500002F4F012B2F5802F00F08880B2F5402FF5 +:104F600008D104EB83030022DB681B6A07F5805736 +:104F700090426DD12903D6F8184813D5E20302D523 +:104F80000020FFF795FEA30302D50120FFF790FE56 +:104F9000670302D50220FFF78BFE260302D503200C +:104FA000FFF786FE6D037FF567AFE00702D50020AF +:104FB000FFF712FFA10702D50120FFF70DFF6207DF +:104FC00002D50220FFF708FF23077FF555AF032026 +:104FD000FFF702FF50E7636DDFF8E8B001930027A9 +:104FE0004FF0010AA36D9B685FFA87F999453FF678 +:104FF0007DAF019B03EB4913D3F8002902F4402253 +:10500000B2F5802F22D1D3F80029002A1EDAD3F876 +:10501000002942F09042C3F80029D3F80029002A61 +:10502000FBDB606D4946FFF769FC22890AFA09F348 +:1050300022EA0303238104EB8903DB689B6813B135 +:105040004946584698474846FFF71AFC0137C9E7D2 +:10505000910708BFD7F80080072A98BF03F8018B93 +:1050600002F1010298BF4FEA182881E7023304EBEE +:10507000830207F580575268D2F818C0DCF8082080 +:10508000DCE9001CA1EB0C0C002188420AD104EBE6 +:10509000830463689B699A6802449A605A68024470 +:1050A0005A6067E711F0030F08BFD7F800808C45FE +:1050B00088BF02F8018B01F1010188BF4FEA18286F +:1050C000E3E700BF303F0020436D03EB4111D1F80F +:1050D000003B43F40013C1F8003B7047436D03EB02 +:1050E0004111D1F8003943F40013C1F80039704779 +:1050F000436D03EB4111D1F8003B23F40013C1F8D9 +:10510000003B7047436D03EB4111D1F8003923F4A4 +:105110000013C1F80039704730B5039C01720433A5 +:1051200004FB0325C0E90653049B03630021059B90 +:10513000C160C0E90000C0E90422C0E90842C0E93A +:105140000A11436330BD0000416A0022C0E9041126 +:10515000C0E90A22C2606FF00101FEF79BBE0000A9 +:10516000D0E90432934201D1C2680AB9181D7047D0 +:105170000020704703691960C2680132C260C269C9 +:10518000134482690361934224BF436A036100218F +:10519000FEF774BE38B504460D46E3683BB162695C +:1051A000131D1268A3621344E362002007E0237A10 +:1051B00033B929462046FEF751FE0028EDDA38BD06 +:1051C0006FF00100FBE70000C368C269013BC360E8 +:1051D0004369134482694361934224BF436A436134 +:1051E00000238362036B03B11847704770B5202317 +:1051F000044683F31188866A3EB9FFF7CBFF054664 +:1052000018B186F31188284670BDA36AE26A13F8C4 +:10521000015BA362934202D32046FFF7D5FF002330 +:1052200083F31188EFE700002DE9F84F04460E469E +:10523000174698464FF0200989F311880025AA46A1 +:10524000D4F828B0BBF1000F09D141462046FFF742 +:10525000A1FF20B18BF311882846BDE8F88FD4E96F +:105260000A12A7EB050B521A934528BF9346BBF1D0 +:10527000400F1BD9334601F1400251F8040B43F8AB +:10528000040B9142F9D1A36A40334036A362403502 +:10529000D4E90A239A4202D32046FFF795FF8AF306 +:1052A0001188BD42D8D289F31188C9E730465A46E1 +:1052B000FCF7B0FBA36A5B445E44A3625D44E7E78E +:1052C00010B5029C0172043304FB0321C0E90613EC +:1052D0000023C0E90A33039B0363049BC460C0E955 +:1052E0000000C0E90422C0E90842436310BD000089 +:1052F000026AC260426AC0E904220022C0E90A22AE +:105300006FF00101FEF7C6BDD0E904239A4201D136 +:10531000C26822B9184650F8043B0B607047002061 +:1053200070470000C368C2690133C3604369134416 +:1053300082694361934224BF436A43610021FEF7BF +:105340009DBD000038B504460D46E3683BB12369B6 +:105350001A1DA262E2691344E362002007E0237A87 +:1053600033B929462046FEF779FD0028EDDA38BD2D +:105370006FF00100FBE7000003691960C268013AA1 +:10538000C260C269134482690361934224BF436AC5 +:10539000036100238362036B03B118477047000069 +:1053A00070B520230D460446114683F31188866AA2 +:1053B0002EB9FFF7C7FF10B186F3118870BDA36A3D +:1053C0001D70A36AE26A01339342A36204D3E169C8 +:1053D00020460439FFF7D0FF002080F31188EDE765 +:1053E0002DE9F84F04460D46904699464FF0200AA5 +:1053F0008AF311880026B346A76A4FB9494620466A +:10540000FFF7A0FF20B187F311883046BDE8F88F81 +:10541000D4E90A073A1AA8EB0607974228BF1746AD +:10542000402F1BD905F1400355F8042B40F8042BFD +:105430009D42F9D1A36A4033A3624036D4E90A23DE +:105440009A4204D3E16920460439FFF795FF8BF3B4 +:1054500011884645D9D28AF31188CDE729463A46C4 +:10546000FCF7D8FAA36A3B443D44A3623E44E5E717 +:10547000D0E904239A4217D1C3689BB1836A8BB1E8 +:10548000043B9B1A0ED01360C368013BC360C36921 +:105490001A44836902619A4224BF436A036100236C +:1054A00083620123184670470023FBE700F088B8A9 +:1054B0004FF08043002258631A610222DA6070477D +:1054C0004FF080430022DA60704700004FF08043C5 +:1054D000586370474FF08043586A70474B68436089 +:1054E0008B688360CB68C3600B6943614B6903625F +:1054F0008B6943620B6803607047000008B5264B58 +:1055000026481A6940F2FF110A431A611A6922F407 +:10551000FF7222F001021A611A691A6B0A431A63B8 +:105520001A6D0A431A651E4A1B6D1146FFF7D6FF16 +:1055300002F11C0100F58060FFF7D0FF02F1380195 +:1055400000F58060FFF7CAFF02F1540100F58060AA +:10555000FFF7C4FF02F1700100F58060FFF7BEFFA6 +:1055600002F18C0100F58060FFF7B8FF02F1A8019D +:1055700000F58060FFF7B2FF02F1C40100F5806022 +:10558000FFF7ACFF02F1E00100F58060FFF7A6FF36 +:10559000BDE8084000F09AB8003802400000024020 +:1055A000D45C000808B500F007FAFEF7C7FBFFF768 +:1055B00091F8BDE80840FEF7E9BD00007047000023 +:1055C000104B1A6C42F001021A641A6E42F001028A +:1055D0001A660D4A1B6E936843F0010393604FF007 +:1055E000804353229A624FF0FF32DA6200229A61BE +:1055F0005A63DA605A6001225A6108211A601C203D +:10560000FDF732BE00380240002004E04FF0804237 +:1056100008B51169D3680B40D9B2C9439B07116122 +:1056200007D5202383F31188FEF7A8FB002383F31B +:10563000118808BD08B5FFF7E9FFBDE80840FFF78E +:10564000A5B800001F4B1A696FEAC2526FEAD25226 +:105650001A611A69C2F308021A614FF0FF301A6921 +:105660005A69586100215A6959615A691A6A62F087 +:1056700080521A621A6A02F080521A621A6A5A6AD0 +:1056800058625A6A59625A6A1A6C42F080521A6415 +:105690001A6E42F080521A661A6E0B4A106840F475 +:1056A00080701060186F00F44070B0F5007F1EBF6E +:1056B0004FF4803018671967536823F40073536000 +:1056C00000F05AB90038024000700040334B4FF0F0 +:1056D00080521A64324A4FF4404111601A6842F015 +:1056E00001021A601A689107FCD59A6822F0030239 +:1056F0009A602A4B9A6812F00C02FBD1196801F0EB +:10570000F90119609A601A6842F480321A601A68C6 +:105710009203FCD55A6F42F001025A671F4B5A6F31 +:105720009007FCD51F4A5A601A6842F080721A60CE +:105730001B4A53685904FCD5184B1A689201FCD5D2 +:10574000194A9A60194B1A68194B9A42194B21D180 +:10575000194A1168194A91421CD140F205121A6087 +:10576000144A136803F00F03052BFAD10B4B9A6808 +:1057700042F002029A609A6802F00C02082AFAD1FA +:105780005A6C42F480425A645A6E42F480425A661D +:105790005B6E704740F20572E1E700BF00380240DF +:1057A000007000400854400700948838002004E04E +:1057B00011640020003C024000ED00E041C20F41B6 +:1057C000084A08B5516913680B4003F0010353619F +:1057D00023B1054A13680BB150689847BDE80840EB +:1057E000FEF7D4BF003C0140A83F0020084A08B59E +:1057F000516913680B4003F00203536123B1054A5A +:1058000093680BB1D0689847BDE80840FEF7BEBF6B +:10581000003C0140A83F0020084A08B551691368C0 +:105820000B4003F00403536123B1054A13690BB124 +:1058300050699847BDE80840FEF7A8BF003C01400A +:10584000A83F0020084A08B5516913680B4003F0CF +:105850000803536123B1054A93690BB1D069984796 +:10586000BDE80840FEF792BF003C0140A83F002081 +:10587000084A08B5516913680B4003F010035361DF +:1058800023B1054A136A0BB1506A9847BDE8084036 +:10589000FEF77CBF003C0140A83F0020174B10B52D +:1058A0005A691C68144004F478725A61A30604D53E +:1058B000134A936A0BB1D06A9847600604D5104A20 +:1058C000136B0BB1506B9847210604D50C4A936BB0 +:1058D0000BB1D06B9847E20504D5094A136C0BB1A4 +:1058E000506C9847A30504D5054A936C0BB1D06C56 +:1058F0009847BDE81040FEF749BF00BF003C01409B +:10590000A83F00201A4B10B55A691C68144004F4D3 +:105910007C425A61620504D5164A136D0BB1506D75 +:105920009847230504D5134A936D0BB1D06D984762 +:10593000E00404D50F4A136E0BB1506E9847A104D2 +:1059400004D50C4A936E0BB1D06E9847620404D50F +:10595000084A136F0BB1506F9847230404D5054ACA +:10596000936F0BB1D06F9847BDE81040FEF70EBFA4 +:10597000003C0140A83F0020062108B50846FDF77D +:1059800073FC06210720FDF76FFC06210820FDF7B8 +:105990006BFC06210920FDF767FC06210A20FDF7B4 +:1059A00063FC06211720FDF75FFCBDE808400621D7 +:1059B0002820FDF759BC000008B5FFF743FE00F0B2 +:1059C0000DF8FDF767FCFDF777FEFDF74FFDFFF7DC +:1059D000F5FDBDE80840FFF769BD00000023054A5A +:1059E00019460133102BC2E9001102F10802F8D167 +:1059F000704700BFA83F002010B501390244904213 +:105A000001D1002005E0037811F8014FA34201D035 +:105A1000181B10BD0130F2E72DE9F041A3B1C91AFE +:105A200017780144044603F1FF3C8C42204601D91B +:105A3000002009E00578BD4204F10104F5D10CEB2A +:105A40000405D618A54201D1BDE8F08115F8018DF5 +:105A500016F801EDF045F5D0E7E70000034611F830 +:105A6000012B03F8012B002AF9D170476F72672EC2 +:105A70006172647570696C6F742E663430355F4D79 +:105A80006174656B41697273706565640000000044 +:105A900053544D3332463F3F3F00000053544D3383 +:105AA00032463430780053544D3332463432780025 +:105AB00053544D33324634343658580000000000F9 +:105AC000905A00083F000000130400009C5A000890 +:105AD0003F00000019040000A65A00083F00000023 +:105AE00021040000B05A00083F00000040A2E4F189 +:105AF000646891060041A3E5F26569920700000021 +:105B000000000000E9330008D53300081134000814 +:105B1000FD33000809340008F5330008E1330008BC +:105B2000CD3300081D340008000000000100000013 +:105B3000000000006D61696E0000000069646C6522 +:105B4000000000003C5B000848360020C037002001 +:105B500001000000393D000800000000417264753A +:105B600050696C6F740025424F415244252D424CC0 +:105B7000002553455249414C250000000200000019 +:105B800000000000053600087136000840004000A3 +:105B9000583C0020683C002002000000000000008B +:105BA0000300000000000000B536000800000000FF +:105BB00010000000783C0020000000000100000000 +:105BC00000000000303F00200101020029410008D0 +:105BD00039400008D5400008B940000843000000E3 +:105BE000E45B000809024300020100C0320904001E +:105BF000000102020100052400100105240100013A +:105C0000042402020524060001070582030800FFA0 +:105C100009040100020A000000070501024000001B +:105C2000070581024000000012000000305C0008FF +:105C30001201100102000040091241570002010246 +:105C4000030100000403090425424F41524425008A +:105C5000663430352D4D6174656B416972737065C2 +:105C60006564003031323334353637383941424398 +:105C70004445460000400000004000000040000095 +:105C800000400000000001000000020000000200CF +:105C900000000200000002000000020000000200FC +:105CA0000000020000000000ED370008A53A0008DF +:105CB000513B000840004000903F0020903F0020F2 +:105CC00001000000A03F0020800000004001000013 +:105CD00003000000AA01A81200000000AAAAAAAAB4 +:105CE00055011400FFBF00008877000070A70A006C +:105CF00000000A0100000000AAAAAAAA00000001F0 +:105D0000FFFF000000000000990000000000A01646 +:105D100000000000AAAAAAA600005011FFDF0000A0 +:105D200000000000007708002000000000000000D4 +:105D3000AAAAAAAA10000000FFFF000000080000A5 +:105D4000000000000000000000000000AAAAAAAAAB +:105D500000000000FFFF0000000000000000000045 +:105D60000000000000000000AAAAAAAA000000008B +:105D7000FFFF000000000000000000000000000025 +:105D800000000000AAAAAAAA00000000FFFF00006D +:105D90000000000000000000000000000000000003 +:105DA0000A000000000000000300000000000000E6 +:105DB00000000000000000000000000000000000E3 +:105DC00000000000000000000000000000000000D3 +:105DD00040A4FF7F01000000F60300000000000067 +:105DE00000000F0000000000640000000000000040 +:105DF00040420F00FE2A0100D2040000FF0096007E +:105E000000000008009600000000080004000000E8 +:105E1000445C0008000000000000000000000000DA +:0C5E200000000000000000000000000076 :00000001FF diff --git a/Tools/bootloaders/f405-MatekGPS_bl.bin b/Tools/bootloaders/f405-MatekGPS_bl.bin index 0ec638650a2..ee2509b0f5a 100755 Binary files a/Tools/bootloaders/f405-MatekGPS_bl.bin and b/Tools/bootloaders/f405-MatekGPS_bl.bin differ diff --git a/Tools/bootloaders/f405-MatekGPS_bl.hex b/Tools/bootloaders/f405-MatekGPS_bl.hex index dbc0e2a2b00..297d7985105 100644 --- a/Tools/bootloaders/f405-MatekGPS_bl.hex +++ b/Tools/bootloaders/f405-MatekGPS_bl.hex @@ -1,25 +1,25 @@ :020000040800F2 -:1000000000070020E50400080D1D00088D1C0008F5 -:10001000E51C00088D1C0008B91C0008E704000856 -:10002000E7040008E7040008E7040008C1430008EB +:1000000000070020E5040008B91D0008391D00089C +:10001000911D0008391D0008651D0008E70400084F +:10002000E7040008E7040008E7040008B1450008F9 :10003000E7040008E7040008E7040008E7040008F4 :10004000E7040008E7040008E7040008E7040008E4 -:10005000E7040008E70400085D540008895400081C -:10006000B5540008E15400080D550008E7040008E5 +:10005000E7040008E70400084D5600087956000838 +:10006000A5560008D1560008FD560008E704000810 :10007000E7040008E7040008E7040008E7040008B4 -:10008000E7040008E7040008E7040008C12B0008A3 -:100090002D2C0008812C0008D52C000839550008AB +:10008000E7040008E7040008E7040008712D0008F1 +:10009000DD2D0008312E0008852E000829570008A4 :1000A000E7040008E7040008E7040008E704000884 -:1000B000D1520008E7040008E7040008E70400083C +:1000B000C1540008E7040008E7040008E70400084A :1000C000E7040008E7040008E7040008E704000864 :1000D000E7040008E7040008E7040008E704000854 -:1000E000A1550008E7040008E7040008E704000839 +:1000E00091570008E7040008E7040008E704000847 :1000F000E7040008E7040008E7040008E704000834 :10010000E7040008E7040008E7040008E704000823 :10011000E7040008E7040008E7040008E704000813 :10012000E7040008E7040008E7040008E704000803 :10013000E7040008E7040008E7040008E7040008F3 -:10014000E7040008E7040008E7040008F94A00088B +:10014000E7040008E7040008E7040008E94C000899 :10015000E7040008E7040008E7040008E7040008D3 :10016000E7040008E7040008E7040008E7040008C3 :10017000E7040008E7040008E7040008E7040008B3 @@ -84,1379 +84,1411 @@ :1005200040F20000C0F2F0004EF68851CEF2000119 :100530000860BFF34F8FBFF36F8F4FF00000E1EE05 :10054000100A4EF63C71CEF200010860062080F3DE -:100550001488BFF36F8F03F0B3FF03F08FFF04F035 -:100560001BFE4FF055301F491B4A91423CBF41F8DA +:100550001488BFF36F8F04F0ABF804F087F804F051 +:1005600013FF4FF055301F491B4A91423CBF41F8E1 :10057000040BFAE71C49194A91423CBF41F8040BAD :10058000FAE71A491A4A1B4B9A423EBF51F8040B2C :1005900042F8040BF8E700201749184A91423CBF83 -:1005A00041F8040BFAE703F06DFF04F049FE144C28 +:1005A00041F8040BFAE704F065F804F041FF144C3D :1005B000144DAC4203DA54F8041B8847F9E700F005 :1005C00041F8114C114DAC4203DA54F8041B884732 -:1005D000F9E703F055BF00000007002000230020CA -:1005E000000000080001002000070020F05A000869 -:1005F000002300205023002050230020144000201E +:1005D000F9E704F04DB800000007002000230020D8 +:1005E000000000080001002000070020E05C000877 +:1005F00000230020542300205823002028400020FE :10060000E0010008E0010008E0010008E001000846 :100610002DE9F04F2DED108AC1F80CD0C3689D462E :10062000BDEC108ABDE8F08F002383F311882846C3 -:10063000A047002003F06EFAFEE703F0E9F900DFBF -:10064000FEE70000F8B503F065FE074603F0B2FED2 -:10065000044688BB1D4B9F422ED001339F422ED0B3 -:100660001B4B27F0FF029A422CD1F8B200F01AFD82 -:10067000264642F2107500F01FFF00F019FD08B980 -:100680000646054634B1134B9F4203D003F08AFE61 -:1006900000252E46002003F047FE0EB100F062F860 -:1006A00001F0C6FA00F02AFF01F052F9284600F0E6 -:1006B000B5F800F057F8F9E726460025DBE70546D0 -:1006C0000126D8E7064641F28835D4E7010007B095 -:1006D000000008B0263A09B008B501F00BF9A0F106 -:1006E00020035842584108BD07B541F212030221C8 -:1006F00001A8ADF8043001F01BF903B05DF804FB6C -:1007000010B5202383F311881248C3680BB103F09E -:1007100087FA114A0F4800234FF47A7103F044FA24 -:10072000002383F311880D4C236813B12368013B28 -:100730002360636813B16368013B6360084B1B78F7 -:1007400033B9636823B9022001F0ECF93223636006 -:1007500010BD00BF50230020010700086C240020BA -:1007600064230020274B284A10B51C461968013124 -:1007700046D004339342F9D16268244B9A423FD960 -:10078000234B9B6803F1006303F580339A4237D211 -:1007900003F0DAFD03F0ECFD002001F0F3F81D4B4F -:1007A0000220187001F0B4F91B4B1A6C00221A6475 -:1007B000196E1A66196E596C5A64596E5A665A6ED9 -:1007C0005A6942F080025A615A6922F080025A61E5 -:1007D0005A691A6942F000521A611A6922F00052ED -:1007E0001A611B6972B64FF0E0232021C3F8084D4F -:1007F000D4E9003281F311889D4683F308881047BD -:1008000010BD00BF0000010820000108FFFF000824 -:100810000023002064230020003802402DE9F04F1F -:1008200093B0AC4B00902022FF210AA89D6801F0F4 -:10083000A9F9A94A1378A3B9A8480121C360117086 -:10084000202383F31188C3680BB103F0E9F9A44AAC -:10085000A24800234FF47A7103F0A6F9002383F332 -:100860001188009B9F4A03B113609F49009C00239D -:100870000B70536098469B461E469A46012001F035 -:1008800047F924B1974B1B68002B00F01C82002015 -:1008900001F030F80390039B002B01DA00F0CEFE4C -:1008A000039B002BEDDB012001F028F9039B213B8A -:1008B000162BE3D801A252F823F000BF1909000853 -:1008C00041090008D50900087D0800087D080008D6 -:1008D0007D080008690A00083B0C0008550B000859 -:1008E000B70B0008DF0B0008050C00087D080008A6 -:1008F000170C00087D080008890C0008B9090008D9 -:100900007D080008CD0C000825090008B909000879 -:100910007D080008B70B00080220FFF7DDFE002865 -:1009200040F0FB81009B0221B8F1000F08BF1C467C -:1009300005A841F21233ADF8143000F0F9FF9DE73D -:100940004FF47A7000F0D6FF071EEBDB0220FFF7B2 -:10095000C3FE0028E6D0013F052F00F2E081DFE86A -:1009600007F0030A0D10133605230593042105A88B -:1009700000F0DEFF17E057480421F9E75B48042147 -:10098000F6E75B480421F3E74FF01C09484600F006 -:10099000FBFF09F104090590042105A800F0C8FF38 -:1009A000B9F12C0FF2D1012000FA07F747EA0B0B3F -:1009B0005FFA8BFB4FF0000A01F030F926B10BF023 -:1009C0000B030B2B08BF0024FFF78EFE56E74948A8 -:1009D0000421CDE7002EA5D00BF00B030B2BA1D1EA -:1009E0000220FFF779FE074600289BD001203E4EEB -:1009F00000F0C8FF0220307001F08AF84FF00008C4 -:100A00005FFA88F9484600F0CDFF044690B14846A9 -:100A100000F0D8FF08F101080028F1D1B8460446DB -:100A200041F21213022105A8ADF814303E4600F041 -:100A30007FFF23E701230220337001F05FF8254692 -:100A4000244B9B68AB4207D9284600F09DFF01303C -:100A500040F068810435F3E7234B00251D70214BDE -:100A6000B8465D603E46A7E7002E3FF45BAF0BF053 -:100A70000B030B2B7FF456AF1B4B0220187001F0B9 -:100A800047F8322000F036FFB0F10009FFF64AAF18 -:100A900019F003077FF446AF0E4A926809EB05038D -:100AA00093423FF63FAFB9F5807F3FF73BAF124B24 -:100AB0000193B94522DD4FF47A7000F01BFF0390DB -:100AC000039A002AFFF62EAF019B039A03F8012B2D -:100AD0000137EDE700230020682400205023002088 -:100AE000010700086C240020642300200423002058 -:100AF000082300200C23002068230020C820FFF7D3 -:100B0000EBFD074600283FF40DAF1F2D11D8C5F1AE -:100B100020024A450AAB25F0030028BF4A46834914 -:100B20000192184401F008F8019A8048FF2101F071 -:100B300029F84FEAA9037D490193C9F387022846A2 -:100B400001F028F8064600283FF46AAF019B05EB48 -:100B5000830531E70220FFF7BFFD00283FF4E2AE36 -:100B600000F05AFF00283FF4DDAE0027B946704B75 -:100B70009B68BB4218D91F2F11D80A9B01330ED096 -:100B800027F0030312AA134453F8203C0593484668 -:100B9000042205A901F0C0F804378146E7E738468A -:100BA00000F0F2FE0590F2E7CDF81490042105A8BC -:100BB00000F0BEFE00E70023642104A8049300F0C7 -:100BC000ADFE00287FF4AEAE0220FFF785FD0028C1 -:100BD0003FF4A8AE049800F007FF0590E6E7002375 -:100BE000642104A8049300F099FE00287FF49AAED3 -:100BF0000220FFF771FD00283FF494AE049800F046 -:100C000003FFEAE70220FFF767FD00283FF48AAE02 -:100C100000F012FFE1E70220FFF75EFD00283FF43D -:100C200081AE05A9142000F00DFF042107460490B1 -:100C300004A800F07DFE3946B9E7322000F05AFEE4 -:100C4000071EFFF66FAEBB077FF46CAE384A9268A2 -:100C500007EB0A0393423FF665AE0220FFF73CFD27 -:100C600000283FF45FAE27F003075744BA453FF42E -:100C7000A3AE504600F088FE0421059005A800F0C0 -:100C800057FE0AF1040AF1E74FF47A70FFF724FDEA -:100C900000283FF447AE00F0BFFE002844D00A9B76 -:100CA00001330BD008220AA9002000F073FF0028AE -:100CB0003AD02022FF210AA800F064FFFFF714FDBC -:100CC0001C4802F02DFF13B0BDE8F08F002E3FF45A -:100CD00029AE0BF00B030B2B7FF424AE0023642111 -:100CE00005A8059300F01AFE074600287FF41AAE07 -:100CF0000220FFF7F1FC814600283FF413AEFFF716 -:100D0000F3FC41F2883002F00BFF059800F0B8FFC9 -:100D10004E4600F083FF3C46B0E506464CE64FF0F9 -:100D2000000AFFE5B8467BE6374679E668230020EF -:100D300000230020A0860100094A136849F26900D7 -:100D400099B21B0C00FB01331360064B186844F288 -:100D5000506182B2000C01FB0200186080B2704743 -:100D60001C2300201823002010B500211022044667 -:100D700000F008FF034B03CB206061601868A0609F -:100D800010BD00BF107AFF1F2DE9F043204DBBB00E -:100D900000F0BEFFAB68C31AF92B32D906AFA860CA -:100DA0002B4628220021384601F04AFC05F10E00AE -:100DB00000F0E0FE002604465FFA80F905F10E0817 -:100DC000F3B2F100994501F1280107D908EB0603B8 -:100DD0000822384601F034FC0136F1E708230122ED -:100DE000CDE9023205340B4B0193A4B230230093BA -:100DF000CDE9047404A3D3E90023297B064801F05C -:100E000037FA3BB0BDE8F08378F6339F93CACD8DB7 -:100E1000B0340020BD3400208C34002070B50D4665 -:100E200014461E4601F0BAF950B9022E10D1012C19 -:100E30000ED112A3D3E90023C5E90023012007E066 -:100E4000282C10D005D8012C09D0052C0FD000205B -:100E500070BD302CFBD10BA3D3E90023ECE70BA32F -:100E6000D3E90023E8E70BA3D3E90023E4E70BA3CE -:100E7000D3E90023E0E700BFAFF30080401DA120CD -:100E800026812A0B78F6339F93CACD8D9E6AC421A2 -:100E9000818A46EE26417272DF25D7B7F017304AB5 -:100EA00039059E5613B504462346084620220021E4 -:100EB000019001F0C5FB22790198032A234628BF3F -:100EC000032203F8042F2021022201F0B9FB6279EA -:100ED0000198072A234628BF072203F8052F22215D -:100EE000032201F0ADFBA2790198072A234628BF0F -:100EF000072203F8062F2521032201F0A1FB019808 -:100F000004F108031022282101F09AFB382002B0D6 -:100F100010BD00002DE9F04FADF5017D21AD0EAE05 -:100F200040F2751280460F4622A80021296000F089 -:100F300029FE48220021304600F024FE00F0E8FEA1 -:100F4000564B4FF47A72B0FBF2F0186093E807004A -:100F5000012386E807000DF15A003382FFF704FFF2 -:100F60004FF20363338407AB18464D4904F0C4FBCA -:100F70001B2230642946304686F83C20FFF792FF5A -:100F800012AB044601460822284601F059FB08220C -:100F9000A1180DF14903284601F052FB0DF14A0357 -:100FA000082204F11001284601F04AFB13AB20226D -:100FB00004F11801284601F043FB14AB402204F170 -:100FC0003801284601F03CFB16AB082204F17801F9 -:100FD000284601F035FB0DF15903082204F1800188 -:100FE000284601F02DFB04F1880A0DF15A0904F599 -:100FF000847B4B465146082228460AF1080A01F034 -:101000001FFBD34509F10109F3D11BAB0822594657 -:10101000284601F015FB04F588744FF0000996F896 -:1010200034304B450AD9B36B21464B44082228463D -:1010300001F006FB083409F10109F0E74FF000095F -:1010400096F83C304B4504EBC90108D9336C0822B3 -:101050004B44284601F0F4FA09F10109F0E70023B6 -:101060000393BB7E0293073107F119030193C1F388 -:10107000CF010123CDE904510093F97E05A3D3E903 -:101080000023404601F0F4F80DF5017DBDE8F08F36 -:10109000AFF300809E6AC421818A46EE742400204A -:1010A00008570008014B1870704700BF80240020CB -:1010B000F0B5334B1C7B85B034B1324B0E221A8114 -:1010C0000024204605B0F0BD2F4A1068516802ABDD -:1010D00003C308232D492E480DEB030204F0EAFA5E -:1010E000054630B9274B2B480A221A8100F0CAFD69 -:1010F000E6E70169B1F5702F06D9224B26480B228D -:101100001A8100F0BFFDDCE7438B40F2F6329342D8 -:1011100007D01C490C2008811946204800F0B2FD78 -:10112000CFE71F4A024402F11003994204D2154B43 -:101130001C4810221A81E4E710398E1A20461449FF -:1011400000F0EAFD3246074605F11801204600F09E -:10115000E3FDAB689F4202D1EB6898420AD0094B8D -:101160000D221A810090D5E902123B460E4800F08C -:1011700089FDA5E70D4800F085FD0124A1E700BF2A -:10118000B034002074240020B5570008DCFF0E00A6 -:101190000000010824570008305700084257000893 -:1011A0000800FFF7605700087D570008A6570008A1 -:1011B0002DE9F04FADB006AF80460C4600F0EEFFD3 -:1011C000054600285AD1237E022B1BD1E38A012B2E -:1011D00018D100F09DFD0646FFF7AEFD03464FF423 -:1011E000C870DFF8D092B3FBF0F206F5167602FB7A -:1011F000103316FA83F3C9F80030E37E33B9A84BF5 -:1012000000221A709C37BD46BDE8F08FA38AEEB26B -:10121000013BB34205F101050BD93B1D1E44E9001A -:1012200000960023082201F0F801204601F0CCF8D6 -:10123000ECE707F11400FFF797FD324607F11401C0 -:10124000381D04F027FA0028D9D10F2E08D8944B66 -:101250001E70D9F80030A3F51673C9F80030D1E735 -:10126000FB1CF8700146009307220346204601F05C -:10127000ABF8F978404600F089FFC3E7E38A282BF2 -:1012800026D010D8012B1ED0052BBBD1BFF34F8F1A -:101290008449854BCA6802F4E0621343CB60BFF314 -:1012A0004F8F00BFFDE7302BACD1637E7F4D013304 -:1012B0006A7BDBB29342E94603D1E27E2B7B9A4202 -:1012C00065D0CD469EE721464046FFF723FE99E7CD -:1012D000A38A013B9BB2C92B94D8744D2E7B26BBAD -:1012E00005F10C030093082233463146204601F0F5 -:1012F0006BF8731CF2B2D9001E46A38A013B9A42D6 -:1013000005DA0E322A44009200230822EEE7002379 -:101310000022C5E900230023AB6085F8D730C5F86B -:10132000D8302B7B0BB9E37E2B73002507F1140912 -:101330003B1D082229464846C7E90155FD6001F0DA -:101340007FF93B7A05F1010AAB424FEACA0608D998 -:10135000FB6808222B443146484601F071F9554696 -:10136000EFE7C6F3CF06E17ECDE9049600230393B1 -:10137000A37E0293193428230093019446A3D3E952 -:101380000023404600F074FFFFF7FEFC3AE74FF001 -:10139000000807F11403A7F81480102200934146B7 -:1013A0000123204601F010F8A68A023EB6B2F31CD3 -:1013B0009B109B000733DB08A9EBC3039D460DF18F -:1013C000180A1FFA88F34FEAC801B34201F110016D -:1013D0000AD20AEB0803009308220023204600F0FB -:1013E000F3FF08F10108ECE795F8D70000F0DAFA0E -:1013F000D5F8D83004461BB995F8D70000F0E2FACA -:10140000D5F8D83033449C4204D295F8D700013047 -:1014100000F0D8FA4FEA960B4FF000081FFA88F157 -:101420008B45D5E9003209D90AEB880103EB880026 -:10143000012200F0AFFB08F10108EFE7F31842F1D9 -:101440000002C5E90032D5F8D83095F8D70006EB90 -:101450000308C5F8D88000F0A5FA804509D395F8AF -:10146000D730D5F8D8000133001B85F8D730C5F840 -:10147000D800FF2E08D800232B7300F0CDFAFFF719 -:1014800017FE08B1FFF76EF92B68094A9B0A013372 -:1014900013810023AB6014E726417272DF25D7B7B2 -:1014A0008534002000ED00E00400FA05B03400208F -:1014B000742400208834002008B54FF000530B4AF4 -:1014C000196891420AD10A4A597D117009481B7D59 -:1014D00003730949C9220E3000F02EFBBDE8084015 -:1014E000E02200214FF0005000F04CBB9AAD44C503 -:1014F00080240020B0340020160000202DE9FF4198 -:10150000434C02236371002302932A250A23581EA9 -:10151000B5FBF3F67343D3F12A02C1B23ED00228E1 -:101520000346F4D19DF80B303A493B485A1E9DF8CA -:101530000A30013B1B0443EA0253BDF80820013A7C -:1015400013434B6001F028FD00230193334B3449D2 -:1015500000933448344B4FF4805200F0F1FD334B8C -:10156000197811B12F4800F011FE00F0D1FB0546AB -:10157000FFF7E2FB4FF4C873B0FBF3F202FB130377 -:1015800005F5167010FA83F0294B186002F012FF6F -:1015900008B10F23238104B0BDE8F081C1EBC1077E -:1015A000FB1C4FEAE30EC3F3C703A1EB030C0EF1E0 -:1015B00001084FF47A705FFA8CF50EFB000058FAC0 -:1015C0008CFCB0FBFCF0B0F5617F07D97B1EC3F348 -:1015D000C703C91ACDB2591E0F2916D86A1E072A89 -:1015E0008CBF00220122591901FB06601149B1FB91 -:1015F000F0F11148814295D1002A93D0ADF80860EE -:101600008DF80A308DF80B508CE71346EBE700BFDE -:101610007424002010230020C83500201D0E00086F -:10162000842400208C340020B11100088024002084 -:101630008834002080DE800240420F002DE9F04F08 -:1016400091A7D7E900670FF24829D9E90089874DAA -:1016500093B0DFF844B2864C284600F06DFE0DF1E1 -:10166000300A079070B310220021504600F08AFA29 -:10167000079B197B4FF0000261F303028DF83020C5 -:10168000586899680EAA03C21B680D9A63F31C027E -:101690009DF830300D9243F020038DF83030002358 -:1016A00052461946584601F087FC079028B928464B -:1016B00000F046FE079B2370CEE72378072B3CD82B -:1016C0000133237018220021504600F05BFADFF846 -:1016D000C8B1684C002319465246584601F094FCA4 -:1016E000014670BB102208A800F04CFA636983F42D -:1016F0008043636100F00EFB0B4612A9024611E91C -:1017000003000DF1240C8CE803009DF83410C1F3A4 -:10171000030089064CBF0E99BDF838C08DF82C0027 -:1017200046BFC1F31C0C4CF00041CCF30A010891F8 -:10173000284608A900F0CCFFCCE7284600F000FEC0 -:10174000C0E7284600F02AFD0446002848D1DFF80B -:101750004CB100F0DDFADBF80030984240D300F0E5 -:10176000D7FA0790FFF7E8FA079A8DF8204003466A -:101770004FF4C87002F51672B3FBF0F101FB1033A1 -:1017800012FA83F3CBF80030DFF814B19BF80010A5 -:1017900011B901238DF8203050460791FFF7E4FA84 -:1017A0000799C1F11004E4B2062C28BF0624224692 -:1017B00051440DF1210000F0BFF908AB0393182349 -:1017C000029301342C4B0193E4B20123009304945F -:1017D0003B463246284600F0E3FC00238BF80030FD -:1017E00000F096FA254A264C1368C31AB3F57A7F9F -:1017F00031D3106000F08EFA02460B46284600F006 -:10180000A9FD284600F0CAFC28B3237BDFF894B07A -:10181000002B14BF032302238BF8053000F078FA65 -:101820004FF47A735146B0FBF3F0CBF80000584602 -:10183000FFF738FB182307300293124B0193C0F3D4 -:10184000CF0040F25513CDE903A0009342464B462A -:10185000284600F0A5FC237B2BB1FFF795FA237BEC -:10186000002B7FF4F6AE13B0BDE8F08F8C3400206F -:10187000953500200000024084340020903500207F -:10188000B034002094350020401DA12026812A0B71 -:10189000F1C6A7C1D068080FC835002088340020E1 -:1018A000853400207424002070B50F4B1B78013361 -:1018B000DBB2012B0C4611D80C4D29684FF47A731A -:1018C0000E6AA2FB0332014622462846B0478442F4 -:1018D00004D1074B00221A70012070BD4FF4FA703A -:1018E00002F01EF90020F8E720230020B037002086 -:1018F000C435002007B50023024601210DF1070081 -:101900008DF80730FFF7D0FF20B19DF8070003B036 -:101910005DF804FB4FF0FF30F9E700000A4608B518 -:101920000421FFF7C1FF80F00100C0B2404208BDB2 -:1019300030B4054C2368DD69044B0A46AC460146C9 -:10194000204630BC604700BFB0370020A0860100B1 -:1019500070B502F095FB094E094D308000242868CF -:101960003388834208D902F085FB2B680444013395 -:10197000B4F5803F2B60F2D370BD00BFC6350020A8 -:101980009835002002F02ABC00F1006000F580309C -:101990000068704700F10060920000F5803002F0AE -:1019A000B5BB0000054B1A68054B1B889B1A834288 -:1019B00002D9104402F05EBB002070479835002029 -:1019C000C635002038B5074D04462868204402F08B -:1019D00059FB28B928682044BDE8384002F06ABBAA -:1019E00038BD00BF9835002010F003030AD1B0F5D0 -:1019F000047F05D200F10050A0F51040D0F8003867 -:101A0000184670470023FBE700F10050A0F5104096 -:101A1000D0F8100A70470000064991F8243033B11D -:101A20000023086A81F824300822FFF7B3BF0120A1 -:101A3000704700BF9C350020014B1868704700BFFD -:101A4000002004E070B52A4B1B68C3F30B02044668 -:101A50001B0C62B140F21340824230D040F2194078 -:101A600082422ED040F2214082422CD10322214DCD -:101A70000C2000FB0252556842F20102934224D02E -:101A8000B3F5805F23D041F20102934221D041F2AD -:101A9000030293421FD041F20702934214BF3F2337 -:101AA0003123013C0C44013D0A46A24215D215F9EE -:101AB000016F501C9EB100F8016C0246F5E701224F -:101AC000D5E70222D3E70C4DD6E73323E9E74123DC -:101AD000E7E75A23E5E75923E3E7104605E02C251D -:101AE0008442157001D9901C5370401A70BD00BF1C -:101AF000002004E0EC570008C0570008022802BF8D -:101B0000024B4FF080429A61704700BF00000240D4 -:101B1000022802BF024B4FF480429A61704700BF17 -:101B200000000240022801BF024A536983F4804347 -:101B3000536170470000024010B50023934203D068 -:101B4000CC5CC4540133F9E710BD000010B5013876 -:101B500010F9013F3BB191F900409C4203D11AB109 -:101B60000131013AF4E71AB191F90020981A10BD39 -:101B70001046FCE703460246D01A12F9011B002961 -:101B8000FAD1704702440346934202D003F8011B86 -:101B9000FAE770472DE9F8431F4D144695F82420C5 -:101BA0000746884652BBDFF870909CB395F8243006 -:101BB0002BB92022FF2148462F62FFF7E3FF95F85B -:101BC0002400C0F10802A24228BF2246D6B24146F4 -:101BD000920005EB8000FFF7AFFF95F82430A41BBF -:101BE0001E44F6B2082E17449044E4B285F82460EF -:101BF000DBD1FFF711FF0028D7D108E02B6A03EBF8 -:101C000082038342CFD0FFF707FF0028CBD100200B -:101C1000BDE8F8830120FBE79C350020024B1A78D1 -:101C2000024B1A70704700BFC435002020230020EB -:101C300010B50F4C0F4801F089FA21460D4801F00C -:101C4000B1FA24680C48626DD2F8043843F00203FC -:101C5000C2F8043801F064FF0849204601F0A8FBEF -:101C6000626DD2F8043823F00203C2F8043810BDC4 -:101C7000E0580008B037002040420F00E858000844 -:101C8000704700000FB4002004B0704700B59BB04F -:101C9000EFF3098168226846FFF74EFFEFF30583F3 -:101CA000044B9A6BDA6A9A6A9A6A9A6A9A6A9A6A88 -:101CB0009B6AFEE700ED00E000B59BB0EFF3098101 -:101CC00068226846FFF738FFEFF30583044B9A6BF1 -:101CD0009A6A9A6A9A6A9A6A9A6A9B6AFEE700BF47 -:101CE00000ED00E000B59BB0EFF309816822684683 -:101CF000FFF722FFEFF30583034B5A6B9A6A9A6A48 -:101D00009A6A9A6A9B6AFEE700ED00E0FEE700002F -:101D100002F09EBA02F076BA30B5094D0A449142FB -:101D20000DD011F8013B5840082340F30004013B5B -:101D30002C4013F0FF0384EA5000F6D1EFE730BDEA -:101D40002083B8ED2DE9F041C56915B9C161BDE841 -:101D5000F0814B6823F06047C3F38A464FEAD37E95 -:101D6000C3F3807816EA230638BF3E46AC462B46BE -:101D70005A68BEEBD27F22F060440AD0002A18DAFB -:101D8000A40CB44217D19D420FD10D60DEE713467B -:101D9000EEE7A74207D102F08044C2F380724245C9 -:101DA0000BD054B1EFE708D2EDE7CCF800100B6090 -:101DB000CDE7B44201D0B442E5D81A689C46002A67 -:101DC000E5D11960C3E700002DE9F047089D01F057 -:101DD00007044FEAD508224405F0070500EBD100BF -:101DE0004FF47F49944201D1BDE8F08704F0070722 -:101DF00005F0070A57453E4638BF5646C6F1080665 -:101E0000111B8E4228BF0E46E10808EBD50E415C3F -:101E100013F80EC0B94029FA06F721FA0AF1FFB209 -:101E20008CEA010147FA0AF739408CEA010C03F801 -:101E30000EC034443544D5E780EA0120082341F23E -:101E4000210201B24000002980B203F1FF33B8BF84 -:101E5000504013F0FF03F4D17047000038B50C4632 -:101E60008D18A54200D138BD14F8011BFFF7E4FF1F -:101E7000F7E7000002684AB113680360C38801896C -:101E800001339BB29942C38038BF0381104670472B -:101E900070B588B0202204460D4668460021FFF741 -:101EA00071FE20460495FFF7E5FF024658B16B46E8 -:101EB000054608AE1C4603CCB44228606960234640 -:101EC00005F10805F6D1104608B070BD10B54B6895 -:101ED00023B9CA8A63F30902CA8210BDC4681A68AA -:101EE0001C60C360438A013B43824A60EFE7000005 -:101EF0002DE9F84F1D46CB8A0F46C3F30901062989 -:101F0000814692460B4630D00020AAB207F1190450 -:101F10009EB2052E1FFA80F80FD8904503F10103F9 -:101F200006D3FB8A0A4462F30903FB8201201AE00C -:101F30001AF80060E6540130EAE79045F1D2A1F1C9 -:101F4000060B1C237C68BBFBF3F203FB12BB1FFADE -:101F50008BF6002C45D14846FFF78CFF044638B974 -:101F600078606FF00200BDE8F88F4FF00008E6E7F8 -:101F7000002606607860ADB24FF0000B454510D9E1 -:101F80000AEB0803221D13F8011B9155B1B208F1A9 -:101F900001081B291FFA88F82BD0454506F10106D8 -:101FA000F1D8FB8AC3F30902154465F30903BCE7C2 -:101FB000013292B21C462368002BF9D1AB1F0B44AF -:101FC0001C21B3FBF1F301339BB29A42D3D2BBF194 -:101FD000000FD0D14846FFF74DFF20B9C4F800B03C -:101FE000BFE70122E7E7C0F800B05E462060044684 -:101FF000C1E74545D5D94846FFF73CFF08B9206001 -:10200000AFE7C0F800B0002620600446B6E7000045 -:102010002DE9F04F2DED028B83B0CDE90013BDF813 -:102020003C4080469246002A00F087802CB10E9BEF -:10203000002B00F08280072C2BD808F10C00FFF752 -:1020400019FF054638B96FF00205284603B0BDEC0C -:10205000028BBDE8F08F14220021FFF793FD22468A -:102060000E9905F10800FFF767FD631C2B749AF8C1 -:1020700000302C4403F01F0363F03F032372009BE6 -:1020800043F00041696040462946FFF75BFE0125A9 -:10209000DBE700F10C034FF0000908EE103A4FF0B7 -:1020A000800B4E464D4618EE100AFFF7E3FE07463A -:1020B0000028C8D014220021FFF764FD002E3AD179 -:1020C000019B3B8102220E9B02F1080103EB060CEF -:1020D00057FA81F11046B44202F10102D2B201D89E -:1020E000024607E01CF8010B01F8010B0136062A35 -:1020F000B6B2EFD99AF8001001F01F01B44208BF40 -:102100004FF0400BB81841EA49114BEA0103037242 -:10211000009B013243F000437B603A7439464046ED -:10212000FFF710FE0135B4422DB289F001094FF0DE -:10213000000BB8D189E70022C5E76FF0010584E7FD -:10214000F8B515460E462422002104461F46FFF727 -:1021500019FD069B6360B5F5001F079BA76034BFA0 -:102160006A094FF6FF72236204F10C0097B2002354 -:102170009A4205D80023036027826382A382F8BDB8 -:102180000660013330462036F2E7000003781BB9C1 -:102190004BB2002BC8BF0170704700000078704739 -:1021A0002DE9F74FDDF83C90BDF830500D9E9DF8BD -:1021B0003840BDF84070804692469B46B9F1000F0A -:1021C00001D1002F51D11F2C4FD898F80000B0B981 -:1021D000072F47D835F0030347D13A4649464FF613 -:1021E000FF70FFF73BFE20F001002D02400445EA9E -:1021F0000464400C44EA40244FF6FF7321E040EAB7 -:102200000520072F40EA0464F6D900254FF6FF7336 -:10221000C5F12000A5F120022AFA05F10BFA00F021 -:1022200001432BFA02F211431846C9B2FFF704FE2C -:102230000835402D0346EBD13A464946FFF70EFEDE -:102240000346CDE90097324621464046FFF7E0FEBF -:1022500033780133DBB21F2B88BF0023337003B008 -:10226000BDE8F08F6FF00300F9E76FF00100F6E7CB -:102270002DE9F04F85B09246DDF848800F9D9DF81E -:1022800040209DF84490BDF84C7006469B46B8F13E -:10229000000F01D1002F48D11F2A46D83378002BD8 -:1022A00046D00C0244EA02649DF8381044EAC9346E -:1022B00044EA01441C43072F44F0800432D9002330 -:1022C0004FF6FF72C3F1200CA3F120002AFA03F1AC -:1022D0000BFA0CFC41EA0C012BFA00F00143C9B2E5 -:1022E00010460393FFF7A8FD039B0833402B0246DB -:1022F000E8D13A464146FFF7B1FD0346CDE90087F4 -:102300002A4621463046FFF783FEB9F1010F06D178 -:102310002B780133DBB21F2B88BF00232B7005B055 -:10232000BDE8F08F4FF6FF73E8E76FF00100F6E7C6 -:102330006FF00300F3E70000C06900B1043070479C -:10234000C3691A68C261C2681A60C360438A013BEC -:10235000438270472DE9F041D0F81880194E144699 -:102360001D464146002709B9BDE8F081D1E90223A5 -:10237000A21A65EB0303964277EB03031ED283692F -:102380008B420DD1FFF7A2FD83691B688361C3688F -:102390000B60438AC1608169013B43828846E2E762 -:1023A000FFF794FD0B68C8F80030C3680B60438AE0 -:1023B000C160013B4382D8F80010D4E78846096821 -:1023C000D1E700BF80841E002DE9F04F8BB00D4691 -:1023D000DDF8509014469B468046002800F0198195 -:1023E000B9F1000F00F01581531E3F2B00F211814F -:1023F000012A03D1BBF1000F40F00B810023CDE98E -:102400000833B8F81430B5EBC30F4FEAC30703D352 -:1024100000200BB0BDE8F08F2B199F42D8F80C308C -:102420003ABF7F1BFFB227461BB9D8F81030002BEC -:102430007AD02F2D4ED8C5F13006B7424FF00003A9 -:102440002CBFF6B23E4600932946D8F8080008ABE8 -:102450003246FFF7B9FCA7EB060A35445FFA8AFA61 -:10246000B8F8143003F10053063BDB000493D8F8AE -:102470000C3003933021039B13B1BAF1000F2CD120 -:10248000D8F8100040B1BAF1000F05D0009608ABA3 -:102490005246691AFFF798FC38B2002FB8D0660789 -:1024A0000AD00AAB03EBD401624211F8083C02F0F7 -:1024B0000702134101F8083C082C3CD9102C40F2CB -:1024C000B580202C40F2B780BBF1000F00F09C805B -:1024D000082334E0BA460026C2E7049BE02B28BF5D -:1024E000E02306930B44AB42059314D95A1B03987F -:1024F0000096924534BF5246D2B2691A08AB0430F6 -:102500000792FFF761FC079A1644AAEB020A1544EA -:10251000F6B25FFA8AFA049B069A05999B1A04930D -:10252000039B1B680393A6E70093D8F8080008AB49 -:102530003A462946AEE7BBF1000F13D00123B4EBB6 -:10254000C30F6CD0082C12D89DF82030621E23FADD -:1025500002F2D50706D54FF0FF3202FA04F4234306 -:102560008DF820309DF8203089F8003051E7102C8C -:1025700012D8BDF82030621E23FA02F2D10706D528 -:102580004FF0FF3202FA04F42343ADF82030BDF8D7 -:102590002030A9F800303CE7202C0FD80899631EA2 -:1025A00021FA03F3DA0705D54FF0FF3202FA04F4FB -:1025B0000C430894089BC9F800302AE7402C2BD024 -:1025C000DDE90865611EC4F12102A4F1210326FAA8 -:1025D00001F105FA02F225FA03F311431943CB077F -:1025E00012D50122A4F12003C4F1200102FA03F361 -:1025F00022FA01F1A240524243EA010363EB430392 -:1026000032432B43CDE90823DDE90823C9E9002340 -:10261000FFE66FF00100FCE66FF00800F9E6082C19 -:10262000A0D9102CB3D9202CEED8C3E7BBF1000FF2 -:10263000ADD0022383E7BBF1000FBBD004237EE7BC -:1026400030B5012A144638BF0124402C85B028BF7C -:1026500040240025012ACDE9025518D81B788DF8B1 -:10266000083063070AD004AB03EBD405624215F8C7 -:10267000083C02F00702934005F8083C009103462D -:102680002246002102A8FFF79FFB05B030BD082AB3 -:10269000E4D9102A03D81B88ADF80830E1E7202AD6 -:1026A0008DBFD3E900231B680293CDE90223D8E74D -:1026B00010B5CB681BB98B600B618B8210BDC468F1 -:1026C0001A681C60C360438A013B4382CA60F0E71A -:1026D0002DE9F04FD1F8008093B018F0800FCDE9CC -:1026E0000323C8F3C01219BFC8F3C03BC8F30626C2 -:1026F0004FF0020B1646B8F1000F04460D4680F26B -:10270000C58118F0C043059340F0C0810B7B002BBE -:1027100000F0BC81BBF1020F03D00178B14240F060 -:10272000B88108F07F0106916AB3C8F3074A2B44C9 -:10273000069A93F80390760646EA0B4646EA8246E6 -:102740005FEAD91346EA0A06079300F09080002258 -:102750000023CDE90A23069B009367685B46524637 -:102760000AA92046B84700287ED0A7699FB93146FC -:1027700004F10C00FFF78CFB0746E0B96FF0020094 -:1027800013B0BDE8F08FC8F30F2A18F07F0F08BF11 -:102790000AF0030ACBE73B699E420DD03F68002F49 -:1027A000F9D1314604F10C00FFF772FB074600280F -:1027B000E4D0A3693B60A761DDE90A2300264FF658 -:1027C000FF70C6F1200E22FA06F103FA0EFEA6F102 -:1027D000200C23FA0CFC41EA0E0141EA0C01C9B2BB -:1027E000083609920893FFF727FB402EDDE90832EF -:1027F000E7D1B882FB7D09F01F06C3F38403F31A07 -:10280000D7E9022198B2002BBCBF00F120031BB214 -:1028100052EA0100C8F304680FD00398821A0498A2 -:1028200060EB0101A14890424FF000028A4104D3BD -:10283000079A002A55D0012B23DDFA7D4FEA890340 -:1028400002F0030203F07C031343FB753946204674 -:10285000FFF73CFB079BA3B9FB7DC3F38402013266 -:1028600062F38603FB7504E06FF00B0088E7A7694D -:1028700017B96FF00C0083E73B699E42BAD03F68FE -:10288000F6E719F0400F2CD0039BBB60049BFB6064 -:10289000142200210DA8FFF775F9039B0A93049BEE -:1028A0000B932B1D0C932B7BADF83EA0013BDBB2B1 -:1028B000ADF83C30069B8DF843308DF840B0A368EE -:1028C0008DF841608DF842800AA920469847FB7D2B -:1028D000C3F38403013303F01F039B02FB82002038 -:1028E0004EE7FB7DC9F34012B2EBD31F40F0D4801A -:1028F000C3F38403B34240F0D28007992B7B4FEAA5 -:102900009912002934D0D20741D4032B40F2CA8057 -:10291000039BBB60049BFB602B7BAE1D033BDBB2C8 -:102920003246394604F10C00FFF7E2FA00280DDACE -:1029300020463946FFF7CAFAFB7DC3F3840301330F -:1029400003F01F039B02FB82032019E7AB883B8344 -:102950002A7B033AB88AD2B23146FFF77FFAFB7D71 -:10296000B882DA43C2F3C01262F3C713FB75B6E74D -:102970006AB92E1D013BDBB23246394604F10C0028 -:10298000FFF7B6FA0028D3DB2A7B013AE2E7F98A9F -:10299000C1F30901013B0529DAB253D8281D0023F0 -:1029A00007F11A0C9A4208D910F801EB0CF801E073 -:1029B000013101330629DBB2F4D103990A9104995C -:1029C0000B91934207F11A010C9138BF04337968D7 -:1029D0000D9134BF55FA83F300230E93FB8AADF8B3 -:1029E0003EA0C3F309031A44069B8DF8433000232D -:1029F000ADF83C208DF840B08DF841608DF84280F4 -:102A00007B602A7BB88A013A291DFFF727FA3B8BA6 -:102A1000B882834203D1A3680AA92046984720467A -:102A20000AA9FFF745FEFB7DB88AC3F3840301338F -:102A300003F01F039B02FB823B8B984214BF1120C3 -:102A400000209DE67B68002BB7D0062001E01C30FB -:102A50006346D3F800C0BCF1000FF8D1091A081D75 -:102A600005F1040C00EB030905989DF8143001EB07 -:102A7000000EBEF11B0FA0D89A429ED91CF8013B54 -:102A800009F8013B059B01330593EDE76FF0090061 -:102A900076E66FF00A0073E66FF00D0070E66FF0F7 -:102AA0000E006DE66FF00F006AE600BF80841E0026 -:102AB000404BF0B51C6C404E44F000741C641D6E1D -:102AC00045F000751D661B6E3C4B9B6AD3F80052A7 -:102AD000354045F00105C3F80052D3F800423440B8 -:102AE00044EA002040F00100C3F80002002952D05F -:102AF0000020C3F81C020546C3F80402C3F80C0208 -:102B0000C3F8140203EBC00401301C28C4F840527F -:102B1000C4F84452F6D100254FF0010C9678148881 -:102B2000F70748BFD3F804720CFA04F044BF074318 -:102B3000C3F80472B70742BFD3F80C720743C3F857 -:102B40000C72760742BFD3F814620643C3F81462CE -:102B500003EBC4045668C4F840629668C4F8446243 -:102B6000D3F81C4201352043A942C3F81C0202F1EC -:102B70000C02D3D1D3F8002222F00102C3F80022C4 -:102B80000C4B1A6C22F000721A641A6E22F000725A -:102B90001A661B6EF0BD0122C3F84012C3F844123E -:102BA000C3F80412C3F81412C3F80C22C3F81C2291 -:102BB000E0E700BF003802400000FFFFC8350020FA -:102BC000184A916A08B58B688B6013F0010104D034 -:102BD00013F00C0F18BF4FF48031D80506D513F44D -:102BE000406F14BF41F4003141F00201D80306D513 -:102BF00013F4402F14BF41F4802141F00401D36944 -:102C00000BB108489847202383F311880648002118 -:102C100000F0AEFF002383F31188BDE8084001F007 -:102C200003BC00BFC8350020D035002038B5124C99 -:102C3000A36ADD68AA0712D05A6922F002025A611B -:102C4000A36913B1012120469847202383F31188FB -:102C50000A48002100F08CFF002383F31188EB0663 -:102C600006D5A36A1021D960236A0BB102489847A0 -:102C7000BDE8384001F0D8BBC8350020D835002069 -:102C800038B5124CA36A1D69AA0712D05A6922F0FE -:102C900010025A61A36913B10221204698472023EC -:102CA00083F311880A48002100F062FF002383F3B8 -:102CB0001188EB0606D5A36A10211961236A0BB1AE -:102CC00002489847BDE8384001F0AEBBC835002047 -:102CD000D835002038B50F4CA36A5D685D602A07BF -:102CE0000AD5042222701A6822F002021A60636A6E -:102CF00013B10021204698476B0706D5A36A99694E -:102D0000236A13B1034809049847BDE8384001F02D -:102D10008BBB00BFC835002010B50E4C204600F01C -:102D200029F90D4BA3620B21132000F00BF90B21A5 -:102D3000142000F007F90B21152000F003F90B21F6 -:102D4000162000F0FFF80022BDE8104011460E20CA -:102D5000FFF7AEBEC835002000640040114B98421A -:102D600010B5044609D1104B1A6C42F000721A6477 -:102D70001A6E42F000721A661B6EA36A01221A6074 -:102D8000A36A5A68D20707D5626851681268D96188 -:102D90001A60064A5A6110BD0121082000F0D4FDD6 -:102DA000EEE700BFC8350020003802405B87010015 -:102DB00003291AD8DFE801F0020A0F14836A9B681E -:102DC00013F0E05F14BF012000207047836A986809 -:102DD000C0F380607047836A9868C0F3C060704732 -:102DE000836A9868C0F30070704700207047000045 -:102DF00010B5032925D8DFE801F00225292D836AC3 -:102E00009968C1F30161183103EB0113107884064E -:102E10004CBF54689488C0F300114FEA410148BF89 -:102E200041EAC40100F00F004CBF41F0040141EA47 -:102E30004451586041F001019068D2689860DA60AE -:102E4000196010BD836A03F5C073DFE7836A03F579 -:102E5000C873DBE7836A03F5D073D7E701290AD08B -:102E600002290FD081B9836ADA68920701D1186903 -:102E700003E001207047836AD86810F0030018BF90 -:102E800001207047836AF2E70020704710B539B916 -:102E9000836AD96889071BD11B699C0704D110BDBF -:102EA000012915D00229FAD1816AD1F8C031D1F8AF -:102EB000C441D1F8C8011061D1F8CC015061202083 -:102EC00008610869800717D1486940F0100012E0D6 -:102ED000816AD1F8B031D1F8B441D1F8B8011061AC -:102EE000D1F8BC0150612020C860C868800703D1B8 -:102EF000486940F002004861C3F34000C3F3800119 -:102F0000000140EA4111107920F0300001431171B5 -:102F100089064BBF91681189DB085B0D4CBF63F3D9 -:102F20001C0163F30A01137948BF916064F3030342 -:102F300013714FEA14234FEA144458BF11811370E0 -:102F40005480ACE700F1604303F561430901C9B265 -:102F500083F80013012200F01F039A4043099B00ED -:102F600003F1604303F56143C3F880211A607047A1 -:102F7000FFF7D2BE012300F10802C0E9022203706C -:102F800000F110020023C0E90422C0E90633C0E9C1 -:102F9000083343607047000010B52023044683F3D4 -:102FA0001188022303704160FFF7D8FE04232370C9 -:102FB000002383F3118810BD2DE9F0411F4604461C -:102FC0000D461646202383F3118800F10808237864 -:102FD000052B0DD029462046FFF7EAFE40B12046DA -:102FE00032462946FFF704FF002080F3118808E0ED -:102FF0003946404600F0A0FD0028E8D0002383F3C6 -:103000001188BDE8F08100002DE9F0411F4604461B -:103010000D461646202383F3118800F1100823780B -:10302000052B0DD029462046FFF718FF40B120465A -:1030300032462946FFF72AFF002080F3118808E076 -:103040003946404600F078FD0028E8D0002383F39D -:103050001188BDE8F08100000268436811430160F7 -:1030600003B118477047000013B5446BD4F894348B -:103070001A681178042915D1217C022912D11979F5 -:10308000128901238B4013420CD101A904F14C0099 -:1030900001F088FFD4F89444019B2179024620680E -:1030A00000F0CEF902B010BD143001F00BBF0000EB -:1030B0004FF0FF33143001F005BF00004C3001F039 -:1030C000DDBF00004FF0FF334C3001F0D7BF0000F0 -:1030D000143001F0D9BE00004FF0FF31143001F080 -:1030E000D3BE00004C3001F0A9BF00004FF0FF320A -:1030F0004C3001F0A3BF00000020704710B5D0F89D -:1031000094341A6811780429044617D1017C0229E5 -:1031100014D15979528901238B4013420ED11430B6 -:1031200001F06CFE024648B1D4F894444FF4807329 -:1031300061792068BDE8104000F070B910BD000052 -:10314000406BFFF7DBBF0000704700007FB5124BFC -:10315000036000234360C0E90233012502260F4BC0 -:10316000057404460290019300F1840229460096FA -:103170004FF48073143001F01DFE094B0294CDE929 -:10318000006304F523724FF48073294604F14C0068 -:1031900001F0E4FE04B070BD1C5800084131000885 -:1031A000693000080B68202282F311880A7903EB4A -:1031B000820290614A79093243F822008A7912B179 -:1031C00003EB8203986102230374C0F89414002374 -:1031D00083F311887047000038B5037F044613B1AC -:1031E00090F85430ABB9201D01250221FFF734FFC0 -:1031F00004F1140025776FF0010100F0B9FC84F8A8 -:10320000545004F14C006FF00101BDE8384000F06B -:10321000AFBC38BD10B5012104460430FFF71CFFD8 -:103220000023237784F8543010BD000038B50446DD -:103230000025143001F0D6FD04F14C00257701F093 -:10324000A5FE201D84F854500121FFF705FF2046FC -:10325000BDE83840FFF752BF90F8443003F06003F8 -:10326000202B07D190F84520212A4FF0000303D8E6 -:103270001F2A06D800207047222AFBD1C0E90E334E -:1032800003E0034A82630722C2630364012070479C -:103290002123002037B5D0F894341A681178042916 -:1032A00004461AD1017C022917D119791289012308 -:1032B0008B40134211D100F14C05284601F026FF46 -:1032C00058B101A9284601F06DFED4F89444019B41 -:1032D00021790246206800F0B3F803B030BD000049 -:1032E000F0B500EB810385B09E6904460D46FEB142 -:1032F000202383F3118804EB8507301D0821FFF795 -:10330000ABFEFB685B691B6806F14C001BB10190CA -:1033100001F056FE019803A901F044FE024648B1AF -:10332000039B2946204600F08BF8002383F3118885 -:1033300005B0F0BDFB685A691268002AF5D01B8AF7 -:10334000013B1340F1D104F14402EAE7093138B5F9 -:1033500050F82140DCB1202383F31188D4F8942461 -:103360001368527903EB8203DB689B695D6845B1A2 -:1033700004216018FFF770FE294604F1140001F0E3 -:1033800047FD2046FFF7BAFE002383F3118838BDBE -:103390007047000001F00AB9012303700023C0E95F -:1033A0000133C36183620362C36243620363704794 -:1033B00038B50446202383F311880025C0E903555E -:1033C000C0E90555416001F001F90223237085F33E -:1033D000118838BD70B500EB810305465069DA608D -:1033E0000E46144618B110220021FEF7CBFBA0694F -:1033F00018B110220021FEF7C5FB31462846BDE872 -:10340000704001F0ADB90000826802F001128260E4 -:103410000022C0E90422826101F02EBAF0B400EB70 -:1034200081044789E4680125A4698D403D434581B5 -:1034300023600023A2606360F0BC01F049BA000081 -:10344000F0B400EB81040789E468012564698D40CC -:103450003D43058123600023A2606360F0BC01F05E -:10346000C3BA000070B50223002504460370C0E90A -:103470000255C0E90455C564856180F8345001F0F7 -:103480000BF963681B6823B129462046BDE87040EC -:10349000184770BD037880F85030052303704368E7 -:1034A0001B6810B504460BB1042198470023A360A4 -:1034B00010BD000090F85020436802701B680BB1EB -:1034C000052118477047000070B590F83430044665 -:1034D00013B1002380F8343004F14402204601F097 -:1034E000EDF963689B68B3B994F8443013F0600554 -:1034F00035D00021204601F03FFC0021204601F09C -:1035000031FC63681B6813B10621204698470623E7 -:1035100084F8343070BD204698470028E4D0B4F8D1 -:103520004A30E26B9A4288BFE36394F94430E56B1A -:10353000002B4FF0200380F20381002D00F0F28079 -:10354000092284F8342083F311880021D4E90E2362 -:103550002046FFF775FF002383F31188DAE794F81C -:10356000452003F07F0343EA022340F202329342F4 -:1035700000F0C58021D8B3F5807F48D00DD8012B4D -:103580003FD0022B00F09380002BB2D104F14C020B -:10359000A2630222E2632364C1E7B3F5817F00F0F6 -:1035A0009B80B3F5407FA4D194F84630012BA0D185 -:1035B000B4F84C3043F0020332E0B3F5006F4DD065 -:1035C00017D8B3F5A06F31D0A3F5C063012B90D805 -:1035D000636894F846205E6894F84710B4F8483061 -:1035E0002046B047002884D04368A3630368E363A0 -:1035F0001AE0B3F5106F36D040F6024293427FF4E2 -:1036000078AF5C4BA3630223E3630023C3E794F822 -:103610004630012B7FF46DAFB4F84C3023F0020339 -:10362000C4E90E55A4F84C30256478E7B4F844306A -:10363000B3F5A06F0ED194F8463084F84E30204692 -:1036400001F082F863681B6813B101212046984796 -:10365000032323700023C4E90E339CE704F14F03D6 -:10366000A3630123C3E72378042B10D1202383F322 -:1036700011882046FFF7C8FE85F31188032163688F -:1036800084F84F5021701B680BB12046984794F87E -:103690004630002BDED084F84F300423237063685B -:1036A0001B68002BD6D0022120469847D2E794F819 -:1036B00048301D0603F00F0120460AD501F0F0F84E -:1036C000012804D002287FF414AF2B4B9AE72B4B30 -:1036D00098E701F0D7F8F3E794F84630002B7FF431 -:1036E00008AF94F8483013F00F01B3D01A06204603 -:1036F00002D501F055FBADE701F048FBAAE794F8CD -:103700004630002B7FF4F5AE94F8483013F00F01EB -:10371000A0D01B06204602D501F02EFB9AE701F04F -:1037200021FB97E7142284F8342083F311882B4679 -:103730002A4629462046FFF771FE85F31188E9E6FF -:103740005DB1152284F8342083F311880021D4E977 -:103750000E232046FFF762FEFDE60B2284F834209C -:1037600083F311882B462A4629462046FFF768FE38 -:10377000E3E700BF4C5800084458000848580008C8 -:1037800038B590F834300446002B3ED0063BDAB210 -:103790000F2A34D80F2B32D8DFE803F03731310845 -:1037A000223231313131313131313737C56BB0F8F7 -:1037B0004A309D4214D2C3681B8AB5FBF3F203FB67 -:1037C00012556DB9202383F311882B462A462946CA -:1037D000FFF736FE85F311880A2384F834300EE0B3 -:1037E000142384F83430202383F3118800231A46ED -:1037F00019462046FFF712FE002383F3118838BDD7 -:10380000036C03B198470023E7E70021204601F04D -:10381000B3FA0021204601F0A5FA63681B6813B1D2 -:103820000621204698470623D7E7000010B590F8F8 -:103830003430142B044629D017D8062B05D001D8D4 -:103840001BB110BD093B022BFBD80021204601F023 -:1038500093FA0021204601F085FA63681B6813B1D2 -:10386000062120469847062319E0152BE9D10B23A2 -:1038700080F83430202383F3118800231A46194638 -:10388000FFF7DEFD002383F31188DAE7C3689B6945 -:103890005B68002BD5D1036C03B19847002384F8F3 -:1038A0003430CEE7024B0022C3E900339A60704700 -:1038B000F4350020002303748268054B1B68996867 -:1038C0009142FBD25A6803604260106058607047B2 -:1038D000F435002008B5202383F31188037C032BE3 -:1038E00005D0042B0DD02BB983F3118808BD436993 -:1038F00000221A604FF0FF334361FFF7DBFF002324 -:10390000F2E7D0E9003213605A60F3E70023037452 -:103910008268054B1B6899689142FBD85A6803601E -:103920004260106058607047F4350020054B1969FB -:103930000874186802681A605360186101230374E0 -:10394000FCF766BEF435002030B54B1C0B4D87B03C -:10395000044610D02B690A4A01A800F025F9204638 -:10396000FFF7E4FF049B13B101A800F059F92B699C -:10397000586907B030BDFFF7D9FFF8E7F4350020EC -:10398000D538000838B50C4D41612B6981689A68BB -:103990009142044603D8BDE83840FFF78BBF184674 -:1039A000FFF7B4FF01232C61014623742046BDE8D4 -:1039B0003840FCF72DBE00BFF4350020044B1A68D8 -:1039C0001B6990689B68984294BF00200120704753 -:1039D000F435002010B5084C236820691A6822606D -:1039E0005460012223611A74FFF790FF0146206999 -:1039F000BDE81040FCF70CBEF435002008B5FFF719 -:103A0000DDFF18B1BDE80840FFF7E4BF08BD0000C6 -:103A1000FFF7E0BFFEE7000010B50C4CFFF742FFD8 -:103A200000F0B4F80A498022204600F03BF8012358 -:103A300044F8180C037400F0D3FC002383F31188BE -:103A400062B60448BDE8104000F04CB81C360020B7 -:103A5000505800086058000800F01CB9EFF31180BE -:103A600020B9EFF30583202282F31188704700000C -:103A700010B530B9EFF30584C4F3080414B180F332 -:103A8000118810BDFFF7BAFF84F31188F9E7000031 -:103A9000034A516853685B1A9842FBD8704700BFCD -:103AA000001000E082600222028270478368A3F166 -:103AB0007C0243F80C2C026943F83C2C426943F821 -:103AC000382C074A43F81C2CC26843F8102C0222F9 -:103AD00003F8082C002203F8072CA3F11800704704 -:103AE0002906000810B5202383F31188FFF7DEFFB5 -:103AF00000210446FFF746FF002383F31188204688 -:103B000010BD0000024B1B6958610F20FFF70EBF6C -:103B1000F4350020202383F31188FFF7F3BF000062 -:103B200008B50146202383F311880820FFF70CFF16 -:103B3000002383F3118808BD49B1064B42681B6915 -:103B400018605A60136043600420FFF7FDBE4FF019 -:103B5000FF307047F43500200368984206D01A6899 -:103B60000260506059611846FFF7A4BE704700001C -:103B700038B504460D462068844200D138BD03683C -:103B800023605C604561FFF795FEF4E7054B03F1A8 -:103B90001402C3E905224FF0FF310022C3E90712E6 -:103BA000704700BFF435002070B51C4EC0E90323F8 -:103BB00005460C4601F0DCFA334653F8142F9A42BE -:103BC0000DD13062C5E901242A600A2C2CBF0019EE -:103BD0000A30C6E90555BDE8704001F0B7BA316A50 -:103BE000431AE31838BF1C469368A34202D9081948 -:103BF00001F0BAFA73699A6894420CD85A68AC60BA -:103C00002B606A6015609A685D60121B9A604FF0C5 -:103C1000FF33F36170BD1B68A41AECE7F435002094 -:103C200038B51B4C636998420DD0D0E9003213605F -:103C30005A6000228168C2609A680A449A604FF014 -:103C4000FF33E36138BD2246036842F8143F002188 -:103C500093425A60C16003D1BDE8384001F07EBA9A -:103C60009A688168256A0A449A6001F081FA63695A -:103C70009A68411B8A42E5D9AB181D1A092D206AA2 -:103C800098BF01F10A02BDE83840104401F06CBA57 -:103C9000F43500202DE9F041184C002704F11406FA -:103CA000656901F065FA236AAA68C11A8A4215D8C3 -:103CB00013442362D5E9003213605A606369D5F872 -:103CC0000C80EF60B34201D101F048FA87F311880C -:103CD0002869C047202383F31188E1E76169B14275 -:103CE00009D013441B1ABDE8F0410A2B2CBFC018A1 -:103CF0000A3001F039BABDE8F08100BFF435002088 -:103D000000207047FEE70000704700004FF0FF30D2 -:103D10007047000002290CD0032904D0012907486C -:103D200018BF00207047032A05D8054800EBC200E1 -:103D30007047044870470020704700BF445900088E -:103D400030230020F858000870B59AB005460846A0 -:103D500001A9144600F0C2F801A8FDF70BFF431CAF -:103D60005B00C5E900340022237003236370C6B2F0 -:103D700001AB02341046D1B28E4204F1020401D8E4 -:103D80001AB070BD13F8011B04F8021C04F8010CF2 -:103D90000132F0E708B5202383F311880348FFF7C9 -:103DA00079FA002383F3118808BD00BFB0370020E3 -:103DB00090F8443003F01F02012A07D190F8452003 -:103DC0000B2A03D10023C0E90E3315E003F0600392 -:103DD000202B08D1B0F848302BB990F84520212A83 -:103DE00003D81F2A04D8FFF737BA222AEBD0FAE704 -:103DF000034A82630722C26303640120704700BF45 -:103E00002823002007B5052917D8DFE801F0191687 -:103E100003191920202383F31188104A01900121EE -:103E2000FFF7D8FA01980E4A0221FFF7D3FA0D489E -:103E3000FFF7FCF9002383F3118803B05DF804FB5E -:103E4000202383F311880748FFF7C6F9F2E7202300 -:103E500083F311880348FFF7DDF9EBE79858000872 -:103E6000BC580008B037002038B50C4D0C4C0D493B -:103E70002A4604F10800FFF767FF05F1CA0204F1C2 -:103E800010000949FFF760FF05F5CA7204F1180038 -:103E90000649BDE83840FFF757BF00BF783C002017 -:103EA0003023002078580008825800088D580008F8 -:103EB00070B5044608460D46FDF75CFEC6B22046C6 -:103EC000013403780BB9184670BD32462946FDF718 -:103ED0003DFE0028F3D10120F6E700002DE9F04770 -:103EE00005460C46FDF746FE2B49C6B22846FFF7AD -:103EF000DFFF08B10636F6B228492846FFF7D8FF9B -:103F000008B11036F6B2632E0BD8DFF88C80DFF8DC -:103F10008C90234FDFF894A02E7846B92670BDE828 -:103F2000F08729462046BDE8F04701F0E5BB252E85 -:103F30002ED1072241462846FDF708FE70B9194BDD -:103F4000224603F10C0153F8040B42F8040B8B4298 -:103F5000F9D11B78137007350D34DDE70822494687 -:103F60002846FDF7F3FD98B90F4BA21C19780909F3 -:103F70000232C95D02F8041C13F8011B01F00F01A5 -:103F80005345C95D02F8031CF0D118340835C3E766 -:103F900004F8016B0135BFE7645900088D5800082B -:103FA0007A5900086C590008107AFF1F1C7AFF1F0D -:103FB000BFF34F8F024AD368DB03FCD4704700BFC6 -:103FC000003C024008B5094B1B7873B9FFF7F0FFBE -:103FD000074B1A69002ABFBF064A5A6002F18832AD -:103FE0005A601A6822F480621A6008BDD63E00202A -:103FF000003C02402301674508B50B4B1B7893B981 -:10400000FFF7D6FF094B1A6942F000421A611A689D -:1040100042F480521A601A6822F480521A601A68B8 -:1040200042F480621A6008BDD63E0020003C024087 -:104030000B28F0B516D80C4C0C4923787BB90C4DE5 -:104040000E460C234FF0006255F8047B46F8042B13 -:10405000013B13F0FF033A44F6D10123237051F8DA -:104060002000F0BD0020FCE7083F0020D83E0020E3 -:104070008C590008014B53F8200070478C590008F8 -:104080000C2070470B2810B5044601D9002010BD44 -:10409000FFF7CEFF064B53F824301844C21A0BB971 -:1040A0000120F4E712680132F0D1043BF6E700BFCB -:1040B0008C5900080B2810B5044621D8FFF778FF6B -:1040C000FFF780FF0F4AF323D360C300DBB243F452 -:1040D000007343F002031361136943F480331361E7 -:1040E000FFF766FFFFF7A4FF074B53F8241000F01B -:1040F00029F9FFF781FF2046BDE81040FFF7C2BF56 -:10410000002010BD003C02408C590008F8B512F0A8 -:104110000103144642D18218B2F1016F57D82D4BDA -:104120001B6813F0010352D02B4DFFF74BFFF32315 -:10413000EB60FFF73DFF40F20127032C15D824F078 -:1041400001046618244C401A40F20117B142236959 -:1041500000EB010524D123F001032361FFF74CFF9D -:104160000120F8BD043C0430E7E78307E7D12B6961 -:1041700023F440732B612B693B432B6151F8046B93 -:104180000660BFF34F8FFFF713FF03689E42E9D02D -:104190002B6923F001032B61FFF72EFF0020E0E7DE -:1041A00023F44073236123693B4323610B882B80F5 -:1041B000BFF34F8FFFF7FCFE2D8831F8023BADB205 -:1041C000AB42C3D0236923F001032361E4E718461F -:1041D000C7E700BF00380240003C0240084908B56C -:1041E0000B7828B11BB9FFF7EDFE01230B7008BD5A -:1041F000002BFCD0BDE808400870FFF7FDBE00BFF3 -:10420000D63E002070B582B0FFF728FC0E4E054662 -:1042100000F0AEFF3268904237BF0C4A0B4951683C -:1042200014682EBFD1E900410131516004190346E1 -:1042300041F10001284601913360FFF719FC019913 -:10424000204602B070BD00BF0C3F0020103F002090 -:1042500070B582B0FFF702FC104E054600F088FFF3 -:104260003268904237BF0E4A0D49516814682EBF1C -:10427000D1E9004101315160041941F100010346C7 -:10428000284601913360FFF7F3FB01994FF47A72EE -:1042900000232046FBF7A4FF02B070BD0C3F0020B6 -:1042A000103F002010B50244064BD2B2904200D11C -:1042B00010BD441C00B253F8200041F8040BE0B2DA -:1042C000F4E700BF502800400F4B30B51C6F2404AA -:1042D00007D41C6F44F400741C671C6F44F4004442 -:1042E0001C670A4C236843F4807323600244084B24 -:1042F000D2B2904200D130BD441C00B251F8045BF0 -:1043000043F82050E0B2F4E700380240007000406B -:104310005028004007B5012201A90020FFF7C2FF85 -:10432000019803B05DF804FB13B50446FFF7F2FFF4 -:10433000A04205D0012201A900200194FFF7C4FF8B -:1043400002B010BD70470000074B45F255521A608D -:1043500002225A6040F6FF729A604CF6CC421A6014 -:10436000024B01221A70704700300040193F0020B4 -:10437000034B1B781BB1034B4AF6AA221A60704705 -:10438000193F002000300040044BD3F874389B00E4 -:1043900042BF034B01221A70704700BF0030024039 -:1043A000183F0020024B4FF08072C3F8742870470A -:1043B00000300240014B1878704700BF183F0020C2 -:1043C000EFF3098305494A6B22F001024A6368331F -:1043D00083F30988002383F31188704700EF00E01E -:1043E000202080F3118862B60C4B0D4AD96821F465 -:1043F000E0610904090C0A43DA60D3F8FC2009499A -:1044000042F08072C3F8FC200A6842F001020A60A0 -:104410001022DA7783F82200704700BF00ED00E039 -:104420000003FA05001000E010B5202383F3118883 -:104430000E4B5B6813F4006314D0F1EE103AEFF307 -:104440000984683C4FF08073E361094BDB6B2366A2 -:1044500084F30988FFF7B2FA10B1064BA36110BDCF -:10446000054BFBE783F31188F9E700BF00ED00E09F -:1044700000EF00E03B0600083E0600087047000021 -:10448000FEE700000A4B0B480B4A90420BD30B4B44 -:10449000DA1C121AC11E22F003028B4238BF00221E -:1044A0000021FDF76FBB53F8041B40F8041BECE739 -:1044B000405B0008144000201440002014400020FD -:1044C0007047000070B5D0E915439E6800224FF098 -:1044D000FF3504EB42135101D3F800090028BEBF99 -:1044E000D3F8000940F08040C3F80009D3F8000B6E -:1044F0000028BEBFD3F8000B40F08040C3F8000B8B -:10450000013263189642C3F80859C3F8085BE0D239 -:104510004FF00113C4F81C3870BD00001D4B03EBB5 -:1045200080022DE9F043D2F80CC05D6DDCF8142058 -:10453000461CD2F800E005EB063605EB4018516842 -:1045400071450AD3D5F83438012202FA00F023EA83 -:104550000000C5F83408BDE8F083BCF81040AEEBAD -:104560000103A34228BF2346D8F81849A4B2B3EBED -:10457000840FF0D89468A4F1040959F8047F3760D7 -:10458000A4EB09071F44042FF7D81C440B44946084 -:104590005360D4E71C3F0020890141F020010161F4 -:1045A00003699B06FCD41220FFF772BA10B5054CC4 -:1045B0002046FEF7F1FE4FF0A0436365024BA36572 -:1045C00010BD00BF1C3F0020E059000870B5037803 -:1045D000012B054650D12A4B446D98421BD1294BE3 -:1045E0005A6B42F080025A635A6D42F080025A655B -:1045F0005A6D5A6942F080025A615A6922F080026B -:104600005A610E2143205B69FEF79CFC1E4BE36060 -:104610001E4BC4F800380023C4F8003EC0232360BA -:104620006E6D4FF40413A3633369002BFCDA01238E -:1046300033610C20FFF72CFA3369DB07FCD412201E -:10464000FFF726FA3369002BFCDA0026A66028461D -:10465000FFF738FF6B68C4F81068DB68C4F81468AB -:10466000C4F81C684BB90A4BA3614FF0FF33636178 -:10467000A36843F00103A36070BD064BF4E700BFDD -:104680001C3F00200038024040140040030020027C -:10469000003C30C0083C30C0F8B5446D05460021F0 -:1046A0002046FFF779FFA96D00234FF001128F68B4 -:1046B000C4F834384FF00066C4F81C284FF0FF30BF -:1046C00004EB431201339F42C2F80069C2F8006B49 -:1046D000C2F80809C2F8080BF2D20B686A6DEB65E4 -:1046E000636210231361166916F01006FBD11220C5 -:1046F000FFF7CEF9D4F8003823F4FE63C4F800388D -:10470000A36943F4402343F01003A3610923C4F8D1 -:104710001038C4F814380A4BEB604FF0C043C4F8AB -:10472000103B084BC4F8003BC4F81069C4F80039CA -:10473000EB6D03F1100243F48013EA65A362F8BD48 -:10474000BC59000840800010426D90F84E10D2F81D -:10475000003823F4FE6343EA0113C2F800387047BF -:104760002DE9F84300EB8103456DDA68166806F021 -:104770000306731E022B05EB41130C4680460FFA0D -:1047800081F94FEA41104FF00001C3F8101B4FF0C0 -:10479000010104F1100398BFB60401FA03F3916913 -:1047A0008EBF334E06F1805606F5004600293AD0FA -:1047B000578A04F15801490137436F50D5F81C1846 -:1047C0000B43C5F81C382B180021C3F81019536986 -:1047D0000127611EA7409BB3138A928B9B08012A75 -:1047E00088BF5343D8F85C20981842EA034301F18C -:1047F000400205EB8202C8F85C002146536028465F -:10480000FFF7CAFE08EB8900C3681B8A43EA84539A -:10481000483464011E432E51D5F81C381F43C5F897 -:104820001C78BDE8F88305EB4917D7F8001B21F485 -:104830000041C7F8001BD5F81C1821EA0303C0E7A4 -:1048400004F13F0305EB83030A4A5A6028462146D8 -:10485000FFF7A2FE05EB4910D0F8003923F400431E -:10486000C0F80039D5F81C3823EA0707D7E700BF9E -:104870000080001000040002826D1268C265FFF71C -:1048800021BE00005831436D49015B5813F40040CC -:1048900004D013F4001F0CBF022001207047000059 -:1048A0004831436D49015B5813F4004004D013F4C0 -:1048B000001F0CBF022001207047000000EB8101A7 -:1048C000CB68196A0B6813604B685360704700002F -:1048D00000EB810330B5DD68AA691368D36019B9AC -:1048E000402B84BF402313606B8A1468426D1C44C4 -:1048F000013CB4FBF3F46343033323F0030302EB03 -:10490000411043EAC44343F0C043C0F8103B2B6856 -:1049100003F00303012B09B20ED1D2F8083802EBE1 -:10492000411013F4807FD0F8003B14BF43F0805354 -:1049300043F00053C0F8003B02EB4112D2F8003BB9 -:1049400043F00443C2F8003B30BD00002DE9F041C4 -:10495000244D6E6D06EB40130446D3F8087BC3F874 -:10496000087B38070AD5D6F81438190706D505EBA1 -:1049700084032146DB6828465B689847FA071FD501 -:10498000D6F81438DB071BD505EB8403D968CCB9FE -:104990008B69488A5A68B2FBF0F600FB16228AB986 -:1049A0001868DA6890420DD2121AC3E90024202355 -:1049B00083F311880B482146FFF78AFF84F311889F -:1049C000BDE8F081012303FA04F26B8923EA0203B4 -:1049D0006B81CB68002BF3D021460248BDE8F04143 -:1049E000184700BF1C3F002000EB810370B5DD6855 -:1049F000436D6C692668E6604A0156BB1A444FF461 -:104A00000020C2F810092A6802F00302012A0AB243 -:104A10000ED1D3F8080803EB421410F4807FD4F8C9 -:104A2000000914BF40F0805040F00050C4F8000965 -:104A300003EB4212D2F8000940F00440C2F800092A -:104A4000D3F83408012202FA01F10143C3F8341803 -:104A500070BD19B9402E84BF4020206020682E8A86 -:104A60008419013CB4FBF6F440EAC44040F0005025 -:104A70001A44C6E7F8B504461E48456D05EB4413D5 -:104A8000D3F80869C3F80869F10717D5D5F81038C5 -:104A9000DA0713D500EB8403D9684B691F68DA681D -:104AA000974218D2D21B00271A605F60202383F33D -:104AB00011882146FFF798FF87F31188330617D531 -:104AC000D5F834280123A340134211D02046BDE875 -:104AD000F840FFF723BD012303FA04F2038923EA18 -:104AE000020303818B68002BE8D021469847E5E755 -:104AF000F8BD00BF1C3F00202DE9F74F984C666DB4 -:104B00007569B3691D4015F48058756107D020465A -:104B1000FEF7A8FC03B0BDE8F04FFFF785BC002D01 -:104B200012DAD6F8003E8E489F071EBFD6F8003E28 -:104B300023F00303C6F8003ED6F8043823F001033F -:104B4000C6F80438FEF7B6FC280505D58448FFF7FB -:104B5000B9FC8348FEF79EFCA9040CD5D6F80838AA -:104B600013F0060FF36823F470530CBF43F4105393 -:104B700043F4A053F3602A0704D56368DB680BB1E4 -:104B800077489847EB0274D4AF0227D5D4F85490F5 -:104B9000DFF8CCB100274FF0010A09EB4712D2F839 -:104BA000003B03F44023B3F5802F11D1D2F8003B32 -:104BB000002B0DDA62890AFA07F322EA0303638104 -:104BC00004EB8703DB68DB6813B139465846984726 -:104BD000A36D01379B68FFB29F42DED9E80617D567 -:104BE000676D3A6AC2F30A1002F00F0302F4F01282 -:104BF000B2F5802F00F08880B2F5402F08D104EB89 -:104C000083030022DB681B6A07F5805790426DD151 -:104C10002903D6F8184813D5E20302D50020FFF780 -:104C200095FEA30302D50120FFF790FE670302D58E -:104C30000220FFF78BFE260302D50320FFF786FE36 -:104C40006D037FF567AFE00702D50020FFF712FF85 -:104C5000A10702D50120FFF70DFF620702D5022050 -:104C6000FFF708FF23077FF555AF0320FFF702FF8B -:104C700050E7636DDFF8E8B0019300274FF0010AB9 -:104C8000A36D9B685FFA87F999453FF67DAF019B5D -:104C900003EB4913D3F8002902F44022B2F5802F28 -:104CA00022D1D3F80029002A1EDAD3F8002942F0D5 -:104CB0009042C3F80029D3F80029002AFBDB606D7D -:104CC0004946FFF769FC22890AFA09F322EA03033D -:104CD000238104EB8903DB689B6813B1494658467E -:104CE00098474846FFF71AFC0137C9E7910708BF04 -:104CF000D7F80080072A98BF03F8018B02F1010260 -:104D000098BF4FEA182881E7023304EB830207F5C6 -:104D100080575268D2F818C0DCF80820DCE9001C83 -:104D2000A1EB0C0C002188420AD104EB83046368D8 -:104D30009B699A6802449A605A6802445A6067E71D -:104D400011F0030F08BFD7F800808C4588BF02F828 -:104D5000018B01F1010188BF4FEA1828E3E700BF8A -:104D60001C3F0020436D03EB4111D1F8003B43F49D -:104D70000013C1F8003B7047436D03EB4111D1F8BC -:104D8000003943F40013C1F800397047436D03EB59 -:104D90004111D1F8003B23F40013C1F8003B7047E8 -:104DA000436D03EB4111D1F8003923F40013C1F82E -:104DB0000039704730B5039C0172043304FB0325AE -:104DC000C0E90653049B03630021059BC160C0E951 -:104DD0000000C0E90422C0E90842C0E90A114363A7 -:104DE00030BD0000416A0022C0E90411C0E90A2276 -:104DF000C2606FF00101FEF7BBBE0000D0E90432D3 -:104E0000934201D1C2680AB9181D7047002070474B -:104E100003691960C2680132C260C26913448269C1 -:104E20000361934224BF436A03610021FEF794BEED -:104E300038B504460D46E3683BB16269131D12683C -:104E4000A3621344E362002007E0237A33B92946C2 -:104E50002046FEF771FE0028EDDA38BD6FF0010044 -:104E6000FBE70000C368C269013BC36043691344A8 -:104E700082694361934224BF436A43610023836292 -:104E8000036B03B11847704770B52023044683F3C2 -:104E90001188866A3EB9FFF7CBFF054618B186F345 -:104EA0001188284670BDA36AE26A13F8015BA36209 -:104EB000934202D32046FFF7D5FF002383F31188E6 -:104EC000EFE700002DE9F84F04460E4617469846D6 -:104ED0004FF0200989F311880025AA46D4F828B09C -:104EE000BBF1000F09D141462046FFF7A1FF20B1D9 -:104EF0008BF311882846BDE8F88FD4E90A12A7EB96 -:104F0000050B521A934528BF9346BBF1400F1BD99E -:104F1000334601F1400251F8040B43F8040B91426F -:104F2000F9D1A36A40334036A3624035D4E90A235D -:104F30009A4202D32046FFF795FF8AF31188BD42BB -:104F4000D8D289F31188C9E730465A46FCF7F4FDF8 -:104F5000A36A5B445E44A3625D44E7E710B5029C2C -:104F60000172043304FB0321C0E906130023C0E9E6 -:104F70000A33039B0363049BC460C0E90000C0E9DB -:104F80000422C0E90842436310BD0000026AC26007 -:104F9000426AC0E904220022C0E90A226FF001013E -:104FA000FEF7E6BDD0E904239A4201D1C26822B9D6 -:104FB000184650F8043B0B60704700207047000013 -:104FC000C368C2690133C3604369134482694361A2 -:104FD000934224BF436A43610021FEF7BDBD000038 -:104FE00038B504460D46E3683BB123691A1DA26239 -:104FF000E2691344E362002007E0237A33B92946CB -:105000002046FEF799FD0028EDDA38BD6FF001006B -:10501000FBE7000003691960C268013AC260C26917 -:10502000134482690361934224BF436A03610023EE -:105030008362036B03B118477047000070B52023EB -:105040000D460446114683F31188866A2EB9FFF790 -:10505000C7FF10B186F3118870BDA36A1D70A36AE3 -:10506000E26A01339342A36204D3E1692046043922 -:10507000FFF7D0FF002080F31188EDE72DE9F84F0E -:1050800004460D46904699464FF0200A8AF311884F -:105090000026B346A76A4FB949462046FFF7A0FF4E -:1050A00020B187F311883046BDE8F88FD4E90A07AC -:1050B0003A1AA8EB0607974228BF1746402F1BD97C -:1050C00005F1400355F8042B40F8042B9D42F9D11B -:1050D000A36A4033A3624036D4E90A239A4204D338 -:1050E000E16920460439FFF795FF8BF311884645A7 -:1050F000D9D28AF31188CDE729463A46FCF71CFD40 -:10510000A36A3B443D44A3623E44E5E7D0E904235F -:105110009A4217D1C3689BB1836A8BB1043B9B1A37 -:105120000ED01360C368013BC360C3691A4483692E -:1051300002619A4224BF436A036100238362012310 -:10514000184670470023FBE700F088B84FF0804313 -:10515000002258631A610222DA6070474FF08043E0 -:105160000022DA60704700004FF0804358637047B8 -:105170004FF08043586A70474B6843608B68836088 -:10518000CB68C3600B6943614B6903628B694362FF -:105190000B6803607047000008B5264B26481A6963 -:1051A00040F2FF110A431A611A6922F4FF7222F0D9 -:1051B00001021A611A691A6B0A431A631A6D0A43CB -:1051C0001A651E4A1B6D1146FFF7D6FF02F11C013E -:1051D00000F58060FFF7D0FF02F1380100F5806034 -:1051E000FFF7CAFF02F1540100F58060FFF7C4FF2A -:1051F00002F1700100F58060FFF7BEFF02F18C0143 -:1052000000F58060FFF7B8FF02F1A80100F58060AB -:10521000FFF7B2FF02F1C40100F58060FFF7ACFFB9 -:1052200002F1E00100F58060FFF7A6FFBDE808404D -:1052300000F09AB80038024000000240EC59000823 -:1052400008B500F007FAFEF7E7FBFFF79DF8BDE8A9 -:105250000840FEF709BE000070470000104B1A6CB2 -:1052600042F001021A641A6E42F001021A660D4AF7 -:105270001B6E936843F0010393604FF08043532209 -:105280009A624FF0FF32DA6200229A615A63DA6062 -:105290005A6001225A6108211A601C20FDF752BE93 -:1052A00000380240002004E04FF0804208B5116948 -:1052B000D3680B40D9B2C9439B07116107D520239E -:1052C00083F31188FEF7C8FB002383F3118808BD20 -:1052D00008B5FFF7E9FFBDE80840FFF7A5B80000F3 -:1052E0001F4B1A696FEAC2526FEAD2521A611A69E9 -:1052F000C2F308021A614FF0FF301A695A69586107 -:1053000000215A6959615A691A6A62F080521A6218 -:105310001A6A02F080521A621A6A5A6A58625A6A03 -:1053200059625A6A1A6C42F080521A641A6E42F03C -:1053300080521A661A6E0B4A106840F48070106032 -:10534000186F00F44070B0F5007F1EBF4FF480303E -:1053500018671967536823F40073536000F05AB953 -:105360000038024000700040334B4FF080521A6406 -:10537000324A4FF4404111601A6842F001021A604B -:105380001A689107FCD59A6822F003029A602A4BAA -:105390009A6812F00C02FBD1196801F0F90119604A -:1053A0009A601A6842F480321A601A689203FCD537 -:1053B0005A6F42F001025A671F4B5A6F9007FCD593 -:1053C0001F4A5A601A6842F080721A601B4A53687A -:1053D0005904FCD5184B1A689201FCD5194A9A60F9 -:1053E000194B1A68194B9A42194B21D1194A116865 -:1053F000194A91421CD140F205121A60144A1368EE -:1054000003F00F03052BFAD10B4B9A6842F002020E -:105410009A609A6802F00C02082AFAD15A6C42F497 -:1054200080425A645A6E42F480425A665B6E7047FC -:1054300040F20572E1E700BF003802400070004012 -:105440000854400700948838002004E011640020CC -:10545000003C024000ED00E041C20F41084A08B59F -:10546000516913680B4003F00103536123B1054AEE -:1054700013680BB150689847BDE80840FEF7D4BFE9 -:10548000003C0140943F0020084A08B55169136868 -:105490000B4003F00203536123B1054A93680BB13B -:1054A000D0689847BDE80840FEF7BEBF003C014009 -:1054B000943F0020084A08B5516913680B4003F077 -:1054C0000403536123B1054A13690BB1506998472E -:1054D000BDE80840FEF7A8BF003C0140943F002013 -:1054E000084A08B5516913680B4003F0080353617B -:1054F00023B1054A93690BB1D0699847BDE80840CC -:10550000FEF792BF003C0140943F0020084A08B5D6 -:10551000516913680B4003F01003536123B1054A2E -:10552000136A0BB1506A9847BDE80840FEF77CBF8C -:10553000003C0140943F0020174B10B55A691C688D -:10554000144004F478725A61A30604D5134A936A8E -:105550000BB1D06A9847600604D5104A136B0BB1A3 -:10556000506B9847210604D50C4A936B0BB1D06B56 -:105570009847E20504D5094A136C0BB1506C984763 -:10558000A30504D5054A936C0BB1D06C9847BDE8D0 -:105590001040FEF749BF00BF003C0140943F00208F -:1055A0001A4B10B55A691C68144004F47C425A61C5 -:1055B000620504D5164A136D0BB1506D984723054B -:1055C00004D5134A936D0BB1D06D9847E00404D510 -:1055D0000F4A136E0BB1506E9847A10404D50C4AC4 -:1055E000936E0BB1D06E9847620404D5084A136FCE -:1055F0000BB1506F9847230404D5054A936F0BB144 -:10560000D06F9847BDE81040FEF70EBF003C014048 -:10561000943F0020062108B50846FDF793FC0621BB -:105620000720FDF78FFC06210820FDF78BFC0621E3 -:105630000920FDF787FC06210A20FDF783FC0621DF -:105640001720FDF77FFCBDE8084006212820FDF764 -:1056500079BC000008B5FFF743FE00F00DF8FDF738 -:1056600087FCFDF797FEFDF76FFDFFF7F5FDBDE841 -:105670000840FFF769BD00000023054A19460133C1 -:10568000102BC2E9001102F10802F8D1704700BFE7 -:10569000943F002010B501390244904201D100200E -:1056A00005E0037811F8014FA34201D0181B10BD8B -:1056B0000130F2E72DE9F041A3B1C91A177801448E -:1056C000044603F1FF3C8C42204601D9002009E04A -:1056D0000578BD4204F10104F5D10CEB0405D618A0 -:1056E000A54201D1BDE8F08115F8018D16F801ED54 -:1056F000F045F5D0E7E70000034611F8012B03F869 -:10570000012B002AF9D170476F72672E61726475A0 -:1057100070696C6F742E663430355F4D6174656BE3 -:10572000475053004E6F20617070207369670A0004 -:10573000426164206677206C656E67746820257509 -:105740000A0042616420626F6172645F69642025AF -:10575000752073686F756C642062652025750A007A -:105760004261642066772064657363726970746F48 -:1057700072206C656E6774682025750A004261644A -:105780002061707020435243203078253038783AB9 -:10579000307825303878203078253038783A3078AD -:1057A000253038780A00476F6F64206669726D771C -:1057B0006172650A0040A2E4F1646891060000008D -:1057C00053544D3332463F3F3F00000053544D3356 -:1057D00032463430780053544D33324634327800F8 -:1057E00053544D33324634343658580000000000CC -:1057F000C05700083F00000013040000CC57000809 -:105800003F00000019040000D65700083F000000C8 -:1058100021040000E05700083F00000000000000E5 -:10582000C5300008B1300008ED300008D93000085C -:10583000E5300008D1300008BD300008A93000086C -:10584000F930000800000000010000000000000026 -:105850006D61696E0000000069646C650000000005 -:105860005858000838360020B037002001000000EA -:10587000153A0008000000004172647550696C6FB1 -:10588000740025424F415244252D424C002553457A -:105890005249414C250000000200000000000000B9 -:1058A000E13200084D33000840004000483C002031 -:1058B000583C00200200000000000000030000002F -:1058C00000000000913300080000000010000000FC -:1058D000683C002000000000010000000000000003 -:1058E0001C3F002001010200053E0008153D000894 -:1058F000B13D0008953D0008430000000059000834 -:1059000009024300020100C0320904000001020242 -:1059100001000524001001052401000104240202F5 -:105920000524060001070582030800FF09040100A1 -:10593000020A00000007050102400000070581027D -:1059400040000000120000004C5900081201100134 -:105950000200004009124157000201020301000049 -:105960000403090425424F41524425006634303572 -:105970002D4D6174656B47505300303132333435EF -:105980003637383941424344454600000040000064 -:105990000040000000400000004000000000010046 -:1059A00000000200000002000000020000000200EF -:1059B00000000200000002000000020000000000E1 -:1059C000C9340008813700082D3800084000400025 -:1059D0007C3F00207C3F0020010000008C3F002025 -:1059E000800000004001000003000000AA01A8128E -:1059F00000000000AAAAAAAA55011400FFBF0000D7 -:105A00008877000070A70A0000000A01000000006B -:105A1000AAAAAAAA00000001FFFF000000000000DF -:105A2000990000000000A01600000000AAAAAAA683 -:105A300000005011FFDF00000000000000770800A8 -:105A40002000000000000000AAAAAAAA100000007E -:105A5000FFFF000000080000000000000000000040 -:105A600000000000AAAAAAAA00000000FFFF000090 -:105A70000000000000000000000000000000000026 -:105A8000AAAAAAAA00000000FFFF00000000000070 -:105A9000000000000000000000000000AAAAAAAA5E -:105AA00000000000FFFF00000000000000000000F8 -:105AB00000000000000000000A00000000000000DC -:105AC00003000000000000000000000000000000D3 -:105AD00000000000000000000000000000000000C6 -:105AE000000000000000000028A7FF7F0100000068 -:105AF000F60300000000000000000F00000000009E -:105B00006400000000000000FE2A0100D204000032 -:105B1000FF0096000000000800960000000008004A -:105B200004000000605900080000000000000000B0 -:105B30000000000000000000000000000000000065 +:10063000A047002003F046FBFEE703F0C1FA00DF0D +:10064000FEE70000F8B503F051FF074603F09CFFFA +:100650000546A0BB1F4B9F4231D001339F4231D092 +:100660001D4B27F0FF029A422FD1F8B200F022FD75 +:100670002E4642F2107400F027FF08B100242646EF +:1006800000F01EFD08B90646044635B1134B9F42E3 +:1006900003D003F071FF00242646002003F030FF52 +:1006A0000EB100F063F801F019FB00F06BFF01F0F0 +:1006B000A5F9204600F0B6F800F058F8F9E72E4604 +:1006C0000024D8E704460126D5E7064641F28834DF +:1006D000D1E700BF010007B0000008B0263A09B01A +:1006E00008B501F05DF9A0F120035842584108BD5A +:1006F00007B541F21203022101A8ADF8043001F060 +:100700006DF903B05DF804FB10B5202383F3118865 +:100710001248C3680BB103F05BFB114A0F4800237A +:100720004FF47A7103F018FB002383F311880D4C0A +:10073000236813B12368013B2360636813B16368C6 +:10074000013B6360084B1B7833B9636823B902200F +:1007500001F03EFA3223636010BD00BF5823002031 +:1007600009070008742400206C230020274B284A26 +:1007700010B51C461968013146D004339342F9D1B3 +:100780006268244B9A423FD9234B9B6803F1006374 +:1007900003F580339A4237D203F0C2FE03F0D4FE51 +:1007A000002001F045F91D4B0220187001F006FAF7 +:1007B0001B4B1A6C00221A64196E1A66196E596C5A +:1007C0005A64596E5A665A6E5A6942F080025A61EA +:1007D0005A6922F080025A615A691A6942F000523D +:1007E0001A611A6922F000521A611B6972B64FF041 +:1007F000E0232021C3F8084DD4E9003281F31188A9 +:100800009D4683F30888104710BD00BF0000010813 +:1008100020000108FFFF0008002300206C230020B7 +:10082000003802402DE9F04F93B0AC4B00902022ED +:10083000FF210AA89D6801F0FBF9A94A1378A3B922 +:10084000A8480121C3601170202383F31188C36875 +:100850000BB103F0BDFAA44AA24800234FF47A7109 +:1008600003F07AFA002383F31188009B9F4A03B1B7 +:1008700013609F49009C00230B70536098469B4671 +:100880001E469A46012001F099F924B1974B1B6846 +:10089000002B00F01C82002001F082F80390039BE3 +:1008A000002B01DA00F020FF039B002BEDDB012081 +:1008B00001F07AF9039B213B162BE3D801A252F8F1 +:1008C00023F000BF2109000849090008DD090008DC +:1008D000850800088508000885080008710A0008D6 +:1008E000430C00085D0B0008BF0B0008E70B000875 +:1008F0000D0C0008850800081F0C0008850800087A +:10090000910C0008C109000885080008D50C0008F2 +:100910002D090008C109000885080008BF0B000860 +:100920000220FFF7DDFE002840F0FB81009B022142 +:10093000B8F1000F08BF1C4605A841F21233ADF80C +:10094000143001F04BF89DE74FF47A7001F028F86D +:10095000071EEBDB0220FFF7C3FE0028E6D0013FB5 +:10096000052F00F2E081DFE807F0030A0D101336CF +:1009700005230593042105A801F030F817E0574836 +:100980000421F9E75B480421F6E75B480421F3E71B +:100990004FF01C09484601F04DF809F10409059093 +:1009A000042105A801F01AF8B9F12C0FF2D10120A9 +:1009B00000FA07F747EA0B0B5FFA8BFB4FF0000AD0 +:1009C00001F082F926B10BF00B030B2B08BF0024BA +:1009D000FFF78EFE56E749480421CDE7002EA5D04B +:1009E0000BF00B030B2BA1D10220FFF779FE07467A +:1009F00000289BD001203E4E01F01AF802203070F2 +:100A000001F0DCF84FF000085FFA88F9484601F081 +:100A10001FF8044690B1484601F02AF808F1010891 +:100A20000028F1D1B846044641F21213022105A86C +:100A3000ADF814303E4600F0D1FF23E70123022039 +:100A4000337001F0B1F82546244B9B68AB4207D9BF +:100A5000284600F0EFFF013040F068810435F3E7ED +:100A6000234B00251D70214BB8465D603E46A7E72D +:100A7000002E3FF45BAF0BF00B030B2B7FF456AF54 +:100A80001B4B0220187001F099F8322000F088FF0B +:100A9000B0F10009FFF64AAF19F003077FF446AF43 +:100AA0000E4A926809EB050393423FF63FAFB9F552 +:100AB000807F3FF73BAF124B0193B94522DD4FF4E6 +:100AC0007A7000F06DFF0390039A002AFFF62EAFB4 +:100AD000019B039A03F8012B0137EDE70023002067 +:100AE00070240020582300200907000874240020E7 +:100AF0006C23002004230020082300200C23002066 +:100B000070230020C820FFF7EBFD074600283FF4C4 +:100B10000DAF1F2D11D8C5F120024A450AAB25F0B3 +:100B2000030028BF4A4683490192184401F05AF84D +:100B3000019A8048FF2101F07BF84FEAA9037D4923 +:100B40000193C9F38702284601F07AF80646002887 +:100B50003FF46AAF019B05EB830531E70220FFF705 +:100B6000BFFD00283FF4E2AE00F0ACFF00283FF4E8 +:100B7000DDAE0027B946704B9B68BB4218D91F2FCA +:100B800011D80A9B01330ED027F0030312AA134495 +:100B900053F8203C05934846042205A901F012F9B8 +:100BA00004378146E7E7384600F044FF0590F2E756 +:100BB000CDF81490042105A800F010FF00E70023F1 +:100BC000642104A8049300F0FFFE00287FF4AEAE79 +:100BD0000220FFF785FD00283FF4A8AE049800F03E +:100BE00059FF0590E6E70023642104A8049300F070 +:100BF000EBFE00287FF49AAE0220FFF771FD00287B +:100C00003FF494AE049800F055FFEAE70220FFF7A6 +:100C100067FD00283FF48AAE00F064FFE1E70220A0 +:100C2000FFF75EFD00283FF481AE05A9142000F017 +:100C30005FFF04210746049004A800F0CFFE394668 +:100C4000B9E7322000F0ACFE071EFFF66FAEBB071F +:100C50007FF46CAE384A926807EB0A0393423FF682 +:100C600065AE0220FFF73CFD00283FF45FAE27F0A1 +:100C700003075744BA453FF4A3AE504600F0DAFEEE +:100C80000421059005A800F0A9FE0AF1040AF1E785 +:100C90004FF47A70FFF724FD00283FF447AE00F0D0 +:100CA00011FF002844D00A9B01330BD008220AA967 +:100CB000002000F0C5FF00283AD02022FF210AA81A +:100CC00000F0B6FFFFF714FD1C4803F001F813B065 +:100CD000BDE8F08F002E3FF429AE0BF00B030B2B79 +:100CE0007FF424AE0023642105A8059300F06CFE78 +:100CF000074600287FF41AAE0220FFF7F1FC814678 +:100D000000283FF413AEFFF7F3FC41F2883002F005 +:100D1000DFFF059801F00AF84E4600F0D5FF3C468B +:100D2000B0E506464CE64FF0000AFFE5B8467BE624 +:100D3000374679E67023002000230020A0860100BA +:100D4000094A136849F2690099B21B0C00FB013390 +:100D50001360064B186844F2506182B2000C01FB2C +:100D60000200186080B27047202300201C2300205E +:100D700010B500211022044600F05AFF034B03CBAC +:100D8000206061601868A06010BD00BF107AFF1F6E +:100D90002DE9F043224DBBB001F010F8AB6840F2F2 +:100DA000ED22C31A934232D906AFA8602B462822FF +:100DB0000021384601F010FD05F10E0000F030FF73 +:100DC000002604465FFA80F905F10E08F3B2F1003F +:100DD000994501F1280107D908EB06030822384696 +:100DE00001F0FAFC0136F1E708230122CDE90232D5 +:100DF00005340C4B0193A4B230230093CDE9047465 +:100E000005A3D3E90023297B074801F0FDFA3BB095 +:100E1000BDE8F083AFF3008078F6339F93CACD8DA1 +:100E2000C0340020CD3400209434002070B50D462D +:100E300014461E4601F07EFA50B9022E10D1012C44 +:100E40000ED112A3D3E90023C5E90023012007E056 +:100E5000282C10D005D8012C09D0052C0FD000204B +:100E600070BD302CFBD10BA3D3E90023ECE70BA31F +:100E7000D3E90023E8E70BA3D3E90023E4E70BA3BE +:100E8000D3E90023E0E700BFAFF30080401DA120BD +:100E900026812A0B78F6339F93CACD8D9E6AC42192 +:100EA000818A46EE26417272DF25D7B7F017304AA5 +:100EB00039059E5613B504462346084620220021D4 +:100EC000019001F089FC22790198032A234628BF6A +:100ED000032203F8042F2021022201F07DFC627915 +:100EE0000198072A234628BF072203F8052F22214D +:100EF000032201F071FCA2790198072A234628BF3A +:100F0000072203F8062F2521032201F065FC019832 +:100F100004F108031022282101F05EFC382002B001 +:100F200010BD00002DE9F04FADF5017D21AD0EAEF5 +:100F300040F2751280460F4622A80021296000F079 +:100F400077FE48220021304600F072FE00F036FFA6 +:100F5000564B4FF47A72B0FBF2F0186093E807003A +:100F6000012386E807000DF15A003382FFF700FFE6 +:100F70004FF20363338407AB18464D4904F0B4FCC9 +:100F80001B2230642946304686F83C20FFF792FF4A +:100F900012AB044601460822284601F01DFC082237 +:100FA000A1180DF14903284601F016FC0DF14A0382 +:100FB000082204F11001284601F00EFC13AB202298 +:100FC00004F11801284601F007FC14AB402204F19B +:100FD0003801284601F000FC16AB082204F1780124 +:100FE000284601F0F9FB0DF15903082204F18001B4 +:100FF000284601F0F1FB04F1880A0DF15A0904F5C5 +:10100000847B4B465146082228460AF1080A01F023 +:10101000E3FBD34509F10109F3D11BAB0822594683 +:10102000284601F0D9FB04F588744FF0000996F8C2 +:1010300034304B450AD9B36B21464B44082228462D +:1010400001F0CAFB083409F10109F0E74FF000098B +:1010500096F83C304B4504EBC90108D9336C0822A3 +:101060004B44284601F0B8FB09F10109F0E70023E1 +:101070000393BB7E0293073107F119030193C1F378 +:10108000CF010123CDE904510093F97E05A3D3E9F3 +:101090000023404601F0B8F90DF5017DBDE8F08F61 +:1010A000AFF300809E6AC421818A46EE7C24002032 +:1010B000F8580008014B1870704700BF88240020C2 +:1010C000F0B5334B1C7B85B034B1324B0E221A8104 +:1010D0000024204605B0F0BD2F4A1068516802ABCD +:1010E00003C308232D492E480DEB030204F0DAFB5D +:1010F000054630B9274B2B480A221A8100F018FE0A +:10110000E6E70169B1F5702F06D9224B26480B227C +:101110001A8100F00DFEDCE7438B40F2F632934279 +:1011200007D01C490C2008811946204800F000FE19 +:10113000CFE71F4A024402F11003994204D2154B33 +:101140001C4810221A81E4E710398E1A20461449EF +:1011500000F038FE3246074605F11801204600F03F +:1011600031FEAB689F4202D1EB6898420AD0094B2E +:101170000D221A810090D5E902123B460E4800F07C +:10118000D7FDA5E70D4800F0D3FD0124A1E700BF7E +:10119000C03400207C240020A5590008DCFF0E008C +:1011A00000000108145900082059000832590008AD +:1011B0000800FFF7505900086D59000896590008BB +:1011C0002DE9F04FADB006AF80460C4601F0B2F805 +:1011D000054600285AD1237E022B1BD1E38A012B1E +:1011E00018D100F0EBFD0646FFF7AAFD03464FF4C9 +:1011F000C870DFF8D092B3FBF0F206F5167602FB6A +:10120000103316FA83F3C9F80030E37E33B9A84BE4 +:1012100000221A709C37BD46BDE8F08FA38AEEB25B +:10122000013BB34205F101050BD93B1D1E44E9000A +:1012300000960023082201F0F801204601F090F901 +:10124000ECE707F11400FFF793FD324607F11401B4 +:10125000381D04F017FB0028D9D10F2E08D8944B65 +:101260001E70D9F80030A3F51673C9F80030D1E725 +:10127000FB1CF8700146009307220346204601F04C +:101280006FF9F978404601F04DF8C3E7E38A282B5F +:1012900026D010D8012B1ED0052BBBD1BFF34F8F0A +:1012A0008449854BCA6802F4E0621343CB60BFF304 +:1012B0004F8F00BFFDE7302BACD1637E7F4D0133F4 +:1012C0006A7BDBB29342E94603D1E27E2B7B9A42F2 +:1012D00065D0CD469EE721464046FFF723FE99E7BD +:1012E000A38A013B9BB2C92B94D8744D2E7B26BB9D +:1012F00005F10C030093082233463146204601F0E5 +:101300002FF9731CF2B2D9001E46A38A013B9A4200 +:1013100005DA0E322A44009200230822EEE7002369 +:101320000022C5E900230023AB6085F8D730C5F85B +:10133000D8302B7B0BB9E37E2B73002507F1140902 +:101340003B1D082229464846C7E90155FD6001F0CA +:1013500043FA3B7A05F1010AAB424FEACA0608D9C3 +:10136000FB6808222B443146484601F035FA5546C1 +:10137000EFE7C6F3CF06E17ECDE9049600230393A1 +:10138000A37E0293193428230093019446A3D3E942 +:101390000023404601F038F8FFF7FAFC3AE74FF037 +:1013A000000807F11403A7F81480102200934146A7 +:1013B0000123204601F0D4F8A68A023EB6B2F31CFF +:1013C0009B109B000733DB08A9EBC3039D460DF17F +:1013D000180A1FFA88F34FEAC801B34201F110015D +:1013E0000AD20AEB0803009308220023204601F0EA +:1013F000B7F808F10108ECE795F8D70000F028FBF2 +:10140000D5F8D83004461BB995F8D70000F030FB6A +:10141000D5F8D83033449C4204D295F8D700013037 +:1014200000F026FB4FEA960B4FF000081FFA88F1F8 +:101430008B45D5E9003209D90AEB880103EB880016 +:10144000012200F0FDFB08F10108EFE7F31842F17B +:101450000002C5E90032D5F8D83095F8D70006EB80 +:101460000308C5F8D88000F0F3FA804509D395F851 +:10147000D730D5F8D8000133001B85F8D730C5F830 +:10148000D800FF2E08D800232B7300F01BFBFFF7BA +:1014900017FE08B1FFF76AF92B68094A9B0A013366 +:1014A00013810023AB6014E726417272DF25D7B7A2 +:1014B0008D34002000ED00E00400FA05C034002067 +:1014C0007C2400209034002030B54FF00054244B91 +:1014D00022689A4285B007D003F060F80446A8B9A4 +:1014E0000024204605B030BD1E4B627D1A701E4898 +:1014F000237D03731D49C9220E3000F073FB204683 +:10150000E022002100F094FB0124EAE7184A194D7B +:10151000136C43F000731364AA6D174B9A42DFD12A +:101520002B6E013B7E2BDBD8144A07CA01AB83E844 +:1015300007001846032100F05BFC6B6D83424FF0FF +:101540000003CDD12A6D8A4201BFAB65054B2A6EDF +:101550001A7003BF0A4BEA6D1A601C46C1E700BF50 +:101560009AAD44C588240020C03400201600002015 +:1015700000380240006600405041A0B0586600406C +:10158000182300202DE9FF474B4C022363710023F1 +:1015900002934A4BD3F800C0BCF57A7F12D3484B74 +:1015A000484FB7FBFCF69C458CBF0A231123581EFD +:1015B000B6FBF3F503FB1562C1B2002A3ED0022848 +:1015C0000346F4D89DF80B303F4940485A1E9DF819 +:1015D0000A30013B1B0443EA0253BDF80820013ADC +:1015E00013434B6001F0B0FD00230193384B3949A0 +:1015F00000933948394B4FF4805200F06DFE384B60 +:10160000197811B1344800F08DFE00F0D7FB054683 +:10161000FFF796FB4FF4C873B0FBF3F202FB130322 +:1016200005F5167010FA83F02E4B186002F0ACFF2F +:1016300008B10F23238104B0BDE8F0876B1EB3F51A +:10164000806FBFD2C1EBC10E0EF103034FEAE30975 +:10165000C3F3C703A1EB030809F1010A4FF47A7041 +:101660005FFA88F609FB00005AFA88F8B0FBF8F038 +:10167000B0F5617F08D90EF1FF33C3F3C703C91A70 +:10168000CEB2591E0F2914D8721E072A8CBF002211 +:101690000122991901FB0551B7FBF1F7BC4591D126 +:1016A000002A8FD0ADF808508DF80A308DF80B6005 +:1016B00088E71346EDE700BF7C24002018230020B4 +:1016C0003F420F0080DE800210230020D83500202A +:1016D0002D0E00088C24002094340020C111000835 +:1016E00088240020903400202DE9F04F91A7D7E9FD +:1016F00000670FF24829D9E90089874D93B0DFF8D8 +:1017000044B2864C284600F0E3FE0DF1300A079003 +:1017100070B310220021504600F08AFA079B197B13 +:101720004FF0000261F303028DF830205868996889 +:101730000EAA03C21B680D9A63F31C029DF8303099 +:101740000D9243F020038DF83030002352461946A5 +:10175000584601F009FD079028B9284600F0BCFE64 +:10176000079B2370CEE72378072B3CD801332370E7 +:1017700018220021504600F05BFADFF8C8B1684C2F +:10178000002319465246584601F016FD014670BB2B +:10179000102208A800F04CFA636983F48043636167 +:1017A00000F00EFB0B4612A9024611E903000DF1F1 +:1017B000240C8CE803009DF83410C1F30300890663 +:1017C0004CBF0E99BDF838C08DF82C0046BFC1F350 +:1017D0001C0C4CF00041CCF30A010891284608A9E2 +:1017E00001F042F8CCE7284600F076FEC0E7284634 +:1017F00000F0A0FD0446002848D1DFF84CB100F00D +:10180000DDFADBF80030984240D300F0D7FA0790B9 +:10181000FFF796FA079A8DF8204003464FF4C870F8 +:1018200002F51672B3FBF0F101FB103312FA83F3E9 +:10183000CBF80030DFF814B19BF8001011B9012388 +:101840008DF8203050460791FFF792FA0799C1F1C1 +:101850001004E4B2062C28BF0624224651440DF1A0 +:10186000210000F0BFF908AB039318230293013461 +:101870002C4B0193E4B20123009304943B4632467F +:10188000284600F059FD00238BF8003000F096FA4E +:10189000254A264C1368C31AB3F57A7F31D31060FA +:1018A00000F08EFA02460B46284600F01FFE28463E +:1018B00000F040FD28B3237BDFF894B0002B14BF69 +:1018C000032302238BF8053000F078FA4FF47A7383 +:1018D0005146B0FBF3F0CBF800005846FFF7EAFAA8 +:1018E000182307300293124B0193C0F3CF0040F24C +:1018F0005513CDE903A0009342464B46284600F01D +:101900001BFD237B2BB1FFF743FA237B002B7FF4D6 +:10191000F6AE13B0BDE8F08F94340020A53500205A +:10192000000002408C340020A0350020C03400208C +:10193000A4350020401DA12026812A0BF1C6A7C195 +:10194000D068080FD8350020903400208D34002056 +:101950007C24002070B50F4B1B780133DBB2012BC8 +:101960000C4611D80C4D29684FF47A730E6AA2FB0D +:101970000332014622462846B047844204D1074B31 +:1019800000221A70012070BD4FF4FA7002F0A0F925 +:101990000020F8E724230020C0370020D4350020A1 +:1019A00007B50023024601210DF107008DF807302D +:1019B000FFF7D0FF20B19DF8070003B05DF804FBEE +:1019C0004FF0FF30F9E700000A4608B50421FFF7A1 +:1019D000C1FF80F00100C0B2404208BD30B4054CE8 +:1019E0002368DD69044B0A46AC460146204630BCFC +:1019F000604700BFC0370020A086010070B502F02C +:101A000017FC094E094D3080002428683388834232 +:101A100008D902F007FC2B6804440133B4F5803F79 +:101A20002B60F2D370BD00BFD6350020A835002052 +:101A300002F0C0BC00F1006000F580300068704723 +:101A400000F10060920000F5803002F03FBC000021 +:101A5000054B1A68054B1B889B1A834202D9104418 +:101A600002F0E0BB00207047A8350020D6350020EA +:101A700038B5074D04462868204402F0DBFB28B93E +:101A800028682044BDE8384002F0ECBB38BD00BFF8 +:101A9000A835002010F003030AD1B0F5047F05D269 +:101AA00000F10050A0F51040D0F8003818467047FB +:101AB0000023FBE700F10050A0F51040D0F8100A19 +:101AC00070470000064991F8243033B10023086ABA +:101AD00081F824300822FFF7B3BF0120704700BF10 +:101AE000AC350020014B1868704700BF002004E0AF +:101AF00070B52A4B1B68C3F30B0204461B0C62B182 +:101B000040F21340824230D040F2194082422ED03F +:101B100040F2214082422CD10322214D0C2000FBB7 +:101B20000252556842F20102934224D0B3F5805F1D +:101B300023D041F20102934221D041F203029342A9 +:101B40001FD041F20702934214BF3F233123013CCF +:101B50000C44013D0A46A24215D215F9016F501CF2 +:101B60009EB100F8016C0246F5E70122D5E702229A +:101B7000D3E70C4DD6E73323E9E74123E7E75A23C0 +:101B8000E5E75923E3E7104605E02C25844215706C +:101B900001D9901C5370401A70BD00BF002004E0B2 +:101BA000DC590008B0590008022802BF024B4FF070 +:101BB00080429A61704700BF00000240022802BFC5 +:101BC000024B4FF480429A61704700BF0000024010 +:101BD000022801BF024A536983F48043536170476E +:101BE0000000024010B50023934203D0CC5CC454E3 +:101BF0000133F9E710BD000010B5013810F9013FBD +:101C00003BB191F900409C4203D11AB10131013A34 +:101C1000F4E71AB191F90020981A10BD1046FCE7BC +:101C200003460246D01A12F9011B0029FAD1704767 +:101C300002440346934202D003F8011BFAE77047BF +:101C40002DE9F8431F4D144695F824200746884691 +:101C500052BBDFF870909CB395F824302BB920224A +:101C6000FF2148462F62FFF7E3FF95F82400C0F1FB +:101C70000802A24228BF2246D6B24146920005EB96 +:101C80008000FFF7AFFF95F82430A41B1E44F6B286 +:101C9000082E17449044E4B285F82460DBD1FFF7A6 +:101CA00011FF0028D7D108E02B6A03EB820383429F +:101CB000CFD0FFF707FF0028CBD10020BDE8F88385 +:101CC0000120FBE7AC350020024B1A78024B1A705A +:101CD000704700BFD43500202423002010B50F4CDE +:101CE0000F4801F00BFB21460D4801F033FB24683F +:101CF0000C48626DD2F8043843F00203C2F804388D +:101D000001F0E6FF0849204601F02AFC626DD2F896 +:101D1000043823F00203C2F8043810BDD05A00087A +:101D2000C037002040420F00D85A0008704700001A +:101D30000FB4002004B0704700B59BB0EFF30981E9 +:101D400068226846FFF74EFFEFF30583044B9A6B5A +:101D5000DA6A9A6A9A6A9A6A9A6A9A6A9B6AFEE741 +:101D600000ED00E000B59BB0EFF309816822684602 +:101D7000FFF738FFEFF30583044B9A6B9A6A9A6A70 +:101D80009A6A9A6A9A6A9B6AFEE700BF00ED00E0D1 +:101D900000B59BB0EFF3098168226846FFF722FF88 +:101DA000EFF30583034B5A6B9A6A9A6A9A6A9A6AA6 +:101DB0009B6AFEE700ED00E0FEE7000002F034BBA6 +:101DC00002F00CBB30B5094D0A4491420DD011F818 +:101DD000013B5840082340F30004013B2C4013F022 +:101DE000FF0384EA5000F6D1EFE730BD2083B8ED61 +:101DF000F7B54FF0FF33DFF854C0DFF854E000EBE5 +:101E000081011A4688421CD050F8044B019401AF5E +:101E1000042417F8015B82EA05620825DB181646E0 +:101E200005F1FF355241002EBCBF83EA0C0382EA64 +:101E30000E0215F0FF05F1D1013C14F0FF04E8D1CA +:101E4000E0E7D843D14303B0F0BD00BF9336EAA921 +:101E5000EBE1F0422DE9F041C56915B9C161BDE87A +:101E6000F0814B6823F06047C3F38A464FEAD37E84 +:101E7000C3F3807816EA230638BF3E46AC462B46AD +:101E80005A68BEEBD27F22F060440AD0002A18DAEA +:101E9000A40CB44217D19D420FD10D60DEE713466A +:101EA000EEE7A74207D102F08044C2F380724245B8 +:101EB0000BD054B1EFE708D2EDE7CCF800100B607F +:101EC000CDE7B44201D0B442E5D81A689C46002A56 +:101ED000E5D11960C3E700002DE9F047089D01F046 +:101EE00007044FEAD508224405F0070500EBD100AE +:101EF0004FF47F49944201D1BDE8F08704F0070711 +:101F000005F0070A57453E4638BF5646C6F1080653 +:101F1000111B8E4228BF0E46E10808EBD50E415C2E +:101F200013F80EC0B94029FA06F721FA0AF1FFB2F8 +:101F30008CEA010147FA0AF739408CEA010C03F8F0 +:101F40000EC034443544D5E780EA0120082341F22D +:101F5000210201B24000002980B203F1FF33B8BF73 +:101F6000504013F0FF03F4D17047000038B50C4621 +:101F70008D18A54200D138BD14F8011BFFF7E4FF0E +:101F8000F7E7000002684AB113680360C38801895B +:101F900001339BB29942C38038BF0381104670471A +:101FA00070B588B0202204460D4668460021FFF730 +:101FB0003FFE20460495FFF7E5FF024658B16B4609 +:101FC000054608AE1C4603CCB4422860696023462F +:101FD00005F10805F6D1104608B070BD082817D9DC +:101FE00009280CD00A280CD00B280CD00C280CD0B7 +:101FF0000D280CD00E2814BF4020302070470C2034 +:102000007047102070471420704718207047202018 +:1020100070470000082817D90C280CD910280CD9B3 +:1020200014280CD918280CD920280CD930288CBF9A +:102030000F200E207047092070470A2070470B20A0 +:1020400070470C2070470D207047000010B54B689A +:1020500023B9CA8A63F30902CA8210BDC4681A6828 +:102060001C60C360438A013B43824A60EFE7000083 +:102070002DE9F84F1D46CB8A0F46C3F30901062907 +:10208000814692460B4630D00020AAB207F11904CF +:102090009EB2052E1FFA80F80FD8904503F1010378 +:1020A00006D3FB8A0A4462F30903FB8201201AE08B +:1020B0001AF80060E6540130EAE79045F1D2A1F148 +:1020C000060B1C237C68BBFBF3F203FB12BB1FFA5D +:1020D0008BF6002C45D14846FFF754FF044638B92B +:1020E00078606FF00200BDE8F88F4FF00008E6E777 +:1020F000002606607860ADB24FF0000B454510D960 +:102100000AEB0803221D13F8011B9155B1B208F127 +:1021100001081B291FFA88F82BD0454506F1010656 +:10212000F1D8FB8AC3F30902154465F30903BCE740 +:10213000013292B21C462368002BF9D1AB1F0B442D +:102140001C21B3FBF1F301339BB29A42D3D2BBF112 +:10215000000FD0D14846FFF715FF20B9C4F800B0F2 +:10216000BFE70122E7E7C0F800B05E462060044602 +:10217000C1E74545D5D94846FFF704FF08B92060B7 +:10218000AFE7C0F800B0002620600446B6E70000C4 +:102190002DE9F04F2DED028B83B0CDE90013BDF892 +:1021A0003C5007469146002A00F092802DB10E9BCC +:1021B000002B00F08D80072D32D807F10C00FFF7BF +:1021C000E1FE044638B96FF00204204603B0BDECCE +:1021D000028BBDE8F08F14220021FFF729FD0E9934 +:1021E0002A4604F10800FFF7FDFC681CC0B2FFF7A7 +:1021F00011FFFFF7F3FE207499F80030013814FA4C +:1022000080F003F01F0363F03F030372009B43F071 +:102210000041616038462146FFF71CFE0124D4E7E7 +:1022200000F10C034FF0000808EE103A4FF0800A5E +:102230004646444618EE100AFFF7A4FE83460028DF +:10224000C1D014220021FFF7F3FCC6BB019BABF801 +:10225000083002200E9B00F1080299195BFA82F205 +:102260000130C0B2082801D0AE422AD3FFF7D2FE17 +:10227000FFF7B4FE99F80020009B411E02F01F02F8 +:1022800042EA4812AE4208BF4FF0400A5BFA81F1C1 +:102290004AEA020A43F0004281F808A08BF81000D5 +:1022A000CBF8042059463846FFF7D4FD0134AE423E +:1022B00024B288F001084FF0000ABBD185E7002066 +:1022C000C8E711F801CB02F801CB0136B6B2C7E777 +:1022D0006FF0010479E70000F8B515460E46282294 +:1022E000002104461F46FFF7A3FC069B6360B5F57B +:1022F000001F079BA76034BF6A094FF6FF72236275 +:1023000004F10C0097B200239A4205D80023036021 +:1023100027826382A382F8BD0660013330462036EF +:10232000F2E7000003781BB94BB2002BC8BF017065 +:1023300070470000007870472DE9F74FDDF83C90BA +:10234000BDF830500D9E9DF83840BDF84070804675 +:1023500092469B46B9F1000F01D1002F51D11F2C9D +:102360004FD898F80000B0B9072F47D835F00303CD +:1023700047D13A4649464FF6FF70FFF7F7FD20F088 +:1023800001002D02400445EA0464400C44EA402464 +:102390004FF6FF7321E040EA0520072F40EA04646E +:1023A000F6D900254FF6FF73C5F12000A5F12002F4 +:1023B0002AFA05F10BFA00F001432BFA02F211435D +:1023C0001846C9B2FFF7C0FD0835402D0346EBD1D2 +:1023D0003A464946FFF7CAFD0346CDE90097324623 +:1023E00021464046FFF7D4FE33780133DBB21F2B82 +:1023F00088BF0023337003B0BDE8F08F6FF0030097 +:10240000F9E76FF00100F6E72DE9F04F85B092464D +:10241000DDF848800F9D9DF840209DF84490BDF860 +:102420004C7006469B46B8F1000F01D1002F48D1F1 +:102430001F2A46D83378002B46D00C0244EA0264A7 +:102440009DF8381044EAC93444EA01441C43072F7C +:1024500044F0800432D900234FF6FF72C3F1200C00 +:10246000A3F120002AFA03F10BFA0CFC41EA0C015B +:102470002BFA00F00143C9B210460393FFF764FD45 +:10248000039B0833402B0246E8D13A464146FFF70A +:102490006DFD0346CDE900872A4621463046FFF709 +:1024A00077FEB9F1010F06D12B780133DBB21F2B78 +:1024B00088BF00232B7005B0BDE8F08F4FF6FF7387 +:1024C000E8E76FF00100F6E76FF00300F3E70000C4 +:1024D000C06900B104307047C3691A68C261C2683C +:1024E0001A60C360438A013B438270472DE9F04183 +:1024F000D0F81880194E14461D464146002709B9E8 +:10250000BDE8F081D1E90223A21A65EB03039642EC +:1025100077EB03031ED283698B420DD1FFF796FD43 +:1025200083691B688361C3680B60438AC1608169EA +:10253000013B43828846E2E7FFF788FD0B68C8F855 +:102540000030C3680B60438AC160013B4382D8F806 +:102550000010D4E788460968D1E700BF80841E00D8 +:102560002DE9F04F8BB00D46DDF8509014469B4698 +:102570008046002800F01981B9F1000F00F01581A4 +:10258000531E3F2B00F21181012A03D1BBF1000F32 +:1025900040F00B810023CDE90833B8F81430B5EBD7 +:1025A000C30F4FEAC30703D300200BB0BDE8F08F81 +:1025B0002B199F42D8F80C303ABF7F1BFFB2274639 +:1025C0001BB9D8F81030002B7AD02F2D4ED8C5F17A +:1025D0003006B7424FF000032CBFF6B23E460093E0 +:1025E0002946D8F8080008AB3246FFF775FCA7EB80 +:1025F000060A35445FFA8AFAB8F8143003F100533A +:10260000063BDB000493D8F80C3003933021039B86 +:1026100013B1BAF1000F2CD1D8F8100040B1BAF1C3 +:10262000000F05D0009608AB5246691AFFF754FC1C +:1026300038B2002FB8D066070AD00AAB03EBD4013A +:10264000624211F8083C02F00702134101F8083C0D +:10265000082C3CD9102C40F2B580202C40F2B780D9 +:10266000BBF1000F00F09C80082334E0BA4600263E +:10267000C2E7049BE02B28BFE02306930B44AB4248 +:10268000059314D95A1B03980096924534BF5246BD +:10269000D2B2691A08AB04300792FFF71DFC079A03 +:1026A0001644AAEB020A1544F6B25FFA8AFA049BB2 +:1026B000069A05999B1A0493039B1B680393A6E74C +:1026C0000093D8F8080008AB3A462946AEE7BBF1BC +:1026D000000F13D00123B4EBC30F6CD0082C12D819 +:1026E0009DF82030621E23FA02F2D50706D54FF07E +:1026F000FF3202FA04F423438DF820309DF8203095 +:1027000089F8003051E7102C12D8BDF82030621E35 +:1027100023FA02F2D10706D54FF0FF3202FA04F491 +:102720002343ADF82030BDF82030A9F800303CE755 +:10273000202C0FD80899631E21FA03F3DA0705D578 +:102740004FF0FF3202FA04F40C430894089BC9F8D6 +:1027500000302AE7402C2BD0DDE90865611EC4F16A +:102760002102A4F1210326FA01F105FA02F225FA69 +:1027700003F311431943CB0712D50122A4F120031F +:10278000C4F1200102FA03F322FA01F1A2405242FD +:1027900043EA010363EB430332432B43CDE90823B0 +:1027A000DDE90823C9E90023FFE66FF00100FCE63C +:1027B0006FF00800F9E6082CA0D9102CB3D9202C12 +:1027C000EED8C3E7BBF1000FADD0022383E7BBF126 +:1027D000000FBBD004237EE730B5012A144638BF72 +:1027E0000124402C85B028BF40240025012ACDE9D2 +:1027F000025518D81B788DF8083063070AD004AB4F +:1028000003EBD405624215F8083C02F0070293403E +:1028100005F8083C009103462246002102A8FFF774 +:102820005BFB05B030BD082AE4D9102A03D81B8809 +:10283000ADF80830E1E7202A8DBFD3E900231B68FB +:102840000293CDE90223D8E710B5CB681BB98B60A2 +:102850000B618B8210BDC4681A681C60C360438A18 +:10286000013B4382CA60F0E72DE9F04FD1F80080C8 +:1028700093B018F0800FCDE90323C8F3C01219BF3D +:10288000C8F3C03BC8F306264FF0020B1646B8F15A +:10289000000F04460D4680F2D18118F0C043059325 +:1028A00040F0CC810B7B002B00F0C881BBF1020F04 +:1028B00003D00178B14240F0C48108F07F01069155 +:1028C0006AB3C8F3074A2B44069A93F80390760636 +:1028D00046EA0B4646EA82465FEAD91346EA0A060A +:1028E000079300F0908000220023CDE90A23069B85 +:1028F000009367685B4652460AA92046B8470028FD +:102900007ED0A7699FB9314604F10C00FFF748FB60 +:102910000746E0B96FF0020013B0BDE8F08FC8F3CE +:102920000F2A18F07F0F08BF0AF0030ACBE73B69B4 +:102930009E420DD03F68002FF9D1314604F10C00C2 +:10294000FFF72EFB07460028E4D0A3693B60A76190 +:10295000DDE90A2300264FF6FF70C6F1200E22FAA9 +:1029600006F103FA0EFEA6F1200C23FA0CFC41EA54 +:102970000E0141EA0C01C9B2083609920893FFF72B +:10298000E3FA402EDDE90832E7D1B882FB7D09F099 +:102990001F06C3F384039B1BD7E9022198B2002BC7 +:1029A000BCBF00F120031BB252EA0100C8F3046867 +:1029B0000FD00398821A049860EB0101A748904257 +:1029C0004FF000028A4104D3079A002A5BD0012B02 +:1029D00023DDFA7D4FEA890302F0030203F07C0352 +:1029E0001343FB7539462046FFF730FB079BA3B91D +:1029F000FB7DC3F38402013262F38603FB7504E0BE +:102A00006FF00B0088E7A76917B96FF00C0083E738 +:102A10003B699E42BAD03F68F6E719F0400F32D0CA +:102A2000039BBB60049BFB60142200210DA8FFF7F1 +:102A3000FFF8039B0A93049B0B932B1D0C932B7B9A +:102A4000ADF83EA0013BDBB2ADF83C30069B8DF803 +:102A5000433094F824308DF840B083F001038DF8B2 +:102A600044308DF84160A3688DF842800AA9204661 +:102A70009847FB7DC3F38403013303F01F039B02DC +:102A8000FB82002048E7FB7DC9F34012B2EBD31F65 +:102A900040F0DA80C3F38403B34240F0D880079952 +:102AA0002B7B4FEA9912002934D0D20741D4032B53 +:102AB00040F2D080039BBB60049BFB602B7BAE1D70 +:102AC000033BDBB23246394604F10C00FFF7D0FA83 +:102AD00000280DDA20463946FFF7B8FAFB7DC3F32C +:102AE0008403013303F01F039B02FB82032013E7DF +:102AF000AB883B832A7B033AB88AD2B23146FFF7D0 +:102B000035FAFB7DB882DA43C2F3C01262F3C71311 +:102B1000FB75B6E76AB92E1D013BDBB2324639467A +:102B200004F10C00FFF7A4FA0028D3DB2A7B013A5A +:102B3000E2E7F98AC1F30901013B0529DAB259D864 +:102B4000281D002307F11A0C9A4208D910F801EB4E +:102B50000CF801E0013101330629DBB2F4D103990D +:102B60000A9104990B91934207F11A010C9138BF15 +:102B7000043379680D9134BF55FA83F300230E9323 +:102B8000FB8AADF83EA0C3F309031A44069B8DF8F7 +:102B9000433094F82430ADF83C2083F001038DF8E5 +:102BA000443000238DF840B08DF841608DF84280AC +:102BB0007B602A7BB88A013A291DFFF7D7F93B8B46 +:102BC000B882834203D1A3680AA9204698472046C9 +:102BD0000AA9FFF739FEFB7DB88AC3F384030133EA +:102BE00003F01F039B02FB823B8B984214BF112012 +:102BF000002091E67B68002BB1D0062001E01C305C +:102C00006346D3F800C0BCF1000FF8D1091A081DC3 +:102C100005F1040C00EB030905989DF8143001EB55 +:102C2000000EBEF11B0F9AD89A4298D91CF8013BAE +:102C300009F8013B059B01330593EDE76FF00900AF +:102C40006AE66FF00A0067E66FF00D0064E66FF069 +:102C50000E0061E66FF00F005EE600BF80841E008C +:102C6000404BF0B51C6C404E44F000741C641D6E6B +:102C700045F000751D661B6E3C4B9B6AD3F80052F5 +:102C8000354045F00105C3F80052D3F80042344006 +:102C900044EA002040F00100C3F80002002952D0AD +:102CA0000020C3F81C020546C3F80402C3F80C0256 +:102CB000C3F8140203EBC00401301C28C4F84052CE +:102CC000C4F84452F6D100254FF0010C96781488D0 +:102CD000F70748BFD3F804720CFA04F044BF074367 +:102CE000C3F80472B70742BFD3F80C720743C3F8A6 +:102CF0000C72760742BFD3F814620643C3F814621D +:102D000003EBC4045668C4F840629668C4F8446291 +:102D1000D3F81C4201352043A942C3F81C0202F13A +:102D20000C02D3D1D3F8002222F00102C3F8002212 +:102D30000C4B1A6C22F000721A641A6E22F00072A8 +:102D40001A661B6EF0BD0122C3F84012C3F844128C +:102D5000C3F80412C3F81412C3F80C22C3F81C22DF +:102D6000E0E700BF003802400000FFFFD835002038 +:102D7000184A916A08B58B688B6013F0010104D082 +:102D800013F00C0F18BF4FF48031D80506D513F49B +:102D9000406F14BF41F4003141F00201D80306D561 +:102DA00013F4402F14BF41F4802141F00401D36992 +:102DB0000BB108489847202383F311880648002167 +:102DC00000F0AEFF002383F31188BDE8084001F056 +:102DD00023BC00BFD8350020E035002038B5124CA8 +:102DE000A36ADD68AA0712D05A6922F002025A616A +:102DF000A36913B1012120469847202383F311884A +:102E00000A48002100F08CFF002383F31188EB06B1 +:102E100006D5A36A1021D960236A0BB102489847EE +:102E2000BDE8384001F0F8BBD8350020E835002077 +:102E300038B5124CA36A1D69AA0712D05A6922F04C +:102E400010025A61A36913B102212046984720233A +:102E500083F311880A48002100F062FF002383F306 +:102E60001188EB0606D5A36A10211961236A0BB1FC +:102E700002489847BDE8384001F0CEBBD835002065 +:102E8000E835002038B50F4CA36A5D685D602A07FD +:102E90000AD5042222701A6822F002021A60636ABC +:102EA00013B10021204698476B0706D5A36A99699C +:102EB000236A13B1034809049847BDE8384001F07C +:102EC000ABBB00BFD835002010B50E4C204600F03B +:102ED00029F90D4BA3620B21132000F00BF90B21F4 +:102EE000142000F007F90B21152000F003F90B2145 +:102EF000162000F0FFF80022BDE8104011460E2019 +:102F0000FFF7AEBED835002000640040114B984258 +:102F100010B5044609D1104B1A6C42F000721A64C5 +:102F20001A6E42F000721A661B6EA36A01221A60C2 +:102F3000A36A5A68D20707D5626851681268D961D6 +:102F40001A60064A5A6110BD0121082000F0D4FD24 +:102F5000EEE700BFD8350020003802405B87010053 +:102F600003291AD8DFE801F0020A0F14836A9B686C +:102F700013F0E05F14BF012000207047836A986857 +:102F8000C0F380607047836A9868C0F3C060704780 +:102F9000836A9868C0F30070704700207047000093 +:102FA00010B5032925D8DFE801F00225292D836A11 +:102FB0009968C1F30161183103EB0113107884069D +:102FC0004CBF54689488C0F300114FEA410148BFD8 +:102FD00041EAC40100F00F004CBF41F0040141EA96 +:102FE0004451586041F001019068D2689860DA60FD +:102FF000196010BD836A03F5C073DFE7836A03F5C8 +:10300000C873DBE7836A03F5D073D7E701290AD0D9 +:1030100002290FD081B9836ADA68920701D1186951 +:1030200003E001207047836AD86810F0030018BFDE +:1030300001207047836AF2E70020704710B539B964 +:10304000836AD96889071BD11B699C0704D110BD0D +:10305000012915D00229FAD1816AD1F8C031D1F8FD +:10306000C441D1F8C8011061D1F8CC0150612020D1 +:1030700008610869800717D1486940F0100012E024 +:10308000816AD1F8B031D1F8B441D1F8B8011061FA +:10309000D1F8BC0150612020C860C868800703D106 +:1030A000486940F002004861C3F34000C3F3800167 +:1030B000000140EA4111107920F030000143117104 +:1030C00089064BBF91681189DB085B0D4CBF63F328 +:1030D0001C0163F30A01137948BF916064F3030391 +:1030E00013714FEA14234FEA144458BF118113702F +:1030F0005480ACE700F1604303F561430901C9B2B4 +:1031000083F80013012200F01F039A4043099B003B +:1031100003F1604303F56143C3F880211A607047EF +:10312000FFF7D2BE012300F10802C0E902220370BA +:1031300000F110020023C0E90422C0E90633C0E90F +:10314000083343607047000010B52023044683F322 +:103150001188022303704160FFF7D8FE0423237017 +:10316000002383F3118810BD2DE9F0411F4604466A +:103170000D461646202383F3118800F108082378B2 +:10318000052B0DD029462046FFF7EAFE40B1204628 +:1031900032462946FFF704FF002080F3118808E03B +:1031A0003946404600F0A0FD0028E8D0002383F314 +:1031B0001188BDE8F08100002DE9F0411F4604466A +:1031C0000D461646202383F3118800F1100823785A +:1031D000052B0DD029462046FFF718FF40B12046A9 +:1031E00032462946FFF72AFF002080F3118808E0C5 +:1031F0003946404600F078FD0028E8D0002383F3EC +:103200001188BDE8F0810000026843681143016045 +:1032100003B118477047000013B5446BD4F89434D9 +:103220001A681178042915D1217C022912D1197943 +:10323000128901238B4013420CD101A904F14C00E7 +:1032400001F0A8FFD4F89444019B2179024620683C +:1032500000F0CEF902B010BD143001F02BBF000019 +:103260004FF0FF33143001F025BF00004C3001F067 +:10327000FDBF00004FF0FF334C3001F0F7BF0000FE +:10328000143001F0F9BE00004FF0FF31143001F0AE +:10329000F3BE00004C3001F0C9BF00004FF0FF3218 +:1032A0004C3001F0C3BF00000020704710B5D0F8CB +:1032B00094341A6811780429044617D1017C022934 +:1032C00014D15979528901238B4013420ED1143005 +:1032D00001F08CFE024648B1D4F894444FF4807358 +:1032E00061792068BDE8104000F070B910BD0000A1 +:1032F000406BFFF7DBBF0000704700007FB5124B4B +:10330000036000234360C0E90233012502260F4B0E +:10331000057404460290019300F184022946009648 +:103320004FF48073143001F03DFE094B0294CDE957 +:10333000006304F523724FF48073294604F14C00B6 +:1033400001F004FF04B070BD0C5A0008F13200080F +:10335000193200080B68202282F311880A7903EBE6 +:10336000820290614A79093243F822008A7912B1C7 +:1033700003EB8203986102230374C0F894140023C2 +:1033800083F311887047000038B5037F044613B1FA +:1033900090F85430ABB9201D01250221FFF734FF0E +:1033A00004F1140025776FF0010100F0B9FC84F8F6 +:1033B000545004F14C006FF00101BDE8384000F0BA +:1033C000AFBC38BD10B5012104460430FFF71CFF27 +:1033D0000023237784F8543010BD000038B504462C +:1033E0000025143001F0F6FD04F14C00257701F0C2 +:1033F000C5FE201D84F854500121FFF705FF20462B +:10340000BDE83840FFF752BF90F8443003F0600346 +:10341000202B07D190F84520212A4FF0000303D834 +:103420001F2A06D800207047222AFBD1C0E90E339C +:1034300003E0034A82630722C263036401207047EA +:103440002523002037B5D0F894341A681178042960 +:1034500004461AD1017C022917D119791289012356 +:103460008B40134211D100F14C05284601F046FF74 +:1034700058B101A9284601F08DFED4F89444019B6F +:1034800021790246206800F0B3F803B030BD000097 +:10349000F0B500EB810385B09E6904460D46FEB190 +:1034A000202383F3118804EB8507301D0821FFF7E3 +:1034B000ABFEFB685B691B6806F14C001BB1019019 +:1034C00001F076FE019803A901F064FE024648B1BE +:1034D000039B2946204600F08BF8002383F31188D4 +:1034E00005B0F0BDFB685A691268002AF5D01B8A46 +:1034F000013B1340F1D104F14402EAE7093138B548 +:1035000050F82140DCB1202383F31188D4F89424AF +:103510001368527903EB8203DB689B695D6845B1F0 +:1035200004216018FFF770FE294604F1140001F031 +:1035300067FD2046FFF7BAFE002383F3118838BDEC +:103540007047000001F02AB9012303700023C0E98D +:103550000133C36183620362C362436203637047E2 +:1035600038B50446202383F311880025C0E90355AC +:10357000C0E90555416001F021F90223237085F36C +:10358000118838BD70B500EB810305465069DA60DB +:103590000E46144618B110220021FEF749FBA0691F +:1035A00018B110220021FEF743FB31462846BDE842 +:1035B000704001F0CDB90000826802F00112826013 +:1035C0000022C0E90422826101F04EBAF0B400EB9F +:1035D00081044789E4680125A4698D403D43458104 +:1035E00023600023A2606360F0BC01F069BA0000B0 +:1035F000F0B400EB81040789E468012564698D401B +:103600003D43058123600023A2606360F0BC01F0AC +:10361000E3BA000070B50223002504460370C0E938 +:103620000255C0E90455C564856180F8345001F045 +:103630002BF963681B6823B129462046BDE870401A +:10364000184770BD037880F8503005230370436835 +:103650001B6810B504460BB1042198470023A360F2 +:1036600010BD000090F85020436802701B680BB139 +:10367000052118477047000070B590F834300446B3 +:1036800013B1002380F8343004F14402204601F0E5 +:103690000DFA63689B68B3B994F8443013F0600581 +:1036A00035D00021204601F05FFC0021204601F0CA +:1036B00051FC63681B6813B1062120469847062316 +:1036C00084F8343070BD204698470028E4D0B4F820 +:1036D0004A30E26B9A4288BFE36394F94430E56B69 +:1036E000002B4FF0200380F20381002D00F0F280C8 +:1036F000092284F8342083F311880021D4E90E23B1 +:103700002046FFF775FF002383F31188DAE794F86A +:10371000452003F07F0343EA022340F20232934242 +:1037200000F0C58021D8B3F5807F48D00DD8012B9B +:103730003FD0022B00F09380002BB2D104F14C0259 +:10374000A2630222E2632364C1E7B3F5817F00F044 +:103750009B80B3F5407FA4D194F84630012BA0D1D3 +:10376000B4F84C3043F0020332E0B3F5006F4DD0B3 +:1037700017D8B3F5A06F31D0A3F5C063012B90D853 +:10378000636894F846205E6894F84710B4F84830AF +:103790002046B047002884D04368A3630368E363EE +:1037A0001AE0B3F5106F36D040F6024293427FF430 +:1037B00078AF5C4BA3630223E3630023C3E794F871 +:1037C0004630012B7FF46DAFB4F84C3023F0020388 +:1037D000C4E90E55A4F84C30256478E7B4F84430B9 +:1037E000B3F5A06F0ED194F8463084F84E302046E1 +:1037F00001F0A2F863681B6813B1012120469847C5 +:10380000032323700023C4E90E339CE704F14F0324 +:10381000A3630123C3E72378042B10D1202383F370 +:1038200011882046FFF7C8FE85F3118803216368DD +:1038300084F84F5021701B680BB12046984794F8CC +:103840004630002BDED084F84F30042323706368A9 +:103850001B68002BD6D0022120469847D2E794F867 +:1038600048301D0603F00F0120460AD501F010F97B +:10387000012804D002287FF414AF2B4B9AE72B4B7E +:1038800098E701F0F7F8F3E794F84630002B7FF45F +:1038900008AF94F8483013F00F01B3D01A06204651 +:1038A00002D501F075FBADE701F068FBAAE794F8DB +:1038B0004630002B7FF4F5AE94F8483013F00F013A +:1038C000A0D01B06204602D501F04EFB9AE701F07E +:1038D00041FB97E7142284F8342083F311882B46A8 +:1038E0002A4629462046FFF771FE85F31188E9E64E +:1038F0005DB1152284F8342083F311880021D4E9C6 +:103900000E232046FFF762FEFDE60B2284F83420EA +:1039100083F311882B462A4629462046FFF768FE86 +:10392000E3E700BF3C5A0008345A0008385A000840 +:1039300038B590F834300446002B3ED0063BDAB25E +:103940000F2A34D80F2B32D8DFE803F03731310893 +:10395000223231313131313131313737C56BB0F845 +:103960004A309D4214D2C3681B8AB5FBF3F203FBB5 +:1039700012556DB9202383F311882B462A46294618 +:10398000FFF736FE85F311880A2384F834300EE001 +:10399000142384F83430202383F3118800231A463B +:1039A00019462046FFF712FE002383F3118838BD25 +:1039B000036C03B198470023E7E70021204601F09C +:1039C000D3FA0021204601F0C5FA63681B6813B1E1 +:1039D0000621204698470623D7E7000010B590F847 +:1039E0003430142B044629D017D8062B05D001D823 +:1039F0001BB110BD093B022BFBD80021204601F072 +:103A0000B3FA0021204601F0A5FA63681B6813B1E0 +:103A1000062120469847062319E0152BE9D10B23F0 +:103A200080F83430202383F3118800231A46194686 +:103A3000FFF7DEFD002383F31188DAE7C3689B6993 +:103A40005B68002BD5D1036C03B19847002384F841 +:103A50003430CEE7024B0022C3E900339A6070474E +:103A600004360020002303748268054B1B689968A4 +:103A70009142FBD25A680360426010605860704700 +:103A80000436002008B5202383F31188037C032B20 +:103A900005D0042B0DD02BB983F3118808BD4369E1 +:103AA00000221A604FF0FF334361FFF7DBFF002372 +:103AB000F2E7D0E9003213605A60F3E700230374A1 +:103AC0008268054B1B6899689142FBD85A6803606D +:103AD000426010605860704704360020054B196939 +:103AE0000874186802681A6053601861012303742F +:103AF000FCF78EBD0436002030B54B1C0B4D87B053 +:103B0000044610D02B690A4A01A800F025F9204686 +:103B1000FFF7E4FF049B13B101A800F059F92B69EA +:103B2000586907B030BDFFF7D9FFF8E70436002029 +:103B3000853A000838B50C4D41612B6981689A6857 +:103B40009142044603D8BDE83840FFF78BBF1846C2 +:103B5000FFF7B4FF01232C61014623742046BDE822 +:103B60003840FCF755BD00BF04360020044B1A68EE +:103B70001B6990689B68984294BF002001207047A1 +:103B80000436002010B5084C236820691A682260AA +:103B90005460012223611A74FFF790FF01462069E7 +:103BA000BDE81040FCF734BD0436002008B5FFF72F +:103BB000DDFF18B1BDE80840FFF7E4BF08BD000015 +:103BC000FFF7E0BFFEE7000010B50C4CFFF742FF27 +:103BD00000F0B4F80A498022204600F03BF80123A7 +:103BE00044F8180C037400F0F3FC002383F31188ED +:103BF00062B60448BDE8104000F04CB82C360020F6 +:103C0000405A0008505A000800F01CB9EFF3118028 +:103C100020B9EFF30583202282F31188704700005A +:103C200010B530B9EFF30584C4F3080414B180F380 +:103C3000118810BDFFF7BAFF84F31188F9E700007F +:103C4000034A516853685B1A9842FBD8704700BF1B +:103C5000001000E082600222028270478368A3F1B4 +:103C60007C0243F80C2C026943F83C2C426943F86F +:103C7000382C074A43F81C2CC26843F8102C022247 +:103C800003F8082C002203F8072CA3F11800704752 +:103C90002906000810B5202383F31188FFF7DEFF03 +:103CA00000210446FFF746FF002383F311882046D6 +:103CB00010BD0000024B1B6958610F20FFF70EBFBB +:103CC00004360020202383F31188FFF7F3BF0000A0 +:103CD00008B50146202383F311880820FFF70CFF65 +:103CE000002383F3118808BD49B1064B42681B6964 +:103CF00018605A60136043600420FFF7FDBE4FF068 +:103D0000FF307047043600200368984206D01A68D6 +:103D10000260506059611846FFF7A4BE704700006A +:103D200038B504460D462068844200D138BD03688A +:103D300023605C604561FFF795FEF4E7054B03F1F6 +:103D40001402C3E905224FF0FF310022C3E9071234 +:103D5000704700BF0436002070B51C4EC0E9032335 +:103D600005460C4601F0FCFA334653F8142F9A42EC +:103D70000DD13062C5E901242A600A2C2CBF00193C +:103D80000A30C6E90555BDE8704001F0D7BA316A7E +:103D9000431AE31838BF1C469368A34202D9081996 +:103DA00001F0DAFA73699A6894420CD85A68AC60E8 +:103DB0002B606A6015609A685D60121B9A604FF014 +:103DC000FF33F36170BD1B68A41AECE704360020D2 +:103DD00038B51B4C636998420DD0D0E900321360AE +:103DE0005A6000228168C2609A680A449A604FF063 +:103DF000FF33E36138BD2246036842F8143F0021D7 +:103E000093425A60C16003D1BDE8384001F09EBAC8 +:103E10009A688168256A0A449A6001F0A1FA636988 +:103E20009A68411B8A42E5D9AB181D1A092D206AF0 +:103E300098BF01F10A02BDE83840104401F08CBA85 +:103E4000043600202DE9F041184C002704F1140637 +:103E5000656901F085FA236AAA68C11A8A4215D8F1 +:103E600013442362D5E9003213605A606369D5F8C0 +:103E70000C80EF60B34201D101F068FA87F311883A +:103E80002869C047202383F31188E1E76169B142C3 +:103E900009D013441B1ABDE8F0410A2B2CBFC018EF +:103EA0000A3001F059BABDE8F08100BF04360020A5 +:103EB00000207047FEE70000704700004FF0FF3021 +:103EC0007047000002290CD0032904D001290748BB +:103ED00018BF00207047032A05D8054800EBC20030 +:103EE0007047044870470020704700BF345B0008EB +:103EF00034230020E85A000870B59AB005460846F9 +:103F000001A9144600F0C2F801A8FDF789FE431C80 +:103F10005B00C5E900340022237003236370C6B23E +:103F200001AB02341046D1B28E4204F1020401D832 +:103F30001AB070BD13F8011B04F8021C04F8010C40 +:103F40000132F0E708B5202383F311880348FFF717 +:103F500079FA002383F3118808BD00BFC037002021 +:103F600090F8443003F01F02012A07D190F8452051 +:103F70000B2A03D10023C0E90E3315E003F06003E0 +:103F8000202B08D1B0F848302BB990F84520212AD1 +:103F900003D81F2A04D8FFF737BA222AEBD0FAE752 +:103FA000034A82630722C26303640120704700BF93 +:103FB0002C23002007B5052917D8DFE801F01916D2 +:103FC00003191920202383F31188104A019001213D +:103FD000FFF7D8FA01980E4A0221FFF7D3FA0D48ED +:103FE000FFF7FCF9002383F3118803B05DF804FBAD +:103FF000202383F311880748FFF7C6F9F2E720234F +:1040000083F311880348FFF7DDF9EBE7885A0008CE +:10401000AC5A0008C037002038B50C4D0C4C0D4987 +:104020002A4604F10800FFF767FF05F1CA0204F110 +:1040300010000949FFF760FF05F5CA7204F1180086 +:104040000649BDE83840FFF757BF00BF883C002055 +:1040500034230020685A0008725A00087D5A00086C +:1040600070B5044608460D46FDF7DAFDC6B2204697 +:10407000013403780BB9184670BD32462946FDF766 +:10408000BBFD0028F3D10120F6E700002DE9F04741 +:1040900005460C46FDF7C4FD2B49C6B22846FFF77E +:1040A000DFFF08B10636F6B228492846FFF7D8FFE9 +:1040B00008B11036F6B2632E0BD8DFF88C80DFF82B +:1040C0008C90234FDFF894A02E7846B92670BDE877 +:1040D000F08729462046BDE8F04701F005BC252EB3 +:1040E0002ED1072241462846FDF786FD70B9194BAF +:1040F000224603F10C0153F8040B42F8040B8B42E7 +:10410000F9D11B78137007350D34DDE708224946D5 +:104110002846FDF771FD98B90F4BA21C19780909C3 +:104120000232C95D02F8041C13F8011B01F00F01F3 +:104130005345C95D02F8031CF0D118340835C3E7B4 +:1041400004F8016B0135BFE7545B00087D5A000895 +:104150006A5B00085C5B0008107AFF1F1C7AFF1F77 +:10416000BFF34F8F024AD368DB03FCD4704700BF14 +:10417000003C024008B5094B1B7873B9FFF7F0FF0C +:10418000074B1A69002ABFBF064A5A6002F18832FB +:104190005A601A6822F480621A6008BDE63E002068 +:1041A000003C02402301674508B50B4B1B7893B9CF +:1041B000FFF7D6FF094B1A6942F000421A611A68EC +:1041C00042F480521A601A6822F480521A601A6807 +:1041D00042F480621A6008BDE63E0020003C0240C6 +:1041E0000B28F0B516D80C4C0C4923787BB90C4D34 +:1041F0000E460C234FF0006255F8047B46F8042B62 +:10420000013B13F0FF033A44F6D10123237051F828 +:104210002000F0BD0020FCE7183F0020E83E002011 +:104220007C5B0008014B53F8200070477C5B000862 +:104230000C2070470B2810B5044601D9002010BD92 +:10424000FFF7CEFF064B53F824301844C21A0BB9BF +:104250000120F4E712680132F0D1043BF6E700BF19 +:104260007C5B00080B2838B5044628D8FFF7CEFC45 +:10427000FFF776FFFFF77EFF124AF323D360E300D8 +:10428000DBB243F4007343F002031361136943F498 +:104290008033136105462046FFF762FFFFF7A0FF5A +:1042A000094B53F8241000F039F92846FFF77CFF3A +:1042B000FFF7B6FC2046BDE83840FFF7BBBF002043 +:1042C00038BD00BF003C02407C5B000812F00103D7 +:1042D0002DE9F04105460E4614464BD18218B2F145 +:1042E000016F61D8314B1B6813F001035CD0304F74 +:1042F000FFF78CFCFFF73EFFF323FB60FFF730FF77 +:10430000314640F20128032C18D824F00104284E2D +:104310000C446D1A40F20118A142336905EB010704 +:104320002AD123F001033361FFF73EFFFFF778FC4A +:104330000120BDE8F081043C0435E4E7AB07E4D19B +:104340003B6923F440733B613B6943EA08033B61EB +:1043500051F8046B2E60BFF34F8FFFF701FF2B68FE +:104360009E42E8D03B6923F001033B61FFF71CFF4D +:10437000FFF756FC0020DCE723F440733361336918 +:1043800043EA080333610B883B80BFF34F8FFFF78D +:10439000E7FE3F8831F8023BBFB2BB42BCD0336975 +:1043A00023F001033361E1E71846C2E70038024019 +:1043B000003C0240084908B50B7828B11BB9FFF74B +:1043C000D9FE01230B7008BD002BFCD0BDE80840CE +:1043D0000870FFF7E9BE00BFE63E002070B582B06E +:1043E000FFF714FC0E4E054600F0BAFF326890420B +:1043F00037BF0C4A0B49516814682EBFD1E9004100 +:10440000013151600419034641F100012846019130 +:104410003360FFF705FC0199204602B070BD00BF74 +:104420001C3F0020203F002070B582B0FFF7EEFB5C +:10443000104E054600F094FF3268904237BF0E4A96 +:104440000D49516814682EBFD1E900410131516016 +:10445000041941F100010346284601913360FFF73A +:10446000DFFB01994FF47A7200232046FBF7B8FE78 +:1044700002B070BD1C3F0020203F002010B5024458 +:10448000064BD2B2904200D110BD441C00B253F88A +:10449000200041F8040BE0B2F4E700BF50280040D0 +:1044A0000F4B30B51C6F240407D41C6F44F4007408 +:1044B0001C671C6F44F400441C670A4C236843F4D7 +:1044C000807323600244084BD2B2904200D130BDC9 +:1044D000441C00B251F8045B43F82050E0B2F4E70A +:1044E00000380240007000405028004007B501220B +:1044F00001A90020FFF7C2FF019803B05DF804FB9B +:1045000013B50446FFF7F2FFA04205D0012201A92E +:1045100000200194FFF7C4FF02B010BD70470000F7 +:10452000074B45F255521A6002225A6040F6FF725C +:104530009A604CF6CC421A60024B01221A70704706 +:10454000003000402C3F0020034B1B781BB1034B75 +:104550004AF6AA221A6070472C3F00200030004023 +:10456000034B1A681AB9034AD2F874281A607047C4 +:10457000283F002000300240024B4FF08072C3F809 +:10458000742870470030024008B5FFF7E9FF024B7E +:104590001868C0F3407008BD283F002008B5FFF739 +:1045A000DFFF024B1868C0F3007008BD283F0020F1 +:1045B000EFF3098305494A6B22F001024A6368332D +:1045C00083F30988002383F31188704700EF00E02C +:1045D000202080F3118862B60C4B0D4AD96821F473 +:1045E000E0610904090C0A43DA60D3F8FC200949A8 +:1045F00042F08072C3F8FC200A6842F001020A60AF +:104600001022DA7783F82200704700BF00ED00E047 +:104610000003FA05001000E010B5202383F3118891 +:104620000E4B5B6813F4006314D0F1EE103AEFF315 +:104630000984683C4FF08073E361094BDB6B2366B0 +:1046400084F30988FFF792FA10B1064BA36110BDFD +:10465000054BFBE783F31188F9E700BF00ED00E0AD +:1046600000EF00E03B0600083E060008704700002F +:10467000FEE700000A4B0B480B4A90420BD30B4B52 +:10468000DA1C121AC11E22F003028B4238BF00222C +:104690000021FDF7CDBA53F8041B40F8041BECE7EA +:1046A000345D0008284000202840002028400020D9 +:1046B0007047000070B5D0E915439E6800224FF0A6 +:1046C000FF3504EB42135101D3F800090028BEBFA7 +:1046D000D3F8000940F08040C3F80009D3F8000B7C +:1046E0000028BEBFD3F8000B40F08040C3F8000B99 +:1046F000013263189642C3F80859C3F8085BE0D248 +:104700004FF00113C4F81C3870BD00001D4B03EBC3 +:1047100080022DE9F043D2F80CC05D6DDCF8142066 +:10472000461CD2F800E005EB063605EB4018516850 +:1047300071450AD3D5F83438012202FA00F023EA91 +:104740000000C5F83408BDE8F083BCF81040AEEBBB +:104750000103A34228BF2346D8F81849A4B2B3EBFB +:10476000840FF0D89468A4F1040959F8047F3760E5 +:10477000A4EB09071F44042FF7D81C440B44946092 +:104780005360D4E7303F0020890141F020010161EE +:1047900003699B06FCD41220FFF752BA10B5054CF2 +:1047A0002046FEF7D1FE4FF0A0436365024BA365A0 +:1047B00010BD00BF303F0020D05B000870B503780B +:1047C000012B054650D12A4B446D98421BD1294BF1 +:1047D0005A6B42F080025A635A6D42F080025A6569 +:1047E0005A6D5A6942F080025A615A6922F0800279 +:1047F0005A610E2143205B69FEF77CFC1E4BE3608F +:104800001E4BC4F800380023C4F8003EC0232360C8 +:104810006E6D4FF40413A3633369002BFCDA01239C +:1048200033610C20FFF70CFA3369DB07FCD412204C +:10483000FFF706FA3369002BFCDA0026A66028464B +:10484000FFF738FF6B68C4F81068DB68C4F81468B9 +:10485000C4F81C684BB90A4BA3614FF0FF33636186 +:10486000A36843F00103A36070BD064BF4E700BFEB +:10487000303F002000380240401400400300200276 +:10488000003C30C0083C30C0F8B5446D05460021FE +:104890002046FFF779FFA96D00234FF001128F68C2 +:1048A000C4F834384FF00066C4F81C284FF0FF30CD +:1048B00004EB431201339F42C2F80069C2F8006B57 +:1048C000C2F80809C2F8080BF2D20B686A6DEB65F2 +:1048D000636210231361166916F01006FBD11220D3 +:1048E000FFF7AEF9D4F8003823F4FE63C4F80038BB +:1048F000A36943F4402343F01003A3610923C4F8E0 +:104900001038C4F814380A4BEB604FF0C043C4F8B9 +:10491000103B084BC4F8003BC4F81069C4F80039D8 +:10492000EB6D03F1100243F48013EA65A362F8BD56 +:10493000AC5B000840800010426D90F84E10D2F839 +:10494000003823F4FE6343EA0113C2F800387047CD +:104950002DE9F84300EB8103456DDA68166806F02F +:104960000306731E022B05EB41130C4680460FFA1B +:1049700081F94FEA41104FF00001C3F8101B4FF0CE +:10498000010104F1100398BFB60401FA03F3916921 +:104990008EBF334E06F1805606F5004600293AD008 +:1049A000578A04F15801490137436F50D5F81C1854 +:1049B0000B43C5F81C382B180021C3F81019536994 +:1049C0000127611EA7409BB3138A928B9B08012A83 +:1049D00088BF5343D8F85C20981842EA034301F19A +:1049E000400205EB8202C8F85C002146536028466D +:1049F000FFF7CAFE08EB8900C3681B8A43EA8453A9 +:104A0000483464011E432E51D5F81C381F43C5F8A5 +:104A10001C78BDE8F88305EB4917D7F8001B21F493 +:104A20000041C7F8001BD5F81C1821EA0303C0E7B2 +:104A300004F13F0305EB83030A4A5A6028462146E6 +:104A4000FFF7A2FE05EB4910D0F8003923F400432C +:104A5000C0F80039D5F81C3823EA0707D7E700BFAC +:104A60000080001000040002826D1268C265FFF72A +:104A700021BE00005831436D49015B5813F40040DA +:104A800004D013F4001F0CBF022001207047000067 +:104A90004831436D49015B5813F4004004D013F4CE +:104AA000001F0CBF022001207047000000EB8101B5 +:104AB000CB68196A0B6813604B685360704700003D +:104AC00000EB810330B5DD68AA691368D36019B9BA +:104AD000402B84BF402313606B8A1468426D1C44D2 +:104AE000013CB4FBF3F46343033323F0030302EB11 +:104AF000411043EAC44343F0C043C0F8103B2B6865 +:104B000003F00303012B09B20ED1D2F8083802EBEF +:104B1000411013F4807FD0F8003B14BF43F0805362 +:104B200043F00053C0F8003B02EB4112D2F8003BC7 +:104B300043F00443C2F8003B30BD00002DE9F041D2 +:104B4000244D6E6D06EB40130446D3F8087BC3F882 +:104B5000087B38070AD5D6F81438190706D505EBAF +:104B600084032146DB6828465B689847FA071FD50F +:104B7000D6F81438DB071BD505EB8403D968CCB90C +:104B80008B69488A5A68B2FBF0F600FB16228AB994 +:104B90001868DA6890420DD2121AC3E90024202363 +:104BA00083F311880B482146FFF78AFF84F31188AD +:104BB000BDE8F081012303FA04F26B8923EA0203C2 +:104BC0006B81CB68002BF3D021460248BDE8F04151 +:104BD000184700BF303F002000EB810370B5DD684F +:104BE000436D6C692668E6604A0156BB1A444FF46F +:104BF0000020C2F810092A6802F00302012A0AB252 +:104C00000ED1D3F8080803EB421410F4807FD4F8D7 +:104C1000000914BF40F0805040F00050C4F8000973 +:104C200003EB4212D2F8000940F00440C2F8000938 +:104C3000D3F83408012202FA01F10143C3F8341811 +:104C400070BD19B9402E84BF4020206020682E8A94 +:104C50008419013CB4FBF6F440EAC44040F0005033 +:104C60001A44C6E7F8B504461E48456D05EB4413E3 +:104C7000D3F80869C3F80869F10717D5D5F81038D3 +:104C8000DA0713D500EB8403D9684B691F68DA682B +:104C9000974218D2D21B00271A605F60202383F34B +:104CA00011882146FFF798FF87F31188330617D53F +:104CB000D5F834280123A340134211D02046BDE883 +:104CC000F840FFF723BD012303FA04F2038923EA26 +:104CD000020303818B68002BE8D021469847E5E763 +:104CE000F8BD00BF303F00202DE9F74F984C666DAE +:104CF0007569B3691D4015F48058756107D0204669 +:104D0000FEF788FC03B0BDE8F04FFFF785BC002D2F +:104D100012DAD6F8003E8E489F071EBFD6F8003E36 +:104D200023F00303C6F8003ED6F8043823F001034D +:104D3000C6F80438FEF796FC280505D58448FFF729 +:104D4000B9FC8348FEF77EFCA9040CD5D6F80838D8 +:104D500013F0060FF36823F470530CBF43F41053A1 +:104D600043F4A053F3602A0704D56368DB680BB1F2 +:104D700077489847EB0274D4AF0227D5D4F8549003 +:104D8000DFF8CCB100274FF0010A09EB4712D2F847 +:104D9000003B03F44023B3F5802F11D1D2F8003B40 +:104DA000002B0DDA62890AFA07F322EA0303638112 +:104DB00004EB8703DB68DB6813B139465846984734 +:104DC000A36D01379B68FFB29F42DED9E80617D575 +:104DD000676D3A6AC2F30A1002F00F0302F4F01290 +:104DE000B2F5802F00F08880B2F5402F08D104EB97 +:104DF00083030022DB681B6A07F5805790426DD160 +:104E00002903D6F8184813D5E20302D50020FFF78E +:104E100095FEA30302D50120FFF790FE670302D59C +:104E20000220FFF78BFE260302D50320FFF786FE44 +:104E30006D037FF567AFE00702D50020FFF712FF93 +:104E4000A10702D50120FFF70DFF620702D502205E +:104E5000FFF708FF23077FF555AF0320FFF702FF99 +:104E600050E7636DDFF8E8B0019300274FF0010AC7 +:104E7000A36D9B685FFA87F999453FF67DAF019B6B +:104E800003EB4913D3F8002902F44022B2F5802F36 +:104E900022D1D3F80029002A1EDAD3F8002942F0E3 +:104EA0009042C3F80029D3F80029002AFBDB606D8B +:104EB0004946FFF769FC22890AFA09F322EA03034B +:104EC000238104EB8903DB689B6813B1494658468C +:104ED00098474846FFF71AFC0137C9E7910708BF12 +:104EE000D7F80080072A98BF03F8018B02F101026E +:104EF00098BF4FEA182881E7023304EB830207F5D5 +:104F000080575268D2F818C0DCF80820DCE9001C91 +:104F1000A1EB0C0C002188420AD104EB83046368E6 +:104F20009B699A6802449A605A6802445A6067E72B +:104F300011F0030F08BFD7F800808C4588BF02F836 +:104F4000018B01F1010188BF4FEA1828E3E700BF98 +:104F5000303F0020436D03EB4111D1F8003B43F497 +:104F60000013C1F8003B7047436D03EB4111D1F8CA +:104F7000003943F40013C1F800397047436D03EB67 +:104F80004111D1F8003B23F40013C1F8003B7047F6 +:104F9000436D03EB4111D1F8003923F40013C1F83C +:104FA0000039704730B5039C0172043304FB0325BC +:104FB000C0E90653049B03630021059BC160C0E95F +:104FC0000000C0E90422C0E90842C0E90A114363B5 +:104FD00030BD0000416A0022C0E90411C0E90A2284 +:104FE000C2606FF00101FEF79BBE0000D0E9043201 +:104FF000934201D1C2680AB9181D7047002070475A +:1050000003691960C2680132C260C26913448269CF +:105010000361934224BF436A03610021FEF774BE1B +:1050200038B504460D46E3683BB16269131D12684A +:10503000A3621344E362002007E0237A33B92946D0 +:105040002046FEF751FE0028EDDA38BD6FF0010072 +:10505000FBE70000C368C269013BC36043691344B6 +:1050600082694361934224BF436A436100238362A0 +:10507000036B03B11847704770B52023044683F3D0 +:105080001188866A3EB9FFF7CBFF054618B186F353 +:105090001188284670BDA36AE26A13F8015BA36217 +:1050A000934202D32046FFF7D5FF002383F31188F4 +:1050B000EFE700002DE9F84F04460E4617469846E4 +:1050C0004FF0200989F311880025AA46D4F828B0AA +:1050D000BBF1000F09D141462046FFF7A1FF20B1E7 +:1050E0008BF311882846BDE8F88FD4E90A12A7EBA4 +:1050F000050B521A934528BF9346BBF1400F1BD9AD +:10510000334601F1400251F8040B43F8040B91427D +:10511000F9D1A36A40334036A3624035D4E90A236B +:105120009A4202D32046FFF795FF8AF31188BD42C9 +:10513000D8D289F31188C9E730465A46FCF752FDA8 +:10514000A36A5B445E44A3625D44E7E710B5029C3A +:105150000172043304FB0321C0E906130023C0E9F4 +:105160000A33039B0363049BC460C0E90000C0E9E9 +:105170000422C0E90842436310BD0000026AC26015 +:10518000426AC0E904220022C0E90A226FF001014C +:10519000FEF7C6BDD0E904239A4201D1C26822B904 +:1051A000184650F8043B0B60704700207047000021 +:1051B000C368C2690133C3604369134482694361B0 +:1051C000934224BF436A43610021FEF79DBD000066 +:1051D00038B504460D46E3683BB123691A1DA26247 +:1051E000E2691344E362002007E0237A33B92946D9 +:1051F0002046FEF779FD0028EDDA38BD6FF001009A +:10520000FBE7000003691960C268013AC260C26925 +:10521000134482690361934224BF436A03610023FC +:105220008362036B03B118477047000070B52023F9 +:105230000D460446114683F31188866A2EB9FFF79E +:10524000C7FF10B186F3118870BDA36A1D70A36AF1 +:10525000E26A01339342A36204D3E1692046043930 +:10526000FFF7D0FF002080F31188EDE72DE9F84F1C +:1052700004460D46904699464FF0200A8AF311885D +:105280000026B346A76A4FB949462046FFF7A0FF5C +:1052900020B187F311883046BDE8F88FD4E90A07BA +:1052A0003A1AA8EB0607974228BF1746402F1BD98A +:1052B00005F1400355F8042B40F8042B9D42F9D129 +:1052C000A36A4033A3624036D4E90A239A4204D346 +:1052D000E16920460439FFF795FF8BF311884645B5 +:1052E000D9D28AF31188CDE729463A46FCF77AFCF1 +:1052F000A36A3B443D44A3623E44E5E7D0E904236E +:105300009A4217D1C3689BB1836A8BB1043B9B1A45 +:105310000ED01360C368013BC360C3691A4483693C +:1053200002619A4224BF436A03610023836201231E +:10533000184670470023FBE700F088B84FF0804321 +:10534000002258631A610222DA6070474FF08043EE +:105350000022DA60704700004FF0804358637047C6 +:105360004FF08043586A70474B6843608B68836096 +:10537000CB68C3600B6943614B6903628B6943620D +:105380000B6803607047000008B5264B26481A6971 +:1053900040F2FF110A431A611A6922F4FF7222F0E7 +:1053A00001021A611A691A6B0A431A631A6D0A43D9 +:1053B0001A651E4A1B6D1146FFF7D6FF02F11C014C +:1053C00000F58060FFF7D0FF02F1380100F5806042 +:1053D000FFF7CAFF02F1540100F58060FFF7C4FF38 +:1053E00002F1700100F58060FFF7BEFF02F18C0151 +:1053F00000F58060FFF7B8FF02F1A80100F58060BA +:10540000FFF7B2FF02F1C40100F58060FFF7ACFFC7 +:1054100002F1E00100F58060FFF7A6FFBDE808405B +:1054200000F09AB80038024000000240DC5B00083F +:1054300008B500F007FAFEF7C7FBFFF791F8BDE8E3 +:105440000840FEF7E9BD000070470000104B1A6CE1 +:1054500042F001021A641A6E42F001021A660D4A05 +:105460001B6E936843F0010393604FF08043532217 +:105470009A624FF0FF32DA6200229A615A63DA6070 +:105480005A6001225A6108211A601C20FDF732BEC1 +:1054900000380240002004E04FF0804208B5116956 +:1054A000D3680B40D9B2C9439B07116107D52023AC +:1054B00083F31188FEF7A8FB002383F3118808BD4E +:1054C00008B5FFF7E9FFBDE80840FFF7A5B8000001 +:1054D0001F4B1A696FEAC2526FEAD2521A611A69F7 +:1054E000C2F308021A614FF0FF301A695A69586115 +:1054F00000215A6959615A691A6A62F080521A6227 +:105500001A6A02F080521A621A6A5A6A58625A6A11 +:1055100059625A6A1A6C42F080521A641A6E42F04A +:1055200080521A661A6E0B4A106840F48070106040 +:10553000186F00F44070B0F5007F1EBF4FF480304C +:1055400018671967536823F40073536000F05AB961 +:105550000038024000700040334B4FF080521A6414 +:10556000324A4FF4404111601A6842F001021A6059 +:105570001A689107FCD59A6822F003029A602A4BB8 +:105580009A6812F00C02FBD1196801F0F901196058 +:105590009A601A6842F480321A601A689203FCD545 +:1055A0005A6F42F001025A671F4B5A6F9007FCD5A1 +:1055B0001F4A5A601A6842F080721A601B4A536888 +:1055C0005904FCD5184B1A689201FCD5194A9A6007 +:1055D000194B1A68194B9A42194B21D1194A116873 +:1055E000194A91421CD140F205121A60144A1368FC +:1055F00003F00F03052BFAD10B4B9A6842F002021D +:105600009A609A6802F00C02082AFAD15A6C42F4A5 +:1056100080425A645A6E42F480425A665B6E70470A +:1056200040F20572E1E700BF003802400070004020 +:105630000854400700948838002004E011640020DA +:10564000003C024000ED00E041C20F41084A08B5AD +:10565000516913680B4003F00103536123B1054AFC +:1056600013680BB150689847BDE80840FEF7D4BFF7 +:10567000003C0140A83F0020084A08B55169136862 +:105680000B4003F00203536123B1054A93680BB149 +:10569000D0689847BDE80840FEF7BEBF003C014017 +:1056A000A83F0020084A08B5516913680B4003F071 +:1056B0000403536123B1054A13690BB1506998473C +:1056C000BDE80840FEF7A8BF003C0140A83F00200D +:1056D000084A08B5516913680B4003F00803536189 +:1056E00023B1054A93690BB1D0699847BDE80840DA +:1056F000FEF792BF003C0140A83F0020084A08B5D1 +:10570000516913680B4003F01003536123B1054A3C +:10571000136A0BB1506A9847BDE80840FEF77CBF9A +:10572000003C0140A83F0020174B10B55A691C6887 +:10573000144004F478725A61A30604D5134A936A9C +:105740000BB1D06A9847600604D5104A136B0BB1B1 +:10575000506B9847210604D50C4A936B0BB1D06B64 +:105760009847E20504D5094A136C0BB1506C984771 +:10577000A30504D5054A936C0BB1D06C9847BDE8DE +:105780001040FEF749BF00BF003C0140A83F002089 +:105790001A4B10B55A691C68144004F47C425A61D3 +:1057A000620504D5164A136D0BB1506D9847230559 +:1057B00004D5134A936D0BB1D06D9847E00404D51E +:1057C0000F4A136E0BB1506E9847A10404D50C4AD2 +:1057D000936E0BB1D06E9847620404D5084A136FDC +:1057E0000BB1506F9847230404D5054A936F0BB152 +:1057F000D06F9847BDE81040FEF70EBF003C014057 +:10580000A83F0020062108B50846FDF773FC0621D5 +:105810000720FDF76FFC06210820FDF76BFC062131 +:105820000920FDF767FC06210A20FDF763FC06212D +:105830001720FDF75FFCBDE8084006212820FDF792 +:1058400059BC000008B5FFF743FE00F00DF8FDF766 +:1058500067FCFDF777FEFDF74FFDFFF7F5FDBDE8AF +:105860000840FFF769BD00000023054A19460133CF +:10587000102BC2E9001102F10802F8D1704700BFF5 +:10588000A83F002010B501390244904201D1002008 +:1058900005E0037811F8014FA34201D0181B10BD99 +:1058A0000130F2E72DE9F041A3B1C91A177801449C +:1058B000044603F1FF3C8C42204601D9002009E058 +:1058C0000578BD4204F10104F5D10CEB0405D618AE +:1058D000A54201D1BDE8F08115F8018D16F801ED62 +:1058E000F045F5D0E7E70000034611F8012B03F877 +:1058F000012B002AF9D170476F72672E61726475AF +:1059000070696C6F742E663430355F4D6174656BF1 +:10591000475053004E6F20617070207369670A0012 +:10592000426164206677206C656E67746820257517 +:105930000A0042616420626F6172645F69642025BD +:10594000752073686F756C642062652025750A0088 +:105950004261642066772064657363726970746F56 +:1059600072206C656E6774682025750A0042616458 +:105970002061707020435243203078253038783AC7 +:10598000307825303878203078253038783A3078BB +:10599000253038780A00476F6F64206669726D772A +:1059A0006172650A0040A2E4F1646891060000009B +:1059B00053544D3332463F3F3F00000053544D3364 +:1059C00032463430780053544D3332463432780006 +:1059D00053544D33324634343658580000000000DA +:1059E000B05900083F00000013040000BC59000833 +:1059F0003F00000019040000C65900083F000000E5 +:105A000021040000D05900083F0000000000000001 +:105A100075320008613200089D32000889320008A2 +:105A200095320008813200086D32000859320008B2 +:105A3000A932000800000000010000000000000082 +:105A40006D61696E0000000069646C650000000013 +:105A5000485A000848360020C037002001000000E6 +:105A6000C53B0008000000004172647550696C6F0E +:105A7000740025424F415244252D424C0025534588 +:105A80005249414C250000000200000000000000C7 +:105A900091340008FD34000840004000583C0020CC +:105AA000683C00200200000000000000030000002D +:105AB0000000000041350008000000001000000058 +:105AC000783C002000000000010000000000000001 +:105AD000303F002001010200B53F0008C53E00082C +:105AE000613F0008453F000843000000F05A0008ED +:105AF00009024300020100C0320904000001020251 +:105B00000100052400100105240100010424020203 +:105B10000524060001070582030800FF09040100AF +:105B2000020A00000007050102400000070581028B +:105B300040000000120000003C5B00081201100150 +:105B40000200004009124157000201020301000057 +:105B50000403090425424F41524425006634303580 +:105B60002D4D6174656B47505300303132333435FD +:105B70003637383941424344454600000040000072 +:105B80000040000000400000004000000000010054 +:105B900000000200000002000000020000000200FD +:105BA00000000200000002000000020000000000EF +:105BB0007936000831390008DD390008400040001E +:105BC000903F0020903F002001000000A03F0020F7 +:105BD000800000004001000003000000AA01A8129C +:105BE00000000000AAAAAAAA55011400FFBF0000E5 +:105BF0008877000070A70A0000000A01000000007A +:105C0000AAAAAAAA00000001FFFF000000000000ED +:105C1000990000000000A01600000000AAAAAAA691 +:105C200000005011FFDF00000000000000770800B6 +:105C30002000000000000000AAAAAAAA100000008C +:105C4000FFFF00000008000000000000000000004E +:105C500000000000AAAAAAAA00000000FFFF00009E +:105C60000000000000000000000000000000000034 +:105C7000AAAAAAAA00000000FFFF0000000000007E +:105C8000000000000000000000000000AAAAAAAA6C +:105C900000000000FFFF0000000000000000000006 +:105CA00000000000000000000A00000000000000EA +:105CB00003000000000000000000000000000000E1 +:105CC00000000000000000000000000000000000D4 +:105CD000000000000000000038A5FF7F0100000068 +:105CE000F60300000000000000000F0000000000AC +:105CF000640000000000000040420F00FE2A010086 +:105D0000D2040000FF00960000000008009600008A +:105D10000000080004000000505B000800000000C4 +:105D20000000000000000000000000000000000073 +:045D3000000000006F :00000001FF diff --git a/Tools/bootloaders/luminousbee5_bl.bin b/Tools/bootloaders/luminousbee5_bl.bin index c076108eb84..59bcdc042f5 100755 Binary files a/Tools/bootloaders/luminousbee5_bl.bin and b/Tools/bootloaders/luminousbee5_bl.bin differ diff --git a/Tools/bootloaders/luminousbee5_bl.elf b/Tools/bootloaders/luminousbee5_bl.elf index 01b2b10221f..ff00fb5b4ba 100755 Binary files a/Tools/bootloaders/luminousbee5_bl.elf and b/Tools/bootloaders/luminousbee5_bl.elf differ diff --git a/Tools/bootloaders/luminousbee5_bl.hex b/Tools/bootloaders/luminousbee5_bl.hex index 6d01b350af8..e6f79a6010c 100644 --- a/Tools/bootloaders/luminousbee5_bl.hex +++ b/Tools/bootloaders/luminousbee5_bl.hex @@ -1,34 +1,34 @@ :020000040800F2 -:1000000000060020A1020008E90F0008ED0F00081B -:1000100045100008ED0F000819100008A3020008A1 -:10002000A3020008A3020008A3020008592900083F +:1000000000060020A10200082D100008AD0F000816 +:1000100005100008AD0F0008D90F0008A302000862 +:10002000A3020008A3020008A30200082129000877 :10003000A3020008A3020008A3020008A30200080C :10004000A3020008A3020008A3020008A3020008FC -:10005000A3020008A3020008D93D0008053E0008DD -:10006000313E00085D3E0008893E0008A3020008FA +:10005000A3020008A3020008A93D0008D53D00083E +:10006000013E00082D3E0008593E0008A30200088A :10007000A3020008A3020008A3020008A3020008CC :10008000A3020008A3020008A3020008A3020008BC -:10009000A3020008A3020008A3020008B53E00085E +:10009000A3020008A3020008A3020008853E00088E :1000A000A3020008A3020008A3020008A30200089C :1000B000A3020008A3020008A3020008A30200088C :1000C000A3020008A3020008A3020008A30200087C :1000D000A3020008A3020008A3020008A30200086C -:1000E000193F0008A3020008A3020008A3020008A9 +:1000E000E93E0008A3020008A3020008A3020008DA :1000F000A3020008A3020008A3020008A30200084C -:10010000A3020008A3020008A13F0008A302000800 +:10010000A3020008A3020008713F0008A302000830 :10011000A3020008A3020008A3020008A30200082B :10012000A3020008A3020008A3020008A30200081B :10013000A3020008A3020008A3020008A30200080B :10014000A3020008A3020008A3020008A3020008FB :10015000A3020008A3020008A3020008A3020008EB :10016000A3020008A3020008A3020008A3020008DB -:10017000A3020008F9340008A3020008A302000843 -:10018000A3020008A30200088D3F0008A302000894 +:10017000A30200088D340008A3020008A3020008AF +:10018000A3020008A30200085D3F0008A3020008C4 :10019000A3020008A3020008A3020008A3020008AB :1001A000A3020008A3020008A3020008A30200089B :1001B000A3020008A3020008A3020008A30200088B :1001C000A3020008A3020008A3020008A30200087B -:1001D000A3020008E5340008A3020008A3020008F7 +:1001D000A302000879340008A3020008A302000863 :1001E000A3020008A3020008A3020008A30200085B :1001F000A3020008A3020008A3020008A30200084B :10020000A3020008A3020008A3020008A30200083A @@ -41,1036 +41,1036 @@ :10027000A3020008A3020008A3020008A3020008CA :10028000A3020008A3020008A3020008A3020008BA :10029000A3020008A3020008A3020008A3020008AA -:1002A00002E000F000F8FEE772B6394880F30888F3 -:1002B000384880F3098838484EF60851CEF20001DC +:1002A00002E000F000F8FEE772B63A4880F30888F2 +:1002B000394880F3098839484EF60851CEF20001DA :1002C000086040F20000CCF200004EF63471CEF22D :1002D00000010860BFF34F8FBFF36F8F40F2000043 :1002E000C0F2F0004EF68851CEF200010860BFF374 :1002F0004F8FBFF36F8F4FF00000E1EE100A4EF604 :100300003C71CEF200010860062080F31488BFF330 -:100310006F8F02F085FB03F039FB4FF055301F491A -:100320001B4A91423CBF41F8040BFAE71C49194AA9 -:1003300091423CBF41F8040BFAE71A491A4A1B4B99 -:100340009A423EBF51F8040B42F8040BF8E7002034 -:100350001749184A91423CBF41F8040BFAE702F0F2 -:10036000A3FB03F093FB144C144DAC4203DA54F896 -:10037000041B8847F9E700F041F8114C114DAC42DD -:1003800003DA54F8041B8847F9E702F08BBB00003E -:1003900000060020002200200000000800000020CD -:1003A00000060020A843000800220020442200206C -:1003B00048220020F0460020A0020008A002000809 -:1003C000A0020008A00200082DE9F04F2DED108AD0 -:1003D000C1F80CD0D0F80CD0BDEC108ABDE8F08F7D -:1003E000002383F311882846A047002001F0B0FEC7 -:1003F000FEE701F031FE00DFFEE7000038B51F4CDC -:100400000523002523700423A57063701E23E57067 -:1004100025716571A571E57125726572A372E5722A -:1004200000F0E2FC20B10E2325726572A372E57222 -:1004300002F054FA044602F089FA0546D0B9104B8E -:100440009C4219D001339C4241F2883412BF0546C8 -:1004500000240125002002F04BFA0DB100F05AF8FB -:1004600000F068FD00F008FC204600F013F900F0F1 -:1004700051F8F9E70024EDE70446EBE748220020B5 -:10048000010007B008B500F0C3FBA0F120035842FB -:10049000584108BD054B07B51B88022101A8ADF8DE -:1004A000043000F0D3FB03B05DF804FB5C400008AF -:1004B00010B5202383F311881248C3680BB101F0F3 -:1004C000E3FE0023104A4FF47A710E4801F08AFED1 -:1004D000002383F311880D4C236813B12368013B7B -:1004E0002360636813B16368013B6360084B1B784A -:1004F00033B9636823B9022000F08CFC32236360B7 -:1005000010BD00BF54220020B10400087023002059 -:1005100068220020554B56492DE9F04153F8042F2D -:10052000013201D1BDE8F0818B42F7D1514C524BE1 -:1005300022689A4240F29880504B9B6803F1006316 -:1005400003F500339A4280F08F80002000F0B0FB6A -:1005500002204B4B187000F053FC4A4BD3F8E820B4 -:100560000022C3F8E820D3F81011C3F81021D3F803 -:100570001011D3F8EC10C3F8EC20D3F81411C3F821 -:100580001421D3F81411D3F8F010C3F8F020D3F8E5 -:100590001811C3F81821D3F81811D3F8801041F0BE -:1005A0000061C3F88010D3F8801021F00061C3F817 -:1005B0008010D3F88010D3F8801041F00071C3F898 -:1005C0008010D3F8801021F00071C3F88010D3F8A8 -:1005D000803072B62C4B2D490B601D682468BFF328 -:1005E0004F8FBFF36F8F2A4BC3F88420BFF34F8F19 -:1005F0005A6922F480325A61BFF34F8FD3F88020BA -:1006000043F6E07EC2F3C906C2F34E32B707520189 -:1006100002EA0E0838463146013948EA000C00F17A -:100620004040B1F1FF3FC3F874C2F5D1203A12F156 -:10063000200FEDD1BFF34F8FBFF36F8FBFF34F8FFD -:10064000BFF36F8F5A6922F400325A610022C3F857 -:100650005022BFF34F8FBFF36F8F202383F3118896 -:10066000AD4685F308882047BDE8F081FCFF01080E -:100670001C00020804000208FFFF010848220020B5 -:1006800068220020004402580000020808ED00E043 -:1006900000ED00E02DE9F04F99B0B34C2022FF218E -:1006A000019010A8A66800F0E7FBB04AA3461378B3 -:1006B000A3B90121AE481170C360202383F31188D0 -:1006C000C3680BB101F0E0FD0023AA4A4FF47A7130 -:1006D000A74801F087FD002383F31188019B13B124 -:1006E000A54B019A1A600023A44AA349019F994689 -:1006F0001C461D46984613704B600292012000F084 -:100700007FFB002F00F012829B4B1B68002B40F0F8 -:100710000D8219B0BDE8F08F0220FFF7B3FE00286C -:1007200040F0FB81019BB9F1000F08BF1F46944BBD -:100730001B8802210BA8ADF82C3000F087FADDE70A -:100740004FF47A7000F064FA031E0393EADB022090 -:10075000FFF798FE82460028E4D0039B581E042829 -:1007600000F2DD81DFE800F0030E1114170018A875 -:100770000523042140F8343D00F068FA54464FF058 -:10078000000856E004217848F6E704217D48F3E7A5 -:1007900004217D48F0E71C242046043400F08AFA46 -:1007A00004210B900BA800F051FA2C2CF4D1E5E7B2 -:1007B000002DB7D0002CB5D00220FFF763FE054610 -:1007C000002800F0AF8101206C4C00F071FA4FF06E -:1007D00000090220207000F013FB5FFA89FA5046EE -:1007E00000F076FA074658B1504609F1010900F0C9 -:1007F0007FFA0028F1D12C46A9460027634B97E7E2 -:1008000001233E460220237000F0F0FADBF80830A6 -:100810009E4206D2304600F04DFA0130EBD104364C -:10082000F4E70026029BA9462C461E703746524B21 -:100830005E6000F075FB15B1002C18BF0027FFF7B4 -:1008400029FE5BE7002D3FF46DAF002C3FF46AAF4B -:100850000220029B187000F0D3FA322000F0D8F981 -:10086000B0F1000AC0F25E811AF0030540F05A812F -:1008700006EB0A03DBF80820934200F25381BAF535 -:10088000807F00F24F8155450DDA4FF47A7000F009 -:10089000BFF90490049B002BC0F24481049B3C4AA6 -:1008A000AB540135EFE7C820FFF7ECFD0546002803 -:1008B00000F038811F2E11D8C6F1200410AB26F0AD -:1008C000030033495445184428BF5446224600F0DB -:1008D000ABFA2246FF212E4800F0CEFA4FEAAA0AD0 -:1008E0002B4930465FFA8AF200F0CEFA044600281F -:1008F00000F01A8106EB8A0605469AE70220FFF708 -:10090000C1FD00283FF40EAF00F00CFA00283FF4C0 -:1009100009AF4FF0000A5346DBF8082092451CD27D -:10092000BAF11F0F12D8109A01320FD02AF0030229 -:1009300018A90A4452F8202C0B92184604220BA93D -:100940000AF1040A00F092FB0346E5E750460393E0 -:1009500000F0B0F9039B0B90EFE718A8042140F8D2 -:100960004C3D00F073F964E7482200206C2300201E -:1009700054220020B10400087023002068220020C7 -:100980005E4000084C2200205022002060400008F9 -:100990006C22002018A80023642140F8343D00F0A8 -:1009A0004BF900287FF4BEAE0220FFF76BFD002854 -:1009B0003FF4B8AE0B9800F0ADF918AB43F8480D12 -:1009C00004211846CDE718A80023642140F8343DDF -:1009D00000F032F900287FF4A5AE0220FFF752FDA7 -:1009E00000283FF49FAE0B9800F096F918AB43F83F -:1009F000440DE5E70220FFF745FD00283FF492AEE5 -:100A000000F0A0F918AB43F8400DD9E70220FFF73A -:100A100039FD00283FF486AE0BA9142000F098F9A8 -:100A2000824618A8042140F83CAD00F00FF9514669 -:100A30000BA896E7322000F0EBF8B0F1000AFFF6C1 -:100A400071AE1AF0030F7FF46DAE0AEB0803DBF80A -:100A5000082093423FF666AE0220FFF713FD002800 -:100A60003FF460AE2AF0030AC244D0453FF4E1AE41 -:100A7000404608F1040800F01DF904210A900AA874 -:100A800000F0E4F8F1E74FF47A70FFF7FBFC002880 -:100A90003FF448AE00F046F900283FF4AFAE109B9B -:100AA00001330CD0082210A9002000F0EDF9002835 -:100AB0003FF4A4AE2022FF2110A800F0DDF9FFF7DB -:100AC000E9FC374801F04AFB23E6002D3FF42AAE4B -:100AD000002C3FF427AE18A80023642140F8343DD1 -:100AE00000F0AAF8824600287FF41CAE0220FFF72F -:100AF000C9FC00283FF416AE0390FFF7CBFC41F28F -:100B00008830574601F02AFB0B9800F04DFA00F0B0 -:100B100007FA039B1C461D46F0E5054689E64FF0A3 -:100B20000008FFE52546FDE52C4667E6002000F0BD -:100B30006FF80490049B002BFFF6E3AD012000F05A -:100B400055F9049B213B122B3FF6D8AD01A252F878 -:100B500023F000BF1907000841070008B10700088B -:100B6000FD060008FD060008FD060008450800080F -:100B7000350A0008FD08000895090008C7090008A3 -:100B8000F5090008FD0600080D0A0008FD0600082A -:100B9000870A000833080008FD060008CB0A000891 -:100BA000A08601002DE9F84F4FF47A7507460E46EE -:100BB00000245543DFF85080DFF8509098F900305A -:100BC0005FFA84FA5A1C01D0A34210D159F82400CC -:100BD000324639460368D3F820B02B46D8478642C0 -:100BE00005D1084B012083F800A0BDE8F88F01343F -:100BF000022CE3D14FF4FA7001F0B0FA0020BDE806 -:100C0000F88F00BFBC2300200022002064400008B1 -:100C100007B5002202AB012103F8012D0246184658 -:100C2000FFF7C0FF20B19DF8070003B05DF804FB9B -:100C30004FF0FF30F9E700000A46042108B5FFF73E -:100C4000B1FF80F00100C0B2404208BD074B30B494 -:100C50001A78074B53F822400A460146236820467B -:100C6000DD69044BAC4630BC604700BFBC230020AC -:100C700064400008A0860100F8B50A4C00250A4E21 -:100C800001F012FD094F208030682388834207D984 -:100C900001F006FD336805440133BD423360F3D9EA -:100CA000F8BD00BFBE23002078230020FFFF010015 -:100CB00001F0C8BD00F1006000F500300068704729 -:100CC00000F10060920000F5003001F049BD000025 -:100CD000054B1A68054B1B889B1A834202D91044A6 -:100CE00001F0DEBC0020704778230020BE230020E6 -:100CF00038B5074D04462868204401F0D7FC28B9D0 -:100D000028682044BDE8384001F0E2BC38BD00BF8F -:100D10007823002000207047014BC058704700BF67 -:100D200000E8F11F064991F8243033B1002308226E -:100D3000086A81F82430FFF7C3BF0120704700BF65 -:100D40007C230020014B1868704700BF0010005C36 -:100D5000234BF0B5234C1B682788C3F30B0665684B -:100D60001B0C94F90820BE4228D0A789BE4206D1A8 -:100D700001220C2505FB0244656894F9082041F224 -:100D80000104A3421CD041F20304A3421AD042F250 -:100D90000104A34218D042F20304A34208BF562222 -:100DA000441E013D0B460C44A34217D215F9016FB6 -:100DB000581C5EB1034600F8016CF5E70022D8E745 -:100DC0005A22EDE75922EBE75822E9E72C25844225 -:100DD0001D7001D9981C5A70401AF0BD1846FBE7E7 -:100DE0000010005C0422002000207047022803D17C -:100DF0004FF00062014B9A61704700BF0004025837 -:100E0000022803D14FF40062014B9A61704700BF82 -:100E100000040258022804D1024A536983F4006393 -:100E20005361704700040258002310B5934203D069 -:100E3000CC5CC4540133F9E710BD000030B5441E4A -:100E400014F9010F0B4658B193F900500131854256 -:100E500006D11AB993F90020801A30BD013AEFE7A4 -:100E6000002AF7D1104630BD02460346981A13F9FE -:100E7000011B0029FAD1704702440346934202D075 -:100E800003F8011BFAE770472DE9F047234C0546AC -:100E90008846174694F8243083BB2E46DFF87C90B2 -:100EA000C7B394F824302BB92022FF21484626628C -:100EB000FFF7E2FF94F824004146C0F1080504EB77 -:100EC0008000BD4228BF3D465FFA85FAAD00A7EB22 -:100ED0000A072A462E44FFF7A7FF94F82430A844B7 -:100EE000FFB29A445FFA8AFABAF1080F84F824A094 -:100EF000D6D1FFF717FF0028D2D108E0266A06EB0B -:100F00008306B042CAD0FFF70DFF0028C5D10020EC -:100F1000BDE8F0870120BDE8F08700BF7C230020FA -:100F2000024B1A78024B1A70704700BFBC23002096 -:100F30000022002038B5164C164D204600F00CFC5F -:100F40002946204600F034FC2D681348D5F890203F -:100F5000D2F8043843F00203C2F8043801F0FEF876 -:100F60000E49284600F036FDD5F890200C48D2F8FE -:100F700004380C49A04223F00203C2F804384FF4AD -:100F8000E1330B6003D0BDE8384000F043BB38BD0F -:100F9000682A00206C41000840420F00944100087C -:100FA00040240020A423002038B50B4B05461A78B6 -:100FB0000A4B53F822400A4B9C420CD0094B0021AB -:100FC00018221846FFF758FF056001462046BDE885 -:100FD000384000F01FBB38BDBC230020644000082F -:100FE000682A0020A4230020FEE7000000B59BB083 -:100FF000EFF3098168226846FFF716FFEFF30583D8 -:10100000044B9A6BDA6A9A6A9A6A9A6A9A6A9A6A34 -:101010009B6AFEE700ED00E000B59BB0EFF30981AD -:1010200068226846FFF700FFEFF30583044B9A6BD5 -:101030009A6A9A6A9A6A9A6A9A6A9B6AFEE700BFF3 -:1010400000ED00E000B59BB0EFF30981682268462F -:10105000FFF7EAFEEFF30583034B5A6B9A6A9A6A2D -:101060009A6A9A6A9B6AFEE700ED00E030B50A448E -:10107000074D91420BD011F8013B09245840013C27 -:10108000F7D040F300032B4083EA5000F7E730BD70 -:101090002083B8ED002304491A465A50C818083373 -:1010A0004260802BF9D17047C0230020026843685A -:1010B0001143016003B1184770470000024A1368EA -:1010C00043F0C003136070470078004013B50E4C26 -:1010D000204600F093FA04F11400009400234FF42A -:1010E00000720A4900F054F90094094B4FF4007261 -:1010F000084904F1380000F0CDF9074BE365074BD0 -:10110000236602B010BD00BF40240020AC240020A4 -:10111000BD100008AC2600200078004000E1F50575 -:10112000254B002908BF1946037C012B30B511D18E -:10113000224B98420ED1224BD3F8E82042F0804255 -:10114000C3F8E820D3F8102142F08042C3F8102100 -:10115000D3F810310A68036EC46D03EB5203816645 -:10116000B3FBF2F34A68150442BF23F0070503F00E -:10117000070343EA4503E3608B6843F04003636081 -:10118000CB68510543F00103A36042F4967343F02A -:10119000010323604FF0FF33236205D512F01022C4 -:1011A00005D0B2F1805F04D080F8643030BD7F2379 -:1011B000FAE73F23F8E700BF8840000840240020FA -:1011C000004402582DE9F047C66D05463768F469BA -:1011D000200734621AD014F0080F0CBF00218021C0 -:1011E000E20748BF41F02001A3074FF0200348BFAA -:1011F00041F04001600748BF41F4807183F31188DA -:10120000281DFFF753FF002383F31188E2050AD559 -:10121000202383F311884FF40071281DFFF746FF48 -:10122000002383F311884FF020094FF0000A14F0D7 -:10123000200831D13B0616D54FF0200905F1380AB8 -:10124000200610D589F31188504600F057F9002880 -:101250002FDA0821281DFFF729FF27F080033360CC -:10126000002383F3118879060DD562060BD5202360 -:1012700083F31188EA6C2B6D9A4201D12B6CEBB988 -:10128000002383F31188E30620D5AA6E1369EBB11E -:101290005069BDE8F047184789F31188736A2846FA -:1012A00095F86410194000F0C3F98AF31188F469C5 -:1012B000BDE7B06288F31188F469C1E727F0400701 -:1012C0001021281DFFF7F2FE3760D9E7BDE8F0874F -:1012D000F8B51546826804460B46AA4200D28568D6 -:1012E000A1692669761AB54207D218462A46FFF741 -:1012F0009BFDA3692B44A3610DE011D9AF1B3246BE -:101300001846FFF791FD3A46E1683044FFF78CFD3F -:10131000E2683A44A261A36828465B1BA360F8BD5B -:1013200018462A46FFF780FDE368E4E783689342A6 -:101330002DE9F04104460F46154600D285686069E4 -:101340002669361AB54207D22A463946FFF76CFDA0 -:1013500063692B4463610EE013D9A5EB060832469E -:101360003946FFF761FD4246B919E068FFF75CFDB9 -:10137000E26842446261A36828465B1BA360BDE843 -:10138000F0812A463946FFF74FFDE368E2E70000A7 -:1013900010B50A440024C361029B00604060846071 -:1013A000C160816141610261036210BD08B582695B -:1013B0004369934201D1826882B9826801328260B6 -:1013C0005A1C42611970426903699A4201D3C36889 -:1013D0004361002100F0DEFE002008BD4FF0FF3029 -:1013E00008BD000070B5202304460E4683F3118823 -:1013F000A568A5B1A368A269013BA360531CA361C2 -:1014000015782269934224BFE368A361E3690BB1B5 -:1014100020469847002383F31188284670BD314643 -:10142000204600F0A7FE0028E2DA85F3118870BD9F -:101430002DE9F74F05460F4690469A46D0F81C9086 -:10144000202686F311884FF0000B144664B1224623 -:1014500039462846FFF73CFF034668B951462846FF -:1014600000F088FE0028F1D0002383F31188A8EB58 -:10147000040003B0BDE8F08FB9F1000F03D0019074 -:101480002846C847019B8BF31188E41A1F4486F352 -:101490001188DBE7C160816141611144C361009B38 -:1014A000006040608260016103627047F8B50446E5 -:1014B0000E461746202383F31188A568A5B1A368BB -:1014C000013BA36063695A1C62611E7023696269F3 -:1014D0009A4224BFE3686361E3690BB120469847F1 -:1014E000002080F31188F8BD3946204600F042FE06 -:1014F0000028E2DA85F31188F8BD000083694269AB -:101500009A4210B501D182687AB98268013282604C -:101510005A1C82611C7803699A4201D3C3688361B3 -:10152000002100F037FE204610BD4FF0FF3010BD07 -:101530002DE9F74F05460F4690469A46D0F81C9085 -:10154000202686F311884FF0000B144664B1224622 -:1015500039462846FFF7EAFE034668B95146284651 -:1015600000F008FE0028F1D0002383F31188A8EBD7 -:10157000040003B0BDE8F08FB9F1000F03D0019073 -:101580002846C847019B8BF31188E41A1F4486F351 -:101590001188DBE7026843681143016003B1184713 -:1015A000704700001430FFF743BF00004FF0FF33D7 -:1015B0001430FFF73DBF00003830FFF7B9BF00001F -:1015C0004FF0FF333830FFF7B3BF00001430FFF7A0 -:1015D00009BF00004FF0FF311430FFF703BF0000D8 -:1015E0003830FFF763BF00004FF0FF323830FFF7AD -:1015F0005DBF000000207047FFF768BD044B03602B -:10160000002343608360C36001230374704700BFFD -:10161000A040000810B52023044683F31188FFF78B -:101620007FFD02232374002383F3118810BD000083 -:1016300038B5C36904460D461BB904210844FFF7B9 -:10164000A9FF294604F11400FFF7B0FE002806DACE -:10165000201D4FF48061BDE83840FFF79BBF38BDC7 -:10166000026843681143016003B1184770470000E6 -:1016700037B5446B41F6A40563591A6811780429FB -:1016800014D1217C022911D11979012312898B40AF -:1016900013420BD101A904F14C0002F075F8645912 -:1016A0000246019B2179206800F0ECF903B030BDBF -:1016B000143001F0F9BF00004FF0FF33143001F097 -:1016C000F3BF00004C3002F0CBB800004FF0FF3306 -:1016D0004C3002F0C5B80000143001F0C7BF000064 -:1016E0004FF0FF31143001F0C1BF00004C3002F068 -:1016F00097B800004FF0FF324C3002F091B8000074 -:1017000070B541F6A4060546825913681978042974 -:1017100001D0012070BD017C0229FAD1127901208B -:101720005C8990400440F4D105F1140001F058FFA9 -:1017300002460028EDD0AD594FF44073286869790E -:1017400000F08EF9204670BD406BFFF7D9BF000056 -:1017500000207047704700007FB5124B012504261A -:10176000044603600023057400F1840243602946A7 -:101770008360C3600C4B0290143001934FF44073AC -:10178000009601F009FF094B04F6944229460193A3 -:1017900004F14C004FF440730294009601F0D0FF26 -:1017A00004B070BDC8400008491700087116000851 -:1017B0000A68202383F311880B790B3342F8230046 -:1017C0004B79133342F823008B7913B10B3342F872 -:1017D000230041F6A403C15002230374002383F3C2 -:1017E0001188704738B5037F044613B190F8543020 -:1017F000ABB90125201D0221FFF732FF04F11400CF -:1018000025776FF0010100F0D1FC84F8545004F109 -:101810004C006FF00101BDE8384000F0C7BC38BD96 -:1018200010B5012104460430FFF71AFF0023237787 -:1018300084F8543010BD000038B50446002514303B -:1018400001F0C2FE04F14C00257701F091FF201D4C -:1018500084F854500121FFF703FF2046BDE83840CB -:10186000FFF74EBF90F8803003F06003202B19D1B2 -:1018700090F88120212A0AD0222A4FF000030ED0AE -:10188000202A0FD1084A42670722826704E0064BEC -:101890004367072383670023C367012070474367BB -:1018A0008367F9E7002070471C22002073B541F6DA -:1018B000A405044643591A681178042919D1017CFA -:1018C000022916D11979012312898B40134210D1B4 -:1018D00000F14C06304602F00BF850B101A9304639 -:1018E00001F052FF64590246019B2179206800F003 -:1018F000C9F802B070BD000001F10B03F7B550F854 -:10190000234005460E46F4B1202383F3118805EBEE -:101910008607201D08214C34FFF7A2FEFB685B6997 -:101920001B6813B1204601F03DFF01A9204601F0DC -:101930002BFF024648B1019B3146284600F0A2F831 -:10194000002383F3118803B0F0BDFB685A69126865 -:10195000002AF5D01B8A013B1340F1D105F180022A -:10196000EAE70000133138B550F82140E4B12023F4 -:1019700083F3118841F6A403E2581368527903EB0C -:101980008203DB689B695D6845B104216018FFF73D -:1019900067FE294604F1140001F02CFE2046FFF7F3 -:1019A000AFFE002383F3118838BD000070470000AC -:1019B00001F00EB9012300F1300200F15001037073 -:1019C0000023436042F8043B8A42D361FAD1038189 -:1019D0004381704738B50446202383F311880025DE -:1019E00000F10C0300F13002416043F8045B9342C4 -:1019F000FBD1204601F00EF90223237085F31188F4 -:101A000038BD000070B500EB8103054650690E46F5 -:101A10001446DA6018B110220021FFF72DFAA069F0 -:101A200018B110220021FFF727FA31462846BDE8F9 -:101A3000704001F001BA0000038900F1300200217A -:101A400003F001030381438903F00103438100F1A3 -:101A5000100343F8041B9342FBD101F085BA000048 -:101A6000F0B4012500EB810447898D40E4683D43D3 -:101A7000A469458123600023A2606360F0BC01F08B -:101A8000A1BA0000F0B4012500EB810407898D4064 -:101A9000E4683D436469058123600023A2606360BC -:101AA000F0BC01F019BB0000022300F10C0200F1B0 -:101AB000300110B5037004460023A0F8883080F888 -:101AC0008A3080F88B300381438142F8043B8A429C -:101AD000FBD184F87030204601F042F963681B683E -:101AE00023B120460021BDE81040184710BD00007A -:101AF000037880F88C300523037043681B6810B5A9 -:101B000004460BB10421984700232381638110BD53 -:101B1000436890F88C201B6802700BB105211847B0 -:101B20007047000090F8703070B5044613B1002380 -:101B300080F8703004F18002204601F039FA6368C1 -:101B40009B6863BB94F8805015F0600615D194F83B -:101B5000813005F07F0545EA032540F202339D42BE -:101B600000F00E815BD8022D00F0DC803FD8002D04 -:101B700000F08780012D00F0CF800021204601F089 -:101B8000D1FC0021204601F0C1FC63681B6813B141 -:101B9000062120469847062384F8703070BD204601 -:101BA00098470028CED094F8872094F8863043EAEE -:101BB0000223A26F934238BFA36794F98030A56FC8 -:101BC000002B4FF0200380F2FD80002D00F0EC8010 -:101BD000092284F8702083F311880021A36F626FBB -:101BE0002046FFF74FFF002383F3118870BDB5F542 -:101BF000817F00F0B180B5F5407F49D0B5F5807F99 -:101C0000BBD194F88230012BB7D1B4F8883023F0DF -:101C10000203A4F888306667A667E667C3E740F268 -:101C200001639D421ED8B5F5C06F3BD2B5F5A06FDC -:101C3000A3D1B4F88030B3F5A06F0ED194F8823000 -:101C4000204684F88A3001F0E9F863681B6813B114 -:101C50000121204698470323237000236367A3676D -:101C6000E367A0E7B5F5106F32D040F602439D421E -:101C700052D0B5F5006F80D104F18B036367012367 -:101C800024E004F18803E56763670223A3678AE71A -:101C900094F88230012B7FF470AFB4F8883043F0B1 -:101CA0000203B6E794F885202046616894F88430F2 -:101CB0004D6843EA022394F8831094F88220A847E1 -:101CC00000283FF45AAF436863670368A367A4E73B -:101CD0002378042B10D1202383F311882046FFF7AB -:101CE000ABFE86F311886368032184F88B601B6860 -:101CF00021700BB12046984794F88230002BACD06D -:101D000084F88B300423237063681B68002BA4D0F5 -:101D1000022120469847A0E7374B63670223A36759 -:101D200000239DE794F88410204611F0800F01F005 -:101D30000F010ED001F02EF9012806D002287FF401 -:101D40001CAF2E4BA067636767E72D4BA5676367E2 -:101D500063E701F011F9EFE794F88230002B7FF48C -:101D60000CAF94F8843013F00F013FF476AF1A06ED -:101D7000204602D501F0EEFB6FE701F0DFFB6CE7D8 -:101D800094F88230002B7FF4F8AE94F8843013F08E -:101D90000F013FF462AF1B06204602D501F0C2FBE3 -:101DA0005BE701F0B3FB58E7142284F8702083F35B -:101DB00011882B462A4629462046FFF751FE85F317 -:101DC000118870BD5DB1152284F8702083F31188ED -:101DD0000021A36F626F2046FFF742FE03E70B224C -:101DE00084F8702083F311882B462A462946204622 -:101DF000FFF748FEE3E700BFF8400008F0400008A6 -:101E0000F440000838B590F870300446152B29D8F6 -:101E1000DFE803F03E28282828283E28280B293907 -:101E200028282828282828283E3E90F8871090F84F -:101E30008620836F42EA01229A4214D9C268128A2C -:101E4000B3FBF2F502FB15356DB9202383F311883E -:101E50002B462A462946FFF715FE85F311880A23EB -:101E600084F8703038BD142384F87030202383F355 -:101E70001188002320461A461946FFF7F1FD00237A -:101E800083F3118838BDC36F03B198470023E7E798 -:101E9000002101F047FB0021204601F037FB636879 -:101EA0001B6813B10621204698470623D8E7000097 -:101EB00090F87020152A38B5044622D801239340A3 -:101EC00040F6416213421DD113F480150FD19B02DD -:101ED00017D50B2380F87030202383F311882B460D -:101EE0002A462946FFF7CEFD85F3118838BDC36821 -:101EF0009B695B682BB9C36F03B19847002384F8D3 -:101F0000703038BD002101F00DFB0021204601F0AA -:101F1000FDFA63681B6813B1062120469847062323 -:101F2000EDE70000024B00221B605B609A60704787 -:101F3000AC280020002382680374054B1B68996855 -:101F40009142FBD25A68036042601060586070474B -:101F5000AC28002008B5202383F31188037C032BD1 -:101F600005D0042B0DD02BB983F3118808BD43692C -:101F700000221A604FF0FF334361FFF7DBFF0023BD -:101F8000F2E790E80C001A6002685360F2E7000084 -:101F9000002382680374054B1B6899689142FBD843 -:101FA0005A6803604260106058607047AC28002097 -:101FB000054B196908741868026853601A60186143 -:101FC00001230374FEF700BAAC2800204B1C30B587 -:101FD000054687B00A4C10D0236901A8094A00F0D1 -:101FE00001F92846FFF7E4FF049B13B101A800F0B4 -:101FF0004BF92369586907B030BDFFF7D9FFF8E7FF -:10200000AC280020551F000838B50C4D044641612E -:102010002B6981689A68914203D8BDE83840FFF780 -:1020200089BF1846FFF7B4FF01232C6101462374D2 -:102030002046BDE83840FEF7C7B900BFAC280020F5 -:10204000044B1A681B6990689B68984294BF0020F3 -:1020500001207047AC28002010B5084C2368206987 -:102060001A6854602260012223611A74FFF790FFFE -:1020700001462069BDE81040FEF7A6B9AC28002053 -:10208000FEE7000010B50C4CFFF74CFF00F09CF889 -:1020900080220A49204600F021F8012344F8180C58 -:1020A000037400F069FC002383F3118862B60448CE -:1020B000BDE8104000F034B8D4280020FC400008EF -:1020C0000441000800F01AB9034B59685A68521AC3 -:1020D0009042FBD8704700BF001000E082600222EF -:1020E00002740022427470478368A3F17C0243F8B3 -:1020F0000C2C026943F83C2C426943F8382C074AFF -:1021000043F81C2CC268A3F1180043F8102C0222DB -:1021100003F8082C002203F8072C7047E10300089D -:1021200010B5202383F31188FFF7DEFF002104465A -:10213000FFF76AFF002383F31188204610BD0000DB -:10214000024B1B6958610F20FFF732BFAC280020FB -:10215000202383F31188FFF7F3BF000008B5014681 -:10216000202383F311880820FFF730FF002383F337 -:10217000118808BD49B1064B42681B6918605A6056 -:10218000136043600420FFF721BF4FF0FF3070471A -:10219000AC2800200368984206D01A68026050609C -:1021A00018465961FFF7C6BE7047000038B50446AF -:1021B0000D462068844200D138BD036823605C600E -:1021C0004561FFF7B7FEF4E7054B03F114025A61CE -:1021D0009A614FF0FF32DA6100221A62704700BF45 -:1021E000AC280020F8B5274F0D4603610446C260B5 -:1021F0003E4601F0B5FB3B46022D294653F8142F0D -:1022000038BF02219A421D460AD1386208447C61D7 -:10221000BC6122606260A160BDE8F84001F08ABB49 -:10222000D7F820E0A0EB0E035F181FD300279068BB -:10223000834217D8376AAA421F44376201D0C01AB6 -:10224000906073699A68914219D85A6823606260F5 -:1022500014605C60A1609868411A99604FF0FF3388 -:10226000F361F8BD97601B1A1268E0E793689F421C -:1022700003D20EEB070001F06DFB3946E1E7891A46 -:102280001B68DFE7AC28002038B51B4B01685A6992 -:102290001D46904203F114020CD0446821600021D5 -:1022A000036893425C60C16025D09A6881680A44E3 -:1022B0009A6038BD59614A6000215B69C1609342F0 -:1022C00003D1BDE8384001F03FBB9A6881680A44F9 -:1022D0009A602C6A01F044FB6A69001B9268824292 -:1022E00009D9111A012998BF821C286ABDE8384013 -:1022F000104401F02FBB38BDAC2800202DE9F84F69 -:10230000204C0027656904F11406B84601F028FB4B -:10231000236AA0EB030AAB6853451DD84FF0200990 -:10232000236AAA68D5F80CB013442362AB68AAEB01 -:10233000030A2B68B3425E606361EF6001D101F074 -:1023400003FB88F311882869D84789F311886569E8 -:10235000AB689A45E4D2D9E76369B34210D02062F2 -:102360009A68A2EB0A029A60226AAB68821A9B1AE8 -:10237000022B2CBFC0180230BDE8F84F01F0EABABA -:10238000BDE8F88FAC28002000207047FEE7000071 -:10239000704700004FF0FF3070470000022906D060 -:1023A000032906D00129064818BF002070470548B8 -:1023B0007047032A9ABF044800EBC2000020704710 -:1023C000F0410008A44100082422002070B59AB012 -:1023D00006460846144601AD294600F095F8284601 -:1023E000FEF742FDC0B2431C5B0086E81800237074 -:1023F0000323023404F8013C00231946DAB2023404 -:10240000904201D81AB070BDEA5C013304F8011C97 -:1024100004F8022CF2E7000008B5202383F31188AA -:102420000348FFF743FA002383F3118808BD00BF78 -:10243000682A002010B50446052916D8DFE801F007 -:1024400016150316161D202383F311880E4A012149 -:10245000FFF7D8FA20460D4A0221FFF7D3FA0C48BD -:10246000FFF7EAF9002383F3118810BD202383F3DB -:1024700011880748FFF7B6F9F4E7202383F31188A2 -:102480000348FFF7CDF9EDE7244100084841000873 -:10249000682A002038B50C4D0C4C2A460C4904F132 -:1024A0000800FFF793FF05F1CA0204F11000094983 -:1024B000FFF78CFF05F5CA7204F118000649BDE864 -:1024C0003840FFF783BF00BF404300202422002094 -:1024D000744100087E4100088941000870B5044637 -:1024E00008460D46FEF7C0FCC6B22046013403780C -:1024F0000BB9184670BD32462946FEF79FFC0028EE -:10250000F3D1012070BD00002DE9F84F05460C46BF -:10251000FEF7AAFC2C49C6B22846FFF7DFFF08B138 -:102520000536F6B229492846FFF7D8FF08B110361C -:10253000F6B2632E0DD8DFF89080DFF89090244F2C -:10254000DFF894A0DFF894B02E7846B92670BDE885 -:10255000F88F29462046BDE8F84F01F077BD252EBB -:102560002ED1072241462846FEF768FC70B9DBF8F9 -:10257000003007350C3444F80C3CDBF8043044F8E8 -:10258000083CDBF8083044F8043CDDE70822494603 -:102590002846FEF753FC98B9A21C0E4B13F8011FF6 -:1025A000023209095345C95D02F8041C197801F08B -:1025B0000F01C95D02F8031CF0D118340835C3E7D8 -:1025C000267001350134BFE7104200088941000838 -:1025D00025420008FFE7F11F0BE8F11F1842000831 -:1025E000BFF34F8F044B1A695107FCD1D3F8102168 -:1025F0005207F8D1704700BF0020005208B50D4BBC -:102600001B78ABB9FFF7ECFF0B4BDA68D10704D5A9 -:102610000A4A5A6002F188325A60D3F80C21D20774 -:1026200006D5064AC3F8042102F18832C3F8042112 -:1026300008BD00BF9E4500200020005223016745D1 -:1026400008B5114B1B78F3B9104B1A69510703D524 -:10265000DA6842F04002DA60D3F81021520705D55B -:10266000D3F80C2142F04002C3F80C21FFF7B8FF69 -:10267000064BDA6842F00102DA60D3F80C2142F02E -:102680000102C3F80C2108BD9E4500200020005225 -:102690000F289ABF00F580604004002070470000BA -:1026A0004FF4003070470000102070470F2808B525 -:1026B0000BD8FFF7EDFF00F500330268013204D1BB -:1026C00004308342F9D1012008BD002008BD00007C -:1026D0000F2810B504463FD8FFF782FFFFF78EFFA3 -:1026E0001E484FF0FF33072C4361C0F814311DD84A -:1026F0000361FFF775FF230243F02403C360C3683F -:1027000043F08003C36003695A07FCD4FFF768FFF6 -:102710002046FFF7BDFF4FF4003100F0F9F8FFF756 -:102720008FFF2046BDE81040FFF7C0BFC0F8103152 -:10273000FFF756FFA4F108031B0243F02403C0F87F -:102740000C31D0F80C3143F08003C0F80C31D0F8D4 -:1027500010315B07FBD4D9E7002010BD00200052E8 -:102760002DE9F84F40EA0203054689469046DB060C -:102770005AD122F0030203460244934205D1FFF7E7 -:102780003DFF4E46DFF8B8B042E0196801314BD149 -:102790000433F2E7264A05F1784326489342264B54 -:1027A000264F88BF9A46A3F1FC039CBFDA46184621 -:1027B00003F1F80388BF1F46FFF712FF4FF0FF3306 -:1027C00006F11C02A5EB060E03603B6843F0020312 -:1027D0003B60331FDAF8004014F00504FAD153F8D7 -:1027E000041F9A424EF80310F4D1BFF34F8FFFF746 -:1027F000F7FE4FF0FF3320223146036028463B6846 -:1028000023F002033B6001F011FC58B9203520365B -:10281000A8EB06034B441F2BBCD80120FFF710FF89 -:10282000BDE8F88F2046F9E70020BDE8F88F00BF2B -:10283000FFFF0F0014210052102100520C20005203 -:102840001020005210B5084C237828B153B9FFF777 -:10285000D5FE0123237010BD23B12070BDE81040C8 -:10286000FFF7EEBE10BD00BF9E45002002440439B4 -:10287000064BD2B210B5904200D110BD441C00B23C -:1028800053F8200041F8040FE0B2F4E7504000583C -:102890000F4B30B51C6F240405D41C6F1C671C6FD4 -:1028A00044F400441C670B4C024404392368D2B240 -:1028B00043F480732360084B904200D130BD441C28 -:1028C00051F8045F00B243F82050E0B2F4E700BFD3 -:1028D00000440258004802585040005807B50122F1 -:1028E00001A90020FFF7C2FF019803B05DF804FBC7 -:1028F00013B50446FFF7F2FFA04206D002A9012259 -:10290000002041F8044DFFF7C3FF02B010BD0000E6 -:102910000144BFF34F8F064B884204D3BFF34F8F60 -:10292000BFF36F8F7047C3F85C022030F4E700BF3D -:1029300000ED00E0034B1B685B0142BF0122024B2C -:102940001A707047D04402589F450020014B1878F8 -:10295000704700BF9F450020EFF3098305496833A6 -:102960004A6822F001024A6083F30988002383F356 -:102970001188704730EF00E0202080F3118862B6A4 -:102980000D4B0E4AD96821F4E0610904090C0A4391 -:102990000B49DA60CA6842F08072CA60094A0A4983 -:1029A000C2F8B01F116841F0010111601022DA77FE -:1029B00083F82200704700BF00ED00E00003FA0535 -:1029C000F0ED00E0001000E055CEACC510B52023BE -:1029D00083F311880E4B5B6813F4006314D0F1EE9F -:1029E000103AEFF309844FF08073683CE361094BC0 -:1029F000DB68236684F30988FFF722FB10B1064BDE -:102A0000A36110BD054BFBE783F3118810BD00BF28 -:102A100000ED00E030EF00E0F3030008F6030008EB -:102A2000F0B5BFF34F8FBFF36F8F1D4B0021C3F87D -:102A30005012BFF34F8FBFF36F8F5A6942F40032C9 -:102A40005A61BFF34F8FBFF36F8FC3F88410BFF38A -:102A50004F8FD3F8802043F6E076C2F3C904C2F367 -:102A60004E32A507520102EA060E284621464EEADA -:102A70000007013900F14040C3F860724F1CF6D1E5 -:102A8000203A12F1200FEED1BFF34F8F5A6942F472 -:102A900080325A61BFF34F8FBFF36F8FF0BD00BF1D -:102AA00000ED00E0FEE70000084A094B09498B42AF -:102AB00004D3094A0021934205D3704752F8040F0A -:102AC00043F8040BF3E743F8041BF4E7E84300087A -:102AD000F0460020F0460020F0460020D0F8943068 -:102AE000002170B5D0F890404FF0FF359E684A0144 -:102AF000A318D3F80009002805DAD3F8000940F03C -:102B00008040C3F80009D3F8000B002805DAD3F899 -:102B1000000B40F08040C3F8000B0131A3188E4237 -:102B2000C3F80859C3F8085BE1D24FF00113C4F8A9 -:102B30001C3870BD00EB81032DE9F04FD3F80CE099 -:102B40004F1C4FEA4118DEF814403F03D4F800C090 -:102B50006568D0F8902065450AD30120D2F8343852 -:102B600000FA01F123EA0101C2F83418BDE8F08F40 -:102B7000ACEB0503BEF81060B34228BF334602EB4E -:102B80000806D6F81869B6B2B3EB860F13D8A66854 -:102B90003A449946A6F1040A5AF804BFB9F1040F61 -:102BA000C2F800B002D9A9F10409F5E71E442B448C -:102BB000A6606360CCE70020BDE8F08F890141F09A -:102BC0002001016103699B06FCD41220FFF77CBA47 -:102BD00010B50A4C2046FEF7EDFE094BC4F89030C4 -:102BE000084BC4F89430084C2046FEF7E3FE074B30 -:102BF000C4F89030064BC4F8943010BDA0450020B6 -:102C0000000008405C4200083C46002000000440F0 -:102C1000684200080378012B70B505465DD1494B29 -:102C2000D0F89040984259D1474B0E216520D3F8F7 -:102C3000D82042F00062C3F8D820D3F8002142F037 -:102C40000062C3F80021D3F80021D3F8802042F0BD -:102C50000062C3F88020D3F8802022F00062C3F81D -:102C60008020D3F8803000F081FC384BE360384B93 -:102C7000C4F800380023D5F89060C4F8003EC023A3 -:102C800023604FF40413A3633369002BFCDA0123A0 -:102C90000C203361FFF718FA3369DB07FCD41220EC -:102CA000FFF712FA3369002BFCDA00262846A660EB -:102CB000FFF714FF6B68C4F81068DB68C4F8146889 -:102CC000C4F81C68002B3AD1224BA3614FF0FF33AC -:102CD0006361A36843F00103A36070BD1E4B98427B -:102CE000C8D1194B0E214D20D3F8D82042F00072E4 -:102CF000C3F8D820D3F8002142F00072C3F80021B5 -:102D0000D3F80021D3F8802042F00072C3F880206D -:102D1000D3F8802022F00072C3F88020D3F88020FE -:102D2000D3F8D82022F08062C3F8D820D3F800214D -:102D300022F08062C3F80021D3F8003193E7074BFB -:102D4000C3E700BFA04500200044025840140040E3 -:102D500003002002003C30C03C460020083C30C04C -:102D6000F8B5D0F89040054600214FF000662046A7 -:102D7000FFF724FFD5F8941000234FF001128F685D -:102D80004FF0FF30C4F83438C4F81C2804EB431269 -:102D900001339F42C2F80069C2F8006BC2F808090B -:102DA000C2F8080BF2D20B68D5F89020C5F898301D -:102DB000636210231361166916F01006FBD112200E -:102DC000FFF782F9D4F8003823F4FE63C4F8003822 -:102DD000A36943F4402343F01003A3610923C4F81B -:102DE0001038C4F814380B4BEB604FF0C043C4F8F4 -:102DF000103B094BC4F8003BC4F81069C4F8003913 -:102E0000D5F8983003F1100243F48013C5F89820E8 -:102E1000A362F8BD3842000840800010D0F890202E -:102E200090F88A10D2F8003823F4FE6343EA0113C5 -:102E3000C2F80038704700002DE9F0410EB20D468F -:102E400000EB8608D8F80C100F6807F00303022B7C -:102E500053D0032B53D03F4A3F4F012B18BF174687 -:102E6000D0F890404FEA451E002205F1100C04EB0B -:102E70000E03C3F8102B8A69002A42D04A8A05F152 -:102E800058033A435B01E2500123D4F81C2803FAAB -:102E90000CF31343C4F81C38A64400234A69CEF847 -:102EA000103905F13F03002A3BD00A8A04EB830363 -:102EB000898B9208012988BF4A43D0F89810561888 -:102EC00041EA02422946C0F8986020465A60FFF75E -:102ED00075FED8F80C301B8A43EA85531F4305F171 -:102EE00048035B01E7500123D4F81C2803FA05F5D9 -:102EF0001543C4F81C58BDE8F081184FB0E7184FCF -:102F0000AEE704EB4613D3F8002B22F40042C3F8DB -:102F1000002B0123D4F81C2803FA0CF322EA030344 -:102F2000B8E704EB83030F4A04EB461629465A60C0 -:102F30002046FFF743FED6F80039012223F4004370 -:102F400002FA05F5C6F80039D4F81C3823EA05055D -:102F5000CFE700BF00800010008004100080081040 -:102F600000800C1000040002D0F894201268C0F811 -:102F70009820FFF7B3BD00005831D0F890304901D8 -:102F80005B5813F4004004D013F4001F14BF012059 -:102F9000022070474831D0F8903049015B5813F453 -:102FA000004004D013F4001F14BF0120022070471A -:102FB00000EB8101CB68196A0B6813604B685360A2 -:102FC0007047000000EB810330B5DD68AA69136823 -:102FD000D36019B9402B84BF402313606B8A1468F7 -:102FE000D0F890201C4402EB4110013C09B2B4FB24 -:102FF000F3F46343033323F0030343EAC44343F08E -:10300000C043C0F8103B2B6803F00303012B0ED123 -:10301000D2F8083802EB411013F4807FD0F8003B5F -:1030200014BF43F0805343F00053C0F8003B02EB61 -:103030004112D2F8003B43F00443C2F8003B30BDDC -:103040002DE9F041D0F8906005460C4606EB41139F -:10305000D3F8087B3A07C3F8087B08D5D6F81438AC -:103060001B0704D500EB8103DB685B689847FA0710 -:103070002FD5D6F81438DB072BD505EB8403D96898 -:10308000CCB98B69488A5E68B6FBF0F200FB12622D -:103090008AB91868DA6890420DD2121A83E81400CF -:1030A000202383F3118821462846FFF78BFF84F302 -:1030B0001188BDE8F081012303FA04F26B8923EA49 -:1030C00002036B81CB6823B121462846BDE8F0415D -:1030D0001847BDE8F081000000EB81034A0170B59C -:1030E000DD68D0F890306C692668E66056BB1A44FB -:1030F0004FF40020C2F810092A6802F00302012AE6 -:103100000AB20ED1D3F8080803EB421410F4807F02 -:10311000D4F8000914BF40F0805040F00050C4F8CB -:10312000000903EB4212D2F8000940F00440C2F853 -:1031300000090122D3F8340802FA01F10143C3F86F -:10314000341870BD19B9402E84BF4020206020681B -:103150001A442E8A841940F00050013CB4FBF6F466 -:1031600040EAC440C6E700002DE9F041D0F8906085 -:1031700004460D4606EB4113D3F80879C3F80879E5 -:10318000FB071CD5D6F81038DA0718D500EB8103F9 -:10319000D3F80CE0DEF81430D3F800C0DA689445B8 -:1031A0001BD2A2EB0C024FF000081A60C3F8048097 -:1031B000202383F31188FFF78FFF88F311883B06E4 -:1031C00018D50123D6F83428AB40134212D0294633 -:1031D0002046BDE8F041FFF7ADBC012303FA01F240 -:1031E000038923EA02030381DEF80830002BE6D0CE -:1031F0009847E4E7BDE8F0812DE9F047D0F890501A -:1032000004466E69AB691E40F1046E6103D5BDE8EA -:10321000F047FEF749BC002E12DAD5F8003E9A07B7 -:1032200005D0D5F8003E23F00303C5F8003ED5F8DD -:103230000438204623F00103C5F80438FEF768FC83 -:10324000330505D52046FFF749FC2046FEF750FC24 -:10325000B7040CD5D5F8083813F0060FEB6823F443 -:1032600070530CBF43F4105343F4A053EB6030078A -:1032700004D56368DB680BB120469847F10200F182 -:10328000A180B2020BD5D4F8908000274FF001093D -:10329000D4F89430F9B29B688B4280F0D280F30668 -:1032A0001AD5D4F890100A6AC2F30A1702F00F0375 -:1032B00002F4F012B2F5802F00F0EB80B2F5402F4F -:1032C0000AD104EB830301F58051DB68186A0023FF -:1032D0001A469F4240F0D1803003D5F8185835D5B2 -:1032E000E90303D500212046FFF7AAFEAA0303D570 -:1032F00001212046FFF7A4FE6B0303D502212046DF -:10330000FFF79EFE2F0303D503212046FFF798FE0B -:10331000E80203D504212046FFF792FEA90203D557 -:1033200005212046FFF78CFE6A0203D506212046C0 -:10333000FFF786FE2B0203D507212046FFF780FE0C -:10334000EF0103D508212046FFF77AFE700340F114 -:10335000C780E90703D500212046FFF705FFAA072C -:1033600003D501212046FFF7FFFE6B0703D502219D -:103370002046FFF7F9FE2F0703D503212046FFF76C -:10338000F3FEEE0603D504212046FFF7EDFEA80666 -:1033900003D505212046FFF7E7FE690603D5062180 -:1033A0002046FFF7E1FE2A0603D507212046FFF756 -:1033B000DBFEEB0540F1948020460821BDE8F04794 -:1033C000FFF7D2BED4F890904FF000084FF0010AFA -:1033D000D4F894305FFA88F79B68BB42FFF451AF92 -:1033E00009EB4713D3F8002902F44022B2F5802FED -:1033F00024D1D3F80029002A20DAD3F8002942F09A -:103400009042C3F80029D3F80029002AFBDB394693 -:10341000D4F89000FFF7D2FB22890AFA07F322EAD8 -:103420000303238104EB8703DB689B6813B13946F0 -:103430002046984739462046FFF77CFB08F10108F3 -:10344000C6E708EB4112D2F8003B03F44023B3F582 -:10345000802F10D1D2F8003B002B0CDA628909FAD8 -:1034600001F322EA0303638104EB8103DB68DB6879 -:103470000BB12046984701370AE713F0030F00D13C -:103480000A68072B03F101039EBF0270120A013084 -:103490001FE704EB830301F58051DA689069026845 -:1034A000D0F808C04068A2EB000E002210469742F8 -:1034B00008D1DB689B699A683A449A605A68174455 -:1034C0005F6009E712F0030F00D10868964502F12A -:1034D000010282BF8CF80000000A0CF1010CE6E743 -:1034E000BDE8F08708B50348FFF786FEBDE8084051 -:1034F000FFF76CBAA045002008B50348FFF77CFE33 -:10350000BDE80840FFF762BA3C460020D0F8903092 -:1035100003EB4111D1F8003B43F40013C1F8003B29 -:1035200070470000D0F8903003EB4111D1F800391A -:1035300043F40013C1F8003970470000D0F8903010 -:1035400003EB4111D1F8003B23F40013C1F8003B19 -:1035500070470000D0F8903003EB4111D1F80039EA -:1035600023F40013C1F800397047000000F16043F4 -:1035700000F01F020901400903F56143C9B2800050 -:1035800083F80013012300F16040934000F561408F -:10359000C0F880310360704730B50433039C01727A -:1035A000002104FB0325C361049B00600363059BAA -:1035B0004060C16042610261856104624262816271 -:1035C000C162436330BD00000022416AC2604161B4 -:1035D00001616FF001018262C262FEF7E7BD000087 -:1035E00003694269934203D1C2680AB1002070475F -:1035F000181D7047036919600021C2680132C2605A -:10360000C269134482699342036124BF436A036120 -:10361000FEF7C0BD38B504460D46E3683BB16269AC -:103620000020131D1268A3621344E36238BD237A9D -:1036300033B929462046FEF79DFD0028EDDA38BD56 -:103640006FF00100FBE70000C368C269013BC36083 -:103650004369134482699342436124BF436A4361CF -:1036600000238362036B03B11847704770B52023B2 -:10367000044683F31188866A3EB9FFF7CBFF0546FF -:1036800018B186F31188284670BDA36AE26A13F860 -:10369000015B9342A36202D32046FFF7D5FF0023CC -:1036A00083F31188EFE700002DE9F84F04460E463A -:1036B00090469946202787F311880025AA46D4F81A -:1036C00028B0BBF1000F09D149462046FFF7A2FF01 -:1036D00020B18BF311882846BDE8F88FA16AA8EBCA -:1036E000050BE36A5B1A9B4528BF9B46BBF1400F65 -:1036F0001BD9334601F1400251F8040B914243F8C3 -:10370000040BF9D1A36A403640354033A362A26A64 -:10371000E36A9A4202D32046FFF796FF8AF31188A4 -:103720004545D8D287F31188C9E730465A46FDF798 -:103730007BFBA36A5E445D445B44A362E7E7000051 -:1037400010B5029C04330172C36103FB0421002302 -:1037500000608362C362039B40600363049BC46098 -:1037600042610261816104624262436310BD0000F4 -:10377000026A6FF00101C260426A42610261002286 -:103780008262C262FEF712BD436902699A4203D1A6 -:10379000C2680AB100207047184650F8043B0B601D -:1037A00070470000C3680021C2690133C3604369E8 -:1037B000134482699342436124BF436A4361FEF725 -:1037C000E9BC000038B504460D46E3683BB1236907 -:1037D00000201A1DA262E2691344E36238BD237A15 -:1037E00033B929462046FEF7C5FC0028EDDA38BD7E -:1037F0006FF00100FBE7000003691960C268013A3D -:10380000C260C269134482699342036124BF436A60 -:10381000036100238362036B03B118477047000004 -:1038200070B5202304460E4683F31188856A35B9A6 -:103830001146FFF7C7FF10B185F3118870BDA36A69 -:103840001E70A36AE26A01339342A36204D3E16962 -:1038500020460439FFF7D0FF002080F3118870BDA7 -:103860002DE9F84F04460D4691469A464FF0200840 -:1038700088F311880026B346A76A4FB951462046FF -:10388000FFF7A0FF20B187F311883046BDE8F88F1D -:10389000A06AA9EB0603E76A3F1A9F4228BF1F46AA -:1038A000402F1BD905F1400355F8042B9D4240F8E9 -:1038B000042BF9D1A36A40364033A362A26AE36ABB -:1038C0009A4204D3E16920460439FFF795FF8BF350 -:1038D00011884E45D9D288F31188CDE729463A465A -:1038E000FDF7A2FAA36A3D443E443B44A362E5E7E8 -:1038F000026943699A4203D1C3681BB918467047ED -:103900000023FBE7836A002BF8D0043B9B1AF5D019 -:103910001360C368013BC360C3691A4483699A4258 -:10392000026124BF436A0361002383620123E5E748 -:1039300000F0BAB8034B002258631A610222DA6021 -:10394000704700BF000C00400022014BDA60704756 -:10395000000C0040014B5863704700BF000C004052 -:10396000014B586A704700BF000C00404B68436031 -:103970008B688360CB68C3600B6943614B690362EA -:103980008B6943620B6803607047000008B5304BD9 -:1039900040F2FF712F48D3F888200A43C3F88820EB -:1039A000D3F8882022F4FF6222F00702C3F88820AF -:1039B000D3F88820D3F8E0200A43C3F8E020D3F8F6 -:1039C00008210A43C3F80821234AD3F808311146D5 -:1039D000FFF7CCFF214802F11C01FFF7C7FF204889 -:1039E00002F13801FFF7C2FF1E4802F15401FFF750 -:1039F000BDFF1D4802F17001FFF7B8FF1B4802F13F -:103A00008C01FFF7B3FF1A4802F1A801FFF7AEFFE0 -:103A1000184802F1C401FFF7A9FF174802F1E001BD -:103A2000FFF7A4FF154802F1FC01FFF79FFF1448C0 -:103A300002F58C71FFF79AFF00F0EAF8114B0522AE -:103A40009A604FF06052DA600F4A1A6108BD00BFF9 -:103A50000044025800000258744200080004025852 -:103A600000080258000C02580010025800140258B6 -:103A700000180258001C0258002002580024025866 -:103A80000028025890ED00E01F00080308B500F080 -:103A9000BBFAFEF7F7FAFEF74DFFBDE80840FEF768 -:103AA000F9BC000070470000114BD3F8E82042F049 -:103AB0000802C3F8E820D3F8102142F00802C3F846 -:103AC00010210C4AD3F81031D36B43F00803D363B1 -:103AD000C722094B9A624FF0FF32DA6200229A61E4 -:103AE0005A63DA605A6001225A611A60704700BF57 -:103AF000004402580010005C000C0040094A08B560 -:103B00001369D1680B40D9B29B076FEA01011161BB -:103B100007D5202383F31188FEF7D4FA002383F31B -:103B2000118808BD000C0040384B4FF0FF31D3F82E -:103B30008020C3F88010D3F880200022C3F88020B2 -:103B4000D3F88000D3F88400C3F88410D3F884003D -:103B5000C3F88420D3F88400D86F40F0FF4040F4CD -:103B6000FF0040F43F5040F03F00D867D86F20F08E -:103B7000FF4020F4FF0020F43F5020F03F00D867C2 -:103B8000D86FD3F888006FEA40506FEA5050C3F8FE -:103B90008800D3F88800C0F30A00C3F88800D3F87F -:103BA0008800D3F89000C3F89010D3F89000C3F8C1 -:103BB0009020D3F89000D3F89400C3F89410D3F871 -:103BC0009400C3F89420D3F89400D3F89800C3F875 -:103BD0009810D3F89800C3F89820D3F89800D3F839 -:103BE0008C00C3F88C10D3F88C00C3F88C20D3F869 -:103BF0008C00D3F89C00C3F89C10D3F89C10C3F839 -:103C00009C20D3F89C3000F0D3B900BF0044025888 -:103C10000122614B1A60614BD3F8F42042F002029A -:103C2000C3F8F420D3F81C2142F00202C3F81C218F -:103C30000222D3F81C315A4BDA605A689104FCD541 -:103C4000584A1A6001229A60574ADA6000221A61C3 -:103C50004FF440429A61524B9A699204FCD51A681B -:103C600042F480721A604D4B1A6F12F4407F04D0F8 -:103C70004FF480321A6700221A671A6842F0010274 -:103C80001A60464A134611684807FCD500211161A5 -:103C90001A6912F03802FBD1012119604FF08041FE -:103CA00059605A67414ADA62414A1A611A6842F415 -:103CB00080321A60394A134611688903FCD51168AD -:103CC00041F4805111601A689204FCD5394A3A498E -:103CD0009A6200225A6319633849DA6399635A6415 -:103CE000374A1A64374ADA621A6842F0A8521A60F0 -:103CF0002A4B1A6802F02852B2F1285FF9D1482203 -:103D00009A614FF48862DA6140221A622E4ADA64BC -:103D10004FF000521A652D4A5A652D4A9A65322293 -:103D20002C4B1A601A6802F00F02022AFAD11B4BC0 -:103D30001A6942F003021A611A6902F03802182A5D -:103D4000FAD1D3F8DC2042F00052C3F8DC20D3F8DB -:103D5000042142F00052C3F80421D3F80421D3F81F -:103D6000DC2042F08042C3F8DC20D3F8042142F08A -:103D70008042C3F80421D3F80421D3F8DC2042F0B8 -:103D80000042C3F8DC20D3F8042142F00042C3F81B -:103D90000421D3F8043170470881005100440258CF -:103DA0000048025800C000F0020000010000FF01BE -:103DB0000088900832306000630207011802030394 -:103DC00047040508FD0BFF01000001200010E00082 -:103DD00000010100002000524FF0B04208B5D2F8B7 -:103DE000883003F00103C2F8883023B1044A136815 -:103DF0000BB150689847BDE80840FEF7E7BD00BF2B -:103E0000C02300204FF0B04208B5D2F8883003F04C -:103E10000203C2F8883023B1044A93680BB1D0681A -:103E20009847BDE80840FEF7D1BD00BFC023002081 -:103E30004FF0B04208B5D2F8883003F00403C2F85E -:103E4000883023B1044A13690BB150699847BDE823 -:103E50000840FEF7BBBD00BFC02300204FF0B042BA -:103E600008B5D2F8883003F00803C2F8883023B1CF -:103E7000044A93690BB1D0699847BDE80840FEF742 -:103E8000A5BD00BFC02300204FF0B04208B5D2F856 -:103E9000883003F01003C2F8883023B1044A136A53 -:103EA0000BB1506A9847BDE80840FEF78FBD00BFD0 -:103EB000C02300204FF0B04310B5D3F8884004F47D -:103EC0007872C3F88820A30604D5124A936A0BB10E -:103ED000D06A9847600604D50E4A136B0BB1506B3D -:103EE0009847210604D50B4A936B0BB1D06B9847CA -:103EF000E20504D5074A136C0BB1506C9847A30533 -:103F000004D5044A936C0BB1D06C9847BDE81040BF -:103F1000FEF75CBDC02300204FF0B04310B5D3F8CE -:103F2000884004F47C42C3F88820620504D5164A10 -:103F3000136D0BB1506D9847230504D5124A936D4C -:103F40000BB1D06D9847E00404D50F4A136E0BB146 -:103F5000506E9847A10404D50B4A936E0BB1D06EF6 -:103F60009847620404D5084A136F0BB1506F984705 -:103F7000230404D5044A936F0BB1D06F9847BDE872 -:103F80001040FEF723BD00BFC023002008B5034842 -:103F9000FDF718F9BDE80840FEF718BD40240020E1 -:103FA00008B5FFF7ABFDBDE80840FEF70FBD000008 -:103FB000062108B50846FFF7D9FA06210720FFF7C2 -:103FC000D5FA06210820FFF7D1FA06210920FFF7CC -:103FD000CDFA06210A20FFF7C9FA06211720FFF7BC -:103FE000C5FA06212820FFF7C1FA09217A20FFF738 -:103FF000BDFA07213220FFF7B9FA0C215220BDE8A3 -:104000000840FFF7B3BA000008B5FFF78DFDFDF7D4 -:1040100041F8FDF7F1FAFDF7CBFCFDF79BFBFFF74D -:1040200041FDBDE80840FFF783BC000010B5013931 -:104030000244904201D1002010BD10F8013B11F85C -:10404000014FA342F5D0181B10BD0000034611F824 -:10405000012B03F8012B002AF9D17047121012131B -:1040600012110000682A00204024002053544D33D0 -:104070003248373F3F3F0053544D33324837343393 -:104080002F373533000000000096000000000000CC -:104090000000000000000000000000000000000020 -:1040A00000000000C1150008AD150008E915000862 -:1040B000D5150008E1150008CD150008B915000850 -:1040C000A5150008F515000800000000CD16000831 -:1040D000B9160008F5160008E1160008ED160008EC -:1040E000D9160008C5160008B116000851170008B7 -:1040F0000000000001000000000000006D61696E1A -:10410000000000001C410008F0280020682A002060 -:1041100001000000812000080000000069646C6557 -:10412000000000000200000000000000F918000874 -:104130006519000840004000104300202043002083 -:10414000020000000000000003000000000000006A -:10415000AD190008000000001000000030430020EE -:10416000000000000100000000000000A045002049 -:10417000010102004172647550696C6F7400254240 -:104180004F415244252D424C002553455249414C44 -:1041900025000000352400089D230008651800084C -:1041A0001924000843000000AC4100080902430044 -:1041B000020100C0320904000001020201000524CE -:1041C0000010010524010001042402020524060058 -:1041D00001070582030800FF09040100020A00002C -:1041E00000070501024000000705810240000000B1 -:1041F00012000000F8410008120110010200004006 -:1042000009124157000201020301000004030904DE -:1042100025424F41524425006C756D696E6F757370 -:1042200062656535003031323334353637383941DF -:10423000424344454600000000000000251B0008E2 -:10424000051E0008B11E000840004000D8460020AE -:10425000D846002001000000E84600208000000051 -:104260004001000008000000000100000004000000 -:10427000080000000000802A00000000AAAAAAAAE4 -:1042800000000000FFFF00000000000000A00A0086 -:104290000001400000000000AAAAAAAA0001000034 -:1042A000FFFF0000000000000000000010000040C0 -:1042B00000000000AAAAAAAA10000040FFFF000008 -:1042C00000000000000000000040000000000000AE -:1042D000AAAAAAAA00400000FFFF000000000000F8 -:1042E000000000000080024000000000AAAAAAAA64 -:1042F00000400140FFFF00000000007007000000C8 +:100310006F8F02F0C3FB02F065FB03F0FFFA4FF0B2 +:1003200055301F491B4A91423CBF41F8040BFAE784 +:100330001C49194A91423CBF41F8040BFAE71A499B +:100340001A4A1B4B9A423EBF51F8040B42F8040B69 +:10035000F8E700201749184A91423CBF41F8040BC6 +:10036000FAE702F07DFB03F05DFB144C144DAC4248 +:1003700003DA54F8041B8847F9E700F041F8114C00 +:10038000114DAC4203DA54F8041B8847F9E702F038 +:1003900065BB0000000600200022002000000008CD +:1003A00000000020000600209043000800220020EA +:1003B0005C22002060220020FC460020A0020008F1 +:1003C000A0020008A0020008A00200082DE9F04FDA +:1003D0002DED108AC1F80CD0D0F80CD0BDEC108AED +:1003E000BDE8F08F002383F311882846A047002042 +:1003F00001F07AFEFEE701F0F5FD00DFFEE7000008 +:1004000038B500F0DDFC30B1164B00220E211A7217 +:100410005A729972DA7202F043FA054602F076FADD +:100420000446D0B9104B9D4219D001339D4241F290 +:10043000883512BF044600250124002002F03AFA54 +:100440000CB100F059F800F057FD00F0FFFB284612 +:1004500000F004F900F050F8F9E70025EDE7054653 +:10046000EBE700BF00220020010007B008B500F054 +:10047000B9FBA0F120035842584108BD07B541F22D +:100480001203022101A8ADF8043000F0C9FB03B04B +:100490005DF804FB202310B583F311881248C3686C +:1004A0000BB101F0A7FE0023104A4FF47A710E48F9 +:1004B00001F064FE002383F311880D4C236813B10F +:1004C0002368013B2360636813B16368013B636089 +:1004D000084B1B7833B9636823B9022000F086FC0F +:1004E0003223636010BD00BF602200209504000825 +:1004F0007C23002074220020F8B5514B514A1C4641 +:100500001968013100F09B8004339342F8D162688E +:100510004D4B9A4240F293804C4B9B6803F1006331 +:1005200003F500339A4280F08A80002000F0A8FB97 +:100530000220474B187000F04FFC464B0021D3F8C7 +:10054000E820C3F8E810D3F81021C3F81011D3F84D +:100550001021D3F8EC20C3F8EC10D3F81421C3F821 +:100560001411D3F81421D3F8F020C3F8F010D3F805 +:100570001821C3F81811D3F81821D3F8802042F0BD +:100580000062C3F88020D3F8802022F00062C3F814 +:100590008020D3F88020D3F8802042F00072C3F886 +:1005A0008020D3F8802022F00072C3F88020D3F896 +:1005B000803072B64FF0E023C3F8084DD4E9000450 +:1005C000BFF34F8FBFF36F8F234AC2F88410BFF37E +:1005D0004F8F536923F480335361BFF34F8FD2F8A9 +:1005E000803043F6E076C3F3C905C3F34E335B01B5 +:1005F00003EA060C29464CEA81770139C2F8747285 +:10060000F9D2203B13F1200FF2D1BFF34F8FBFF38C +:100610006F8FBFF34F8FBFF36F8F536923F4003396 +:1006200053610023C2F85032BFF34F8FBFF36F8F77 +:10063000202383F31188854680F308882047F8BD7E +:100640000000020820000208FFFF0108002200202D +:10065000742200200044025800ED00E02DE9F04F24 +:1006600093B0A94B2022FF2100900AA89D6800F0BA +:10067000EDFBA64A1378A3B90121A5481170C36008 +:10068000202383F31188C3680BB101F0B3FD00236D +:10069000A04A4FF47A719E4801F070FD002383F365 +:1006A0001188009B9C4A03B1136000239B49009C66 +:1006B00098469B461E469A460B705360012000F0F8 +:1006C0008BFB24B1944B1B68002B00F0168200209A +:1006D00000F088FA0390039B002BF2DB012000F06E +:1006E00071FB039B213B162BE8D801A252F823F0A3 +:1006F0004D0700087507000809080008BD06000836 +:10070000BD060008BD0600089D0800086F0A000825 +:1007100089090008EB090008130A0008390A0008D3 +:10072000BD0600084B0A0008BD060008BD0A000807 +:10073000ED070008BD060008010B00085907000876 +:10074000ED070008BD060008EB0900080220FFF7CE +:100750008DFE002840F0FB81009B022105A8B8F126 +:10076000000F08BF1C4641F21233ADF8143000F000 +:1007700057FAA3E74FF47A7000F034FA071EEBDB68 +:100780000220FFF773FE0028E6D0013F052F00F29C +:10079000E081DFE807F0030A0D101336052304217A +:1007A00005A8059300F03CFA17E004215648F9E744 +:1007B00004215B48F6E704215A48F3E74FF01C098F +:1007C000484609F1040900F05DFA0421059005A8E6 +:1007D00000F026FAB9F12C0FF2D101204FF0000AF7 +:1007E00000FA07F747EA0B0B5FFA8BFB00F07AFB86 +:1007F00026B10BF00B030B2B08BF0024FFF73EFEC6 +:100800005CE704214848CDE7002EA5D00BF00B0390 +:100810000B2BA1D10220FFF729FE074600289BD011 +:1008200001203E4E00F02CFA4FF0000802203070FC +:1008300000F0D2FA5FFA88F9484600F031FA04462F +:1008400090B1484608F1010800F03AFA0028F1D1C9 +:10085000B846044641F21213022105A83E46ADF8FF +:10086000143000F0DDF929E701232546022033701A +:1008700000F0A8FA244B9B68AB4207D9284600F049 +:1008800001FA013040F068810435F3E70025234B7D +:10089000B8463E461D70204B5D60A7E7002E3FF432 +:1008A0005BAF0BF00B030B2B7FF456AF02201B4BFF +:1008B000187000F091FA322000F094F9B0F10009BC +:1008C000FFF64AAF19F003077FF446AF0E4A09EB73 +:1008D0000503926893423FF63FAFB9F5807F3FF73B +:1008E0003BAF124BB945019322DD4FF47A7000F013 +:1008F00079F90390039A002AFFF62EAF039A013785 +:10090000019B03F8012BEDE7002200207823002053 +:1009100060220020950400087C230020742200201F +:1009200004220020082200200C220020782200202F +:10093000C820FFF79BFD074600283FF40DAF1F2D91 +:1009400011D8C5F120020AAB25F0030084494A45BD +:10095000184428BF4A46019200F052FA019AFF213A +:100960007F4800F073FA4FEAA903C9F387027C4974 +:100970002846019300F072FA064600283FF46AAF59 +:10098000019B05EB830531E70220FFF76FFD00288F +:100990003FF4E2AE00F0B0F900283FF4DDAE0027EE +:1009A000B946704B9B68BB4218D91F2F11D80A9BC0 +:1009B00001330ED027F0030312AA134453F8203C4E +:1009C00005934846042205A9043700F031FB81460F +:1009D000E7E7384600F056F90590F2E7CDF81490B5 +:1009E000042105A800F01CF900E70023642104A8F5 +:1009F000049300F00BF900287FF4AEAE0220FFF75D +:100A000035FD00283FF4A8AE049800F06BF905907E +:100A1000E6E70023642104A8049300F0F7F8002817 +:100A20007FF49AAE0220FFF721FD00283FF494AE38 +:100A3000049800F059F9EAE70220FFF717FD0028B3 +:100A40003FF48AAE00F068F9E1E70220FFF70EFDFF +:100A500000283FF481AE05A9142000F063F9074691 +:100A60000421049004A800F0DBF83946B9E73220ED +:100A700000F0B8F8071EFFF66FAEBB077FF46CAE50 +:100A8000384A07EB0A03926893423FF665AE0220AC +:100A9000FFF7ECFC00283FF45FAE27F00307574454 +:100AA000BA453FF4A3AE50460AF1040A00F0EAF852 +:100AB0000421059005A800F0B3F8F1E74FF47A702F +:100AC000FFF7D4FC00283FF447AE00F015F90028EA +:100AD00044D00A9B01330BD008220AA9002000F061 +:100AE000BDF900283AD02022FF210AA800F0AEF973 +:100AF000FFF7C4FC1C4801F0FDFA13B0BDE8F08F0D +:100B0000002E3FF429AE0BF00B030B2B7FF424AE29 +:100B10000023642105A8059300F078F80746002813 +:100B20007FF41AAE0220FFF7A1FC814600283FF4B3 +:100B300013AEFFF7A3FC41F2883001F0DBFA059811 +:100B400000F014FA4E463C4600F0CCF9B6E50646F5 +:100B50004CE64FF0000AFFE5B8467BE6374679E6FB +:100B60007822002000220020A0860100F7B50C4664 +:100B7000184E4FF47A71054602FB01F396F90020F6 +:100B8000501C0BD11448294601930268176A22466B +:100B9000B8478442019B03D1002310E0002AF1D022 +:100BA00096F90020511C01D0012A0DD10B4829468D +:100BB0000268166A2246B047844205D10123084ADA +:100BC0000120137003B0F0BD4FF4FA7001F092FAF7 +:100BD0000020F7E710220020F0290020CC2300207D +:100BE000C8230020002307B5024601210DF10700AC +:100BF0008DF80730FFF7BAFF20B19DF8070003B06A +:100C00005DF804FB4FF0FF30F9E700000A460421CD +:100C100008B5FFF7ABFF80F00100C0B2404208BD4D +:100C2000074B0A4630B41978064B53F82140014669 +:100C300023682046DD69044BAC4630BC604700BFEA +:100C4000C823002064400008A086010070B50A4E49 +:100C500000240A4D01F0FCFC308028683388834270 +:100C600008D901F0F1FC2B6804440133B4F5003FCE +:100C70002B60F2D370BD00BFCA2300208423002064 +:100C800001F0C4BD00F1006000F50030006870475D +:100C900000F10060920000F5003001F03BBD000063 +:100CA000054B1A68054B1B889B1A834202D91044D6 +:100CB00001F0CABC0020704784230020CA23002012 +:100CC00038B5074D04462868204401F0C3FC28B914 +:100CD00028682044BDE8384001F0CEBC38BD00BFD4 +:100CE000842300200020704700F1FF5000F58F1092 +:100CF000D0F8000870470000064991F8243033B15D +:100D000000230822086A81F82430FFF7C1BF0120C0 +:100D1000704700BF88230020014B1868704700BF50 +:100D20000010005C244BF0B51A680446234BC2F354 +:100D30000B06120C1F885868BE4293F9085028D041 +:100D40009F89BE4206D101200C2505FB003358685F +:100D500093F9085041F201039A421CD041F2030377 +:100D60009A421AD042F201039A4218D042F2030387 +:100D70009A4208BF5625621E0B46441E0A449342FF +:100D80000FD214F9016F581C6EB1034600F8016CC4 +:100D9000F5E70020D8E75A25EDE75925EBE7582578 +:100DA000E9E7184605E02C2482421C7001D9981C02 +:100DB0005D70401AF0BD00BF0010005C14220020DE +:100DC00000207047022803D1024B4FF000629A6165 +:100DD000704700BF00040258022803D1024B4FF4B1 +:100DE00000629A61704700BF00040258022804D1D3 +:100DF000024A536983F40063536170470004025848 +:100E0000002310B5934203D0CC5CC4540133F9E7FE +:100E100010BD0000013810B510F9013F3BB191F948 +:100E200000409C4203D11AB10131013AF4E71AB1F2 +:100E300091F90020981A10BD1046FCE703460246BF +:100E4000D01A12F9011B0029FAD170470244034657 +:100E5000934202D003F8011BFAE770472DE9F843EB +:100E60001F4D14460746884695F8242052BBDFF8EC +:100E700070909CB395F824302BB92022FF2148466E +:100E80002F62FFF7E3FF95F824004146C0F1080206 +:100E900005EB8000A24228BF2246D6B29200FFF79F +:100EA000AFFF95F82430A41B17441E449044E4B2CD +:100EB000F6B2082E85F82460DBD1FFF71DFF00286D +:100EC000D7D108E02B6A03EB82038342CFD0FFF730 +:100ED00013FF0028CBD10020BDE8F8830120FBE7F9 +:100EE00088230020024B1A78024B1A70704700BF0B +:100EF000C82300201022002038B5164C164D20467D +:100F000000F0FAFB2946204600F022FC2D68134829 +:100F1000D5F89020D2F8043843F00203C2F8043820 +:100F200001F0E8F80E49284600F020FDD5F89020A1 +:100F30000C48D2F804380C49A04223F00203C2F84E +:100F400004384FF4E1330B6003D0BDE8384000F0C3 +:100F500031BB38BDF02900207041000840420F002D +:100F600078410008CC230020B023002038B50B4B7B +:100F700004461A780A4B53F822500A4B9D420CD073 +:100F8000094B002118221846FFF760FF0460014654 +:100F90002846BDE8384000F00DBB38BDC82300200E +:100FA00064400008F0290020B023002000B59BB069 +:100FB000EFF3098168226846FFF722FFEFF305830C +:100FC000044B9A6BDA6A9A6A9A6A9A6A9A6A9A6A75 +:100FD0009B6AFEE700ED00E000B59BB0EFF30981EE +:100FE00068226846FFF70CFFEFF30583044B9A6B0A +:100FF0009A6A9A6A9A6A9A6A9A6A9B6AFEE700BF34 +:1010000000ED00E000B59BB0EFF30981682268466F +:10101000FFF7F6FEEFF30583034B5A6B9A6A9A6A61 +:101020009A6A9A6A9B6AFEE700ED00E0FEE700001C +:1010300030B50A44084D91420DD011F8013B58409B +:10104000082340F30004013B2C4013F0FF0384EA23 +:101050005000F6D1EFE730BD2083B8ED0268436859 +:101060001143016003B1184770470000024A13683A +:1010700043F0C003136070470078004013B50E4C76 +:10108000204600F08BFA04F1140000234FF40072A4 +:101090000A49009400F04CF9094B4FF400720949D9 +:1010A00004F13800009400F0C5F9074A074BC4E981 +:1010B000172302B010BD00BFCC230020382400202D +:1010C0006D100008382600200078004000E1F5058A +:1010D000037C30B5244C002918BF0C46012B11D1DC +:1010E000224B98420ED1224BD3F8E82042F08042A6 +:1010F000C3F8E820D3F8102142F08042C3F8102151 +:10110000D3F810312268036EC16D03EB520384667D +:10111000B3FBF2F36268150442BF23F0070503F046 +:10112000070343EA4503CB60A36843F040034B60E9 +:10113000E36843F001038B6042F4967343F00103CC +:101140000B604FF0FF330B62510505D512F01022F2 +:1011500005D0B2F1805F04D080F8643030BD7F23C9 +:10116000FAE73F23F8E700BF6C400008CC230020DB +:10117000004402582DE9F047C66D05463768F4690A +:101180002107346219D014F0080118BF8021E2074A +:1011900048BF41F02001A3074FF0200348BF41F0B2 +:1011A0004001600748BF41F4807183F31188281D16 +:1011B000FFF754FF002383F31188E2050AD52023AB +:1011C00083F311884FF40071281DFFF747FF0023B8 +:1011D00083F311884FF020094FF0000A14F0200823 +:1011E00038D13B0616D54FF0200905F1380A200604 +:1011F00010D589F31188504600F050F9002836DAEE +:101200000821281DFFF72AFF27F080033360002301 +:1012100083F31188790614D5620612D5202383F34F +:101220001188D5E913239A4208D12B6C33B127F0EA +:1012300040071021281DFFF711FF3760002383F3BB +:101240001188E30618D5AA6E1369ABB15069BDE8E1 +:10125000F047184789F31188736A284695F8641097 +:10126000194000F0B5F98AF31188F469B6E7B06265 +:1012700088F31188F469BAE7BDE8F087F8B5154638 +:10128000826804460B46AA4200D28568A169266995 +:10129000761AB5420BD218462A46FFF7B1FDA3696C +:1012A0002B44A3612846A3685B1BA360F8BD0CD93F +:1012B000AF1B18463246FFF7A3FD3A46E1683044BB +:1012C000FFF79EFDE3683B44EBE718462A46FFF72D +:1012D00097FDE368E5E7000083689342F7B50446AD +:1012E000154600D28568D4E90460361AB5420BD29F +:1012F0002A46FFF785FD63692B4463612846A3688E +:101300005B1BA36003B0F0BD0DD93246AF1B01914A +:10131000FFF776FD01993A46E0683144FFF770FD2A +:10132000E3683B44E9E72A46FFF76AFDE368E4E740 +:1013300010B50A440024C361029B8460C16002614D +:101340000362C0E90000C0E9051110BD08B5D0E98D +:101350000532934201D1826882B98268013282608B +:101360005A1C426119700021D0E904329A4224BF0C +:10137000C368436100F0DAFE002008BD4FF0FF3083 +:10138000FBE7000070B5202304460E4683F3118866 +:10139000A568A5B1A368A269013BA360531CA36122 +:1013A00015782269934224BFE368A361E3690BB116 +:1013B00020469847002383F31188284607E03146EA +:1013C000204600F0A3FE0028E2DA85F3118870BD04 +:1013D0002DE9F74F04460E4617469846D0F81C9064 +:1013E0004FF0200A8AF311884FF0000B154665B1C3 +:1013F0002A4631462046FFF741FF034660B9414681 +:10140000204600F083FE0028F1D0002383F31188EA +:10141000781B03B0BDE8F08FB9F1000F03D0019045 +:101420002046C847019B8BF31188ED1A1E448AF3AE +:101430001188DCE7C160C361009B82600362C0E980 +:1014400005111144C0E9000001617047F8B5044678 +:101450000D461646202383F31188A768A7B1A36819 +:10146000013BA36063695A1C62611D70D4E90432B8 +:101470009A4224BFE3686361E3690BB12046984751 +:10148000002080F3118807E03146204600F03EFE40 +:101490000028E2DA87F31188F8BD0000D0E90523BF +:1014A00010B59A4201D182687AB98268002101326E +:1014B00082605A1C82611C7803699A4224BFC36807 +:1014C000836100F033FE204610BD4FF0FF30FBE794 +:1014D0002DE9F74F04460E4617469846D0F81C9063 +:1014E0004FF0200A8AF311884FF0000B154665B1C2 +:1014F0002A4631462046FFF7EFFE034660B94146D3 +:10150000204600F003FE0028F1D0002383F3118869 +:10151000781B03B0BDE8F08FB9F1000F03D0019044 +:101520002046C847019B8BF31188ED1A1E448AF3AD +:101530001188DCE7026843681143016003B1184772 +:10154000704700001430FFF743BF00004FF0FF3337 +:101550001430FFF73DBF00003830FFF7B9BF00007F +:101560004FF0FF333830FFF7B3BF00001430FFF700 +:1015700009BF00004FF0FF311430FFF703BF000038 +:101580003830FFF763BF00004FF0FF323830FFF70D +:101590005DBF000000207047FFF770BD044B036083 +:1015A00000234360C0E9023301230374704700BF86 +:1015B0008440000810B52023044683F31188FFF708 +:1015C00087FD02232374002383F3118810BD0000DC +:1015D00038B5C36904460D461BB904210844FFF71A +:1015E000A9FF294604F11400FFF7B0FE002806DA2F +:1015F000201D4FF48061BDE83840FFF79BBF38BD28 +:10160000026843681143016003B118477047000046 +:1016100013B5406B00F58054D4F8A4381A681178DB +:10162000042914D1017C022911D1197901231289CD +:101630008B4013420BD101A94C3002F06FF8D4F863 +:10164000A4480246019B2179206800F0DFF902B02E +:1016500010BD0000143001F0F1BF00004FF0FF3367 +:10166000143001F0EBBF00004C3002F0C3B80000B2 +:101670004FF0FF334C3002F0BDB80000143001F0E1 +:10168000BFBF00004FF0FF31143001F0B9BF0000C0 +:101690004C3002F08FB800004FF0FF324C3002F0B7 +:1016A00089B800000020704710B500F58054D4F8C8 +:1016B000A4381A681178042917D1017C022914D1A1 +:1016C0005979012352898B4013420ED1143001F015 +:1016D00051FF024648B1D4F8A4484FF440736179F1 +:1016E0002068BDE8104000F07FB910BD406BFFF7E7 +:1016F000DBBF0000704700007FB5124B01250426B8 +:10170000044603600023057400F184024360294607 +:10171000C0E902330C4B0290143001934FF4407334 +:10172000009601F003FF094B04F69442294604F1A8 +:101730004C000294CDE900634FF4407301F0CAFFFE +:1017400004B070BDAC400008ED160008111600088A +:101750000A68202383F311880B790B3342F82300A6 +:101760004B79133342F823008B7913B10B3342F8D2 +:10177000230000F58053C3F8A41802230374002348 +:1017800083F311887047000038B5037F044613B116 +:1017900090F85430ABB90125201D0221FFF730FF2E +:1017A00004F114006FF00101257700F0CBFC04F187 +:1017B0004C0084F854506FF00101BDE8384000F04F +:1017C000C1BC38BD10B5012104460430FFF718FF35 +:1017D0000023237784F8543010BD000038B5044648 +:1017E0000025143001F0BAFE04F14C00257701F019 +:1017F00089FF201D84F854500121FFF701FF204686 +:10180000BDE83840FFF750BF90F8803003F0600328 +:10181000202B06D190F881200023212A03D81F2AEB +:1018200006D800207047222AFBD1C0E91D3303E00F +:10183000034A426707228267C3670120704700BFDF +:101840002C22002037B500F58055D5F8A4381A6849 +:10185000117804291AD1017C022917D119790123A1 +:1018600012898B40134211D100F14C04204602F042 +:1018700009F858B101A9204601F050FFD5F8A44855 +:101880000246019B2179206800F0C0F803B030BD0A +:1018900001F10B03F0B550F8236085B004460D4606 +:1018A000FEB1202383F3118804EB8507301D082146 +:1018B000FFF7A6FEFB6806F14C005B691B681BB1D5 +:1018C000019001F039FF019803A901F027FF0246BA +:1018D00048B1039B2946204600F098F8002383F383 +:1018E000118805B0F0BDFB685A691268002AF5D06E +:1018F0001B8A013B1340F1D104F18002EAE70000AA +:10190000133138B550F82140ECB1202383F311880E +:1019100004F58053D3F8A4281368527903EB8203AB +:10192000DB689B695D6845B104216018FFF768FEBC +:10193000294604F1140001F027FE2046FFF7B4FE0B +:10194000002383F3118838BD7047000001F01AB9F5 +:1019500001234022002110B5044600F8303BFFF778 +:1019600075FA0023C4E9013310BD000010B520232F +:10197000044683F311882422416000210C30FFF7D4 +:1019800065FA204601F020F902232370002383F337 +:10199000118810BD70B500EB8103054650690E46F5 +:1019A0001446DA6018B110220021FFF74FFAA0693F +:1019B00018B110220021FFF749FA31462846BDE848 +:1019C000704001F013BA000083682022002103F068 +:1019D000011310B5044683601030FFF737FA204634 +:1019E000BDE8104001F08EBAF0B4012500EB81048F +:1019F00047898D40E4683D43A46945812360002305 +:101A0000A2606360F0BC01F0ABBA0000F0B4012545 +:101A100000EB810407898D40E4683D4364690581DA +:101A200023600023A2606360F0BC01F021BB0000D2 +:101A300070B5022300250446242203702946C0F80D +:101A400088500C3040F8045CFFF700FA204684F818 +:101A5000705001F05FF963681B6823B12946204686 +:101A6000BDE87040184770BD037880F88C300523BE +:101A7000037043681B6810B504460BB104219847F6 +:101A80000023A36010BD000090F88C204368027012 +:101A90001B680BB1052118477047000070B590F81E +:101AA0007030044613B1002380F8703004F18002D6 +:101AB000204601F04BFA63689B68B3B994F8803014 +:101AC00013F0600535D00021204601F0F5FC00211F +:101AD000204601F0E5FC63681B6813B1062120462F +:101AE0009847062384F8703070BD20469847002838 +:101AF000E4D0B4F88630A26F9A4288BFA36794F905 +:101B00008030A56F002B4FF0200380F20381002D61 +:101B100000F0F280092284F8702083F311880021FC +:101B20002046D4E91D23FFF771FF002383F31188BA +:101B3000DAE794F8812003F07F0343EA022340F2BE +:101B40000232934200F0C58021D8B3F5807F48D09F +:101B50000DD8012B3FD0022B00F09380002BB2D187 +:101B600004F1880262670222A267E367C1E7B3F566 +:101B7000817F00F09B80B3F5407FA4D194F8823040 +:101B8000012BA0D1B4F8883043F0020332E0B3F562 +:101B9000006F4DD017D8B3F5A06F31D0A3F5C06357 +:101BA000012B90D86368204694F882205E6894F8F0 +:101BB0008310B4F88430B047002884D0436863674A +:101BC0000368A3671AE0B3F5106F36D040F60242FF +:101BD00093427FF478AF5C4B63670223A3670023D3 +:101BE000C3E794F88230012B7FF46DAFB4F88830EE +:101BF00023F00203A4F88830C4E91D55E56778E7AF +:101C0000B4F88030B3F5A06F0ED194F8823020463E +:101C100084F88A3001F0DCF863681B6813B1012195 +:101C200020469847032323700023C4E91D339CE713 +:101C300004F18B0363670123C3E72378042B10D1DE +:101C4000202383F311882046FFF7BEFE85F3118819 +:101C50000321636884F88B5021701B680BB1204608 +:101C6000984794F88230002BDED084F88B30042320 +:101C7000237063681B68002BD6D00221204698474A +:101C8000D2E794F8843020461D0603F00F010AD5F0 +:101C900001F04EF9012804D002287FF414AF2B4B39 +:101CA0009AE72B4B98E701F035F9F3E794F8823087 +:101CB000002B7FF408AF94F8843013F00F01B3D0F9 +:101CC0001A06204602D501F00FFCADE701F000FC3A +:101CD000AAE794F88230002B7FF4F5AE94F88430B4 +:101CE00013F00F01A0D01B06204602D501F0E4FB43 +:101CF0009AE701F0D5FB97E7142284F8702083F36C +:101D000011882B462A4629462046FFF76DFE85F3AB +:101D10001188E9E65DB1152284F8702083F31188FB +:101D200000212046D4E91D23FFF75EFEFDE60B22CD +:101D300084F8702083F311882B462A4629462046D2 +:101D4000FFF764FEE3E700BFDC400008D440000872 +:101D5000D840000838B590F870300446002B3ED0CB +:101D6000063BDAB20F2A34D80F2B32D8DFE803F063 +:101D70003731310822323131313131313131373778 +:101D8000856FB0F886309D4214D2C3681B8AB5FBBC +:101D9000F3F203FB12556DB9202383F311882B4610 +:101DA0002A462946FFF732FE85F311880A2384F874 +:101DB00070300EE0142384F87030202383F31188F0 +:101DC000002320461A461946FFF70EFE002383F330 +:101DD000118838BDC36F03B198470023E7E700219E +:101DE000204601F069FB0021204601F059FB6368A1 +:101DF0001B6813B10621204698470623D7E7000049 +:101E000010B590F870300446142B29D017D8062B43 +:101E100005D001D81BB110BD093B022BFBD8002116 +:101E2000204601F049FB0021204601F039FB6368A0 +:101E30001B6813B1062120469847062319E0152B8D +:101E4000E9D10B2380F87030202383F3118800231D +:101E50001A461946FFF7DAFD002383F31188DAE703 +:101E6000C3689B695B68002BD5D1C36F03B19847EA +:101E7000002384F87030CEE7024B0022C3E9003320 +:101E80009A60704738280020002382680374054B4D +:101E90001B6899689142FBD25A68036042601060E7 +:101EA000586070473828002008B5202383F3118834 +:101EB000037C032B05D0042B0DD02BB983F31188A1 +:101EC00008BD436900221A604FF0FF334361FFF7FA +:101ED000DBFF0023F2E7D0E9003213605A60F3E73A +:101EE000002382680374054B1B6899689142FBD8F4 +:101EF0005A680360426010605860704738280020BC +:101F0000054B196908741868026853601A601861F3 +:101F100001230374FEF75ABA382800204B1C30B551 +:101F2000044687B00A4D10D02B6901A8094A00F079 +:101F300025F92046FFF7E4FF049B13B101A800F048 +:101F400059F92B69586907B030BDFFF7D9FFF8E799 +:101F500038280020A91E000838B50C4D0446416100 +:101F60002B6981689A68914203D8BDE83840FFF731 +:101F70008BBF1846FFF7B4FF01232C610146237481 +:101F80002046BDE83840FEF721BA00BF38280020BF +:101F9000044B1A681B6990689B68984294BF0020A4 +:101FA000012070473828002010B5084C23682069AC +:101FB0001A6854602260012223611A74FFF790FFAF +:101FC00001462069BDE81040FEF700BA382800201D +:101FD00008B5FFF7DDFF18B1BDE80840FFF7E4BF23 +:101FE00008BD0000FFF7E0BFFEE7000010B50C4C95 +:101FF000FFF742FF00F0B4F880220A49204600F0C3 +:102000003BF8012344F8180C037400F099FC0023FA +:1020100083F3118862B60448BDE8104000F04CB864 +:1020200060280020E0400008F040000800F01CB9E3 +:10203000EFF3118020B9EFF30583202282F311889A +:102040007047000010B530B9EFF30584C4F30804FD +:1020500014B180F3118810BDFFF7BAFF84F3118823 +:10206000F9E70000034A516853685B1A9842FBD8AD +:10207000704700BF001000E08260022202827047B9 +:102080008368A3F17C0243F80C2C026943F83C2CD2 +:10209000426943F8382C074A43F81C2CC268A3F164 +:1020A000180043F8102C022203F8082C002203F831 +:1020B000072C7047E503000810B5202383F311882F +:1020C000FFF7DEFF00210446FFF746FF002383F3FE +:1020D0001188204610BD0000024B1B6958610F207B +:1020E000FFF70EBF38280020202383F31188FFF765 +:1020F000F3BF000008B50146202383F311880820B0 +:10210000FFF70CFF002383F3118808BD49B1064B8C +:1021100042681B6918605A60136043600420FFF72F +:10212000FDBE4FF0FF30704738280020036898420A +:1021300006D01A680260506018465961FFF7A4BEC5 +:102140007047000038B504460D462068844200D12F +:1021500038BD036823605C604561FFF795FEF4E7D6 +:10216000054B4FF0FF3103F11402C3E905220022B1 +:10217000C3E90712704700BF3828002070B51C4E15 +:1021800005460C46C0E9032301F0B2FB334653F881 +:10219000142F9A420DD130620A2C2CBF00190A303C +:1021A0002A60C5E90124C6E90555BDE8704001F083 +:1021B00089BB316A431AE31838BF1C469368A342AF +:1021C00002D9081901F08EFB73699A6894420CD801 +:1021D0005A68AC602B606A6015609A685D60121B7B +:1021E0009A604FF0FF33F36170BDA41A1B68ECE7EF +:1021F0003828002038B51B4C636998420DD081689F +:10220000D0E9003213605A600022C2609A680A4422 +:102210009A604FF0FF33E36138BD03682246002126 +:1022200042F8143F93425A60C16003D1BDE8384080 +:1022300001F052BB9A688168256A0A449A6001F0ED +:1022400057FB6369411B9A688A42E5D9AB181D1A8E +:10225000206A092D98BF01F10A02BDE838401044F8 +:1022600001F040BB382800202DE9F041184C002730 +:1022700004F11406656901F03BFB236AAA68C11AE0 +:102280008A4215D81344D5F80C802362D5E9003270 +:1022900013605A606369EF60B34201D101F01CFB27 +:1022A00087F311882869C047202383F31188E1E769 +:1022B0006169B14209D013441B1ABDE8F0410A2BF1 +:1022C0002CBFC0180A3001F00DBBBDE8F08100BF83 +:1022D0003828002000207047FEE70000704700000B +:1022E0004FF0FF307047000002290CD0032904D0C2 +:1022F0000129074818BF00207047032A05D8054860 +:1023000000EBC2007047044870470020704700BFD0 +:10231000D44100083C2200208841000870B59AB0E2 +:1023200005460846144601A900F0C2F801A8FEF7C8 +:1023300085FD431C0022C6B25B001046C5E900348F +:1023400023700323023404F8013C01ABD1B2023400 +:102350008E4201D81AB070BD13F8011B013204F887 +:10236000010C04F8021CF1E708B5202383F311885F +:102370000348FFF767FA002383F3118808BD00BF05 +:10238000F029002090F8803003F01F02012A07D1C5 +:1023900090F881200B2A03D10023C0E91D3315E0FA +:1023A00003F06003202B08D1B0F884302BB990F8EB +:1023B0008120212A03D81F2A04D8FFF725BA222A10 +:1023C000EBD0FAE7034A426707228267C36701201E +:1023D000704700BF3322002007B5052917D8DFE872 +:1023E00001F0191603191920202383F31188104ACC +:1023F00001210190FFF7CEFA019802210D4AFFF763 +:10240000C9FA0D48FFF7EAF9002383F3118803B0F6 +:102410005DF804FB202383F311880748FFF7B4F924 +:10242000F2E7202383F311880348FFF7CBF9EBE7AA +:10243000284100084C410008F029002038B50C4D17 +:102440000C4C2A460C4904F10800FFF767FF05F120 +:10245000CA0204F110000949FFF760FF05F5CA72CE +:1024600004F118000649BDE83840FFF757BF00BF28 +:10247000C84200203C220020084100081241000808 +:102480001D41000870B5044608460D46FEF7D6FC0F +:10249000C6B22046013403780BB9184670BD3246E7 +:1024A0002946FEF7B7FC0028F3D10120F6E700002B +:1024B0002DE9F84F05460C46FEF7C0FC2C49C6B284 +:1024C0002846FFF7DFFF08B10536F6B2294928464E +:1024D000FFF7D8FF08B11036F6B2632E0DD8DFF83B +:1024E0009080DFF89090244FDFF894A0DFF894B04C +:1024F0002E7846B92670BDE8F88F29462046BDE8FB +:10250000F84F01F099BD252E2ED1072241462846CD +:10251000FEF780FC70B9DBF8003007350C3444F866 +:102520000C3CDBF8043044F8083CDBF8083044F895 +:10253000043CDDE7082249462846FEF76BFC98B9C3 +:10254000A21C0E4B197802320909C95D02F8041C5D +:1025500013F8011B01F00F015345C95D02F8031C7C +:10256000F0D118340835C3E7013504F8016BBFE733 +:10257000F44100081D4100080942000800E8F11F6D +:102580000CE8F11FFC410008BFF34F8F044B1A69A0 +:102590005107FCD1D3F810215207F8D1704700BF82 +:1025A0000020005208B50D4B1B78ABB9FFF7ECFFCC +:1025B0000B4BDA68D10704D50A4A5A6002F1883217 +:1025C0005A60D3F80C21D20706D5064AC3F8042175 +:1025D00002F18832C3F8042108BD00BF264500205F +:1025E000002000522301674508B5114B1B78F3B951 +:1025F000104B1A69510703D5DA6842F04002DA60DD +:10260000D3F81021520705D5D3F80C2142F040022F +:10261000C3F80C21FFF7B8FF064BDA6842F001025D +:10262000DA60D3F80C2142F00102C3F80C2108BD96 +:1026300026450020002000520F289ABF00F5806038 +:1026400040040020704700004FF400307047000045 +:10265000102070470F2808B50BD8FFF7EDFF00F5E5 +:1026600000330268013204D104308342F9D10120E1 +:1026700008BD0020FCE700000F2870B5054645D8CE +:10268000FFF7D6FC224CFFF77FFF0646FFF78AFFD5 +:102690004FF0FF33072D6361C4F8143120D8236154 +:1026A000FFF772FF2B0243F02403E360E36843F07B +:1026B0008003E36023695A07FCD42846FFF764FFD0 +:1026C0004FF40031FFF7B8FF00F002F93046FFF792 +:1026D0008BFFFFF7B7FC2846BDE87040FFF7BABF95 +:1026E000C4F81031FFF750FFA5F108031B0243F0B7 +:1026F0002403C4F80C31D4F80C3143F08003C4F83F +:102700000C31D4F810315B07FBD4D6E7002070BD44 +:10271000002000522DE9F84F40EA020305460C461E +:102720001746D80602D00020BDE8F88F27F01F0713 +:10273000DFF8D4B0FFF736FF2744BC4203D10120B5 +:10274000FFF752FFF0E720222946204601F064FC03 +:1027500010B920352034F0E72B4605F120021E6821 +:10276000711CE0D104339A42F9D1FFF761FC05F105 +:102770007843234AB3F5801F224B28BF9A4603F1C2 +:10278000040338BF9046A2F1080228BF9846A3F17F +:1027900008033ABF9146DA469946FFF7F5FEC8F8B6 +:1027A0000060A5EB040CD9F8002004F11C0142F0F4 +:1027B0000202C9F80020221FDAF8006016F00506B0 +:1027C000FAD152F8043F8A424CF80230F4D1BFF3F8 +:1027D0004F8FFFF7D9FE4FF0FF32C8F80020D9F82D +:1027E000002022F00202C9F80020FFF72BFC202273 +:1027F0002146284601F010FC0028AAD030469FE769 +:1028000014200052102100521020005210B5084C24 +:10281000237828B11BB9FFF7C5FE0123237010BD33 +:10282000002BFCD02070BDE81040FFF7DDBE00BFDC +:10283000264500200244074BD2B210B5904200D189 +:1028400010BD441C00B253F8200041F8040BE0B264 +:10285000F4E700BF504000580E4B30B51C6F240405 +:1028600005D41C6F1C671C6F44F400441C670A4CA1 +:1028700002442368D2B243F480732360074B904232 +:1028800000D130BD441C51F8045B00B243F8205025 +:10289000E0B2F4E7004402580048025850400058A3 +:1028A00007B5012201A90020FFF7C4FF019803B07A +:1028B0005DF804FB13B50446FFF7F2FFA04205D014 +:1028C000012201A900200194FFF7C6FF02B010BD4C +:1028D0000144BFF34F8F064B884204D3BFF34F8FA1 +:1028E000BFF36F8F7047C3F85C022030F4E700BF7E +:1028F00000ED00E0034B1A681AB9034AD2F8D0245D +:102900001A607047284500200040025808B5FFF7BC +:10291000F1FF024B1868C0F3806008BD2845002015 +:10292000EFF30983054968334A6B22F001024A63D9 +:1029300083F30988002383F31188704700EF00E0D8 +:10294000202080F3118862B60D4B0E4AD96821F41D +:10295000E0610904090C0A430B49DA60D3F8FC2052 +:1029600042F08072C3F8FC20084AC2F8B01F116818 +:1029700041F0010111601022DA7783F822007047DC +:1029800000ED00E00003FA0555CEACC5001000E0F4 +:10299000202310B583F311880E4B5B6813F400639A +:1029A00014D0F1EE103AEFF309844FF08073683CD5 +:1029B000E361094BDB6B236684F30988FFF7E8FAD0 +:1029C00010B1064BA36110BD054BFBE783F31188E3 +:1029D000F9E700BF00ED00E000EF00E0F7030008BA +:1029E000FA03000870B5BFF34F8FBFF36F8F1A4A19 +:1029F0000021C2F85012BFF34F8FBFF36F8F53699E +:102A000043F400335361BFF34F8FBFF36F8FC2F8AE +:102A10008410BFF34F8FD2F8803043F6E074C3F3D5 +:102A2000C900C3F34E335B0103EA0406014646EADC +:102A300081750139C2F86052F9D2203B13F1200FA1 +:102A4000F2D1BFF34F8F536943F480335361BFF327 +:102A50004F8FBFF36F8F70BD00ED00E0FEE7000009 +:102A60000A4B0B480B4A90420BD30B4BC11EDA1C8E +:102A7000121A22F003028B4238BF00220021FEF717 +:102A8000E5B953F8041B40F8041BECE7EC430008DD +:102A9000FC460020FC460020FC4600207047000059 +:102AA00070B5D0E9244300224FF0FF359E6804EB57 +:102AB00042135101D3F80009002805DAD3F80009C0 +:102AC00040F08040C3F80009D3F8000B002805DA75 +:102AD000D3F8000B40F08040C3F8000B01326318BC +:102AE0009642C3F80859C3F8085BE0D24FF00113CF +:102AF000C4F81C3870BD000000EB8103D3F80CC093 +:102B00002DE9F043DCF814204E1CD0F89050D2F898 +:102B100000E005EB063605EB4118506870450AD316 +:102B20000122D5F8343802FA01F123EA0101C5F88F +:102B30003418BDE8F083AEEB0003BCF81040A342AC +:102B400028BF2346D8F81849A4B2B3EB840FF0D8B5 +:102B50009468A4F1040959F8047F3760A4EB0907CD +:102B60001F44042FF7D81C44034494605360D4E7F7 +:102B7000890141F02001016103699B06FCD4122008 +:102B8000FFF770BA10B50A4C2046FEF7E1FE094B7C +:102B9000C4F89030084BC4F89430084C2046FEF737 +:102BA000D7FE074BC4F89030064BC4F8943010BDE4 +:102BB0002C4500200000084040420008C845002085 +:102BC000000004404C42000870B503780546012B14 +:102BD0005DD1494BD0F89040984259D1474B0E21D6 +:102BE0006520D3F8D82042F00062C3F8D820D3F88B +:102BF000002142F00062C3F80021D3F80021D3F88D +:102C0000802042F00062C3F88020D3F8802022F0B8 +:102C10000062C3F88020D3F8803000F071FC384B9C +:102C2000E360384BC4F800380023D5F89060C4F84E +:102C3000003EC02323604FF40413A3633369002BC9 +:102C4000FCDA01230C203361FFF70CFA3369DB0750 +:102C5000FCD41220FFF706FA3369002BFCDA0026B9 +:102C60002846A660FFF71CFF6B68C4F81068DB6895 +:102C7000C4F81468C4F81C68002B3AD1224BA36135 +:102C80004FF0FF336361A36843F00103A36070BD9D +:102C90001E4B9842C8D1194B0E214D20D3F8D82095 +:102CA00042F00072C3F8D820D3F8002142F000723D +:102CB000C3F80021D3F80021D3F8802042F000723D +:102CC000C3F88020D3F8802022F00072C3F880205F +:102CD000D3F88020D3F8D82022F08062C3F8D8201F +:102CE000D3F8002122F08062C3F80021D3F800312C +:102CF00093E7074BC3E700BF2C4500200044025870 +:102D00004014004003002002003C30C0C8450020B1 +:102D1000083C30C0F8B5D0F89040054600214FF08F +:102D200000662046FFF724FFD5F8941000234FF0EB +:102D300001128F684FF0FF30C4F83438C4F81C28F3 +:102D400004EB431201339F42C2F80069C2F8006BE2 +:102D5000C2F80809C2F8080BF2D20B68D5F8902027 +:102D6000C5F89830636210231361166916F01006D7 +:102D7000FBD11220FFF776F9D4F8003823F4FE6374 +:102D8000C4F80038A36943F4402343F01003A3615F +:102D90000923C4F81038C4F814380B4BEB604FF01B +:102DA000C043C4F8103B094BC4F8003BC4F8106999 +:102DB000C4F80039D5F8983003F1100243F48013B9 +:102DC000C5F89820A362F8BD1C420008408000109E +:102DD000D0F8902090F88A10D2F8003823F4FE63DF +:102DE00043EA0113C2F80038704700002DE9F843A8 +:102DF00000EB8103D0F890500C468046DA680FFA59 +:102E000081F94801166806F00306731E022B05EBD4 +:102E100041134FF0000194BFB604384EC3F8101BA5 +:102E20004FF0010104F1100398BF06F1805601FA3A +:102E300003F3916998BF06F5004600293AD0578AF6 +:102E400004F15801374349016F50D5F81C180B4362 +:102E50000021C5F81C382B180127C3F81019A7400A +:102E60005369611E9BB3138A928B9B08012A88BF0A +:102E70005343D8F89820981842EA034301F14002DE +:102E80002146C8F89800284605EB82025360FFF7F8 +:102E90006FFE08EB8900C3681B8A43EA84534834F9 +:102EA0001E4364012E51D5F81C381F43C5F81C7809 +:102EB000BDE8F88305EB4917D7F8001B21F4004162 +:102EC000C7F8001BD5F81C1821EA0303C0E704F17A +:102ED0003F030B4A2846214605EB83035A60FFF760 +:102EE00047FE05EB4910D0F8003923F40043C0F841 +:102EF0000039D5F81C3823EA0707D7E7008000100F +:102F000000040002D0F894201268C0F89820FFF75F +:102F1000C7BD00005831D0F8903049015B5813F418 +:102F2000004004D013F4001F0CBF022001207047A2 +:102F30004831D0F8903049015B5813F4004004D078 +:102F400013F4001F0CBF02200120704700EB810129 +:102F5000CB68196A0B6813604B68536070470000B8 +:102F600000EB810330B5DD68AA691368D36019B935 +:102F7000402B84BF402313606B8A1468D0F89020E4 +:102F80001C4402EB4110013C09B2B4FBF3F463436F +:102F9000033323F0030343EAC44343F0C043C0F8C0 +:102FA000103B2B6803F00303012B0ED1D2F8083835 +:102FB00002EB411013F4807FD0F8003B14BF43F0C4 +:102FC000805343F00053C0F8003B02EB4112D2F8AB +:102FD000003B43F00443C2F8003B30BD2DE9F04113 +:102FE000D0F8906005460C4606EB4113D3F8087BF9 +:102FF0003A07C3F8087B08D5D6F814381B0704D560 +:1030000000EB8103DB685B689847FA071FD5D6F8A9 +:103010001438DB071BD505EB8403D968CCB98B6961 +:10302000488A5A68B2FBF0F600FB16228AB9186883 +:10303000DA6890420DD2121AC3E90024202383F3E8 +:10304000118821462846FFF78BFF84F31188BDE8DD +:10305000F081012303FA04F26B8923EA02036B81F6 +:10306000CB68002BF3D021462846BDE8F041184735 +:1030700000EB81034A0170B5DD68D0F890306C69CF +:103080002668E66056BB1A444FF40020C2F81009C7 +:103090002A6802F00302012A0AB20ED1D3F8080806 +:1030A00003EB421410F4807FD4F8000914BF40F001 +:1030B000805040F00050C4F8000903EB4212D2F8EF +:1030C000000940F00440C2F800090122D3F8340896 +:1030D00002FA01F10143C3F8341870BD19B9402E4A +:1030E00084BF4020206020681A442E8A8419013C45 +:1030F000B4FBF6F440EAC44040F00050C6E70000DC +:103100002DE9F041D0F8906004460D4606EB4113DE +:10311000D3F80879C3F80879FB071CD5D6F810381E +:10312000DA0718D500EB8103D3F80CC0DCF81430B3 +:10313000D3F800E0DA6896451BD2A2EB0E024FF0FE +:1031400000081A60C3F80480202383F31188FFF776 +:103150008FFF88F311883B0618D50123D6F8342851 +:10316000AB40134212D029462046BDE8F041FFF79C +:10317000C3BC012303FA01F2038923EA020303819A +:10318000DCF80830002BE6D09847E4E7BDE8F08192 +:103190002DE9F84FD0F8905004466E69AB691E4097 +:1031A00016F480586E6103D0BDE8F84FFEF740BCBE +:1031B000002E12DAD5F8003E9F0705D0D5F8003E64 +:1031C00023F00303C5F8003ED5F80438204623F069 +:1031D0000103C5F80438FEF757FC300505D5204635 +:1031E000FFF75EFC2046FEF73FFCB1040CD5D5F896 +:1031F000083813F0060FEB6823F470530CBF43F448 +:10320000105343F4A053EB60320704D56368DB68C6 +:103210000BB120469847F30200F1BA80B70226D5D9 +:10322000D4F8909000274FF0010A09EB4712D2F82A +:10323000003B03F44023B3F5802F11D1D2F8003BBB +:10324000002B0DDA62890AFA07F322EA030363818D +:1032500004EB8703DB68DB6813B1394620469847E7 +:103260000137D4F89430FFB29B689F42DDD9F00655 +:1032700019D5D4F89000026AC2F30A1702F00F03BE +:1032800002F4F012B2F5802F00F0CC80B2F5402F9E +:1032900009D104EB8303002200F58050DB681B6A30 +:1032A000974240F0B2803003D5F8185835D5E9037D +:1032B00003D500212046FFF791FEAA0303D5012183 +:1032C0002046FFF78BFE6B0303D502212046FFF754 +:1032D00085FE2F0303D503212046FFF77FFEE8027A +:1032E00003D504212046FFF779FEA90203D5052165 +:1032F0002046FFF773FE6A0203D506212046FFF73A +:103300006DFE2B0203D507212046FFF767FEEF0174 +:1033100003D508212046FFF761FE700340F1A98024 +:10332000E90703D500212046FFF7EAFEAA0703D5E7 +:1033300001212046FFF7E4FE6B0703D5022120465A +:10334000FFF7DEFE2F0703D503212046FFF7D8FE47 +:10335000EE0603D504212046FFF7D2FEA80603D5CA +:1033600005212046FFF7CCFE690603D5062120463D +:10337000FFF7C6FE2A0603D507212046FFF7C0FE49 +:10338000EB0576D520460821BDE8F84FFFF7B8BE1B +:10339000D4F8909000274FF0010AD4F894305FFAE7 +:1033A00087FB9B689B453FF639AF09EB4B13D3F87E +:1033B000002902F44022B2F5802F24D1D3F800294D +:1033C000002A20DAD3F8002942F09042C3F80029FD +:1033D000D3F80029002AFBDB5946D4F89000FFF708 +:1033E000C7FB22890AFA0BF322EA0303238104EBC9 +:1033F0008B03DB689B6813B15946204698475946B2 +:103400002046FFF779FB0137C7E7910701D1D0F8D4 +:103410000080072A02F101029CBF03F8018B4FEAEA +:1034200018283DE704EB830300F58050DA68D2F8F2 +:1034300018C0DCF80820DCE9001CA1EB0C0C002112 +:103440008F4208D1DB689B699A683A449A605A684F +:103450003A445A6027E711F0030F01D1D0F80080F9 +:103460008C4501F1010184BF02F8018B4FEA182855 +:10347000E6E7BDE8F88F000008B50348FFF788FECF +:10348000BDE80840FFF784BA2C45002008B5034882 +:10349000FFF77EFEBDE80840FFF77ABAC845002076 +:1034A000D0F8903003EB4111D1F8003B43F4001306 +:1034B000C1F8003B70470000D0F8903003EB411199 +:1034C000D1F8003943F40013C1F800397047000007 +:1034D000D0F8903003EB4111D1F8003B23F40013F6 +:1034E000C1F8003B70470000D0F8903003EB411169 +:1034F000D1F8003923F40013C1F8003970470000F7 +:10350000090100F16043012203F56143C9B283F868 +:10351000001300F01F039A4043099B0003F160432E +:1035200003F56143C3F880211A60704730B5043356 +:10353000039C0172002104FB0325C160C0E906530E +:10354000049B0363059BC0E90000C0E90422C0E9B5 +:103550000842C0E90A11436330BD00000022416AFD +:10356000C260C0E90411C0E90A226FF00101FEF750 +:10357000E9BD0000D0E90432934201D1C2680AB922 +:10358000181D704700207047036919600021C26848 +:103590000132C260C269134482699342036124BF4D +:1035A000436A0361FEF7C2BD38B504460D46E368C1 +:1035B0003BB162690020131D1268A3621344E362E9 +:1035C00007E0237A33B929462046FEF79FFD0028FD +:1035D000EDDA38BD6FF00100FBE70000C368C26997 +:1035E000013BC3604369134482699342436124BF32 +:1035F000436A436100238362036B03B1184770473A +:1036000070B52023044683F31188866A3EB9FFF71C +:10361000CBFF054618B186F31188284670BDA36A12 +:10362000E26A13F8015B9342A36202D32046FFF7DC +:10363000D5FF002383F31188EFE700002DE9F84F51 +:1036400004460E46174698464FF0200989F3118824 +:103650000025AA46D4F828B0BBF1000F09D1414695 +:103660002046FFF7A1FF20B18BF311882846BDE863 +:10367000F88FD4E90A12A7EB050B521A934528BF1D +:103680009346BBF1400F1BD9334601F1400251F87C +:10369000040B914243F8040BF9D1A36A403640353C +:1036A0004033A362D4E90A239A4202D32046FFF7AB +:1036B00095FF8AF31188BD42D8D289F31188C9E7F2 +:1036C00030465A46FDF79CFBA36A5E445D445B446A +:1036D000A362E7E710B5029C0433017204FB0321E7 +:1036E000C460C0E906130023C0E90A33039B0363E7 +:1036F000049BC0E90000C0E90422C0E9084243631A +:1037000010BD0000026A6FF00101C260426AC0E9A8 +:1037100004220022C0E90A22FEF714BDD0E90423E6 +:103720009A4201D1C26822B9184650F8043B0B6096 +:103730007047002070470000C3680021C269013350 +:10374000C3604369134482699342436124BF436A5F +:103750004361FEF7EBBC000038B504460D46E36854 +:103760003BB1236900201A1DA262E2691344E3629F +:1037700007E0237A33B929462046FEF7C7FC002824 +:10378000EDDA38BD6FF00100FBE700000369196056 +:10379000C268013AC260C2691344826993420361FC +:1037A00024BF436A036100238362036B03B118479C +:1037B0007047000070B520230D460446114683F380 +:1037C0001188866A2EB9FFF7C7FF10B186F31188FA +:1037D00070BDA36A1D70A36AE26A01339342A362BB +:1037E00004D3E16920460439FFF7D0FF002080F3BD +:1037F0001188EDE72DE9F84F04460D4690469946AD +:103800004FF0200A8AF311880026B346A76A4FB901 +:1038100049462046FFF7A0FF20B187F311883046C4 +:10382000BDE8F88FD4E90A073A1AA8EB06079742D1 +:1038300028BF1746402F1BD905F1400355F8042B2C +:103840009D4240F8042BF9D1A36A40364033A3626D +:10385000D4E90A239A4204D3E16920460439FFF7E8 +:1038600095FF8BF311884645D9D28AF31188CDE7AD +:1038700029463A46FDF7C4FAA36A3D443E443B4418 +:10388000A362E5E7D0E904239A4217D1C3689BB14C +:10389000836A8BB1043B9B1A0ED01360C368013B53 +:1038A000C360C3691A4483699A42026124BF436AB0 +:1038B0000361002383620123184670470023FBE75E +:1038C00000F0DAB8034B002258631A610222DA6072 +:1038D000704700BF000C0040014B0022DA607047C7 +:1038E000000C0040014B5863704700BF000C0040C3 +:1038F000014B586A704700BF000C00404B684360A2 +:103900008B688360CB68C3600B6943614B6903625A +:103910008B6943620B6803607047000008B53C4B3D +:1039200040F2FF713B48D3F888200A43C3F888204F +:10393000D3F8882022F4FF6222F00702C3F888201F +:10394000D3F88820D3F8E0200A43C3F8E020D3F866 +:1039500008210A43C3F808212F4AD3F80831114639 +:10396000FFF7CCFF00F5806002F11C01FFF7C6FFF6 +:1039700000F5806002F13801FFF7C0FF00F58060BC +:1039800002F15401FFF7BAFF00F5806002F1700107 +:10399000FFF7B4FF00F5806002F18C01FFF7AEFF86 +:1039A00000F5806002F1A801FFF7A8FF00F5806034 +:1039B00002F1C401FFF7A2FF00F5806002F1E0010F +:1039C000FFF79CFF00F5806002F1FC01FFF796FF16 +:1039D00002F58C7100F58060FFF790FF00F000F9B0 +:1039E0000E4BD3F8902242F00102C3F89022D3F894 +:1039F000942242F00102C3F894220522C3F89820D1 +:103A00004FF06052C3F89C20054AC3F8A02008BDBF +:103A100000440258000002585842000800ED00E03F +:103A20001F00080308B500F0D7FAFEF7DFFA0F4BC6 +:103A3000D3F8DC2042F04002C3F8DC20D3F80421A4 +:103A400022F04002C3F80421D3F80431084B1A686D +:103A500042F008021A601A6842F004021A60FEF787 +:103A600049FFBDE80840FEF7E9BC00BF004402582A +:103A70000018024870470000114BD3F8E82042F0CC +:103A80000802C3F8E820D3F8102142F00802C3F876 +:103A900010210C4AD3F81031D36B43F00803D363E1 +:103AA000C722094B9A624FF0FF32DA6200229A6114 +:103AB0005A63DA605A6001225A611A60704700BF87 +:103AC000004402580010005C000C0040094A08B590 +:103AD0001169D3680B40D9B29B076FEA01011161EC +:103AE00007D5202383F31188FEF7A0FA002383F380 +:103AF000118808BD000C0040384B4FF0FF31D3F85F +:103B00008020C3F88010D3F880200022C3F88020E2 +:103B1000D3F88000D3F88400C3F88410D3F884006D +:103B2000C3F88420D3F88400D86F40F0FF4040F4FD +:103B3000FF0040F43F5040F03F00D867D86F20F0BE +:103B4000FF4020F4FF0020F43F5020F03F00D867F2 +:103B5000D86FD3F888006FEA40506FEA5050C3F82E +:103B60008800D3F88800C0F30A00C3F88800D3F8AF +:103B70008800D3F89000C3F89010D3F89000C3F8F1 +:103B80009020D3F89000D3F89400C3F89410D3F8A1 +:103B90009400C3F89420D3F89400D3F89800C3F8A5 +:103BA0009810D3F89800C3F89820D3F89800D3F869 +:103BB0008C00C3F88C10D3F88C00C3F88C20D3F899 +:103BC0008C00D3F89C00C3F89C10D3F89C10C3F869 +:103BD0009C20D3F89C3000F0D3B900BF00440258B9 +:103BE000614B0122C3F80821604BD3F8F42042F066 +:103BF0000202C3F8F420D3F81C2142F00202C3F8F9 +:103C00001C210222D3F81C31594BDA605A68910406 +:103C1000FCD5584A1A6001229A60574ADA6000229D +:103C20001A614FF440429A61514B9A699204FCD553 +:103C30001A6842F480721A604C4B1A6F12F4407F7B +:103C400004D04FF480321A6700221A671A6842F0D3 +:103C500001021A60454B1A685007FCD500221A6110 +:103C60001A6912F03802FBD1012119604FF080412E +:103C700059605A67414ADA62414A1A611A6842F445 +:103C800080321A60394B1A689103FCD51A6842F4E5 +:103C900080521A601A689204FCD53A4A3A499A62EC +:103CA00000225A6319633949DA6399635A64384ABE +:103CB0001A64384ADA621A6842F0A8521A602B4B2A +:103CC0001A6802F02852B2F1285FF9D148229A61AD +:103CD0004FF48862DA6140221A622F4ADA644FF0A8 +:103CE00080521A652D4A5A652D4A9A6532232D4A0B +:103CF0001360136803F00F03022BFAD11B4B1A69F0 +:103D000042F003021A611A6902F03802182AFAD145 +:103D1000D3F8DC2042F00052C3F8DC20D3F80421B1 +:103D200042F00052C3F80421D3F80421D3F8DC2078 +:103D300042F08042C3F8DC20D3F8042142F08042F4 +:103D4000C3F80421D3F80421D3F8DC2042F0004268 +:103D5000C3F8DC20D3F8042142F00042C3F8042168 +:103D6000D3F80431704700BF00800051004402586E +:103D70000048025800C000F0020000010000FF01EE +:103D80000088900832206000630209011D020400CF +:103D900047040508FD0BFF01200000200010E00093 +:103DA00000010100002000524FF0B04208B5D2F8E7 +:103DB000883003F00103C2F8883023B1044A136845 +:103DC0000BB150689847BDE80840FEF7E1BD00BF61 +:103DD0007C4600204FF0B04208B5D2F8883003F09E +:103DE0000203C2F8883023B1044A93680BB1D0684B +:103DF0009847BDE80840FEF7CBBD00BF7C460020D9 +:103E00004FF0B04208B5D2F8883003F00403C2F88E +:103E1000883023B1044A13690BB150699847BDE853 +:103E20000840FEF7B5BD00BF7C4600204FF0B04211 +:103E300008B5D2F8883003F00803C2F8883023B1FF +:103E4000044A93690BB1D0699847BDE80840FEF772 +:103E50009FBD00BF7C4600204FF0B04208B5D2F8AD +:103E6000883003F01003C2F8883023B1044A136A83 +:103E70000BB1506A9847BDE80840FEF789BD00BF06 +:103E80007C4600204FF0B04310B5D3F8884004F4CE +:103E90007872C3F88820A30604D5124A936A0BB13E +:103EA000D06A9847600604D50E4A136B0BB1506B6D +:103EB0009847210604D50B4A936B0BB1D06B9847FA +:103EC000E20504D5074A136C0BB1506C9847A30563 +:103ED00004D5044A936C0BB1D06C9847BDE81040F0 +:103EE000FEF756BD7C4600204FF0B04310B5D3F826 +:103EF000884004F47C42C3F88820620504D5164A41 +:103F0000136D0BB1506D9847230504D5124A936D7C +:103F10000BB1D06D9847E00404D50F4A136E0BB176 +:103F2000506E9847A10404D50B4A936E0BB1D06E26 +:103F30009847620404D5084A136F0BB1506F984735 +:103F4000230404D5044A936F0BB1D06F9847BDE8A2 +:103F50001040FEF71DBD00BF7C46002008B5034899 +:103F6000FDF708F9BDE80840FEF712BDCC2300209C +:103F700008B5FFF7ABFDBDE80840FEF709BD00003E +:103F8000062108B50846FFF7BBFA06210720FFF710 +:103F9000B7FA06210820FFF7B3FA06210920FFF738 +:103FA000AFFA06210A20FFF7ABFA06211720FFF728 +:103FB000A7FA06212820FFF7A3FA09217A20FFF7A4 +:103FC0009FFA07213220FFF79BFA0C215220BDE80F +:103FD0000840FFF795BA000008B5FFF78DFD00F027 +:103FE0000DF8FDF7D9FAFDF7B1FCFDF783FBFFF7FC +:103FF00041FDBDE80840FFF763BC00000023054A0F +:1040000019460133102BC2E9001102F10802F8D160 +:10401000704700BF7C46002010B501390244904231 +:1040200001D1002005E0037811F8014FA34201D02F +:10403000181B10BD0130F2E7034611F8012B03F8FD +:10404000012B002AF9D1704753544D333248373F82 +:104050003F3F0053544D3332483734332F373533D5 +:1040600000000000F0290020CC2300200096000072 +:104070000000000000000000000000000000000040 +:104080000000000000000000611500084D15000848 +:104090008915000875150008811500086D150008C0 +:1040A0005915000845150008951500080000000086 +:1040B000711600085D16000899160008851600089C +:1040C000911600087D1600086916000855160008AC +:1040D000A51600080000000001000000000000001C +:1040E0006D61696E0000000069646C65000000008D +:1040F000E840000878280020F02900200100000096 +:10410000E91F0008000000004172647550696C6F7F +:10411000740025424F415244252D424C0025534501 +:104120005249414C25000000020000000000000040 +:104130009118000801190008400040009842002032 +:10414000A842002002000000000000000300000060 +:1041500000000000491900080000000010000000E5 +:10416000B842002000000000010000000000000034 +:104170002C45002001010200D9230008E922000893 +:1041800085230008692300084300000090410008CF +:1041900009024300020100C03209040000010202CA +:1041A000010005240010010524010001042402027D +:1041B0000524060001070582030800FF0904010029 +:1041C000020A000000070501024000000705810205 +:1041D0004000000012000000DC4100081201100144 +:1041E00002000040091241570002010203010000D1 +:1041F0000403090425424F41524425006C756D6942 +:104200006E6F757362656535003031323334353623 +:104210003738394142434445460000000000000061 +:104220009D1A0008551D0008011E000840004000AE +:10423000644600206446002001000000744600200F +:1042400080000000400100000800000000010000A4 +:1042500000040000080000000000802A00000000A8 +:10426000AAAAAAAA00000024FFFF00000000000084 +:1042700000A00A000001400000000000AAAAAAAAAB +:1042800000010000FFFF000000000000000000002F +:104290001000004000000000AAAAAAAA10000040D6 +:1042A000FFFF0000000000000000000000400000D0 +:1042B00000000000AAAAAAAA00400000FFFF000018 +:1042C000000000000000000000800240000000002C +:1042D000AAAAAAAA00400140FFFF00000000007047 +:1042E000070000000000000000000000AAAAAAAA1F +:1042F00000000000FFFF00000000000000000000C0 :104300000000000000000000AAAAAAAA0000000005 :10431000FFFF00000000000000000000000000009F :1043200000000000AAAAAAAA00000000FFFF0000E7 @@ -1080,10 +1080,10 @@ :1043600000000000FFFF000000000000000000004F :104370000000000000000000AAAAAAAA0000000095 :10438000FFFF00000000000000000000000000002F -:1043900000000000AAAAAAAA00000000FFFF000077 -:1043A0000000000000000000FF000000000000000E -:1043B0006C4000083F0000005004000077400008F7 -:1043C0003F0000000096000000000800040000000C -:1043D0000C42000800000000000000000000000087 +:10439000050400000000000000001E0000000000F6 +:1043A000FF00000000000000484000083F0000003F +:1043B00050040000534000083F0000000096000039 +:1043C0000000080096000000000800000400000043 +:1043D000F0410008000000000000000000000000A4 :0C43E000000000000000000000000000D1 :00000001FF diff --git a/Tools/bootloaders/mRo-M10095_bl.bin b/Tools/bootloaders/mRo-M10095_bl.bin index e1756e23407..6a6d9fca48c 100755 Binary files a/Tools/bootloaders/mRo-M10095_bl.bin and b/Tools/bootloaders/mRo-M10095_bl.bin differ diff --git a/Tools/bootloaders/mRo-M10095_bl.elf b/Tools/bootloaders/mRo-M10095_bl.elf index 24bde255159..2a0813d9b78 100755 Binary files a/Tools/bootloaders/mRo-M10095_bl.elf and b/Tools/bootloaders/mRo-M10095_bl.elf differ diff --git a/Tools/bootloaders/mRo-M10095_bl.hex b/Tools/bootloaders/mRo-M10095_bl.hex index d2a0513c15a..d7264495c62 100644 --- a/Tools/bootloaders/mRo-M10095_bl.hex +++ b/Tools/bootloaders/mRo-M10095_bl.hex @@ -1,19 +1,19 @@ :020000040800F2 -:1000000000070020F5040008ED280008F12800088A -:1000100049290008F12800081D290008F7040008F4 -:10002000F7040008F7040008F70400081D3700086B +:1000000000070020F5040008292C0008A92B00088F +:10001000012C0008A92B0008D52B0008F7040008C4 +:10002000F7040008F7040008F70400087D3A000808 :10003000F7040008F7040008F7040008F7040008B4 :10004000F7040008F7040008F7040008F7040008A4 -:10005000F7040008F704000821490008494900088E -:100060007149000899490008C1490008F7040008CF +:10005000F7040008F7040008AD4C0008D54C000870 +:10006000FD4C0008254D00084D4D0008F704000820 :10007000F7040008F7040008F7040008F704000874 :10008000F7040008F7040008F7040008F704000864 -:10009000F70400085126000861260008E949000815 +:10009000F70400082528000835280008754D0008D9 :1000A000F7040008F7040008F7040008F704000844 -:1000B000D14A0008F7040008F7040008F704000814 +:1000B0005D4E0008F7040008F7040008F704000884 :1000C000F7040008F7040008F7040008F704000824 -:1000D000F7040008BD4A0008F7040008F704000808 -:1000E0004D4A0008F7040008F7040008F704000868 +:1000D000F7040008494E0008F7040008F704000878 +:1000E000D94D0008F7040008F7040008F7040008D9 :1000F000F7040008F7040008F7040008F7040008F4 :10010000F7040008F7040008F7040008F7040008E3 :10011000F7040008F7040008F7040008F7040008D3 @@ -29,7 +29,7 @@ :1001B000F7040008F7040008F7040008F704000833 :1001C000F7040008F7040008F7040008F704000823 :1001D000F7040008F7040008F7040008F704000813 -:1001E00031180008000000000000000000000000BE +:1001E000611800080000000000000000000000008E :1001F00053B94AB9002908BF00281CBF4FF0FF318E :100200004FF0FF3000F074B9ADF1080C6DE904CE89 :1002100000F006F8DDF804E0DDE9022304B07047E1 @@ -85,1192 +85,1251 @@ :1005300040F20000C0F2F0004EF68851CEF2000109 :100540000860BFF34F8FBFF36F8F4FF00000E1EEF5 :10055000100A4EF63C71CEF200010860062080F3CE -:100560001488BFF36F8F04F06DF804F049F804F0BD -:1005700093F84FF055301F491B4A91423CBF41F858 +:100560001488BFF36F8F04F033FA04F00FFA04F02D +:1005700059FA4FF055301F491B4A91423CBF41F890 :10058000040BFAE71C49194A91423CBF41F8040B9D :10059000FAE71A491A4A1B4B9A423EBF51F8040B1C :1005A00042F8040BF8E700201749184A91423CBF73 -:1005B00041F8040BFAE704F027F804F0B3F8144C00 +:1005B00041F8040BFAE704F0EDF904F079FA144C71 :1005C000144DAC4203DA54F8041B8847F9E700F0F5 :1005D00041F8114C114DAC4203DA54F8041B884722 -:1005E000F9E704F00FB80000000700200023002006 -:1005F000000000080001002000070020184F00083C -:10060000002300208823002088230020744F00202E +:1005E000F9E704F0D5B9000000070020002300203F +:1005F000000000080001002000070020B852000899 +:10060000002300208C23002090230020B84F0020DE :10061000E0010008E4010008E4010008E40100082A :100620002DE9F04F2DED108AC1F80CD0C3689D461E :10063000BDEC108ABDE8F08F002383F311882846B3 -:10064000A047002003F0E8FCFEE703F061FC00DFB8 -:10065000FEE70000F8B503F079FF074603F0CAFF94 -:10066000044688BB1D4B9F422ED001339F422ED0A3 -:100670001B4B27F0FF029A422CD1F8B200F022FD6A -:10068000264642F2107500F027FF00F021FD08B960 -:100690000646054634B1134B9F4203D003F0A2FF38 -:1006A00000252E46002003F05BFF0EB100F062F83B -:1006B00001F034FA00F032FF01F020F9284600F092 -:1006C000ADF800F057F8F9E726460025DBE70546C8 -:1006D0000126D8E706464FF47A75D4E7010007B043 -:1006E000000008B0263A09B008B501F0D9F8A0F129 -:1006F00020035842584108BD07B541F212030221B8 -:1007000001A8ADF8043001F0E9F803B05DF804FB8E -:1007100010B5202383F311881248C3680BB103F08E -:10072000F3FC114A0F4800234FF47A7103F0B0FC38 -:10073000002383F311880D4C236813B12368013B18 -:100740002360636813B16368013B6360084B1B78E7 -:1007500033B9636823B9022001F06EF93223636074 -:1007600010BD00BF8823002011070008A42400202A -:100770009C23002038B5234A234B1968013140D00F -:1007800004339342F9D1214C1F4DD4F80428AA42D6 -:1007900037D31F4B9B6803F1006303F5F0439A4284 -:1007A0002FD203F0F1FE03F003FF002001F0C0F8A8 -:1007B000184B0220187001F037F9174B9A6D002280 -:1007C0009A65996F9A67996FD96DDA65D96FDA670B -:1007D000D96F196E1A66D3F88010C3F88020D3F849 -:1007E000803072B64FF0E0232021C3F8085DD4F8C2 -:1007F0000038D4F8042881F311889D4683F30888D3 -:10080000104738BD20780008007800080070000804 -:10081000002300209C230020001002402DE9F04F0F -:1008200093B0A74B00902022FF210AA89D6801F0F9 -:100830001FF9A44A1378A3B9A3480121C36011701A -:10084000202383F31188C3680BB103F05DFC9F4A3A -:100850009D4800234FF47A7103F01AFC002383F3C0 -:100860001188009B9A4A03B113609A49009C0023A7 -:100870000B70536098469B461E469A46012001F035 -:10088000D3F824B1924B1B68002B00F0108200209B -:1008900001F006F80390039B002B01DA00F082FEC2 -:1008A000039B002BEDDB012001F0B6F8039B213BFD -:1008B000122BE3D801A252F823F000BF0909000867 -:1008C00031090008BF0900087D0800087D080008FC -:1008D0007D080008530A0008230C00083D0B00089F -:1008E0009F0B0008C70B0008ED0B00087D080008EF -:1008F000FF0B00087D080008710C0008770900084C -:100900007D080008B50C00080220FFF7EDFE002866 -:1009100040F0F781009B0221B8F1000F08BF1C4690 -:1009200005A841F21233ADF8143000F0D7FFA5E767 -:100930004FF47A7000F0B4FF071EEBDB0220FFF7E4 -:10094000D3FE0028E6D0013F042F00F2DC81DFE86F -:1009500007F0031D2023260005230593042105A885 -:1009600000F0BCFF012000FA07F747EA0B0B5FFA23 -:100970008BFB4FF0000A01F0C7F826B10BF00B0318 -:100980000B2B08BF0024FFF7B7FE77E74C48042184 -:10099000E6E751480421E3E750480421E0E74FF03F -:1009A0001C09484600F0C6FF09F10409059004211E -:1009B00005A800F093FFB9F12C0FF2D1D2E7002E79 -:1009C000A8D00BF00B030B2BA4D10220FFF78CFE59 -:1009D000074600289ED001203E4E00F0A9FF0220CD -:1009E000307001F021F84FF000085FFA88F94846AE -:1009F00000F0B0FF044690B1484600F0BBFF08F19C -:100A000001080028F1D1B846044641F21213022130 -:100A100005A8ADF814303E4600F060FF2EE7012334 -:100A20000220337000F0F8FF2546254B9B68AB424F -:100A300007D9284600F07EFF013040F06781043579 -:100A4000F3E7244B00251D70214BB8465D603E4600 -:100A500091E7002E3FF45EAF0BF00B030B2B7FF4FE -:100A600059AF1C4B0220187000F0DEFF322000F05E -:100A700017FFB0F10009FFF64DAF19F003077FF43F -:100A800049AF0F4A926809EB050393423FF642AF24 -:100A9000B9F5807F3FF73EAF114B0193B94521DD9A -:100AA0004FF47A7000F0FCFE0390039A002AFFF6E0 -:100AB00031AF019B039A03F8012B0137EDE700BF2B -:100AC00000230020A0240020882300201107000814 -:100AD000A42400209C2300200423002008230020BD -:100AE000A0230020C820FFF7FFFD074600283FF4A1 -:100AF00011AF1F2D11D8C5F120024A450AAB25F0D0 -:100B0000030028BF4A4683490192184400F09EFF23 -:100B1000019A8048FF2100F0ABFF4FEAA9037D490D -:100B20000193C9F38702284600F0AAFF0646002871 -:100B30003FF46BAF019B05EB83051CE70220FFF739 -:100B4000D3FD00283FF4E6AE00F030FF00283FF46C -:100B5000E1AE0027B946704B9B68BB4218D91F2FE6 -:100B600011D80A9B01330ED027F0030312AA1344B5 -:100B700053F8203C05934846042205A901F002FFE2 -:100B800004378146E7E7384600F0D4FE0590F2E7E7 -:100B9000CDF81490042105A800F0A0FEEBE6002398 -:100BA000642104A8049300F08FFE00287FF4B2AE05 -:100BB0000220FFF799FD00283FF4ACAE049800F046 -:100BC000EBFE0590E6E70023642104A8049300F0FF -:100BD0007BFE00287FF49EAE0220FFF785FD0028F3 -:100BE0003FF498AE049800F0D9FEEAE70220FFF740 -:100BF0007BFD00283FF48EAE00F0E8FEE1E7022026 -:100C0000FFF772FD00283FF485AE05A9142000F01F -:100C1000E3FE04210746049004A800F05FFE394675 -:100C2000B9E7322000F03CFE071EFFF673AEBB07AB -:100C30007FF470AE384A926807EB0A0393423FF69E -:100C400069AE0220FFF750FD00283FF463AE27F0A5 -:100C500003075744BA453FF48EAE504600F06AFE93 -:100C60000421059005A800F039FE0AF1040AF1E715 -:100C70004FF47A70FFF738FD00283FF44BAE00F0D8 -:100C800095FE002844D00A9B01330BD008220AA904 -:100C9000002000F0F5FE00283AD02022FF210AA80B -:100CA00000F0E6FEFFF728FD1C4803F0BBF913B087 -:100CB000BDE8F08F002E3FF42DAE0BF00B030B2B95 -:100CC0007FF428AE0023642105A8059300F0FCFD05 -:100CD000074600287FF41EAE0220FFF705FD81467F -:100CE00000283FF417AEFFF707FD41F2883003F00C -:100CF00099F9059800F01EFF4E4600F005FF3C46AE -:100D0000BCE5064637E64FF0000A03E6B8467CE647 -:100D100037467AE6A023002000230020A0860100A9 -:100D2000094A136849F2690099B21B0C00FB0133B0 -:100D30001360064B186844F2506182B2000C01FB4C -:100D40000200186080B27047102300200C2300209E -:100D500010B500211022044600F08AFE034B03CB9D -:100D6000206061601868A06010BD00BF9075FF1F13 -:100D70002DE9F043204DBBB001F000FEAB68C31A73 -:100D8000F92B32D906AFA8602B462822002138461D -:100D900002F08CFA05F10E0000F062FE0026044617 -:100DA0005FFA80F905F10E08F3B2F100994501F1FF -:100DB000280107D908EB06030822384602F076FA24 -:100DC0000136F1E708230122CDE9023205340B4B4D -:100DD0000193A4B230230093CDE9047404A3D3E9B2 -:100DE0000023297B064802F079F83BB0BDE8F08388 -:100DF00078F6339F93CACD8D68490020754900204D -:100E0000C434002070B50D4614461E4601F0FCFFA8 -:100E100050B9022E10D1012C0ED112A3D3E9002318 -:100E2000C5E90023012007E0282C10D005D8012CAB -:100E300009D0052C0FD0002070BD302CFBD10BA3A6 -:100E4000D3E90023ECE70BA3D3E90023E8E70BA3E6 -:100E5000D3E90023E4E70BA3D3E90023E0E700BFD5 -:100E6000AFF30080401DA12026812A0B78F6339F26 -:100E700093CACD8D9E6AC421818A46EE2641727244 -:100E8000DF25D7B7F017304A39059E5613B504460B -:100E90002346084620220021019002F007FA227919 -:100EA0000198032A234628BF032203F8042F202198 -:100EB000022202F0FBF962790198072A234628BF33 -:100EC000072203F8052F2221032202F0EFF9A2796D -:100ED0000198072A234628BF072203F8062F252159 -:100EE000032202F0E3F9019804F1080310222821FB -:100EF00002F0DCF9382002B010BD00002DE9F04FFF -:100F0000ADF5017D21AD0EAE40F2751280460F4663 -:100F100022A80021296000F0ABFD482200213046C4 -:100F200000F0A6FD01F02AFD564B4FF47A72B0FB9B -:100F3000F2F0186093E80700012386E807000DF13E -:100F40005A003382FFF704FF41F20413338407ABE6 -:100F500018464D4903F0A4FE182230642946304655 -:100F600086F83C20FFF792FF12AB044601460822A8 -:100F7000284602F09BF90822A1180DF149032846E2 -:100F800002F094F90DF14A03082204F110012846F9 -:100F900002F08CF913AB202204F11801284602F06C -:100FA00085F914AB402204F13801284602F07EF99D -:100FB00016AB082204F17801284602F077F90DF10A -:100FC0005903082204F18001284602F06FF904F168 -:100FD000880A0DF15A0904F5847B4B4651460822D4 -:100FE00028460AF1080A02F061F9D34509F101091E -:100FF000F3D11BAB08225946284602F057F904F5F5 -:1010000088744FF0000996F834304B450AD9B36B19 -:1010100021464B440822284602F048F9083409F1D9 -:101020000109F0E74FF0000996F83C304B4504EB1E -:10103000C90108D9336C08224B44284602F036F91E -:1010400009F10109F0E700230393BB7E0293073106 -:1010500007F119030193C1F3CF010123CDE9045135 -:101060000093F97E05A3D3E90023404601F036FF43 -:101070000DF5017DBDE8F08FAFF300809E6AC421BD -:10108000818A46EEAC240020D04C000810B50A4BF3 -:101090000A4A1A6003F5805393F840203AB9DC6B92 -:1010A0002CB1204601F0E8FA204603F063FDBDE8CC -:1010B0001040034801F0E0BAE8340020B04D0008C9 -:1010C00010450020014B1870704700BFB824002065 -:1010D000F0B5334B1C7B85B034B1324B0E221A81F4 -:1010E0000024204605B0F0BD2F4A1068516802ABBD -:1010F00003C308232D492E480DEB030203F062FDC4 -:10110000054630B9274B2B480A221A8101F0B0FA64 -:10111000E6E70169B1F5623F06D9224B26480B226A -:101120001A8101F0A5FADCE7438B40F211429342A9 -:1011300007D01C490C2008811946204801F098FA74 -:10114000CFE71F4A024402F11003994204D2154B23 -:101150001C4810221A81E4E710398E1A20461449DF -:1011600001F010FC3246074605F11801204601F057 -:1011700009FCAB689F4202D1EB6898420AD0094B48 -:101180000D221A810090D5E902123B460E4801F06B -:101190006FFAA5E70D4801F06BFA0124A1E700BF43 -:1011A00068490020AC2400207D4D0008DC87030046 -:1011B00000780008EC4C0008F84C00080A4D0008C4 -:1011C0000888FFF7284D0008454D00086E4D0008BF -:1011D0002DE9F04FADB006AF80460C4601F014FE8D -:1011E000054600285AD1237E022B1BD1E38A012B0E -:1011F00018D101F0C3FB0646FFF792FD03464FF4FA -:10120000C870DFF8D092B3FBF0F206F5167602FB59 -:10121000103316FA83F3C9F80030E37E33B9A84BD4 -:1012200000221A709C37BD46BDE8F08FA38AEEB24B -:10123000013BB34205F101050BD93B1D1E44E900FA -:1012400000960023082201F0F801204601F0F2FE8A -:10125000ECE707F11400FFF77BFD324607F11401BC -:10126000381D03F09FFC0028D9D10F2E08D8944BCD -:101270001E70D9F80030A3F51673C9F80030D1E715 -:10128000FB1CF8700146009307220346204601F03C -:10129000D1FEF978404601F0AFFDC3E7E38A282B81 -:1012A00026D010D8012B1ED0052BBBD1BFF34F8FFA -:1012B0008449854BCA6802F4E0621343CB60BFF3F4 -:1012C0004F8F00BFFDE7302BACD1637E7F4D0133E4 -:1012D0006A7BDBB29342E94603D1E27E2B7B9A42E2 -:1012E00065D0CD469EE721464046FFF707FE99E7C9 -:1012F000A38A013B9BB2C92B94D8744D2E7B26BB8D -:1013000005F10C030093082233463146204601F0D4 -:1013100091FE731CF2B2D9001E46A38A013B9A4289 -:1013200005DA0E322A44009200230822EEE7002359 -:101330000022C5E900230023AB6085F8D730C5F84B -:10134000D8302B7B0BB9E37E2B73002507F11409F2 -:101350003B1D082229464846C7E90155FD6001F0BA -:10136000A5FF3B7A05F1010AAB424FEACA0608D94C -:10137000FB6808222B443146484601F097FF55464A -:10138000EFE7C6F3CF06E17ECDE904960023039391 -:10139000A37E0293193428230093019446A3D3E932 -:1013A0000023404601F09AFDFFF7E2FC3AE74FF0D8 -:1013B000000807F11403A7F8148010220093414697 -:1013C0000123204601F036FEA68A023EB6B2F31C87 -:1013D0009B109B000733DB08A9EBC3039D460DF16F -:1013E000180A1FFA88F34FEAC801B34201F110014D -:1013F0000AD20AEB0803009308220023204601F0DA -:1014000019FE08F10108ECE795F8D70000F0A2FA00 -:10141000D5F8D83004461BB995F8D70000F0AAFAE1 -:10142000D5F8D83033449C4204D295F8D700013027 -:1014300000F0A0FA4FEA960B4FF000081FFA88F16F -:101440008B45D5E9003209D90AEB880103EB880006 -:10145000012200F015FB08F10108EFE7F31842F153 -:101460000002C5E90032D5F8D83095F8D70006EB70 -:101470000308C5F8D88000F06DFA804509D395F8C7 -:10148000D730D5F8D8000133001B85F8D730C5F820 -:10149000D800FF2E08D800232B7300F087FAFFF73F -:1014A00017FE08B1FFF766F92B68094A9B0A01335A -:1014B00013810023AB6014E726417272DF25D7B792 -:1014C000BD34002000ED00E00400FA05684900206A -:1014D000AC240020C034002008B54FF000530B4A64 -:1014E000196891420AD10A4A597D117009481B7D39 -:1014F00003730949C9220E3000F0A8FABDE808407C -:10150000E02200214FF0005000F0B2BA9AAD44C57D -:10151000B8240020684900201600002037B5184D77 -:1015200018491948022301226B7100F023FD0023A2 -:101530000193164B164900931648174B4FF48052EF -:1015400001F034FC154B197811B1124801F054FC2C -:1015500001F014FA0446FFF7E3FB4FF4C873B0FB45 -:10156000F3F202FB130304F5167010FA83F00C4B30 -:10157000186003F03FF808B10F232B8103B030BD92 -:10158000AC24002040420F00E8340020050E000883 -:10159000BC240020C4340020D1110008B82400204D -:1015A000C03400202DE9F04F2DED028B97A7D7E92D -:1015B00000670FF26029D9E900898E4C95B0DFF8F9 -:1015C0005CA2DFF85CB2204601F0ECFC034650B3AD -:1015D0000025CDE9115510958DF84C50027B8DF802 -:1015E0004C209968406811AA03C21B6843F000436D -:1015F000109301F0C5F910EB0A0241F100030095C8 -:1016000010A9584600F000FBA8427B4A05DD2046A1 -:1016100001F0CCFC784A1570D5E71378072B00F25F -:10162000BA80013313700DAD9FED708B0023DFF88E -:10163000F0B10C938DF83C300D936B6000230DF1ED -:1016400025028DED008B4FF0010A09A958468DF84F -:1016500025308DF824A000F0A1FF9DF82420002360 -:10166000002A40F09C80204601F0CEFB0546002871 -:1016700047D1DFF8B0B101F081F9DBF800309842D2 -:101680003FD301F07BF90790FFF74AFB079A4FF42D -:10169000C87302F51672B0FBF3F101FB130312FAE3 -:1016A00083F3CBF80030DFF880B19BF8001007918E -:1016B000002914BF2B46534610A88DF83030FFF791 -:1016C00047FB0799C1F11002D2B2062A10AB28BF1E -:1016D000062219440DF13100079200F0B7F9079A7C -:1016E0000CAB0393182302930132444BD2B2CDE9E1 -:1016F00000A304923B463246204601F087FB8BF85C -:10170000005001F03BF93E4A3E4D1368C31AB3F551 -:101710007A7F33D3106001F033F902460B4620463E -:1017200001F04EFC204601F06FFB38B32B7BDFF855 -:10173000FCA0002B14BF032302238AF8053001F01C -:101740001DF90DF1400B4FF47A735946B0FBF3F0DD -:10175000CAF800005046FFF799FB182307300293A0 -:10176000294B0193C0F3CF0040F25513CDE903B0EC -:10177000009342464B46204601F048FB2B7B2BB1A1 -:10178000FFF7F6FA2B7B002B7FF419AF15B0BDECF9 -:10179000028BBDE8F08F204601F008FC43E74FF0D4 -:1017A000904110A84A6982F010024A61194610223D -:1017B00000F05EF90DF126030AAA0CA9584600F0C4 -:1017C000CFFA95E8030011AB83E803009DF83C30A5 -:1017D0008DF84C300C9B109310A9DDE90A232046AC -:1017E00001F0ACFD2AE700BFAFF30080000000006D -:1017F00000000000C43400204D4A0020BC3400200A -:10180000484A0020684900204C4A0020401DA12081 -:1018100026812A0BF1C6A7C1D068080F40420F00ED -:10182000E8340020C0340020BD340020AC24002067 -:1018300008B5054800F01CFBBDE80840034A044910 -:10184000002003F091B900BFE8340020A04A002036 -:101850008D10000870B50F4B1B780133DBB2012BE4 -:101860000C4611D80C4D29684FF47A730E6AA2FB0E -:101870000332014622462846B047844204D1074B32 -:1018800000221A70012070BD4FF4FA7002F0CAFBFA -:101890000020F8E714230020A44A0020944A0020E6 -:1018A00007B50023024601210DF107008DF807302E -:1018B000FFF7D0FF20B19DF8070003B05DF804FBEF -:1018C0004FF0FF30F9E700000A4608B50421FFF7A2 -:1018D000C1FF80F00100C0B2404208BD30B4054CE9 -:1018E0002368DD69044B0A46AC460146204630BCFD -:1018F000604700BFA44A0020A086010070B502F036 -:10190000C9FC094E094D3080002428683388834281 -:1019100008D902F0BBFC2B6804440133B4F5F04F46 -:101920002B60F2D370BD00BF964A0020504A0020C1 -:1019300002F05EBD00F1006000F5E040D0F8000864 -:101940007047000000F10060920000F5F04002F0E6 -:10195000DDBC0000054B1A68054B1B889B1A8342AF -:1019600002D9104402F092BC00207047504A002077 -:10197000964A002038B5074D04462868204402F0F6 -:101980008BFC28B928682044BDE8384002F096BC9A -:1019900038BD00BF504A00200020704700F10050C1 -:1019A000A0F51040D0F8900570470000064991F866 -:1019B000243033B10023086A81F824300822FFF76D -:1019C000C1BF0120704700BF544A0020014B186876 -:1019D000704700BF002004E070B50E4B5C6893F9BF -:1019E0000860421E0A44013C0B46934207D214F998 -:1019F000015F581C2DB100F8015C0346F5E718465D -:101A000005E02C2482421C7001D9981C5E70401A9B -:101A100070BD00BF18230020022802BF4FF0904382 -:101A200010229A6170470000022802BF4FF09043D5 -:101A30004FF480129A617047022801BF4FF0904224 -:101A4000536983F0100353617047000010B5002301 -:101A5000934203D0CC5CC4540133F9E710BD0000BD -:101A600003460246D01A12F9011B0029FAD1704729 -:101A700002440346934202D003F8011BFAE7704781 -:101A80002DE9F8431F4D144695F824200746884653 -:101A900052BBDFF870909CB395F824302BB920220C -:101AA000FF2148462F62FFF7E3FF95F82400C0F1BD -:101AB0000802A24228BF2246D6B24146920005EB58 -:101AC0008000FFF7C3FF95F82430A41B1E44F6B234 -:101AD000082E17449044E4B285F82460DBD1FFF768 -:101AE00065FF0028D7D108E02B6A03EB820383420D -:101AF000CFD0FFF75BFF0028CBD10020BDE8F883F3 -:101B00000120FBE7544A0020024B1A78024B1A705E -:101B1000704700BF944A0020142300200349044862 -:101B20004FF4E1330B6002F017B900BF7C4A00208C -:101B3000A44A0020074B10B500210446182218467D -:101B4000FFF796FF04600146BDE81040024802F02E -:101B500003B900BF7C4A0020A44A0020202383F35D -:101B6000118862B670470000002383F3118862B6C3 -:101B70007047000001207047704700007047000068 -:101B800000F5805090F851047047000000F5805037 -:101B900090F84A04704700005020704700F58052CA -:101BA00008B5FFF7DBFFD2F87434D2F8700418449C -:101BB000D2F86C341844D2F858341844D2F864344B -:101BC0001844D2F860341844FFF7CEFF08BD000077 -:101BD00038B5426A936923F001039361044600F02B -:101BE000CDFE0546636A9B69DB0706D500F0C6FE9D -:101BF000431BFA2BF6D9002004E004F580540120A1 -:101C000084F84A0438BD0000F8B500F580551F4639 -:101C1000D5F854340133C5F854340C6814F000542A -:101C200061D10B7B082B5ED895F84A34002B5AD033 -:101C3000FFF794FF436AD3F8C460B60208D5D5F81D -:101C400058340133C5F858342046FFF78DFFF8BDEE -:101C5000D3F8C4400D68C369C4F30144482616FB99 -:101C60000436002DB4BF45F08045AD0435600B68E7 -:101C70005B0044BF45F0005535600D7B230643EA09 -:101C8000054373604B68B3608B68F360456A01235A -:101C9000A340C5F8CC3000EB441303F58253C3E9ED -:101CA000022700EB441303F58253103301F10C02B9 -:101CB00051F8045B43F8045B9142F9D10A781A7039 -:101CC00004F18302530100EB4212C450BDF81830F6 -:101CD000117903F0030343F0100321F01F010B43BC -:101CE00013710120B1E7D5F858340133C5F85834E1 -:101CF0004FF0FF30ABE7000013B50446019100F050 -:101D0000F1FC1F280AD901992022204600F060FD2D -:101D1000A0F120035842584102B010BD0020FBE75B -:101D200008B500F58050FFF719FFC06B00F0AEFC5E -:101D3000BDE80840FFF718BF00220260027342604E -:101D40008260704710B500220023C0E90023002301 -:101D5000044603810C30FFF7EFFF204610BD000062 -:101D60002DE9F041054688B005F5805568461F46C7 -:101D70000C46FFF7F3FE9046FFF7E4FFE86B00F038 -:101D800097FC1F2805D80020FFF7EEFE08B0BDE83D -:101D9000F081E86B2022694600F09CFD2028F2D1FA -:101DA00095F84A34002BEED003AD05AB2E4603CE9A -:101DB0009E4220606160354604F10804F6D1306827 -:101DC000206033792371DDE90023C8E90023BDF8E1 -:101DD00008303B800120D7E72DE9F84F8046214BA2 -:101DE00048F8283B00F5815504460F46464608351D -:101DF00030462036FFF7A6FFAE42F9D104F58055F4 -:101E00004FF480534FF00009C5E90B39C5F828801D -:101E10000123EE6304F5A35804F58356C5F8349006 -:101E200085F8383085F84030083608F108084FF05A -:101E3000000A4FF0000B46E908ABA6F11800FFF7C7 -:101E40007BFF203646F8289C4645F4D185F850742F -:101E500017B1054800F08CFD044B63622046BDE8D5 -:101E6000F88F00BFB04D0008944D0008006400409A -:101E700010B5044B197804464A1C1A70FFF7ACFFE2 -:101E8000204610BD9D4A00202DE9F04300294FD087 -:101E9000284B2948B0FBF1F099428CBF0A2311234B -:101EA0005D1EB0FBF3F703FB1703ECB22BB1022D61 -:101EB0002B46F5D80020BDE8F0837E1EB6F5806F76 -:101EC000F8D2C4EBC40C0CF103034FEAE308C3F3EC -:101ED000C703A4EB030E08F101094FF47A755FFA0A -:101EE0008EF008FB055559FA8EFEB5FBFEF5B5F5EB -:101EF000617FC1BF0CF1FF33C3F3C703E01AC0B267 -:101F00005C1C50FA84F40C4D7C43B5FBF4F4A14204 -:101F1000D0D1013BDBB20F2BCCD80138C0B207289F -:101F2000C8D80021107116809170D3700120C2E7CB -:101F30000846C0E73F420F0000127A000B4B10B575 -:101F40004FF45472044600211846FFF791FD084BE8 -:101F5000236140336361D833A361F033E361636A83 -:101F6000E0600022C3F8C02010BD00BF00A4004004 -:101F700070A400402DE9F04700F5805588B095F831 -:101F80005034012B04468846164647D87E4A52F8FC -:101F9000231009B942F823007C49C4F804800B7867 -:101FA000267293B9FFF7DAFD794B9A6D42F0007211 -:101FB0009A659A6B42F000729A639A6B22F00072F3 -:101FC0009A6301230B70FFF7CFFD95F8493473B97D -:101FD00002211520FFF7C2FD01F00CFD02211620A1 -:101FE00001F008FD012385F84934FFF7BDFDFFF737 -:101FF000B5FD626A936923F01003936100F0BEFCA3 -:102000008146636A9F6917F008070AD000F0B6FCA2 -:10201000A0EB0903FA2BF4D9FFF7A6FD4FF0000857 -:10202000AEE09A6942F001029A6100F0A7FC814695 -:10203000636A9A69D10706D400F0A0FCA0EB0903FB -:10204000FA2BF5D9E8E79A6942F002029A61636ACD -:102050004FF00009C3F85490FFF786FDE86B00F0DD -:1020600015FB04F5825A0AF1080A2022002168466D -:10207000FFF7FEFC02A8FFF75FFECDF818906A4656 -:102080000AEB07030DF1180E9446BCE80300F44573 -:1020900018605960624603F10803F5D1DCF80000CE -:1020A000186020379CF804201A71B7F5806FDCD1D6 -:1020B00000276A46414685F8487485F84B742046E7 -:1020C000ADF80070ADF802708DF80470FFF7DCFE1B -:1020D000626A804680B9936923F00103936100F03E -:1020E0004DFC0546636A9B69DA0797D500F046FC0C -:1020F000431BFA2BF6D991E79DF802309DF803E0D7 -:102100009DF80400BDF800C05B0643EA0E230343BC -:1021100043EA0C43D3614FEA0E21626A41EA0C4361 -:1021200043EA0013D3602046FFF708FF85F8517497 -:10213000636A6FF040421A65636A164A5A65636AB9 -:1021400044229A65636A0722C3F8DC20636A03228B -:102150009642DA6514D0626A936923F001039361B1 -:1021600000F00CFC0646636A9B69DB0705D500F0AE -:1021700005FC831BFA2BF6D950E7012385F84A3476 -:10218000404608B0BDE8F087984A00209C4A0020ED -:10219000001002409B0008002DE9F043074689B07B -:1021A00090469946002600F580557B6AD3F8D430D6 -:1021B000F340D9073ED506F1830307EB43131A79A1 -:1021C000120737D4D5F85C240132C5F85C241A799B -:1021D00042F008021A71D30724D595F84B340BB39B -:1021E00007F582541034684604EB4614FFF7AAFD45 -:1021F0000DF10C0C04F1080220686168634603C30A -:10220000083494429C46F7D12068186023798CF8F2 -:102210000430E86B01236946CDE90089ADF8083048 -:10222000FFF76AFDD5F84C3423B1D5F87834013383 -:10223000C5F878340136202EB7D109B0BDE8F08357 -:102240002DE9F0478CB004468A4600F099FB8146A0 -:102250008846BAF1000F5BD1636AD3F890209701EA -:1022600041BF04F58051D1F870240132C1F87024C7 -:10227000D3F89020160703D100200CB0BDE8F087FA -:10228000D3F890606569C6F30126482303FB065521 -:102290006F463846FFF750FD2A6851004ABF22F0CA -:1022A0006043C2F38A4343F00043920048BF43F0C7 -:1022B00080430093EB8803F00F038DF80C3001AAE4 -:1022C000EB1D0F3513F8011F02F8011BAB42F9D1CA -:1022D000BAF1000F35D1636AC3F8946004A8FFF720 -:1022E00031FD97E80F0007AD07C504F580542B704A -:1022F000E06B002304A9CDE90498ADF81830FFF78E -:10230000FBFC28B3D4F868340133C4F86834B4E76C -:10231000BAF1010FB0D1636AD3F89820950141BF9B -:1023200004F58051D1F870240132C1F87024D3F83B -:1023300098201007A0D0D3F89860A569C6F30126AD -:10234000A3E7BAF1010F04BF636AC3F89C60C5E755 -:10235000D4F86C340133C4F86C3401208DE70000EC -:10236000F8B505460F4600F5805401263946284643 -:10237000FFF766FF10B184F84B64F7E7D4F84C34EC -:1023800023B1D4F878340133C4F87834F8BD0000B0 -:10239000F0B5436A1A6C12F47F0F29D000F580540F -:1023A0001B6CC4F87C3400F583560023012703F12D -:1023B000830200EB421211798D0716D5490714D418 -:1023C0005901456A7158D5F8C8C007FA01F111EAF8 -:1023D0000C0F0AD0C5F8D010117941F00401117129 -:1023E000D4F864240132C4F864240133202BDED1F4 -:1023F000F0BD000010B5254C254B226802B338B360 -:102400001A6D12060ED580221A6500F0B9FA50EA4C -:1024100001020B4602D0013861F100030246206838 -:10242000FFF7BAFE1A4A136D1B032AD523684FF42F -:10243000002103F580531165012283F8512420E027 -:1024400001221A6508221A654FF480621A6510BDD0 -:10245000196DC80702D4196D890705D503211965BF -:1024600010460021FFF77CFF094B1A6D100702D4BC -:102470001A6DD10605D518221A6520680121FFF7CB -:102480006FFF2068BDE81040FFF782BF984A002028 -:102490000064004008B5FFF761FBFFF779FFBDE876 -:1024A0000840FFF761BB0000436AD3F8C40080F422 -:1024B0000010C0F34050704700F5805008B5FFF79A -:1024C0004DFBC06B00F0F4F8FFF74EFB43090CBF67 -:1024D0000120002008BD000000F5805393F851242E -:1024E00062B1416A8A6922F001028A61D3F87424D8 -:1024F0000132C3F87424002283F85124704700008D -:102500002DE9F34100F5825198460831FFF726FB8B -:1025100000254FF0010E00F5805C05F1830400EB0F -:10252000441423795E071CD4DB061AD5436A8E69EE -:10253000D3F8C8700EFA06F63E4212D04F680197E3 -:102540000F689742019F77EB08070AD2C3F8D06063 -:10255000237943F004032371DCF860340133CCF8B1 -:1025600060340135202D01F12001D6D102B0BDE843 -:10257000F041FFF7F9BA0000F8B51E4600231370CA -:102580000F4605461446FFF797FF80F001003870AC -:102590001EB12846FFF788FF2070F8BD2DE9F04FE7 -:1025A00085B099460B7801930E4613780293DDE9C6 -:1025B0000EBA8046174600F0E3F9337804460D461C -:1025C00013B93B78002B41D022462B464046FFF7FB -:1025D00097FFFFF75FFFFFF77FFF4B463A46314615 -:1025E000FFF7CAFF33782BB1019B1BB1012005B067 -:1025F000BDE8F08F3B7813B1029B002BF6D108F5B4 -:10260000805303935C4575EB0A031FD2039BD3F8F9 -:102610004C04D8B10368BBEB0402D9686AEB05032C -:1026200088474B463A4631464046FFF7A5FF337888 -:1026300013B1019B002BD9D13B7813B1029B002B26 -:10264000D4D100F09DF904460D46DBE70020CEE72B -:1026500008B50020FFF7CEFEBDE8084001F092B8B3 -:1026600008B50120FFF7C6FEBDE8084001F08AB8B2 -:102670000FB4002004B0704710B5037C044613B9B2 -:10268000006802F087FA204610BD00000023BFF367 -:102690005B8FC360BFF35B8FBFF35B8F8360BFF360 -:1026A0005B8F7047BFF35B8F0068BFF35B8F704732 -:1026B00070B505460C30FFF7F5FF05F10806044636 -:1026C0003046FFF7EFFFA04206D930466D68FFF7AE -:1026D000E9FF2544281A70BD3046FFF7E3FF201AB2 -:1026E000F9E7000070B50546406898B105F10800AB -:1026F000FFF7D8FF05F10C0604463046FFF7D2FF7E -:102700008442304694BF6D680025FFF7CBFF013C43 -:102710002C44201A70BD000038B50C460546FFF762 -:10272000C7FFA04210D305F10800FFF7BBFF044428 -:102730006868B4FBF0F100FB1144BFF35B8F01202C -:10274000AC60BFF35B8F38BD0020FCE72DE9F041A2 -:10275000144607460D46FFF7C5FF844228BF0446CE -:10276000D4B1B84658F80C6B4046FFF79BFF304495 -:10277000286040467E68FFF795FF331A9C4203D8D5 -:102780006C600120BDE8F0816B60A41B3B68AB600E -:102790002044E8600220F5E72046F3E738B50C4610 -:1027A0000546FFF79FFFA04210D305F10C00FFF78D -:1027B00079FF04446868B4FBF0F100FB1144BFF3F7 -:1027C0005B8F0120EC60BFF35B8F38BD0020FCE71E -:1027D0002DE9FF41884669460746FFF7B7FF6C467B -:1027E00006B204EBC6060025B44209D06268206830 -:1027F00008EB0501FFF72AF9636808341D44F3E785 -:1028000029463846FFF7CAFF284604B0BDE8F081E4 -:10281000F8B505460C300F46FFF744FF05F10806F2 -:1028200004463046FFF73EFFA042304688BF6C6842 -:10283000FFF738FF201A386020B130462C68FFF7C8 -:1028400031FF2044F8BD000073B5144606460D461E -:10285000FFF72EFF844228BF04460190DCB101A996 -:102860003046FFF7D5FF019B33B93268C5E9023323 -:10287000C5E9002401200CE09C4238BF0194286087 -:10288000019868608442F5D93368AB60241AEC6023 -:10289000022002B070BD2046FBE700002DE9FF4199 -:1028A0000F466946FFF7D0FF6C4600B204EBC00547 -:1028B0000026AC4209D0D4F8048054F8081BB8199B -:1028C0004246FFF7C3F84644F3E7304604B0BDE89C -:1028D000F081000038B50546FFF7E0FF04460146E9 -:1028E0002846FFF719FF204638BD0000FEE700002C -:1028F00000B59BB0EFF3098168226846FFF7A6F8A0 -:10290000EFF30583044B9A6BDA6A9A6A9A6A9A6AB9 -:102910009A6A9A6A9B6AFEE700ED00E000B59BB0F8 -:10292000EFF3098168226846FFF790F8EFF305831B -:10293000044B9A6B9A6A9A6A9A6A9A6A9A6A9B6A2A -:10294000FEE700BF00ED00E000B59BB0EFF30981AA -:1029500068226846FFF77AF8EFF30583034B5A6B5A -:102960009A6A9A6A9A6A9A6A9B6AFEE700ED00E0A0 -:102970000FB408B5029801F0EFFAFEE701F082BD4E -:1029800001F05ABD30B5094D0A4491420DD011F8FD -:10299000013B5840082340F30004013B2C4013F056 -:1029A000FF0384EA5000F6D1EFE730BD2083B8ED95 -:1029B0002DE9F041C56915B9C161BDE8F0814B68E9 -:1029C00023F06047C3F38A464FEAD37EC3F380788F -:1029D00016EA230638BF3E46AC462B465A68BEEB85 -:1029E000D27F22F060440AD0002A18DAA40CB44244 -:1029F00017D19D420FD10D60DEE71346EEE7A742E7 -:102A000007D102F08044C2F3807242450BD054B12A -:102A1000EFE708D2EDE7CCF800100B60CDE7B44249 -:102A200001D0B442E5D81A689C46002AE5D1196065 -:102A3000C3E700002DE9F047089D01F007044FEAC5 -:102A4000D508224405F0070500EBD1004FF47F497B -:102A5000944201D1BDE8F08704F0070705F0070AAA -:102A600057453E4638BF5646C6F10806111B8E42F2 -:102A700028BF0E46E10808EBD50E415C13F80EC0E6 -:102A8000B94029FA06F721FA0AF1FFB28CEA0101EE -:102A900047FA0AF739408CEA010C03F80EC03444B7 -:102AA0003544D5E780EA0120082341F2210201B232 -:102AB0004000002980B203F1FF33B8BF504013F04B -:102AC000FF03F4D17047000038B50C468D18A542BD -:102AD00000D138BD14F8011BFFF7E4FFF7E7000051 -:102AE00002684AB113680360C388018901339BB24D -:102AF0009942C38038BF03811046704770B588B0D3 -:102B0000202204460D4668460021FEF7B1FF20460C -:102B10000495FFF7E5FF024658B16B46054608AE3F -:102B20001C4603CCB44228606960234605F10805C1 -:102B3000F6D1104608B070BD10B54B6823B9CA8AEB -:102B400063F30902CA8210BDC4681A681C60C360BE -:102B5000438A013B43824A60EFE700002DE9F84FCA -:102B60001D46CB8A0F46C3F30901062981469246CA -:102B70000B4630D00020AAB207F119049EB2052EF0 -:102B80001FFA80F80FD8904503F1010306D3FB8AA2 -:102B90000A4462F30903FB8201201AE01AF800607C -:102BA000E6540130EAE79045F1D2A1F1060B1C236F -:102BB0007C68BBFBF3F203FB12BB1FFA8BF6002C05 -:102BC00045D14846FFF78CFF044638B978606FF06E -:102BD0000200BDE8F88F4FF00008E6E70026066027 -:102BE0007860ADB24FF0000B454510D90AEB0803F1 -:102BF000221D13F8011B9155B1B208F101081B29E0 -:102C00001FFA88F82BD0454506F10106F1D8FB8A5A -:102C1000C3F30902154465F30903BCE7013292B21C -:102C20001C462368002BF9D1AB1F0B441C21B3FBBE -:102C3000F1F301339BB29A42D3D2BBF1000FD0D152 -:102C40004846FFF74DFF20B9C4F800B0BFE70122A6 -:102C5000E7E7C0F800B05E4620600446C1E745459E -:102C6000D5D94846FFF73CFF08B92060AFE7C0F868 -:102C700000B0002620600446B6E700002DE9F04FC2 -:102C80002DED028B83B0CDE90013BDF83C408046AA -:102C90009246002A00F087802CB10E9B002B00F09A -:102CA0008280072C2BD808F10C00FFF719FF05468E -:102CB00038B96FF00205284603B0BDEC028BBDE8C1 -:102CC000F08F14220021FEF7D3FE22460E9905F163 -:102CD0000800FEF7BBFE631C2B749AF800302C44EE -:102CE00003F01F0363F03F032372009B43F0004196 -:102CF000696040462946FFF75BFE0125DBE700F1EE -:102D00000C034FF0000908EE103A4FF0800B4E46CE -:102D10004D4618EE100AFFF7E3FE07460028C8D01C -:102D200014220021FEF7A4FE002E3AD1019B3B8124 -:102D300002220E9B02F1080103EB060C57FA81F107 -:102D40001046B44202F10102D2B201D8024607E0B5 -:102D50001CF8010B01F8010B0136062AB6B2EFD9B7 -:102D60009AF8001001F01F01B44208BF4FF0400B69 -:102D7000B81841EA49114BEA01030372009B013282 -:102D800043F000437B603A7439464046FFF710FE3B -:102D90000135B4422DB289F001094FF0000BB8D1D2 -:102DA00089E70022C5E76FF0010584E7F8B515460D -:102DB0000E462422002104461F46FEF759FE069BBC -:102DC0006360B5F5001F079BA76034BF6A094FF623 -:102DD000FF72236204F10C0097B200239A4205D8D7 -:102DE0000023036027826382A382F8BD066001335B -:102DF00030462036F2E7000003781BB94BB2002BB7 -:102E0000C8BF017070470000007870472DE9F74F88 -:102E1000DDF83C90BDF830500D9E9DF83840BDF86F -:102E20004070804692469B46B9F1000F01D1002FB9 -:102E300051D11F2C4FD898F80000B0B9072F47D8B0 -:102E400035F0030347D13A4649464FF6FF70FFF786 -:102E50003BFE20F001002D02400445EA0464400CD2 -:102E600044EA40244FF6FF7321E040EA0520072F93 -:102E700040EA0464F6D900254FF6FF73C5F120003F -:102E8000A5F120022AFA05F10BFA00F001432BFA12 -:102E900002F211431846C9B2FFF704FE0835402D6F -:102EA0000346EBD13A464946FFF70EFE0346CDE90D -:102EB0000097324621464046FFF7E0FE3378013363 -:102EC000DBB21F2B88BF0023337003B0BDE8F08F47 -:102ED0006FF00300F9E76FF00100F6E72DE9F04F1E -:102EE00085B09246DDF848800F9D9DF840209DF802 -:102EF0004490BDF84C7006469B46B8F1000F01D1D6 -:102F0000002F48D11F2A46D83378002B46D00C0218 -:102F100044EA02649DF8381044EAC93444EA0144A2 -:102F20001C43072F44F0800432D900234FF6FF7270 -:102F3000C3F1200CA3F120002AFA03F10BFA0CFCD8 -:102F400041EA0C012BFA00F00143C9B21046039389 -:102F5000FFF7A8FD039B0833402B0246E8D13A4611 -:102F60004146FFF7B1FD0346CDE900872A462146D9 -:102F70003046FFF783FEB9F1010F06D12B780133FC -:102F8000DBB21F2B88BF00232B7005B0BDE8F08F8C -:102F90004FF6FF73E8E76FF00100F6E76FF003000C -:102FA000F3E70000C06900B104307047C3691A68D4 -:102FB000C261C2681A60C360438A013B43827047A2 -:102FC0002DE9F041D0F81880194E14461D464146AF -:102FD000002709B9BDE8F081D1E90223A21A65EB07 -:102FE0000303964277EB03031ED283698B420DD114 -:102FF000FFF7A2FD83691B688361C3680B60438A86 -:10300000C1608169013B43828846E2E7FFF794FD96 -:103010000B68C8F80030C3680B60438AC160013B8D -:103020004382D8F80010D4E788460968D1E700BF8A -:1030300080841E002DE9F04F8BB00D46DDF85090D6 -:1030400014469B468046002800F01981B9F1000F14 -:1030500000F01581531E3F2B00F21181012A03D18C -:10306000BBF1000F40F00B810023CDE90833B8F825 -:103070001430B5EBC30F4FEAC30703D300200BB0E6 -:10308000BDE8F08F2B199F42D8F80C303ABF7F1B58 -:10309000FFB227461BB9D8F81030002B7AD02F2D5D -:1030A0004ED8C5F13006B7424FF000032CBFF6B240 -:1030B0003E4600932946D8F8080008AB3246FFF791 -:1030C000B9FCA7EB060A35445FFA8AFAB8F814305F -:1030D00003F10053063BDB000493D8F80C30039354 -:1030E0003021039B13B1BAF1000F2CD1D8F8100096 -:1030F00040B1BAF1000F05D0009608AB5246691AEC -:10310000FFF798FC38B2002FB8D066070AD00AAB98 -:1031100003EBD401624211F8083C02F007021341AC -:1031200001F8083C082C3CD9102C40F2B580202C2A -:1031300040F2B780BBF1000F00F09C80082334E020 -:10314000BA460026C2E7049BE02B28BFE023069383 -:103150000B44AB42059314D95A1B03980096924531 -:1031600034BF5246D2B2691A08AB04300792FFF757 -:1031700061FC079A1644AAEB020A1544F6B25FFAFC -:103180008AFA049B069A05999B1A0493039B1B6871 -:103190000393A6E70093D8F8080008AB3A462946FF -:1031A000AEE7BBF1000F13D00123B4EBC30F6CD01B -:1031B000082C12D89DF82030621E23FA02F2D5079F -:1031C00006D54FF0FF3202FA04F423438DF8203085 -:1031D0009DF8203089F8003051E7102C12D8BDF846 -:1031E0002030621E23FA02F2D10706D54FF0FF32DB -:1031F00002FA04F42343ADF82030BDF82030A9F8DA -:1032000000303CE7202C0FD80899631E21FA03F305 -:10321000DA0705D54FF0FF3202FA04F40C430894A4 -:10322000089BC9F800302AE7402C2BD0DDE908655F -:10323000611EC4F12102A4F1210326FA01F105FA6D -:1032400002F225FA03F311431943CB0712D50122E9 -:10325000A4F12003C4F1200102FA03F322FA01F1E0 -:10326000A240524243EA010363EB430332432B4340 -:10327000CDE90823DDE90823C9E90023FFE66FF063 -:103280000100FCE66FF00800F9E6082CA0D9102C2C -:10329000B3D9202CEED8C3E7BBF1000FADD0022389 -:1032A00083E7BBF1000FBBD004237EE730B5012AD2 -:1032B000144638BF0124402C85B028BF4024002587 -:1032C000012ACDE9025518D81B788DF8083063071C -:1032D0000AD004AB03EBD405624215F8083C02F0B7 -:1032E0000702934005F8083C00910346224600215E -:1032F00002A8FFF79FFB05B030BD082AE4D9102AC9 -:1033000003D81B88ADF80830E1E7202A8DBFD3E948 -:1033100000231B680293CDE90223D8E710B5CB68E0 -:103320001BB98B600B618B8210BDC4681A681C606E -:10333000C360438A013B4382CA60F0E72DE9F04F46 -:10334000D1F8008093B018F0800FCDE90323C8F3C3 -:10335000C01219BFC8F3C03BC8F306264FF0020BDA -:103360001646B8F1000F04460D4680F2C58118F0EC -:10337000C043059340F0C0810B7B002B00F0BC8163 -:10338000BBF1020F03D00178B14240F0B88108F0E0 -:103390007F0106916AB3C8F3074A2B44069A93F853 -:1033A0000390760646EA0B4646EA82465FEAD91360 -:1033B00046EA0A06079300F0908000220023CDE938 -:1033C0000A23069B009367685B4652460AA920467B -:1033D000B84700287ED0A7699FB9314604F10C0098 -:1033E000FFF78CFB0746E0B96FF0020013B0BDE8B1 -:1033F000F08FC8F30F2A18F07F0F08BF0AF0030AF6 -:10340000CBE73B699E420DD03F68002FF9D1314692 -:1034100004F10C00FFF772FB07460028E4D0A36913 -:103420003B60A761DDE90A2300264FF6FF70C6F175 -:10343000200E22FA06F103FA0EFEA6F1200C23FA62 -:103440000CFC41EA0E0141EA0C01C9B208360992AE -:103450000893FFF727FB402EDDE90832E7D1B88259 -:10346000FB7D09F01F06C3F38403F31AD7E9022199 -:1034700098B2002BBCBF00F120031BB252EA01003E -:10348000C8F304680FD00398821A049860EB010116 -:10349000A14890424FF000028A4104D3079A002AC3 -:1034A00055D0012B23DDFA7D4FEA890302F0030298 -:1034B00003F07C031343FB7539462046FFF73CFBC2 -:1034C000079BA3B9FB7DC3F38402013262F3860339 -:1034D000FB7504E06FF00B0088E7A76917B96FF080 -:1034E0000C0083E73B699E42BAD03F68F6E719F0CB -:1034F000400F2CD0039BBB60049BFB601422002177 -:103500000DA8FEF7B5FA039B0A93049B0B932B1DA2 -:103510000C932B7BADF83EA0013BDBB2ADF83C3009 -:10352000069B8DF843308DF840B0A3688DF841605C -:103530008DF842800AA920469847FB7DC3F3840397 -:10354000013303F01F039B02FB8200204EE7FB7D4B -:10355000C9F34012B2EBD31F40F0D480C3F384030D -:10356000B34240F0D28007992B7B4FEA9912002991 -:1035700034D0D20741D4032B40F2CA80039BBB60F6 -:10358000049BFB602B7BAE1D033BDBB2324639460E -:1035900004F10C00FFF7E2FA00280DDA2046394664 -:1035A000FFF7CAFAFB7DC3F38403013303F01F0363 -:1035B0009B02FB82032019E7AB883B832A7B033AFB -:1035C000B88AD2B23146FFF77FFAFB7DB882DA4380 -:1035D000C2F3C01262F3C713FB75B6E76AB92E1DBA -:1035E000013BDBB23246394604F10C00FFF7B6FA74 -:1035F0000028D3DB2A7B013AE2E7F98AC1F309010B -:10360000013B0529DAB253D8281D002307F11A0C13 -:103610009A4208D910F801EB0CF801E001310133AE -:103620000629DBB2F4D103990A9104990B919342D4 -:1036300007F11A010C9138BF043379680D9134BF3A -:1036400055FA83F300230E93FB8AADF83EA0C3F333 -:1036500009031A44069B8DF843300023ADF83C2043 -:103660008DF840B08DF841608DF842807B602A7BF8 -:10367000B88A013A291DFFF727FA3B8BB8828342AB -:1036800003D1A3680AA92046984720460AA9FFF754 -:1036900045FEFB7DB88AC3F38403013303F01F03A7 -:1036A0009B02FB823B8B984214BF112000209DE6B9 -:1036B0007B68002BB7D0062001E01C306346D3F8AE -:1036C00000C0BCF1000FF8D1091A081D05F1040C67 -:1036D00000EB030905989DF8143001EB000EBEF1D4 -:1036E0001B0FA0D89A429ED91CF8013B09F8013B58 -:1036F000059B01330593EDE76FF0090076E66FF067 -:103700000A0073E66FF00D0070E66FF00E006DE6D4 -:103710006FF00F006AE600BF80841E00EFF309839C -:1037200005494A6B22F001024A63683383F3098832 -:10373000002383F31188704700EF00E0202080F31E -:10374000118862B60C4B0D4AD96821F4E061090476 -:10375000090C0A43DA60D3F8FC20094942F0807270 -:10376000C3F8FC200A6842F001020A601022DA77EE -:1037700083F82200704700BF00ED00E00003FA0567 -:10378000001000E010B5202383F311880E4B5B6816 -:1037900013F4006314D0F1EE103AEFF30984683C9F -:1037A0004FF08073E361094BDB6B236684F3098878 -:1037B00000F084FB10B1064BA36110BD054BFBE785 -:1037C00083F31188F9E700BF00ED00E000EF00E0AF -:1037D0004B0600084E06000802684368114301606A -:1037E00003B1184770470000024A136843F0C00352 -:1037F000136070470038014013B50E4C204600F0AE -:103800009FFA04F114000C49009400234FF48072D5 -:1038100000F060F9094B0A4900944FF4807204F1FA -:10382000380000F0D9F9074A074BC4E9172302B062 -:1038300010BD00BFA44A0020104B0020E93700084B -:10384000104C002000380140007A030A30B5037C98 -:10385000234C002918BF0C46012B0FD1214B984255 -:103860000CD1214B1A6E42F480421A66D3F88020A4 -:1038700042F48042C3F88020D3F880302268036E7F -:10388000C16D846603EB5203B3FBF2F36268150467 -:1038900042BF23F0070503F0070343EA4503CB606B -:1038A000A36843F040034B60E36843F001038B607F -:1038B00042F4967343F001030B604FF0FF330B6249 -:1038C000510505D512F0102205D0B2F1805F04D069 -:1038D00080F8643030BD7F23FAE73F23F8E700BF6C -:1038E000E44D0008A44A0020001002402DE9F047F2 -:1038F000C66D3768F46934622107054618D014F0A4 -:10390000080118BF8021E20748BF41F02001A3074A -:1039100048BF41F04001600748BF41F48071202357 -:1039200083F31188281DFFF757FF002383F31188C5 -:10393000E2050AD5202383F311884FF40071281D76 -:10394000FFF74AFF002383F311884FF020094FF05F -:10395000000A14F0200838D13B0616D54FF0200994 -:1039600005F1380A200610D589F31188504600F079 -:1039700067F9002836DA0821281DFFF72DFF27F008 -:1039800080033360002383F31188790614D562061F -:1039900012D5202383F31188D5E913239A4208D145 -:1039A0002B6C33B11021281D27F04007FFF714FFBF -:1039B0003760002383F31188E30618D5AA6E1369D4 -:1039C000ABB1BDE8F0475069184789F31188736AB5 -:1039D00095F864102846194000F0CCF98AF3118854 -:1039E000F469B6E7B06288F31188F469BAE7BDE814 -:1039F000F087000000F1604303F561430901C9B29B -:103A000083F80013012200F01F039A4043099B0032 -:103A100003F1604303F56143C3F880211A607047E6 -:103A2000F8B5154682680669AA420B46816938BF17 -:103A30008568761AB54204460BD218462A46FEF728 -:103A400005F8A3692B44A361A3685B1BA360284608 -:103A5000F8BD0CD918463246FDF7F8FFAF1BE168F8 -:103A60003A463044FDF7F2FFE3683B44EBE7184683 -:103A70002A46FDF7EBFFE368E5E700008368934221 -:103A8000F7B51546044638BF8568D0E90460361A94 -:103A9000B5420BD22A46FDF7D9FF63692B44636117 -:103AA000A36828465B1BA36003B0F0BD0DD9324666 -:103AB0000191FDF7CBFF0199E068AF1B3A46314415 -:103AC000FDF7C4FFE3683B44E9E72A46FDF7BEFF84 -:103AD000E368E4E710B50A440024C361029B8460F4 -:103AE000C0E90000C0E90511C1600261036210BDB8 -:103AF00008B5D0E90532934201D1826882B9826863 -:103B0000013282605A1C42611970D0E904329A4233 -:103B100024BFC3684361002100F0A0FA002008BD63 -:103B20004FF0FF30FBE7000070B5202304460E463F -:103B300083F31188A568A5B1A368A269013BA360BE -:103B4000531CA36115782269934224BFE368A361E3 -:103B5000E3690BB120469847002383F31188284678 -:103B600007E03146204600F069FA0028E2DA85F3E2 -:103B7000118870BD2DE9F74F04460E46174698464A -:103B8000D0F81C904FF0200A8AF311884FF0000BF8 -:103B9000154665B12A4631462046FFF741FF0346E8 -:103BA00060B94146204600F049FA0028F1D00023D0 -:103BB00083F31188781B03B0BDE8F08FB9F1000FD3 -:103BC00003D001902046C847019B8BF31188ED1A62 -:103BD0001E448AF31188DCE7C0E90511C160C361A6 -:103BE0001144009B8260C0E90000016103627047DC -:103BF000F8B504460D461646202383F31188A768BE -:103C0000A7B1A368013BA36063695A1C62611D7080 -:103C1000D4E904329A4224BFE3686361E3690BB1DB -:103C200020469847002080F3118807E0314620465F -:103C300000F004FA0028E2DA87F31188F8BD0000EA -:103C4000D0E905239A4210B501D182687AB9826819 -:103C5000013282605A1C82611C7803699A4224BF37 -:103C6000C3688361002100F0F9F9204610BD4FF0D0 -:103C7000FF30FBE72DE9F74F04460E4617469846FE -:103C8000D0F81C904FF0200A8AF311884FF0000BF7 -:103C9000154665B12A4631462046FFF7EFFE03463A -:103CA00060B94146204600F0C9F90028F1D0002350 -:103CB00083F31188781B03B0BDE8F08FB9F1000FD2 -:103CC00003D001902046C847019B8BF31188ED1A61 -:103CD0001E448AF31188DCE70268436811430160DF -:103CE00003B11847704700001430FFF743BF0000CE -:103CF0004FF0FF331430FFF73DBF00003830FFF7BF -:103D0000B9BF00004FF0FF333830FFF7B3BF0000FA -:103D10001430FFF709BF00004FF0FF311430FFF7F8 -:103D200003BF00003830FFF763BF00004FF0FF32E1 -:103D30003830FFF75DBF000000207047FFF75CBD23 -:103D4000044B03600023C0E9023343600123037482 -:103D5000704700BFFC4D000810B52023044683F3D4 -:103D60001188FFF773FD02232374002383F3118866 -:103D700010BD000038B5C36904460D461BB90421C7 -:103D80000844FFF7A9FF294604F11400FFF7B0FE2D -:103D9000002806DA201D4FF48061BDE83840FFF7A7 -:103DA0009BBF38BD024B0022C3E900339A607047C5 -:103DB000104D0020002303748268054B1B6899682E -:103DC0009142FBD25A6803604260106058607047AD -:103DD000104D002008B5202383F31188037C032BAA -:103DE00005D0042B0DD02BB983F3118808BD43698E -:103DF00000221A604FF0FF334361FFF7DBFF00231F -:103E0000F2E7D0E9003213605A60F3E7002303744D -:103E10008268054B1B6899689142FBD85A68036019 -:103E20004260106058607047104D0020054B1969C2 -:103E30000874186802681A605360186101230374DB -:103E4000FCF7EEBB104D002030B54B1C0B4D87B07E -:103E5000044610D02B690A4A01A800F019F920463F -:103E6000FFF7E4FF049B13B101A800F04DF92B69A3 -:103E7000586907B030BDFFF7D9FFF8E7104D0020B3 -:103E8000D53D000838B50C4D41612B6981689A68B1 -:103E90009142044603D8BDE83840FFF78BBF18466F -:103EA000FFF7B4FF01232C61014623742046BDE8CF -:103EB0003840FCF7B5BB00BF104D0020044B1A681A -:103EC0001B6990689B68984294BF0020012070474E -:103ED000104D002010B5084C236820691A68226034 -:103EE0005460012223611A74FFF790FF0146206994 -:103EF000BDE81040FCF794BB104D002008B5FFF75B -:103F0000DDFF18B1BDE80840FFF7E4BF08BD0000C1 -:103F1000FFF7E0BFFEE7000010B50C4CFFF742FFD3 -:103F200000F0A8F80A498022204600F03DF801235D -:103F300044F8180C0374FFF701FC002383F3118885 -:103F400062B60448BDE8104000F04EB8384D00207D -:103F5000244E0008344E000808B572B6034B586270 -:103F600000F05AFA00F00EFBFEE700BF104D0020F3 -:103F700000F004B9EFF3118020B9EFF3058320229C -:103F800082F311887047000010B530B9EFF3058453 -:103F9000C4F3080414B180F3118810BDFFF7AEFF1D -:103FA00084F31188F9E700008260022202827047E0 -:103FB0008368A3F17C0243F80C2C026943F83C2C83 -:103FC000426943F8382C074A43F81C2CC26843F86E -:103FD000102C022203F8082C002203F8072CA3F16E -:103FE000180070473906000810B5202383F31188A4 -:103FF000FFF7DEFF00210446FFF744FF002383F3B1 -:104000001188204610BD0000024B1B6958610F202B -:10401000FFF70CBF104D0020202383F31188FFF71A -:10402000F3BF000008B50146202383F31188082060 -:10403000FFF70AFF002383F3118808BD49B1064B3F -:1040400042681B6918605A60136043600420FFF7E0 -:10405000FBBE4FF0FF307047104D002003689842C0 -:1040600006D01A680260506059611846FFF7A2BE78 -:1040700070470000054B03F11402C3E905224FF01D -:10408000FF310022C3E90712704700BF104D002026 -:1040900070B51C4EC0E9032305460C4600F0E8FA53 -:1040A000334653F8142F9A420DD13062C5E90124EA -:1040B0002A60022C2CBF00190230C6E90555BDE864 -:1040C000704000F0C3BA316A431AE31838BF1C4687 -:1040D0009368A34202D9081900F0C6FA73699A6876 -:1040E00094420CD85A68AC602B606A6015609A687C -:1040F0005D60121B9A604FF0FF33F36170BD1B6867 -:10410000A41AECE7104D002038B51B4C63699842A7 -:104110000DD0D0E9003213605A6000228168C2607D -:104120009A680A449A604FF0FF33E36138BD224633 -:10413000036842F8143F002193425A60C16003D1E2 -:10414000BDE8384000F08ABA9A688168256A0A4456 -:104150009A6000F08DFA63699A68411B8A42E5D93A -:10416000AB181D1A012D206A98BF8A1CBDE8384083 -:10417000104400F079BA00BF104D00202DE9F04145 -:10418000184C002704F11406656900F071FA236ADF -:10419000AA68C11A8A4215D813442362D5E90032AD -:1041A00013605A606369D5F80C80EF60B34201D1A7 -:1041B00000F054FA87F311882869C047202383F35D -:1041C0001188E1E76169B14209D013441B1ABDE8C7 -:1041D000F041022B2CBFC018023000F045BABDE8F8 -:1041E000F08100BF104D002000207047FEE7000066 -:1041F000704700004FF0FF3070470000BFF34F8F53 -:10420000024A1369DB03FCD4704700BF0020024060 -:1042100008B5094B1B7873B9FFF7F0FF074B5A69D4 -:10422000002ABFBF064A9A6002F188329A601A6873 -:1042300022F480621A6008BDD84E0020002002409F -:104240002301674508B50B4B1B7893B9FFF7D6FFE1 -:10425000094B5A6942F000425A611A6842F480528E -:104260001A601A6822F480521A601A6842F4806256 -:104270001A6008BDD84E0020002002407F289ABF57 -:1042800000F58030C0020020704700004FF400604D -:1042900070470000802070477F2808B50BD8FFF7D3 -:1042A000EDFF00F500630268013204D1043083425F -:1042B000F9D1012008BD0020FCE700007F2810B5DF -:1042C00004461FD8FFF79AFFFFF7A2FF0E4BF32219 -:1042D0001A6102225A615A6942EAC0025A615A6955 -:1042E00042F480325A61FFF789FF4FF40061FFF713 -:1042F000C5FF00F043F9FFF7A5FF2046BDE81040D9 -:10430000FFF7CABF002010BD002002402DE9F8438E -:1043100040EA020313F00703144606D02E4B40F286 -:10432000BF221A600020BDE8F88385182B4A954209 -:104330000CD9294A4FF431711160F3E7031D1B6852 -:104340004A68934208D1083C08300831072C14D938 -:1043500002680B689A42F1D0FFF75AFFFFF74EFF51 -:104360001F4E08314FF001084FF00009012CA1F158 -:10437000080706D8FFF766FF01E0002CECD101200A -:10438000D1E7C6F81480054651F8083C45F8043BCF -:1043900051F8043C4360FFF731FFC6F814900268FF -:1043A00051F8083C9A420CD00B4B40F2EA221A60BA -:1043B0000C4B18600C4B1C600C4B1F60FFF742FF4E -:1043C000B0E72D6851F8043C9D4201F10801EBD1A2 -:1043D000083C0830CAE700BFD44E0020FFFF0308A6 -:1043E00000200240C84E0020D04E0020CC4E0020BD -:1043F000084908B50B7828B11BB9FFF709FF01235D -:104400000B7008BD002BFCD0BDE808400870FFF71A -:1044100019BF00BFD84E002008B54FF4C0314FF08F -:10442000005000F0ADF8BDE808404FF480414FF077 -:10443000805000F0A5B8000070B582B0FFF79AFD7B -:104440000E4E054600F014F93268904237BF0C4A10 -:104450000B49516814682EBFD1E900410131516008 -:104460000419034641F10001284601913360FFF72A -:104470008BFD0199204602B070BD00BFDC4E0020CC -:10448000E04E002070B582B0FFF774FD104E054677 -:1044900000F0EEF83268904237BF0E4A0D4951687D -:1044A00014682EBFD1E9004101315160041941F176 -:1044B00000010346284601913360FFF765FD01992D -:1044C0004FF47A7200232046FBF792FE02B070BDD3 -:1044D000DC4E0020E04E00200244D2B2904200D1D7 -:1044E0007047431C800000F1804000F514500068C4 -:1044F00041F8040BD8B2F1E7124B10B5D3F8904055 -:10450000240409D4D3F89040C3F89040D3F89040E5 -:1045100044F40044C3F890400B4C2368024443F435 -:1045200080732360D2B2904200D110BD431C800042 -:1045300000F1804000F5145051F8044B0460D8B2EB -:10454000F1E700BF001002400070004007B50122F3 -:1045500001A90020FFF7C0FF019803B05DF804FB3C -:1045600013B50446FFF7F2FFA04205D0012201A9CE -:1045700000200194FFF7C0FF02B010BD704700009B -:104580007047000070470000074B45F255521A6013 -:1045900002225A6040F6FF729A604CF6CC421A60D2 -:1045A000024B01221A70704700300040E94E002093 -:1045B000034B1B781BB1034B4AF6AA221A607047C3 -:1045C000E94E002000300040044BD3F894309B00AB -:1045D00042BF034B01221A70704700BF0010024017 -:1045E000E84E0020024B4FF40002C3F894207047BD -:1045F00000100240014B1878704700BFE84E0020C1 -:1046000070470000FEE700000A4B0B480B4A90423F -:104610000BD30B4BDA1C121AC11E22F003028B4281 -:1046200038BF00220021FDF723BA53F8041B40F8DD -:10463000041BECE7A04F0008744F0020744F0020CB -:10464000744F00207047000000F078B84FF08043AE -:10465000002258631A610222DA6070474FF08043EB -:104660000022DA60704700004FF0804358637047C3 -:104670004FF08043586A70474B6843608B68836093 -:10468000CB68C3600B6943614B6903628B6943620A -:104690000B6803607047000008B5204BDA6A42F0EF -:1046A0007F02DA62DA6A22F07F02DA62DA6ADA6CB0 -:1046B00042F07F02DA64DA6E42F07F02DA66184A6C -:1046C000DB6E11464FF09040FFF7D6FF02F11C0160 -:1046D00000F58060FFF7D0FF02F1380100F580603F -:1046E000FFF7CAFF02F1540100F58060FFF7C4FF35 -:1046F00002F1700100F58060FFF7BEFF02F18C014E -:1047000000F58060FFF7B8FF02F1A80100F58060B6 -:10471000FFF7B2FFBDE8084000F064B800100240A7 -:104720004C4E000808B500F003FAFFF7F5FBBDE8B2 -:104730000840FFF749BF0000704700000F4B9A6D1B -:1047400042F001029A659A6F42F001029A670C4AA0 -:104750009B6F936843F0010393604FF08043A7225F -:104760009A624FF0FF32DA6200229A615A63DA608D -:104770005A6001225A611A60704700BF001002405F -:10478000002004E04FF0804208B51169D3680B4067 -:10479000D9B2C9439B07116107D5202383F3118840 -:1047A000FFF7E6FB002383F3118808BD08B50B4B28 -:1047B000D3F8902012F4407F1FBF4FF48032C3F82B -:1047C00090200022C3F89020D3F89020C3F89020C6 -:1047D00000F086F9024B00225A6008BD001002402A -:1047E00000700040484B4FF0FF319A6A99629A6A14 -:1047F00000229A62986AD86A60F07F00D862D86A0C -:1048000000F07F00D862D86A186B1963186B1A63BE -:10481000186B986B9963986B9A63986BD86BD96394 -:10482000D86BDA63D86B186C1964196C1A641A6C3B -:104830009A6D42F080529A659A6F22F080529A6780 -:104840009A6F324A4FF400711160516911F480611E -:10485000FBD14FF40040516090604FF48070D16004 -:10486000C2F88000116251629162D162116351639A -:104870009163D163116451649164D1641165516590 -:10488000D3F8982042F00102C3F89820D3F898207A -:104890009007FBD51A6842F480321A601A689103B7 -:1048A000FCD51A490A6842F480720A60184ADA6034 -:1048B0001A6842F080721A601A689201FCD50022D0 -:1048C00014499A60C3F888101349C3F89C20134A0E -:1048D0000A600A6802F00F02042AFAD19A6842F0CC -:1048E00003029A609A6802F00C020C2AFAD11A6E3E -:1048F00042F001021A66D3F8802042F00102C3F8A8 -:104900008020D3F8803070470010024000700040D3 -:10491000032A6101550100500020024004070400F1 -:10492000074A08B5536903F00103536123B1054AEF -:1049300013680BB150689847BDE80840FEF722BFE6 -:1049400000040140EC4E0020074A08B5536903F00B -:104950000203536123B1054A93680BB1D0689847AD -:10496000BDE80840FEF70EBF00040140EC4E0020F9 -:10497000074A08B5536903F00403536123B1054A9C -:1049800013690BB150699847BDE80840FEF7FABEBD -:1049900000040140EC4E0020074A08B5536903F0BB -:1049A0000803536123B1054A93690BB1D069984755 -:1049B000BDE80840FEF7E6BE00040140EC4E0020D2 -:1049C000074A08B5536903F01003536123B1054A40 -:1049D000136A0BB1506A9847BDE80840FEF7D2BE93 -:1049E00000040140EC4E0020164B10B55C6904F445 -:1049F00078725A61A30604D5134A936A0BB1D06A40 -:104A00009847600604D5104A136B0BB1506B98475A -:104A1000210604D50C4A936B0BB1D06B9847E20585 -:104A200004D5094A136C0BB1506C9847A30504D503 -:104A3000054A936C0BB1D06C9847BDE81040FEF767 -:104A4000A1BE00BF00040140EC4E0020194B10B580 -:104A50005C6904F47C425A61620504D5164A136D00 -:104A60000BB1506D9847230504D5134A936D0BB1D4 -:104A7000D06D9847E00404D50F4A136E0BB1506E09 -:104A80009847A10404D50C4A936E0BB1D06E984799 -:104A9000620404D5084A136F0BB1506F9847230482 -:104AA00004D5054A936F0BB1D06F9847BDE810400D -:104AB000FEF768BE00040140EC4E002008B5034834 -:104AC000FEF714FFBDE80840FEF75CBEA44A0020D4 -:104AD00008B5FFF757FEBDE80840FEF753BE0000DB -:104AE000062108B50846FEF785FF06210720FEF7D8 -:104AF00081FF06210820FEF77DFF06210920FEF731 -:104B000079FF06210A20FEF775FF06211720FEF720 -:104B100071FF06212820FEF76DFF07211C20FEF7FC -:104B200069FFBDE808400C212520FEF763BF0000A7 -:104B300008B5FFF73BFE00F009F8FFF7FFF8FFF7B5 -:104B4000FBFDBDE80840FFF77FBD00000023054ADC -:104B500019460133102BC2E9001102F10802F8D105 -:104B6000704700BFEC4E00200B460146184600F08F -:104B700003B8000000F00EB810B5054C13462CB178 -:104B80000A4601460220AFF3008010BD2046FCE734 -:104B900000000000024B0146186800F035B800BF65 -:104BA0002423002010B501390244904201D1002095 -:104BB00005E0037811F8014FA34201D0181B10BD86 -:104BC0000130F2E72DE9F041A3B1C91A1778014489 -:104BD000044603F1FF3C8C42204601D9002009E045 -:104BE0000578BD4204F10104F5D10CEB0405D6189B -:104BF000A54201D1BDE8F08115F8018D16F801ED4F -:104C0000F045F5D0E7E7000037B5002944D051F86A -:104C1000043C0190002BA1F10404B8BFE41800F09B -:104C200047F81E4A0198136833B96360146003B0F3 -:104C3000BDE8304000F042B8A34208D925686119A8 -:104C40008B4201BF19685B6849192160EDE71A467C -:104C50005B680BB1A342FAD911685518A5420BD174 -:104C6000246821445418A3421160E0D11C685B6899 -:104C7000536021441160DAE702D90C230360D6E7C0 -:104C8000256861198B4204BF19685B68636004BFC3 -:104C9000491921605460CAE703B030BD6C4F002051 -:104CA000034611F8012B03F8012B002AF9D17047B4 -:104CB000014800F009B800BF704F0020014800F023 -:104CC00005B800BF704F002070470000704700001B -:104CD0006F72672E6172647570696C6F742E6D529D -:104CE0006F2D4D3130303935000000004E6F20619E -:104CF0007070207369670A00426164206677206CD7 -:104D0000656E6774682025750A0042616420626FD1 -:104D10006172645F69642025752073686F756C64C7 -:104D20002062652025750A00426164206677206450 -:104D3000657363726970746F72206C656E677468F6 -:104D40002025750A0042616420617070204352433F -:104D5000203078253038783A30782530387820304F -:104D600078253038783A3078253038780A00476F1F -:104D70006F64206669726D776172650A0040A2E413 -:104D8000F16468910600000053544D333247343FBC -:104D90003F0000004261642043414E496661636503 -:104DA00020696E6465782E0000000000000000009D -:104DB000751F00089D250008751B0008091C0008C8 -:104DC000611D0008D11B0008991B00089D1B0008ED -:104DD000791B0008811B00087D1B0008211D0008AD -:104DE0008D1B00080096000000000000000000007D -:104DF00000000000000000000000000000000000B3 -:104E0000053D0008F13C00082D3D0008193D000853 -:104E1000253D0008113D0008FD3C0008E93C000864 -:104E2000393D00086D61696E0000000069646C65C1 -:104E3000000000002C4E0008504D0020C84E0020FD -:104E400001000000153F0008000000000001A82A32 -:104E500000000000AAAABEAA00001400EFFF000094 -:104E60000000000070970900000000000000000032 -:104E7000AAAAAAAA00000000FFFF0000000000008C -:104E8000000000000000000000000000AAAAAAAA7A -:104E900000000000FFFF0000000000000000000014 -:104EA0000000000000000000AAAAAAAA000000005A -:104EB000FFFF0000000000000000000000000000F4 -:104EC00000000000AAAAAAAA00000000FFFF00003C -:104ED00000000000000000000000000000000000D2 -:104EE000AAAAAAAA00000000FFFF0000000000001C -:104EF000000000000000000000000000AAAAAAAA0A -:104F000000000000FFFF00000000000000000000A3 -:104F100010B3FF7F0100000011040000000000003A -:104F200000880300FE2A0100D2040000FF000000F8 -:104F300000000000884D00083F00000028230020EA -:104F40000000000000000000000000000000000061 -:104F50000000000000000000000000000000000051 -:104F60000000000000000000000000000000000041 -:104F70000000000000000000000000000000000031 -:104F80000000000000000000000000000000000021 -:104F90000000000000000000000000000000000011 +:10064000A047002003F098FEFEE703F011FE00DF54 +:10065000FEE70000F8B504F03BF9074604F08CF91A +:100660000546A0BB1F4B9F4231D001339F4231D082 +:100670001D4B27F0FF029A422FD1F8B200F036FD51 +:100680002E4642F2107400F03BFF08B100242646CB +:1006900000F032FD08B90646044635B1134B9F42BF +:1006A00003D004F061F900242646002004F01AF972 +:1006B0000EB100F063F801F049FA00F045FF01F0D7 +:1006C00035F9204600F0AEF800F058F8F9E72E466C +:1006D0000024D8E704460126D5E706464FF47A748D +:1006E000D1E700BF010007B0000008B0263A09B00A +:1006F00008B501F0EDF8A0F120035842584108BDBB +:1007000007B541F21203022101A8ADF8043001F04F +:10071000FDF803B05DF804FB10B5202383F31188C6 +:100720001248C3680BB103F09FFE114A0F48002323 +:100730004FF47A7103F05CFE002383F311880D4CB3 +:10074000236813B12368013B2360636813B16368B6 +:10075000013B6360084B1B7833B9636823B90220FF +:1007600001F082F93223636010BD00BF90230020A6 +:1007700019070008AC240020A423002038B5234A20 +:10078000234B1968013140D004339342F9D1214CF5 +:100790001F4DD4F80428AA4237D31F4B9B6803F19E +:1007A000006303F5F0439A422FD204F0AFF804F04F +:1007B000C1F8002001F0D4F8184B0220187001F0A5 +:1007C0004BF9174B9A6D00229A65996F9A67996F4A +:1007D000D96DDA65D96FDA67D96F196E1A66D3F8F1 +:1007E0008010C3F88020D3F8803072B64FF0E02339 +:1007F0002021C3F8085DD4F80038D4F8042881F328 +:1008000011889D4683F30888104738BD207800087A +:10081000007800080070000800230020A4230020B6 +:10082000001002402DE9F04F93B0AC4B0090202215 +:10083000FF210AA89D6801F033F9A94A1378A3B9EA +:10084000A8480121C3601170202383F31188C36875 +:100850000BB103F009FEA44AA24800234FF47A71B9 +:1008600003F0C6FD002383F31188009B9F4A03B168 +:1008700013609F49009C00230B70536098469B4671 +:100880001E469A46012001F0E7F824B1974B1B68F9 +:10089000002B00F01C82002001F01AF80390039B4B +:1008A000002B01DA00F096FE039B002BEDDB01200C +:1008B00001F0CAF8039B213B162BE3D801A252F8A2 +:1008C00023F000BF2109000849090008DD090008DC +:1008D000850800088508000885080008710A0008D6 +:1008E000430C00085D0B0008BF0B0008E70B000875 +:1008F0000D0C0008850800081F0C0008850800087A +:10090000910C0008C109000885080008D50C0008F2 +:100910002D090008C109000885080008BF0B000860 +:100920000220FFF7E5FE002840F0FB81009B02213A +:10093000B8F1000F08BF1C4605A841F21233ADF80C +:10094000143000F0E3FF9DE74FF47A7000F0C0FF31 +:10095000071EEBDB0220FFF7CBFE0028E6D0013FAD +:10096000052F00F2E081DFE807F0030A0D101336CF +:1009700005230593042105A800F0C8FF17E0574898 +:100980000421F9E75B480421F6E75B480421F3E71B +:100990004FF01C09484600F0E5FF09F104090590F5 +:1009A000042105A800F0B2FFB9F12C0FF2D101200B +:1009B00000FA07F747EA0B0B5FFA8BFB4FF0000AD0 +:1009C00001F0BAF826B10BF00B030B2B08BF002483 +:1009D000FFF796FE56E749480421CDE7002EA5D043 +:1009E0000BF00B030B2BA1D10220FFF781FE074672 +:1009F00000289BD001203E4E00F0B2FF0220307054 +:100A000001F02AF84FF000085FFA88F9484600F034 +:100A1000B9FF044690B1484600F0C4FF08F1010850 +:100A20000028F1D1B846044641F21213022105A86C +:100A3000ADF814303E4600F069FF23E701230220A1 +:100A4000337001F001F82546244B9B68AB4207D96F +:100A5000284600F087FF013040F068810435F3E755 +:100A6000234B00251D70214BB8465D603E46A7E72D +:100A7000002E3FF45BAF0BF00B030B2B7FF456AF54 +:100A80001B4B0220187000F0E7FF322000F020FF1F +:100A9000B0F10009FFF64AAF19F003077FF446AF43 +:100AA0000E4A926809EB050393423FF63FAFB9F552 +:100AB000807F3FF73BAF124B0193B94522DD4FF4E6 +:100AC0007A7000F005FF0390039A002AFFF62EAF1C +:100AD000019B039A03F8012B0137EDE70023002067 +:100AE000A82400209023002019070008AC2400202F +:100AF000A423002004230020082300200C2300202E +:100B0000A8230020C820FFF7F3FD074600283FF484 +:100B10000DAF1F2D11D8C5F120024A450AAB25F0B3 +:100B2000030028BF4A4683490192184400F0A6FFFB +:100B3000019A8048FF2100F0B3FF4FEAA9037D49E5 +:100B40000193C9F38702284600F0B2FF0646002849 +:100B50003FF46AAF019B05EB830531E70220FFF705 +:100B6000C7FD00283FF4E2AE00F038FF00283FF454 +:100B7000DDAE0027B946704B9B68BB4218D91F2FCA +:100B800011D80A9B01330ED027F0030312AA134495 +:100B900053F8203C05934846042205A902F052F878 +:100BA00004378146E7E7384600F0DCFE0590F2E7BF +:100BB000CDF81490042105A800F0A8FE00E700235A +:100BC000642104A8049300F097FE00287FF4AEAEE1 +:100BD0000220FFF78DFD00283FF4A8AE049800F036 +:100BE000F3FE0590E6E70023642104A8049300F0D7 +:100BF00083FE00287FF49AAE0220FFF779FD0028DB +:100C00003FF494AE049800F0E1FEEAE70220FFF71B +:100C10006FFD00283FF48AAE00F0F0FEE1E702200D +:100C2000FFF766FD00283FF481AE05A9142000F00F +:100C3000EBFE04210746049004A800F067FE394645 +:100C4000B9E7322000F044FE071EFFF66FAEBB0787 +:100C50007FF46CAE384A926807EB0A0393423FF682 +:100C600065AE0220FFF744FD00283FF45FAE27F099 +:100C700003075744BA453FF4A3AE504600F072FE56 +:100C80000421059005A800F041FE0AF1040AF1E7ED +:100C90004FF47A70FFF72CFD00283FF447AE00F0C8 +:100CA0009DFE002844D00A9B01330BD008220AA9DC +:100CB000002000F0FDFE00283AD02022FF210AA8E3 +:100CC00000F0EEFEFFF71CFD1C4803F05BFB13B0C9 +:100CD000BDE8F08F002E3FF429AE0BF00B030B2B79 +:100CE0007FF424AE0023642105A8059300F004FEE0 +:100CF000074600287FF41AAE0220FFF7F9FC814670 +:100D000000283FF413AEFFF7FBFC41F2883003F0FC +:100D100039FB059800F026FF4E4600F00DFF3C46DB +:100D2000B0E506464CE64FF0000AFFE5B8467BE624 +:100D3000374679E6A823002000230020A086010082 +:100D4000094A136849F2690099B21B0C00FB013390 +:100D50001360064B186844F2506182B2000C01FB2C +:100D60000200186080B27047142300201023002076 +:100D700010B500211022044600F092FE034B03CB75 +:100D8000206061601868A06010BD00BF9075FF1FF3 +:100D90002DE9F043224DBBB001F04EFFAB6840F2AD +:100DA000ED22C31A934232D906AFA8602B462822FF +:100DB0000021384602F01EFC05F10E0000F068FE2E +:100DC000002604465FFA80F905F10E08F3B2F1003F +:100DD000994501F1280107D908EB06030822384696 +:100DE00002F008FC0136F1E708230122CDE90232C6 +:100DF00005340C4B0193A4B230230093CDE9047465 +:100E000005A3D3E90023297B074802F00BFA3BB086 +:100E1000BDE8F083AFF3008078F6339F93CACD8DA1 +:100E2000A8490020B5490020CC34002070B50D46FB +:100E300014461E4602F08CF950B9022E10D1012C36 +:100E40000ED112A3D3E90023C5E90023012007E056 +:100E5000282C10D005D8012C09D0052C0FD000204B +:100E600070BD302CFBD10BA3D3E90023ECE70BA31F +:100E7000D3E90023E8E70BA3D3E90023E4E70BA3BE +:100E8000D3E90023E0E700BFAFF30080401DA120BD +:100E900026812A0B78F6339F93CACD8D9E6AC42192 +:100EA000818A46EE26417272DF25D7B7F017304AA5 +:100EB00039059E5613B504462346084620220021D4 +:100EC000019002F097FB22790198032A234628BF5C +:100ED000032203F8042F2021022202F08BFB627907 +:100EE0000198072A234628BF072203F8052F22214D +:100EF000032202F07FFBA2790198072A234628BF2C +:100F0000072203F8062F2521032202F073FB019824 +:100F100004F108031022282102F06CFB382002B0F3 +:100F200010BD00002DE9F04FADF5017D21AD0EAEF5 +:100F300040F2751280460F4622A80021296000F079 +:100F4000AFFD48220021304600F0AAFD01F074FEFA +:100F5000564B4FF47A72B0FBF2F0186093E807003A +:100F6000012386E807000DF15A003382FFF700FFE6 +:100F700041F20413338407AB18464D4904F056F888 +:100F8000182230642946304686F83C20FFF792FF4D +:100F900012AB044601460822284602F02BFB082229 +:100FA000A1180DF14903284602F024FB0DF14A0374 +:100FB000082204F11001284602F01CFB13AB20228A +:100FC00004F11801284602F015FB14AB402204F18D +:100FD0003801284602F00EFB16AB082204F1780116 +:100FE000284602F007FB0DF15903082204F18001A5 +:100FF000284602F0FFFA04F1880A0DF15A0904F5B7 +:10100000847B4B465146082228460AF1080A02F022 +:10101000F1FAD34509F10109F3D11BAB0822594676 +:10102000284602F0E7FA04F588744FF0000996F8B4 +:1010300034304B450AD9B36B21464B44082228462D +:1010400002F0D8FA083409F10109F0E74FF000097D +:1010500096F83C304B4504EBC90108D9336C0822A3 +:101060004B44284602F0C6FA09F10109F0E70023D3 +:101070000393BB7E0293073107F119030193C1F378 +:10108000CF010123CDE904510093F97E05A3D3E9F3 +:101090000023404602F0C6F80DF5017DBDE8F08F53 +:1010A000AFF300809E6AC421818A46EEB4240020FA +:1010B0005C50000810B50A4B0A4A1A6003F58053C9 +:1010C00093F848203AB95C6C2CB1204601F032FC10 +:1010D000204603F015FFBDE81040034801F02ABC8C +:1010E000F83400203C51000828450020014B1870BE +:1010F000704700BFC0240020F0B5334B1C7B85B087 +:1011000034B1324B0E221A810024204605B0F0BDC6 +:101110002F4A1068516802AB03C308232D492E489B +:101120000DEB030203F014FF054630B9274B2B48A3 +:101130000A221A8101F086FBE6E70169B1F5623FF8 +:1011400006D9224B26480B221A8101F07BFBDCE7F3 +:10115000438B40F21142934207D01C490C20088176 +:101160001946204801F06EFBCFE71F4A024402F106 +:101170001003994204D2154B1C4810221A81E4E74F +:1011800010398E1A2046144901F05CFD324607469C +:1011900005F11801204601F055FDAB689F4202D1D0 +:1011A000EB6898420AD0094B0D221A810090D5E9CC +:1011B00002123B460E4801F045FBA5E70D4801F041 +:1011C00041FB0124A1E700BFA8490020B42400206E +:1011D00009510008DC8703000078000878500008F7 +:1011E00084500008965000080888FFF7B4500008A3 +:1011F000D1500008FA5000082DE9F04FADB006AF0D +:1012000080460C4601F0A4FF054600285AD1237EF3 +:10121000022B1BD1E38A012B18D101F00DFD0646EC +:10122000FFF78EFD03464FF4C870DFF8D092B3FB92 +:10123000F0F206F5167602FB103316FA83F3C9F8BE +:101240000030E37E33B9A84B00221A709C37BD46AC +:10125000BDE8F08FA38AEEB2013BB34205F1010570 +:101260000BD93B1D1E44E90000960023082201F023 +:10127000F801204602F082F8ECE707F11400FFF7CE +:1012800077FD324607F11401381D03F051FE0028A6 +:10129000D9D10F2E08D8944B1E70D9F80030A3F581 +:1012A0001673C9F80030D1E7FB1CF87001460093B3 +:1012B00007220346204602F061F8F978404601F023 +:1012C0003FFFC3E7E38A282B26D010D8012B1ED07E +:1012D000052BBBD1BFF34F8F8449854BCA6802F4FD +:1012E000E0621343CB60BFF34F8F00BFFDE7302BAD +:1012F000ACD1637E7F4D01336A7BDBB29342E9461A +:1013000003D1E27E2B7B9A4265D0CD469EE72146F3 +:101310004046FFF707FE99E7A38A013B9BB2C92B22 +:1013200094D8744D2E7B26BB05F10C030093082244 +:1013300033463146204602F021F8731CF2B2D90040 +:101340001E46A38A013B9A4205DA0E322A440092D5 +:1013500000230822EEE700230022C5E90023002332 +:10136000AB6085F8D730C5F8D8302B7B0BB9E37E5E +:101370002B73002507F114093B1D08222946484616 +:10138000C7E90155FD6002F035F93B7A05F1010A24 +:10139000AB424FEACA0608D9FB6808222B44314603 +:1013A000484602F027F95546EFE7C6F3CF06E17E3F +:1013B000CDE9049600230393A37E029319342823D6 +:1013C0000093019446A3D3E90023404601F02AFF8D +:1013D000FFF7DEFC3AE74FF0000807F11403A7F827 +:1013E00014801022009341460123204601F0C6FFDD +:1013F000A68A023EB6B2F31C9B109B000733DB08A3 +:10140000A9EBC3039D460DF1180A1FFA88F34FEAB2 +:10141000C801B34201F110010AD20AEB080300939C +:1014200008220023204601F0A9FF08F10108ECE79B +:1014300095F8D70000F0A6FAD5F8D83004461BB9C5 +:1014400095F8D70000F0AEFAD5F8D83033449C4276 +:1014500004D295F8D700013000F0A4FA4FEA960BB9 +:101460004FF000081FFA88F18B45D5E9003209D901 +:101470000AEB880103EB8800012200F019FB08F158 +:101480000108EFE7F31842F10002C5E90032D5F890 +:10149000D83095F8D70006EB0308C5F8D88000F0DF +:1014A00071FA804509D395F8D730D5F8D8000133C3 +:1014B000001B85F8D730C5F8D800FF2E08D80023C8 +:1014C0002B7300F08BFAFFF717FE08B1FFF756F900 +:1014D0002B68094A9B0A013313810023AB6014E790 +:1014E00026417272DF25D7B7C534002000ED00E039 +:1014F0000400FA05A8490020B4240020C8340020C4 +:1015000010B54FF000540C4B22689A4211D10B4B8E +:10151000627D1A700A48237D03730A49C9220E307E +:1015200000F0ACFAE0220021204600F0B9FA0120D8 +:1015300010BD0020FCE700BF9AAD44C5C0240020C8 +:10154000A84900201600002037B5194D19491A483E +:1015500002236B710022012300F0A6FD00230193FA +:10156000164B174900931748174B4FF4805201F060 +:10157000C1FD164B197811B1124801F0E1FD01F0DF +:101580005BFB0446FFF7DCFB4FF4C873B0FBF3F2E0 +:1015900002FB130304F5167010FA83F00C4B18606D +:1015A00003F0EAF908B10F232B8103B030BD00BF6F +:1015B000B424002040420F00F83400202D0E000813 +:1015C000C4240020CC340020F9110008C0240020DD +:1015D000C83400202DE9F04F2DED028B97A7D7E9F5 +:1015E00000670FF26029D9E900898E4C95B0DFF8C9 +:1015F0005CA2DFF85CB2204601F078FE034650B3EF +:101600000025CDE911551095ADF84C50027B8DF8B1 +:101610004C209968406811AA03C21B6843F000433C +:10162000109301F00BFB10EB0A0241F1000300954F +:1016300010A9584600F0F4FAA8427B4A05DD20467E +:1016400001F058FE784A1570D5E71378072B00F2A1 +:10165000BA80013313700DAD9FED708B0023DFF85E +:10166000F0B10C93ADF83C300D936B6000230DF19D +:1016700025028DED008B4FF0010A09A958468DF81F +:1016800025308DF824A001F073F89DF82420002364 +:10169000002A40F09C80204601F05AFD05460028B3 +:1016A00047D1DFF8B0B101F0C7FADBF8003098425B +:1016B0003FD301F0C1FA0790FFF742FB079A4FF4BE +:1016C000C87302F51672B0FBF3F101FB130312FAB3 +:1016D00083F3CBF80030DFF880B19BF8001007915E +:1016E000002914BF2B46534610A88DF83030FFF761 +:1016F0003FFB0799C1F11002D2B2062A10AB28BFF6 +:10170000062219440DF13100079200F0B7F9079A4B +:101710000CAB0393182302930132444BD2B2CDE9B0 +:1017200000A304923B463246204601F013FD8BF89D +:10173000005001F081FA3E4A3E4D1368C31AB3F5DA +:101740007A7F33D3106001F079FA02460B462046C7 +:1017500001F0DAFD204601F0FBFC38B32B7BDFF80B +:10176000FCA0002B14BF032302238AF8053001F0EC +:1017700063FA0DF1400B4FF47A735946B0FBF3F066 +:10178000CAF800005046FFF795FB18230730029374 +:10179000294B0193C0F3CF0040F25513CDE903B0BC +:1017A000009342464B46204601F0D4FC2B7B2BB1E4 +:1017B000FFF7EEFA2B7B002B7FF419AF15B0BDECD1 +:1017C000028BBDE8F08F204601F094FD43E74FF017 +:1017D000904110A84A6982F010024A61194610220D +:1017E00000F05EF90DF126030AAA0CA9584600F094 +:1017F00025FB95E8030011AB83E803009DF83C301E +:101800008DF84C300C9B109310A9DDE90A2320467B +:1018100001F038FF2AE700BFAFF3008000000000AE +:1018200000000000CC3400208D4A0020C434002089 +:10183000884A0020A84900208C4A0020401DA12091 +:1018400026812A0BF1C6A7C1D068080F40420F00BD +:10185000F8340020C8340020C5340020B42400200F +:1018600008B5054800F08EFBBDE80840034A04496E +:10187000002003F03FBB00BFF8340020E04A002006 +:10188000B510000870B50F4B1B780133DBB2012B8C +:101890000C4611D80C4D29684FF47A730E6AA2FBDE +:1018A0000332014622462846B047844204D1074B02 +:1018B00000221A70012070BD4FF4FA7002F062FD30 +:1018C0000020F8E718230020E44A0020D44A002032 +:1018D00007B50023024601210DF107008DF80730FE +:1018E000FFF7D0FF20B19DF8070003B05DF804FBBF +:1018F0004FF0FF30F9E700000A4608B50421FFF772 +:10190000C1FF80F00100C0B2404208BD30B4054CB8 +:101910002368DD69044B0A46AC460146204630BCCC +:10192000604700BFE44A0020A086010070B502F0C5 +:1019300061FE094E094D30800024286833888342B7 +:1019400008D902F053FE2B6804440133B4F5F04F7C +:101950002B60F2D370BD00BFD64A0020904A002011 +:1019600002F008BF00F1006000F5E040D0F8000888 +:101970007047000000F10060920000F5F04002F0B6 +:101980007DBE0000054B1A68054B1B889B1A8342DD +:1019900002D9104402F02ABE00207047904A00206D +:1019A000D64A002038B5074D04462868204402F086 +:1019B00023FE28B928682044BDE8384002F02EBE36 +:1019C00038BD00BF904A00200020704700F1005051 +:1019D000A0F51040D0F8900570470000064991F836 +:1019E000243033B10023086A81F824300822FFF73D +:1019F000C1BF0120704700BF944A0020014B186806 +:101A0000704700BF002004E070B50E4B5C6893F98E +:101A10000860421E0A44013C0B46934207D214F967 +:101A2000015F581C2DB100F8015C0346F5E718462C +:101A300005E02C2482421C7001D9981C5E70401A6B +:101A400070BD00BF1C230020022802BF4FF090434E +:101A500010229A6170470000022802BF4FF09043A5 +:101A60004FF480129A617047022801BF4FF09042F4 +:101A7000536983F0100353617047000010B50023D1 +:101A8000934203D0CC5CC4540133F9E710BD00008D +:101A900003460246D01A12F9011B0029FAD17047F9 +:101AA00002440346934202D003F8011BFAE7704751 +:101AB0002DE9F8431F4D144695F824200746884623 +:101AC00052BBDFF870909CB395F824302BB92022DC +:101AD000FF2148462F62FFF7E3FF95F82400C0F18D +:101AE0000802A24228BF2246D6B24146920005EB28 +:101AF0008000FFF7C3FF95F82430A41B1E44F6B204 +:101B0000082E17449044E4B285F82460DBD1FFF737 +:101B100065FF0028D7D108E02B6A03EB82038342DC +:101B2000CFD0FFF75BFF0028CBD10020BDE8F883C2 +:101B30000120FBE7944A0020024B1A78024B1A70EE +:101B4000704700BFD44A00201823002003490448EE +:101B50004FF4E1330B6002F0AFBA00BFBC4A002083 +:101B6000E44A0020074B10B500210446182218460D +:101B7000FFF796FF04600146BDE81040024802F0FE +:101B80009BBA00BFBC4A0020E44A0020202383F314 +:101B9000118862B670470000002383F3118862B693 +:101BA0007047000001207047704700007047000038 +:101BB00010B41346026814680022A4465DF8044B72 +:101BC0006047000000F5805090F85904704700000D +:101BD00000F5805090F852047047000000F58050E6 +:101BE00090F95804704700005020704700F580526B +:101BF00008B5FFF7CBFFD2F89834D2F89404184414 +:101C0000D2F890341844D2F878341844D2F8883492 +:101C10001844D2F884341844FFF7BEFF08BD000012 +:101C20002DE9F74F0C4600F580511F4691F85234CC +:101C3000BDF83090054690469BB1D1F8743401331D +:101C4000C1F8743423689A0006D4237B082B0BD97F +:101C5000627B0AB10F2B07D9D1F878340133C1F870 +:101C600078344FF0FF300FE0FFF790FFEB6AD3F8C6 +:101C7000C42012F4001A0AD0D1F87C340133C1F820 +:101C80007C34FFF789FF002003B0BDE8F08FD3F864 +:101C9000C46022686B6AC6F301464FF0480B002A05 +:101CA0001BFB063BB4BF42F080429204CBF80020FD +:101CB00023685B0044BF42F00052CBF80020227B37 +:101CC000330643EA0243CBF80430607B720118B359 +:101CD00043F44013CBF80430D1F8A4340133C1F8F5 +:101CE000A434AB1803F58353197B41F02001197319 +:101CF000207B019200F002FE019A033080105FFA0F +:101D00008AF383420AF1010A0DDA04EB83010BEB3B +:101D1000830349689960F2E7AB1803F58353197B95 +:101D200060F34511E3E7EB6A0121B140C3F8CC1041 +:101D3000AB1803F58253C3E9048705EB461303F59B +:101D400082532146183304F10C0051F804CB43F8B8 +:101D500004CB8142F9D1098819802A4441F26803F1 +:101D60002846D65002F5805209F0030392F86C1011 +:101D700043F0100321F01F010B4382F86C30FFF792 +:101D80000BFF42463B462146CDF8309003B0BDE8FC +:101D9000F04F00F079BD000038B5C26A936923F0B6 +:101DA00001039361044600F047FF0546E36A9B691F +:101DB000DB0706D500F040FF431BFA2BF6D90020C5 +:101DC00004E004F58054012084F8520438BD00007A +:101DD00013B500F580540191606C00F0E1FD1F28FF +:101DE0000AD90199606C202200F050FEA0F1200376 +:101DF0005842584102B010BD0020FBE708B500F57D +:101E00008050FFF7C3FE406C00F09EFDBDE8084027 +:101E1000FFF7C2BE0022026082814260826070478A +:101E200010B500220023C0E90023002304460381EB +:101E30000C30FFF7EFFF204610BD00002DE9F04702 +:101E4000074688B007F5805468469A468846FFF7EB +:101E50009DFE9146FFF7E4FF606C00F087FD1F28B0 +:101E60002CD9606C2022694600F092FE202825D1F2 +:101E700094F8523413B303AD444605AB2E4603CE5B +:101E80009E4220606160354604F10804F6D1306856 +:101E90002060B388A380DDE90023C9E90023BDF8F1 +:101EA0000830AAF80030FFF777FE4A46534641460D +:101EB000384608B0BDE8F04700F0D4BCFFF76CFE30 +:101EC000002008B0BDE8F0872DE9F84F0023064652 +:101ED000C0E90133284B46F8303B00F581540546F4 +:101EE00088463746103438462037FFF799FFA74217 +:101EF000F9D105F580544FF4805326630026C4E9D8 +:101F00000D366764012305F5835705F5A359E6638C +:101F100084F8403084F84830103709F110094FF048 +:101F2000000A4FF0000B47E908ABA7F11800FFF7D4 +:101F300071FF203747F8286C4F45F4D184F8588456 +:101F4000A4F85A64A4F85C64A4F85E6484F860643D +:101F5000A4F86264A4F86464A4F8666484F868640D +:101F6000B8F1000F02D0054800F060FE044BEB62B0 +:101F70002846BDE8F88F00BF3C51000820510008FA +:101F80000064004010B5044B197804464A1C1A70CE +:101F9000FFF79AFF204610BDDD4A00202DE9F043EF +:101FA00000295FD03048314BB3FBF1F381428CBF45 +:101FB0000A201120451EB3FBF0F700FB1730ECB2EE +:101FC00020B1022D2846F5D8002037E07D1EB5F55A +:101FD000806F33D2C4EBC40808F103034FEAE30E69 +:101FE000C3F3C703A4EB030C0EF101094FF47A709D +:101FF0005FFA8CF60EFB000E59FA8CFCBEFBFCFC63 +:10200000BCF5617F1CDC1FFA8CF4581C56FA80F07A +:1020100047431648B0FBF7F7B942D5D1013BDBB2D5 +:102020000F2BD1D8711EC9B207294FF0000005D877 +:10203000107114805580537191710120BDE8F083B7 +:1020400008F1FF334FEAE30CC3F3C703E41A0CF1C2 +:10205000010EE6B20CFB00005EFA84F4B0FBF4F46F +:10206000A4B2D2E70846E9E73F420F0000127A0027 +:102070000B4B10B54FF45472044600211846FFF77D +:102080000FFD084BA3614033E361D8332362F03383 +:102090006362E36A60610022C3F8C02010BD00BF24 +:1020A00000A4004070A400402DE9F04F00F58055D9 +:1020B000994695F85834012B89B004468A469046D3 +:1020C00004D90027384609B0BDE8F08F904A52F88D +:1020D000231009B942F823008E49C4F80CA00B78EC +:1020E00084F8109093B9FFF751FD8B4B9A6D42F035 +:1020F00000729A659A6B42F000729A639A6B22F0B2 +:1021000000729A6301230B70FFF746FD95F8513476 +:1021100073B902211520FFF739FD01F01BFE0221E2 +:10212000162001F017FE012385F85134FFF734FD26 +:10213000FFF72CFDE26A936923F01003936100F02E +:102140007BFD0746E36A9E6916F0080607D000F09B +:1021500073FDC31BFA2BF5D9FFF71EFDB1E79A6992 +:1021600042F001029A6100F067FD0746E36A9A694E +:10217000D00705D400F060FDC31BFA2BF6D9EBE7BE +:102180009A6942F002029A61E36A00275F65FFF7ED +:1021900003FD686C00F0D8FB04F5825B0BF1100BBB +:1021A000202200216846FFF77BFC02A8FFF732FEE1 +:1021B00006976A460BEB06030DF1180E9446BCE831 +:1021C0000300F44518605960624603F10803F5D135 +:1021D000DCF80000186020369CF804201A71B6F56F +:1021E000806FDDD1002304F5A25285F8503485F8C4 +:1021F00053341A3251462046FFF7D0FE074690B9B5 +:10220000E26A936923F00103936100F015FD05462E +:10221000E36A9B69D9077FF554AF00F00DFD431BBE +:10222000FA2BF5D94DE795F85F6495F85E24C5F86B +:102230006CA4360246EA426695F86024E36A1643C7 +:10224000B5F85C2446EA0246DE61B8F1000F29D0F9 +:1022500004F5A352023241462046FFF79FFE90B993 +:10226000E26A936923F00103936100F0E5FC0546FF +:10227000E36A9B69DA077FF524AF00F0DDFC431BBE +:10228000FA2BF5D91DE795F8683495F86714C5F869 +:1022900070841B0143EA0123B5F86414E26A43EA3F +:1022A0000143D3602046FFF7E3FE002385F859344D +:1022B000E36A6FF040421A65E36A184A5A65E36AB6 +:1022C00044229A65E36A0722C3F8DC20E36A03220A +:1022D000DA65E26A9369B9F1030F43F440739361DD +:1022E0003FF4F0AEE26A936923F00103936100F0DA +:1022F000A3FC0646E36A9B69DB0705D500F09CFC5E +:10230000831BFA2BF6D9DCE6012385F85234D9E693 +:10231000D84A0020DC4A0020001002409B00080040 +:102320002DE9F04F054689B090469946002741F2C5 +:10233000680A00F58056EB6AD3F8D430FB40D80722 +:102340004AD505EB471252444FEA471B1379190748 +:1023500042D4D6F880340133C6F8803413799A0613 +:1023600048BFD6F8A83405EB0B0248BF01335244EE +:1023700048BFC6F8A834137943F008031371DB078C +:1023800022D596F85334FBB105F5825418346846CB +:102390005C44FFF745FD03AB04F1080C206861685D +:1023A0001A4603C2083464451346F7D1206810600A +:1023B000A2889A800123ADF808302B68CDE9008906 +:1023C0001B6C694628469847D6F8543423B1D6F892 +:1023D0009C340133C6F89C340137202FABD109B0AF +:1023E000BDE8F08F2DE9F04F8DB004460F4600F0A8 +:1023F00025FC82468946002F56D1E36AD3F8902007 +:10240000920141BF04F58051D1F894240132C1F802 +:102410009424D3F89020160703D100200DB0BDE816 +:10242000F08FD3F89050E669C5F30125482303FBEC +:102430000566E8464046FFF7EDFC326851004ABFAA +:1024400022F06043C2F38A4343F00043920048BF46 +:1024500043F080430093736813F400131FBF04F527 +:10246000805201238DF80D30D2F8AC340EBF8DF8B8 +:102470000D300133C2F8AC34F38803F00F038DF84C +:102480000C304FF0000B9DF80C0000F037FA5FFAAB +:102490008BF3984220D9F2180CA90B44127A03F856 +:1024A0002C2C0BF1010BEEE7012FB6D1E36AD3F828 +:1024B0009820950141BF04F58051D1F89424013250 +:1024C000C1F89424D3F898201007A6D0D3F89850D8 +:1024D000266AC5F30125A9E7EFB9E36AC3F894506A +:1024E00004A8FFF79DFC98E80F0007AD07C52B80F7 +:1024F0000023ADF8183023682046CDE904A91B6CF1 +:1025000004A9984704F5805458B1D4F88C340133A9 +:10251000C4F88C3482E7012F04BFE36AC3F89C50EF +:10252000DEE7D4F890340133C4F89034012075E725 +:10253000F8B505460F4600F5805401263946284671 +:10254000FFF750FF10B184F85364F7E7D4F8543420 +:1025500023B1D4F89C340133C4F89C34F8BD000096 +:10256000F0B5C36A1A6C12F47F0F2BD000F58054BB +:102570001B6CC4F8A03441F26805002347194FF0E2 +:10258000010C00EB43122A445E01117911F0020F95 +:1025900015D0490713D4B959C66AD6F8C8E00CFA61 +:1025A00001F111EA0E0F0AD0C6F8D010117941F0EE +:1025B00004011171D4F888240132C4F8882401334D +:1025C000202BDED1F0BD000010B5254C254B226834 +:1025D00002B338B31A6D12060ED580221A6500F0C8 +:1025E0002DFB50EA01020B4602D0013861F10003D5 +:1025F00002462068FFF794FE1A4A136D1B032AD582 +:1026000023684FF4002103F580531165012283F8FC +:10261000592420E001221A6508221A654FF48062CD +:102620001A6510BD196DC80702D4196D890705D543 +:102630000321196510460021FFF77AFF094B1A6D37 +:10264000100702D41A6DD10605D518221A65206824 +:102650000121FFF76DFF2068BDE81040FFF780BF44 +:10266000D84A00200064004008B5FFF78FFAFFF752 +:1026700077FFBDE80840FFF78FBA0000C36AD3F8C0 +:10268000C40080F40010C0F34050704700F5805043 +:1026900008B5FFF77BFA406C00F068F9FFF77CFAA9 +:1026A00043090CBF0120002008BD000000F5805345 +:1026B00093F8592462B1C16A8A6922F001028A61E1 +:1026C000D3F898240132C3F89824002283F85924BF +:1026D000704700002DE9F74300F58251984610310C +:1026E000FFF754FA002541F2680E4FF0010900F59A +:1026F000805C00EB4514744423795E071CD4DB0630 +:102700001AD5C36A8E69D3F8C87009FA06F63E4234 +:1027100012D04F6801970F689742019F77EB080727 +:102720000AD2C3F8D060237943F004032371DCF8A4 +:1027300084340133CCF884340135202D01F120019B +:10274000D7D103B0BDE8F043FFF726BAF8B51E466F +:10275000002313700F4605461446FFF797FF80F0DD +:10276000010038701EB12846FFF788FF2070F8BDC1 +:102770002DE9F04F85B099460B7801930E461378FA +:102780000293DDE90EBA8046174600F057FA337817 +:1027900004460D4613B93B78002B41D022462B4608 +:1027A0004046FFF797FFFFF75FFFFFF77FFF4B46BE +:1027B0003A463146FFF7CAFF33782BB1019B1BB174 +:1027C000012005B0BDE8F08F3B7813B1029B002BD0 +:1027D000F6D108F5805303935C4575EB0A031FD2CD +:1027E000039BD3F85404D8B10368BBEB0402D96847 +:1027F0006AEB050388474B463A4631464046FFF7A9 +:10280000A5FF337813B1019B002BD9D13B7813B1CD +:10281000029B002BD4D100F011FA04460D46DBE7F1 +:102820000020CEE708B50020FFF7CEFEBDE8084047 +:1028300001F058B908B50120FFF7C6FEBDE8084011 +:1028400001F050B90FB4002004B0704713B56C46C6 +:1028500084E80600031D94E8030083E805000120D6 +:1028600002B010BD73B58568019155B11B885B0737 +:1028700007D4D0E90036DB6B9847019AC1B23046E5 +:10288000A847012002B070BDF0B5866889B0054642 +:102890000C465EB1BDF838305B070AD4D0E900378A +:1028A000DB6B98472246C1B23846B047012009B0D9 +:1028B000F0BD00220023CDE900230023ADF808304D +:1028C0000A4603AB01F10806106851681C4603C4B0 +:1028D0000832B2422346F7D1106820609288A28065 +:1028E00000F0AEF90423ADF808302B68CDE9000103 +:1028F0001B6C694628469847D8E70000082817D976 +:1029000009280CD00A280CD00B280CD00C280CD08D +:102910000D280CD00E2814BF4020302070470C200A +:1029200070471020704714207047182070472020EF +:102930007047000010B5037C044613B9006802F02C +:10294000EFFA204610BD00000023BFF35B8FC36089 +:10295000BFF35B8FBFF35B8F8360BFF35B8F704709 +:10296000BFF35B8F0068BFF35B8F704770B50546A0 +:102970000C30FFF7F5FF05F1080604463046FFF777 +:10298000EFFFA04206D930466D68FFF7E9FF254406 +:10299000281A70BD3046FFF7E3FF201AF9E7000060 +:1029A00070B50546406898B105F10800FFF7D8FFFB +:1029B00005F10C0604463046FFF7D2FF844230464C +:1029C00094BF6D680025FFF7CBFF013C2C44201A13 +:1029D00070BD000038B50C460546FFF7C7FFA042A2 +:1029E00010D305F10800FFF7BBFF04446868B4FB8F +:1029F000F0F100FB1144BFF35B8F0120AC60BFF32B +:102A00005B8F38BD0020FCE72DE9F04114460746F6 +:102A10000D46FFF7C5FF844228BF0446D4B1B8462F +:102A200058F80C6B4046FFF79BFF30442860404647 +:102A30007E68FFF795FF331A9C4203D86C60012033 +:102A4000BDE8F0816B60A41B3B68AB602044E8608C +:102A50000220F5E72046F3E738B50C460546FFF7B8 +:102A60009FFFA04210D305F10C00FFF779FF04444B +:102A70006868B4FBF0F100FB1144BFF35B8F0120E9 +:102A8000EC60BFF35B8F38BD0020FCE72DE9FF4110 +:102A9000884669460746FFF7B7FF6C4606B204EB67 +:102AA000C6060025B44209D06268206808EB05011B +:102AB000FEF7E4FF636808341D44F3E7294638460F +:102AC000FFF7CAFF284604B0BDE8F081F8B5054617 +:102AD0000C300F46FFF744FF05F108060446304668 +:102AE000FFF73EFFA042304688BF6C68FFF738FF13 +:102AF000201A386020B130462C68FFF731FF20449F +:102B0000F8BD000073B5144606460D46FFF72EFFCC +:102B1000844228BF04460190DCB101A93046FFF78A +:102B2000D5FF019B33B93268C5E90233C5E90024FA +:102B300001200CE09C4238BF019428600198686035 +:102B40008442F5D93368AB60241AEC60022002B0ED +:102B500070BD2046FBE700002DE9FF410F466946A6 +:102B6000FFF7D0FF6C4600B204EBC0050026AC4274 +:102B700009D0D4F8048054F8081BB8194246FEF76F +:102B80007DFF4644F3E7304604B0BDE8F081000025 +:102B900038B50546FFF7E0FF044601462846FFF733 +:102BA00019FF204638BD000000B59BB0EFF3098146 +:102BB00068226846FEF762FFEFF30583044B9A6BC9 +:102BC000DA6A9A6A9A6A9A6A9A6A9A6A9B6AFEE7C3 +:102BD00000ED00E000B59BB0EFF309816822684684 +:102BE000FEF74CFFEFF30583044B9A6B9A6A9A6ADF +:102BF0009A6A9A6A9A6A9B6AFEE700BF00ED00E053 +:102C000000B59BB0EFF3098168226846FEF736FFF6 +:102C1000EFF30583034B5A6B9A6A9A6A9A6A9A6A27 +:102C20009B6AFEE700ED00E0FEE700000FB408B588 +:102C3000029801F041FBFEE701F0E6BD01F0BEBDE8 +:102C400001F0BCBD30B5094D0A4491420DD011F8D8 +:102C5000013B5840082340F30004013B2C4013F093 +:102C6000FF0384EA5000F6D1EFE730BD2083B8EDD2 +:102C70002DE9F041C56915B9C161BDE8F0814B6826 +:102C800023F06047C3F38A464FEAD37EC3F38078CC +:102C900016EA230638BF3E46AC462B465A68BEEBC2 +:102CA000D27F22F060440AD0002A18DAA40CB44281 +:102CB00017D19D420FD10D60DEE71346EEE7A74224 +:102CC00007D102F08044C2F3807242450BD054B168 +:102CD000EFE708D2EDE7CCF800100B60CDE7B44287 +:102CE00001D0B442E5D81A689C46002AE5D11960A3 +:102CF000C3E700002DE9F047089D01F007044FEA03 +:102D0000D508224405F0070500EBD1004FF47F49B8 +:102D1000944201D1BDE8F08704F0070705F0070AE7 +:102D200057453E4638BF5646C6F10806111B8E422F +:102D300028BF0E46E10808EBD50E415C13F80EC023 +:102D4000B94029FA06F721FA0AF1FFB28CEA01012B +:102D500047FA0AF739408CEA010C03F80EC03444F4 +:102D60003544D5E780EA0120082341F2210201B26F +:102D70004000002980B203F1FF33B8BF504013F088 +:102D8000FF03F4D17047000038B50C468D18A542FA +:102D900000D138BD14F8011BFFF7E4FFF7E700008E +:102DA00002684AB113680360C388018901339BB28A +:102DB0009942C38038BF03811046704770B588B010 +:102DC000202204460D4668460021FEF769FE204693 +:102DD0000495FFF7E5FF024658B16B46054608AE7D +:102DE0001C4603CCB44228606960234605F10805FF +:102DF000F6D1104608B070BD082817D909280CD0A4 +:102E00000A280CD00B280CD00C280CD00D280CD084 +:102E10000E2814BF4020302070470C20704710202F +:102E2000704714207047182070472020704700001A +:102E3000082817D90C280CD910280CD914280CD91B +:102E400018280CD920280CD930288CBF0F200E2030 +:102E50007047092070470A2070470B2070470C20EC +:102E600070470D207047000010B54B6823B9CA8A1F +:102E700063F30902CA8210BDC4681A681C60C3608B +:102E8000438A013B43824A60EFE700002DE9F84F97 +:102E90001D46CB8A0F46C3F3090106298146924697 +:102EA0000B4630D00020AAB207F119049EB2052EBD +:102EB0001FFA80F80FD8904503F1010306D3FB8A6F +:102EC0000A4462F30903FB8201201AE01AF8006049 +:102ED000E6540130EAE79045F1D2A1F1060B1C233C +:102EE0007C68BBFBF3F203FB12BB1FFA8BF6002CD2 +:102EF00045D14846FFF754FF044638B978606FF073 +:102F00000200BDE8F88F4FF00008E6E700260660F3 +:102F10007860ADB24FF0000B454510D90AEB0803BD +:102F2000221D13F8011B9155B1B208F101081B29AC +:102F30001FFA88F82BD0454506F10106F1D8FB8A27 +:102F4000C3F30902154465F30903BCE7013292B2E9 +:102F50001C462368002BF9D1AB1F0B441C21B3FB8B +:102F6000F1F301339BB29A42D3D2BBF1000FD0D11F +:102F70004846FFF715FF20B9C4F800B0BFE70122AB +:102F8000E7E7C0F800B05E4620600446C1E745456B +:102F9000D5D94846FFF704FF08B92060AFE7C0F86D +:102FA00000B0002620600446B6E700002DE9F04F8F +:102FB0002DED028B83B0CDE90013BDF83C500746E0 +:102FC0009146002A00F092802DB10E9B002B00F05C +:102FD0008D80072D32D807F10C00FFF7E1FE044683 +:102FE00038B96FF00204204603B0BDEC028BBDE897 +:102FF000F08F14220021FEF753FD0E992A4604F1AA +:103000000800FEF73BFD681CC0B2FFF711FFFFF799 +:10301000F3FE207499F80030013814FA80F003F0C0 +:103020001F0363F03F030372009B43F000416160A4 +:1030300038462146FFF71CFE0124D4E700F10C03BB +:103040004FF0000808EE103A4FF0800A464644461A +:1030500018EE100AFFF7A4FE83460028C1D0142200 +:103060000021FEF71DFDC6BB019BABF80830022016 +:103070000E9B00F1080299195BFA82F20130C0B28E +:10308000082801D0AE422AD3FFF7D2FEFFF7B4FEE4 +:1030900099F80020009B411E02F01F0242EA4812EC +:1030A000AE4208BF4FF0400A5BFA81F14AEA020AD9 +:1030B00043F0004281F808A08BF81000CBF8042000 +:1030C00059463846FFF7D4FD0134AE4224B288F0A9 +:1030D00001084FF0000ABBD185E70020C8E711F8CE +:1030E00001CB02F801CB0136B6B2C7E76FF001049D +:1030F00079E70000F8B515460E462822002104465F +:103100001F46FEF7CDFC069B6360B5F5001F079BCD +:10311000A76034BF6A094FF6FF72236204F10C0006 +:1031200097B200239A4205D8002303602782638266 +:10313000A382F8BD0660013330462036F2E7000076 +:1031400003781BB94BB2002BC8BF01707047000059 +:10315000007870472DE9F74FDDF83C90BDF830500E +:103160000D9E9DF83840BDF84070804692469B46C3 +:10317000B9F1000F01D1002F51D11F2C4FD898F871 +:103180000000B0B9072F47D835F0030347D13A46BE +:1031900049464FF6FF70FFF7F7FD20F001002D02C2 +:1031A000400445EA0464400C44EA40244FF6FF73AF +:1031B00021E040EA0520072F40EA0464F6D9002503 +:1031C0004FF6FF73C5F12000A5F120022AFA05F1A0 +:1031D0000BFA00F001432BFA02F211431846C9B270 +:1031E000FFF7C0FD0835402D0346EBD13A4649466E +:1031F000FFF7CAFD0346CDE9009732462146404617 +:10320000FFF7D4FE33780133DBB21F2B88BF0023D6 +:10321000337003B0BDE8F08F6FF00300F9E76FF093 +:103220000100F6E72DE9F04F85B09246DDF84880C1 +:103230000F9D9DF840209DF84490BDF84C700646C7 +:103240009B46B8F1000F01D1002F48D11F2A46D864 +:103250003378002B46D00C0244EA02649DF8381003 +:1032600044EAC93444EA01441C43072F44F0800473 +:1032700032D900234FF6FF72C3F1200CA3F12000D6 +:103280002AFA03F10BFA0CFC41EA0C012BFA00F0CC +:103290000143C9B210460393FFF764FD039B083353 +:1032A000402B0246E8D13A464146FFF76DFD034602 +:1032B000CDE900872A4621463046FFF777FEB9F16F +:1032C000010F06D12B780133DBB21F2B88BF0023FF +:1032D0002B7005B0BDE8F08F4FF6FF73E8E76FF095 +:1032E0000100F6E76FF00300F3E70000C06900B1EA +:1032F00004307047C3691A68C261C2681A60C3604B +:10330000438A013B438270472DE9F041D0F8188091 +:10331000194E14461D464146002709B9BDE8F08103 +:10332000D1E90223A21A65EB0303964277EB03036C +:103330001ED283698B420DD1FFF796FD83691B680E +:103340008361C3680B60438AC1608169013B43822A +:103350008846E2E7FFF788FD0B68C8F80030C368CD +:103360000B60438AC160013B4382D8F80010D4E768 +:1033700088460968D1E700BF80841E002DE9F04F20 +:103380008BB00D46DDF8509014469B4680460028D1 +:1033900000F01981B9F1000F00F01581531E3F2B89 +:1033A00000F21181012A03D1BBF1000F40F00B8123 +:1033B0000023CDE90833B8F81430B5EBC30F4FEA5A +:1033C000C30703D300200BB0BDE8F08F2B199F4239 +:1033D000D8F80C303ABF7F1BFFB227461BB9D8F88C +:1033E0001030002B7AD02F2D4ED8C5F13006B742C1 +:1033F0004FF000032CBFF6B23E4600932946D8F8A2 +:10340000080008AB3246FFF775FCA7EB060A354407 +:103410005FFA8AFAB8F8143003F10053063BDB0078 +:103420000493D8F80C3003933021039B13B1BAF105 +:10343000000F2CD1D8F8100040B1BAF1000F05D020 +:10344000009608AB5246691AFFF754FC38B2002FB9 +:10345000B8D066070AD00AAB03EBD401624211F878 +:10346000083C02F00702134101F8083C082C3CD943 +:10347000102C40F2B580202C40F2B780BBF1000F39 +:1034800000F09C80082334E0BA460026C2E7049B83 +:10349000E02B28BFE02306930B44AB42059314D9DD +:1034A0005A1B03980096924534BF5246D2B2691A0D +:1034B00008AB04300792FFF71DFC079A1644AAEBED +:1034C000020A1544F6B25FFA8AFA049B069A059935 +:1034D0009B1A0493039B1B680393A6E70093D8F8F9 +:1034E000080008AB3A462946AEE7BBF1000F13D0FF +:1034F0000123B4EBC30F6CD0082C12D89DF82030F8 +:10350000621E23FA02F2D50706D54FF0FF3202FA07 +:1035100004F423438DF820309DF8203089F80030E2 +:1035200051E7102C12D8BDF82030621E23FA02F2A7 +:10353000D10706D54FF0FF3202FA04F42343ADF869 +:103540002030BDF82030A9F800303CE7202C0FD8FF +:103550000899631E21FA03F3DA0705D54FF0FF320D +:1035600002FA04F40C430894089BC9F800302AE7D7 +:10357000402C2BD0DDE90865611EC4F12102A4F1C5 +:10358000210326FA01F105FA02F225FA03F31143A9 +:103590001943CB0712D50122A4F12003C4F1200165 +:1035A00002FA03F322FA01F1A240524243EA010374 +:1035B00063EB430332432B43CDE90823DDE90823C2 +:1035C000C9E90023FFE66FF00100FCE66FF0080098 +:1035D000F9E6082CA0D9102CB3D9202CEED8C3E7DB +:1035E000BBF1000FADD0022383E7BBF1000FBBD0CE +:1035F00004237EE730B5012A144638BF0124402C4D +:1036000085B028BF40240025012ACDE9025518D8ED +:103610001B788DF8083063070AD004AB03EBD405A0 +:10362000624215F8083C02F00702934005F8083C96 +:10363000009103462246002102A8FFF75BFB05B07C +:1036400030BD082AE4D9102A03D81B88ADF8083009 +:10365000E1E7202A8DBFD3E900231B680293CDE95F +:103660000223D8E710B5CB681BB98B600B618B8246 +:1036700010BDC4681A681C60C360438A013B438262 +:10368000CA60F0E72DE9F04FD1F8008093B018F050 +:10369000800FCDE90323C8F3C01219BFC8F3C03BA4 +:1036A000C8F306264FF0020B1646B8F1000F044689 +:1036B0000D4680F2D18118F0C043059340F0CC81D3 +:1036C0000B7B002B00F0C881BBF1020F03D0017807 +:1036D000B14240F0C48108F07F0106916AB3C8F39B +:1036E000074A2B44069A93F80390760646EA0B465F +:1036F00046EA82465FEAD91346EA0A06079300F0D3 +:10370000908000220023CDE90A23069B009367687E +:103710005B4652460AA92046B84700287ED0A769D2 +:103720009FB9314604F10C00FFF748FB0746E0B9AA +:103730006FF0020013B0BDE8F08FC8F30F2A18F045 +:103740007F0F08BF0AF0030ACBE73B699E420DD00A +:103750003F68002FF9D1314604F10C00FFF72EFB32 +:1037600007460028E4D0A3693B60A761DDE90A238E +:1037700000264FF6FF70C6F1200E22FA06F103FA7A +:103780000EFEA6F1200C23FA0CFC41EA0E0141EAE0 +:103790000C01C9B2083609920893FFF7E3FA402EEC +:1037A000DDE90832E7D1B882FB7D09F01F06C3F3DB +:1037B00084039B1BD7E9022198B2002BBCBF00F108 +:1037C00020031BB252EA0100C8F304680FD003982B +:1037D000821A049860EB0101A74890424FF0000262 +:1037E0008A4104D3079A002A5BD0012B23DDFA7D9E +:1037F0004FEA890302F0030203F07C031343FB75D5 +:1038000039462046FFF730FB079BA3B9FB7DC3F386 +:103810008402013262F38603FB7504E06FF00B0053 +:1038200088E7A76917B96FF00C0083E73B699E42F0 +:10383000BAD03F68F6E719F0400F32D0039BBB6067 +:10384000049BFB60142200210DA8FEF729F9039BBD +:103850000A93049B0B932B1D0C932B7BADF83EA07E +:10386000013BDBB2ADF83C30069B8DF8433094F859 +:1038700024308DF840B083F001038DF844308DF88A +:103880004160A3688DF842800AA920469847FB7DD5 +:10389000C3F38403013303F01F039B02FB82002068 +:1038A00048E7FB7DC9F34012B2EBD31F40F0DA804A +:1038B000C3F38403B34240F0D88007992B7B4FEACF +:1038C0009912002934D0D20741D4032B40F2D08082 +:1038D000039BBB60049BFB602B7BAE1D033BDBB2F9 +:1038E0003246394604F10C00FFF7D0FA00280DDA11 +:1038F00020463946FFF7B8FAFB7DC3F38403013352 +:1039000003F01F039B02FB82032013E7AB883B837A +:103910002A7B033AB88AD2B23146FFF735FAFB7DEB +:10392000B882DA43C2F3C01262F3C713FB75B6E77D +:103930006AB92E1D013BDBB23246394604F10C0058 +:10394000FFF7A4FA0028D3DB2A7B013AE2E7F98AE1 +:10395000C1F30901013B0529DAB259D8281D00231A +:1039600007F11A0C9A4208D910F801EB0CF801E0A3 +:10397000013101330629DBB2F4D103990A9104998C +:103980000B91934207F11A010C9138BF0433796807 +:103990000D9134BF55FA83F300230E93FB8AADF8E3 +:1039A0003EA0C3F309031A44069B8DF8433094F8F4 +:1039B0002430ADF83C2083F001038DF8443000231F +:1039C0008DF840B08DF841608DF842807B602A7B95 +:1039D000B88A013A291DFFF7D7F93B8BB882834299 +:1039E00003D1A3680AA92046984720460AA9FFF7F1 +:1039F00039FEFB7DB88AC3F38403013303F01F0350 +:103A00009B02FB823B8B984214BF1120002091E661 +:103A10007B68002BB1D0062001E01C306346D3F850 +:103A200000C0BCF1000FF8D1091A081D05F1040C03 +:103A300000EB030905989DF8143001EB000EBEF170 +:103A40001B0F9AD89A4298D91CF8013B09F8013B00 +:103A5000059B01330593EDE76FF009006AE66FF00F +:103A60000A0067E66FF00D0064E66FF00E0061E695 +:103A70006FF00F005EE600BF80841E00EFF3098345 +:103A800005494A6B22F001024A63683383F30988CF +:103A9000002383F31188704700EF00E0202080F3BB +:103AA000118862B60C4B0D4AD96821F4E061090413 +:103AB000090C0A43DA60D3F8FC20094942F080720D +:103AC000C3F8FC200A6842F001020A601022DA778B +:103AD00083F82200704700BF00ED00E00003FA0504 +:103AE000001000E010B5202383F311880E4B5B68B3 +:103AF00013F4006314D0F1EE103AEFF30984683C3C +:103B00004FF08073E361094BDB6B236684F3098814 +:103B100000F084FB10B1064BA36110BD054BFBE721 +:103B200083F31188F9E700BF00ED00E000EF00E04B +:103B30004B0600084E060008026843681143016006 +:103B400003B1184770470000024A136843F0C003EE +:103B5000136070470038014013B50E4C204600F04A +:103B60009FFA04F114000C49009400234FF4807272 +:103B700000F060F9094B0A4900944FF4807204F197 +:103B8000380000F0D9F9074A074BC4E9172302B0FF +:103B900010BD00BFE44A0020504B0020493B000804 +:103BA000504C002000380140007A030A30B5037CF5 +:103BB000234C002918BF0C46012B0FD1214B9842F2 +:103BC0000CD1214B1A6E42F480421A66D3F8802041 +:103BD00042F48042C3F88020D3F880302268036E1C +:103BE000C16D846603EB5203B3FBF2F36268150404 +:103BF00042BF23F0070503F0070343EA4503CB6008 +:103C0000A36843F040034B60E36843F001038B601B +:103C100042F4967343F001030B604FF0FF330B62E5 +:103C2000510505D512F0102205D0B2F1805F04D005 +:103C300080F8643030BD7F23FAE73F23F8E700BF08 +:103C400080510008E44A0020001002402DE9F047AE +:103C5000C66D3768F46934622107054618D014F040 +:103C6000080118BF8021E20748BF41F02001A307E7 +:103C700048BF41F04001600748BF41F480712023F4 +:103C800083F31188281DFFF757FF002383F3118862 +:103C9000E2050AD5202383F311884FF40071281D13 +:103CA000FFF74AFF002383F311884FF020094FF0FC +:103CB000000A14F0200838D13B0616D54FF0200931 +:103CC00005F1380A200610D589F31188504600F016 +:103CD00067F9002836DA0821281DFFF72DFF27F0A5 +:103CE00080033360002383F31188790614D56206BC +:103CF00012D5202383F31188D5E913239A4208D1E2 +:103D00002B6C33B11021281D27F04007FFF714FF5B +:103D10003760002383F31188E30618D5AA6E136970 +:103D2000ABB1BDE8F0475069184789F31188736A51 +:103D300095F864102846194000F0CCF98AF31188F0 +:103D4000F469B6E7B06288F31188F469BAE7BDE8B0 +:103D5000F087000000F1604303F561430901C9B237 +:103D600083F80013012200F01F039A4043099B00CF +:103D700003F1604303F56143C3F880211A60704783 +:103D8000F8B5154682680669AA420B46816938BFB4 +:103D90008568761AB54204460BD218462A46FDF7C6 +:103DA0006DFEA3692B44A361A3685B1BA360284637 +:103DB000F8BD0CD918463246FDF760FEAF1BE1682E +:103DC0003A463044FDF75AFEE3683B44EBE71846B9 +:103DD0002A46FDF753FEE368E5E700008368934257 +:103DE000F7B51546044638BF8568D0E90460361A31 +:103DF000B5420BD22A46FDF741FE63692B4463614D +:103E0000A36828465B1BA36003B0F0BD0DD9324602 +:103E10000191FDF733FE0199E068AF1B3A4631444A +:103E2000FDF72CFEE3683B44E9E72A46FDF726FE52 +:103E3000E368E4E710B50A440024C361029B846090 +:103E4000C0E90000C0E90511C1600261036210BD54 +:103E500008B5D0E90532934201D1826882B98268FF +:103E6000013282605A1C42611970D0E904329A42D0 +:103E700024BFC3684361002100F0A0FA002008BD00 +:103E80004FF0FF30FBE7000070B5202304460E46DC +:103E900083F31188A568A5B1A368A269013BA3605B +:103EA000531CA36115782269934224BFE368A36180 +:103EB000E3690BB120469847002383F31188284615 +:103EC00007E03146204600F069FA0028E2DA85F37F +:103ED000118870BD2DE9F74F04460E4617469846E7 +:103EE000D0F81C904FF0200A8AF311884FF0000B95 +:103EF000154665B12A4631462046FFF741FF034685 +:103F000060B94146204600F049FA0028F1D000236C +:103F100083F31188781B03B0BDE8F08FB9F1000F6F +:103F200003D001902046C847019B8BF31188ED1AFE +:103F30001E448AF31188DCE7C0E90511C160C36142 +:103F40001144009B8260C0E9000001610362704778 +:103F5000F8B504460D461646202383F31188A7685A +:103F6000A7B1A368013BA36063695A1C62611D701D +:103F7000D4E904329A4224BFE3686361E3690BB178 +:103F800020469847002080F3118807E031462046FC +:103F900000F004FA0028E2DA87F31188F8BD000087 +:103FA000D0E905239A4210B501D182687AB98268B6 +:103FB000013282605A1C82611C7803699A4224BFD4 +:103FC000C3688361002100F0F9F9204610BD4FF06D +:103FD000FF30FBE72DE9F74F04460E46174698469B +:103FE000D0F81C904FF0200A8AF311884FF0000B94 +:103FF000154665B12A4631462046FFF7EFFE0346D7 +:1040000060B94146204600F0C9F90028F1D00023EC +:1040100083F31188781B03B0BDE8F08FB9F1000F6E +:1040200003D001902046C847019B8BF31188ED1AFD +:104030001E448AF31188DCE702684368114301607B +:1040400003B11847704700001430FFF743BF00006A +:104050004FF0FF331430FFF73DBF00003830FFF75B +:10406000B9BF00004FF0FF333830FFF7B3BF000097 +:104070001430FFF709BF00004FF0FF311430FFF795 +:1040800003BF00003830FFF763BF00004FF0FF327E +:104090003830FFF75DBF000000207047FFF75CBDC0 +:1040A000044B03600023C0E902334360012303741F +:1040B000704700BF9851000810B52023044683F3D1 +:1040C0001188FFF773FD02232374002383F3118803 +:1040D00010BD000038B5C36904460D461BB9042164 +:1040E0000844FFF7A9FF294604F11400FFF7B0FECA +:1040F000002806DA201D4FF48061BDE83840FFF744 +:104100009BBF38BD024B0022C3E900339A60704761 +:10411000504D0020002303748268054B1B6899688A +:104120009142FBD25A680360426010605860704749 +:10413000504D002008B5202383F31188037C032B06 +:1041400005D0042B0DD02BB983F3118808BD43692A +:1041500000221A604FF0FF334361FFF7DBFF0023BB +:10416000F2E7D0E9003213605A60F3E700230374EA +:104170008268054B1B6899689142FBD85A680360B6 +:104180004260106058607047504D0020054B19691F +:104190000874186802681A60536018610123037478 +:1041A000FCF73EBA504D002030B54B1C0B4D87B08C +:1041B000044610D02B690A4A01A800F019F92046DC +:1041C000FFF7E4FF049B13B101A800F04DF92B6940 +:1041D000586907B030BDFFF7D9FFF8E7504D002010 +:1041E0003541000838B50C4D41612B6981689A68EA +:1041F0009142044603D8BDE83840FFF78BBF18460C +:10420000FFF7B4FF01232C61014623742046BDE86B +:104210003840FCF705BA00BF504D0020044B1A6827 +:104220001B6990689B68984294BF002001207047EA +:10423000504D002010B5084C236820691A68226090 +:104240005460012223611A74FFF790FF0146206930 +:10425000BDE81040FCF7E4B9504D002008B5FFF769 +:10426000DDFF18B1BDE80840FFF7E4BF08BD00005E +:10427000FFF7E0BFFEE7000010B50C4CFFF742FF70 +:1042800000F0A8F80A498022204600F03DF80123FA +:1042900044F8180C0374FFF701FC002383F3118822 +:1042A00062B60448BDE8104000F04EB8784D0020DA +:1042B000C0510008D051000808B572B6034B5862CF +:1042C00000F06CFA00F020FBFEE700BF504D00202C +:1042D00000F004B9EFF3118020B9EFF30583202239 +:1042E00082F311887047000010B530B9EFF30584F0 +:1042F000C4F3080414B180F3118810BDFFF7AEFFBA +:1043000084F31188F9E7000082600222028270477C +:104310008368A3F17C0243F80C2C026943F83C2C1F +:10432000426943F8382C074A43F81C2CC26843F80A +:10433000102C022203F8082C002203F8072CA3F10A +:10434000180070473906000810B5202383F3118840 +:10435000FFF7DEFF00210446FFF744FF002383F34D +:104360001188204610BD0000024B1B6958610F20C8 +:10437000FFF70CBF504D0020202383F31188FFF777 +:10438000F3BF000008B50146202383F311880820FD +:10439000FFF70AFF002383F3118808BD49B1064BDC +:1043A00042681B6918605A60136043600420FFF77D +:1043B000FBBE4FF0FF307047504D0020036898421D +:1043C00006D01A680260506059611846FFF7A2BE15 +:1043D00070470000054B03F11402C3E905224FF0BA +:1043E000FF310022C3E90712704700BF504D002083 +:1043F00070B51C4EC0E9032305460C4600F0FEFADA +:10440000334653F8142F9A420DD13062C5E9012486 +:104410002A600A2C2CBF00190A30C6E90555BDE8F0 +:10442000704000F0D9BA316A431AE31838BF1C460D +:104430009368A34202D9081900F0DCFA73699A68FC +:1044400094420CD85A68AC602B606A6015609A6818 +:104450005D60121B9A604FF0FF33F36170BD1B6803 +:10446000A41AECE7504D002038B51B4C6369984204 +:104470000DD0D0E9003213605A6000228168C2601A +:104480009A680A449A604FF0FF33E36138BD2246D0 +:10449000036842F8143F002193425A60C16003D17F +:1044A000BDE8384000F0A0BA9A688168256A0A44DD +:1044B0009A6000F0A3FA63699A68411B8A42E5D9C1 +:1044C000AB181D1A092D206A98BF01F10A02BDE838 +:1044D0003840104400F08EBA504D00202DE9F041D4 +:1044E000184C002704F11406656900F087FA236A66 +:1044F000AA68C11A8A4215D813442362D5E900324A +:1045000013605A606369D5F80C80EF60B34201D143 +:1045100000F06AFA87F311882869C047202383F3E3 +:104520001188E1E76169B14209D013441B1ABDE863 +:10453000F0410A2B2CBFC0180A3000F05BBABDE86E +:10454000F08100BF504D002000207047FEE70000C2 +:10455000704700004FF0FF3070470000BFF34F8FEF +:10456000024A1369DB03FCD4704700BF00200240FD +:1045700008B5094B1B7873B9FFF7F0FF074B5A6971 +:10458000002ABFBF064A9A6002F188329A601A6810 +:1045900022F480621A6008BD184F002000200240FB +:1045A0002301674508B50B4B1B7893B9FFF7D6FF7E +:1045B000094B5A6942F000425A611A6842F480522B +:1045C0001A601A6822F480521A601A6842F48062F3 +:1045D0001A6008BD184F0020002002407F289ABFB3 +:1045E00000F58030C0020020704700004FF40060EA +:1045F00070470000802070477F2808B50BD8FFF770 +:10460000EDFF00F500630268013204D104308342FB +:10461000F9D1012008BD0020FCE700007F2838B553 +:10462000044626D8FFF756FEFFF798FFFFF7A0FFD6 +:10463000114BF3221A6102225A615A6942EAC402FA +:104640005A615A6942F480325A6105462046FFF7A2 +:1046500085FF4FF40061FFF7C1FF00F051F92846D4 +:10466000FFF7A0FFFFF740FE2046BDE83840FFF708 +:10467000C3BF002038BD00BF0020024040EA020353 +:1046800013F007032DE9F04705460C46164606D001 +:10469000324B40F2FB221A600020BDE8F0878118FF +:1046A0002F4A91420CD92D4A4FF440711160F3E723 +:1046B0002B1D1B686268934208D1083E08350834F8 +:1046C000072E19D92A6823689A42F1D0FFF702FE13 +:1046D000FFF74EFFFFF742FF04F10801214C4FF0B6 +:1046E00001084FF00009012EA1F1080708D8FFF7D3 +:1046F00059FFFFF7F9FD01E0002EE7D10120CCE7DB +:10470000C4F81480AA4651F8083C4AF8043B51F812 +:10471000043C6B60FFF722FFC4F814902A6851F83C +:10472000083C9A420ED00D4B40F226321A600E4BD6 +:104730001D600E4B1E600E4B1F60FFF733FFFFF72F +:10474000D3FDA9E7DAF800A051F8043C9A4501F13D +:104750000801E8D1083E0835C5E700BF144F002026 +:104760000000040800200240084F0020104F0020E5 +:104770000C4F0020084908B50B7828B11BB9FFF78A +:10478000F7FE01230B7008BD002BFCD0BDE80840EC +:104790000870FFF707BF00BF184F002008B54FF49F +:1047A000C0314FF0005000F0ADF8BDE808404FF4C4 +:1047B00080414FF0805000F0A5B8000070B582B085 +:1047C000FFF788FD0E4E054600F018F9326890425A +:1047D00037BF0C4A0B49516814682EBFD1E900411C +:1047E000013151600419034641F10001284601914D +:1047F0003360FFF779FD0199204602B070BD00BF1C +:104800001C4F0020204F002070B582B0FFF762FDE2 +:10481000104E054600F0F2F83268904237BF0E4A5B +:104820000D49516814682EBFD1E900410131516032 +:10483000041941F100010346284601913360FFF756 +:1048400053FD01994FF47A7200232046FBF7D0FC08 +:1048500002B070BD1C4F0020204F00200244D2B295 +:10486000904200D17047431C800000F1804000F569 +:104870001450006841F8040BD8B2F1E7124B10B5A0 +:10488000D3F89040240409D4D3F89040C3F8904062 +:10489000D3F8904044F40044C3F890400B4C236894 +:1048A000024443F480732360D2B2904200D110BD21 +:1048B000431C800000F1804000F5145051F8044B77 +:1048C0000460D8B2F1E700BF001002400070004061 +:1048D00007B5012201A90020FFF7C0FF019803B02E +:1048E0005DF804FB13B50446FFF7F2FFA04205D0C4 +:1048F000012201A900200194FFF7C0FF02B010BD02 +:10490000704700007047000070470000074B45F2F9 +:1049100055521A6002225A6040F6FF729A604CF6B5 +:10492000CC421A60024B01221A70704700300040DE +:104930002C4F0020034B1B781BB1034B4AF6AA22D5 +:104940001A6070472C4F002000300040054B1A6859 +:1049500032B902F1804202F50432D2F894201A6092 +:10496000704700BF284F0020024B4FF40002C3F8ED +:10497000942070470010024008B5FFF7E7FF024B94 +:104980001868C0F3407008BD284F00207047000031 +:10499000FEE700000A4B0B480B4A90420BD30B4B2F +:1049A000DA1C121AC11E22F003028B4238BF002209 +:1049B0000021FDF775B853F8041B40F8041BECE721 +:1049C00044530008B84F0020B84F0020B84F0020D3 +:1049D0007047000000F078B84FF080430022586321 +:1049E0001A610222DA6070474FF080430022DA60D9 +:1049F000704700004FF08043586370474FF080438A +:104A0000586A70474B6843608B688360CB68C360AB +:104A10000B6943614B6903628B6943620B680360F6 +:104A20007047000008B5204BDA6A42F07F02DA6274 +:104A3000DA6A22F07F02DA62DA6ADA6C42F07F0226 +:104A4000DA64DA6E42F07F02DA66184ADB6E1146EB +:104A50004FF09040FFF7D6FF02F11C0100F5806097 +:104A6000FFF7D0FF02F1380100F58060FFF7CAFFC1 +:104A700002F1540100F58060FFF7C4FF02F17001FC +:104A800000F58060FFF7BEFF02F18C0100F5806049 +:104A9000FFF7B8FF02F1A80100F58060FFF7B2FF51 +:104AA000BDE8084000F064B800100240E85100087A +:104AB00008B500F003FAFFF7DFFBBDE80840FFF799 +:104AC00045BF0000704700000F4B9A6D42F0010295 +:104AD0009A659A6F42F001029A670C4A9B6F93683D +:104AE00043F0010393604FF08043A7229A624FF096 +:104AF000FF32DA6200229A615A63DA605A60012258 +:104B00005A611A60704700BF00100240002004E0A4 +:104B10004FF0804208B51169D3680B40D9B2C94340 +:104B20009B07116107D5202383F31188FFF7D0FB82 +:104B3000002383F3118808BD08B50B4BD3F89020F0 +:104B400012F4407F1FBF4FF48032C3F89020002240 +:104B5000C3F89020D3F89020C3F8902000F086F995 +:104B6000024B00225A6008BD001002400070004055 +:104B7000484B4FF0FF319A6A99629A6A00229A6212 +:104B8000986AD86A60F07F00D862D86A00F07F0027 +:104B9000D862D86A186B1963186B1A63186B986B14 +:104BA0009963986B9A63986BD86BD963D86BDA6307 +:104BB000D86B186C1964196C1A641A6C9A6D42F0EF +:104BC00080529A659A6F22F080529A679A6F324AA1 +:104BD0004FF400711160516911F48061FBD14FF401 +:104BE0000040516090604FF48070D160C2F8800046 +:104BF000116251629162D162116351639163D16319 +:104C0000116451649164D16411655165D3F89820A1 +:104C100042F00102C3F89820D3F898209007FBD502 +:104C20001A6842F480321A601A689103FCD51A4956 +:104C30000A6842F480720A60184ADA601A6842F020 +:104C400080721A601A689201FCD5002214499A6099 +:104C5000C3F888101349C3F89C20134A0A600A68F5 +:104C600002F00F02042AFAD19A6842F003029A6015 +:104C70009A6802F00C020C2AFAD11A6E42F0010274 +:104C80001A66D3F8802042F00102C3F88020D3F8DE +:104C9000803070470010024000700040032A61011C +:104CA000550100500020024004070400074A08B5DF +:104CB000536903F00103536123B1054A13680BB133 +:104CC00050689847BDE80840FEF70CBF000401405B +:104CD000304F0020074A08B5536903F002035361BF +:104CE00023B1054A93680BB1D0689847BDE80840E6 +:104CF000FEF7F8BE00040140304F0020074A08B517 +:104D0000536903F00403536123B1054A13690BB1DE +:104D100050699847BDE80840FEF7E4BE0004014032 +:104D2000304F0020074A08B5536903F00803536168 +:104D300023B1054A93690BB1D0699847BDE8084093 +:104D4000FEF7D0BE00040140304F0020074A08B5EE +:104D5000536903F01003536123B1054A136A0BB181 +:104D6000506A9847BDE80840FEF7BCBE0004014009 +:104D7000304F0020164B10B55C6904F478725A610C +:104D8000A30604D5134A936A0BB1D06A984760060C +:104D900004D5104A136B0BB1506B9847210604D50C +:104DA0000C4A936B0BB1D06B9847E20504D5094AC6 +:104DB000136C0BB1506C9847A30504D5054A936C4E +:104DC0000BB1D06C9847BDE81040FEF78BBE00BF1A +:104DD00000040140304F0020194B10B55C6904F409 +:104DE0007C425A61620504D5164A136D0BB1506DB1 +:104DF0009847230504D5134A936D0BB1D06D98479E +:104E0000E00404D50F4A136E0BB1506E9847A1040D +:104E100004D50C4A936E0BB1D06E9847620404D54A +:104E2000084A136F0BB1506F9847230404D5054A05 +:104E3000936F0BB1D06F9847BDE81040FEF752BE9C +:104E400000040140304F002008B50348FEF7FEFE85 +:104E5000BDE80840FEF746BEE44A002008B5FFF76B +:104E600057FEBDE80840FEF73DBE0000062108B52C +:104E70000846FEF76FFF06210720FEF76BFF0621AD +:104E80000820FEF767FF06210920FEF763FF0621D1 +:104E90000A20FEF75FFF06211720FEF75BFF0621C1 +:104EA0002820FEF757FF07211C20FEF753FFBDE81F +:104EB00008400C212520FEF74DBF000008B5FFF784 +:104EC0003BFE00F009F8FFF7E9F8FFF7FBFDBDE84E +:104ED0000840FFF77FBD00000023054A1946013353 +:104EE000102BC2E9001102F10802F8D1704700BF8F +:104EF000304F00200B460146184600F003B8000072 +:104F000000F00EB810B5054C13462CB10A46014608 +:104F10000220AFF3008010BD2046FCE70000000037 +:104F2000024B0146186800F035B800BF2823002066 +:104F300010B501390244904201D1002005E0037808 +:104F400011F8014FA34201D0181B10BD0130F2E748 +:104F50002DE9F041A3B1C91A17780144044603F1C1 +:104F6000FF3C8C42204601D9002009E00578BD4273 +:104F700004F10104F5D10CEB0405D618A54201D1CA +:104F8000BDE8F08115F8018D16F801EDF045F5D07A +:104F9000E7E7000037B5002944D051F8043C019000 +:104FA000002BA1F10404B8BFE41800F047F81E4A32 +:104FB0000198136833B96360146003B0BDE83040F2 +:104FC00000F042B8A34208D9256861198B4201BF9D +:104FD00019685B6849192160EDE71A465B680BB1F7 +:104FE000A342FAD911685518A5420BD1246821446F +:104FF0005418A3421160E0D11C685B6853602144DF +:105000001160DAE702D90C230360D6E7256861193D +:105010008B4204BF19685B68636004BF4919216053 +:105020005460CAE703B030BDB04F0020034611F80A +:10503000012B03F8012B002AF9D17047014800F039 +:1050400009B800BFB44F0020014800F005B800BF08 +:10505000B44F002070470000704700006F72672E49 +:105060006172647570696C6F742E6D526F2D4D3165 +:1050700030303935000000004E6F206170702073B1 +:1050800069670A00426164206677206C656E677408 +:10509000682025750A0042616420626F6172645F56 +:1050A00069642025752073686F756C6420626520C3 +:1050B00025750A0042616420667720646573637217 +:1050C0006970746F72206C656E6774682025750A4C +:1050D0000042616420617070204352432030782583 +:1050E0003038783A307825303878203078253038A4 +:1050F000783A3078253038780A00476F6F64206638 +:1051000069726D776172650A0040A2E4F16468918A +:105110000600000053544D333247343F3F00000037 +:105120004261642043414E496661636520696E6453 +:1051300065782E000000000000000000A920000893 +:10514000B11B000871270008A51B0008211C0008DE +:105150003D1E0008991D0008E91B0008ED1B000812 +:10516000A91B0008C51B0008AD1B0008FD1D000899 +:10517000D11B00084D280008DD1B0008D11D0008C8 +:105180000096000000000000000000000000000089 +:105190000000000000000000000000006540000862 +:1051A000514000088D400008794000088540000803 +:1051B000714000085D40000849400008994000081F +:1051C0006D61696E0000000069646C65000000009C +:1051D000C8510008904D0020084F00200100000039 +:1051E00075420008000000000001A82A000000002D +:1051F000AAAABEAA00001424EFFF000000000000CD +:10520000709709000000000000000000AAAAAAAAE6 +:1052100000000000FFFF0000000000000000000090 +:105220000000000000000000AAAAAAAA00000000D6 +:10523000FFFF000000000000000000000000000070 +:1052400000000000AAAAAAAA00000000FFFF0000B8 +:10525000000000000000000000000000000000004E +:10526000AAAAAAAA00000000FFFF00000000000098 +:10527000000000000000000000000000AAAAAAAA86 +:1052800000000000FFFF0000000000000000000020 +:105290000000000000000000AAAAAAAA0000000066 +:1052A000FFFF0000000000000000000074AFFF7F5F +:1052B00001000000000000001104000000000000D8 +:1052C0000088030000000000FE2A0100D204000054 +:1052D000FF00000000000000145100083F00000023 +:1052E0002C2300200000000000000000000000004F +:1052F00000000000000000000000000000000000AE +:10530000000000000000000000000000000000009D +:10531000000000000000000000000000000000008D +:10532000000000000000000000000000000000007D +:10533000000000000000000000000000000000006D +:045340000000000069 :00000001FF diff --git a/Tools/bootloaders/revo-mini-sd_bl.bin b/Tools/bootloaders/revo-mini-sd_bl.bin new file mode 100755 index 00000000000..52cc65dd781 Binary files /dev/null and b/Tools/bootloaders/revo-mini-sd_bl.bin differ diff --git a/Tools/bootloaders/revo-mini-sd_bl.elf b/Tools/bootloaders/revo-mini-sd_bl.elf new file mode 100755 index 00000000000..2ec43778f8c Binary files /dev/null and b/Tools/bootloaders/revo-mini-sd_bl.elf differ diff --git a/Tools/bootloaders/revo-mini-sd_bl.hex b/Tools/bootloaders/revo-mini-sd_bl.hex new file mode 100644 index 00000000000..1e27d0ad396 --- /dev/null +++ b/Tools/bootloaders/revo-mini-sd_bl.hex @@ -0,0 +1,886 @@ +:020000040800F2 +:1000000000060020E1010008610E0008E10D000873 +:10001000390E0008E10D00080D0E0008E30100088C +:10002000E3010008E3010008E3010008C120000823 +:10003000E3010008E3010008E3010008E301000810 +:10004000E3010008E3010008E3010008E301000800 +:10005000E3010008E301000889310008B531000818 +:10006000E13100080D32000839320008E3010008D0 +:10007000E3010008E3010008E3010008E3010008D0 +:10008000E3010008E3010008E3010008E3010008C0 +:10009000E3010008E3010008E301000865320008FD +:1000A000E3010008E3010008E3010008E3010008A0 +:1000B000FD2F0008E3010008E3010008E301000848 +:1000C000E3010008E3010008E3010008E301000880 +:1000D000E3010008E3010008E3010008E301000870 +:1000E000CD320008E3010008E3010008E301000845 +:1000F000E3010008E3010008E3010008E301000850 +:10010000E3010008E3010008E3010008E30100083F +:10011000E3010008E3010008E3010008E30100082F +:10012000E3010008E3010008E3010008E30100081F +:10013000E3010008E3010008E3010008E30100080F +:10014000E3010008E3010008E3010008F9270008C3 +:10015000E3010008E3010008E3010008E3010008EF +:10016000E3010008E3010008E3010008E3010008DF +:10017000E3010008E3010008E3010008E3010008CF +:10018000E3010008E3010008E3010008E3010008BF +:10019000E3010008E3010008E3010008E3010008AF +:1001A000E3010008E3010008E3010008E30100089F +:1001B000E3010008E3010008E3010008E30100088F +:1001C000E3010008E3010008E3010008E30100087F +:1001D000E3010008E3010008E3010008E30100086F +:1001E00002E000F000F8FEE772B63A4880F30888B3 +:1001F000394880F3098839484EF60851CEF200019B +:10020000086040F20000CCF200004EF63471CEF2ED +:1002100000010860BFF34F8FBFF36F8F40F2000003 +:10022000C0F2F0004EF68851CEF200010860BFF334 +:100230004F8FBFF36F8F4FF00000E1EE100A4EF6C4 +:100240003C71CEF200010860062080F31488BFF3F1 +:100250006F8F01F0B5FF01F091FF02F033FE4FF018 +:1002600055301F491B4A91423CBF41F8040BFAE745 +:100270001C49194A91423CBF41F8040BFAE71A495C +:100280001A4A1B4B9A423EBF51F8040B42F8040B2A +:10029000F8E700201749184A91423CBF41F8040B87 +:1002A000FAE701F06FFF02F061FE144C144DAC420E +:1002B00003DA54F8041B8847F9E700F041F8114CC1 +:1002C000114DAC4203DA54F8041B8847F9E701F0FA +:1002D00057BF000000060020002200200000000898 +:1002E0000000002000060020F83600080022002050 +:1002F0004022002040220020A42D0020E001000820 +:10030000E0010008E0010008E00100082DE9F04FDD +:100310002DED108AC1F80CD0C3689D46BDEC108A43 +:10032000BDE8F08F002383F311882846A047002002 +:1003300001F0E8FAFEE701F07DFA00DFFEE70000D9 +:1003400038B501F08FFE054601F0B4FE0446D8B979 +:100350000F4B9D421AD001339D4218BF044641F213 +:10036000883504BF01240025002001F085FE0CB172 +:1003700000F056F800F00AFD00F086FB284600F079 +:10038000A7F800F04DF8F9E70025EDE70546EBE7A3 +:10039000010007B008B500F049FBA0F12003584266 +:1003A000584108BD07B541F21203022101A8ADF87A +:1003B000043000F059FB03B05DF804FB10B52023B6 +:1003C00083F311881248C3680BB101F021FB114A75 +:1003D0000F4800234FF47A7101F0DEFA002383F313 +:1003E00011880D4C236813B12368013B23606368B7 +:1003F00013B16368013B6360084B1B7833B96368D2 +:1004000023B9022000F034FC3223636010BD00BF2A +:1004100040220020BD0300085C230020542200205D +:10042000254B264A10B51C461968013142D00433C9 +:100430009342F9D16268224B9A423BD9214B9B6887 +:1004400003F1006303F580339A4233D2002000F0B9 +:1004500035FB1D4B0220187000F0FCFB1B4B1A6C87 +:1004600000221A64196E1A66196E596C5A64596E14 +:100470005A665A6E5A6942F080025A615A6922F0ED +:1004800080025A615A691A6942F000521A611A6967 +:1004900022F000521A611B6972B64FF0E02320214E +:1004A000C3F8084DD4E9003281F311889D4683F3E7 +:1004B0000888104710BD00BF000001082000010897 +:1004C000FFFF0008002200205422002000380240D4 +:1004D0002DE9F04F93B0A94B00902022FF210AA8EC +:1004E0009D6800F0FDFBA64A1378A3B9A548012139 +:1004F000C3601170202383F31188C3680BB101F02E +:1005000087FAA14A9F4800234FF47A7101F044FA18 +:10051000002383F31188009B9C4A03B113609C491C +:10052000009C00230B70536098469B461E469A46DB +:10053000012000F08FFB24B1944B1B68002B00F0CE +:100540001682002000F072FA0390039B002BF2DB6E +:10055000012000F06FFB039B213B162BE8D801A282 +:1005600052F823F0C1050008E90500087D060008DF +:1005700031050008310500083105000811070008A1 +:10058000E3080008FD0700085F0800088708000866 +:10059000AD08000831050008BF0800083105000853 +:1005A00031090008610600083105000875090008D6 +:1005B000CD05000861060008310500085F08000845 +:1005C0000220FFF7E7FE002840F0FB81009B02219C +:1005D000B8F1000F08BF1C4605A841F21233ADF870 +:1005E000143000F041FAA3E74FF47A7000F01EFADD +:1005F000071EEBDB0220FFF7CDFE0028E6D0013F0F +:10060000052F00F2E081DFE807F0030A0D10133632 +:1006100005230593042105A800F026FA17E05748A2 +:100620000421F9E75B480421F6E75B480421F3E77E +:100630004FF01C09484600F043FA09F104090590FF +:10064000042105A800F010FAB9F12C0FF2D1012015 +:1006500000FA07F747EA0B0B5FFA8BFB4FF0000A33 +:1006600000F08AFB26B10BF00B030B2B08BF002414 +:10067000FFF798FE5CE749480421CDE7002EA5D09E +:100680000BF00B030B2BA1D10220FFF783FE0746D3 +:1006900000289BD001203E4E00F010FA022030705E +:1006A00000F0D8FA4FF000085FFA88F9484600F0E9 +:1006B00015FA044690B1484600F020FA08F1010806 +:1006C0000028F1D1B846044641F21213022105A8D0 +:1006D000ADF814303E4600F0C7F929E701230220A7 +:1006E000337000F0A7FA2546244B9B68AB4207D92C +:1006F000284600F0E5F9013040F068810435F3E761 +:10070000234B00251D70214BB8465D603E46A7E790 +:10071000002E3FF45BAF0BF00B030B2B7FF456AFB7 +:100720001B4B0220187000F095FA322000F07EF981 +:10073000B0F10009FFF64AAF19F003077FF446AFA6 +:100740000E4A926809EB050393423FF63FAFB9F5B5 +:10075000807F3FF73BAF124B0193B94522DD4FF449 +:100760007A7000F063F90390039A002AFFF62EAF27 +:10077000019B039A03F8012B0137EDE700220020CB +:100780005823002040220020BD0300085C230020E5 +:100790005422002004220020082200200C220020E5 +:1007A00058220020C820FFF7F5FD074600283FF437 +:1007B0000DAF1F2D11D8C5F120024A450AAB25F017 +:1007C000030028BF4A4683490192184400F062FAA8 +:1007D000019A8048FF2100F083FA4FEAA9037D497E +:1007E0000193C9F38702284600F082FA06460028E2 +:1007F0003FF46AAF019B05EB830531E70220FFF769 +:10080000C9FD00283FF4E2AE00F0A2F900283FF451 +:10081000DDAE0027B946704B9B68BB4218D91F2F2D +:1008200011D80A9B01330ED027F0030312AA1344F8 +:1008300053F8203C05934846042205A900F012FB1A +:1008400004378146E7E7384600F03AF90590F2E7C9 +:10085000CDF81490042105A800F006F900E7002364 +:10086000642104A8049300F0F5F800287FF4AEAEEC +:100870000220FFF78FFD00283FF4A8AE049800F097 +:100880004FF90590E6E70023642104A8049300F0E3 +:10089000E1F800287FF49AAE0220FFF77BFD0028E4 +:1008A0003FF494AE049800F04BF9EAE70220FFF71A +:1008B00071FD00283FF48AAE00F05AF9E1E702200A +:1008C000FFF768FD00283FF481AE05A9142000F071 +:1008D00055F904210746049004A800F0C5F83946EC +:1008E000B9E7322000F0A2F8071EFFF66FAEBB0793 +:1008F0007FF46CAE384A926807EB0A0393423FF6E6 +:1009000065AE0220FFF746FD00283FF45FAE27F0FA +:1009100003075744BA453FF4A3AE504600F0D0F861 +:100920000421059005A800F09FF80AF1040AF1E7F8 +:100930004FF47A70FFF72EFD00283FF447AE00F029 +:1009400007F9002844D00A9B01330BD008220AA9DA +:10095000002000F0CDF900283AD02022FF210AA87B +:1009600000F0BEF9FFF71EFD1C4800F0D1FF13B0E8 +:10097000BDE8F08F002E3FF429AE0BF00B030B2BDC +:100980007FF424AE0023642105A8059300F062F8EB +:10099000074600287FF41AAE0220FFF7FBFC8146D1 +:1009A00000283FF413AEFFF7FDFC41F2883000F061 +:1009B000AFFF059800F012FA4E4600F0DDF93C4614 +:1009C000B6E506464CE64FF0000AFFE5B8467BE682 +:1009D000374679E65822002000220020A086010038 +:1009E00070B50F4B1B780133DBB2012B0C4611D8CD +:1009F0000C4D29684FF47A730E6AA2FB033201464C +:100A000022462846B047844204D1074B00221A7080 +:100A1000012070BD4FF4FA7000F07AFF0020F8E773 +:100A200010220020502500209023002007B500232D +:100A3000024601210DF107008DF80730FFF7D0FFC6 +:100A400020B19DF8070003B05DF804FB4FF0FF30C4 +:100A5000F9E700000A4608B50421FFF7C1FF80F05E +:100A60000100C0B2404208BD30B4054C2368DD69C6 +:100A7000044B0A46AC460146204630BC604700BFE6 +:100A800050250020A086010070B501F0F1F9094E53 +:100A9000094D3080002428683388834208D901F04A +:100AA000E1F92B6804440133B4F5803F2B60F2D3A5 +:100AB00070BD00BF922300206423002001F086BA9D +:100AC00000F1006000F580300068704700F10060C0 +:100AD000920000F5803001F011BA0000054B1A6851 +:100AE000054B1B889B1A834202D9104401F0BAB906 +:100AF00000207047642300209223002038B5074D62 +:100B000004462868204401F0B5F928B92868204433 +:100B1000BDE8384001F0C6B938BD00BF64230020ED +:100B200010F003030AD1B0F5047F05D200F10050A4 +:100B3000A0F51040D0F80038184670470023FBE7B6 +:100B400000F10050A0F51040D0F8100A70470000E6 +:100B5000064991F8243033B10023086A81F8243023 +:100B60000822FFF7B3BF0120704700BF68230020B1 +:100B7000014B1868704700BF002004E070B52A4B95 +:100B80001B68C3F30B0204461B0C62B140F2134016 +:100B9000824230D040F2194082422ED040F22140B1 +:100BA00082422CD10322214D0C2000FB02525568B9 +:100BB00042F20102934224D0B3F5805F23D041F288 +:100BC0000102934221D041F2030293421FD041F22D +:100BD0000702934214BF3F233123013C0C44013DE3 +:100BE0000A46A24215D215F9016F501C9EB100F8B9 +:100BF000016C0246F5E70122D5E70222D3E70C4D4E +:100C0000D6E73323E9E74123E7E75A23E5E759230A +:100C1000E3E7104605E02C258442157001D9901CAD +:100C20005370401A70BD00BF002004E0F833000884 +:100C3000CC330008022804D1054B4FF400129A610E +:100C400070470128FCD1024B4FF48012F7E700BF38 +:100C500000040240022803D1044B20229A6170470D +:100C60000128FCD1014B1022F8E700BF000402402C +:100C7000022805D1064A536983F020035361704767 +:100C80000128FCD1024A536983F01003F6E700BF44 +:100C90000004024010B50023934203D0CC5CC4543E +:100CA0000133F9E710BD000010B5013810F9013F1C +:100CB0003BB191F900409C4203D11AB10131013A94 +:100CC000F4E71AB191F90020981A10BD1046FCE71C +:100CD00003460246D01A12F9011B0029FAD17047C7 +:100CE00002440346934202D003F8011BFAE770471F +:100CF0002DE9F8431F4D144695F8242007468846F1 +:100D000052BBDFF870909CB395F824302BB92022A9 +:100D1000FF2148462F62FFF7E3FF95F82400C0F15A +:100D20000802A24228BF2246D6B24146920005EBF5 +:100D30008000FFF7AFFF95F82430A41B1E44F6B2E5 +:100D4000082E17449044E4B285F82460DBD1FFF705 +:100D5000FFFE0028D7D108E02B6A03EB8203834211 +:100D6000CFD0FFF7F5FE0028CBD10020BDE8F883F7 +:100D70000120FBE768230020024B1A78024B1A700F +:100D8000704700BF902300201022002010B50F4CA8 +:100D90000F4800F0F7F821460D4800F01FF92468CD +:100DA0000C48626DD2F8043843F00203C2F80438EC +:100DB00000F0AEFD0849204600F016FA626DD2F848 +:100DC000043823F00203C2F8043810BDEC340008E4 +:100DD0005025002040420F00F43400087047000006 +:100DE00000B59BB0EFF3098168226846FFF752FF18 +:100DF000EFF30583044B9A6BDA6A9A6A9A6A9A6AE5 +:100E00009A6A9A6A9B6AFEE700ED00E000B59BB023 +:100E1000EFF3098168226846FFF73CFFEFF3058393 +:100E2000044B9A6B9A6A9A6A9A6A9A6A9A6A9B6A55 +:100E3000FEE700BF00ED00E000B59BB0EFF30981D5 +:100E400068226846FFF726FFEFF30583034B5A6BD2 +:100E50009A6A9A6A9A6A9A6A9B6AFEE700ED00E0CB +:100E6000FEE7000030B5094D0A4491420DD011F85B +:100E7000013B5840082340F30004013B2C4013F091 +:100E8000FF0384EA5000F6D1EFE730BD2083B8EDD0 +:100E9000026843681143016003B1184770470000BE +:100EA00013B5446BD4F894341A681178042915D119 +:100EB000217C022912D11979128901238B40134216 +:100EC0000CD101A904F14C0001F002FFD4F89444C4 +:100ED000019B21790246206800F0CEF902B010BDD6 +:100EE000143001F085BE00004FF0FF33143001F0E4 +:100EF0007FBE00004C3001F057BF00004FF0FF33C1 +:100F00004C3001F051BF0000143001F053BE00001E +:100F10004FF0FF31143001F04DBE00004C3001F0B5 +:100F200023BF00004FF0FF324C3001F01DBF000026 +:100F30000020704710B5D0F894341A68117804294D +:100F4000044617D1017C022914D159795289012311 +:100F50008B4013420ED1143001F0E6FD024648B139 +:100F6000D4F894444FF4807361792068BDE8104050 +:100F700000F070B910BD0000406BFFF7DBBF000050 +:100F8000704700007FB5124B036000234360C0E947 +:100F90000233012502260F4B05740446029001938B +:100FA00000F18402294600964FF48073143001F05A +:100FB00097FD094B0294CDE9006304F523724FF4C9 +:100FC0008073294604F14C0001F05EFE04B070BD50 +:100FD00028340008790F0008A10E00080B682022B1 +:100FE00082F311880A7903EB820290614A7909320F +:100FF00043F822008A7912B103EB8203986102233D +:101000000374C0F89414002383F311887047000020 +:1010100038B5037F044613B190F85430ABB9201DA6 +:1010200001250221FFF734FF04F1140025776FF04A +:10103000010100F095FC84F8545004F14C006FF06D +:101040000101BDE8384000F08BBC38BD10B501216E +:1010500004460430FFF71CFF0023237784F8543044 +:1010600010BD000038B504460025143001F050FDD5 +:1010700004F14C00257701F01FFE201D84F8545028 +:101080000121FFF705FF2046BDE83840FFF752BFBA +:1010900090F8443003F06003202B07D190F84520EE +:1010A000212A4FF0000303D81F2A06D800207047DA +:1010B000222AFBD1C0E90E3303E0034A82630722F0 +:1010C000C2630364012070471122002037B5D0F8B5 +:1010D00094341A681178042904461AD1017C022933 +:1010E00017D11979128901238B40134211D100F1D4 +:1010F0004C05284601F0A0FE58B101A9284601F090 +:10110000E7FDD4F89444019B21790246206800F061 +:10111000B3F803B030BD0000F0B500EB810385B03B +:101120009E6904460D46FEB1202383F3118804EB2B +:101130008507301D0821FFF7ABFEFB685B691B6864 +:1011400006F14C001BB1019001F0D0FD019803A9FC +:1011500001F0BEFD024648B1039B2946204600F03F +:101160008BF8002383F3118805B0F0BDFB685A6942 +:101170001268002AF5D01B8A013B1340F1D104F11B +:101180004402EAE7093138B550F82140DCB12023A8 +:1011900083F31188D4F894241368527903EB820303 +:1011A000DB689B695D6845B104216018FFF770FE3C +:1011B000294604F1140001F0C1FC2046FFF7BAFEF5 +:1011C000002383F3118838BD7047000001F06EB82A +:1011D000012303700023C0E90133C361836203620A +:1011E000C36243620363704738B50446202383F328 +:1011F00011880025C0E90355C0E90555416001F09B +:1012000065F80223237085F3118838BD70B500EBB3 +:10121000810305465069DA600E46144618B1102263 +:101220000021FFF75DFDA06918B110220021FFF732 +:1012300057FD31462846BDE8704001F011B9000065 +:10124000826802F0011282600022C0E904228261F9 +:1012500001F092B9F0B400EB81044789E4680125FC +:10126000A4698D403D43458123600023A2606360F3 +:10127000F0BC01F0ADB90000F0B400EB81040789C7 +:10128000E468012564698D403D43058123600023A6 +:10129000A2606360F0BC01F027BA000070B50223C1 +:1012A000002504460370C0E90255C0E90455C56431 +:1012B000856180F8345001F06FF863681B6823B1D2 +:1012C00029462046BDE87040184770BD037880F875 +:1012D00050300523037043681B6810B504460BB1FA +:1012E000042198470023A36010BD000090F850200F +:1012F000436802701B680BB1052118477047000056 +:1013000070B590F83430044613B1002380F83430BF +:1013100004F14402204601F051F963689B68B3B9B7 +:1013200094F8443013F0600535D00021204601F0D8 +:10133000A3FB0021204601F095FB63681B6813B1F5 +:10134000062120469847062384F8343070BD204695 +:1013500098470028E4D0B4F84A30E26B9A4288BF3C +:10136000E36394F94430E56B002B4FF0200380F2E7 +:101370000381002D00F0F280092284F8342083F3E9 +:1013800011880021D4E90E232046FFF775FF0023C2 +:1013900083F31188DAE794F8452003F07F0343EAEA +:1013A000022340F20232934200F0C58021D8B3F507 +:1013B000807F48D00DD8012B3FD0022B00F09380C6 +:1013C000002BB2D104F14C02A2630222E263236437 +:1013D000C1E7B3F5817F00F09B80B3F5407FA4D1D6 +:1013E00094F84630012BA0D1B4F84C3043F00203FE +:1013F00032E0B3F5006F4DD017D8B3F5A06F31D000 +:10140000A3F5C063012B90D8636894F846205E680A +:1014100094F84710B4F848302046B047002884D0EC +:101420004368A3630368E3631AE0B3F5106F36D033 +:1014300040F6024293427FF478AF5C4BA3630223F1 +:10144000E3630023C3E794F84630012B7FF46DAFCC +:10145000B4F84C3023F00203C4E90E55A4F84C3024 +:10146000256478E7B4F84430B3F5A06F0ED194F852 +:10147000463084F84E30204600F0E6FF63681B6873 +:1014800013B1012120469847032323700023C4E9A8 +:101490000E339CE704F14F03A3630123C3E72378D2 +:1014A000042B10D1202383F311882046FFF7C8FEB8 +:1014B00085F311880321636884F84F5021701B68FD +:1014C0000BB12046984794F84630002BDED084F8C4 +:1014D0004F300423237063681B68002BD6D0022191 +:1014E00020469847D2E794F848301D0603F00F01D4 +:1014F00020460AD501F054F8012804D002287FF4D0 +:1015000014AF2B4B9AE72B4B98E701F03BF8F3E72E +:1015100094F84630002B7FF408AF94F8483013F06D +:101520000F01B3D01A06204602D501F0B9FAADE793 +:1015300001F0ACFAAAE794F84630002B7FF4F5AE40 +:1015400094F8483013F00F01A0D01B06204602D5B6 +:1015500001F092FA9AE701F085FA97E7142284F8ED +:10156000342083F311882B462A4629462046FFF76C +:1015700071FE85F31188E9E65DB1152284F8342007 +:1015800083F311880021D4E90E232046FFF762FE81 +:10159000FDE60B2284F8342083F311882B462A467B +:1015A00029462046FFF768FEE3E700BF58340008ED +:1015B000503400085434000838B590F834300446EC +:1015C000002B3ED0063BDAB20F2A34D80F2B32D88C +:1015D000DFE803F037313108223231313131313136 +:1015E00031313737C56BB0F84A309D4214D2C368E9 +:1015F0001B8AB5FBF3F203FB12556DB9202383F36D +:1016000011882B462A462946FFF736FE85F31188B6 +:101610000A2384F834300EE0142384F83430202375 +:1016200083F3118800231A4619462046FFF712FE5D +:10163000002383F3118838BD036C03B1984700235E +:10164000E7E70021204601F017FA0021204601F0CB +:1016500009FA63681B6813B10621204698470623E0 +:10166000D7E7000010B590F83430142B044629D089 +:1016700017D8062B05D001D81BB110BD093B022B92 +:10168000FBD80021204601F0F7F90021204601F0A7 +:10169000E9F963681B6813B10621204698470623C1 +:1016A00019E0152BE9D10B2380F83430202383F384 +:1016B000118800231A461946FFF7DEFD002383F345 +:1016C0001188DAE7C3689B695B68002BD5D1036C8E +:1016D00003B19847002384F83430CEE7024B002250 +:1016E000C3E900339A6070479423002000230374F9 +:1016F0008268054B1B6899689142FBD25A68036067 +:1017000042601060586070479423002008B5202381 +:1017100083F31188037C032B05D0042B0DD02BB948 +:1017200083F3118808BD436900221A604FF0FF332C +:101730004361FFF7DBFF0023F2E7D0E900321360DB +:101740005A60F3E7002303748268054B1B689968AD +:101750009142FBD85A68036042601060586070473D +:1017600094230020054B19690874186802681A60F0 +:101770005360186101230374FEF7C8BD9423002051 +:1017800030B54B1C0B4D87B0044610D02B690A4A6C +:1017900001A800F001F92046FFF7E4FF049B13B114 +:1017A00001A800F035F92B69586907B030BDFFF783 +:1017B000D9FFF8E7942300200D17000838B50C4D29 +:1017C00041612B6981689A689142044603D8BDE85B +:1017D0003840FFF78BBF1846FFF7B4FF01232C6199 +:1017E000014623742046BDE83840FEF78FBD00BF98 +:1017F00094230020044B1A681B6990689B689842E8 +:1018000094BF0020012070479423002010B5084C9D +:10181000236820691A6822605460012223611A74C7 +:10182000FFF790FF01462069BDE81040FEF76EBD4E +:1018300094230020FFF7EABFFEE7000010B50C4C30 +:10184000FFF74CFF00F09AF80A498022204600F08A +:1018500021F8012344F8180C037400F041FC002324 +:1018600083F3118862B60448BDE8104000F032B836 +:10187000BC2300205C3400086C34000800F002B97E +:10188000034A516853685B1A9842FBD8704700BFFF +:10189000001000E082600222028270478368A3F198 +:1018A0007C0243F80C2C026943F83C2C426943F853 +:1018B000382C074A43F81C2CC26843F8102C02222B +:1018C00003F8082C002203F8072CA3F11800704736 +:1018D0002503000810B5202383F31188FFF7DEFFEE +:1018E00000210446FFF76AFF002383F31188204696 +:1018F00010BD0000024B1B6958610F20FFF732BF7B +:1019000094230020202383F31188FFF7F3BF000006 +:1019100008B50146202383F311880820FFF730FF24 +:10192000002383F3118808BD49B1064B42681B6947 +:1019300018605A60136043600420FFF721BF4FF026 +:10194000FF307047942300200368984206D01A683D +:101950000260506059611846FFF7C8BE704700002A +:1019600038B504460D462068844200D138BD03686E +:1019700023605C604561FFF7B9FEF4E7054B03F1B6 +:101980001402C3E905224FF0FF310022C3E9071218 +:10199000704700BF9423002070B51C4EC0E903239C +:1019A00005460C4601F07AFA334653F8142F9A4252 +:1019B0000DD13062C5E901242A600A2C2CBF001920 +:1019C0000A30C6E90555BDE8704001F055BA316AE4 +:1019D000431AE31838BF1C469368A34202D908197A +:1019E00001F058FA73699A6894420CD85A68AC604E +:1019F0002B606A6015609A685D60121B9A604FF0F8 +:101A0000FF33F36170BD1B68A41AECE79423002038 +:101A100038B51B4C636998420DD0D0E90032136091 +:101A20005A6000228168C2609A680A449A604FF046 +:101A3000FF33E36138BD2246036842F8143F0021BA +:101A400093425A60C16003D1BDE8384001F01CBA2E +:101A50009A688168256A0A449A6001F01FFA6369EE +:101A60009A68411B8A42E5D9AB181D1A092D206AD4 +:101A700098BF01F10A02BDE83840104401F00ABAEB +:101A8000942300202DE9F041184C002704F114069E +:101A9000656901F003FA236AAA68C11A8A4215D857 +:101AA00013442362D5E9003213605A606369D5F8A4 +:101AB0000C80EF60B34201D101F0E6F987F31188A1 +:101AC0002869C047202383F31188E1E76169B142A7 +:101AD00009D013441B1ABDE8F0410A2B2CBFC018D3 +:101AE0000A3001F0D7B9BDE8F08100BF942300208F +:101AF00000207047FEE70000704700004FF0FF3005 +:101B00007047000002290CD0032904D0012907489E +:101B100018BF00207047032A05D8054800EBC20013 +:101B20007047044870470020704700BF50350008D8 +:101B3000202200200435000870B59AB005460846FA +:101B400001A9144600F0C2F801A8FFF7C1F8431C30 +:101B50005B00C5E900340022237003236370C6B222 +:101B600001AB02341046D1B28E4204F1020401D816 +:101B70001AB070BD13F8011B04F8021C04F8010C24 +:101B80000132F0E708B5202383F311880348FFF7FB +:101B90009DFA002383F3118808BD00BF5025002063 +:101BA00090F8443003F01F02012A07D190F8452035 +:101BB0000B2A03D10023C0E90E3315E003F06003C4 +:101BC000202B08D1B0F848302BB990F84520212AB5 +:101BD00003D81F2A04D8FFF75BBA222AEBD0FAE712 +:101BE000034A82630722C26303640120704700BF77 +:101BF0001822002007B5052917D8DFE801F01916CB +:101C000003191920202383F31188104A0190012120 +:101C1000FFF7FCFA01980E4A0221FFF7F7FA0D4888 +:101C2000FFF720FA002383F3118803B05DF804FB6B +:101C3000202383F311880748FFF7EAF9F2E720230E +:101C400083F311880348FFF701FAEBE7A434000897 +:101C5000C83400085025002038B50C4D0C4C0D49F7 +:101C60002A4604F10800FFF767FF05F1CA0204F1F4 +:101C700010000949FFF760FF05F5CA7204F118006A +:101C80000649BDE83840FFF757BF00BF182A0020BB +:101C900020220020843400088E3400089934000883 +:101CA00070B5044608460D46FFF712F8C6B2204646 +:101CB000013403780BB9184670BD32462946FEF749 +:101CC000F3FF0028F3D10120F6E700002DE9F84FDB +:101CD00005460C46FEF7FCFF2B49C6B22846FFF727 +:101CE000DFFF08B10536F6B228492846FFF7D8FFCE +:101CF00008B11036F6B2632E0DD8DFF88C80DFF80D +:101D00008C90234FDFF890A0DFF890B02E7846B982 +:101D10002670BDE8F88F29462046BDE8F84F01F04F +:101D20004DBB252E2BD1072241462846FEF7BCFF8E +:101D300058B9DBF800302360DBF804306360DBF86F +:101D40000830A36007350C34E0E7082249462846EE +:101D5000FEF7AAFF98B90F4BA21C197809090232A5 +:101D6000C95D02F8041C13F8011B01F00F01534573 +:101D7000C95D02F8031CF0D118340835C6E704F831 +:101D8000016B0135C2E700BF7035000899340008C7 +:101D900085350008107AFF1F1C7AFF1F7835000870 +:101DA000BFF34F8F024AD368DB03FCD4704700BFF8 +:101DB000003C024008B5094B1B7873B9FFF7F0FFF0 +:101DC000074B1A69002ABFBF064A5A6002F18832DF +:101DD0005A601A6822F480621A6008BD762C0020CE +:101DE000003C02402301674508B50B4B1B7893B9B3 +:101DF000FFF7D6FF094B1A6942F000421A611A68D0 +:101E000042F480521A601A6822F480521A601A68EA +:101E100042F480621A6008BD762C0020003C02402B +:101E20000B28F0B516D80C4C0C4923787BB90C4D17 +:101E30000E460C234FF0006255F8047B46F8042B45 +:101E4000013B13F0FF033A44F6D10123237051F80C +:101E50002000F0BD0020FCE7A82C0020782C0020FA +:101E600098350008014B53F820007047983500085A +:101E70000C2070470B2810B5044601D9002010BD76 +:101E8000FFF7CEFF064B53F824301844C21A0BB9A3 +:101E90000120F4E712680132F0D1043BF6E700BFFD +:101EA000983500080B2810B5044621D8FFF778FFB5 +:101EB000FFF780FF0F4AF323D360C300DBB243F484 +:101EC000007343F002031361136943F48033136119 +:101ED000FFF766FFFFF7A4FF074B53F8241000F04D +:101EE000D9F8FFF781FF2046BDE81040FFF7C2BFD9 +:101EF000002010BD003C024098350008F8B512F0F3 +:101F00000103144642D18218B2F1016F57D82D4B0C +:101F10001B6813F0010352D02B4DFFF74BFFF32347 +:101F2000EB60FFF73DFF40F20127032C15D824F0AA +:101F300001046618244C401A40F20117B14223698B +:101F400000EB010524D123F001032361FFF74CFFCF +:101F50000120F8BD043C0430E7E78307E7D12B6993 +:101F600023F440732B612B693B432B6151F8046BC5 +:101F70000660BFF34F8FFFF713FF03689E42E9D05F +:101F80002B6923F001032B61FFF72EFF0020E0E710 +:101F900023F44073236123693B4323610B882B8027 +:101FA000BFF34F8FFFF7FCFE2D8831F8023BADB237 +:101FB000AB42C3D0236923F001032361E4E7184651 +:101FC000C7E700BF00380240003C0240084908B59E +:101FD0000B7828B11BB9FFF7EDFE01230B7008BD8C +:101FE000002BFCD0BDE808400870FFF7FDBE00BF25 +:101FF000762C002010B50244064BD2B2904200D19C +:1020000010BD441C00B253F8200041F8040BE0B2AC +:10201000F4E700BF502800400F4B30B51C6F24047C +:1020200007D41C6F44F400741C671C6F44F4004414 +:102030001C670A4C236843F4807323600244084BF6 +:10204000D2B2904200D130BD441C00B251F8045BC2 +:1020500043F82050E0B2F4E700380240007000403E +:102060005028004007B5012201A90020FFF7C2FF58 +:10207000019803B05DF804FB13B50446FFF7F2FFC7 +:10208000A04205D0012201A900200194FFF7C4FF5E +:1020900002B010BD70470000044BD3F874389B00A9 +:1020A00042BF034B01221A70704700BF003002404C +:1020B000A92C0020014B1878704700BFA92C0020E4 +:1020C000EFF3098305494A6B22F001024A63683342 +:1020D00083F30988002383F31188704700EF00E041 +:1020E000202080F3118862B60C4B0D4AD96821F488 +:1020F000E0610904090C0A43DA60D3F8FC200949BD +:1021000042F08072C3F8FC200A6842F001020A60C3 +:102110001022DA7783F82200704700BF00ED00E05C +:102120000003FA05001000E010B5202383F31188A6 +:102130000E4B5B6813F4006314D0F1EE103AEFF32A +:102140000984683C4FF08073E361094BDB6B2366C5 +:1021500084F30988FFF74EFB10B1064BA36110BD55 +:10216000054BFBE783F31188F9E700BF00ED00E0C2 +:1021700000EF00E0370300083A0300087047000052 +:10218000FEE700000A4B0B480B4A90420BD30B4B67 +:10219000DA1C121AC11E22F003028B4238BF002241 +:1021A0000021FEF79DBD53F8041B40F8041BECE72B +:1021B00038370008A42D0020A42D0020A42D0020D5 +:1021C0007047000070B5D0E915439E6800224FF0BB +:1021D000FF3504EB42135101D3F800090028BEBFBC +:1021E000D3F8000940F08040C3F80009D3F8000B91 +:1021F0000028BEBFD3F8000B40F08040C3F8000BAE +:10220000013263189642C3F80859C3F8085BE0D25C +:102210004FF00113C4F81C3870BD00001D4B03EBD8 +:1022200080022DE9F043D2F80CC05D6DDCF814207B +:10223000461CD2F800E005EB063605EB4018516865 +:1022400071450AD3D5F83438012202FA00F023EAA6 +:102250000000C5F83408BDE8F083BCF81040AEEBD0 +:102260000103A34228BF2346D8F81849A4B2B3EB10 +:10227000840FF0D89468A4F1040959F8047F3760FA +:10228000A4EB09071F44042FF7D81C440B449460A7 +:102290005360D4E7AC2C0020890141F0200101619A +:1022A00003699B06FCD41220FFF7EABA10B5054C6F +:1022B0002046FEF78DFF4FF0A0436365024BA365F8 +:1022C00010BD00BFAC2C0020EC35000870B50378C1 +:1022D000012B054650D12A4B446D98421BD1294B06 +:1022E0005A6B42F080025A635A6D42F080025A657E +:1022F0005A6D5A6942F080025A615A6922F080028E +:102300005A610E2143205B6900F0D4FB1E4BE36051 +:102310001E4BC4F800380023C4F8003EC0232360DD +:102320006E6D4FF40413A3633369002BFCDA0123B1 +:1023300033610C20FFF7A4FA3369DB07FCD41220C9 +:10234000FFF79EFA3369002BFCDA0026A6602846C8 +:10235000FFF738FF6B68C4F81068DB68C4F81468CE +:10236000C4F81C684BB90A4BA3614FF0FF3363619B +:10237000A36843F00103A36070BD064BF4E700BF00 +:10238000AC2C002000380240401400400300200222 +:10239000003C30C0083C30C0F8B5446D0546002113 +:1023A0002046FFF779FFA96D00234FF001128F68D7 +:1023B000C4F834384FF00066C4F81C284FF0FF30E2 +:1023C00004EB431201339F42C2F80069C2F8006B6C +:1023D000C2F80809C2F8080BF2D20B686A6DEB6507 +:1023E000636210231361166916F01006FBD11220E8 +:1023F000FFF746FAD4F8003823F4FE63C4F8003837 +:10240000A36943F4402343F01003A3610923C4F8F4 +:102410001038C4F814380A4BEB604FF0C043C4F8CE +:10242000103B084BC4F8003BC4F81069C4F80039ED +:10243000EB6D03F1100243F48013EA65A362F8BD6B +:10244000C835000840800010426D90F84E10D2F858 +:10245000003823F4FE6343EA0113C2F800387047E2 +:102460002DE9F84300EB8103456DDA68166806F044 +:102470000306731E022B05EB41130C4680460FFA30 +:1024800081F94FEA41104FF00001C3F8101B4FF0E3 +:10249000010104F1100398BFB60401FA03F3916936 +:1024A0008EBF334E06F1805606F5004600293AD01D +:1024B000578A04F15801490137436F50D5F81C1869 +:1024C0000B43C5F81C382B180021C3F810195369A9 +:1024D0000127611EA7409BB3138A928B9B08012A98 +:1024E00088BF5343D8F85C20981842EA034301F1AF +:1024F000400205EB8202C8F85C0021465360284682 +:10250000FFF7CAFE08EB8900C3681B8A43EA8453BD +:10251000483464011E432E51D5F81C381F43C5F8BA +:102520001C78BDE8F88305EB4917D7F8001B21F4A8 +:102530000041C7F8001BD5F81C1821EA0303C0E7C7 +:1025400004F13F0305EB83030A4A5A6028462146FB +:10255000FFF7A2FE05EB4910D0F8003923F4004341 +:10256000C0F80039D5F81C3823EA0707D7E700BFC1 +:102570000080001000040002826D1268C265FFF73F +:1025800021BE00005831436D49015B5813F40040EF +:1025900004D013F4001F0CBF02200120704700007C +:1025A0004831436D49015B5813F4004004D013F4E3 +:1025B000001F0CBF022001207047000000EB8101CA +:1025C000CB68196A0B6813604B6853607047000052 +:1025D00000EB810330B5DD68AA691368D36019B9CF +:1025E000402B84BF402313606B8A1468426D1C44E7 +:1025F000013CB4FBF3F46343033323F0030302EB26 +:10260000411043EAC44343F0C043C0F8103B2B6879 +:1026100003F00303012B09B20ED1D2F8083802EB04 +:10262000411013F4807FD0F8003B14BF43F0805377 +:1026300043F00053C0F8003B02EB4112D2F8003BDC +:1026400043F00443C2F8003B30BD00002DE9F041E7 +:10265000244D6E6D06EB40130446D3F8087BC3F897 +:10266000087B38070AD5D6F81438190706D505EBC4 +:1026700084032146DB6828465B689847FA071FD524 +:10268000D6F81438DB071BD505EB8403D968CCB921 +:102690008B69488A5A68B2FBF0F600FB16228AB9A9 +:1026A0001868DA6890420DD2121AC3E90024202378 +:1026B00083F311880B482146FFF78AFF84F31188C2 +:1026C000BDE8F081012303FA04F26B8923EA0203D7 +:1026D0006B81CB68002BF3D021460248BDE8F04166 +:1026E000184700BFAC2C002000EB810370B5DD68FB +:1026F000436D6C692668E6604A0156BB1A444FF484 +:102700000020C2F810092A6802F00302012A0AB266 +:102710000ED1D3F8080803EB421410F4807FD4F8EC +:10272000000914BF40F0805040F00050C4F8000988 +:1027300003EB4212D2F8000940F00440C2F800094D +:10274000D3F83408012202FA01F10143C3F8341826 +:1027500070BD19B9402E84BF4020206020682E8AA9 +:102760008419013CB4FBF6F440EAC44040F0005048 +:102770001A44C6E7F8B504461E48456D05EB4413F8 +:10278000D3F80869C3F80869F10717D5D5F81038E8 +:10279000DA0713D500EB8403D9684B691F68DA6840 +:1027A000974218D2D21B00271A605F60202383F360 +:1027B00011882146FFF798FF87F31188330617D554 +:1027C000D5F834280123A340134211D02046BDE898 +:1027D000F840FFF723BD012303FA04F2038923EA3B +:1027E000020303818B68002BE8D021469847E5E778 +:1027F000F8BD00BFAC2C00202DE9F74F984C666D5A +:102800007569B3691D4015F48058756107D020467D +:10281000FEF744FD03B0BDE8F04FFFF785BC002D87 +:1028200012DAD6F8003E8E489F071EBFD6F8003E4B +:1028300023F00303C6F8003ED6F8043823F0010362 +:10284000C6F80438FEF752FD280505D58448FFF781 +:10285000B9FC8348FEF73AFDA9040CD5D6F8083830 +:1028600013F0060FF36823F470530CBF43F41053B6 +:1028700043F4A053F3602A0704D56368DB680BB107 +:1028800077489847EB0274D4AF0227D5D4F8549018 +:10289000DFF8CCB100274FF0010A09EB4712D2F85C +:1028A000003B03F44023B3F5802F11D1D2F8003B55 +:1028B000002B0DDA62890AFA07F322EA0303638127 +:1028C00004EB8703DB68DB6813B139465846984749 +:1028D000A36D01379B68FFB29F42DED9E80617D58A +:1028E000676D3A6AC2F30A1002F00F0302F4F012A5 +:1028F000B2F5802F00F08880B2F5402F08D104EBAC +:1029000083030022DB681B6A07F5805790426DD174 +:102910002903D6F8184813D5E20302D50020FFF7A3 +:1029200095FEA30302D50120FFF790FE670302D5B1 +:102930000220FFF78BFE260302D50320FFF786FE59 +:102940006D037FF567AFE00702D50020FFF712FFA8 +:10295000A10702D50120FFF70DFF620702D5022073 +:10296000FFF708FF23077FF555AF0320FFF702FFAE +:1029700050E7636DDFF8E8B0019300274FF0010ADC +:10298000A36D9B685FFA87F999453FF67DAF019B80 +:1029900003EB4913D3F8002902F44022B2F5802F4B +:1029A00022D1D3F80029002A1EDAD3F8002942F0F8 +:1029B0009042C3F80029D3F80029002AFBDB606DA0 +:1029C0004946FFF769FC22890AFA09F322EA030360 +:1029D000238104EB8903DB689B6813B149465846A1 +:1029E00098474846FFF71AFC0137C9E7910708BF27 +:1029F000D7F80080072A98BF03F8018B02F1010283 +:102A000098BF4FEA182881E7023304EB830207F5E9 +:102A100080575268D2F818C0DCF80820DCE9001CA6 +:102A2000A1EB0C0C002188420AD104EB83046368FB +:102A30009B699A6802449A605A6802445A6067E740 +:102A400011F0030F08BFD7F800808C4588BF02F84B +:102A5000018B01F1010188BF4FEA1828E3E700BFAD +:102A6000AC2C0020436D03EB4111D1F8003B43F443 +:102A70000013C1F8003B7047436D03EB4111D1F8DF +:102A8000003943F40013C1F800397047436D03EB7C +:102A90004111D1F8003B23F40013C1F8003B70470B +:102AA000436D03EB4111D1F8003923F40013C1F851 +:102AB0000039704700F1604303F561430901C9B271 +:102AC00083F80013012200F01F039A4043099B0082 +:102AD00003F1604303F56143C3F880211A60704736 +:102AE00030B5039C0172043304FB0325C0E906538F +:102AF000049B03630021059BC160C0E90000C0E99D +:102B00000422C0E90842C0E90A11436330BD000055 +:102B1000416A0022C0E90411C0E90A22C2606FF0D4 +:102B20000101FEF71DBF0000D0E90432934201D13C +:102B3000C2680AB9181D7047002070470369196000 +:102B4000C2680132C260C269134482690361934260 +:102B500024BF436A03610021FEF7F6BE38B5044680 +:102B60000D46E3683BB16269131D1268A36213440A +:102B7000E362002007E0237A33B929462046FEF7B6 +:102B8000D3FE0028EDDA38BD6FF00100FBE700004E +:102B9000C368C269013BC3604369134482694361EE +:102BA000934224BF436A436100238362036B03B1F2 +:102BB0001847704770B52023044683F31188866A4E +:102BC0003EB9FFF7CBFF054618B186F311882846BA +:102BD00070BDA36AE26A13F8015BA362934202D359 +:102BE0002046FFF7D5FF002383F31188EFE70000AD +:102BF0002DE9F84F04460E46174698464FF0200937 +:102C000089F311880025AA46D4F828B0BBF1000F3B +:102C100009D141462046FFF7A1FF20B18BF311886F +:102C20002846BDE8F88FD4E90A12A7EB050B521A23 +:102C3000934528BF9346BBF1400F1BD9334601F1A2 +:102C4000400251F8040B43F8040B9142F9D1A36AF6 +:102C500040334036A3624035D4E90A239A4202D376 +:102C60002046FFF795FF8AF31188BD42D8D289F339 +:102C70001188C9E730465A46FEF70CF8A36A5B4450 +:102C80005E44A3625D44E7E710B5029C0172043321 +:102C900004FB0321C0E906130023C0E90A33039BA8 +:102CA0000363049BC460C0E90000C0E90422C0E9DA +:102CB0000842436310BD0000026AC260426AC0E974 +:102CC00004220022C0E90A226FF00101FEF748BE8B +:102CD000D0E904239A4201D1C26822B9184650F8BB +:102CE000043B0B607047002070470000C368C26956 +:102CF0000133C3604369134482694361934224BF33 +:102D0000436A43610021FEF71FBE000038B5044648 +:102D10000D46E3683BB123691A1DA262E2691344C0 +:102D2000E362002007E0237A33B929462046FEF704 +:102D3000FBFD0028EDDA38BD6FF00100FBE7000075 +:102D400003691960C268013AC260C26913448269AA +:102D50000361934224BF436A036100238362036BD0 +:102D600003B118477047000070B520230D46044694 +:102D7000114683F31188866A2EB9FFF7C7FF10B199 +:102D800086F3118870BDA36A1D70A36AE26A0133DD +:102D90009342A36204D3E16920460439FFF7D0FFD0 +:102DA000002080F31188EDE72DE9F84F04460D4629 +:102DB000904699464FF0200A8AF311880026B346C0 +:102DC000A76A4FB949462046FFF7A0FF20B187F315 +:102DD00011883046BDE8F88FD4E90A073A1AA8EB03 +:102DE0000607974228BF1746402F1BD905F140031D +:102DF00055F8042B40F8042B9D42F9D1A36A4033C7 +:102E0000A3624036D4E90A239A4204D3E1692046FA +:102E10000439FFF795FF8BF311884645D9D28AF321 +:102E20001188CDE729463A46FDF734FFA36A3B44B3 +:102E30003D44A3623E44E5E7D0E904239A4217D11A +:102E4000C3689BB1836A8BB1043B9B1A0ED013609D +:102E5000C368013BC360C3691A44836902619A4233 +:102E600024BF436A0361002383620123184670472D +:102E70000023FBE700F088B84FF08043002258633E +:102E80001A610222DA6070474FF080430022DA6054 +:102E9000704700004FF08043586370474FF0804305 +:102EA000586A70474B6843608B688360CB68C36027 +:102EB0000B6943614B6903628B6943620B68036072 +:102EC0007047000008B5264B26481A6940F2FF11EA +:102ED0000A431A611A6922F4FF7222F001021A6190 +:102EE0001A691A6B0A431A631A6D0A431A651E4A55 +:102EF0001B6D1146FFF7D6FF02F11C0100F5806043 +:102F0000FFF7D0FF02F1380100F58060FFF7CAFF3C +:102F100002F1540100F58060FFF7C4FF02F1700177 +:102F200000F58060FFF7BEFF02F18C0100F58060C4 +:102F3000FFF7B8FF02F1A80100F58060FFF7B2FFCC +:102F400002F1C40100F58060FFF7ACFF02F1E0017F +:102F500000F58060FFF7A6FFBDE8084000F09AB8D2 +:102F60000038024000000240F835000808B500F0C3 +:102F700007FAFEF763FCFFF78FF8BDE80840FEF79D +:102F80006BBE000070470000104B1A6C42F001024B +:102F90001A641A6E42F001021A660D4A1B6E93689B +:102FA00043F0010393604FF0804353229A624FF045 +:102FB000FF32DA6200229A615A63DA605A600122B3 +:102FC0005A6108211A601C20FFF774BD00380240C6 +:102FD000002004E04FF0804208B51169D3680B402F +:102FE000D9B2C9439B07116107D5202383F3118808 +:102FF000FEF744FC002383F3118808BD08B5FFF7F2 +:10300000E9FFBDE80840FFF78FB800001F4B1A69C1 +:103010006FEAC2526FEAD2521A611A69C2F3080209 +:103020001A614FF0FF301A695A69586100215A69D4 +:1030300059615A691A6A62F080521A621A6A02F079 +:1030400080521A621A6A5A6A58625A6A59625A6AED +:103050001A6C42F080521A641A6E42F080521A665C +:103060001A6E0B4A106840F480701060186F00F4FC +:103070004070B0F5007F1EBF4FF4803018671967AD +:10308000536823F40073536000F05AB900380240CB +:1030900000700040334B4FF080521A64324A4FF4B4 +:1030A000404111601A6842F001021A601A689107E3 +:1030B000FCD59A6822F003029A602A4B9A6812F0B3 +:1030C0000C02FBD1196801F0F90119609A601A68C5 +:1030D00042F480321A601A689203FCD55A6F42F0AB +:1030E00001025A671F4B5A6F9007FCD51F4A5A605E +:1030F0001A6842F080721A601B4A53685904FCD562 +:10310000184B1A689201FCD5194A9A60194B1A6833 +:10311000194B9A42194B21D1194A1168194A914207 +:103120001CD140F205121A60144A136803F00F0311 +:10313000052BFAD10B4B9A6842F002029A609A680A +:1031400002F00C02082AFAD15A6C42F480425A6406 +:103150005A6E42F480425A665B6E704740F20572C6 +:10316000E1E700BF0038024000700040085440070B +:1031700000948838002004E011640020003C0240E4 +:1031800000ED00E041C20F41084A08B551691368DB +:103190000B4003F00103536123B1054A13680BB1DF +:1031A00050689847BDE80840FEF7BEBF003C0140AC +:1031B000242D0020084A08B5516913680B4003F01C +:1031C0000203536123B1054A93680BB1D068984755 +:1031D000BDE80840FEF7A8BF003C0140242D0020B8 +:1031E000084A08B5516913680B4003F004035361A2 +:1031F00023B1054A13690BB150699847BDE80840EF +:10320000FEF792BF003C0140242D0020084A08B57B +:10321000516913680B4003F00803536123B1054A59 +:1032200093690BB1D0699847BDE80840FEF77CBFB1 +:10323000003C0140242D0020084A08B5516913685C +:103240000B4003F01003536123B1054A136A0BB11D +:10325000506A9847BDE80840FEF766BF003C014051 +:10326000242D0020174B10B55A691C68144004F433 +:1032700078725A61A30604D5134A936A0BB1D06AD7 +:103280009847600604D5104A136B0BB1506B9847F2 +:10329000210604D50C4A936B0BB1D06B9847E2051D +:1032A00004D5094A136C0BB1506C9847A30504D59B +:1032B000054A936C0BB1D06C9847BDE81040FEF7FF +:1032C00033BF00BF003C0140242D00201A4B10B535 +:1032D0005A691C68144004F47C425A61620504D5A2 +:1032E000164A136D0BB1506D9847230504D5134A48 +:1032F000936D0BB1D06D9847E00404D50F4A136E5F +:103300000BB1506E9847A10404D50C4A936E0BB1D3 +:10331000D06E9847620404D5084A136F0BB1506F02 +:103320009847230404D5054A936F0BB1D06F984793 +:10333000BDE81040FEF7F8BE003C0140242D0020FF +:10334000062108B50846FFF7B5FB06210720FFF761 +:10335000B1FB06210820FFF7ADFB06210920FFF78E +:10336000A9FB06210A20FFF7A5FB06211720FFF77E +:10337000A1FBBDE8084006212820FFF79BBB000009 +:1033800008B5FFF743FE00F00BF8FDF71FFFFDF750 +:10339000F7FDFFF7F7FDBDE80840FFF76BBD000044 +:1033A0000023054A19460133102BC2E9001102F12E +:1033B0000802F8D1704700BF242D0020034611F801 +:1033C000012B03F8012B002AF9D1704753544D33D8 +:1033D00032463F3F3F00000053544D3332463430B5 +:1033E000780053544D3332463432780053544D33C1 +:1033F000324634343658580000000000CC33000800 +:103400003F00000013040000D83300083F00000014 +:1034100019040000E23300083F000000210400000E +:10342000EC3300083F00000000000000FD0E000823 +:10343000E90E0008250F0008110F00081D0F0008F5 +:10344000090F0008F50E0008E10E0008310F000812 +:103450000000000001000000000000006D61696EC6 +:103460000000000069646C6500000000643400081E +:10347000D823002050250020010000003918000842 +:10348000000000004172647550696C6F7400254241 +:103490004F415244252D424C002553455249414C41 +:1034A00025000000020000000000000019110008C3 +:1034B0008511000840004000E8290020F82900207C +:1034C00002000000000000000300000000000000F7 +:1034D000C91100080000000010000000082A0020A8 +:1034E000000000000100000000000000AC2C0020E3 +:1034F00001010200F51B0008051B0008A11B0008C4 +:10350000851B0008430000000C3500080902430039 +:10351000020100C03209040000010202010005247A +:103520000010010524010001042402020524060004 +:1035300001070582030800FF09040100020A0000D8 +:10354000000705010240000007058102400000005D +:10355000120000005835000812011001020000405E +:10356000091241570002010203010000040309048B +:1035700025424F41524425007265766F2D6D696E6C +:10358000692D736400303132333435363738394180 +:103590004243444546000000004000000040000057 +:1035A0000040000000400000000001000000020098 +:1035B0000000020000000200000002000000020003 +:1035C00000000200000002000000000001130008DB +:1035D000B915000865160008400040000C2D0020B9 +:1035E0000C2D0020010000001C2D00208000000098 +:1035F0004001000003000000000180020000000004 +:10360000AAAAAAAA00010000FFFF00000000000013 +:1036100000A00A004005000000000000AAAAAAAA13 +:1036200040000000CFFF000000000000000000008C +:103630000000000000000000AAAAAAAA00000000E2 +:10364000FFFF00000000000000000000000000007C +:1036500000000000AAAAAAAA00000000FFFF0000C4 +:10366000000000000000000000000000000000005A +:10367000AAAAAAAA00000000FFFF000000000000A4 +:10368000000000000000000000000000AAAAAAAA92 +:1036900000000000FFFF000000000000000000002C +:1036A0000000000000000000AAAAAAAA0000000072 +:1036B000FFFF00000000000000000000000000000C +:1036C000000000000A0000000000000003000000ED +:1036D00000000000000000000000000000000000EA +:1036E00000000000000000000000000000000000DA +:1036F00000000000000000007C000000000000004E +:1037000000000F0000000000FF009600000000080D +:103710000096000000000800040000006C3500085E +:103720000000000000000000000000000000000099 +:08373000000000000000000091 +:00000001FF diff --git a/Tools/bootloaders/speedybeef4v3_bl.bin b/Tools/bootloaders/speedybeef4v3_bl.bin new file mode 100644 index 00000000000..efba10cbf7d Binary files /dev/null and b/Tools/bootloaders/speedybeef4v3_bl.bin differ diff --git a/Tools/bootloaders/speedybeef4v3_bl.hex b/Tools/bootloaders/speedybeef4v3_bl.hex new file mode 100644 index 00000000000..baf0c1ecdab --- /dev/null +++ b/Tools/bootloaders/speedybeef4v3_bl.hex @@ -0,0 +1,894 @@ +:020000040800F2 +:1000000000060020E10100086D0E0008ED0D00085B +:10001000450E0008ED0D0008190E0008E301000868 +:10002000E3010008E3010008E301000841210008A2 +:10003000E3010008E3010008E3010008E301000810 +:10004000E3010008E3010008E3010008E301000800 +:10005000E3010008E3010008093200083532000816 +:10006000613200088D320008B9320008E30100084F +:10007000E3010008E3010008E3010008E3010008D0 +:10008000E3010008E3010008E3010008E3010008C0 +:10009000E3010008E3010008E3010008E53200087D +:1000A000E3010008E3010008E3010008E3010008A0 +:1000B0007D300008E3010008E3010008E3010008C7 +:1000C000E3010008E3010008E3010008E301000880 +:1000D000E3010008E3010008E3010008E301000870 +:1000E0004D330008E3010008E3010008E3010008C4 +:1000F000E3010008E3010008E3010008E301000850 +:10010000E3010008E3010008E3010008E30100083F +:10011000E3010008E3010008E3010008E30100082F +:10012000E3010008E3010008E3010008E30100081F +:10013000E3010008E3010008E3010008E30100080F +:10014000E3010008E3010008E30100087928000842 +:10015000E3010008E3010008E3010008E3010008EF +:10016000E3010008E3010008E3010008E3010008DF +:10017000E3010008E3010008E3010008E3010008CF +:10018000E3010008E3010008E3010008E3010008BF +:10019000E3010008E3010008E3010008E3010008AF +:1001A000E3010008E3010008E3010008E30100089F +:1001B000E3010008E3010008E3010008E30100088F +:1001C000E3010008E3010008E3010008E30100087F +:1001D000E3010008E3010008E3010008E30100086F +:1001E00002E000F000F8FEE772B63A4880F30888B3 +:1001F000394880F3098839484EF60851CEF200019B +:10020000086040F20000CCF200004EF63471CEF2ED +:1002100000010860BFF34F8FBFF36F8F40F2000003 +:10022000C0F2F0004EF68851CEF200010860BFF334 +:100230004F8FBFF36F8F4FF00000E1EE100A4EF6C4 +:100240003C71CEF200010860062080F31488BFF3F1 +:100250006F8F01F0F5FF01F0D1FF02F073FE4FF058 +:1002600055301F491B4A91423CBF41F8040BFAE745 +:100270001C49194A91423CBF41F8040BFAE71A495C +:100280001A4A1B4B9A423EBF51F8040B42F8040B2A +:10029000F8E700201749184A91423CBF41F8040B87 +:1002A000FAE701F0AFFF02F0A1FE144C144DAC428E +:1002B00003DA54F8041B8847F9E700F041F8114CC1 +:1002C000114DAC4203DA54F8041B8847F9E701F0FA +:1002D00097BF000000060020002200200000000858 +:1002E00000000020000600207837000800220020CF +:1002F0004022002040220020A82D0020E00100081C +:10030000E0010008E0010008E00100082DE9F04FDD +:100310002DED108AC1F80CD0C3689D46BDEC108A43 +:10032000BDE8F08F002383F311882846A047002002 +:1003300001F012FBFEE701F08DFA00DFFEE700009E +:1003400038B501F0CDFE054601F0F0FE0446D8B9FF +:100350000F4B9D421AD001339D4218BF044641F213 +:10036000883504BF01240025002001F0C3FE0CB134 +:1003700000F076F800F010FD00F09EFB284600F03B +:10038000BFF800F06DF8F9E70025EDE70546EBE76B +:10039000010007B008B500F061FBA0F1200358424E +:1003A000584108BD07B541F21203022101A8ADF87A +:1003B000043000F071FB03B05DF804FB38B5202376 +:1003C00083F311881748C3680BB101F04BFB164A41 +:1003D000144800234FF47A7101F008FB002383F3E3 +:1003E0001188124C236813B12368013B23606368B2 +:1003F00013B16368013B63600D4D2B7833B96368BB +:100400007BB9022000F042FC322363602B78032B7F +:1004100007D163682BB9022000F038FC4FF47A73DF +:10042000636038BD40220020BD0300085C2300202B +:1004300054220020084B187003280CD8DFE800F085 +:1004400008050208022000F017BC022000F00ABCD8 +:10045000024B00225A607047542200205C23002087 +:10046000234B244A10B51C46196801313FD0043390 +:100470009342F9D16268A24239D31F4B9B6803F1C2 +:10048000006303F540439A4231D2002000F02EFB76 +:100490000220FFF7CFFF194B1A6C00221A64196E65 +:1004A0001A66196E596C5A64596E5A665A6E5A69B0 +:1004B00042F080025A615A6922F080025A615A69F8 +:1004C0001A6942F000521A611A6922F000521A6148 +:1004D0001B6972B64FF0E0232021C3F8084DD4E920 +:1004E000003281F311889D4683F30888104710BDC0 +:1004F00000C0000820C00008002200200038024090 +:100500002DE9F04F93B0A94B00902022FF210AA8BB +:100510009D6800F0EBFBA64A1378A3B9A54801211A +:10052000C3601170202383F31188C3680BB101F0FD +:1005300099FAA14A9F4800234FF47A7101F056FAC4 +:10054000002383F31188009B13B19C4B009A1A601F +:100550009B4A009C1378032B1EBF00231370974AFD +:100560004FF0000A18BF5360D3465646D1460120CB +:1005700000F082FB24B1914B1B68002B00F00F822E +:10058000002000F06BFA0390039B002BF2DB0120AC +:1005900000F068FB039B213B162BE8D801A252F820 +:1005A00023F000BF0106000829060008BD06000868 +:1005B0006F0500086F0500086F0500084507000873 +:1005C000130900082D0800088F080008B708000864 +:1005D000DD0800086F050008EF0800086F05000837 +:1005E00061090008A10600086F050008A5090008B8 +:1005F0000D060008A10600086F0500088F08000816 +:100600000220FFF7C7FE002840F0F381009B022183 +:10061000BAF1000F08BF1C4605A841F21233ADF82D +:10062000143000F039FAA2E74FF47A7000F016FAAD +:10063000071EEBDB0220FFF7ADFE0028E6D0013FEE +:10064000052F00F2D881DFE807F0030A0D101336FA +:1006500005230593042105A800F01EFA17E053486E +:100660000421F9E757480421F6E757480421F3E746 +:100670004FF01C08404600F03BFA08F104080590D2 +:10068000042105A800F008FAB8F12C0FF2D10120DE +:1006900000FA07F747EA0B0B5FFA8BFB4FF00009F4 +:1006A00000F070FB26B10BF00B030B2B08BF0024EE +:1006B000FFF778FE5BE745480421CDE7002EA5D083 +:1006C0000BF00B030B2BA1D10220FFF763FE0746B3 +:1006D00000289BD0012000F009FA0220FFF7AAFEB3 +:1006E00000265FFA86F8404600F010FA044688B10A +:1006F000404600F01BFA01360028F2D1BA46044603 +:1007000041F21213022105A8ADF814303E4600F064 +:10071000C3F92CE70120FFF78DFE2546234B9B688C +:10072000AB4207D9284600F0E3F9013040F066817A +:100730000435F3E7224B00251D70204BBA465D605F +:100740003E46ADE7002E3FF461AF0BF00B030B2BE1 +:100750007FF45CAF0220FFF76DFE322000F07EF9DF +:10076000B0F10008FFF652AF18F003077FF44EAF68 +:100770000E4A926808EB050393423FF647AFB8F57F +:10078000807F3FF743AF124B0193B84522DD4FF412 +:100790007A7000F063F90390039A002AFFF636AFEF +:1007A000019B039A03F8012B0137EDE7002200209B +:1007B0005823002040220020BD0300085C230020B5 +:1007C0005422002004220020082200200C220020B5 +:1007D00058220020C820FFF7DDFD074600283FF41F +:1007E00015AF1F2D11D8C5F1200242450AAB25F0E7 +:1007F000030028BF424683490192184400F050FA92 +:10080000019A8048FF2100F071FA4FEAA8037D4960 +:100810000193C8F38702284600F070FA06460028C4 +:100820003FF46EAF019B05EB830539E70220FFF72C +:10083000B1FD00283FF4EAAE00F0A2F900283FF431 +:10084000E5AE0027B846704B9B68BB4218D91F2FF6 +:1008500011D80A9B01330ED027F0030312AA1344C8 +:1008600053F8203C05934046042205A900F000FB04 +:1008700004378046E7E7384600F03AF90590F2E79A +:10088000CDF81480042105A800F006F908E700233C +:10089000642104A8049300F0F5F800287FF4B6AEB4 +:1008A0000220FFF777FD00283FF4B0AE049800F077 +:1008B0004FF90590E6E70023642104A8049300F0B3 +:1008C000E1F800287FF4A2AE0220FFF763FD0028C4 +:1008D0003FF49CAE049800F04BF9EAE70220FFF7E2 +:1008E00059FD00283FF492AE00F05AF9E1E70220EA +:1008F000FFF750FD00283FF489AE05A9142000F051 +:1009000055F904210746049004A800F0C5F83946BB +:10091000B9E7322000F0A2F8071EFFF677AEBB075A +:100920007FF474AE384A926807EB090393423FF6AE +:100930006DAE0220FFF72EFD00283FF467AE27F0D2 +:1009400003074F44B9453FF4ABAE484600F0D0F83A +:100950000421059005A800F09FF809F10409F1E7CA +:100960004FF47A70FFF716FD00283FF44FAE00F009 +:1009700007F9002844D00A9B01330BD008220AA9AA +:10098000002000F0BBF900283AD02022FF210AA85D +:1009900000F0ACF9FFF706FD1C4800F0E3FF13B0D0 +:1009A000BDE8F08F002E3FF431AE0BF00B030B2BA4 +:1009B0007FF42CAE0023642105A8059300F062F8B3 +:1009C000074600287FF422AE0220FFF7E3FC8046B2 +:1009D00000283FF41BAEFFF7E5FC41F2883000F041 +:1009E000C1FF059800F000FA464600F0CBF93C46FE +:1009F000BDE5064654E64FF0000907E6BA467FE635 +:100A000037467DE65822002000220020A086010003 +:100A100070B50F4B1B780133DBB2012B0C4611D89C +:100A20000C4D29684FF47A730E6AA2FB033201461B +:100A300022462846B047844204D1074B00221A7050 +:100A4000012070BD4FF4FA7000F08CFF0020F8E731 +:100A500010220020502500209023002007B50023FD +:100A6000024601210DF107008DF80730FFF7D0FF96 +:100A700020B19DF8070003B05DF804FB4FF0FF3094 +:100A8000F9E700000A4608B50421FFF7C1FF80F02E +:100A90000100C0B2404208BD30B4054C2368DD6996 +:100AA000044B0A46AC460146204630BC604700BFB6 +:100AB00050250020A086010070B501F003FA094E10 +:100AC000094D3080002428683388834208D901F01A +:100AD000F3F92B6804440133B4F5404F2B60F2D393 +:100AE00070BD00BF922300206423002001F0ACBA47 +:100AF00000F1006000F540400068704700F10060C0 +:100B0000920000F5404001F02BBA0000054B1A6836 +:100B1000054B1B889B1A834202D9104401F0CCB9C3 +:100B200000207047642300209223002038B5074D31 +:100B300004462868204401F0C7F928B928682044F1 +:100B4000BDE8384001F0D8B938BD00BF64230020AB +:100B500010F003030AD1B0F5047F05D200F1005074 +:100B6000A0F51040D0F80038184670470023FBE786 +:100B700000F10050A0F51040D0F8100A70470000B6 +:100B8000064991F8243033B10023086A81F82430F3 +:100B90000822FFF7B3BF0120704700BF6823002081 +:100BA000014B1868704700BF002004E070B52A4B65 +:100BB0001B68C3F30B0204461B0C62B140F21340E6 +:100BC000824230D040F2194082422ED040F2214081 +:100BD00082422CD10322214D0C2000FB0252556889 +:100BE00042F20102934224D0B3F5805F23D041F258 +:100BF0000102934221D041F2030293421FD041F2FD +:100C00000702934214BF3F233123013C0C44013DB2 +:100C10000A46A24215D215F9016F501C9EB100F888 +:100C2000016C0246F5E70122D5E70222D3E70C4D1D +:100C3000D6E73323E9E74123E7E75A23E5E75923DA +:100C4000E3E7104605E02C258442157001D9901C7D +:100C50005370401A70BD00BF002004E078340008D3 +:100C60004C340008022802BF024B4FF080729A6198 +:100C7000704700BF00080240022802BF024B4FF439 +:100C800080729A61704700BF00080240022801BFCD +:100C9000024A536983F4807353617047000802402D +:100CA00010B50023934203D0CC5CC4540133F9E760 +:100CB00010BD000010B5013810F9013F3BB191F9AA +:100CC00000409C4203D11AB10131013AF4E71AB154 +:100CD00091F90020981A10BD1046FCE70346024621 +:100CE000D01A12F9011B0029FAD1704702440346B9 +:100CF000934202D003F8011BFAE770472DE9F8434D +:100D00001F4D144695F824200746884652BBDFF84D +:100D100070909CB395F824302BB92022FF214846CF +:100D20002F62FFF7E3FF95F82400C0F10802A2420A +:100D300028BF2246D6B24146920005EB8000FFF75D +:100D4000AFFF95F82430A41B1E44F6B2082E1744BA +:100D50009044E4B285F82460DBD1FFF711FF00284E +:100D6000D7D108E02B6A03EB82038342CFD0FFF791 +:100D700007FF0028CBD10020BDE8F8830120FBE766 +:100D800068230020024B1A78024B1A70704700BF8C +:100D9000902300201022002010B50F4C0F4800F0C7 +:100DA000F7F821460D4800F01FF924680C48626DE1 +:100DB000D2F8043843F00203C2F8043800F0D2FD40 +:100DC0000849204600F016FA626DD2F8043823F084 +:100DD0000203C2F8043810BD6C350008502500200D +:100DE00040420F00743500087047000000B59BB00A +:100DF000EFF3098168226846FFF752FFEFF305839E +:100E0000044B9A6BDA6A9A6A9A6A9A6A9A6A9A6A36 +:100E10009B6AFEE700ED00E000B59BB0EFF30981AF +:100E200068226846FFF73CFFEFF30583044B9A6B9B +:100E30009A6A9A6A9A6A9A6A9A6A9B6AFEE700BFF5 +:100E400000ED00E000B59BB0EFF309816822684631 +:100E5000FFF726FFEFF30583034B5A6B9A6A9A6AF2 +:100E60009A6A9A6A9B6AFEE700ED00E0FEE70000DE +:100E700030B5094D0A4491420DD011F8013B58405C +:100E8000082340F30004013B2C4013F0FF0384EAE5 +:100E90005000F6D1EFE730BD2083B8ED026843681B +:100EA0001143016003B118477047000013B5446B4C +:100EB000D4F894341A681178042915D1217C0229B8 +:100EC00012D11979128901238B4013420CD101A947 +:100ED00004F14C0001F03CFFD4F89444019B2179CB +:100EE0000246206800F0CEF902B010BD143001F0C7 +:100EF000BFBE00004FF0FF33143001F0B9BE000058 +:100F00004C3001F091BF00004FF0FF334C3001F046 +:100F10008BBF0000143001F08DBE00004FF0FF3198 +:100F2000143001F087BE00004C3001F05DBF0000BE +:100F30004FF0FF324C3001F057BF000000207047E7 +:100F400010B5D0F894341A6811780429044617D1E2 +:100F5000017C022914D15979528901238B40134213 +:100F60000ED1143001F020FE024648B1D4F894446A +:100F70004FF4807361792068BDE8104000F070B9CB +:100F800010BD0000406BFFF7DBBF000070470000A2 +:100F90007FB5124B036000234360C0E90233012593 +:100FA00002260F4B057404460290019300F184025F +:100FB000294600964FF48073143001F0D1FD094B9F +:100FC0000294CDE9006304F523724FF4807329463F +:100FD00004F14C0001F098FE04B070BDA834000884 +:100FE000850F0008AD0E00080B68202282F31188DF +:100FF0000A7903EB820290614A79093243F82200B0 +:101000008A7912B103EB8203986102230374C0F85A +:101010009414002383F311887047000038B5037FD0 +:10102000044613B190F85430ABB9201D01250221BC +:10103000FFF734FF04F1140025776FF0010100F091 +:10104000B9FC84F8545004F14C006FF00101BDE884 +:10105000384000F0AFBC38BD10B501210446043063 +:10106000FFF71CFF0023237784F8543010BD0000E5 +:1010700038B504460025143001F08AFD04F14C0017 +:10108000257701F059FE201D84F854500121FFF707 +:1010900005FF2046BDE83840FFF752BF90F84430C6 +:1010A00003F06003202B07D190F84520212A4FF050 +:1010B000000303D81F2A06D800207047222AFBD13C +:1010C000C0E90E3303E0034A82630722C26303646C +:1010D000012070471122002037B5D0F894341A68E7 +:1010E0001178042904461AD1017C022917D11979F3 +:1010F000128901238B40134211D100F14C0528467F +:1011000001F0DAFE58B101A9284601F021FED4F819 +:101110009444019B21790246206800F0B3F803B0A3 +:1011200030BD0000F0B500EB810385B09E69044638 +:101130000D46FEB1202383F3118804EB8507301D93 +:101140000821FFF7ABFEFB685B691B6806F14C00EA +:101150001BB1019001F00AFE019803A901F0F8FD0E +:10116000024648B1039B2946204600F08BF8002335 +:1011700083F3118805B0F0BDFB685A691268002A34 +:10118000F5D01B8A013B1340F1D104F14402EAE798 +:10119000093138B550F82140DCB1202383F31188A0 +:1011A000D4F894241368527903EB8203DB689B69BB +:1011B0005D6845B104216018FFF770FE294604F10F +:1011C000140001F0FBFC2046FFF7BAFE002383F376 +:1011D000118838BD7047000001F0A8B801230370E2 +:1011E0000023C0E90133C36183620362C3624362C7 +:1011F0000363704738B50446202383F31188002524 +:10120000C0E90355C0E90555416001F09FF802238C +:10121000237085F3118838BD70B500EB8103054656 +:101220005069DA600E46144618B110220021FFF70B +:101230005DFDA06918B110220021FFF757FD31466E +:101240002846BDE8704001F04BB90000826802F00A +:10125000011282600022C0E90422826101F0CCB94F +:10126000F0B400EB81044789E4680125A4698D404E +:101270003D43458123600023A2606360F0BC01F020 +:10128000E7B90000F0B400EB81040789E4680125A8 +:1012900064698D403D43058123600023A260636043 +:1012A000F0BC01F061BA000070B5022300250446CD +:1012B0000370C0E90255C0E90455C564856180F832 +:1012C000345001F0A9F863681B6823B12946204611 +:1012D000BDE87040184770BD037880F85030052392 +:1012E000037043681B6810B504460BB1042198478E +:1012F0000023A36010BD000090F8502043680270E6 +:101300001B680BB1052118477047000070B590F8B5 +:101310003430044613B1002380F8343004F1440221 +:10132000204601F08BF963689B68B3B994F84430A8 +:1013300013F0600535D00021204601F0DDFB0021CF +:10134000204601F0CFFB63681B6813B106212046DD +:101350009847062384F8343070BD2046984700280B +:10136000E4D0B4F84A30E26B9A4288BFE36394F960 +:101370004430E56B002B4FF0200380F20381002DF9 +:1013800000F0F280092284F8342083F311880021D0 +:10139000D4E90E232046FFF775FF002383F311885D +:1013A000DAE794F8452003F07F0343EA022340F292 +:1013B0000232934200F0C58021D8B3F5807F48D037 +:1013C0000DD8012B3FD0022B00F09380002BB2D11F +:1013D00004F14C02A2630222E2632364C1E7B3F585 +:1013E000817F00F09B80B3F5407FA4D194F8463014 +:1013F000012BA0D1B4F84C3043F0020332E0B3F536 +:10140000006F4DD017D8B3F5A06F31D0A3F5C063EE +:10141000012B90D8636894F846205E6894F84710D2 +:10142000B4F848302046B047002884D04368A3630E +:101430000368E3631AE0B3F5106F36D040F602425A +:1014400093427FF478AF5C4BA3630223E3630023F2 +:10145000C3E794F84630012B7FF46DAFB4F84C30FD +:1014600023F00203C4E90E55A4F84C30256478E754 +:10147000B4F84430B3F5A06F0ED194F8463084F838 +:101480004E30204601F020F863681B6813B101213B +:1014900020469847032323700023C4E90E339CE7BA +:1014A00004F14F03A3630123C3E72378042B10D176 +:1014B000202383F311882046FFF7C8FE85F31188A7 +:1014C0000321636884F84F5021701B680BB12046DC +:1014D000984794F84630002BDED084F84F30042330 +:1014E000237063681B68002BD6D0022120469847E2 +:1014F000D2E794F848301D0603F00F0120460AD5C4 +:1015000001F08EF8012804D002287FF414AF2B4B91 +:101510009AE72B4B98E701F075F8F3E794F846301B +:10152000002B7FF408AF94F8483013F00F01B3D0CC +:101530001A06204602D501F0F3FAADE701F0E6FA0B +:10154000AAE794F84630002B7FF4F5AE94F84830C3 +:1015500013F00F01A0D01B06204602D501F0CCFAF3 +:101560009AE701F0BFFA97E7142284F8342083F356 +:1015700011882B462A4629462046FFF771FE85F33F +:101580001188E9E65DB1152284F8342083F31188CF +:101590000021D4E90E232046FFF762FEFDE60B2270 +:1015A00084F8342083F311882B462A4629462046A6 +:1015B000FFF768FEE3E700BFD8340008D034000826 +:1015C000D434000838B590F834300446002B3ED0AF +:1015D000063BDAB20F2A34D80F2B32D8DFE803F0FB +:1015E0003731310822323131313131313131373710 +:1015F000C56BB0F84A309D4214D2C3681B8AB5FB54 +:10160000F3F203FB12556DB9202383F311882B46A7 +:101610002A462946FFF736FE85F311880A2384F807 +:1016200034300EE0142384F83430202383F31188FF +:1016300000231A4619462046FFF712FE002383F3C3 +:10164000118838BD036C03B198470023E7E70021F8 +:10165000204601F051FA0021204601F043FA636868 +:101660001B6813B10621204698470623D7E70000E0 +:1016700010B590F83430142B044629D017D8062B17 +:1016800005D001D81BB110BD093B022BFBD80021AE +:10169000204601F031FA0021204601F023FA636868 +:1016A0001B6813B1062120469847062319E0152B25 +:1016B000E9D10B2380F83430202383F311880023F1 +:1016C0001A461946FFF7DEFD002383F31188DAE797 +:1016D000C3689B695B68002BD5D1036C03B1984745 +:1016E000002384F83430CEE7024B0022C3E90033F4 +:1016F0009A60704794230020002303748268054B8E +:101700001B6899689142FBD25A680360426010607E +:10171000586070479423002008B5202383F3118874 +:10172000037C032B05D0042B0DD02BB983F3118838 +:1017300008BD436900221A604FF0FF334361FFF791 +:10174000DBFF0023F2E7D0E9003213605A60F3E7D1 +:10175000002303748268054B1B6899689142FBD88B +:101760005A680360426010605860704794230020FC +:10177000054B19690874186802681A60536018618B +:1017800001230374FEF7C2BD9423002030B54B1C27 +:101790000B4D87B0044610D02B690A4A01A800F00F +:1017A00025F92046FFF7E4FF049B13B101A800F0E0 +:1017B00059F92B69586907B030BDFFF7D9FFF8E731 +:1017C000942300201917000838B50C4D41612B698E +:1017D00081689A689142044603D8BDE83840FFF713 +:1017E0008BBF1846FFF7B4FF01232C610146237419 +:1017F0002046BDE83840FEF789BD00BF9423002095 +:10180000044B1A681B6990689B68984294BF00203B +:10181000012070479423002010B5084C23682069EC +:101820001A6822605460012223611A74FFF790FF46 +:1018300001462069BDE81040FEF768BD94230020F2 +:1018400008B5FFF7DDFF18B1BDE80840FFF7E4BFBA +:1018500008BD0000FFF7E0BFFEE7000010B50C4C2C +:10186000FFF742FF00F0B4F80A498022204600F05A +:101870003BF8012344F8180C037400F071FC0023BA +:1018800083F3118862B60448BDE8104000F04CB8FC +:10189000BC230020DC340008EC34000800F01CB944 +:1018A000EFF3118020B9EFF30583202282F3118832 +:1018B0007047000010B530B9EFF30584C4F3080495 +:1018C00014B180F3118810BDFFF7BAFF84F31188BB +:1018D000F9E70000034A516853685B1A9842FBD845 +:1018E000704700BF001000E0826002220282704751 +:1018F0008368A3F17C0243F80C2C026943F83C2C6A +:10190000426943F8382C074A43F81C2CC26843F854 +:10191000102C022203F8082C002203F8072CA3F154 +:10192000180070472503000810B5202383F31188A1 +:10193000FFF7DEFF00210446FFF746FF002383F395 +:101940001188204610BD0000024B1B6958610F2012 +:10195000FFF70EBF94230020202383F31188FFF7A5 +:10196000F3BF000008B50146202383F31188082047 +:10197000FFF70CFF002383F3118808BD49B1064B24 +:1019800042681B6918605A60136043600420FFF7C7 +:10199000FDBE4FF0FF30704794230020036898424B +:1019A00006D01A680260506059611846FFF7A4BE5D +:1019B0007047000038B504460D462068844200D1C7 +:1019C00038BD036823605C604561FFF795FEF4E76E +:1019D000054B03F11402C3E905224FF0FF31002249 +:1019E000C3E90712704700BF9423002070B51C4E56 +:1019F000C0E9032305460C4601F090FA334653F83C +:101A0000142F9A420DD13062C5E901242A600A2CB4 +:101A10002CBF00190A30C6E90555BDE8704001F039 +:101A20006BBA316A431AE31838BF1C469368A34265 +:101A300002D9081901F06EFA73699A6894420CD8B9 +:101A40005A68AC602B606A6015609A685D60121B12 +:101A50009A604FF0FF33F36170BD1B68A41AECE786 +:101A60009423002038B51B4C636998420DD0D0E90F +:101A7000003213605A6000228168C2609A680A448A +:101A80009A604FF0FF33E36138BD2246036842F8A5 +:101A9000143F002193425A60C16003D1BDE8384031 +:101AA00001F032BA9A688168256A0A449A6001F0A6 +:101AB00035FA63699A68411B8A42E5D9AB181D1A49 +:101AC000092D206A98BF01F10A02BDE83840104490 +:101AD00001F020BA942300202DE9F041184C002792 +:101AE00004F11406656901F019FA236AAA68C11A9B +:101AF0008A4215D813442362D5E9003213605A6034 +:101B00006369D5F80C80EF60B34201D101F0FCF9B4 +:101B100087F311882869C047202383F31188E1E700 +:101B20006169B14209D013441B1ABDE8F0410A2B88 +:101B30002CBFC0180A3001F0EDB9BDE8F08100BF3C +:101B40009423002000207047FEE70000704700004B +:101B50004FF0FF307047000002290CD0032904D059 +:101B60000129074818BF00207047032A05D80548F7 +:101B700000EBC2007047044870470020704700BF68 +:101B8000D0350008202200208435000870B59AB0B6 +:101B90000546084601A9144600F0C2F801A8FFF75F +:101BA0009DF8431C5B00C5E9003400222370032329 +:101BB0006370C6B201AB02341046D1B28E4204F15A +:101BC000020401D81AB070BD13F8011B04F8021CFE +:101BD00004F8010C0132F0E708B5202383F31188E3 +:101BE0000348FFF779FA002383F3118808BD00BF8B +:101BF0005025002090F8443003F01F02012A07D13D +:101C000090F845200B2A03D10023C0E90E3315E0DC +:101C100003F06003202B08D1B0F848302BB990F8BE +:101C20004520212A03D81F2A04D8FFF737BA222AD1 +:101C3000EBD0FAE7034A82630722C2630364012000 +:101C4000704700BF1822002007B5052917D8DFE824 +:101C500001F0191603191920202383F31188104A63 +:101C600001900121FFF7D8FA01980E4A0221FFF7EF +:101C7000D3FA0D48FFF7FCF9002383F3118803B072 +:101C80005DF804FB202383F311880748FFF7C6F9AA +:101C9000F2E7202383F311880348FFF7DDF9EBE730 +:101CA00024350008483500085025002038B50C4D73 +:101CB0000C4C0D492A4604F10800FFF767FF05F1B7 +:101CC000CA0204F110000949FFF760FF05F5CA7266 +:101CD00004F118000649BDE83840FFF757BF00BFC0 +:101CE000182A002020220020043500080E350008A4 +:101CF0001935000870B5044608460D46FEF7EEFF9C +:101D0000C6B22046013403780BB9184670BD32467E +:101D10002946FEF7CFFF0028F3D10120F6E70000A7 +:101D20002DE9F04705460C46FEF7D8FF2B49C6B211 +:101D30002846FFF7DFFF08B10636F6B228492846E5 +:101D4000FFF7D8FF08B11036F6B2632E0BD8DFF8D4 +:101D50008C80DFF88C90234FDFF894A02E7846B962 +:101D60002670BDE8F08729462046BDE8F04701F01F +:101D700065BB252E2ED1072241462846FEF79AFF45 +:101D800070B9194B224603F10C0153F8040B42F8C9 +:101D9000040B8B42F9D11B78137007350D34DDE746 +:101DA000082249462846FEF785FF98B90F4BA21C2A +:101DB000197809090232C95D02F8041C13F8011BE5 +:101DC00001F00F015345C95D02F8031CF0D118342E +:101DD0000835C3E704F8016B0135BFE7F0350008AB +:101DE0001935000806360008F8350008107AFF1F7C +:101DF0001C7AFF1FBFF34F8F024AD368DB03FCD46A +:101E0000704700BF003C024008B5094B1B7873B90E +:101E1000FFF7F0FF074B1A69002ABFBF064A5A6056 +:101E200002F188325A601A6822F480621A6008BD92 +:101E3000762C0020003C02402301674508B50B4B7F +:101E40001B7893B9FFF7D6FF094B1A6942F000429D +:101E50001A611A6842F480521A601A6822F4805299 +:101E60001A601A6842F480621A6008BD762C00205D +:101E7000003C02400B28F0B516D80C4C0C492378D6 +:101E80007BB90C4D0E460C234FF0006255F8047BD5 +:101E900046F8042B013B13F0FF033A44F6D101232B +:101EA000237051F82000F0BD0020FCE7A82C002092 +:101EB000782C002018360008014B53F8200070479A +:101EC000183600080C2070470B2810B5044601D9BD +:101ED000002010BDFFF7CEFF064B53F82430184406 +:101EE000C21A0BB90120F4E712680132F0D1043BA9 +:101EF000F6E700BF183600080B2838B5044628D886 +:101F0000FFF7CEFCFFF776FFFFF77EFF124AF323C1 +:101F1000D360E300DBB243F4007343F002031361C8 +:101F2000136943F48033136105462046FFF762FFCF +:101F3000FFF7A0FF094B53F8241000F0E9F82846FA +:101F4000FFF77CFFFFF7B6FC2046BDE83840FFF7FF +:101F5000BBBF002038BD00BF003C0240183600085F +:101F600012F001032DE9F04105460E4614464BD10F +:101F70008218B2F1016F61D8314B1B6813F0010375 +:101F80005CD0304FFFF78CFCFFF73EFFF323FB6084 +:101F9000FFF730FF314640F20128032C18D824F017 +:101FA0000104284E0C446D1A40F20118A142336915 +:101FB00005EB01072AD123F001033361FFF73EFF50 +:101FC000FFF778FC0120BDE8F081043C0435E4E72C +:101FD000AB07E4D13B6923F440733B613B6943EABF +:101FE00008033B6151F8046B2E60BFF34F8FFFF77E +:101FF00001FF2B689E42E8D03B6923F001033B615F +:10200000FFF71CFFFFF756FC0020DCE723F44073CA +:102010003361336943EA080333610B883B80BFF3C4 +:102020004F8FFFF7E7FE3F8831F8023BBFB2BB425C +:10203000BCD0336923F001033361E1E71846C2E7FE +:1020400000380240003C0240084908B50B7828B12E +:102050001BB9FFF7D9FE01230B7008BD002BFCD084 +:10206000BDE808400870FFF7E9BE00BF762C0020ED +:1020700010B50244064BD2B2904200D110BD441CB0 +:1020800000B253F8200041F8040BE0B2F4E700BFBF +:10209000502800400F4B30B51C6F240407D41C6F30 +:1020A00044F400741C671C6F44F400441C670A4C21 +:1020B000236843F4807323600244084BD2B29042F9 +:1020C00000D130BD441C00B251F8045B43F82050ED +:1020D000E0B2F4E7003802400070004050280040B1 +:1020E00007B5012201A90020FFF7C2FF019803B044 +:1020F0005DF804FB13B50446FFF7F2FFA04205D0DC +:10210000012201A900200194FFF7C4FF02B010BD15 +:1021100070470000034B1A681AB9034AD2F87428B2 +:102120001A607047AC2C00200030024008B5FFF761 +:10213000F1FF024B1868C0F3407008BDAC2C0020C2 +:10214000EFF3098305494A6B22F001024A636833C1 +:1021500083F30988002383F31188704700EF00E0C0 +:10216000202080F3118862B60C4B0D4AD96821F407 +:10217000E0610904090C0A43DA60D3F8FC2009493C +:1021800042F08072C3F8FC200A6842F001020A6043 +:102190001022DA7783F82200704700BF00ED00E0DC +:1021A0000003FA05001000E010B5202383F3118826 +:1021B0000E4B5B6813F4006314D0F1EE103AEFF3AA +:1021C0000984683C4FF08073E361094BDB6B236645 +:1021D00084F30988FFF714FB10B1064BA36110BD0F +:1021E000054BFBE783F31188F9E700BF00ED00E042 +:1021F00000EF00E0370300083A03000870470000D2 +:10220000FEE700000A4B0B480B4A90420BD30B4BE6 +:10221000DA1C121AC11E22F003028B4238BF0022C0 +:102220000021FEF763BD53F8041B40F8041BECE7E4 +:10223000B8370008A82D0020A82D0020A82D0020C8 +:102240007047000070B5D0E915439E6800224FF03A +:10225000FF3504EB42135101D3F800090028BEBF3B +:10226000D3F8000940F08040C3F80009D3F8000B10 +:102270000028BEBFD3F8000B40F08040C3F8000B2D +:10228000013263189642C3F80859C3F8085BE0D2DC +:102290004FF00113C4F81C3870BD00001D4B03EB58 +:1022A00080022DE9F043D2F80CC05D6DDCF81420FB +:1022B000461CD2F800E005EB063605EB40185168E5 +:1022C00071450AD3D5F83438012202FA00F023EA26 +:1022D0000000C5F83408BDE8F083BCF81040AEEB50 +:1022E0000103A34228BF2346D8F81849A4B2B3EB90 +:1022F000840FF0D89468A4F1040959F8047F37607A +:10230000A4EB09071F44042FF7D81C440B44946026 +:102310005360D4E7B02C0020890141F02001016115 +:1023200003699B06FCD41220FFF7D4BA10B5054C04 +:102330002046FEF753FF4FF0A0436365024BA365B1 +:1023400010BD00BFB02C00206C36000870B50378BB +:10235000012B054650D12A4B446D98421BD1294B85 +:102360005A6B42F080025A635A6D42F080025A65FD +:102370005A6D5A6942F080025A615A6922F080020D +:102380005A610E2143205B6900F0D4FB1E4BE360D1 +:102390001E4BC4F800380023C4F8003EC02323605D +:1023A0006E6D4FF40413A3633369002BFCDA012331 +:1023B00033610C20FFF78EFA3369DB07FCD412205F +:1023C000FFF788FA3369002BFCDA0026A66028465E +:1023D000FFF738FF6B68C4F81068DB68C4F814684E +:1023E000C4F81C684BB90A4BA3614FF0FF3363611B +:1023F000A36843F00103A36070BD064BF4E700BF80 +:10240000B02C00200038024040140040030020029D +:10241000003C30C0083C30C0F8B5446D0546002192 +:102420002046FFF779FFA96D00234FF001128F6856 +:10243000C4F834384FF00066C4F81C284FF0FF3061 +:1024400004EB431201339F42C2F80069C2F8006BEB +:10245000C2F80809C2F8080BF2D20B686A6DEB6586 +:10246000636210231361166916F01006FBD1122067 +:10247000FFF730FAD4F8003823F4FE63C4F80038CC +:10248000A36943F4402343F01003A3610923C4F874 +:102490001038C4F814380A4BEB604FF0C043C4F84E +:1024A000103B084BC4F8003BC4F81069C4F800396D +:1024B000EB6D03F1100243F48013EA65A362F8BDEB +:1024C0004836000840800010426D90F84E10D2F857 +:1024D000003823F4FE6343EA0113C2F80038704762 +:1024E0002DE9F84300EB8103456DDA68166806F0C4 +:1024F0000306731E022B05EB41130C4680460FFAB0 +:1025000081F94FEA41104FF00001C3F8101B4FF062 +:10251000010104F1100398BFB60401FA03F39169B5 +:102520008EBF334E06F1805606F5004600293AD09C +:10253000578A04F15801490137436F50D5F81C18E8 +:102540000B43C5F81C382B180021C3F81019536928 +:102550000127611EA7409BB3138A928B9B08012A17 +:1025600088BF5343D8F85C20981842EA034301F12E +:10257000400205EB8202C8F85C0021465360284601 +:10258000FFF7CAFE08EB8900C3681B8A43EA84533D +:10259000483464011E432E51D5F81C381F43C5F83A +:1025A0001C78BDE8F88305EB4917D7F8001B21F428 +:1025B0000041C7F8001BD5F81C1821EA0303C0E747 +:1025C00004F13F0305EB83030A4A5A60284621467B +:1025D000FFF7A2FE05EB4910D0F8003923F40043C1 +:1025E000C0F80039D5F81C3823EA0707D7E700BF41 +:1025F0000080001000040002826D1268C265FFF7BF +:1026000021BE00005831436D49015B5813F400406E +:1026100004D013F4001F0CBF0220012070470000FB +:102620004831436D49015B5813F4004004D013F462 +:10263000001F0CBF022001207047000000EB810149 +:10264000CB68196A0B6813604B68536070470000D1 +:1026500000EB810330B5DD68AA691368D36019B94E +:10266000402B84BF402313606B8A1468426D1C4466 +:10267000013CB4FBF3F46343033323F0030302EBA5 +:10268000411043EAC44343F0C043C0F8103B2B68F9 +:1026900003F00303012B09B20ED1D2F8083802EB84 +:1026A000411013F4807FD0F8003B14BF43F08053F7 +:1026B00043F00053C0F8003B02EB4112D2F8003B5C +:1026C00043F00443C2F8003B30BD00002DE9F04167 +:1026D000244D6E6D06EB40130446D3F8087BC3F817 +:1026E000087B38070AD5D6F81438190706D505EB44 +:1026F00084032146DB6828465B689847FA071FD5A4 +:10270000D6F81438DB071BD505EB8403D968CCB9A0 +:102710008B69488A5A68B2FBF0F600FB16228AB928 +:102720001868DA6890420DD2121AC3E900242023F7 +:1027300083F311880B482146FFF78AFF84F3118841 +:10274000BDE8F081012303FA04F26B8923EA020356 +:102750006B81CB68002BF3D021460248BDE8F041E5 +:10276000184700BFB02C002000EB810370B5DD6876 +:10277000436D6C692668E6604A0156BB1A444FF403 +:102780000020C2F810092A6802F00302012A0AB2E6 +:102790000ED1D3F8080803EB421410F4807FD4F86C +:1027A000000914BF40F0805040F00050C4F8000908 +:1027B00003EB4212D2F8000940F00440C2F80009CD +:1027C000D3F83408012202FA01F10143C3F83418A6 +:1027D00070BD19B9402E84BF4020206020682E8A29 +:1027E0008419013CB4FBF6F440EAC44040F00050C8 +:1027F0001A44C6E7F8B504461E48456D05EB441378 +:10280000D3F80869C3F80869F10717D5D5F8103867 +:10281000DA0713D500EB8403D9684B691F68DA68BF +:10282000974218D2D21B00271A605F60202383F3DF +:1028300011882146FFF798FF87F31188330617D5D3 +:10284000D5F834280123A340134211D02046BDE817 +:10285000F840FFF723BD012303FA04F2038923EABA +:10286000020303818B68002BE8D021469847E5E7F7 +:10287000F8BD00BFB02C00202DE9F74F984C666DD5 +:102880007569B3691D4015F48058756107D02046FD +:10289000FEF70AFD03B0BDE8F04FFFF785BC002D41 +:1028A00012DAD6F8003E8E489F071EBFD6F8003ECB +:1028B00023F00303C6F8003ED6F8043823F00103E2 +:1028C000C6F80438FEF718FD280505D58448FFF73B +:1028D000B9FC8348FEF700FDA9040CD5D6F80838EA +:1028E00013F0060FF36823F470530CBF43F4105336 +:1028F00043F4A053F3602A0704D56368DB680BB187 +:1029000077489847EB0274D4AF0227D5D4F8549097 +:10291000DFF8CCB100274FF0010A09EB4712D2F8DB +:10292000003B03F44023B3F5802F11D1D2F8003BD4 +:10293000002B0DDA62890AFA07F322EA03036381A6 +:1029400004EB8703DB68DB6813B1394658469847C8 +:10295000A36D01379B68FFB29F42DED9E80617D509 +:10296000676D3A6AC2F30A1002F00F0302F4F01224 +:10297000B2F5802F00F08880B2F5402F08D104EB2B +:1029800083030022DB681B6A07F5805790426DD1F4 +:102990002903D6F8184813D5E20302D50020FFF723 +:1029A00095FEA30302D50120FFF790FE670302D531 +:1029B0000220FFF78BFE260302D50320FFF786FED9 +:1029C0006D037FF567AFE00702D50020FFF712FF28 +:1029D000A10702D50120FFF70DFF620702D50220F3 +:1029E000FFF708FF23077FF555AF0320FFF702FF2E +:1029F00050E7636DDFF8E8B0019300274FF0010A5C +:102A0000A36D9B685FFA87F999453FF67DAF019BFF +:102A100003EB4913D3F8002902F44022B2F5802FCA +:102A200022D1D3F80029002A1EDAD3F8002942F077 +:102A30009042C3F80029D3F80029002AFBDB606D1F +:102A40004946FFF769FC22890AFA09F322EA0303DF +:102A5000238104EB8903DB689B6813B14946584620 +:102A600098474846FFF71AFC0137C9E7910708BFA6 +:102A7000D7F80080072A98BF03F8018B02F1010202 +:102A800098BF4FEA182881E7023304EB830207F569 +:102A900080575268D2F818C0DCF80820DCE9001C26 +:102AA000A1EB0C0C002188420AD104EB830463687B +:102AB0009B699A6802449A605A6802445A6067E7C0 +:102AC00011F0030F08BFD7F800808C4588BF02F8CB +:102AD000018B01F1010188BF4FEA1828E3E700BF2D +:102AE000B02C0020436D03EB4111D1F8003B43F4BF +:102AF0000013C1F8003B7047436D03EB4111D1F85F +:102B0000003943F40013C1F800397047436D03EBFB +:102B10004111D1F8003B23F40013C1F8003B70478A +:102B2000436D03EB4111D1F8003923F40013C1F8D0 +:102B30000039704700F1604303F561430901C9B2F0 +:102B400083F80013012200F01F039A4043099B0001 +:102B500003F1604303F56143C3F880211A607047B5 +:102B600030B5039C0172043304FB0325C0E906530E +:102B7000049B03630021059BC160C0E90000C0E91C +:102B80000422C0E90842C0E90A11436330BD0000D5 +:102B9000416A0022C0E90411C0E90A22C2606FF054 +:102BA0000101FEF707BF0000D0E90432934201D1D2 +:102BB000C2680AB9181D7047002070470369196080 +:102BC000C2680132C260C2691344826903619342E0 +:102BD00024BF436A03610021FEF7E0BE38B5044616 +:102BE0000D46E3683BB16269131D1268A36213448A +:102BF000E362002007E0237A33B929462046FEF736 +:102C0000BDFE0028EDDA38BD6FF00100FBE70000E3 +:102C1000C368C269013BC36043691344826943616D +:102C2000934224BF436A436100238362036B03B171 +:102C30001847704770B52023044683F31188866ACD +:102C40003EB9FFF7CBFF054618B186F31188284639 +:102C500070BDA36AE26A13F8015BA362934202D3D8 +:102C60002046FFF7D5FF002383F31188EFE700002C +:102C70002DE9F84F04460E46174698464FF02009B6 +:102C800089F311880025AA46D4F828B0BBF1000FBB +:102C900009D141462046FFF7A1FF20B18BF31188EF +:102CA0002846BDE8F88FD4E90A12A7EB050B521AA3 +:102CB000934528BF9346BBF1400F1BD9334601F122 +:102CC000400251F8040B43F8040B9142F9D1A36A76 +:102CD00040334036A3624035D4E90A239A4202D3F6 +:102CE0002046FFF795FF8AF31188BD42D8D289F3B9 +:102CF0001188C9E730465A46FDF7D2FFA36A5B4404 +:102D00005E44A3625D44E7E710B5029C01720433A0 +:102D100004FB0321C0E906130023C0E90A33039B27 +:102D20000363049BC460C0E90000C0E90422C0E959 +:102D30000842436310BD0000026AC260426AC0E9F3 +:102D400004220022C0E90A226FF00101FEF732BE20 +:102D5000D0E904239A4201D1C26822B9184650F83A +:102D6000043B0B607047002070470000C368C269D5 +:102D70000133C3604369134482694361934224BFB2 +:102D8000436A43610021FEF709BE000038B50446DE +:102D90000D46E3683BB123691A1DA262E269134440 +:102DA000E362002007E0237A33B929462046FEF784 +:102DB000E5FD0028EDDA38BD6FF00100FBE700000B +:102DC00003691960C268013AC260C269134482692A +:102DD0000361934224BF436A036100238362036B50 +:102DE00003B118477047000070B520230D46044614 +:102DF000114683F31188866A2EB9FFF7C7FF10B119 +:102E000086F3118870BDA36A1D70A36AE26A01335C +:102E10009342A36204D3E16920460439FFF7D0FF4F +:102E2000002080F31188EDE72DE9F84F04460D46A8 +:102E3000904699464FF0200A8AF311880026B3463F +:102E4000A76A4FB949462046FFF7A0FF20B187F394 +:102E500011883046BDE8F88FD4E90A073A1AA8EB82 +:102E60000607974228BF1746402F1BD905F140039C +:102E700055F8042B40F8042B9D42F9D1A36A403346 +:102E8000A3624036D4E90A239A4204D3E16920467A +:102E90000439FFF795FF8BF311884645D9D28AF3A1 +:102EA0001188CDE729463A46FDF7FAFEA36A3B446E +:102EB0003D44A3623E44E5E7D0E904239A4217D19A +:102EC000C3689BB1836A8BB1043B9B1A0ED013601D +:102ED000C368013BC360C3691A44836902619A42B3 +:102EE00024BF436A036100238362012318467047AD +:102EF0000023FBE700F088B84FF0804300225863BE +:102F00001A610222DA6070474FF080430022DA60D3 +:102F1000704700004FF08043586370474FF0804384 +:102F2000586A70474B6843608B688360CB68C360A6 +:102F30000B6943614B6903628B6943620B680360F1 +:102F40007047000008B5264B26481A6940F2FF1169 +:102F50000A431A611A6922F4FF7222F001021A610F +:102F60001A691A6B0A431A631A6D0A431A651E4AD4 +:102F70001B6D1146FFF7D6FF02F11C0100F58060C2 +:102F8000FFF7D0FF02F1380100F58060FFF7CAFFBC +:102F900002F1540100F58060FFF7C4FF02F17001F7 +:102FA00000F58060FFF7BEFF02F18C0100F5806044 +:102FB000FFF7B8FF02F1A80100F58060FFF7B2FF4C +:102FC00002F1C40100F58060FFF7ACFF02F1E001FF +:102FD00000F58060FFF7A6FFBDE8084000F09AB852 +:102FE00000380240000002407836000808B500F0C2 +:102FF00007FAFEF733FCFFF78DF8BDE80840FEF74F +:1030000055BE000070470000104B1A6C42F00102E0 +:103010001A641A6E42F001021A660D4A1B6E93681A +:1030200043F0010393604FF0804353229A624FF0C4 +:10303000FF32DA6200229A615A63DA605A60012232 +:103040005A6108211A601C20FFF774BD0038024045 +:10305000002004E04FF0804208B51169D3680B40AE +:10306000D9B2C9439B07116107D5202383F3118887 +:10307000FEF714FC002383F3118808BD08B5FFF7A1 +:10308000E9FFBDE80840FFF78FB800001F4B1A6941 +:103090006FEAC2526FEAD2521A611A69C2F3080289 +:1030A0001A614FF0FF301A695A69586100215A6954 +:1030B00059615A691A6A62F080521A621A6A02F0F9 +:1030C00080521A621A6A5A6A58625A6A59625A6A6D +:1030D0001A6C42F080521A641A6E42F080521A66DC +:1030E0001A6E0B4A106840F480701060186F00F47C +:1030F0004070B0F5007F1EBF4FF48030186719672D +:10310000536823F40073536000F05AB9003802404A +:1031100000700040334B4FF080521A64324A4FF433 +:10312000404111601A6842F001021A601A68910762 +:10313000FCD59A6822F003029A602A4B9A6812F032 +:103140000C02FBD1196801F0F90119609A601A6844 +:1031500042F480321A601A689203FCD55A6F42F02A +:1031600001025A671F4B5A6F9007FCD51F4A5A60DD +:103170001A6842F080721A601B4A53685904FCD5E1 +:10318000184B1A689201FCD5194A9A60194B1A68B3 +:10319000194B9A42194B21D1194A1168194A914287 +:1031A0001CD140F205121A60144A136803F00F0391 +:1031B000052BFAD10B4B9A6842F002029A609A688A +:1031C00002F00C02082AFAD15A6C42F480425A6486 +:1031D0005A6E42F480425A665B6E704740F2057246 +:1031E000E1E700BF0038024000700040085440078B +:1031F00000948838002004E011640020003C024064 +:1032000000ED00E041C20F41084A08B5516913685A +:103210000B4003F00103536123B1054A13680BB15E +:1032200050689847BDE80840FEF7BEBF003C01402B +:10323000282D0020084A08B5516913680B4003F097 +:103240000203536123B1054A93680BB1D0689847D4 +:10325000BDE80840FEF7A8BF003C0140282D002033 +:10326000084A08B5516913680B4003F00403536121 +:1032700023B1054A13690BB150699847BDE808406E +:10328000FEF792BF003C0140282D0020084A08B5F7 +:10329000516913680B4003F00803536123B1054AD9 +:1032A00093690BB1D0699847BDE80840FEF77CBF31 +:1032B000003C0140282D0020084A08B551691368D8 +:1032C0000B4003F01003536123B1054A136A0BB19D +:1032D000506A9847BDE80840FEF766BF003C0140D1 +:1032E000282D0020174B10B55A691C68144004F4AF +:1032F00078725A61A30604D5134A936A0BB1D06A57 +:103300009847600604D5104A136B0BB1506B984771 +:10331000210604D50C4A936B0BB1D06B9847E2059C +:1033200004D5094A136C0BB1506C9847A30504D51A +:10333000054A936C0BB1D06C9847BDE81040FEF77E +:1033400033BF00BF003C0140282D00201A4B10B5B0 +:103350005A691C68144004F47C425A61620504D521 +:10336000164A136D0BB1506D9847230504D5134AC7 +:10337000936D0BB1D06D9847E00404D50F4A136EDE +:103380000BB1506E9847A10404D50C4A936E0BB153 +:10339000D06E9847620404D5084A136F0BB1506F82 +:1033A0009847230404D5054A936F0BB1D06F984713 +:1033B000BDE81040FEF7F8BE003C0140282D00207B +:1033C000062108B50846FFF7B5FB06210720FFF7E1 +:1033D000B1FB06210820FFF7ADFB06210920FFF70E +:1033E000A9FB06210A20FFF7A5FB06211720FFF7FE +:1033F000A1FBBDE8084006212820FFF79BBB000089 +:1034000008B5FFF743FE00F00BF8FDF7E5FEFDF70A +:10341000BDFDFFF7F7FDBDE80840FFF76BBD0000FD +:103420000023054A19460133102BC2E9001102F1AD +:103430000802F8D1704700BF282D0020034611F87C +:10344000012B03F8012B002AF9D1704753544D3357 +:1034500032463F3F3F00000053544D333246343034 +:10346000780053544D3332463432780053544D3340 +:103470003246343436585800000000004C340008FE +:103480003F00000013040000583400083F00000013 +:1034900019040000623400083F000000210400000D +:1034A0006C3400083F00000000000000090F000815 +:1034B000F50E0008310F00081D0F0008290F000845 +:1034C000150F0008010F0008ED0E00083D0F000861 +:1034D0000000000001000000000000006D61696E46 +:1034E0000000000069646C6500000000E43400081E +:1034F000D8230020502500200100000059180008A2 +:10350000000000004172647550696C6F74002542C0 +:103510004F415244252D424C002553455249414CC0 +:103520002500000002000000000000002511000836 +:103530009111000840004000E8290020F8290020EF +:103540000200000000000000030000000000000076 +:10355000D51100080000000010000000082A00201B +:10356000000000000100000000000000B02C00205E +:1035700001010200491C0008591B0008F51B000846 +:10358000D91B0008430000008C35000809024300E5 +:10359000020100C0320904000001020201000524FA +:1035A0000010010524010001042402020524060084 +:1035B00001070582030800FF09040100020A000058 +:1035C00000070501024000000705810240000000DD +:1035D00012000000D835000812011001020000405E +:1035E000091241570002010203010000040309040B +:1035F00025424F41524425007370656564796265C8 +:103600006566347633003031323334353637383905 +:103610004142434445460000004000000040000095 +:103620000040000000400000000001000000020017 +:103630000000020000000200000002000000020082 +:103640000000020000000200000000000D1300084E +:10365000C51500087116000840004000102D00201C +:10366000102D002001000000202D0020800000000F +:103670004001000003000000000180420000000043 +:10368000AAAAAAAA00010040FFFF00000000000053 +:1036900000A00A000000000100000000AAAAAAAAD7 +:1036A00000000001FFFF000000000000000000001B +:1036B0000000010000000000AAAAAAAA0000000061 +:1036C000FFFE0000000000000000000000000000FD +:1036D00000000000AAAAAAAA00000000FFFF000044 +:1036E00000000000000000000000000000000000DA +:1036F000AAAAAAAA00000000FFFF00000000000024 +:10370000000000000000000000000000AAAAAAAA11 +:1037100000000000FFFF00000000000000000000AB +:103720000000000000000000AAAAAAAA00000000F1 +:10373000FFFF00000000000000000000000000008B +:10374000000000000A00000000000000030000006C +:103750000000000000000000000000000000000069 +:103760000000000000000000000000000000000059 +:1037700000000000000000003A040000000000000B +:1037800000400F0000000000FF009600000000084D +:10379000009600000000080004000000EC3500085E +:1037A0000000000000000000000000000000000019 +:0837B000000000000000000011 +:00000001FF diff --git a/Tools/completion/bash/_ap_autotest b/Tools/completion/bash/_ap_autotest old mode 100644 new mode 100755 diff --git a/Tools/completion/bash/_ap_bin b/Tools/completion/bash/_ap_bin old mode 100644 new mode 100755 diff --git a/Tools/completion/bash/_sim_vehicle b/Tools/completion/bash/_sim_vehicle old mode 100644 new mode 100755 diff --git a/Tools/completion/bash/_waf b/Tools/completion/bash/_waf old mode 100644 new mode 100755 diff --git a/Tools/completion/completion.bash b/Tools/completion/completion.bash old mode 100644 new mode 100755 diff --git a/Tools/completion/completion.zsh b/Tools/completion/completion.zsh old mode 100644 new mode 100755 diff --git a/Tools/debug/gdb_crashdump.sh b/Tools/debug/gdb_crashdump.sh new file mode 100755 index 00000000000..89f6b4d66c1 --- /dev/null +++ b/Tools/debug/gdb_crashdump.sh @@ -0,0 +1,13 @@ +#!/bin/bash + +# script to more easily get a backtrace from an ArduPilot crash_dump.bin + +[ $# -eq 2 ] || { + echo "Usage: gdb_crashdump.sh ELF_FILE CRASH_DUMP" + exit 1 +} + +ELF_FILE=$1 +CRASH_DUMP=$2 + +arm-none-eabi-gdb -nx "$ELF_FILE" -ex "set target-charset ASCII" -ex "target remote | modules/CrashDebug/bins/lin64/CrashDebug --elf $ELF_FILE --dump $CRASH_DUMP" diff --git a/Tools/environment_install/install-ROS-ubuntu.sh b/Tools/environment_install/install-ROS-ubuntu.sh new file mode 100644 index 00000000000..90804c15dbc --- /dev/null +++ b/Tools/environment_install/install-ROS-ubuntu.sh @@ -0,0 +1,253 @@ +#!/bin/bash +echo "---------- $0 start ----------" +set -e +# set -x + +ROS_WS_ROOT=$HOME/ardupilot-ws + +red=`tput setaf 1` +green=`tput setaf 2` +reset=`tput sgr0` + +sep="##############################################" + + +function heading() { + echo "$sep" + echo $* + echo "$sep" +} + +ASSUME_YES=false + +function maybe_prompt_user() { + if $ASSUME_YES; then + return 0 + else + read -p "$1" + if [[ $REPLY =~ ^[Yy]$ ]]; then + return 0 + else + return 1 + fi + fi +} + +function usage +{ + echo "Usage: ./installROS.sh [[-p package] | [-h]]" + echo "Install ROS1" + echo "This script will select the ROS distribution according to the OS being used" + echo "Installs desktop-full as default base package; Use -p to override" + echo "-p | --package ROS package to install" + echo " Multiple usage allowed" + echo " Must include one of the following:" + echo " ros-base" + echo " desktop" + echo " desktop-full" + echo "-h | --help This message" +} + +function shouldInstallPackages +{ + echo "${red}Your package list did not include a recommended base package${reset}" + echo "Please include one of the following:" + echo " ros-base" + echo " desktop" + echo " desktop-full" + echo "" + echo "ROS not installed" +} + +function package_is_installed() { + dpkg-query -W -f='${Status}' "$1" 2>/dev/null | grep -c "ok installed" +} + +# Iterate through command line inputs +packages=() +while [ "$1" != "" ]; do + case $1 in + -p | --package ) shift + packages+=("$1") + ;; + -h | --help ) usage + exit + ;; + * ) usage + exit 1 + esac + shift +done + +# Install lsb-release as it is needed to check Ubuntu version +if ! package_is_installed "lsb-release"; then + heading "Installing lsb-release" + sudo apt install lsb-release -y + echo "Done!" +fi + +# Checking Ubuntu release to adapt software version to install +RELEASE_CODENAME=$(lsb_release -c -s) +PYTHON_V="python3" # starting from ubuntu 20.04, python isn't symlink to default python interpreter + + +# echo $RELEASE_CODENAME + +if [ ${RELEASE_CODENAME} == 'bionic' ] ; then + #Ubuntu 18.04 - Melodic + ROS_VERSION="melodic" + PYTHON_V="python2" + heading "${green}Detected Ubuntu 18.04, installing ROS Melodic${reset}" +elif [ ${RELEASE_CODENAME} == 'buster' ]; then + #RPi Buster - Melodic + ROS_VERSION="melodic" + PYTHON_V="python2" + heading "${green}Detected RPi Buster, installing ROS Melodic${reset}" +elif [ ${RELEASE_CODENAME} == 'focal' ]; then + #Ubuntu 20.04 - Noetic + ROS_VERSION="noetic" + PYTHON_V="python3" + heading "${green}Detected Ubuntu 20.04, installing ROS Noetic${reset}" +elif [ ${RELEASE_CODENAME} == 'jammy' ]; then + #Ubuntu 22.04 - unsupported only ROS2 + heading "${red}Currently only ROS1 is supported. This Ubuntu release can only be used with ROS2.${reset}" + exit 1 +else + # We assume an unsupported OS is being used. + heading "${red}Unsupported OS detected. Please refer to the ROS webpage to find how to install ROS1 on your system if at all possible.${reset}" + exit 1 +fi + +# Check to see if other packages were specified +# If not, set the default base package +if [ ${#packages[@]} -eq 0 ] ; then + packages+="desktop-full" +fi +echo "Packages to install: "${packages[@]} +# Check to see if we have a ROS base kinda thingie +hasBasePackage=false +for package in "${packages[@]}"; do + if [[ $package == "ros-base" ]]; then + delete=ros-base + packages=( "${packages[@]/$delete}" ) + packages+=" ros-${ROS_VERSION}-ros-base" + hasBasePackage=true + break + elif [[ $package == "desktop" ]]; then + delete=desktop + packages=( "${packages[@]/$delete}" ) + packages+=" ros-${ROS_VERSION}-desktop" + hasBasePackage=true + break + elif [[ $package == "desktop-full" ]]; then + delete=desktop-full + packages=( "${packages[@]/$delete}" ) + packages+=" ros-${ROS_VERSION}-desktop-full" + hasBasePackage=true + break + fi +done +if [ $hasBasePackage == false ] ; then + shouldInstallPackages + exit 1 +fi + +heading "${green}Adding Repositories and source lists${reset}" +#Lets start instaling stuff +sudo apt install software-properties-common -y +sudo apt-add-repository universe +sudo apt-add-repository multiverse +sudo apt-add-repository restricted + +# Setup sources.lst +sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list' +# Setup keys +sudo apt-key adv --keyserver 'hkp://keyserver.ubuntu.com:80' --recv-key C1CF6E31E6BADE8868B172B4F42ED6FBAB17C654 +# If you experience issues connecting to the keyserver, you can try substituting hkp://pgp.mit.edu:80 or hkp://keyserver.ubuntu.com:80 in the previous command. +# Installation + +heading "${green}Updating apt${reset}" +sudo apt update + +heading "${green}Installing ROS${reset}" +# Here we loop through any packages passed on the command line +# Install packages ... +for package in "${packages[@]}"; do + sudo apt install $package -y +done + +# This is where you might start to modify the packages being installed, i.e.# sudo apt install ros-${ROS_VERSION}-{package_name} +# sudo apt install -y setpriv +# sudo apt install -y ros-${ROS_VERSION}-robot-upstart +# sudo apt install -y ros-${ROS_VERSION}-navigation + +# Install MAVROS and the geographic libs +sudo apt install -y ros-${ROS_VERSION}-mavros + +wget https://raw.githubusercontent.com/mavlink/mavros/master/mavros/scripts/install_geographiclib_datasets.sh +sudo bash ./install_geographiclib_datasets.sh + +# install other needed packages +sudo apt install build-essential cmake -y + +# +# To find available packages: +# apt-cache search ros-melodic +# +# Initialize rosdep + +heading "${green}Installing rosdep${reset}" + +sudo apt install ${PYTHON_V}-rosdep -y +# Certificates are messed up on earlier version Jetson for some reason +# Do not know if it is an issue with the Xavier, test by commenting out +# sudo c_rehash /etc/ssl/certs +# Initialize rosdep + +heading "${green}Initializaing rosdep${reset}" + +sudo rosdep init || true +# To find available packages, use: +rosdep update +# Use this to install dependencies of packages in a workspace +# rosdep install --from-paths src --ignore-src --rosdistro=${ROS_DISTRO} -y +# Environment Setup - Don't add /opt/ros/${ROS_VERSION}/setup.bash if it's already in bashrc +if maybe_prompt_user "Do you want to add ROS_HOSTNAME and ROS_MASTER_URI to your .bashrc [N/y]?" ; then + heading "${green}Adding setup.bash, ROS_MASTER_URI and ROS_HOSTNAME to .bashrc ${reset}" + grep -q -F "ROS_HOSTNAME=$HOSTNAME.local" ~/.bashrc || echo "ROS_HOSTNAME=$HOSTNAME.local" >> ~/.bashrc + grep -q -F "ROS_MASTER_URI=http://$HOSTNAME.local:11311" ~/.bashrc || echo "ROS_MASTER_URI=http://$HOSTNAME.local:11311" >> ~/.bashrc + grep -q -F "source /opt/ros/${ROS_VERSION}/setup.bash" ~/.bashrc || echo "source /opt/ros/${ROS_VERSION}/setup.bash" >> ~/.bashrc + source ~/.bashrc +fi + +heading "${green}Installing rosinstall tools${reset}" + +sudo apt install ${PYTHON_V}-rosinstall ${PYTHON_V}-rosinstall-generator ${PYTHON_V}-wstool ${PYTHON_V}-catkin-tools -y + +heading "${green}Installing Ardupilot-ROS workspace${reset}" + +if maybe_prompt_user "Add ardupilot-ws to your home folder [N/y]?" ; then + if [ ! -d $ROS_WS_ROOT ]; then + mkdir -p $ROS_WS_ROOT/src + pushd $ROS_WS_ROOT + catkin init + pushd src + git clone https://github.com/ArduPilot/ardupilot_ros.git + popd + sudo apt update + rosdep install --from-paths src --ignore-src --rosdistro=${ROS_DISTRO} -y + catkin build + popd + else + heading "${red}ardupilot-ws already exists, skipping...${reset}" + fi + +else + echo "Skipping adding ardupilot_ws to your home folder." +fi + +heading "${green}Adding setup.bash, ROS_MASTER_URI and ROS_HOSTNAME to .bashrc ${reset}" +grep -q -F "source $ROS_WS_ROOT/devel/setup.bash" ~/.bashrc || echo "source $ROS_WS_ROOT/devel/setup.bash" >> ~/.bashrc +source ~/.bashrc + +heading "${green}Installation complete! Please close this terminal and open a new one for changes to take effect!${reset}" diff --git a/Tools/environment_install/install-prereqs-arch.sh b/Tools/environment_install/install-prereqs-arch.sh index 908fc08c37f..2681c38d9f3 100755 --- a/Tools/environment_install/install-prereqs-arch.sh +++ b/Tools/environment_install/install-prereqs-arch.sh @@ -23,10 +23,10 @@ while getopts "yq" opt; do done BASE_PKGS="base-devel ccache git gsfonts tk wget gcc" -SITL_PKGS="python-pip python-setuptools python-wheel wxpython opencv python-numpy python-scipy" +SITL_PKGS="python-pip python-setuptools python-wheel python-wxpython opencv python-numpy python-scipy" PX4_PKGS="lib32-glibc zip zlib ncurses" -PYTHON_PKGS="future lxml pymavlink MAVProxy argparse matplotlib pyparsing geocoder pyserial empy" +PYTHON_PKGS="future lxml pymavlink MAVProxy pexpect argparse matplotlib pyparsing geocoder pyserial empy dronecan" # GNU Tools for ARM Embedded Processors # (see https://launchpad.net/gcc-arm-embedded/) @@ -68,7 +68,7 @@ pip3 -q install --user -U $PYTHON_PKGS if [ ! -d $OPT/$ARM_ROOT ]; then ( cd $OPT; - sudo wget $ARM_TARBALL_URL; + sudo wget --progress=dot:giga $ARM_TARBALL_URL; sudo tar xjf ${ARM_TARBALL}; sudo rm ${ARM_TARBALL}; ) diff --git a/Tools/environment_install/install-prereqs-mac.sh b/Tools/environment_install/install-prereqs-mac.sh index 7039f8ecd29..9b72ba9ac91 100755 --- a/Tools/environment_install/install-prereqs-mac.sh +++ b/Tools/environment_install/install-prereqs-mac.sh @@ -96,6 +96,13 @@ function maybe_prompt_user() { fi } +# delete links installed by github in /usr/local/bin; installing or +# upgrading python via brew fails if these links are in place. brew +# auto-updates things when you install other packages which depend on +# more recent versions. +# see https://github.com/orgs/Homebrew/discussions/3895 +find /usr/local/bin -lname '*/Library/Frameworks/Python.framework/*' -delete + brew update brew install gawk curl coreutils wget @@ -111,7 +118,7 @@ if maybe_prompt_user "Install python using pyenv [N/y]?" ; then pushd $HOME/.pyenv git fetch --tags - git checkout v2.0.4 + git checkout v2.3.9 popd exportline="export PYENV_ROOT=\$HOME/.pyenv" echo $exportline >> ~/$SHELL_LOGIN @@ -124,8 +131,12 @@ if maybe_prompt_user "Install python using pyenv [N/y]?" ; then source ~/$SHELL_LOGIN } echo "pyenv installed" - env PYTHON_CONFIGURE_OPTS="--enable-framework" pyenv install 3.9.4 - pyenv global 3.9.4 + { + $(pyenv global 3.10.4) + } || { + env PYTHON_CONFIGURE_OPTS="--enable-framework" pyenv install 3.10.4 + pyenv global 3.10.4 + } fi @@ -148,7 +159,7 @@ if [[ $DO_AP_STM_ENV -eq 1 ]]; then install_arm_none_eabi_toolchain fi -PYTHON_PKGS="future lxml pymavlink MAVProxy pexpect geocoder flake8 empy" +PYTHON_PKGS="future lxml pymavlink MAVProxy pexpect geocoder flake8 empy dronecan" # add some Python packages required for commonly-used MAVProxy modules and hex file generation: if [[ $SKIP_AP_EXT_ENV -ne 1 ]]; then PYTHON_PKGS="$PYTHON_PKGS intelhex gnureadline" diff --git a/Tools/environment_install/install-prereqs-ubuntu.sh b/Tools/environment_install/install-prereqs-ubuntu.sh index eddef64ef4e..61b9b282e3a 100755 --- a/Tools/environment_install/install-prereqs-ubuntu.sh +++ b/Tools/environment_install/install-prereqs-ubuntu.sh @@ -59,34 +59,35 @@ fi # Checking Ubuntu release to adapt software version to install RELEASE_CODENAME=$(lsb_release -c -s) -PYTHON_V="python" # starting from ubuntu 20.04, python isn't symlink to default python interpreter -PIP=pip2 - -if [ ${RELEASE_CODENAME} == 'xenial' ]; then - SITLFML_VERSION="2.3v5" - SITLCFML_VERSION="2.3" -elif [ ${RELEASE_CODENAME} == 'disco' ]; then +PYTHON_V="python3" # starting from ubuntu 20.04, python isn't symlink to default python interpreter +PIP=pip3 + +if [ ${RELEASE_CODENAME} == 'bionic' ] ; then + SITLFML_VERSION="2.4" + SITLCFML_VERSION="2.4" + PYTHON_V="python" + PIP=pip2 +elif [ ${RELEASE_CODENAME} == 'buster' ]; then SITLFML_VERSION="2.5" SITLCFML_VERSION="2.5" -elif [ ${RELEASE_CODENAME} == 'eoan' ]; then + PYTHON_V="python" + PIP=pip2 +elif [ ${RELEASE_CODENAME} == 'focal' ] || [ ${RELEASE_CODENAME} == 'ulyssa' ]; then SITLFML_VERSION="2.5" SITLCFML_VERSION="2.5" -elif [ ${RELEASE_CODENAME} == 'focal' ] || [ ${RELEASE_CODENAME} == 'ulyssa' ]; then + PYTHON_V="python3" + PIP=pip3 +elif [ ${RELEASE_CODENAME} == 'jammy' ]; then SITLFML_VERSION="2.5" SITLCFML_VERSION="2.5" PYTHON_V="python3" PIP=pip3 elif [ ${RELEASE_CODENAME} == 'groovy' ] || - [ ${RELEASE_CODENAME} == 'hirsute' ] || - [ ${RELEASE_CODENAME} == 'bullseye' ] || - [ ${RELEASE_CODENAME} == 'impish' ]; then + [ ${RELEASE_CODENAME} == 'bullseye' ]; then SITLFML_VERSION="2.5" SITLCFML_VERSION="2.5" PYTHON_V="python3" PIP=pip3 -elif [ ${RELEASE_CODENAME} == 'trusty' ]; then - SITLFML_VERSION="2" - SITLCFML_VERSION="2" else # We assume APT based system, so let's try with apt-cache first. SITLCFML_VERSION=$(apt-cache search -n '^libcsfml-audio' | cut -d" " -f1 | head -1 | grep -Eo '[+-]?[0-9]+([.][0-9]+)?') @@ -113,7 +114,7 @@ if [ "$ARM_PKG_CONFIG_NOT_PRESENT" -eq 1 ]; then $APT_GET install pkg-config if [ -f /usr/share/pkg-config-crosswrapper ]; then # We are on non-Ubuntu so simulate effect of installing pkg-config-arm-linux-gnueabihf. - sudo ln -s /usr/share/pkg-config-crosswrapper /usr/bin/arm-linux-gnueabihf-pkg-config + sudo ln -sf /usr/share/pkg-config-crosswrapper /usr/bin/arm-linux-gnueabihf-pkg-config else echo "Warning: unable to link to pkg-config-crosswrapper" fi @@ -124,16 +125,20 @@ fi # Lists of packages to install BASE_PKGS="build-essential ccache g++ gawk git make wget" -if [ ${RELEASE_CODENAME} == 'xenial' ] || [ ${RELEASE_CODENAME} == 'disco' ] || [ ${RELEASE_CODENAME} == 'eoan' ]; then +if [ ${RELEASE_CODENAME} == 'bionic' ]; then # use fixed version for package that drop python2 support - PYTHON_PKGS="future lxml pymavlink MAVProxy pexpect flake8==3.7.9 geocoder empy configparser==5.0.0 click==7.1.2 decorator==4.4.2" + PYTHON_PKGS="future lxml pymavlink MAVProxy pexpect flake8==3.7.9 requests==2.27.1 monotonic==1.6 geocoder empy configparser==4.0.2 click==7.1.2 decorator==4.4.2 dronecan" else - PYTHON_PKGS="future lxml pymavlink MAVProxy pexpect flake8 geocoder empy" + PYTHON_PKGS="future lxml pymavlink MAVProxy pexpect flake8 geocoder empy dronecan" fi # add some Python packages required for commonly-used MAVProxy modules and hex file generation: if [[ $SKIP_AP_EXT_ENV -ne 1 ]]; then - PYTHON_PKGS="$PYTHON_PKGS pygame intelhex" + if [ ${RELEASE_CODENAME} == 'bionic' ]; then + PYTHON_PKGS="$PYTHON_PKGS pygame==2.0.3 intelhex" + else + PYTHON_PKGS="$PYTHON_PKGS pygame intelhex" + fi fi ARM_LINUX_PKGS="g++-arm-linux-gnueabihf $INSTALL_PKG_CONFIG" # python-wxgtk packages are added to SITL_PKGS below @@ -149,27 +154,50 @@ fi # ArduPilot official Toolchain for STM32 boards function install_arm_none_eabi_toolchain() { - # GNU Tools for ARM Embedded Processors - # (see https://launchpad.net/gcc-arm-embedded/) - ARM_ROOT="gcc-arm-none-eabi-10-2020-q4-major" - ARM_TARBALL="$ARM_ROOT-x86_64-linux.tar.bz2" - ARM_TARBALL_URL="https://firmware.ardupilot.org/Tools/STM32-tools/$ARM_TARBALL" - if [ ! -d $OPT/$ARM_ROOT ]; then - ( - cd $OPT; - heading "Installing toolchain for STM32 Boards" - echo "Downloading from ArduPilot server" - sudo wget $ARM_TARBALL_URL - echo "Installing..." - sudo tar xjf ${ARM_TARBALL} - echo "... Cleaning" - sudo rm ${ARM_TARBALL}; - ) - fi - echo "Registering STM32 Toolchain for ccache" - sudo ln -s -f $CCACHE_PATH /usr/lib/ccache/arm-none-eabi-g++ - sudo ln -s -f $CCACHE_PATH /usr/lib/ccache/arm-none-eabi-gcc - echo "Done!" + # GNU Tools for ARM Embedded Processors + # (see https://launchpad.net/gcc-arm-embedded/) + ARM_ROOT="gcc-arm-none-eabi-10-2020-q4-major" + case $(uname -m) in + x86_64) + if [ ! -d $OPT/$ARM_ROOT ]; then + ( + cd $OPT + heading "Installing toolchain for STM32 Boards" + echo "Installing toolchain for STM32 Boards" + echo "Downloading from ArduPilot server" + sudo wget --progress=dot:giga https://firmware.ardupilot.org/Tools/STM32-tools/gcc-arm-none-eabi-10-2020-q4-major-x86_64-linux.tar.bz2 + echo "Installing..." + sudo chmod -R 777 gcc-arm-none-eabi-10-2020-q4-major-x86_64-linux.tar.bz2 + sudo tar xjf gcc-arm-none-eabi-10-2020-q4-major-x86_64-linux.tar.bz2 + echo "... Cleaning" + sudo rm gcc-arm-none-eabi-10-2020-q4-major-x86_64-linux.tar.bz2 + ) + fi + echo "Registering STM32 Toolchain for ccache" + sudo ln -s -f $CCACHE_PATH /usr/lib/ccache/arm-none-eabi-g++ + sudo ln -s -f $CCACHE_PATH /usr/lib/ccache/arm-none-eabi-gcc + echo "Done!";; + + aarch64) + if [ ! -d $OPT/$ARM_ROOT ]; then + ( + cd $OPT + heading "Installing toolchain for STM32 Boards" + echo "Installing toolchain for STM32 Boards" + echo "Downloading from ArduPilot server" + sudo wget --progress=dot:giga https://firmware.ardupilot.org/Tools/STM32-tools/gcc-arm-none-eabi-10-2020-q4-major-aarch64-linux.tar.bz2 + echo "Installing..." + sudo chmod -R 777 gcc-arm-none-eabi-10-2020-q4-major-aarch64-linux.tar.bz2 + sudo tar xjf gcc-arm-none-eabi-10-2020-q4-major-aarch64-linux.tar.bz2 + echo "... Cleaning" + sudo rm gcc-arm-none-eabi-10-2020-q4-major-aarch64-linux.tar.bz2 + ) + fi + echo "Registering STM32 Toolchain for ccache" + sudo ln -s -f $CCACHE_PATH /usr/lib/ccache/arm-none-eabi-g++ + sudo ln -s -f $CCACHE_PATH /usr/lib/ccache/arm-none-eabi-gcc + echo "Done!";; + esac } function maybe_prompt_user() { @@ -196,9 +224,8 @@ then BASE_PKGS+=" python-is-python3" SITL_PKGS+=" libpython3-stdlib" # for argparse elif [ ${RELEASE_CODENAME} == 'groovy' ] || - [ ${RELEASE_CODENAME} == 'hirsute' ] || [ ${RELEASE_CODENAME} == 'bullseye' ] || - [ ${RELEASE_CODENAME} == 'impish' ]; then + [ ${RELEASE_CODENAME} == 'jammy' ]; then BASE_PKGS+=" python-is-python3" SITL_PKGS+=" libpython3-stdlib" # for argparse else @@ -210,7 +237,6 @@ if [[ $SKIP_AP_GRAPHIC_ENV -ne 1 ]]; then if [ ${RELEASE_CODENAME} == 'bullseye' ]; then SITL_PKGS+=" libjpeg62-turbo-dev" elif [ ${RELEASE_CODENAME} == 'groovy' ] || - [ ${RELEASE_CODENAME} == 'hirsute' ] || [ ${RELEASE_CODENAME} == 'focal' ] || [ ${RELEASE_CODENAME} == 'ulyssa' ]; then SITL_PKGS+=" libjpeg8-dev" @@ -226,10 +252,9 @@ if [[ $SKIP_AP_GRAPHIC_ENV -ne 1 ]]; then fi if [ ${RELEASE_CODENAME} == 'bullseye' ] || [ ${RELEASE_CODENAME} == 'groovy' ] || - [ ${RELEASE_CODENAME} == 'hirsute' ] || [ ${RELEASE_CODENAME} == 'focal' ] || [ ${RELEASE_CODENAME} == 'ulyssa' ] || - [ ${RELEASE_CODENAME} == 'impish' ]; then + [ ${RELEASE_CODENAME} == 'jammy' ]; then SITL_PKGS+=" python3-wxgtk4.0" SITL_PKGS+=" fonts-freefont-ttf libfreetype6-dev libpng16-16 libportmidi-dev libsdl-image1.2-dev libsdl-mixer1.2-dev libsdl-ttf2.0-dev libsdl1.2-dev" # for pygame fi @@ -250,7 +275,7 @@ fi # Install all packages $APT_GET install $BASE_PKGS $SITL_PKGS $PX4_PKGS $ARM_LINUX_PKGS $COVERAGE_PKGS # Update Pip and Setuptools on old distro -if [ ${RELEASE_CODENAME} == 'xenial' ] || [ ${RELEASE_CODENAME} == 'disco' ] || [ ${RELEASE_CODENAME} == 'eoan' ]; then +if [ ${RELEASE_CODENAME} == 'bionic' ]; then # use fixed version for package that drop python2 support $PIP install --user -U pip==20.3 setuptools==44.0.0 fi @@ -260,10 +285,13 @@ if [[ -z "${DO_AP_STM_ENV}" ]] && maybe_prompt_user "Install ArduPilot STM32 too DO_AP_STM_ENV=1 fi -heading "Removing modemmanager package that could conflict with firmware uploading" +heading "Removing modemmanager and brltty package that could conflict with firmware uploading" if package_is_installed "modemmanager"; then $APT_GET remove modemmanager fi +if package_is_installed "brltty"; then + $APT_GET remove brltty +fi echo "Done!" CCACHE_PATH=$(which ccache) @@ -281,7 +309,8 @@ echo "Done!" SHELL_LOGIN=".profile" if $IS_DOCKER; then echo "Inside docker, we add the tools path into .bashrc directly" - SHELL_LOGIN=".bashrc" + SHELL_LOGIN=".ardupilot_env" + echo "# ArduPilot env file. Need to be loaded by your Shell." > ~/$SHELL_LOGIN fi heading "Adding ArduPilot Tools to environment" @@ -342,4 +371,10 @@ if [[ $SKIP_AP_GIT_CHECK -ne 1 ]]; then echo "Done!" fi fi + +if $IS_DOCKER; then + echo "Finalizing ArduPilot env for Docker" + echo "source ~/.ardupilot_env">> ~/.bashrc +fi + echo "---------- $0 end ----------" diff --git a/Tools/environment_install/install-prereqs-windows-andAPMSource.ps1 b/Tools/environment_install/install-prereqs-windows-andAPMSource.ps1 index 99eabd93035..bfb76b51cd6 100644 --- a/Tools/environment_install/install-prereqs-windows-andAPMSource.ps1 +++ b/Tools/environment_install/install-prereqs-windows-andAPMSource.ps1 @@ -19,7 +19,7 @@ Start-Process -wait -FilePath "C:\cygwin64\bin\bash" -ArgumentList "--login -i - Start-Process -wait -FilePath "C:\cygwin64\bin\bash" -ArgumentList "--login -i -c 'ln -sf /usr/bin/pip3.7 /usr/bin/pip'" Write-Output "Downloading extra Python packages (5/8)" -Start-Process -wait -FilePath "C:\cygwin64\bin\bash" -ArgumentList "--login -i -c 'pip install empy pyserial pymavlink intelhex'" +Start-Process -wait -FilePath "C:\cygwin64\bin\bash" -ArgumentList "--login -i -c 'pip install empy pyserial pymavlink intelhex dronecan'" Write-Output "Downloading APM source (6/8)" Copy-Item "APM_install.sh" -Destination "C:\cygwin64\home" diff --git a/Tools/environment_install/install-prereqs-windows.ps1 b/Tools/environment_install/install-prereqs-windows.ps1 index d427759a901..ed3f1e2d199 100644 --- a/Tools/environment_install/install-prereqs-windows.ps1 +++ b/Tools/environment_install/install-prereqs-windows.ps1 @@ -19,7 +19,7 @@ Start-Process -wait -FilePath "C:\cygwin64\bin\bash" -ArgumentList "--login -i - Start-Process -wait -FilePath "C:\cygwin64\bin\bash" -ArgumentList "--login -i -c 'ln -sf /usr/bin/pip3.7 /usr/bin/pip'" Write-Output "Downloading extra Python packages (5/7)" -Start-Process -wait -FilePath "C:\cygwin64\bin\bash" -ArgumentList "--login -i -c 'pip install empy pyserial pymavlink intelhex'" +Start-Process -wait -FilePath "C:\cygwin64\bin\bash" -ArgumentList "--login -i -c 'pip install empy pyserial pymavlink intelhex dronecan'" Write-Output "Installing ARM GCC Compiler 10-2020-Q4-Major (6/7)" & $PSScriptRoot\gcc-arm-none-eabi-10-2020-q4-major-win32.exe /S /P /R diff --git a/Tools/scripts/CAN/can_sitl.sh b/Tools/scripts/CAN/can_sitl.sh index 00907e626d2..65aa2339a5f 100755 --- a/Tools/scripts/CAN/can_sitl.sh +++ b/Tools/scripts/CAN/can_sitl.sh @@ -32,6 +32,7 @@ done sudo modprobe vcan sudo ip link add dev vcan0 type vcan sudo ip link set up vcan0 +sudo ip link set vcan0 mtu 72 sudo modprobe slcan sudo modprobe can-gw sudo slcan_attach -f -s8 -o "$DEVPATH" diff --git a/Tools/scripts/CAN/can_sitl_nodev.sh b/Tools/scripts/CAN/can_sitl_nodev.sh index 36c2145f528..d31514c802f 100755 --- a/Tools/scripts/CAN/can_sitl_nodev.sh +++ b/Tools/scripts/CAN/can_sitl_nodev.sh @@ -19,4 +19,5 @@ done sudo modprobe vcan sudo ip link add dev vcan0 type vcan sudo ip link set up vcan0 +sudo ip link set vcan0 mtu 72 sudo modprobe can-gw diff --git a/Tools/scripts/CAN/fix2_gap.py b/Tools/scripts/CAN/fix2_gap.py new file mode 100755 index 00000000000..e72d6ccecab --- /dev/null +++ b/Tools/scripts/CAN/fix2_gap.py @@ -0,0 +1,44 @@ +#!/usr/bin/env python3 +''' +test script to check if all CAN GPS nodes are producing Fix2 frames at the expected rate +''' + +import dronecan, time +from dronecan import uavcan + +# get command line arguments +from argparse import ArgumentParser +parser = ArgumentParser(description='Fix2 gap example') +parser.add_argument("--bitrate", default=1000000, type=int, help="CAN bit rate") +parser.add_argument("--node-id", default=100, type=int, help="CAN node ID") +parser.add_argument("--max-gap", default=0.25, type=float, help="max gap in seconds") +parser.add_argument("port", default=None, type=str, help="serial port or mavcan URI") +args = parser.parse_args() + +# Initializing a DroneCAN node instance. +node = dronecan.make_node(args.port, node_id=args.node_id, bitrate=args.bitrate) + +# Initializing a node monitor +node_monitor = dronecan.app.node_monitor.NodeMonitor(node) + +last_fix2 = {} + +def handle_fix2(msg): + nodeid = msg.transfer.source_node_id + tstamp = msg.transfer.ts_real + if not nodeid in last_fix2: + last_fix2[nodeid] = tstamp + return + dt = tstamp - last_fix2[nodeid] + last_fix2[nodeid] = tstamp + if dt > args.max_gap: + print("Node %u gap=%.3f" % (nodeid, dt)) + +# callback for printing ESC status message to stdout in human-readable YAML format. +node.add_handler(dronecan.uavcan.equipment.gnss.Fix2, handle_fix2) + +while True: + try: + node.spin() + except Exception as ex: + print(ex) diff --git a/Tools/scripts/apj_tool.py b/Tools/scripts/apj_tool.py index e67d76c26c0..26b5e25a01a 100755 --- a/Tools/scripts/apj_tool.py +++ b/Tools/scripts/apj_tool.py @@ -229,11 +229,14 @@ def defaults_contents(firmware, ofs, length): defaults = embedded_defaults(args.firmware_file) - if not defaults.find(): + have_defaults = defaults.find() + + if not have_defaults and not args.extract: print("Error: Param defaults support not found in firmware") sys.exit(1) - - print("Found param defaults max_length=%u length=%u" % (defaults.max_len, defaults.length)) + + if have_defaults: + print("Found param defaults max_length=%u length=%u" % (defaults.max_len, defaults.length)) if args.set_file: # load new defaults from a file diff --git a/Tools/scripts/board_list.py b/Tools/scripts/board_list.py index d823dffacd4..544b20a4d7b 100755 --- a/Tools/scripts/board_list.py +++ b/Tools/scripts/board_list.py @@ -2,6 +2,7 @@ import os import re +import fnmatch ''' list of boards for build_binaries.py and custom build server @@ -14,6 +15,23 @@ class Board(object): def __init__(self, name): self.name = name self.is_ap_periph = False + self.autobuild_targets = [ + 'Tracker', + 'Blimp', + 'Copter', + 'Heli', + 'Plane', + 'Rover', + 'Sub', + ] + + +def in_blacklist(blacklist, b): + '''return true if board b is in the blacklist, including wildcards''' + for bl in blacklist: + if fnmatch.fnmatch(b, bl): + return True + return False class BoardList(object): @@ -77,6 +95,17 @@ def __init__(self): if re.match(r"^\s*env AP_PERIPH_HEAVY 1", line): board.is_ap_periph = 1 + # a hwdef can specify which vehicles this target is valid for: + match = re.match(r"AUTOBUILD_TARGETS\s*(.*)", line) + if match is not None: + mname = match.group(1) + if mname.lower() == 'none': + board.autobuild_targets = [] + else: + board.autobuild_targets = [ + x.rstrip().lstrip().lower() for x in mname.split(",") + ] + def read_hwdef(self, filepath): fh = open(filepath) ret = [] @@ -89,7 +118,7 @@ def read_hwdef(self, filepath): ret += [line] return ret - def find_autobuild_boards(self): + def find_autobuild_boards(self, build_target=None): ret = [] for board in self.boards: if board.is_ap_periph: @@ -101,29 +130,16 @@ def find_autobuild_boards(self): # should probably have a line in the hwdef indicating they # shouldn't be auto-built... blacklist = [ - # the following boards are hacked into build_binaries.py - # to be built for Copter only: - "CubeGreen-solo", - "CubeSolo", - "skyviper-journey", - "skyviper-v2450", - # IOMCU: "iomcu", 'iomcu_f103_8MHz', - # evaluation boards - 'H757I_EVAL', - 'H757I_EVAL_intf', - "Nucleo-G491", - "NucleoH743", - # bdshot - "CubeYellow-bdshot", "fmuv3-bdshot", - "KakuteF7-bdshot", "OMNIBUSF7V2-bdshot", - "Pixhawk1-1M-bdshot", + + # renamed to KakuteH7Mini-Nand + "KakuteH7Miniv2", # other "crazyflie2", @@ -132,11 +148,26 @@ def find_autobuild_boards(self): "MazzyStarDrone", "omnibusf4pro-one", "skyviper-f412-rev1", + "*-ODID", + "*-ODID-heli", ] - ret = filter(lambda x : x not in blacklist, ret) + ret = filter(lambda x : not in_blacklist(blacklist, x), ret) + + # if the caller has supplied a vehicle to limit to then we do that here: + if build_target is not None: + # Slow down: n^2 algorithm ahead + newret = [] + for x in ret: + for b in self.boards: + if b.name.lower() != x.lower(): + continue + if build_target.lower() not in [y.lower() for y in b.autobuild_targets]: + continue + newret.append(x) + ret = newret - return list(ret) + return sorted(list(ret)) def find_ap_periph_boards(self): blacklist = [ @@ -146,11 +177,6 @@ def find_ap_periph_boards(self): "G4-ESC", "HereID", "HerePro", - - # evaluation boards - "H757I_EVAL", - "Nucleo-L476", - "Nucleo-L496", ] ret = [] for x in self.boards: @@ -159,8 +185,28 @@ def find_ap_periph_boards(self): if x.name in blacklist: continue ret.append(x.name) - return list(ret) + return sorted(list(ret)) AUTOBUILD_BOARDS = BoardList().find_autobuild_boards() AP_PERIPH_BOARDS = BoardList().find_ap_periph_boards() + +if __name__ == '__main__': + import argparse + parser = argparse.ArgumentParser(description='list boards to build') + + parser.add_argument('target') + parser.add_argument('--per-line', action='store_true', default=False, help='list one per line for use with xargs') + args = parser.parse_args() + board_list = BoardList() + target = args.target + if target == "AP_Periph": + blist = board_list.find_ap_periph_boards() + else: + blist = board_list.find_autobuild_boards(target) + blist = sorted(blist) + if args.per_line: + for b in blist: + print(b) + else: + print(blist) diff --git a/Tools/scripts/build-jsbsim.sh b/Tools/scripts/build-jsbsim.sh index a6ba075a1fd..9e84927015e 100755 --- a/Tools/scripts/build-jsbsim.sh +++ b/Tools/scripts/build-jsbsim.sh @@ -13,7 +13,7 @@ else echo "$JSBBINARY does not exist, building it in your home folder:" cd ~ rm -rf jsbsim - git clone git://github.com/JSBSim-Team/jsbsim.git + git clone https://github.com/JSBSim-Team/jsbsim.git cd jsbsim mkdir build cd build diff --git a/Tools/scripts/build_all.sh b/Tools/scripts/build_all.sh index 61d42b645f2..5a3eaf84130 100755 --- a/Tools/scripts/build_all.sh +++ b/Tools/scripts/build_all.sh @@ -3,8 +3,6 @@ # This helps when doing large merges # Andrew Tridgell, November 2011 -. config.mk - set -e set -x diff --git a/Tools/scripts/build_autotest.sh b/Tools/scripts/build_autotest.sh index 6bef60a344b..789c89b6d00 100755 --- a/Tools/scripts/build_autotest.sh +++ b/Tools/scripts/build_autotest.sh @@ -52,39 +52,16 @@ lock_file build.lck || { ( date -report() { - d="$1" - old="$2" - new="$3" - cat < 0: + target_elf_filename += ".elf" + files_to_copy.append((bare_path, target_elf_filename)) + + for (path, target_filename) in files_to_copy: try: - self.copyit(path, ddir, tag, vehicle) + '''copy path into various places, adding metadata''' + bname = os.path.basename(ddir) + tdir = os.path.join(os.path.dirname(os.path.dirname( + os.path.dirname(ddir))), tag, bname) + if tag == "latest": + # we keep a permanent archive of all + # "latest" builds, their path including a + # build timestamp: + if not os.path.exists(ddir): + self.mkpath(ddir) + self.addfwversion(ddir, vehicle) + self.progress("Copying %s to %s" % (path, ddir,)) + shutil.copy(path, os.path.join(ddir, target_filename)) + # the most recent build of every tag is kept around: + self.progress("Copying %s to %s" % (path, tdir)) + if not os.path.exists(tdir): + self.mkpath(tdir) + # must addfwversion even if path already + # exists as we re-use the "beta" directories + self.addfwversion(tdir, vehicle) + shutil.copy(path, os.path.join(tdir, target_filename)) except Exception as e: self.print_exception_caught(e) self.progress("Failed to copy %s to %s: %s" % (path, ddir, str(e))) @@ -524,28 +535,27 @@ def build_vehicle(self, tag, vehicle, boards, vehicle_binaries_subdir, def get_exception_stacktrace(self, e): if sys.version_info[0] >= 3: ret = "%s\n" % e - ret += ''.join(traceback.format_exception(etype=type(e), - value=e, + ret += ''.join(traceback.format_exception(type(e), + e, tb=e.__traceback__)) return ret + + # Python2: return traceback.format_exc(e) def print_exception_caught(self, e, send_statustext=True): self.progress("Exception caught: %s" % self.get_exception_stacktrace(e)) - def common_boards(self): - '''returns list of boards common to all vehicles''' - return AUTOBUILD_BOARDS - def AP_Periph_boards(self): return AP_PERIPH_BOARDS def build_arducopter(self, tag): '''build Copter binaries''' + boards = [] - boards.extend(["skyviper-v2450", "aerofc-v1", "bebop", "CubeSolo", "CubeGreen-solo", "skyviper-journey"]) - boards.extend(self.common_boards()[:]) + boards.extend(["aerofc-v1", "bebop"]) + boards.extend(self.board_list.find_autobuild_boards('Copter')) self.build_vehicle(tag, "ArduCopter", boards, @@ -555,7 +565,7 @@ def build_arducopter(self, tag): def build_arduplane(self, tag): '''build Plane binaries''' - boards = self.common_boards()[:] + boards = self.board_list.find_autobuild_boards('Plane')[:] boards.append("disco") self.build_vehicle(tag, "ArduPlane", @@ -565,19 +575,17 @@ def build_arduplane(self, tag): def build_antennatracker(self, tag): '''build Tracker binaries''' - boards = self.common_boards()[:] self.build_vehicle(tag, "AntennaTracker", - boards, + self.board_list.find_autobuild_boards('Tracker')[:], "AntennaTracker", "antennatracker") def build_rover(self, tag): '''build Rover binaries''' - boards = self.common_boards() self.build_vehicle(tag, "Rover", - boards, + self.board_list.find_autobuild_boards('Rover')[:], "Rover", "ardurover") @@ -585,7 +593,7 @@ def build_ardusub(self, tag): '''build Sub binaries''' self.build_vehicle(tag, "ArduSub", - self.common_boards(), + self.board_list.find_autobuild_boards('Sub')[:], "Sub", "ardusub") @@ -600,10 +608,9 @@ def build_AP_Periph(self, tag): def build_blimp(self, tag): '''build Blimp binaries''' - boards = self.common_boards() self.build_vehicle(tag, "Blimp", - boards, + self.board_list.find_autobuild_boards('Blimp')[:], "Blimp", "blimp") @@ -613,21 +620,9 @@ def generate_manifest(self): base_url = 'https://firmware.ardupilot.org' generator = generate_manifest.ManifestGenerator(self.binaries, base_url) - content = generator.json() - new_json_filepath = os.path.join(self.binaries, "manifest.json.new") - self.write_string_to_filepath(content, new_json_filepath) - # provide a pre-compressed manifest. For reference, a 7M manifest - # "gzip -9"s to 300k in 1 second, "xz -e"s to 80k in 26 seconds - new_json_filepath_gz = os.path.join(self.binaries, - "manifest.json.gz.new") - with gzip.open(new_json_filepath_gz, 'wb') as gf: - if running_python3: - content = bytes(content, 'ascii') - gf.write(content) - json_filepath = os.path.join(self.binaries, "manifest.json") - json_filepath_gz = os.path.join(self.binaries, "manifest.json.gz") - shutil.move(new_json_filepath, json_filepath) - shutil.move(new_json_filepath_gz, json_filepath_gz) + generator.run() + + generator.write_manifest_json(os.path.join(self.binaries, "manifest.json")) self.progress("Manifest generation successful") self.progress("Generating stable releases") @@ -642,18 +637,6 @@ def validate(self): (str(self.tags))) self.dirty = True - def pollute_env_from_file(self, filepath): - with open(filepath) as f: - for line in f: - try: - (name, value) = str.split(line, "=") - except ValueError as e: - self.progress("%s: split failed: %s" % (filepath, str(e))) - continue - value = value.rstrip() - self.progress("%s: %s=%s" % (filepath, name, value)) - os.environ[name] = value - def remove_tmpdir(self): if os.path.exists(self.tmpdir): self.progress("Removing (%s)" % (self.tmpdir,)) @@ -706,10 +689,6 @@ def run(self): self.basedir = os.getcwd() self.error_strings = [] - if os.path.exists("config.mk"): - # FIXME: narrow exception - self.pollute_env_from_file("config.mk") - if not self.dirty: self.run_git_update_submodules() self.buildroot = os.path.join(os.environ.get("TMPDIR"), diff --git a/Tools/scripts/build_binaries_history.py b/Tools/scripts/build_binaries_history.py index 83d22bafabb..6054669e38d 100644 --- a/Tools/scripts/build_binaries_history.py +++ b/Tools/scripts/build_binaries_history.py @@ -1,5 +1,3 @@ -#!/usr/bin/env python - from __future__ import print_function import os diff --git a/Tools/scripts/build_bootloaders.py b/Tools/scripts/build_bootloaders.py index 7340d490307..2cd9e07dfe5 100755 --- a/Tools/scripts/build_bootloaders.py +++ b/Tools/scripts/build_bootloaders.py @@ -10,11 +10,18 @@ import sys import fnmatch -board_pattern = '*' +# get command line arguments +from argparse import ArgumentParser +parser = ArgumentParser(description='make_secure_bl') +parser.add_argument("--signing-key", type=str, default=None, help="signing key for secure bootloader") +parser.add_argument("--debug", action='store_true', default=False, help="build with debug symbols") +parser.add_argument("pattern", type=str, default='*', help="board wildcard pattern") +args = parser.parse_args() -# allow argument for pattern of boards to build -if len(sys.argv)>1: - board_pattern = sys.argv[1] +if args.signing_key is not None and os.path.basename(args.signing_key).lower().find("private") != -1: + # prevent the easy mistake of using private key + print("You must use the public key in the bootloader") + sys.exit(1) os.environ['PYTHONUNBUFFERED'] = '1' @@ -39,7 +46,15 @@ def run_program(cmd_list): return True def build_board(board): - if not run_program(["./waf", "configure", "--board", board, "--bootloader", "--no-submodule-update", "--Werror"]): + configure_args = "--board %s --bootloader --no-submodule-update --Werror" % board + configure_args = configure_args.split() + if args.signing_key is not None: + print("Building secure bootloader") + configure_args.append("--signed-fw") + if args.debug: + print("Building with debug symbols") + configure_args.append("--debug") + if not run_program(["./waf", "configure"] + configure_args): return False if not run_program(["./waf", "clean"]): return False @@ -48,17 +63,31 @@ def build_board(board): return True for board in get_board_list(): - if not fnmatch.fnmatch(board, board_pattern): + if not fnmatch.fnmatch(board, args.pattern): continue print("Building for %s" % board) if not build_board(board): failed_boards.add(board) continue - shutil.copy('build/%s/bin/AP_Bootloader.bin' % board, 'Tools/bootloaders/%s_bl.bin' % board) - if not run_program(["Tools/scripts/bin2hex.py", "--offset", "0x08000000", 'Tools/bootloaders/%s_bl.bin' % board, 'Tools/bootloaders/%s_bl.hex' % board]): + bl_file = 'Tools/bootloaders/%s_bl.bin' % board + hex_file = 'Tools/bootloaders/%s_bl.hex' % board + elf_file = 'Tools/bootloaders/%s_bl.elf' % board + shutil.copy('build/%s/bin/AP_Bootloader.bin' % board, bl_file) + print("Created %s" % bl_file) + shutil.copy('build/%s/bootloader/AP_Bootloader' % board, elf_file) + print("Created %s" % elf_file) + if args.signing_key is not None: + print("Signing bootloader with %s" % args.signing_key) + if not run_program(["./Tools/scripts/signing/make_secure_bl.py", bl_file, args.signing_key]): + print("Failed to sign bootloader for %s" % board) + sys.exit(1) + if not run_program(["./Tools/scripts/signing/make_secure_bl.py", elf_file, args.signing_key]): + print("Failed to sign ELF bootloader for %s" % board) + sys.exit(1) + if not run_program([sys.executable, "Tools/scripts/bin2hex.py", "--offset", "0x08000000", bl_file, hex_file]): failed_boards.add(board) continue - shutil.copy('build/%s/bootloader/AP_Bootloader' % board, 'Tools/bootloaders/%s_bl.elf' % board) + print("Created %s" % hex_file) if len(failed_boards): print("Failed boards: %s" % list(failed_boards)) diff --git a/Tools/scripts/build_ci.sh b/Tools/scripts/build_ci.sh index a682f74b926..e57467a16f7 100755 --- a/Tools/scripts/build_ci.sh +++ b/Tools/scripts/build_ci.sh @@ -3,8 +3,12 @@ # This helps when doing large merges # Andrew Tridgell, November 2011 +XOLDPWD=$PWD # profile changes directory :-( + . ~/.profile +cd $XOLDPWD + set -ex # CXX and CC are exported by default by travis @@ -14,6 +18,7 @@ cxx_compiler=${CXX:-g++} export BUILDROOT=/tmp/ci.build rm -rf $BUILDROOT export GIT_VERSION="abcdef" +export GIT_VERSION_INT="15" export CHIBIOS_GIT_VERSION="12345667" export CCACHE_SLOPPINESS="include_file_ctime,include_file_mtime" autotest_args="" @@ -31,6 +36,15 @@ echo "Compiler: $c_compiler" pymavlink_installed=0 mavproxy_installed=0 +function install_pymavlink() { + if [ $pymavlink_installed -eq 0 ]; then + echo "Installing pymavlink" + git submodule update --init --recursive + (cd modules/mavlink/pymavlink && python setup.py build install --user) + pymavlink_installed=1 + fi +} + function run_autotest() { NAME="$1" BVEHICLE="$2" @@ -51,12 +65,7 @@ function run_autotest() { # now uninstall the version of pymavlink pulled in by MAVProxy deps: python -m pip uninstall -y pymavlink fi - if [ $pymavlink_installed -eq 0 ]; then - echo "Installing pymavlink" - git submodule update --init --recursive - (cd modules/mavlink/pymavlink && python setup.py build install --user) - pymavlink_installed=1 - fi + install_pymavlink unset BUILDROOT echo "Running SITL $NAME test" @@ -64,13 +73,13 @@ function run_autotest() { if [ $c_compiler == "clang" ]; then w="$w --check-c-compiler=clang --check-cxx-compiler=clang++" fi - if [ $NAME == "Rover" ]; then + if [ "$NAME" == "Rover" ]; then w="$w --enable-math-check-indexes" fi if [ "x$CI_BUILD_DEBUG" != "x" ]; then w="$w --debug" fi - if [ $NAME == "Examples" ]; then + if [ "$NAME" == "Examples" ]; then w="$w --speedup=5 --timeout=14400 --debug --no-clean" fi Tools/autotest/autotest.py --show-test-timings --waf-configure-args="$w" "$BVEHICLE" "$RVEHICLE" @@ -83,11 +92,6 @@ for t in $CI_BUILD_TARGET; do run_autotest "Heli" "build.Helicopter" "test.Helicopter" continue fi - # travis-ci - if [ "$t" == "sitltest-copter-tests1" ]; then - run_autotest "Copter" "build.Copter" "test.CopterTests1" - continue - fi #github actions ci if [ "$t" == "sitltest-copter-tests1a" ]; then run_autotest "Copter" "build.Copter" "test.CopterTests1a" @@ -109,13 +113,6 @@ for t in $CI_BUILD_TARGET; do run_autotest "Copter" "build.Copter" "test.CopterTests1e" continue fi - - # travis-ci - if [ "$t" == "sitltest-copter-tests2" ]; then - run_autotest "Copter" "build.Copter" "test.CopterTests2" - continue - fi - #github actions ci if [ "$t" == "sitltest-copter-tests2a" ]; then run_autotest "Copter" "build.Copter" "test.CopterTests2a" continue @@ -143,6 +140,10 @@ for t in $CI_BUILD_TARGET; do run_autotest "Rover" "build.Rover" "test.Rover" continue fi + if [ "$t" == "sitltest-sailboat" ]; then + run_autotest "Rover" "build.Rover" "test.Sailboat" + continue + fi if [ "$t" == "sitltest-tracker" ]; then run_autotest "Tracker" "build.Tracker" "test.Tracker" continue @@ -286,6 +287,15 @@ for t in $CI_BUILD_TARGET; do continue fi + if [ "$t" == "CubeOrange-ODID" ]; then + echo "Building CubeOrange-ODID" + $waf configure --board CubeOrange-ODID + $waf clean + $waf copter + $waf plane + continue + fi + if [ "$t" == "fmuv2-plane" ]; then echo "Building fmuv2 plane" $waf configure --board fmuv2 @@ -321,6 +331,21 @@ for t in $CI_BUILD_TARGET; do continue fi + if [ "$t" == "signing" ]; then + echo "Building signed firmwares" + sudo apt-get update + sudo apt-get install -y python3-dev + python3 -m pip install pymonocypher==3.1.3.2 + ./Tools/scripts/signing/generate_keys.py testkey + $waf configure --board CubeOrange-ODID --signed-fw --private-key testkey_private_key.dat + $waf copter + $waf configure --board MatekL431-DShot --signed-fw --private-key testkey_private_key.dat + $waf AP_Periph + ./Tools/scripts/build_bootloaders.py --signing-key testkey_public_key.dat CubeOrange-ODID + ./Tools/scripts/build_bootloaders.py --signing-key testkey_public_key.dat MatekL431-DShot + continue + fi + if [ "$t" == "python-cleanliness" ]; then echo "Checking Python code cleanliness" ./Tools/scripts/run_flake8.py @@ -333,6 +358,24 @@ for t in $CI_BUILD_TARGET; do continue fi + if [ "$t" == "build-options-defaults-test" ]; then + install_pymavlink + echo "Checking default options in build_options.py work" + time ./Tools/autotest/test_build_options.py \ + --no-disable-all \ + --no-disable-none \ + --no-disable-in-turn \ + --board=CubeOrange \ + --build-targets=copter \ + --build-targets=plane + echo "Checking all/none options in build_options.py work" + time ./Tools/autotest/test_build_options.py \ + --no-disable-in-turn \ + --build-targets=copter \ + --build-targets=plane + continue + fi + if [[ -z ${CI_CRON_JOB+1} ]]; then echo "Starting waf build for board ${t}..." $waf configure --board "$t" \ diff --git a/Tools/scripts/build_log_message_documentation.sh b/Tools/scripts/build_log_message_documentation.sh index 0734612953e..1ec04d08f93 100755 --- a/Tools/scripts/build_log_message_documentation.sh +++ b/Tools/scripts/build_log_message_documentation.sh @@ -3,7 +3,10 @@ set -e set -x -DIR="../buildlogs/LogMessages" +if [ "x$BUILDLOGS" = "x" ]; then + BUILDLOGS="../buildlogs" +fi +DIR="$BUILDLOGS/LogMessages" # work from either APM directory or above [ -d ArduPlane ] || cd APM diff --git a/Tools/scripts/build_options.py b/Tools/scripts/build_options.py index b77346cf031..2c630dbea0a 100644 --- a/Tools/scripts/build_options.py +++ b/Tools/scripts/build_options.py @@ -1,13 +1,21 @@ -#!/usr/bin/env python - ''' Provide structured data understood by the CustomBuild server app.py + +AP_FLAKE8_CLEAN + ''' class Feature: - '''defines a feature which can be built into the firmware, along with its dependencies''' - def __init__(self, category, label, define, description, default, dependency): + '''defines a feature which can be built into the firmware, along with + its dependencies''' + def __init__(self, + category, + label, + define, + description, + default, + dependency): self.category = category self.label = label self.define = define @@ -15,68 +23,87 @@ def __init__(self, category, label, define, description, default, dependency): self.default = default self.dependency = dependency -# list of build options to offer -# NOTE: the dependencies must be written as a single string with commas and no spaces, eg. 'dependency1,dependency2' + +# list of build options to offer NOTE: the dependencies must be +# written as a single string with commas and no spaces, +# eg. 'dependency1,dependency2' BUILD_OPTIONS = [ Feature('AHRS', 'EKF3', 'HAL_NAVEKF3_AVAILABLE', 'Enable EKF3', 1, None), Feature('AHRS', 'EKF2', 'HAL_NAVEKF2_AVAILABLE', 'Enable EKF2', 0, None), Feature('AHRS', 'AHRS_EXT', 'HAL_EXTERNAL_AHRS_ENABLED', 'Enable External AHRS', 0, None), Feature('AHRS', 'TEMPCAL', 'HAL_INS_TEMPERATURE_CAL_ENABLE', 'Enable IMU Temperature Calibration', 0, None), - Feature('AHRS', 'VISUALODOM', 'HAL_VISUALODOM_ENABLED', 'Enable Visual Odometry', 0, None), + Feature('AHRS', 'VISUALODOM', 'HAL_VISUALODOM_ENABLED', 'Enable Visual Odometry', 0, 'EKF3_EXTNAV'), + Feature('AHRS', 'EKF3_EXTNAV', 'EK3_FEATURE_EXTERNAL_NAV', 'Enable External Navigation for EKF3', 0, None), Feature('Safety', 'PARACHUTE', 'HAL_PARACHUTE_ENABLED', 'Enable Parachute', 0, None), + Feature('Safety', 'FENCE', 'AP_FENCE_ENABLED', 'Enable Geofence', 2, None), Feature('Safety', 'PROXIMITY', 'HAL_PROXIMITY_ENABLED', 'Enable Proximity', 0, None), - Feature('Safety', 'AC_OAPATHPLANNER', 'AC_OAPATHPLANNER_ENABLED', 'Enable Object Avoidance Path Planner', 0, None), + Feature('Safety', 'AC_AVOID', 'AC_AVOID_ENABLED', 'Enable Avoidance', 0, 'FENCE'), + Feature('Safety', 'AC_OAPATHPLANNER', 'AC_OAPATHPLANNER_ENABLED', 'Enable Object Avoidance Path Planner', 0, 'FENCE'), - Feature('Battery', 'BATTMON_FUEL', 'AP_BATTMON_FUEL_ENABLE', 'Enable Fuel BatteryMonitor', 0, None), + Feature('Battery', 'BATTMON_FUELFLOW', 'AP_BATTMON_FUELFLOW_ENABLE', 'Enable Fuel Flow BatteryMonitor', 0, None), + Feature('Battery', 'BATTMON_FUELLEVEL_PWM', 'AP_BATTMON_FUELLEVEL_PWM_ENABLE', 'Enable Flow Level PWM BattryMonitor', 0, None), # noqa: E501 + Feature('Battery', 'BATTMON_FUELLEVEL_ANALOG', 'AP_BATTMON_FUELLEVEL_ANALOG_ENABLE', 'Enable Flow Level Analog BattryMonitor', 0, None), # noqa: E501 Feature('Battery', 'BATTMON_SMBUS', 'AP_BATTMON_SMBUS_ENABLE', 'Enable SMBUS BatteryMonitor', 0, None), Feature('Battery', 'BATTMON_INA2XX', 'HAL_BATTMON_INA2XX_ENABLED', 'Enable INA2XX BatteryMonitor', 0, None), Feature('Ident', 'ADSB', 'HAL_ADSB_ENABLED', 'Enable ADSB', 0, None), Feature('Ident', 'ADSB_SAGETECH', 'HAL_ADSB_SAGETECH_ENABLED', 'Enable SageTech ADSB', 0, 'ADSB'), - Feature('Ident', 'ADSB_UAVIONIX', 'HAL_ADSB_UAVIONIX_MAVLINK_ENABLED', 'Enable Uavionix ADSB', 0, 'ADSB'), - Feature('Ident', 'AIS', 'HAL_AIS_ENABLED', 'Enable AIS', 0, None), + Feature('Ident', 'ADSB_SAGETECH_MXS', 'HAL_ADSB_SAGETECH_MXS_ENABLED', 'Enable SageTech MXS ADSB', 0, 'ADSB'), + Feature('Ident', 'ADSB_UAVIONIX', 'HAL_ADSB_UAVIONIX_MAVLINK_ENABLED', 'Enable UAvionix ADSB', 0, 'ADSB'), + Feature('Ident', 'ADSB_UAVIONX_UCP', 'HAL_ADSB_UCP_ENABLED', 'Enable uAvionix UCP ADSB', 0 , 'ADSB'), + Feature('Ident', 'AIS', 'AP_AIS_ENABLED', 'Enable AIS', 0, None), Feature('Telemetry', 'CRSF', 'HAL_CRSF_TELEM_ENABLED', 'Enable CRSF Telemetry', 0, None), Feature('Telemetry', 'CRSFText', 'HAL_CRSF_TELEM_TEXT_SELECTION_ENABLED', 'Enable CRSF Text Param Selection', 0, 'CRSF'), Feature('Telemetry', 'HIGHLAT2', 'HAL_HIGH_LATENCY2_ENABLED', 'Enable HighLatency2 Support', 0, None), Feature('Telemetry', 'HOTT', 'HAL_HOTT_TELEM_ENABLED', 'Enable HOTT Telemetry', 0, None), Feature('Telemetry', 'SPEKTRUM', 'HAL_SPEKTRUM_TELEM_ENABLED', 'Enable Spektrum Telemetry', 0, None), + Feature('Telemetry', 'LTM', 'AP_LTM_TELEM_ENABLED', 'Enable LTM Telemetry', 0, None), Feature('MSP', 'MSP', 'HAL_MSP_ENABLED', 'Enable MSP Telemetry and MSP OSD', 0, 'OSD'), - Feature('MSP', 'MSP_SENSORS', 'HAL_MSP_SENSORS_ENABLED', 'Enable MSP Sensors', 0, 'MSP_GPS,MSP_BARO,MSP_COMPASS,MSP_AIRSPEED,MSP,MSP_OPTICALFLOW,MSP_RANGEFINDER,OSD'), + Feature('MSP', 'MSP_SENSORS', 'HAL_MSP_SENSORS_ENABLED', 'Enable MSP Sensors', 0, 'MSP_GPS,MSP_BARO,MSP_COMPASS,MSP_AIRSPEED,MSP,MSP_OPTICALFLOW,MSP_RANGEFINDER,OSD'), # NOQA: E501 Feature('MSP', 'MSP_GPS', 'HAL_MSP_GPS_ENABLED', 'Enable MSP GPS', 0, 'MSP,OSD'), Feature('MSP', 'MSP_COMPASS', 'HAL_MSP_COMPASS_ENABLED', 'Enable MSP Compass', 0, 'MSP,OSD'), - Feature('MSP', 'MSP_BARO', 'HAL_MSP_BARO_ENABLED', 'Enable MSP Baro', 0, 'MSP,OSD'), - Feature('MSP', 'MSP_AIRSPEED', 'HAL_MSP_AIRSPEED_ENABLED', 'Enable MSP AirSpeed', 0, 'MSP,OSD'), - Feature('MSP', 'MSP_OPTICALFLOW', 'HAL_MSP_OPTICALFLOW_ENABLED', 'Enable MSP OpticalFlow', 0, 'MSP,OSD'), # also OPTFLOW dep - Feature('MSP', 'MSP_RANGEFINDER', 'HAL_MSP_RANGEFINDER_ENABLED', 'Enable MSP Rangefinder', 0, 'MSP,OSD'), - Feature('MSP', 'MSP_DISPLAYPORT', 'HAL_WITH_MSP_DISPLAYPORT', 'Enable MSP DisplayPort OSD (aka CANVAS MODE)', 0, 'MSP,OSD'), + Feature('MSP', 'MSP_OPTICALFLOW', 'HAL_MSP_OPTICALFLOW_ENABLED', 'Enable MSP OpticalFlow', 0, 'MSP,OSD,OPTICALFLOW'), # also OPTFLOW dep # NOQA: E501 + Feature('MSP', 'MSP_RANGEFINDER', 'HAL_MSP_RANGEFINDER_ENABLED', 'Enable MSP Rangefinder', 0, 'MSP,OSD,RANGEFINDER'), + Feature('MSP', 'MSP_DISPLAYPORT', 'HAL_WITH_MSP_DISPLAYPORT', 'Enable MSP DisplayPort OSD (aka CANVAS MODE)', 0, 'MSP,OSD'), # NOQA: E501 + Feature('ICE', 'ICE Engine', 'AP_ICENGINE_ENABLED', 'Enable Internal Combustion Engine support', 0, None), Feature('ICE', 'EFI', 'HAL_EFI_ENABLED', 'Enable EFI Monitoring', 0, None), Feature('ICE', 'EFI_NMPWU', 'HAL_EFI_NWPWU_ENABLED', 'Enable EFI NMPMU', 0, None), Feature('ICE', 'GENERATOR', 'HAL_GENERATOR_ENABLED', 'Enable Generator', 0, None), Feature('OSD', 'OSD', 'OSD_ENABLED', 'Enable OSD', 0, None), - Feature('OSD', 'PLUSCODE', 'HAL_PLUSCODE_ENABLE', 'Enable PlusCode', 0, None), - Feature('OSD', 'RUNCAM', 'HAL_RUNCAM_ENABLED', 'Enable RunCam', 0, None), - Feature('OSD', 'SMARTAUDIO', 'HAL_SMARTAUDIO_ENABLED', 'Enable SmartAudio', 0, None), + Feature('OSD', 'PLUSCODE', 'HAL_PLUSCODE_ENABLE', 'Enable PlusCode', 0, 'OSD'), Feature('OSD', 'OSD_PARAM', 'OSD_PARAM_ENABLED', 'Enable OSD param', 0, 'OSD'), Feature('OSD', 'OSD_SIDEBARS', 'HAL_OSD_SIDEBAR_ENABLE', 'Enable Scrolling Sidebars', 0, 'OSD'), + Feature('VTX', 'SMARTAUDIO', 'HAL_SMARTAUDIO_ENABLED', 'Enable SmartAudio VTX Contol', 0, None), + Feature('VTX', 'TRAMP', 'AP_TRAMP_ENABLED', 'Enable IRC Tramp VTX Control', 0, None), + Feature('ESC', 'PICCOLOCAN', 'HAL_PICCOLO_CAN_ENABLE', 'Enable PiccoloCAN', 0, None), Feature('ESC', 'TORQEEDO', 'HAL_TORQEEDO_ENABLED', 'Enable Torqeedo Motors', 0, None), + Feature('Camera', 'RUNCAM', 'HAL_RUNCAM_ENABLED', 'Enable RunCam Control', 0, None), - Feature('Mode', 'MODE_ZIGZAG', 'MODE_ZIGZAG_ENABLED', 'Enable Mode ZigZag', 0, None), - Feature('Mode', 'MODE_SYSTEMID', 'MODE_SYSTEMID_ENABLED', 'Enable Mode SystemID', 0, None), - Feature('Mode', 'MODE_SPORT', 'MODE_SPORT_ENABLED', 'Enable Mode Sport', 0, None), - Feature('Mode', 'MODE_FOLLOW', 'MODE_FOLLOW_ENABLED', 'Enable Mode Follow', 0, None), - Feature('Mode', 'MODE_TURTLE', 'MODE_TURTLE_ENABLED', 'Enable Mode Turtle', 0, None), - Feature('Mode', 'MODE_GUIDED_NOGPS', 'MODE_GUIDED_NOGPS_ENABLED', 'Enable Mode Guided NoGPS', 0, None), + Feature('Copter', 'MODE_ZIGZAG', 'MODE_ZIGZAG_ENABLED', 'Enable Mode ZigZag', 0, None), + Feature('Copter', 'MODE_SYSTEMID', 'MODE_SYSTEMID_ENABLED', 'Enable Mode SystemID', 0, None), + Feature('Copter', 'MODE_SPORT', 'MODE_SPORT_ENABLED', 'Enable Mode Sport', 0, None), + Feature('Copter', 'MODE_FOLLOW', 'MODE_FOLLOW_ENABLED', 'Enable Mode Follow', 0, 'AC_AVOID'), + Feature('Copter', 'MODE_TURTLE', 'MODE_TURTLE_ENABLED', 'Enable Mode Turtle', 0, None), + Feature('Copter', 'MODE_GUIDED_NOGPS', 'MODE_GUIDED_NOGPS_ENABLED', 'Enable Mode Guided NoGPS', 0, None), + Feature('Copter', 'MODE_FLOWHOLD', 'MODE_FLOWHOLD_ENABLED', 'Enable Mode Flowhold', 0, "OPTICALFLOW"), + Feature('Copter', 'MODE_FLIP', 'MODE_FLIP_ENABLED', 'Enable Mode Flip', 0, None), Feature('Gimbal', 'MOUNT', 'HAL_MOUNT_ENABLED', 'Enable Mount', 0, None), - Feature('Gimbal', 'SOLOGIMBAL', 'HAL_SOLO_GIMBAL_ENABLED', 'Enable Solo Gimbal', 0, None), + Feature('Gimbal', 'ALEXMOS', 'HAL_MOUNT_ALEXMOS_ENABLED', 'Enable Alexmos Gimbal', 0, "MOUNT"), + Feature('Gimbal', 'GREMSY', 'HAL_MOUNT_GREMSY_ENABLED', 'Enable Gremsy Gimbal', 0, "MOUNT"), + Feature('Gimbal', 'SERVO', 'HAL_MOUNT_SERVO_ENABLED', 'Enable Servo Gimbal', 0, "MOUNT"), + Feature('Gimbal', 'SIYI', 'HAL_MOUNT_SIYI_ENABLED', 'Enable Siyi Gimbal', 0, "MOUNT"), + Feature('Gimbal', 'SOLOGIMBAL', 'HAL_SOLO_GIMBAL_ENABLED', 'Enable Solo Gimbal', 0, "MOUNT"), + Feature('Gimbal', 'STORM32_MAVLINK', 'HAL_MOUNT_STORM32MAVLINK_ENABLED', 'Enable SToRM32 MAVLink Gimbal', 0, "MOUNT"), + Feature('Gimbal', 'STORM32_SERIAL', 'HAL_MOUNT_STORM32SERIAL_ENABLED', 'Enable SToRM32 Serial Gimbal', 0, "MOUNT"), Feature('VTOL Frame', 'QUAD', 'AP_MOTORS_FRAME_QUAD_ENABLED', 'QUADS(BI,TRI also)', 1, None), Feature('VTOL Frame', 'HEXA', 'AP_MOTORS_FRAME_HEXA_ENABLED', 'HEXA', 0, None), @@ -95,26 +122,77 @@ def __init__(self, category, label, define, description, default, dependency): Feature('Plane', 'SOARING', 'HAL_SOARING_ENABLED', 'Enable Soaring', 0, None), Feature('Plane', 'DEEPSTALL', 'HAL_LANDING_DEEPSTALL_ENABLED', 'Enable Deepstall Landing', 0, None), - Feature('Sensors', 'AIRSPEED', 'AP_AIRSPEED_ENABLED', 'Enable Airspeed Sensors', 1, None), # Default to enabled to not annoy Plane users - Feature('Sensors', 'BEACON', 'BEACON_ENABLED', 'Enable Beacon', 0, None), - Feature('Sensors', 'GPS_MOVING_BASELINE', 'GPS_MOVING_BASELINE', 'Enable GPS Moving Baseline', 0, None), + Feature('Rangefinder', 'RANGEFINDER', 'AP_RANGEFINDER_ENABLED', "Enable Rangefinders", 0, None), # NOQA: E501 + Feature('Rangefinder', 'RANGEFINDER_ANALOG', 'AP_RANGEFINDER_ANALOG_ENABLED', "Enable Rangefinder - Analog", 0, "RANGEFINDER"), # NOQA: E501 + Feature('Rangefinder', 'RANGEFINDER_BBB_PRU', 'AP_RANGEFINDER_BBB_PRU_ENABLED', "Enable Rangefinder - BBB PRU", 0, "RANGEFINDER"), # NOQA: E501 + Feature('Rangefinder', 'RANGEFINDER_BEBOP', 'AP_RANGEFINDER_BEBOP_ENABLED', "Enable Rangefinder - Bebop", 0, "RANGEFINDER"), # NOQA: E501 + Feature('Rangefinder', 'RANGEFINDER_BENEWAKE_CAN', 'AP_RANGEFINDER_BENEWAKE_CAN_ENABLED', "Enable Rangefinder - Benewake (CAN)", 0, "RANGEFINDER"), # NOQA: E501 + Feature('Rangefinder', 'RANGEFINDER_BENEWAKE_TF02', 'AP_RANGEFINDER_BENEWAKE_TF02_ENABLED', "Enable Rangefinder - Benewake -TF02", 0, "RANGEFINDER"), # NOQA: E501 + Feature('Rangefinder', 'RANGEFINDER_BENEWAKE_TF03', 'AP_RANGEFINDER_BENEWAKE_TF03_ENABLED', "Enable Rangefinder - Benewake - TF03", 0, "RANGEFINDER"), # NOQA: E501 + Feature('Rangefinder', 'RANGEFINDER_BENEWAKE_TFMINI', 'AP_RANGEFINDER_BENEWAKE_TFMINI_ENABLED', "Enable Rangefinder - Benewake - TFMini", 0, "RANGEFINDER"), # NOQA: E501 + Feature('Rangefinder', 'RANGEFINDER_BENEWAKE_TFMINIPLUS', 'AP_RANGEFINDER_BENEWAKE_TFMINIPLUS_ENABLED', "Enable Rangefinder - Benewake - TFMiniPlus", 0, "RANGEFINDER"), # NOQA: E501 + Feature('Rangefinder', 'RANGEFINDER_BLPING', 'AP_RANGEFINDER_BLPING_ENABLED', "Enable Rangefinder - BLPing", 0, "RANGEFINDER"), # NOQA: E501 + Feature('Rangefinder', 'RANGEFINDER_GYUS42V2', 'AP_RANGEFINDER_GYUS42V2_ENABLED', "Enable Rangefinder - GYUS42V2", 0, "RANGEFINDER"), # NOQA: E501 + Feature('Rangefinder', 'RANGEFINDER_HC_SR04', 'AP_RANGEFINDER_HC_SR04_ENABLED', "Enable Rangefinder - HC_SR04", 0, "RANGEFINDER"), # NOQA: E501 + Feature('Rangefinder', 'RANGEFINDER_LANBAO', 'AP_RANGEFINDER_LANBAO_ENABLED', "Enable Rangefinder - Lanbao", 0, "RANGEFINDER"), # NOQA: E501 + Feature('Rangefinder', 'RANGEFINDER_LEDDARONE', 'AP_RANGEFINDER_LEDDARONE_ENABLED', "Enable Rangefinder - LeddarOne", 0, "RANGEFINDER"), # NOQA: E501 + Feature('Rangefinder', 'RANGEFINDER_LEDDARVU8', 'AP_RANGEFINDER_LEDDARVU8_ENABLED', "Enable Rangefinder - LeddarVU8", 0, "RANGEFINDER"), # NOQA: E501 + Feature('Rangefinder', 'RANGEFINDER_LIGHTWARE_SERIAL', 'AP_RANGEFINDER_LIGHTWARE_SERIAL_ENABLED', "Enable Rangefinder - Lightware (serial)", 0, "RANGEFINDER"), # NOQA: E501 + Feature('Rangefinder', 'RANGEFINDER_LWI2C', 'AP_RANGEFINDER_LWI2C_ENABLED', "Enable Rangefinder - Lightware (i2c)", 0, "RANGEFINDER"), # NOQA: E501 + Feature('Rangefinder', 'RANGEFINDER_MAVLINK', 'AP_RANGEFINDER_MAVLINK_ENABLED', "Enable Rangefinder - MAVLink", 0, "RANGEFINDER"), # NOQA: E501 + Feature('Rangefinder', 'RANGEFINDER_MAXBOTIX_SERIAL', 'AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED', "Enable Rangefinder - MaxBotix (serial)", 0, "RANGEFINDER"), # NOQA: E501 + Feature('Rangefinder', 'RANGEFINDER_MAXSONARI2CXL', 'AP_RANGEFINDER_MAXSONARI2CXL_ENABLED', "Enable Rangefinder - MaxSonarI2CXL", 0, "RANGEFINDER"), # NOQA: E501 + Feature('Rangefinder', 'RANGEFINDER_NMEA', 'AP_RANGEFINDER_NMEA_ENABLED', "Enable Rangefinder - NMEA", 0, "RANGEFINDER"), # NOQA: E501 + Feature('Rangefinder', 'RANGEFINDER_PULSEDLIGHTLRF', 'AP_RANGEFINDER_PULSEDLIGHTLRF_ENABLED', "Enable Rangefinder - PulsedLightLRF", 0, "RANGEFINDER"), # NOQA: E501 + Feature('Rangefinder', 'RANGEFINDER_PWM', 'AP_RANGEFINDER_PWM_ENABLED', "Enable Rangefinder - PWM", 0, "RANGEFINDER"), # NOQA: E501 + Feature('Rangefinder', 'RANGEFINDER_SIM', 'AP_RANGEFINDER_SIM_ENABLED', "Enable Rangefinder - SIM", 0, "RANGEFINDER"), # NOQA: E501 + Feature('Rangefinder', 'RANGEFINDER_TRI2C', 'AP_RANGEFINDER_TRI2C_ENABLED', "Enable Rangefinder - TeraRangerI2C", 0, "RANGEFINDER"), # NOQA: E501 + Feature('Rangefinder', 'RANGEFINDER_TR_SERIAL', 'AP_RANGEFINDER_TERARANGER_SERIAL_ENABLED', "Enable Rangefinder - TeraRanger Serial", 0, "RANGEFINDER"), # NOQA: E501 + Feature('Rangefinder', 'RANGEFINDER_UAVCAN', 'AP_RANGEFINDER_UAVCAN_ENABLED', "Enable Rangefinder - UAVCAN", 0, "RANGEFINDER"), # NOQA: E501 + Feature('Rangefinder', 'RANGEFINDER_USD1_CAN', 'AP_RANGEFINDER_USD1_CAN_ENABLED', "Enable Rangefinder - USD1 (CAN)", 0, "RANGEFINDER"), # NOQA: E501 + Feature('Rangefinder', 'RANGEFINDER_USD1_SERIAL', 'AP_RANGEFINDER_USD1_SERIAL_ENABLED', "Enable Rangefinder - USD1 (SERIAL)", 0, "RANGEFINDER"), # NOQA: E501 + Feature('Rangefinder', 'RANGEFINDER_VL53L0X', 'AP_RANGEFINDER_VL53L0X_ENABLED', "Enable Rangefinder - VL53L0X", 0, "RANGEFINDER"), # NOQA: E501 + Feature('Rangefinder', 'RANGEFINDER_VL53L1X', 'AP_RANGEFINDER_VL53L1X_ENABLED', "Enable Rangefinder - VL53L1X", 0, "RANGEFINDER"), # NOQA: E501 + Feature('Rangefinder', 'RANGEFINDER_WASP', 'AP_RANGEFINDER_WASP_ENABLED', "Enable Rangefinder - Wasp", 0, "RANGEFINDER"), # NOQA: E501 Feature('Sensors', 'OPTICALFLOW', 'AP_OPTICALFLOW_ENABLED', 'Enable Optical Flow', 0, None), Feature('Sensors', 'OPTICALFLOW_CXOF', 'AP_OPTICALFLOW_CXOF_ENABLED', 'Enable Optical flow CXOF Sensor', 0, "OPTICALFLOW"), - Feature('Sensors', 'OPTICALFLOW_HEREFLOW', 'AP_OPTICALFLOW_HEREFLOW_ENABLED', 'Enable Optical flow HereFlow Sensor', 0, "OPTICALFLOW"), - Feature('Sensors', 'OPTICALFLOW_MAV', 'AP_OPTICALFLOW_MAV_ENABLED', 'Enable Optical flow MAVLink Sensor', 0, "OPTICALFLOW"), - Feature('Sensors', 'OPTICALFLOW_ONBOARD', 'AP_OPTICALFLOW_ONBOARD_ENABLED', 'Enable Optical flow ONBOARD Sensor', 0, "OPTICALFLOW"), - Feature('Sensors', 'OPTICALFLOW_PX4FLOW', 'AP_OPTICALFLOW_PX4FLOW_ENABLED', 'Enable Optical flow PX4FLOW Sensor', 0, "OPTICALFLOW"), - Feature('Sensors', 'OPTICALFLOW_PIXART', 'AP_OPTICALFLOW_PIXART_ENABLED', 'Enable Optical flow PIXART Sensor', 0, "OPTICALFLOW"), - Feature('Sensors', 'OPTICALFLOW_UPFLOW', 'AP_OPTICALFLOW_UPFLOW_ENABLED', 'Enable Optical flow UPFLOW Sensor', 0, "OPTICALFLOW"), + Feature('Sensors', 'OPTICALFLOW_HEREFLOW', 'AP_OPTICALFLOW_HEREFLOW_ENABLED', 'Enable Optical flow HereFlow Sensor', 0, "OPTICALFLOW"), # NOQA: E501 + Feature('Sensors', 'OPTICALFLOW_MAV', 'AP_OPTICALFLOW_MAV_ENABLED', 'Enable Optical flow MAVLink Sensor', 0, "OPTICALFLOW"), # NOQA: E501 + Feature('Sensors', 'OPTICALFLOW_ONBOARD', 'AP_OPTICALFLOW_ONBOARD_ENABLED', 'Enable Optical flow ONBOARD Sensor', 0, "OPTICALFLOW"), # NOQA: E501 + Feature('Sensors', 'OPTICALFLOW_PX4FLOW', 'AP_OPTICALFLOW_PX4FLOW_ENABLED', 'Enable Optical flow PX4FLOW Sensor', 0, "OPTICALFLOW"), # NOQA: E501 + Feature('Sensors', 'OPTICALFLOW_PIXART', 'AP_OPTICALFLOW_PIXART_ENABLED', 'Enable Optical flow PIXART Sensor', 0, "OPTICALFLOW"), # NOQA: E501 + Feature('Sensors', 'OPTICALFLOW_UPFLOW', 'AP_OPTICALFLOW_UPFLOW_ENABLED', 'Enable Optical flow UPFLOW Sensor', 0, "OPTICALFLOW"), # NOQA: E501 + + Feature('Sensors', 'BMP085', 'AP_BARO_BMP085_ENABLED', 'Enable BMP085 Barometric Sensor', 1, None), + Feature('Sensors', 'BMP280', 'AP_BARO_BMP280_ENABLED', 'Enable BMP280 Barometric Sensor', 1, None), + Feature('Sensors', 'BMP388', 'AP_BARO_BMP388_ENABLED', 'Enable BMP388 Barometric Sensor', 1, None), + Feature('Sensors', 'DPS280', 'AP_BARO_DPS280_ENABLED', 'Enable DPS280 Barometric Sensor', 1, None), + Feature('Sensors', 'DUMMY', 'AP_BARO_DUMMY_ENABLED', 'Enable DUMMY Barometric Sensor', 0, None), + Feature('Sensors', 'EXTERNALAHRS', 'AP_BARO_EXTERNALAHRS_ENABLED', 'Enable EXTERNALAHRS Barometric Sensor', 0, None), + Feature('Sensors', 'FBM320', 'AP_BARO_FBM320_ENABLED', 'Enable FBM320 Barometric Sensor', 1, None), + Feature('Sensors', 'ICM20789', 'AP_BARO_ICM20789_ENABLED', 'Enable ICM20789 Barometric Sensor', 1, None), + Feature('Sensors', 'KELLERLD', 'AP_BARO_KELLERLD_ENABLED', 'Enable KELLERLD Barometric Sensor', 1, None), + Feature('Sensors', 'LPS2XH', 'AP_BARO_LPS2XH_ENABLED', 'Enable LPS2XH Barometric Sensor', 1, None), + Feature('Sensors', 'MS56XX', 'AP_BARO_MS56XX_ENABLED', 'Enable MS56XX Barometric Sensor', 1, None), + Feature('Sensors', 'MSP_BARO', 'AP_BARO_MSP_ENABLED', 'Enable MSP Barometric Sensor', 0, 'MSP'), + Feature('Sensors', 'SPL06', 'AP_BARO_SPL06_ENABLED', 'Enable SPL06 Barometric Sensor', 1, None), + Feature('Sensors', 'UAVCAN_BARO', 'AP_BARO_UAVCAN_ENABLED', 'Enable UAVCAN Barometric Sensor', 0, None), + Feature('Sensors', 'ICP101XX', 'AP_BARO_ICP101XX_ENABLED', 'Enable ICP101XX Barometric Sensor', 0, None), + Feature('Sensors', 'ICP201XX', 'AP_BARO_ICP201XX_ENABLED', 'Enable ICP201XX Barometric Sensor', 0, None), Feature('Sensors', 'RPM', 'RPM_ENABLED', 'Enable RPM sensors', 0, None), + Feature('Sensors', 'AIRSPEED', 'AP_AIRSPEED_ENABLED', 'Enable Airspeed Sensors', 1, None), # Default to enabled to not annoy Plane users # NOQA: E501 + Feature('Sensors', 'BEACON', 'BEACON_ENABLED', 'Enable Beacon', 0, None), + Feature('Sensors', 'GPS_MOVING_BASELINE', 'GPS_MOVING_BASELINE', 'Enable GPS Moving Baseline', 0, None), - Feature('Other', 'DSP', 'HAL_WITH_DSP', 'Enable DSP for In-Flight FFT', 0, None), + + Feature('Other', 'DSP', 'HAL_WITH_DSP', 'Enable DSP for In-Flight FFT', 0, None), Feature('Other', 'DISPLAY', 'HAL_DISPLAY_ENABLED', 'Enable I2C Displays', 0, None), Feature('Other', 'NMEA_OUTPUT', 'HAL_NMEA_OUTPUT_ENABLED', 'Enable NMEA Output', 0, None), Feature('Other', 'BARO_WIND_COMP', 'HAL_BARO_WIND_COMP_ENABLED', 'Enable Baro Wind Compensation', 0, None), + Feature('GPS Drivers', 'UBLOX', 'AP_GPS_UBLOX_ENABLED', 'Enable u-blox GPS', 1, None), Feature('GPS Drivers', 'SBP2', 'AP_GPS_SBP2_ENABLED', 'Enable SBP2 GPS', 0, 'SBP'), Feature('GPS Drivers', 'SBP', 'AP_GPS_SBP_ENABLED', 'Enable SBP GPS', 0, None), Feature('GPS Drivers', 'ERB', 'AP_GPS_ERB_ENABLED', 'Enable ERB GPS', 0, None), @@ -124,6 +202,20 @@ def __init__(self, category, label, define, description, default, dependency): Feature('GPS Drivers', 'NOVA', 'AP_GPS_NOVA_ENABLED', 'Enable NOVA GPS', 0, None), Feature('GPS Drivers', 'SBF', 'AP_GPS_SBF_ENABLED', 'Enable SBF GPS', 0, None), Feature('GPS Drivers', 'SIRF', 'AP_GPS_SIRF_ENABLED', 'Enable SiRF GPS', 0, None), - ] + + Feature('Airspeed Drivers', 'Analog', 'AP_AIRSPEED_ANALOG_ENABLED', 'Enable Analog Airspeed', 0, 'AIRSPEED'), + Feature('Airspeed Drivers', 'ASP5033', 'AP_AIRSPEED_ASP5033_ENABLED', 'ENABLE ASP5033 AIRSPEED', 0, 'AIRSPEED'), # NOQA: E501 + Feature('Airspeed Drivers', 'DLVR', 'AP_AIRSPEED_DLVR_ENABLED', 'ENABLE DLVR AIRSPEED', 0, 'AIRSPEED'), + Feature('Airspeed Drivers', 'MS4525', 'AP_AIRSPEED_MS4525_ENABLED', 'ENABLE MS4525 AIRSPEED', 0, 'AIRSPEED'), + Feature('Airspeed Drivers', 'MS5525', 'AP_AIRSPEED_MS5525_ENABLED', 'ENABLE MS5525 AIRSPEED', 0, 'AIRSPEED'), + Feature('Airspeed Drivers', 'MSP_AIRSPEED', 'AP_AIRSPEED_MSP_ENABLED', 'ENABLE MSP AIRSPEED', 0, 'AIRSPEED,MSP,OSD'), + Feature('Airspeed Drivers', 'NMEA', 'AP_AIRSPEED_NMEA_ENABLED', 'ENABLE NMEA AIRSPEED', 0, 'AIRSPEED'), + Feature('Airspeed Drivers', 'SDP3X', 'AP_AIRSPEED_SDP3X_ENABLED', 'ENABLE SDP3X AIRSPEED', 0, 'AIRSPEED'), + Feature('Airspeed Drivers', 'UAVCAN_ASPD', 'AP_AIRSPEED_UAVCAN_ENABLED', 'ENABLE UAVCAN AIRSPEED', 0, 'AIRSPEED'), # NOQA: E501 + + Feature('Actuators', 'Volz', 'AP_VOLZ_ENABLED', 'Enable Volz Protocol', 0, None), + Feature('Actuators', 'RobotisServo', 'AP_ROBOTISSERVO_ENABLED', 'Enable RobotisServo Protocol', 0, None), + Feature('Actuators', 'FETTecOneWire', 'AP_FETTEC_ONEWIRE_ENABLED', 'Enable FETTec OneWire ESCs', 0, None), +] BUILD_OPTIONS.sort(key=lambda x: x.category) diff --git a/Tools/scripts/build_parameters.sh b/Tools/scripts/build_parameters.sh index 7b5d6c2c4d5..b0ee979a6a6 100755 --- a/Tools/scripts/build_parameters.sh +++ b/Tools/scripts/build_parameters.sh @@ -3,7 +3,10 @@ set -e set -x -PARAMS_DIR="../buildlogs/Parameters" +if [ "x$BUILDLOGS" = "x" ]; then + BUILDLOGS="../buildlogs" +fi +PARAMS_DIR="$BUILDLOGS/Parameters" # work from either APM directory or above [ -d ArduPlane ] || cd APM diff --git a/Tools/scripts/build_sizes/build_sizes.py b/Tools/scripts/build_sizes/build_sizes.py index 02042a65c38..d5cce220ad3 100755 --- a/Tools/scripts/build_sizes/build_sizes.py +++ b/Tools/scripts/build_sizes/build_sizes.py @@ -16,7 +16,7 @@ parser.add_argument('--outfile', default="builds.html", help='output file') build_dirs = ['latest', 'beta', 'stable'] -builds = ['Plane', 'Copter', 'Rover', 'Sub', 'Blimp', 'AP_Periph'] +builds = ['Plane', 'Copter', 'Rover', 'Sub', 'Blimp', 'AntennaTracker', 'AP_Periph'] args = parser.parse_args() diff --git a/Tools/scripts/configure-ci.sh b/Tools/scripts/configure-ci.sh index 9ec4f55ad0a..fbd3a30318c 100755 --- a/Tools/scripts/configure-ci.sh +++ b/Tools/scripts/configure-ci.sh @@ -101,5 +101,4 @@ python -m pip install --user -U argparse pyserial pexpect future lxml python -m pip install --user -U intelhex python -m pip install --user -U numpy python -m pip install --user -U edn_format -python -m pip install --user -U empy - +python -m pip install --user -U empy==3.3.4 diff --git a/Tools/scripts/configure_all.py b/Tools/scripts/configure_all.py index 8de8208060b..2c28c8fc7ba 100755 --- a/Tools/scripts/configure_all.py +++ b/Tools/scripts/configure_all.py @@ -15,8 +15,9 @@ parser = argparse.ArgumentParser(description='configure all ChibiOS boards') parser.add_argument('--build', action='store_true', default=False, help='build as well as configure') parser.add_argument('--build-target', default='copter', help='build target') -parser.add_argument('--stop', action='store_true', default=False, help='stop on build fail') +parser.add_argument('--stop', action='store_true', default=False, help='stop on configure or build failure') parser.add_argument('--no-bl', action='store_true', default=False, help="don't check bootloader builds") +parser.add_argument('--only-bl', action='store_true', default=False, help="only check bootloader builds") parser.add_argument('--Werror', action='store_true', default=False, help="build with -Werror") parser.add_argument('--pattern', default='*') parser.add_argument('--start', default=None, type=int, help='continue from specified build number') @@ -83,7 +84,8 @@ def is_ap_periph(board): config_opts = ["--board", board] if args.Werror: config_opts += ["--Werror"] - run_program([args.python, "waf", "configure"] + config_opts, "configure: " + board) + if not args.only_bl: + run_program([args.python, "waf", "configure"] + config_opts, "configure: " + board) if args.copy_hwdef_incs_to_directory is not None: source = os.path.join("build", board, "hwdef.h") if board == "iomcu": diff --git a/Tools/scripts/cygwin_build.sh b/Tools/scripts/cygwin_build.sh index 62767fe8ea9..7761bd5ae32 100755 --- a/Tools/scripts/cygwin_build.sh +++ b/Tools/scripts/cygwin_build.sh @@ -8,11 +8,22 @@ set -x +# TOOLCHAIN=i686-pc-cygwin +TOOLCHAIN=x86_64-pc-cygwin +GPP_COMPILER="${TOOLCHAIN}-g++" + +$GPP_COMPILER -print-sysroot + +SYS_ROOT=$($GPP_COMPILER -print-sysroot) +echo "SYS_ROOT=$SYS_ROOT" + +git config --global --add safe.directory /cygdrive/d/a/ardupilot/ardupilot + rm -rf artifacts mkdir artifacts ( - python ./waf --color yes --toolchain i686-pc-cygwin --board sitl configure 2>&1 + python ./waf --color yes --toolchain $TOOLCHAIN --board sitl configure 2>&1 python ./waf plane 2>&1 python ./waf copter 2>&1 python ./waf heli 2>&1 @@ -20,7 +31,13 @@ mkdir artifacts python ./waf sub 2>&1 ) | tee artifacts/build.txt -i686-pc-cygwin-g++ -print-sysroot +# copy both with exe and without to cope with differences +# between windows versions in CI +cp -v build/sitl/bin/arduplane artifacts/ArduPlane.elf.exe +cp -v build/sitl/bin/arducopter artifacts/ArduCopter.elf.exe +cp -v build/sitl/bin/arducopter-heli artifacts/ArduHeli.elf.exe +cp -v build/sitl/bin/ardurover artifacts/ArduRover.elf.exe +cp -v build/sitl/bin/ardusub artifacts/ArduSub.elf.exe cp -v build/sitl/bin/arduplane artifacts/ArduPlane.elf cp -v build/sitl/bin/arducopter artifacts/ArduCopter.elf @@ -28,6 +45,14 @@ cp -v build/sitl/bin/arducopter-heli artifacts/ArduHeli.elf cp -v build/sitl/bin/ardurover artifacts/ArduRover.elf cp -v build/sitl/bin/ardusub artifacts/ArduSub.elf -cp -v /usr/i686-pc-cygwin/sys-root/usr/bin/*.dll artifacts/ +# Find all cyg*.dll files returned by cygcheck for each exe in artifacts +# and copy them over +for exe in artifacts/*.exe; do + echo $exe + cygcheck $exe | grep -oP 'cyg[^\s\\/]+\.dll' | while read -r line; do + cp -v /usr/bin/$line artifacts/ + done +done git log -1 > artifacts/git.txt +ls -l artifacts/ diff --git a/Tools/scripts/decode_devid.py b/Tools/scripts/decode_devid.py index 43fc0cdc9db..15b574306bf 100755 --- a/Tools/scripts/decode_devid.py +++ b/Tools/scripts/decode_devid.py @@ -97,6 +97,8 @@ def num(s): 0x36 : "DEVTYPE_INS_ICM40605", 0x37 : "DEVTYPE_INS_IIM42652", 0x38 : "DEVTYPE_INS_BMI270", + 0x39 : "DEVTYPE_INS_BMI085", + 0x3A : "DEVTYPE_INS_ICM42670", } baro_types = { @@ -113,6 +115,13 @@ def num(s): 0x0B : "DEVTYPE_BARO_MS5611", 0x0C : "DEVTYPE_BARO_SPL06", 0x0D : "DEVTYPE_BARO_UAVCAN", + 0x0E : "DEVTYPE_BARO_MSP", + 0x0F : "DEVTYPE_BARO_ICP101XX", + 0x10 : "DEVTYPE_BARO_ICP201XX", + 0x11 : "DEVTYPE_BARO_MS5607", + 0x12 : "DEVTYPE_BARO_MS5837", + 0x13 : "DEVTYPE_BARO_MS5637", + 0x14 : "DEVTYPE_BARO_BMP390", } airspeed_types = { diff --git a/Tools/scripts/du32_change.py b/Tools/scripts/du32_change.py new file mode 100755 index 00000000000..b0452b4c572 --- /dev/null +++ b/Tools/scripts/du32_change.py @@ -0,0 +1,118 @@ +#!/usr/bin/env python + +""" +Parses a log file and shows how Copter's du32 changes over time + +AP_FLAKE8_CLEAN + +""" + +from __future__ import print_function + +import optparse +import sys +import time + +from pymavlink import mavutil + + +class DU32Change(object): + def __init__(self, master): + self.master = master + + def progress(self, text): + '''emit text with possible timestamps etc''' + print("%u: %s" % (time.time(), text)) + + def run(self): + + self.progress("Creating connection") + self.conn = mavutil.mavlink_connection(master) + + # this eas was generated from Copter.h's structure for ap_t: + bit_descriptions_list = [ + "unused1", + "unused_was_simple_mode bit1", + "unused_was_simple_mode bit2", + "pre_arm_rc_check", + "pre_arm_check", + "auto_armed", + "logging_started", + "land_complete", + "new_radio_frame", + "usb_connected_unused", + "rc_receiver_present", + "compass_mot", + "motor_test", + "initialised", + "land_complete_maybe", + "throttle_zero", + "system_time_set_unused", + "gps_glitching", + "using_interlock", + "land_repo_active", + "motor_interlock_switch", + "in_arming_delay", + "initialised_params", + "unused3", + "unused2", + "armed_with_airmode_switch", + "prec_land_active", + ] + bit_descriptions = {} + count = 0 + for bit in bit_descriptions_list: + bit_descriptions[bit] = count + count += 1 + + old_m = None + + desired_type = "DU32" + while True: + m = self.conn.recv_match(type=desired_type) + if m is None: + break + if m.Id != 7: + # 7 is LOG_DATA_ID from AP_Logger.h + continue + if old_m is not None and m.Value == old_m.Value: + continue + line = "" + if old_m is None: + for bit in sorted(bit_descriptions.keys()): + bit_set = m.Value & (1 << bit_descriptions[bit]) + if bit_set: + print("Original %s: 1" % bit) + else: + print("Original %s: 0" % bit) + else: + for bit in bit_descriptions.keys(): + old_bit_set = old_m.Value & (1 << bit_descriptions[bit]) + new_bit_set = m.Value & (1 << bit_descriptions[bit]) + if new_bit_set and not old_bit_set: + line += " +%s" % bit + elif not new_bit_set and old_bit_set: + line += " -%s" % bit + + timestamp = getattr(m, '_timestamp', 0.0) + formatted_timestamp = "%s.%02u" % ( + time.strftime("%Y-%m-%d %H:%M:%S", time.localtime(timestamp)), + int(timestamp * 100.0) % 100) + + print("%s: %s" % (formatted_timestamp, line)) + old_m = m + + +if __name__ == '__main__': + parser = optparse.OptionParser("du32_change.py [options]") + + (opts, args) = parser.parse_args() + + if len(args) < 1: + parser.print_help() + sys.exit(1) + + master = args[0] + + tester = DU32Change(master) + tester.run() diff --git a/Tools/scripts/extract_features.py b/Tools/scripts/extract_features.py new file mode 100755 index 00000000000..75c6db9b8da --- /dev/null +++ b/Tools/scripts/extract_features.py @@ -0,0 +1,295 @@ +#!/usr/bin/env python + +""" +script to determine what features have been built into an ArduPilot binary + +AP_FLAKE8_CLEAN +""" + +import optparse +import os +import re +import string +import subprocess +import sys +import time +import build_options + + +if sys.version_info[0] < 3: + running_python3 = False +else: + running_python3 = True + + +class ExtractFeatures(object): + + def __init__(self, filename): + self.filename = filename + self.nm = 'arm-none-eabi-nm' + + # feature_name should match the equivalent feature in + # build_options.py ('FEATURE_NAME', 'EXPECTED_SYMBOL'). + # EXPECTED_SYMBOL is a regular expression which will be matched + # against "define" in build_options's feature list, and + # FEATURE_NAME will have substitutions made from the match. + # the substitutions will be upper-cased + self.features = [ + ('AP_AIRSPEED_ENABLED', 'AP_Airspeed::AP_Airspeed',), + ('AP_AIRSPEED_{type}_ENABLED', r'AP_Airspeed_(?P.*)::init',), + + ('HAL_ADSB_ENABLED', 'AP_ADSB::AP_ADSB',), + ('HAL_ADSB_{type}_ENABLED', r'AP_ADSB_(?P.*)::update',), + ('HAL_ADSB_UCP_ENABLED', 'AP_ADSB_uAvionix_UCP::update',), + ('AP_AIS_ENABLED', 'AP_AIS::AP_AIS',), + + ('HAL_EFI_ENABLED', 'AP_EFI::AP_EFI',), + ('BEACON_ENABLED', 'AP_Beacon::AP_Beacon',), + ('HAL_TORQEEDO_ENABLED', 'AP_Torqeedo::AP_Torqeedo'), + + ('HAL_NAVEKF3_AVAILABLE', 'NavEKF3::NavEKF3',), + ('HAL_NAVEKF2_AVAILABLE', 'NavEKF2::NavEKF2',), + ('HAL_EXTERNAL_AHRS_ENABLED', r'AP_ExternalAHRS::init\b',), + ('HAL_INS_TEMPERATURE_CAL_ENABLE', 'AP_InertialSensor::TCal::Learn::save_calibration',), + ('HAL_VISUALODOM_ENABLED', 'AP_VisualOdom::init',), + + ('AP_RANGEFINDER_ENABLED', 'RangeFinder::RangeFinder',), + ('AP_RANGEFINDER_{type}_ENABLED', r'AP_RangeFinder_(?P.*)::update\b',), + ('AP_RANGEFINDER_{type}_ENABLED', r'AP_RangeFinder_(?P.*)::get_reading\b',), + ('AP_RANGEFINDER_{type}_ENABLED', r'AP_RangeFinder_(?P.*)::model_dist_max_cm\b',), + ('AP_RANGEFINDER_LIGHTWARE_SERIAL_ENABLED', r'AP_RangeFinder_LightWareSerial::get_reading\b',), + ('AP_RANGEFINDER_LWI2C_ENABLED', r'AP_RangeFinder_LightWareI2C::update\b',), + ('AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED', r'AP_RangeFinder_MaxsonarSerialLV::get_reading\b',), + ('AP_RANGEFINDER_TRI2C_ENABLED', r'AP_RangeFinder_TeraRangerI2C::update\b',), + + ('AP_GPS_{type}_ENABLED', r'AP_GPS_(?P.*)::read\b',), + + ('AP_OPTICALFLOW_ENABLED', 'AP_OpticalFlow::AP_OpticalFlow',), + ('AP_OPTICALFLOW_{type}_ENABLED', r'AP_OpticalFlow_(?P.*)::update\b',), + + ('AP_BARO_{type}_ENABLED', r'AP_Baro_(?P.*)::update\b',), + + ('AP_MOTORS_FRAME_{type}_ENABLED', r'AP_MotorsMatrix::setup_(?P.*)_matrix\b',), + + ('HAL_MSP_ENABLED', r'AP_MSP::init\b',), + ('HAL_MSP_{type}_ENABLED', r'AP_(?P.*)_MSP::update\b',), + ('HAL_MSP_{type}_ENABLED', r'AP_(?P.*)_MSP::read\b',), + ('HAL_WITH_MSP_DISPLAYPORT', r'AP_OSD_MSP_DisplayPort::init\b',), + + + ('AP_BATTMON_{type}_ENABLE', r'AP_BattMonitor_(?P.*)::init\b',), + ('HAL_BATTMON_{type}_ENABLED', r'AP_BattMonitor_(?P.*)::init\b',), + + ('HAL_MOUNT_ENABLED', 'AP_Mount::AP_Mount',), + ('HAL_MOUNT_{type}_ENABLED', r'AP_Mount_(?P.*)::update\b',), + ('HAL_SOLO_GIMBAL_ENABLED', 'AP_Mount_SoloGimbal::init',), + ('HAL_MOUNT_STORM32SERIAL_ENABLED', 'AP_Mount_SToRM32_serial::init',), + ('HAL_MOUNT_STORM32MAVLINK_ENABLED', 'AP_Mount_SToRM32::init',), + + ('HAL_{type}_TELEM_ENABLED', r'AP_(?P.*)_Telem::init',), + ('HAL_CRSF_TELEM_TEXT_SELECTION_ENABLED', 'AP_CRSF_Telem::calc_text_selection',), + ('AP_LTM_TELEM_ENABLED', 'AP_LTM_Telem::init',), + ('HAL_HIGH_LATENCY2_ENABLED', 'GCS_MAVLINK::handle_control_high_latency',), + + ('MODE_{type}_ENABLED', r'Mode(?P.+)::init',), + ('MODE_GUIDED_NOGPS_ENABLED', r'ModeGuidedNoGPS::init',), + + ('HAL_RUNCAM_ENABLED', 'AP_RunCam::AP_RunCam',), + + ('HAL_PARACHUTE_ENABLED', 'AP_Parachute::update',), + ('AP_FENCE_ENABLED', r'AC_Fence::check\b',), + ('HAL_PROXIMITY_ENABLED', 'AP_Proximity::AP_Proximity',), + ('AC_AVOID_ENABLED', 'AC_Avoid::AC_Avoid',), + ('AC_OAPATHPLANNER_ENABLED', 'AP_OAPathPlanner::AP_OAPathPlanner',), + + ('AP_ICENGINE_ENABLED', 'AP_ICEngine::AP_ICEngine',), + ('HAL_EFI_ENABLED', 'AP_RPM_EFI::AP_RPM_EFI',), + ('HAL_EFI_NWPWU_ENABLED', r'AP_EFI_NWPMU::update\b',), + ('HAL_GENERATOR_ENABLED', 'AP_Generator::AP_Generator',), + + ('OSD_ENABLED', 'AP_OSD::AP_OSD',), + ('HAL_PLUSCODE_ENABLE', 'AP_OSD_Screen::draw_pluscode',), + ('OSD_PARAM_ENABLED', 'AP_OSD_ParamScreen::AP_OSD_ParamScreen',), + ('HAL_OSD_SIDEBAR_ENABLE', 'AP_OSD_Screen::draw_sidebars',), + + ('HAL_SMARTAUDIO_ENABLED', 'AP_SmartAudio::AP_SmartAudio',), + ('AP_TRAMP_ENABLED', 'AP_Tramp::AP_Tramp',), + + ('HAL_QUADPLANE_ENABLED', 'QuadPlane::QuadPlane',), + ('HAL_SOARING_ENABLED', 'SoaringController::var_info',), + ('HAL_LANDING_DEEPSTALL_ENABLED', r'AP_Landing_Deepstall::terminate\b',), + + ('GRIPPER_ENABLED', r'AP_Gripper::init\b',), + ('HAL_SPRAYER_ENABLED', 'AC_Sprayer::AC_Sprayer',), + ('LANDING_GEAR_ENABLED', r'AP_LandingGear::init\b',), + ('WINCH_ENABLED', 'AP_Winch::AP_Winch',), + + ('AP_VOLZ_ENABLED', r'AP_Volz_Protocol::init\b',), + ('AP_ROBOTISSERVO_ENABLED', r'AP_RobotisServo::init\b',), + ('AP_FETTEC_ONEWIRE_ENABLED', r'AP_FETtecOneWire::init\b',), + + ('RPM_ENABLED', 'AP_RPM::AP_RPM',), + + ('GPS_MOVING_BASELINE', r'AP_GPS_Backend::calculate_moving_base_yaw\b',), + + ('HAL_WITH_DSP', r'AP_HAL::DSP::find_peaks\b',), + ('HAL_DISPLAY_ENABLED', r'Display::init\b',), + ('HAL_NMEA_OUTPUT_ENABLED', r'AP_NMEA_Output::update\b',), + ('HAL_BARO_WIND_COMP_ENABLED', r'AP_Baro::wind_pressure_correction\b',), + + ('HAL_PICCOLO_CAN_ENABLE', r'AP_PiccoloCAN::update',), + ('EK3_FEATURE_EXTERNAL_NAV', r'NavEKF3::writeExtNavVelData'), + ] + + def progress(self, string): + '''pretty-print progress''' + print("EF: %s" % string) + + def run_program(self, prefix, cmd_list, show_output=True, env=None): + '''swiped from build_binaries.py''' + if show_output: + self.progress("Running (%s)" % " ".join(cmd_list)) + p = subprocess.Popen(cmd_list, bufsize=1, stdin=None, + stdout=subprocess.PIPE, close_fds=True, + stderr=subprocess.STDOUT, env=env) + output = "" + while True: + x = p.stdout.readline() + if len(x) == 0: + returncode = os.waitpid(p.pid, 0) + if returncode: + break + # select not available on Windows... probably... + time.sleep(0.1) + continue + if running_python3: + x = bytearray(x) + x = filter(lambda x : chr(x) in string.printable, x) + x = "".join([chr(c) for c in x]) + output += x + x = x.rstrip() + if show_output: + print("%s: %s" % (prefix, x)) + (_, status) = returncode + if status != 0 and show_output: + self.progress("Process failed (%s)" % + str(returncode)) + raise subprocess.CalledProcessError( + returncode, cmd_list) + return output + + class Symbols(object): + def __init__(self): + self.symbols = dict() + self.symbols_without_arguments = dict() + + def add(self, key, attributes): + self.symbols[key] = attributes + + # also keep around the same symbol name without arguments. + # if the key is already present then the attributes become + # None as there are multiple possible answers... + m = re.match("^([^(]+).*", key) + if m is None: + extracted_symbol_name = key + else: + extracted_symbol_name = m.group(1) + # print("Adding (%s)" % str(extracted_symbol_name)) + if extracted_symbol_name in self.symbols_without_arguments: + self.symbols_without_arguments[extracted_symbol_name] = None + else: + self.symbols_without_arguments[extracted_symbol_name] = attributes + + def dict_for_symbol(self, symbol): + if '(' not in symbol: + some_dict = self.symbols_without_arguments + else: + some_dict = self.symbols + return some_dict + + def extract_symbols_from_elf(self, filename): + '''parses ELF in filename, returns dict of symbols=>attributes''' + text_output = self.run_program('EF', [ + self.nm, + '--demangle', + '--print-size', + filename + ], show_output=False) + ret = ExtractFeatures.Symbols() + for line in text_output.split("\n"): + m = re.match("^([^ ]+) ([^ ]+) ([^ ]) (.*)", line.rstrip()) + if m is None: + m = re.match("^([^ ]+) ([^ ]) (.*)", line.rstrip()) + if m is None: + # raise ValueError("Did not match (%s)" % line) + # e.g. Did not match ( U _errno) + continue + (offset, symbol_type, symbol_name) = m.groups() + size = "0" + else: + (offset, size, symbol_type, symbol_name) = m.groups() + size = int(size, 16) + # print("symbol (%s) size %u" % (str(symbol_name), size)) + ret.add(symbol_name, { + "size": size, + }) + + return ret + + def create_string(self): + + ret = "" + + build_options_defines = set([x.define for x in build_options.BUILD_OPTIONS]) + + symbols = self.extract_symbols_from_elf(self.filename) + + remaining_build_options_defines = build_options_defines + compiled_in_feature_defines = [] + for (feature_define, symbol) in self.features: + some_dict = symbols.dict_for_symbol(symbol) + # look for symbols without arguments + # print("Looking for (%s)" % str(name)) + for s in some_dict.keys(): + m = re.match(symbol, s) + # print("matching %s with %s" % (symbol, s)) + if m is None: + continue + d = m.groupdict() + for key in d.keys(): + d[key] = d[key].upper() + # filter to just the defines present in + # build_options.py - otherwise we end up with (e.g.) + # AP_AIRSPEED_BACKEND_ENABLED, even 'though that + # doesn't exist in the ArduPilot codebase. + some_define = feature_define.format(**d) + if some_define not in build_options_defines: + continue + compiled_in_feature_defines.append(some_define) + remaining_build_options_defines.discard(some_define) + + for compiled_in_feature_define in sorted(compiled_in_feature_defines): + ret += compiled_in_feature_define + "\n" + for remaining in sorted(remaining_build_options_defines): + ret += "!" + remaining + "\n" + + return ret + + def run(self): + print(self.create_string()) + + +if __name__ == '__main__': + + parser = optparse.OptionParser("extract_features.py FILENAME") + + cmd_opts, cmd_args = parser.parse_args() + + if len(cmd_args) < 1: + parser.print_help() + sys.exit(1) + + filename = cmd_args[0] + + ef = ExtractFeatures(filename) + ef.run() diff --git a/Tools/scripts/generate_features_txt_files.py b/Tools/scripts/generate_features_txt_files.py new file mode 100755 index 00000000000..a998814d607 --- /dev/null +++ b/Tools/scripts/generate_features_txt_files.py @@ -0,0 +1,52 @@ +#!/usr/bin/env python + +''' +recurse through directory tree rooted at supplied path. For every elf file found, write out next to it a features.txt +''' + +import optparse +import os +import sys + +import extract_features + +class GenerateFeatureTxtFiles(object): + def __init__(self, path): + self.path = path + + def write_features_txt_for_filepath(self, filepath): + ef = extract_features.ExtractFeatures(filepath) + text = ef.create_string() + features_txt_filepath = os.path.join(os.path.dirname(filepath), "features.txt") + with open(features_txt_filepath, "w") as fh: + fh.write(text) + + def run(self): + done_dirpaths = dict() + for (dirpath, dirnames, filenames) in os.walk(self.path): + for filename in filenames: + if os.path.splitext(filename)[1].upper() != ".ELF": + continue + if dirpath in done_dirpaths: + raise ValueError( + "Already processed elf (%s) in dirpath (%s) but also found elf (%s)" % + (done_dirpaths[dirpath], dirpath, filename)) + done_dirpaths[dirpath] = filename + filepath = os.path.join(dirpath, filename) + self.write_features_txt_for_filepath(filepath) + + +if __name__ == '__main__': + + parser = optparse.OptionParser("generate_features_txt_files.py DIRPATH") + + cmd_opts, cmd_args = parser.parse_args() + + if len(cmd_args) < 1: + parser.print_help() + sys.exit(1) + + dirpath = cmd_args[0] + + gen = GenerateFeatureTxtFiles(dirpath) + gen.run() diff --git a/Tools/scripts/generate_manifest.py b/Tools/scripts/generate_manifest.py index 7c1057003ee..70c19cd752e 100755 --- a/Tools/scripts/generate_manifest.py +++ b/Tools/scripts/generate_manifest.py @@ -2,20 +2,28 @@ from __future__ import print_function -import sys +import copy +import fnmatch +import gen_stable +import gzip import json import os import re -import fnmatch -import gen_stable import subprocess +import shutil +import sys if sys.version_info[0] < 3: running_python3 = False + running_python310 = False +elif sys.version_info[1] < 10: + running_python3 = True + running_python310 = False else: running_python3 = True + running_python310 = True -FIRMWARE_TYPES = ["AntennaTracker", "Copter", "Plane", "Rover", "Sub", "AP_Periph"] +FIRMWARE_TYPES = ["AntennaTracker", "Copter", "Plane", "Rover", "Sub", "AP_Periph", "Blimp"] RELEASE_TYPES = ["beta", "latest", "stable", "stable-*", "dirty"] # mapping for board names to brand name and manufacturer @@ -31,6 +39,10 @@ 'KakuteF7Mini' : ('KakuteF7Mini', 'Holybro'), 'KakuteF4Mini' : ('KakuteF4Mini', 'Holybro'), 'KakuteH7Mini' : ('KakuteH7Mini', 'Holybro'), + 'KakuteH7Mini-Nand' : ('KakuteH7Mini-Nand', 'Holybro'), + 'KakuteH7' : ('KakuteH7', 'Holybro'), + 'KakuteH7-bdshot' : ('KakuteH7', 'Holybro'), + 'KakuteH7v2' : ('KakuteH7v2', 'Holybro'), 'CubeBlack' : ('CubeBlack', 'Hex/ProfiCNC'), 'CubeYellow' : ('CubeYellow', 'Hex/ProfiCNC'), 'CubeOrange' : ('CubeOrange', 'Hex/ProfiCNC'), @@ -43,6 +55,7 @@ 'CUAVv5Nano' : ('CUAVv5 Nano', 'CUAV'), 'CUAVv5Nano-bdshot' : ('CUAVv5 Nano', 'CUAV'), 'CUAV-Nora' : ('CUAV Nora', 'CUAV'), + 'CUAV-Nora-bdshot' : ('CUAV Nora', 'CUAV'), 'CUAV-X7' : ('CUAV X7', 'CUAV'), 'CUAV-X7-bdshot' : ('CUAV X7', 'CUAV'), 'DrotekP3Pro' : ('Pixhawk 3 Pro', 'Drotek'), @@ -74,17 +87,23 @@ 'OmnibusNanoV6' : ('Omnibus Nano V6', 'Airbot'), 'OmnibusNanoV6-bdshot' : ('Omnibus Nano V6', 'Airbot'), 'speedybeef4' : ('SpeedyBee F4', 'SpeedyBee'), + 'speedybeef4v3' : ('SpeedyBee F4 v3', 'SpeedyBee'), 'QioTekZealotF427' : ('ZealotF427', 'QioTek'), 'BeastH7' : ('Beast H7 55A AIO', 'iFlight'), + 'BeastH7v2' : ('Beast H7 v2 55A AIO', 'iFlight'), 'BeastF7' : ('Beast F7 45A AIO', 'iFlight'), 'BeastF7v2' : ('Beast F7 v2 55A AIO', 'iFlight'), 'MambaF405US-I2C' : ('Diatone Mamba Basic F405 MK3/MK3.5', 'Diatone'), + 'MambaF405-2022' : ('Diatone Mamba Basic F405 MK4', 'Diatone'), + 'MambaH743v4' : ('Diatone Mamba H743 MK4', 'Diatone'), "FlywooF745" : ('Flywoo Goku GN 745 AIO', 'Flywoo'), "FlywooF745Nano" : ('Flywoo Goku Hex F745', 'Flywoo'), "modalai_fc-v1" : ('ModalAI FlightCore v1', 'ModalAI'), 'Pixhawk5X' : ('Pixhawk 5X', 'Holybro'), "AIRLink" : ("Sky-Drones Technologies", "AIRLink"), "SPRacingH7" : ("Seriously Pro Racing", "H7 Extreme"), + "SkystarsH7HD" : ("Skystars", "H743 HD"), + "SkystarsH7HD-bdshot" : ("Skystars", "H743 HD"), } class Firmware(): @@ -227,7 +246,7 @@ def add_USB_IDs_ChibiOS(self, firmware): # map of vendor specific USB IDs USBID_MAP = { 'CubeBlack': ['0x2DAE/0x1011'], - 'CubeOrange': ['0x2DAE/0x1016'], + 'CubeOrange': ['0x2DAE/0x1016', '0x2DAE/0x1017'], 'CubePurple': ['0x2DAE/0x1005'], 'CubeYellow': ['0x2DAE/0x1002'], 'Pixhawk4': ['0x3162/0x0047'], @@ -273,6 +292,16 @@ def add_USB_IDs_ChibiOS(self, firmware): firmware['bootloader_str'].append('MindPX BL FMU v2.x') firmware['USBID'].append('0x26AC/0x0030') + if board_id == 53: + # special case for 6X, they always get the px4 bootloader IDs as an option + firmware['bootloader_str'].append('PX4 BL FMU v6X.x') + firmware['USBID'].append('0x3185/0x0035') + + if board_id == 56: + # special case for 6C, they always get the px4 bootloader IDs as an option + firmware['bootloader_str'].append('PX4 BL FMU v6C.x') + firmware['USBID'].append('0x3185/0x0038') + if platform in brand_map: (brand_name, manufacturer) = brand_map[platform] firmware['brand_name'] = brand_name @@ -377,8 +406,14 @@ def add_firmware_data_from_dir(self, frame = vehicletype # e.g. Plane platform = platformdir # e.g. apm2 + # also gather information from any features.txt files present: + features_text = None + features_filepath = os.path.join(some_dir, "features.txt") + if os.path.exists(features_filepath): + features_text = sorted(open(features_filepath).read().rstrip().split("\n")) + for filename in os.listdir(some_dir): - if filename in ["git-version.txt", "firmware-version.txt", "files.html"]: + if filename in ["git-version.txt", "firmware-version.txt", "files.html", "features.txt"]: continue if filename.startswith("."): continue @@ -396,7 +431,7 @@ def add_firmware_data_from_dir(self, filepath = os.path.join(some_dir, filename) firmware_format = self.firmware_format_for_filepath(filepath) - if firmware_format not in [ "ELF", "abin", "apj", "hex", "px4", "bin" ]: + if firmware_format not in [ "elf", "ELF", "abin", "apj", "hex", "px4", "bin" ]: print("Unknown firmware format (%s)" % firmware_format) firmware = Firmware() @@ -429,6 +464,8 @@ def add_firmware_data_from_dir(self, firmware["format"] = firmware_format firmware["firmware-version"] = firmware_version + firmware["features"] = features_text + firmware_data.append(firmware) def valid_release_type(self, tag): @@ -489,6 +526,8 @@ def walk_directory(self, basedir): # convert from ardupilot-naming conventions to common JSON format: firmware_json = [] + features_json = [] # a structure containing summarised features per firmware + for firmware in firmwares: filepath = firmware["filepath"] # replace the base directory with the base URL @@ -507,6 +546,7 @@ def walk_directory(self, basedir): "latest": firmware["latest"], "format": firmware["format"], }) + if firmware["firmware-version"]: try: (major, minor, patch, release_type) = self.parse_fw_version( @@ -526,22 +566,83 @@ def walk_directory(self, basedir): #print(some_json['url']) firmware_json.append(some_json) + # now the features the firmware supports... + try: + features = firmware["features"] + # check apj here in case we're creating bin and apj etc: + if (firmware["format"] == "apj" and + features is not None and + bool(firmware["latest"])): + x = dict({ + "vehicletype": firmware["vehicletype"], + "platform": firmware["platform"], + "git-sha": firmware["git_sha"], + "latest": firmware["latest"], + }) + x["features"] = features + features_json.append(x) + + except KeyError: + pass + ret = { "format-version": "1.0.0", # semantic versioning "firmware": firmware_json } - return ret + features_ret = { + "format-version": "1.0.0", # semantic versioning + "features": features_json + } - def json(self): - '''walk directory supplied in constructor, return json string''' + return ret, features_ret + + def run(self): + '''walk directory supplied in constructor, record results in self''' if not self.looks_like_binaries_directory(self.basedir): print("Warning: this does not look like a binaries directory", file=sys.stderr) - structure = self.walk_directory(self.basedir) - return json.dumps(structure, indent=4, separators=(',', ': ')) + self.structure, self.features_structure = self.walk_directory(self.basedir) + def json(self): + '''returns JSON string for version information for all firmwares''' + if getattr(self, 'structure', None) is None: + self.run() + return json.dumps(self.structure, indent=4, separators=(',', ': ')) + + def json_features(self): + '''returns JSON string for supported features for all firmwares. + run() method must have been called already''' + return json.dumps(self.features_structure, indent=4, separators=(',', ': ')) + + def write_string_to_filepath(self, string, filepath): + '''writes the entirety of string to filepath''' + with open(filepath, "w") as x: + x.write(string) + + def write_json(self, content, path): + '''write content to path, also creating a compress .gz version''' + new_json_filepath = path + ".new" + self.write_string_to_filepath(content, new_json_filepath) + # provide a pre-compressed version. For reference, a 7M manifest + # "gzip -9"s to 300k in 1 second, "xz -e"s to 80k in 26 seconds + new_json_filepath_gz = path + ".gz.new" + with gzip.open(new_json_filepath_gz, 'wb') as gf: + if running_python3: + content = bytes(content, 'ascii') + gf.write(content) + gf.close() + shutil.move(new_json_filepath, path) + shutil.move(new_json_filepath_gz, path + ".gz") + + def write_manifest_json(self, path): + '''write generated JSON content to path''' + self.write_json(self.json(), path) + + def write_features_json(self, path): + '''write generated features JSON content to path''' + self.write_json(self.json_features(), path) def usage(): return '''Usage: @@ -553,6 +654,7 @@ def usage(): parser = argparse.ArgumentParser(description='generate manifest.json') parser.add_argument('--outfile', type=str, default=None, help='output file, default stdout') + parser.add_argument('--outfile-features-json', type=str, default=None, help='output file for features json file') parser.add_argument('--baseurl', type=str, default="https://firmware.ardupilot.org", help='base binaries directory') parser.add_argument('basedir', type=str, default="-", help='base binaries directory') @@ -562,12 +664,13 @@ def usage(): gen_stable.make_all_stable(args.basedir) generator = ManifestGenerator(args.basedir, args.baseurl) + generator.run() + + content = generator.json() if args.outfile is None: - print(generator.json()) + print(content) else: - f = open(args.outfile, "w") - content = generator.json() - if running_python3: - content = bytes(content, 'ascii') - f.write(content) - f.close() + generator.write_manifest_json(args.outfile) + + if args.outfile_features_json is not None: + generator.write_features_json(args.outfile_features_json) diff --git a/Tools/scripts/magfit_flashlog.py b/Tools/scripts/magfit_flashlog.py old mode 100644 new mode 100755 diff --git a/Tools/scripts/make_apj.py b/Tools/scripts/make_apj.py index e05e72aeb60..69165edb8a3 100755 --- a/Tools/scripts/make_apj.py +++ b/Tools/scripts/make_apj.py @@ -27,7 +27,8 @@ "summary": args.bin, "version": "0.1", "image_size": len(img), - "board_revision": 0 + "board_revision": 0, + "signed_firmware": False, } f = open(args.apj, "w") diff --git a/Tools/scripts/powr_change.py b/Tools/scripts/powr_change.py index 3d515ceedca..332f9814dcd 100755 --- a/Tools/scripts/powr_change.py +++ b/Tools/scripts/powr_change.py @@ -28,7 +28,9 @@ def bit_description(self, bit_number): if 1 << bit_number not in mavutil.mavlink.enums["MAV_POWER_STATUS"]: return "UNKNOWN_BIT[%u]" % bit_number - return mavutil.mavlink.enums["MAV_POWER_STATUS"][1 << bit_number].name + name = mavutil.mavlink.enums["MAV_POWER_STATUS"][1 << bit_number].name + # return name with common prefix removed: + return name[len("MAV_POWER_STATUS_"):] def run(self): diff --git a/Tools/scripts/run_flake8.py b/Tools/scripts/run_flake8.py index 695f86f0146..acfde4e4e52 100755 --- a/Tools/scripts/run_flake8.py +++ b/Tools/scripts/run_flake8.py @@ -19,16 +19,18 @@ class Flake8Checker(object): def __init__(self): self.retcode = 0 + self.files_to_check = [] def progress(self, string): print("****** %s" % (string,)) - def check(self, filepath): - self.progress("Checking (%s)" % filepath) - retcode = subprocess.call(["flake8", filepath]) - if retcode != 0: - self.progress("File (%s) failed with retcode (%s)" % - (filepath, retcode)) + def check(self): + for path in self.files_to_check: + self.progress("Checking (%s)" % path) + ret = subprocess.run(["flake8", "--show-source"] + self.files_to_check, + stdout=subprocess.PIPE, stderr=subprocess.STDOUT, text=True) + if ret.returncode != 0: + self.progress("Flake8 check failed: (%s)" % (ret.stdout)) self.retcode = 1 def run(self): @@ -40,7 +42,8 @@ def run(self): content = open(filepath).read() if "AP_FLAKE8_CLEAN" not in content: continue - self.check(filepath) + self.files_to_check.append(filepath) + self.check() return self.retcode diff --git a/Tools/scripts/runplanetest.py b/Tools/scripts/runplanetest.py index d94a55a2435..4ceaa13bc16 100755 --- a/Tools/scripts/runplanetest.py +++ b/Tools/scripts/runplanetest.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 import pexpect, time, sys from pymavlink import mavutil @@ -25,6 +25,20 @@ def wait_mode(mav, modes, timeout=10): print("Failed to get mode from %s" % modes) sys.exit(1) +def wait_prearm_ok(mav, timeout=30): + '''wait for pre-arm OK''' + start_time = time.time() + last_mode = None + while time.time() < start_time+timeout: + m = mav.recv_match(type='SYS_STATUS', blocking=True, timeout=2) + if m is None: + return + if m.onboard_control_sensors_health & mavutil.mavlink.MAV_SYS_STATUS_PREARM_CHECK != 0: + print("Prearm OK") + return + print("Failed to get pre-arm OK") + sys.exit(1) + def wait_time(mav, simtime): '''wait for simulation time to pass''' imu = mav.recv_match(type='RAW_IMU', blocking=True) @@ -36,17 +50,24 @@ def wait_time(mav, simtime): break cmd = '../Tools/autotest/sim_vehicle.py -D -f quadplane' -mavproxy = pexpect.spawn(cmd, logfile=sys.stdout, timeout=30) +mavproxy = pexpect.spawn(cmd, logfile=sys.stdout.buffer, timeout=30) mavproxy.expect("ArduPilot Ready") mav = mavutil.mavlink_connection('127.0.0.1:14550') mavproxy.send('speedup 40\n') -mavproxy.expect('using GPS') -mavproxy.expect('using GPS') -mavproxy.expect('using GPS') -mavproxy.expect('using GPS') -mavproxy.send('auto\n') +wait_prearm_ok(mav) +mavproxy.send('mode guided\n') +wait_mode(mav, ['GUIDED']) mavproxy.send('arm throttle\n') -wait_mode(mav, ['AUTO']) -mavproxy.expect("Mission: 5 WP") +mavproxy.send('takeoff 40\n') +wait_time(mav, 30) +mavproxy.send('mode cruise\n') +wait_mode(mav, ['CRUISE']) +wait_time(mav, 10) +mavproxy.send('mode qrtl\n') +wait_mode(mav, ['QRTL']) +mavproxy.send('module load console\n') +mavproxy.send('module load map\n') +mavproxy.logfile = None +mavproxy.interact() diff --git a/Tools/scripts/signing/ArduPilotKeys/ArduPilot_public_key1.dat b/Tools/scripts/signing/ArduPilotKeys/ArduPilot_public_key1.dat new file mode 100644 index 00000000000..e6a0b3b7f3a --- /dev/null +++ b/Tools/scripts/signing/ArduPilotKeys/ArduPilot_public_key1.dat @@ -0,0 +1 @@ +PUBLIC_KEYV1:WJbbpbjOz/yMB3JxnvqyTUInCQdZcStkA0qhn2ldhPI= diff --git a/Tools/scripts/signing/ArduPilotKeys/ArduPilot_public_key2.dat b/Tools/scripts/signing/ArduPilotKeys/ArduPilot_public_key2.dat new file mode 100644 index 00000000000..c70a68cc9a7 --- /dev/null +++ b/Tools/scripts/signing/ArduPilotKeys/ArduPilot_public_key2.dat @@ -0,0 +1 @@ +PUBLIC_KEYV1:X8jdVqxIIUmCuMSi8IhTZ40VkXW0gbRczzMtdSghqCI= diff --git a/Tools/scripts/signing/ArduPilotKeys/ArduPilot_public_key3.dat b/Tools/scripts/signing/ArduPilotKeys/ArduPilot_public_key3.dat new file mode 100644 index 00000000000..22e4303bce3 --- /dev/null +++ b/Tools/scripts/signing/ArduPilotKeys/ArduPilot_public_key3.dat @@ -0,0 +1 @@ +PUBLIC_KEYV1:snNHkX96F9A+/ISppHZrc1jjPo3jMNN+g2PToKhWSgA= diff --git a/Tools/scripts/signing/README.md b/Tools/scripts/signing/README.md new file mode 100644 index 00000000000..473a14a8e9e --- /dev/null +++ b/Tools/scripts/signing/README.md @@ -0,0 +1,149 @@ +# Secure Boot Support + +To assist with vendors needing high levels of tamper resistance with +RemoteID, you can optionally use secure boot with ArduPilot. This +involves installing a bootloader with up to 10 public keys included +and signing the ArduPilot vehicle firmware with one secret key. The +bootloader will refuse to boot the firmware if the signature on the +firmware doesn't match any of the public keys in the bootloader. + +## Generating Keys + +To generate a public/private key pair, run the following command: + +``` + python3 -m pip install pymonocypher==3.1.3.2 + Tools/scripts/signing/generate_keys.py NAME +``` + +That will create two files: + - NAME_private_key.dat + - NAME_public_key.dat + +NAME can be any string, but would usually be your vendor name. It is +only used for the local filenames. + +The generated private key should be kept in a secure location. The +public key will be used to create a secure bootloader that will only +accept firmwares signed with one of the public keys in the bootloader. + +## Building secure bootloader + +To build a secure bootloader run this command: + +``` + Tools/scripts/build_bootloaders.py BOARDNAME --signing-key=NAME_public_key.dat +``` + +That will update the bootloader in Tools/bootloaders/BOARDNAME_bl.bin +to enable secure boot with the specified public key. Next time you +build a firmware for this board then that bootloader will be included +in ROMFS. + +Note that this will include the 3 ArduPilot signing keys by default as +well as your key. This is done so that your users can update to a +standard ArduPilot firmware release and also prevents issues with +vendors who can no longer provide firmware updates to users. If you +have a very good reason for not including the ArduPilot signing keys +then you can pass the option --omit-ardupilot-keys to the +make_secure_bl.py script. + +## Building Signed Firmware + +To build a signed firmware run this command (example is for a copter build): + +``` + ./waf configure --board BOARDNAME --signed-fw + ./waf copter + ./Tools/scripts/signing/make_secure_fw.py build/BOARDNAME/bin/arducopter.apj NAME_private_key.dat +``` + +The final step signs the apj firmware with your private key. You can +then load that secure firmware as usual with your ground station, for +example using load custom firmware in MissionPlanner or +Tools/scripts/uploader.py on Linux. + +Alternatively you can set the private key in the configure step, which +allows for build and upload in one step for faster development: + +``` + ./waf configure --board BOARDNAME --signed-fw --private-key NAME_private_key.dat + ./waf copter --upload +``` + +## Flashing the secure bootloader + +There are two methods of getting the secure bootloader onto the +board. The simplest is to follow the above steps and then follow the +usual method of updating the bootloader, which involves sending a +MAVLink command to ask the firmware to flash the embedded bootloader +from ROMFS. The firmware generated using the above steps will have +your secure bootloader included in ROMFS, so when the users asks for +the bootloader to update it will flash the secure bootloader. + +The second method is to put the board into DFU mode. If your hwdef.dat +and hwdef-bl.dat include the ENABLE_DFU_BOOT options and your board is +based on a STM32H7 then your ground station should be able to put the +board into DFU mode. You can then flash the bootloader bin file to +address 0x08000000 using any DFU capable client. + +Note that the flight controller will refuse a switch to DFU mode if it +is running a secure bootloader already. + +## How to tell you are using secure boot + +When using a secure bootloader the USB ID presented by the bootloader +will have a "Secure" string added. For example, you would see this in +"dmesg" in Linux: + +``` + Product: BOARDNAME-Secure-BL-v10 +``` + +On Windows you can look at the device properties in device manager +when the bootloader is running and look for the "Bus reported device +description". It will have the above "Secure" string. Note that this +string only appears when in the bootloader. To ensure the board stays +in the bootloader for long enough to see this string just flash a +normal unsigned firmware. With a secure bootloader and an unsigned +firmware the board will stay in the bootloader forever as it will be +failing the secure boot checks. + +## Reverting to normal boot + +If you have installed secure boot on a board then to revert to normal +boot you would need to flash a new bootloader that does not have +secure boot enabled. To do that you should replace +Tools/bootloaders/BOARDNAME_bl.bin with the normal bootloader for your +board then build and sign a firmware as above. Then ask the flight +controller to flash the updated bootloader using the GCS interface and +you will then be running a normal bootloader. + +## Supported Boards + +Secure boot is only supported on boards with at least 32k of flash +space for the bootloader. This includes all boards based on the +STM32H7 and STM32F7. You can use secure boot on older other boards if +you change the hwdef.dat and hwdef-bl.dat to add more space for the +bootloader. + +## Public key update over MAVLink + +If you have a private key corresponding to one of the public keys in +the bootloader on a board then you can use the MAVLink2 SECURE_COMMAND +messages to change the public keys, or even remove all public keys to +allow the use of unsigned firmwares. + +MAVProxy version 1.8.55 and later has a "securecommand" module which +gives you commands for: + + - generating a session key for remote update + - fetching the current public keys + - setting new public keys as additonal or replacement keys + - removing all public keys + +It is expected that future versions of MissionPlanner will include a +plugin with the same functionality. + +Using SECURE_COMMAND in combination with MAVLink forwarding you can +hand over management of a vehicle between vendors. diff --git a/Tools/scripts/signing/generate_keys.py b/Tools/scripts/signing/generate_keys.py new file mode 100755 index 00000000000..3ff80baa98e --- /dev/null +++ b/Tools/scripts/signing/generate_keys.py @@ -0,0 +1,35 @@ +#!/usr/bin/env python3 +''' +generate a public/private key pair using Monocypher +''' + +import sys +import base64 + +try: + import monocypher +except ImportError: + print("Please install monocypher with: python3 -m pip install pymonocypher==3.1.3.2") + sys.exit(1) + + +if len(sys.argv) != 2: + print("Usage: generate_keys.py BASENAME") + sys.exit(1) + +bname = sys.argv[1] + +def encode_key(ktype, key): + return ktype + "_KEYV1:" + base64.b64encode(key).decode('utf-8') + +private_key = monocypher.generate_key() +public_key = monocypher.compute_signing_public_key(private_key) + +public_fname = "%s_public_key.dat" % bname +private_fname = "%s_private_key.dat" % bname + +open(private_fname, "w").write(encode_key("PRIVATE", private_key)) +print("Generated %s" % private_fname) + +open(public_fname, "w").write(encode_key("PUBLIC", public_key)) +print("Generated %s" % public_fname) diff --git a/Tools/scripts/signing/make_secure_bl.py b/Tools/scripts/signing/make_secure_bl.py new file mode 100755 index 00000000000..10c700d2ca4 --- /dev/null +++ b/Tools/scripts/signing/make_secure_bl.py @@ -0,0 +1,76 @@ +#!/usr/bin/env python3 +''' +add a set of up to 10 public keys to an ArduPilot bootloader bin file +''' + +import sys +import os +import base64 + +try: + import monocypher +except ImportError: + print("Please install monocypher with: python3 -m pip install pymonocypher==3.1.3.2") + sys.exit(1) + +# get command line arguments +from argparse import ArgumentParser +parser = ArgumentParser(description='make_secure_bl') +parser.add_argument("--omit-ardupilot-keys", action='store_true', default=False, help="omit ArduPilot signing keys") +parser.add_argument("bootloader", type=str, default=None, help="bootloader") +parser.add_argument("keys", nargs='*', type=str, default=[], help="keys") +args = parser.parse_args() + +descriptor = b'\x4e\xcf\x4e\xa5\xa6\xb6\xf7\x29' +max_keys = 10 +key_len = 32 + +img = open(args.bootloader, 'rb').read() + +offset = img.find(descriptor) +if offset == -1: + print("Failed to find descriptor") + sys.exit(1) + +offset += 8 +desc = b'' +desc_len = 0 + +keys = [] + +if not args.omit_ardupilot_keys: + print("Adding ArduPilot keys") + signing_dir = os.path.dirname(os.path.realpath(__file__)) + keydir = os.path.join(signing_dir,"ArduPilotKeys") + for root, dirs, files in os.walk(keydir): + for f in files: + if f.endswith(".dat"): + keys.append(os.path.relpath(os.path.join(keydir, f))) + +keys += args.keys[:] + +if len(keys) > max_keys: + print("Too many key files %u, max is %u" % (len(keys), max_keys)) + sys.exit(1) + +if len(keys) <= 0: + print("At least one key file required") + sys.exit(1) + +def decode_key(ktype, key): + ktype += "_KEYV1:" + if not key.startswith(ktype): + print("Invalid key type") + sys.exit(1) + return base64.b64decode(key[len(ktype):]) + +for kfile in keys: + key = decode_key("PUBLIC", open(kfile, "r").read()) + print("Applying Public Key %s" % kfile) + if len(key) != key_len: + print("Bad key length %u in %s" % (len(key), kfile)) + sys.exit(1) + desc += key + desc_len += key_len +img = img[:offset] + desc + img[offset+desc_len:] +open(sys.argv[1], 'wb').write(img) diff --git a/Tools/scripts/signing/make_secure_fw.py b/Tools/scripts/signing/make_secure_fw.py new file mode 100755 index 00000000000..fea837f5807 --- /dev/null +++ b/Tools/scripts/signing/make_secure_fw.py @@ -0,0 +1,91 @@ +#!/usr/bin/env python3 +''' +sign an ArduPilot APJ firmware with a private key +''' + +import sys +import struct +import json, base64, zlib + +try: + import monocypher +except ImportError: + print("Please install monocypher with: python3 -m pip install pymonocypher==3.1.3.2") + sys.exit(1) + +key_len = 32 +sig_len = 64 +sig_version = 30437 +descriptor = b'\x41\xa3\xe5\xf2\x65\x69\x92\x07' + +if len(sys.argv) < 3: + print("Usage: make_secure_fw.py APJ_FILE PRIVATE_KEYFILE") + sys.exit(1) + +def to_unsigned(i): + '''convert a possibly signed integer to unsigned''' + if i < 0: + i += 2**32 + return i + +apj_file = sys.argv[1] +key_file = sys.argv[2] + +# open apj file +apj = open(apj_file, 'r').read() + +# decode json in apj +d = json.loads(apj) + +# get image data +img = zlib.decompress(base64.b64decode(d['image'])) +img_len = len(img) + +def decode_key(ktype, key): + ktype += "_KEYV1:" + if not key.startswith(ktype): + print("Invalid key type") + sys.exit(1) + return base64.b64decode(key[len(ktype):]) + +key = decode_key("PRIVATE", open(key_file, 'r').read()) +if len(key) != key_len: + print("Bad key length %u" % len(key)) + sys.exit(1) + +offset = img.find(descriptor) +if offset == -1: + print("No APP_DESCRIPTOR found") + sys.exit(1) + +offset += 8 +desc_len = 92 + +flash1 = img[:offset] +flash2 = img[offset+desc_len:] +flash12 = flash1 + flash2 + +signature = monocypher.signature_sign(key, flash12) +if len(signature) != sig_len: + print("Bad signature length %u should be %u" % (len(signature), sig_len)) + sys.exit(1) + +# pack signature in 4 bytes length, 8 byte signature version and 64 byte +# signature. We have a signature version to allow for changes to signature +# system in the future +desc = struct.pack(" 1 + % Reset prevent Adding + if abs(sigDiff(i)) < 90 + skip = 0; + % Add to offset, if switch happened from 2pi to 0 + elseif sigDiff(i) <= -90 && ~skip + offset = offset + 360;%(sigIn(i-2)+sigIn(i-1))/2; % Smooth signal values since they are oscillating at jumps + skip = 1; + % Subtract from offset, if switch happened from 0 tp 2 pi + elseif sigDiff(i) > 90 && ~skip + offset = offset - 360;%(sigIn(i+2)+sigIn(i+1))/2; % Smooth signal values since they are oscillating at jumps + skip = 1; + end + end +end + +% Apply moving average filter to smooth out sample value jumps +steps = 10; +coeffFilt = ones(1, steps)/steps; +% sigOut = filter(coeffFilt, 1, sigOut); +sigOut = movmean(sigOut, 9); +end + diff --git a/Tools/simulink/arducopter/functions/getMotorMixerFactors.m b/Tools/simulink/arducopter/functions/getMotorMixerFactors.m new file mode 100644 index 00000000000..8962bad03a4 --- /dev/null +++ b/Tools/simulink/arducopter/functions/getMotorMixerFactors.m @@ -0,0 +1,126 @@ +% Function to get the copters number of motors and there configuration to +% calculate the motor mixer factors for roll, pitch and yaw +% +% Fabian Bredemeier - IAV GmbH +% License: GPL v3 +function [num_motors, axis_facs_motors] = getMotorMixerFactors(frame_class, frame_type) + d2r = pi/180; + axis_facs_motors = struct; + num_motors = 0; + % Preliminary cell array for the motors axis factors consisting of the + % roll/pitch factor in degree (first element of cells) and the yaw + % factor + axis_facs_motors_pre = cell(0,0); + + %% Get configuration + + switch frame_class + case 1 % Quad + num_motors = 4; + axis_facs_motors_pre = cell(4,1); + switch frame_type + case 0 % Plus + axis_facs_motors_pre = { [90, 1]; [-90, 1]; [0, -1]; [180, -1] }; + case 1 % X + axis_facs_motors_pre = { [45, 1]; [-135, 1]; [-45, -1]; [135, -1] }; + case 2 % V + axis_facs_motors_pre = { [45, 0.7981]; [-135, 1.0]; [-45, -0.7981]; [135, -1.0] }; + case 3 % H + axis_facs_motors_pre = { [45, -1]; [-135, -1]; [-45, 1]; [135, 1] }; + case 13 % DJIX + axis_facs_motors_pre = { [45, 1]; [-45, -1]; [-135, 1]; [135, -1] }; + case 14 % Clockwise ordering + axis_facs_motors_pre = { [45, 1]; [135, -1]; [-135, 1]; [-45, -1] }; + end + case 2 % Hexa + num_motors = 6; + case {3, 4} % Octa and OctaQuad + num_motors = 8; + axis_facs_motors_pre = cell(8,1); + switch frame_type + case 0 % Plus + axis_facs_motors_pre = { [0, -1]; [180, -1]; [45, 1]; [135, 1]; ... + [-45, 1]; [-135, 1]; [-90, -1]; [90, -1] }; + case 1 % X + axis_facs_motors_pre = { [22.5, -1]; [-157.5, -1]; [67.5, 1]; [157.5, 1]; ... + [-22.5, 1]; [-122.5, 1]; [-67.5, -1]; [112.5, -1] }; + case 2 % V + axis_facs_motors_pre = { [0.83, 0.34, -1]; [-0.67, -0.32, -1]; [0.67, -0.32, 1]; [-0.50, -1.00, 1]; ... + [1.00, 1.00, 1]; [-0.83, 0.34, 1]; [-1.00, 1.00, -1]; [0.5, -1.00, -1] }; + end + case 5 % Y6 + num_motors = 6; + case 12 % DodecaHexa + num_motors = 12; + case 14 % Deca + num_motors = 14; + end + + %% Check if configuration is defined + % Leave function if frame class is not configured yet + if num_motors == 0 + disp("Frame class unknown. Please add the configuration to the function."); + return; + end + % Leave function if axis factors are not yet defined for frame + if isempty(axis_facs_motors_pre) + disp("Motor axis factors are not yet defined for frame class!"); + disp("The factors can be found in the setup_motors function within AP_MotorsMatrix.cpp."); + return; + end + + %% Calculate axis factors (roll/pitch) from preliminary array + % Create the output struct that stores the factors for the different + % axis in separate arrays. Each column of the subarrays represents one motor. + axis_facs_motors = struct('roll', zeros(1,num_motors), ... + 'pitch', zeros(1,num_motors), ... + 'yaw', zeros(1,num_motors) , ... + 'throttle', zeros(1, num_motors) ); + for i=1:num_motors + % Check if factors for roll and pitch are defined separately and + % therefore in radian -> dimension of a cell would be 3 + if ( length(axis_facs_motors_pre{i}) >= 3 ) + axis_facs_motors.roll(1,i) = axis_facs_motors_pre{i}(1); + axis_facs_motors.pitch(1,i) = axis_facs_motors_pre{i}(2); + else + axis_facs_motors.roll(1,i) = cos( (axis_facs_motors_pre{i}(1)+90)*d2r ); + axis_facs_motors.pitch(1,i) = cos( (axis_facs_motors_pre{i}(1))*d2r ); + end + % The factors for yaw can be acquired directly from the preliminary + % array + axis_facs_motors.yaw(1,i) = axis_facs_motors_pre{i}(2); + % The factors for throttle are 1.0 by default (see AP_MotorsMatrix.h, + % line 87) + axis_facs_motors.throttle(1,i) = 1.0; + end + + %% Normalization of factors (AP_MotorsMatrix.cpp, line 1218) + roll_fac_max = 0.0; + pitch_fac_max = 0.0; + yaw_fac_max = 0.0; + throttle_fac_max = 0.0; + + % Find maximum factor + for i=1:num_motors + roll_fac_max = max(roll_fac_max, axis_facs_motors.roll(1,i)); + pitch_fac_max = max(pitch_fac_max, axis_facs_motors.pitch(1,i)); + yaw_fac_max = max(yaw_fac_max, axis_facs_motors.yaw(1,i)); + throttle_fac_max = max(throttle_fac_max, axis_facs_motors.throttle(1,i)); + end + + % Scale factors back to -0.5 to +0.5 for each axis + for i=1:num_motors + if(roll_fac_max ~= 0) + axis_facs_motors.roll(1,i) = 0.5 * axis_facs_motors.roll(1,i) / roll_fac_max; + end + if(pitch_fac_max ~= 0) + axis_facs_motors.pitch(1,i) = 0.5 * axis_facs_motors.pitch(1,i) / pitch_fac_max; + end + if(yaw_fac_max ~= 0) + axis_facs_motors.yaw(1,i) = 0.5 * axis_facs_motors.yaw(1,i) / yaw_fac_max; + end + if(throttle_fac_max ~= 0) + axis_facs_motors.throttle(1,i) = 0.5 * axis_facs_motors.throttle(1,i) / throttle_fac_max; + end + end +end \ No newline at end of file diff --git a/Tools/simulink/arducopter/functions/getParamVal.m b/Tools/simulink/arducopter/functions/getParamVal.m new file mode 100644 index 00000000000..df1863bdb1e --- /dev/null +++ b/Tools/simulink/arducopter/functions/getParamVal.m @@ -0,0 +1,39 @@ +function paramVals = getParamVal(obj,paramName) +% Return the value for the parameters defined in the cell array +% paramName of the sid object obj +% +% Fabian Bredemeier - IAV GmbH +% License: GPL v3 + +% Get list of parameter names +param_names = cell(length(obj.PARM.Name),1); +for i=1:length(obj.PARM.Name) + param_names{i,1} = deblank(obj.PARM.Name(i,1:16)); +end + +% Translate parameter name to cell array if only one name is provided +if ~iscell(paramName) + desParamNames{1} = paramName; +else + desParamNames = paramName; +end + +% Read parameter(s) with boolean indexing +paramVals = single(zeros(numel(desParamNames),1)); +for i = 1:length(desParamNames) + paramIdx = strcmp(param_names, desParamNames{i}); + paramVal = single(obj.PARM.Value(paramIdx)); + if isempty(paramVal) + warning('Parameter could not be found!'); + paramVal = []; + return; + end + paramVals(i,1) = paramVal(1); % Prevent nultidimensional parameters + + if isempty(paramVals) + error(['Parameter ' desParam{i} ' could not be found.']); + end +end + +end + diff --git a/Tools/simulink/arducopter/functions/getTimeZero.m b/Tools/simulink/arducopter/functions/getTimeZero.m new file mode 100644 index 00000000000..60fcf378401 --- /dev/null +++ b/Tools/simulink/arducopter/functions/getTimeZero.m @@ -0,0 +1,47 @@ +function timeZero = getTimeZero(log, msgs, msgs2Ex) +% Get the earliest time stamp in the log +% +% Fabian Bredemeier - IAV GmbH +% License: GPL v3 + +% Create dummy zero timestamp +if isprop(log, 'RATE') + timeZero = log.RATE.TimeS(1); +else + error('Message RATE not contained in log.'); +end + +% Define messages that should not be included in search for time stamp +if nargin < 3 + msgs2Exclude = {'FMT', 'FMTU', 'MODE', 'MULT', 'UNIT', 'PARM'}; +else + msgs2Exclude = msgs2Ex; +end + +for m = msgs + msg = m{1}; + % Skip messages to exclude + if any(strcmp(msgs2Exclude, msg)) + continue; + end + + % Output warning if message is not included in log + if ~any(strcmp(fieldnames(log), msg)) + warning(['Message ' msg ' not included in log!']); + end + + % Skip message if message is deleted handle + if ~isvalid(log.(msg)) + continue; + end + + % Compare first time stamps and get lower start time + firstTime = log.(msg).TimeS(1); + if abs(timeZero - firstTime) > 2 + error(['Time vector of ' msg ' invalid. The first time stamp is too far off. Aborting.']); + elseif firstTime < timeZero + timeZero = firstTime; + end +end +end + diff --git a/Tools/simulink/arducopter/functions/plausibilizeTime.m b/Tools/simulink/arducopter/functions/plausibilizeTime.m new file mode 100644 index 00000000000..554dac8db19 --- /dev/null +++ b/Tools/simulink/arducopter/functions/plausibilizeTime.m @@ -0,0 +1,98 @@ +function [timePlaus, signalPlaus] = plausibilizeTime(time,signal) +% Checks if time vector has a major tracking error and delete respective +% element from time and signal vector +% +% Fabian Bredemeier - IAV GmbH +% License: GPL v3 + +% Get indices for time values that are too high +validIdx = ~(time > 1e6); +if time(1) > time(2) % First time stamp is invalid if greater than second + validIdx(1) = 0; +end + +% Calculate average sample time +Ts_avg = sum(diff(time(validIdx)))/length(time); + +% Only plausibilize time vector +if nargin == 1 + % Set first element + if time(1) > 1e6 && time(2) < 1e6 || time(1) > time(2) + timePlaus = time(2)-Ts_avg; + else + timePlaus = time(1); + end + idxDiff = 0; % Tracking of removed elements + skipNext = 0; % Flag to skip next element + for i = 2:length(time)-1 + if skipNext + skipNext = 0; + continue; + end + if(time(i+1) abs((time(i+1)-time(i-1))-Ts_avg) && time(i+1)-time(i-1) > 0 + % Current element is wrong since deviation to average + % sample time is larger - skip current and do nothing + + else + % Next element is wrong, so add current to corrected vector + timePlaus(i-idxDiff,1) = time(i); + + % Make sure next one is skipped + skipNext = 1; + end + idxDiff = idxDiff + 1; + else + timePlaus(i-idxDiff,1) = time(i); + end + end + % Add last element + len = length(time); + timePlaus(len-idxDiff,1) = time(end); + return; + +% Also plausibilize signal vector +elseif nargin == 2 + % Set first element + if time(1) > 1e6 && time(2) < 1e6 || time(1) > time(2) + timePlaus = time(2)-Ts_avg; + signalPlaus = signal(2); + else + timePlaus = time(1); + signalPlaus = signal(1); + end + idxDiff = 0; % Tracking of removed elements + skipNext = 0; % Flag to skip next element + for i = 2:length(time)-1 + if skipNext + skipNext = 0; + continue; + end + if(time(i+1) abs((time(i+1)-time(i-1))-Ts_avg) && time(i+1)-time(i-1) > 0 + % Current element is wrong since deviation to average + % sample time is larger - skip current and do nothing + + else + % Next element is wrong, so add current to corrected vector + timePlaus(i-idxDiff,1) = time(i); + signalPlaus(i-idxDiff,1) = signal(i); + + % Make sure next one is skipped + skipNext = 1; + end + idxDiff = idxDiff + 1; + else + timePlaus(i-idxDiff,1) = time(i); + signalPlaus(i-idxDiff,1) = signal(i); + end + end + % Add last element + len = length(time); + timePlaus(len-idxDiff,1) = time(end); + signalPlaus(len-idxDiff,1) = signal(end); +end +end + diff --git a/Tools/simulink/arducopter/functions/resampleLog.m b/Tools/simulink/arducopter/functions/resampleLog.m new file mode 100644 index 00000000000..100c7cf108f --- /dev/null +++ b/Tools/simulink/arducopter/functions/resampleLog.m @@ -0,0 +1,166 @@ +function [logResampled] = resampleLog(log,resampling,method) +% Resamples log if resample is set to true, so that all included messages +% have the same first time stamp and the same amount of elements +% (if they have the same sample time) +% If resample is set to false, the Time vector of all messages is just +% adapted to the first time stamp of the log +% +% Fabian Bredemeier - IAV GmbH +% License: GPL v3 + +headerProps2Copy = {'fileName', 'filePathName', 'platform', 'version', ... + 'commit', 'bootTimeUTC', 'msgsContained', 'totalLogMsgs', 'msgFilter', ... + 'numMsgs'}; + +% Define messages that are to be excluded from resampling, but still copied +msgs2Exclude = {'FMT', 'FMTU', 'MODE', 'MULT', 'UNIT', 'PARM', 'SIDS'}; + +% Messages with multiple instances +msgWithMultInstances = {'ARSP', 'BARO', 'BAT', 'BCL', 'BCL2', 'ESC', ... + 'GPA', 'GPS', 'IMU', 'MAG', 'PRX', 'RFND'}; + +% Define message header props that need to be copied to new log +msgProps2Copy = {'typeNumID', 'fieldUnits', 'fieldMultipliers', 'name', ... + 'MsgInstance'}; + +% Define message props that need to be excluded in new log +msgProps2Exclude = {'TimeS', 'LineNo', 'DatenumUTC', 'TimeUS'}; + +% Define sample times that are used for logging +TsVec = [0.00025 0.001 0.0025 0.01 0.02 0.04 0.1 0.2 1]; + +% Allowed jitter percentage of sample time +TsJitPerc = 0.5; + +% Get first timestamp of log +timeZero = getTimeZero(log, log.msgsContained, msgs2Exclude); + +% Convert LogMsgGroup object into structs +log = log.getStruct(); + +for prop = string(fieldnames(log))' + propObj = log.(prop); + + % Just copy property if contained in cell array + if any(strcmp(prop, headerProps2Copy)) + logResampled.(prop) = propObj; + continue; + end + + % Skip message if it shall be excluded + if any(strcmp(prop, msgs2Exclude)) + logResampled.(prop) = propObj; + continue; + end + + % Skip message if it is a deleted handle + if isempty(propObj) + continue; + end + + % Handle messages with multiple instances (like BAT) + if any(strcmp(msgWithMultInstances, prop)) + % Create idx vector for certain instance + if isfield(propObj, 'Instance') % Check message name of instance + idxVec = propObj.Instance == 0; + elseif isfield(propObj, 'I') + idxVec = propObj.I == 0; + elseif isfield(propObj, 'C') % XKF messages + idxVec = propObj.C == 0; + end + else % Message without multiple instances + idxVec = logical(ones(length(propObj.TimeS),1)); + end + + % Get plausibilized time vector + timePlaus = plausibilizeTime(log.(prop).TimeS(idxVec)); + + % Determine sample time of message + TsRaw = mean(diff(timePlaus)); + Ts = 0; + for TsElem = TsVec + if TsRaw > TsElem*(1-TsJitPerc) && TsRaw < TsElem*(1+TsJitPerc) + Ts = TsElem; + break; + end + end + % Throw error if Ts could not be determined + if Ts == 0 + error(['Sample time of message ' char(prop) ' could not be determined. Mean: ' num2str(TsRaw) 's']); + end + + % Copy properties to new object. Resample signals + msgProps = string(fieldnames(log.(prop)))'; + for msgProp = msgProps(1:end) + + % Copy property if included in msgProps2Copy + if any(strcmp(msgProp, msgProps2Copy)) + logResampled.(prop).(msgProp) = propObj.(msgProp); + continue; + end + + % Skip property if included in msgProps2Exclude + if any(strcmp(msgProp, msgProps2Exclude)) + continue; + end + + % Get signal values for the correct indices + signal = propObj.(msgProp)(idxVec); + + % Define time starting from first time stamp + time = propObj.TimeS(idxVec) - timeZero; + + % Plausibilize time and signal vector + [time, signal] = plausibilizeTime(time, signal); + + % If any time sample is still larger than the final time, + % plausibilize the time vector again + while(any(time > time(end))) + [time, signal] = plausibilizeTime(time, signal); + end + + % Define old time vector. Insert zero at beginning for the signals + % to start at 0s. Insert first signal value in value vector. + if time(1) > 1e-3 + timeOld = zeros(length(time)+1,1); + signalOld = zeros(length(signal)+1,1); + timeOld(2:length(time)+1, 1) = time; + timeOld(1) = 0; + signalOld(2:length(signal)+1, 1) = signal; + signalOld(1) = signal(1); + else + timeOld = time; + signalOld = signal; + end + + % Catch nan in signal + if any(isnan(signalOld)) + signalOld = zeros(length(signalOld),1); + warning(['Detected nan in ' char(prop) '.' char(msgProp)]) + end + + if resampling + % Resample signal + if any(strcmp(method, 'makima')) || any(strcmp(method, 'nearest')) + len = round(timeOld(end) / Ts, 0); % Get amount of time vec elements + timeNew = Ts * (0:len)'; + signalNew = interp1(timeOld, signalOld, timeNew, method, 'extrap'); + else + [signalNew, timeNew] = resample(signalOld, timeOld, 1/Ts, method); + end + else + signalNew = signal; + timeNew = Ts*(0:length(signal)-1)'; + end + + % Insert property + logResampled.(prop).(msgProp) = signalNew; + % Add new property sampling time Ts + logResampled.(prop).Ts = Ts; + end + + % Add Time Property + logResampled.(prop).TimeS = timeNew; +end +end + diff --git a/Tools/simulink/arducopter/sid_controller_validation.m b/Tools/simulink/arducopter/sid_controller_validation.m new file mode 100644 index 00000000000..014ea31c24e --- /dev/null +++ b/Tools/simulink/arducopter/sid_controller_validation.m @@ -0,0 +1,237 @@ +% Validation of the controller model +% +% The script initializes and runs the Simulink model in controller +% validation mode and validates the controller model. +% +% The user has to specify the controller that is to be validated (simMode) +% and the index of the logfile in "sidLogs" (log_idx) that is used for the +% validation. +% +% Fabian Bredemeier - IAV GmbH +% License: GPL v3 + +curPath = pwd; + +%% Define log file index and controller type to be validated +% Log file index used for validation +log_idx = 2; + +% Check validity of log_idx +if log_idx > numel(sidLogs) + error(['Defined log_idx exceeds number of elements in sidLogs (' num2str(numel(sidLogs)) ')!']); +end + +% Show figure with flight paths for user to decide which controller to +% validate +figure % Attitude controller signals +subplot(311) +plot(sidLogs(log_idx).data.RATE.TimeS, sidLogs(log_idx).data.RATE.RDes, 'LineWidth', 1.4); +hold on +plot(sidLogs(log_idx).data.RATE.TimeS, sidLogs(log_idx).data.RATE.R, 'LineWidth', 1.4); +hold off +grid on +legend('Desired', 'Actual'); +xlabel('Time (s)'); +ylabel('Roll angle (deg)'); +xlim([0 max(sidLogs(log_idx).data.RATE.TimeS)]); +subplot(312) +plot(sidLogs(log_idx).data.RATE.TimeS, sidLogs(log_idx).data.RATE.PDes, 'LineWidth', 1.4); +hold on +plot(sidLogs(log_idx).data.RATE.TimeS, sidLogs(log_idx).data.RATE.P, 'LineWidth', 1.4); +hold off +grid on +legend('Desired', 'Actual'); +xlabel('Time (s)'); +ylabel('Pitch angle (deg)'); +xlim([0 max(sidLogs(log_idx).data.RATE.TimeS)]); +subplot(313) +plot(sidLogs(log_idx).data.RATE.TimeS, sidLogs(log_idx).data.RATE.YDes, 'LineWidth', 1.4); +hold on +plot(sidLogs(log_idx).data.RATE.TimeS, sidLogs(log_idx).data.RATE.Y, 'LineWidth', 1.4); +hold off +grid on +legend('Desired', 'Actual'); +xlabel('Time (s)'); +ylabel('Yaw angle (deg)'); +xlim([0 max(sidLogs(log_idx).data.RATE.TimeS)]); + +% Plot z Controller signals if Althold flight mode was active +if sidLogs(log_idx).data.MODE.Mode == 2 + figure + plot(sidLogs(log_idx).data.PSCD.TimeS, -1*(sidLogs(log_idx).data.PSCD.TPD), 'LineWidth', 1.4); % -1 to yield upwards position + hold on + plot(sidLogs(log_idx).data.PSCD.TimeS, -1*(sidLogs(log_idx).data.PSCD.PD), 'LineWidth', 1.4); + hold off + grid on + legend('Desired', 'Actual'); + xlabel('Time (s)'); + ylabel('z Position (m)'); + xlim([0 max(sidLogs(log_idx).data.RATE.TimeS)]); +end + +% Ask user for controller to validate +% 1 = Rate controller +% 2 = Attitude controller +% 3 = Position controller +fprintf('Flight mode in log file: '); +fprintf('%d', sidLogs(log_idx).data.MODE.Mode); +switch sidLogs(log_idx).data.MODE.Mode + case 0 + fprintf(' (Stabilize)\n'); + case 2 + fprintf(' (Althold)\n'); +end +fprintf('Available controllers that can be validated: \n'); +fprintf('1 = Rate controller\n'); +fprintf('2 = Attitude controller\n'); +fprintf('3 = z Position controller\n'); +fprintf('0 = Abort.\n'); +simMode = input(['Enter controller to be validated: ']); +switch simMode + case 0 + fprintf('Aborting...\n'); + close all + return; + case 1 + ctrlName = 'rateCtrl'; + case 2 + ctrlName = 'attCtrl'; + case 3 + ctrlName = 'zPosCtrl'; +end + +% Define title of validation for documentation purposes +valTitle = 'Arducopter-4.3'; + +%% Configuration of validation - Get signal names for comparison +% Declaration of temporary evaluation structs +val_out_sig_names = {}; +val_out_sig_sim = {}; +val_out_sig_meas = {}; +val_in_sig_names = {}; +val_in_sig = {}; + +% Call the config script to read the necessary signals for the evaluation +% and the names of their counterparts in the Ardupilot code +sid_controller_validation_cfg + +%% Run simulation +% Sim init script +sid_sim_init + +% Run simulation +simOut = sim("arducopter"); + +%% Store results + +% Create directory for storing the results for the controller validation +% if we are not currently in the result folder... +if isempty(regexp(curPath, 'results')) + % ...AND if the folder is not already existing on the current path + if ~exist('results', 'file') + mkdir results + cd results + else + cd results + end +end +if isempty(regexp(curPath, 'ctrlVal')) + if ~exist('ctrlVal', 'file') + mkdir ctrlVal + cd ctrlVal + else + cd ctrlVal + end +end + +% Get number of existing subdirectories with today's date and create new +% subdirectory with the validation title and controller that is validated +date = datestr(now, 'yy_mm_dd'); +numFolders = 0; +while true + if numFolders < 10 + dir_name = [date '_0' num2str(numFolders) '_' valTitle '_' ctrlName]; + if ~(isfolder(dir_name)) + mkdir(dir_name); + break; + end + else + dir_name = [date '_' num2str(numFolders) '_' valTitle '_' ctrlName]; + if ~(isfolder(dir_name)) + mkdir(dir_name); + break; + end + end + numFolders = numFolders + 1; +end + +% Open or create log +log_id = fopen('result_log.txt','a+'); +fprintf(log_id, 'Validation %s\n', dir_name); % Print directory to safe figures +fprintf(log_id, 'Flight data path: %s\n', sidLogs(log_idx).data.filePathName); % Print flight data path +fprintf(log_id, 'Flight data file: %s\n', sidLogs(log_idx).data.fileName); % Print flight data file name +fprintf(log_id, 'Subflight: %d\n', loadedDataConfig.subflights(log_idx)); +header_mark = '---------------------------------------------------------------\n'; +fprintf(log_id, header_mark); +table_header = '%s\t\t\t|%s\n'; +fprintf(log_id, table_header, 'Signal', 'Fit between measured and simulated signal (in %)'); +fprintf(log_id, header_mark); +fclose(log_id); + +% Calculate evaluation struct & save results +for i=1:length(val_out_sig_names) + % Get SimulationData object + out_sim = simOut.logsout.get(val_out_sig_sim{i}); + out_meas = simOut.logsout.get(val_out_sig_meas{i}); + out_name = val_out_sig_names{i}; + in_test = simOut.logsout.get(val_in_sig{i}); + + % Create figure of results + figure('Name', out_name); + plot(out_sim.Values.time, out_sim.Values.Data); + hold on + plot(out_meas.Values.time, out_meas.Values.Data); + hold off + ylabel(out_name) + + yyaxis right + plot(in_test.Values.time, in_test.Values.Data); + yAxR = gca; + ylabel(val_in_sig_names{i}); + yAxR.YLim = [min(in_test.Values.Data)-min(in_test.Values.Data)*0.05, max(in_test.Values.Data)+max(in_test.Values.Data)*0.05]; + + % Figure settings + xlim([0 out_sim.Values.time(end)]); % Limit time + grid on % Activate grid of axes + title([out_name ': Comparison between simulated and measured controller outputs.'], 'Interpreter', 'none'); + legend('Simulated Output', 'Measured Output', 'Input'); + + % Save figure + cd(dir_name) + savefig([out_name '.fig']) + cd .. + close all + + % Calculate coefficient of determination to determine fit between + % measured and simulated signal + sigFit = 1 - sum((out_meas.Values.Data - out_sim.Values.Data).^2)/sum(out_meas.Values.Data.^2); + + % Write log + log_line = '%s\t\t| %6.3f \n'; + log_id = fopen('result_log.txt','a'); + fprintf(log_id, log_line, out_name, sigFit*100); + fclose(log_id); +end + +log_id = fopen('result_log.txt','a'); +fprintf(log_id, '\n'); +fclose(log_id); + +% Return to main directory +cd(curPath); + +clear val_in_sig val_in_sig_names val_out_sig_meas val_out_sig_sim val_out_sig_names +clear valTitle sigFit sig_name out_name sig_meas sig_test test_sig test_sig_names +clear table_header f_name num_folders file_struct header header_mark +clear log_id log_line num_folders sig_name_ap sig_sim sig_real signal_log underscore +clear date i dir_name out out_meas out_sim in_test yAxR ctrlName \ No newline at end of file diff --git a/Tools/simulink/arducopter/sid_controller_validation_cfg.m b/Tools/simulink/arducopter/sid_controller_validation_cfg.m new file mode 100644 index 00000000000..2f3792ba45b --- /dev/null +++ b/Tools/simulink/arducopter/sid_controller_validation_cfg.m @@ -0,0 +1,27 @@ +% Configuration script for the control model validation +% Determines simulated and measured signals that are compared to validate +% the control model +% +% Fabian Bredemeier - IAV GmbH +% License: GPL v3 + +switch simMode + case 1 % Rate Controller + val_out_sig_names = {'RATE.ROut', 'RATE.POut', 'RATE.YOut'}; % Names of signals in the Ardupilot dataflash logs + val_out_sig_sim = {'rollRateCtrlOut', 'pitchRateCtrlOut', 'yawRateCtrlOut'}; % Names of the simulated signals + val_out_sig_meas = {'rollRateTotMeas', 'pitchRateTotMeas', 'yawRateTotMeas'}; % Names of the measured signals + val_in_sig_names = {'RATE_RDes', 'RATE_PDes', 'RATE_YDes'}; + val_in_sig = {'', '', ''}; + case 2 % Attitude controller + val_out_sig_names = {'RATE.RDes','RATE.PDes', 'RATE.YDes'}; + val_out_sig_sim = {'rollRateTar', 'pitchRateTar', 'yawRateTar'}; + val_out_sig_meas = {'rollRateTarMeas','pitchRateTarMeas', 'yawRateTarMeas'}; + val_in_sig_names = {'RCIN.C1', 'RCIN.C2', 'RCIN.C4'}; + val_in_sig = {'rcinRoll', 'rcinPitch', 'rcinYaw'}; + case 3 % z position controller + val_out_sig_names = {'CTUN.ThI', 'PSCD.TAD', 'PSCD.TVD'}; + val_out_sig_sim = {'thrOut', 'zAccTar', 'zVelTar'}; + val_out_sig_meas = {'thrInMeas', 'zAccTarMeas', 'zVelTarMeas'}; + val_in_sig_names = {'PSCD.TAD', 'PSCD.TVD', 'PSCD.TPD'}; + val_in_sig = {'zAccTar', 'zVelTar', 'zPosTar'}; +end \ No newline at end of file diff --git a/Tools/simulink/arducopter/sid_pre.m b/Tools/simulink/arducopter/sid_pre.m new file mode 100644 index 00000000000..948d1fe264b --- /dev/null +++ b/Tools/simulink/arducopter/sid_pre.m @@ -0,0 +1,537 @@ +% Reads ArduPilot's system identification dataflash logs and extracts the SID +% subsections of the fligts into .mat file, discarding all irrelevant data +% +% +% Fabian Bredemeier - IAV GmbH +% License: GPL v3 + +close all; + +addpath(genpath('functions')) +%% File selection by user + +% ---------------------------------------------- % +% % +% File selection % +% % +% ---------------------------------------------- % + +% 1) Ask user if next data should be added to existing data set +if exist('sidLogs', 'var') + % Abort if config data for existing data is missing + if ~exist('loadedDataConfig', 'var') + error('No configuration of the existing data could be found. Aborting...'); + end + addData = input('Add next data to existing data set (0: no, 1: yes)?'); + if addData > 1 && ~isnumeric(addData) + error('Input not valid. Only 0 or 1 are allowed.') + end +else + addData = 0; +end + +% Delete old data of new data will not be added. Otherwise get number of +% existing elements +if ~addData + clear sidLogs idData + numOldSubflights = 0; + numOldSysidflights = 0; +else + numOldSubflights = numel(sidLogs); + if exist('idData', 'var') + numOldSysidflights = numel(idData); + end +end + +% 2) User chooses new flight data from explorer +mainPath = pwd; +flightDataSearchPath = [mainPath]; +[files,flightDataPath] = uigetfile({'*.*'},... + 'Select One or More Files', ... + 'MultiSelect', 'on', ... + flightDataSearchPath); +% If only one file is selected, convert char array to cell array +if ~iscell(files) + files = cellstr(files); + numFiles = 1; +else + numFiles = size(files,2); +end + +% 3) Get file extensions - .BIN oder .mat +fileExt = cell(numFiles,1); +for i=1:numFiles + fileExt{i} = files{i}(end-2:end); +end + +% 4) Create cell array with file names +fileNames = cell(numFiles,1); +for i=1:numFiles + fileNames{i} = [flightDataPath files{i}]; +end + +% 5) Load .mat files - loadedDataConfig is struct, so load fileName field +chooseSubflights = false; +for i=1:numFiles + if strcmp(fileExt{i}, 'mat') + load(fileNames{i}); + fileNames = loadedDataConfig.fileNames; + % Fill chooseSubflights variable with false for amount of + % subflights + for j=1:length(loadedDataConfig.subflights) + chooseSubflights(j) = false; + end + else + % Activate subflight choosing if BIN files were selected + chooseSubflights(i) = true; + end +end + +%% Load complete log data and show tested modes + +% ---------------------------------------------- % +% % +% Loading Dataflash Logs % +% % +% ---------------------------------------------- % + +fprintf('\n-------------------------------------------\nLoading Flash Logs...\n') +fprintf('-------------------------------------------\n'); + +% Variables to store subflight numbers,amount of subflights and modes +subflights = 0; +fileIndices = 0; +numSubflights = 0; +modes = 0; + +for fileIdx = 1:length(fileNames) + + fprintf('Processing file %d ...\n', fileIdx); + + % Throw error if files cannot be found + if ~isfile(fileNames{fileIdx}) + error(['File ' + string(fileNames{fileIdx}) + ' could not be found.']); + end + logs(fileIdx) = Ardupilog(char(fileNames{fileIdx})); + + % Plot and Output for sysid mode + if any(logs(fileIdx).MODE.Mode == 25) + fig = figure; + set(fig, 'defaultAxesColorOrder', [[0 0 0]; [0 0 0]]); % Set axes color to black + + subplot(2, 1, 1); + plot(logs(fileIdx).MODE.TimeS, logs(fileIdx).MODE.ModeNum, 'k*'); + ylabel(logs(fileIdx).getLabel('MODE/ModeNum')); + if ~issorted(logs(fileIdx).MODE.TimeS, 'strictascend') + disp([char(fileNames{fileIdx}) ' MODE.TimeS is not monotonic!']) + end + title(['Sysid Mode' fileNames{fileIdx}], 'Interpreter', 'none'); + + % Plot tested SID axes + hold on; + yyaxis right; + plot(logs(fileIdx).SIDS.TimeS, logs(fileIdx).SIDS.Ax, 'r*'); + ylabel(logs(fileIdx).getLabel('SIDS/Ax')); + if ~issorted(logs(fileIdx).SIDS.TimeS, 'strictascend') + disp([char(fileNames{fileIdx}) ' SIDS.TimeS is not monotonic!']) + end + xlim([logs(fileIdx).MODE.TimeS(1) logs(fileIdx).PIDR.TimeS(end)]); + hold off; + + % Plot frequency of SID tests + subplot(2, 1, 2); + plot(logs(fileIdx).SIDD.TimeS, logs(fileIdx).SIDD.F, 'b.'); + ylabel(logs(fileIdx).getLabel('SIDD/F')); + if ~issorted(logs(fileIdx).SIDD.TimeS, 'strictascend') + disp([char(fileNames{fileIdx}) ' SIDD.TimeS is not monotonic!']) + end + hold on; + + % Plot subflight numbers + yyaxis right; + TimeS = logs(fileIdx).MODE.TimeS; + subflightNr = 1:length(logs(fileIdx).MODE.Mode); + plot(TimeS, subflightNr, 'k*'); + ylabel('subflight'); + if ~issorted(logs(fileIdx).SIDS.TimeS, 'strictascend') + disp([char(fileNames{fileIdx}) ' SIDS.TimeS is not monotonic!']) + end + xlim([logs(fileIdx).MODE.TimeS(1) logs(fileIdx).PIDR.TimeS(end)]); + hold off; + end + + % Plot for z position controller + if ~isempty(logs(fileIdx).PSCD.TimeS) + fig = figure; + set(fig, 'defaultAxesColorOrder', [[0 0 0]; [0 0 0]]); % Set axes color to black + + % Plot mode numbers + subplot(2, 1, 1); + plot(logs(fileIdx).MODE.TimeS, logs(fileIdx).MODE.ModeNum, 'k*'); + ylabel(logs(fileIdx).getLabel('MODE/ModeNum')); + if ~issorted(logs(fileIdx).MODE.TimeS, 'strictascend') + disp([char(fileNames{fileIdx}) ' MODE.TimeS is not monotonic!']) + end + xlim([logs(fileIdx).MODE.TimeS(1) logs(fileIdx).PIDR.TimeS(end)]); + ylim([min(logs(fileIdx).MODE.ModeNum)-1 max(logs(fileIdx).MODE.ModeNum)+1]); + title(['Other Modes' fileNames{fileIdx}], 'Interpreter', 'none'); + + % Plot measured z position + subplot(2,1,2); + plot(logs(fileIdx).PSCD.TimeS, -1*(logs(fileIdx).PSCD.PD), 'b.'); % -1 because of inverted logging of PSCD.PD + ylabel('z-Position (m)'); + if ~issorted(logs(fileIdx).PSCD.TimeS, 'strictascend') + disp([char(fileNames{fileIdx}) ' PSCD.TimeS is not monotonic!']) + end + % Plot subflight numbers + hold on; + yyaxis right; + TimeS = logs(fileIdx).MODE.TimeS; + subflightNr = 1:length(logs(fileIdx).MODE.Mode); + plot(TimeS, subflightNr, 'k*'); + ylabel('subflight'); + xlim([logs(fileIdx).MODE.TimeS(1) logs(fileIdx).PIDR.TimeS(end)]); + ylim([0 subflightNr(end)+1]); + hold off; + end + + % Plot for x-y position controller + if ~isempty(logs(fileIdx).PSCN.TimeS) && ~isempty(logs(fileIdx).PSCE.TimeS) + fig = figure; + set(fig, 'defaultAxesColorOrder', [[0 0 0]; [0 0 0]]); % Set axes color to black + + % Plot mode numbers + subplot(2, 1, 1); + plot(logs(fileIdx).MODE.TimeS, logs(fileIdx).MODE.ModeNum, 'k*'); + ylabel(logs(fileIdx).getLabel('MODE/ModeNum')); + if ~issorted(logs(fileIdx).MODE.TimeS, 'strictascend') + disp([char(fileNames{fileIdx}) ' MODE.TimeS is not monotonic!']) + end + xlim([logs(fileIdx).MODE.TimeS(1) logs(fileIdx).PIDR.TimeS(end)]); + ylim([min(logs(fileIdx).MODE.ModeNum)-1 max(logs(fileIdx).MODE.ModeNum)+1]); + title(['Other Modes' fileNames{fileIdx}], 'Interpreter', 'none'); + + % Plot measured x and y position + subplot(2,1,2); + plot(logs(fileIdx).PSCN.TimeS, logs(fileIdx).PSCN.PN, 'r.'); + ylabel('Position (m)'); + if ~issorted(logs(fileIdx).PSCN.TimeS, 'strictascend') + disp([char(fileNames{fileIdx}) ' PSCN.TimeS is not monotonic!']) + end + hold on; + plot(logs(fileIdx).PSCE.TimeS, logs(fileIdx).PSCE.PE', 'b.'); + if ~issorted(logs(fileIdx).PSCE.TimeS, 'strictascend') + disp([char(fileNames{fileIdx}) ' PSCE.TimeS is not monotonic!']) + end + + % Plot subflight numbers + yyaxis right; + TimeS = logs(fileIdx).MODE.TimeS; + subflightNr = 1:length(logs(fileIdx).MODE.Mode); + plot(TimeS, subflightNr, 'k*'); + ylabel('subflight'); + xlim([logs(fileIdx).MODE.TimeS(1) logs(fileIdx).PIDR.TimeS(end)]); + ylim([0 subflightNr(end)+1]); + hold off; + legend('x-Position', 'y-Position', 'Subflight') % PSCN is x, PSCE is y + end + + % This aids the users configuring the subflights + disp('Tested Flight Modes:'); + disp(' flight filename'); + disp([' ' num2str(fileIdx) ' ' char(fileNames{fileIdx})]); + fprintf('Subflight\tMode\tSID_AXIS\n'); + j = 1; + for i=1:length(logs(fileIdx).MODE.Mode) + if logs(fileIdx).MODE.Mode(i) == 25 + % If mode is sysid, print tested axis + + % Decrement sysid mode index j if the start time of + % sysid mode was not tracked (and does not equal the mode + % time stamps as a result). If it was not tracked, the + % settings are identical to the sysid mode before and were + % not changed. + if abs(logs(fileIdx).MODE.TimeS(i)-logs(fileIdx).SIDS.TimeS(j)) > 0.01 && j > 1 + j = j-1; + end + + fprintf('\t%d\t\t%d\t\t%d\n', i, logs(fileIdx).MODE.Mode(i), logs(fileIdx).SIDS.Ax(j)); + + % Increment sysid mode index j only if the start time was + % tracked (and equals the mode time stamps as a result). + % Otherwise, the tracked sysid information belongs to the + % next sysid flight and is equal to the current, so that + % the index should not be changed to derive the same infos. + if abs(logs(fileIdx).MODE.TimeS(i)-logs(fileIdx).SIDS.TimeS(j)) < 0.01 + j = j+1; + end + else + % If not, just print mode + fprintf('\t%d\t\t%d\t\t-\n', i, logs(fileIdx).MODE.Mode(i)); + end + end + + % Let the user select the subflight if BIN files are selected + iSubflights = 1; + while(true) + if chooseSubflights(fileIdx) + nextSubflight = input('Insert number of subflight to be saved (skip with 0): '); + % Repeat loop if input is empty + if isempty(nextSubflight) + continue; + end + % Leave loop when nextSubflight is zero + if nextSubflight == 0 + fprintf(['Subflight selection for flight ' num2str(fileIdx) ' done.\n']); + break; + end + % Give warnings when given number exceeds number of + % subflights... + if nextSubflight > length(logs(fileIdx).MODE.Mode) + warning('Given number exceeds number of subflights!'); + continue + end + % ...or when subflight was selected twice for the same flight + if any(nextSubflight == subflights(numSubflights+1:end)) + warning('Subflight already selected!'); + continue + end + + else + % Break if number of added subflights equals the total number + % of loaded subflights for that file (represented by appearence + % of the respective file index in fileIndices) + if numel(subflights)-numSubflights >= sum(loadedDataConfig.fileIndices == fileIdx) && subflights ~= 0 + break; + end + % mat file was chosen - read subflight from config + nextSubflight = loadedDataConfig.subflights(numSubflights+iSubflights); + end + + % Add subflight, file index and mode + subflights(numSubflights+iSubflights) = nextSubflight; + fileIndices(numSubflights+iSubflights) = fileIdx; + modes(numSubflights+iSubflights) = logs(fileIdx).MODE.Mode(nextSubflight); + modesConfig(numSubflights+iSubflights) = ModeConfig(modes(end)); + iSubflights = iSubflights + 1; % Update subflight index + + % Break loop if number of selected subflights equals number of + % modes + if length(logs(fileIdx).MODE.Mode) < iSubflights + break; + end + end + % Update amount of subflights only if 0 was not chosen as subflight + if ~any(subflights == 0) + numSubflights = length(subflights); + end +end +clear file ax TimeS subflightNr fig nextSubflight iSubflights numFiles fileIdx fileExt +clear flightDataSearchPath +%% Slice logs to desired subflights + +% Time increment that is used to extend the slicing time interval to +% prevent signals (that are only defined at the first time step) to be +% excluded from the sliced log because of floating point precision +dt_ext = 0.001; + +% Create list for axis that were tested (axis=0 if sysid was not used) +axisList = 0; + +% ---------------------------------------------- % +% % +% Extract relevant log messages and slice logs % +% % +% ---------------------------------------------- % + +% slice the system identification flight subsection(s) +fprintf('\n-------------------------------------------\n') +fprintf('Extracting messages and slicing logs...\n'); +fprintf('-------------------------------------------\n'); +% Delete sid in case of reloading for new config +clear sid +for i = 1:length(fileIndices) + fprintf(['Subflight Nr. ' num2str(i) '\n']); + % Check if current subflight number doesn't exceed actual subflights + if (subflights(i) > length(logs(fileIndices(i)).MODE.Mode) ) + error(['Defined subflight (index ' num2str(i) ') exceeds amount of actual subflights!']); + end + + % Filter log messages + logFilterMsgs = {}; + logFilterMsgs = modesConfig(i).filter_msgs; + % Check if log_filter_msgs is not empty + if ~iscellstr(logFilterMsgs) + error('logFilterMsgs variable is not a string cell array'); + end + % Check if message is included in flight log + for msg = logFilterMsgs + % Skip message if it was not defined - delete it from array + if ~isprop(logs(fileIndices(i)), msg{1}) + warning(['Message ' msg{1} ' not included in subflight ' ... + num2str(subflights(i)) ' of logfile ' ... + fileNames{fileIndices(i)} '!']) + elseif isempty(logs(fileIndices(i)).(msg{1}).LineNo) + warning(['Message ' msg{1} ' not included in subflight ' ... + num2str(subflights(i)) ' of logfile ' ... + fileNames{fileIndices(i)} '!']); + logFilterMsgs(strcmp(logFilterMsgs, msg{1})) = []; + end + end + log = logs(fileIndices(i)).filterMsgs(logFilterMsgs); + + % Slice log to desired time section + if subflights(i) < length(logs(fileIndices(i)).MODE.Mode) + % Current subflight is not last subflight of log + start_time = logs(fileIndices(i)).MODE.TimeUS(subflights(i))/1e6; + % end time: Subtract 2*dt_ext to prevent first time step of + % next flight mode to be part of sliced log + end_time = logs(fileIndices(i)).MODE.TimeUS(subflights(i)+1)/1e6-2*dt_ext; + else % use end time of TimeUS message in case of the last subflight + start_time = logs(fileIndices(i)).MODE.TimeUS(subflights(i))/1e6; + end_time = logs(fileIndices(i)).RATE.TimeUS(end)/1e6; + end + log = log.getSlice( [start_time-dt_ext end_time+dt_ext], 'TimeS'); + + % Check if flight mode of log corresponds to defined mode in config + if modes(i) ~= log.MODE.Mode + error_msg = ['Defined Mode (' num2str(modes(i)) ') in ' ... + 'mode_list with index ' num2str(i) ' does not correspond '... + 'to mode of log (' num2str(log.MODE.Mode) ')!']; + error(error_msg); + end + + % preserve some messages that are outside of the slice time interval + log.FMT = logs(fileIndices(i)).FMT; + log.UNIT = logs(fileIndices(i)).UNIT; + log.FMTU = logs(fileIndices(i)).FMTU; + log.MULT = logs(fileIndices(i)).MULT; + log.PARM = logs(fileIndices(i)).PARM; + % Update the number of actual included messages + log.numMsgs = 0; + for msg = log.msgsContained + msgName = char(msg); + % Check if message has been sliced off log + if ~isvalid(log.(msgName)) + warning(['Message ' msg{1} ' in log ' ... + num2str(i) ' was sliced off message!']); + else + log.numMsgs = log.numMsgs + length(log.(msgName).LineNo); + end + end + + % Get axis from flight. Set to 0 if sysid mode is not active. + axis = get_axis(log); + axis = axis(1); + % Add new axis. + axisList(i) = axis; + + % Resample log and save it to sid array + sidLogs(numOldSubflights + i).data = resampleLog(log, true, 'linear'); +end + +% Save identification data in IdData objects +% Index to save IO data of SID runs +j = 1; +for i=1:length(sidLogs)-numOldSubflights + if sidLogs(numOldSubflights + i).data.MODE.Mode == 25 + % Let user insert minimum and maximum frequencies for spectral + % analysis + disp('Insert minimum and maximum frequency for spectral analysis (enter no value to choose sweep values):') + fminSweep = sidLogs(numOldSubflights + i).data.SIDS.FSt; + fmaxSweep = sidLogs(numOldSubflights + i).data.SIDS.FSp; + fmin = input(['Minimum frequency (sweep = ' num2str(fminSweep) '): fmin = ']); + fmax = input(['Maximum frequency (sweep = ' num2str(fmaxSweep) '): fmax = ']); + if isempty(fmin) fmin = fminSweep; end + if isempty(fmax) fmax = fmaxSweep; end + idData(numOldSysidflights + j) = IdData(sidLogs(numOldSubflights + i).data, subflights(i), i, fmin, fmax); + + % Increment IO data index for later saving + j = j+1; + end +end + +% Print modes and/or tested sid axis in log array +fprintf('\nChosen test flights:\n') +fprintf('Dataset\t|File\t|Subflight\t|Mode\t|Axis\t|Id Quality\n') +for i=1:length(sidLogs)-numOldSubflights + if (isfield(sidLogs(numOldSubflights + i).data, 'SIDS')) + % Find correct idData object for data quality + idDataObj = findobj(idData, '-function', ... + @(obj) strcmp(obj.fileName, fileNames{fileIndices(i)}) && obj.dataIndex == i); + % When identical objects are contained in idData vector, use latest + idDataObj = idDataObj(end); + fprintf('sid(%d)\t|%d\t\t|%d\t\t\t|%d\t\t|%d\t\t|%.2f\t\n', int16(i+numOldSubflights), ... + fileIndices(i), subflights(i), sidLogs(numOldSubflights + i).data.MODE.Mode(1), ... + sidLogs(numOldSubflights + i).data.SIDS.Ax, idDataObj.dataQuality); + else + fprintf('sid(%d)\t|%d\t\t|%d\t\t\t|%d\t\t|-\t\t|-\n', int16(i+numOldSubflights), ... + fileIndices(i), subflights(i), sidLogs(numOldSubflights + i).data.MODE.Mode(1)); + end +end + +% Save configuration of loaded data to struct and to repo +if numOldSubflights == 0 + % No configuration in workspace yet + loadedDataConfig.fileNames = fileNames; + loadedDataConfig.fileIndices = fileIndices; + loadedDataConfig.subflights = subflights; + loadedDataConfig.modes = modes; + loadedDataConfig.modesConfig = modesConfig; + loadedDataConfig.axisList = axisList; +else + % Add new configuration to existing configuration array + for i=1:length(fileNames) + loadedDataConfig.fileNames{end+1} = fileNames{i}; + end + for i=1:length(fileIndices) + % File indices must be adjusted to index of file in existing config + loadedDataConfig.fileIndices(numOldSubflights+i) = length(loadedDataConfig.fileNames); + loadedDataConfig.subflights(numOldSubflights+i) = subflights(i); + loadedDataConfig.modes(numOldSubflights+i) = modes(i); + loadedDataConfig.modesConfig(numOldSubflights+i) = modesConfig(i); + loadedDataConfig.axisList(numOldSubflights+i) = axisList(i); + end +end +loadedDataConfigFile = [flightDataPath 'dataLoadConfig.mat']; +save(loadedDataConfigFile, 'loadedDataConfig'); + +% Save new flightdata to repo +newDataFile = 'sid.mat'; +newDataFile = [flightDataPath newDataFile]; +if exist(newDataFile, 'file') + [filename, path] = uiputfile({'*.mat','Mat file (*.mat)';'*.*','All files (*.*)'}, 'Save File Name', ... + newDataFile); + % Set user-specified file name + newDataFile = [flightDataPath filename]; +end +if newDataFile ~= 0 + if exist('idData','var') + save(newDataFile, 'sidLogs', 'idData', 'loadedDataConfig'); + else + save(newDataFile, 'sidLogs', 'loadedDataConfig'); + end +end + +clear msg msgName filename path in_dat out_dat len idd delta_T k +clear start_time end_time sid idDataObj minNumElem +clear newDataFile logPathName numOldSubflights numOldSysidflights +clear fmin fminSweep fmax fmaxSweep addData logs + +clear i j dt_ext log_filenames axis axisList files chooseSubflights +clear numSubflights storedFile logFilterMsgs fileNames fileIndices subflights +clear dataLoadConfigFile dataStored loadedDataConfigFile modes modesConfig + +% Interact with user to continue +uiwait(msgbox(['Data loaded. Press ok to close figures and continue.'],'Data loaded','none','nonmodal')); +close all +%% Functions +% Function to read tested axis from log +function axis = get_axis(obj) + if isprop(obj, 'SIDS') + axis = obj.SIDS.Ax; + else + % Set to zero if sysid mode is not active + axis = 0; + end +end \ No newline at end of file diff --git a/Tools/simulink/arducopter/sid_sim_init.m b/Tools/simulink/arducopter/sid_sim_init.m new file mode 100644 index 00000000000..320e698451c --- /dev/null +++ b/Tools/simulink/arducopter/sid_sim_init.m @@ -0,0 +1,911 @@ +% Initialization of the Simulink model. The script loads all important +% signals and parameter to the workspace. +% +% Fabian Bredemeier - IAV GmbH +% License: GPL v3 +%% Define log index and start + stop time +if ~exist('log_idx', 'var') + log_idx = 2; +end +tStart = 0; +tEnd = inf; + +%% Setting simInMode +% 0 = Model validation - Identified models are used and full control loop +% is active +% 1 = Rate Controller validation - No models used, measured input signals +% of rate controller are used +% 2 = Attitude Controller validation - No models used, measured input +% signals of attitude controller are used +% 3 = Altitude Controller validation - No models used, measured input +% signals of attitude controller are used +% 4 = Optimization of controller - Not implemented yet +if ~exist('simInMode', 'var') + simInMode = 3; +end + +%% Check for existance of data + +% Check if sid data is existing +if exist('sidLogs', 'var') % in Workspace + disp('.mat file already loaded. Reading parameter and signals...'); +elseif exist('sid.mat', 'file') % in a .mat file with all other axis tests + load('sid.mat'); + disp('Loaded data from sid.mat'); +elseif ~exist(loadedDataConfig) + error('Could not find configuration struct. Aborting script.') +else + error('Could not find data. Aborting script.') +end + +%% Config and variable declaration + +% Sample rate of simInulation +Fs = 400; +dt = 0.0025; +simIn.param.dt = 0.0025; + +% Load data +sid = sidLogs(log_idx).data; +% Check if relevant messages are defined +if (numel(sid) == 0) + error('Ardupilog object sid is empty. Aborting.'); +end + +% Get mode of current test run +mode = loadedDataConfig.modes(log_idx); +% Get manual throttle flag for current test run +thr_man = loadedDataConfig.modesConfig(log_idx).thr_man; +% Get filter messages of current test run +msgs = loadedDataConfig.modesConfig(log_idx).filter_msgs; +% Set axis +axis = loadedDataConfig.axisList(log_idx); +% Check if config parameters are complete +if (isempty(mode) || isempty(thr_man) || isempty(msgs)) + error('Config variables (mode, thr_man, msgs) not complete. Aborting.'); +end + +% Define validation and optimization flag of simInulation +simIn.param.mdlVal = simInMode == 0; +simIn.param.rateCtrlVal = simInMode == 1; +simIn.param.attCtrlVal = simInMode == 2 || simInMode == 3; +simIn.param.altCtrlVal = simInMode == 3 || mode == 2; +simIn.param.optCtrl = simInMode == 4; + +%% General Copter settings +simIn.param.LOOP_RATE = getParamVal(sid, 'SCHED_LOOP_RATE'); +simIn.param.dt = round(double(1 / simIn.param.LOOP_RATE), 4); % Sample time resulting from loop rate. Round to four decimal digits +simIn.param.FRAME_CLASS = getParamVal(sid, 'FRAME_CLASS'); +simIn.param.FRAME_TYPE = getParamVal(sid, 'FRAME_TYPE'); +[simIn.param.NUM_MOTORS, simIn.param.AXIS_FAC_MOTORS] = getMotorMixerFactors(simIn.param.FRAME_CLASS, simIn.param.FRAME_TYPE); +simIn.param.EKF_TYPE = getParamVal(sid, 'AHRS_EKF_TYPE'); +simIn.param.GRAVITY_MSS = single(9.80665); +simIn.param.dt_THR_LOOP = 1 / 50; % Sample time of throttle loop in Copter.cpp. Defined in Copter.cpp, line 94 +simIn.param.ANGLE_MAX = getParamVal(sid, 'ANGLE_MAX'); % Maximum lean angle in all flight modes +simIn.param.PILOT_Y_EXPO = getParamVal(sid, 'PILOT_Y_EXPO'); % Acro yaw expo to allow faster rotation when stick at edges +simIn.param.PILOT_Y_RATE = getParamVal(sid, 'PILOT_Y_RATE'); +simIn.param.PILOT_Y_RATE_TC = getParamVal(sid, 'PILOT_Y_RATE_TC'); % Pilot yaw rate control input time constant + +% Abort script if frame configuration is not defined yet +if (isempty(simIn.param.AXIS_FAC_MOTORS) || simIn.param.NUM_MOTORS == 0) + error("Body configuration of copter is not defined yet!"); +end + +%% Simulation duration +% Define end time of simInulation +if simIn.param.mdlVal || simIn.param.rateCtrlVal || simIn.param.attCtrlVal || simIn.param.altCtrlVal + if isinf(tEnd) % Run full data + simIn.param.timeEnd = sid.RATE.TimeS(end); + else % Only run part of data + duration = tEnd-tStart; + iEnd = int16(duration/dt); + simIn.param.timeEnd = sid.RATE.TimeS(iEnd); + clear duration iEnd + end +elseif simIn.param.optCtrl + simIn.param.timeEnd = OPT.tEndOpt; +end + +%% Inertial Sensor +simIn.param.INS.GYRO_FILTER = getParamVal(sid, 'INS_GYRO_FILTER'); % Filter cutoff frequency for gyro lowpass filter +simIn.param.INS.GYRO_RATE = 400; % Gyro sampling rate. Actually define by INS_GYRO_RATE, but simInulation is run with 400 Hz + +%% AHRS +trim_x = getParamVal(sid, 'AHRS_TRIM_X'); +trim_y = getParamVal(sid, 'AHRS_TRIM_Y'); +simIn.param.AHRS.FC2BF = single(dcmFromEuler(trim_x, trim_y, 0)); % Rotation matrix from FC to Body Frame based on AP_AHRS constructor +simIn.param.AHRS.BF2FC = simIn.param.AHRS.FC2BF'; + +clear trim_x trim_y +%% RCIN - Radio Input and parameters for Attitude Control +rollCh = getParamVal(sid, 'RCMAP_ROLL'); +pitchCh = getParamVal(sid, 'RCMAP_PITCH'); +yawCh = getParamVal(sid, 'RCMAP_YAW'); +thrCh = getParamVal(sid, 'RCMAP_THROTTLE'); + +simIn.param.RCIN.DZ_RLL = getParamVal(sid, ['RC' num2str(rollCh) '_DZ']); +simIn.param.RCIN.MIN_RLL = getParamVal(sid, ['RC' num2str(rollCh) '_MIN']); +simIn.param.RCIN.MAX_RLL = getParamVal(sid, ['RC' num2str(rollCh) '_MAX']); +simIn.param.RCIN.TRIM_RLL = getParamVal(sid, ['RC' num2str(rollCh) '_TRIM']); +simIn.param.RCIN.REVERSED_RLL = getParamVal(sid, ['RC' num2str(rollCh) '_REVERSED']); +simIn.param.RCIN.DZ_PIT = getParamVal(sid, ['RC' num2str(pitchCh) '_DZ']); +simIn.param.RCIN.MIN_PIT = getParamVal(sid, ['RC' num2str(pitchCh) '_MIN']); +simIn.param.RCIN.MAX_PIT = getParamVal(sid, ['RC' num2str(pitchCh) '_MAX']); +simIn.param.RCIN.TRIM_PIT = getParamVal(sid, ['RC' num2str(pitchCh) '_TRIM']); +simIn.param.RCIN.REVERSED_PIT = getParamVal(sid, ['RC' num2str(pitchCh) '_REVERSED']); +simIn.param.RCIN.DZ_YAW = getParamVal(sid, ['RC' num2str(yawCh) '_DZ']); +simIn.param.RCIN.MIN_YAW = getParamVal(sid, ['RC' num2str(yawCh) '_MIN']); +simIn.param.RCIN.MAX_YAW = getParamVal(sid, ['RC' num2str(yawCh) '_MAX']); +simIn.param.RCIN.TRIM_YAW = getParamVal(sid, ['RC' num2str(yawCh) '_TRIM']); +simIn.param.RCIN.REVERSED_YAW = getParamVal(sid, ['RC' num2str(yawCh) '_REVERSED']); +simIn.param.RCIN.DZ_THR = getParamVal(sid, ['RC' num2str(thrCh) '_DZ']); +simIn.param.RCIN.MIN_THR = getParamVal(sid, ['RC' num2str(thrCh) '_MIN']); +simIn.param.RCIN.MAX_THR = getParamVal(sid, ['RC' num2str(thrCh) '_MAX']); +simIn.param.RCIN.TRIM_THR = getParamVal(sid, ['RC' num2str(thrCh) '_TRIM']); +simIn.param.RCIN.REVERSED_THR = getParamVal(sid, ['RC' num2str(thrCh) '_REVERSED']); + +simIn.param.RCIN.ROLL_PITCH_YAW_INPUT_MAX = 4500; % Yaw, roll, pitch input range, defined in config.h + +% Check if RCIN log is available +if simIn.param.mdlVal || simIn.param.attCtrlVal || simIn.param.altCtrlVal + if isfield(sid, 'RCIN') + iVec = (sid.RCIN.TimeS >= tStart & sid.RCIN.TimeS <= tEnd); + simIn.signals.RCIN.Time = single(sid.RCIN.TimeS(iVec)-tStart); + simIn.signals.RCIN.RollInput = eval(['single(sid.RCIN.C' num2str(rollCh) '(iVec))']); + simIn.signals.RCIN.PitchInput = eval(['single(sid.RCIN.C' num2str(pitchCh) '(iVec))']); + simIn.signals.RCIN.YawInput = eval(['single(sid.RCIN.C' num2str(yawCh) '(iVec))']); + simIn.signals.RCIN.ThrottleInput = eval(['single(sid.RCIN.C' num2str(thrCh) '(iVec))']); + else + if ~isfield(sid, 'RCIN') && axis == 13 + warning(['RCIN message cannot be found in log ' num2str(log_idx) '! Validating vertical motion model.']); + else + warning(['RCIN message cannot be found in log ' num2str(log_idx) '! Ommiting attitude controller and models in simInulation. Only rate controller is validated']); + simIn.param.rateCtrlVal = 1; + simIn.param.mdlVal = 0; + end + % Set RCIN signals to zero + simIn.signals.RCIN.Time = single(0:0.1:simIn.param.timeEnd); + simIn.signals.RCIN.RollInput = single(zeros(length(simIn.signals.RCIN.Time),1)); + simIn.signals.RCIN.PitchInput = single(zeros(length(simIn.signals.RCIN.Time),1)); + simIn.signals.RCIN.YawInput = single(zeros(length(simIn.signals.RCIN.Time),1)); + simIn.signals.RCIN.ThrottleInput = single(zeros(length(simIn.signals.RCIN.Time),1)); + end +end + +%% Attitude +% Yaw Angle signals are a modulo of 360°, so this operation has to be +% inverted +iVec = (sid.ATT.TimeS >= tStart & sid.ATT.TimeS <= tEnd); +simIn.signals.ATT.Time = single(sid.ATT.TimeS(iVec)-tStart); +simIn.signals.ATT.Roll = single(sid.ATT.Roll(iVec)); +simIn.signals.ATT.Pitch = single(sid.ATT.Pitch(iVec)); +simIn.signals.ATT.Yaw = single(demodYawAngle(sid.ATT.Yaw(iVec))); +simIn.signals.ATT.DesRoll = single(sid.ATT.DesRoll(iVec)); +simIn.signals.ATT.DesPitch = single(sid.ATT.DesPitch(iVec)); +simIn.signals.ATT.DesYaw = single(demodYawAngle(sid.ATT.DesYaw(iVec))); + +% The actual yaw angle is calculated from the DCM with +% Matrix3::to_euler() with the four-quadrant arcus tangens atan2(), for +% example in AP_AHRS_View::update(), so the controller can only handle +% values in the range [-pi, pi]. +simIn.signals.ATT.Yaw = simIn.signals.ATT.Yaw - 360 * (simIn.signals.ATT.Yaw > 180); +simIn.signals.ATT.DesYaw = simIn.signals.ATT.DesYaw - 360 * (simIn.signals.ATT.DesYaw > 180); + +% Initial DCM matrix based on initial Euler angles +% Calculation based on Matrix3::from_euler() +for i=1:length(iVec) + if iVec(i) == 1 + iInit = i; + break; + end +end +rollAngInit = single(sid.ATT.Roll(iInit))*pi/180; +pitchAngInit = single(sid.ATT.Pitch(iInit))*pi/180; +yawAngInit = single(simIn.signals.ATT.Yaw(1))*pi/180; +simIn.init.ATT.Roll = rollAngInit; +simIn.init.ATT.Pitch = pitchAngInit; +simIn.init.ATT.Yaw = yawAngInit; +simIn.init.ATT.DCM = dcmFromEuler(rollAngInit, pitchAngInit, yawAngInit); + +% Initialize attitudeTarget according to +% AC_AttitudeControl::reset_yaw_target_and_rate(), which is called in +% ModeStabilize::run() when copter is landed +attitudeTargetUpdate = fromAxisAngle([0;0;yawAngInit]); +simIn.init.ATT.attitudeTarget = quatMult(attitudeTargetUpdate, [1;0;0;0]); +simIn.init.ATT.eulerRateTar = [0;0;0]; + +% Test signals in SITL +% Attitude Controller Targets +% simIn.signals.ATT.attTarMeasW = single(sid.ATAR.attW); +% simIn.signals.ATT.attTarMeasX = single(sid.ATAR.attX); +% simIn.signals.ATT.attTarMeasY = single(sid.ATAR.attY); +% simIn.signals.ATT.attTarMeasZ = single(sid.ATAR.attZ); +% simIn.signals.ATT.eulerAngTarMeasX = single(sid.ATAR.angX); +% simIn.signals.ATT.eulerAngTarMeasY = single(sid.ATAR.angY); +% simIn.signals.ATT.eulerAngTarMeasZ = single(sid.ATAR.angZ); +% simIn.signals.ATT.eulerRatTarMeasX = single(sid.ATAR.ratX); +% simIn.signals.ATT.eulerRatTarMeasY = single(sid.ATAR.ratY); +% simIn.signals.ATT.eulerRatTarMeasZ = single(sid.ATAR.ratZ); +% +% simIn.signals.ATT.CtrlRollIn = single(sid.CTIN.rllCtrl); +% simIn.signals.ATT.CtrlPitchIn = single(sid.CTIN.pitCtrl); +% simIn.signals.ATT.CtrlYawIn = single(sid.CTIN.yawCtrl); +% simIn.signals.ATT.yawRateDesMeas = single(sid.ATIN.yawDes); + +clear rollAngInit pitchAngInit yawAngInit attitudeTargetUpdate iInit + +%% Attitude Controller General +simIn.param.ATC.RATE_FF_ENAB = getParamVal(sid, 'ATC_RATE_FF_ENAB'); +simIn.param.ATC.INPUT_TC = getParamVal(sid, 'ATC_INPUT_TC'); % Attitude control input time constant +% Roll Angle Controller +simIn.param.ATC.ANG_RLL_P = getParamVal(sid, 'ATC_ANG_RLL_P'); +simIn.param.ATC.ACCEL_R_MAX = getParamVal(sid, 'ATC_ACCEL_R_MAX'); +simIn.param.ATC.RATE_R_MAX = getParamVal(sid, 'ATC_RATE_R_MAX'); +simIn.param.ATC.ACCEL_RP_CONTROLLER_MIN_RADSS = 40*pi/180; % Maximum body-frame acceleration limit for the stability controller, defined in AC_AttitudeControl.h +simIn.param.ATC.ACCEL_RP_CONTROLLER_MAX_RADSS = 720*pi/180; +% Pitch Angle Controller +simIn.param.ATC.ANG_PIT_P = getParamVal(sid, 'ATC_ANG_PIT_P'); +simIn.param.ATC.ACCEL_P_MAX = getParamVal(sid, 'ATC_ACCEL_P_MAX'); +simIn.param.ATC.RATE_P_MAX = getParamVal(sid, 'ATC_RATE_P_MAX'); +% Yaw Angle Controller +simIn.param.ATC.ANG_YAW_P = getParamVal(sid, 'ATC_ANG_YAW_P'); +simIn.param.ATC.ACCEL_Y_MAX = getParamVal(sid, 'ATC_ACCEL_Y_MAX'); +simIn.param.ATC.RATE_Y_MAX = getParamVal(sid, 'ATC_RATE_Y_MAX'); +simIn.param.ATC.ACCEL_Y_CONTROLLER_MAX_RADSS = single(120*pi/180); % Maximum body-frame acceleration limit for the stability controller, defined in AC_AttitudeControl.h +simIn.param.ATC.ACCEL_Y_CONTROLLER_MIN_RADSS = single(10*pi/180); +simIn.param.ATC.THRUST_ERROR_ANGLE = single(30*pi/180); % Thrust angle error above which yaw corrections are limited. Defined in AC_AttitudeControl.h + +% Thrust and throttle calculation parameters +simIn.param.MODE.THR_MAN_FLG = thr_man; % Flag for manual throttle, which depends on the current mode. +if thr_man + simIn.param.ATC.THR_FILT_CUTOFF = getParamVal(sid, 'PILOT_THR_FILT'); % Cutoff frequency of throttle filter for modes with manual throttle. parameter is given to function call of AC_AttitudeControl_Multi::set_throttle_out(). +else + simIn.param.ATC.THR_FILT_CUTOFF = 2.0; % Cutoff frequency of throttle filter for modes with z position control (Defined in AC_PosControl.h, line 33) +end +simIn.param.ATC.ANGLE_BOOST = getParamVal(sid, 'ATC_ANGLE_BOOST'); % Enabling of angle boost to increase output throttle. Used in AC_AttitudeConrtol_Multi::get_throttle_boosted() +simIn.param.ATC.THR_MIX_MAN = getParamVal(sid, 'ATC_THR_MIX_MAN'); % Throttle vs. attitude priorisation during manual flight +simIn.param.ATC.THR_MIX_MIN = getParamVal(sid, 'ATC_THR_MIX_MIN'); % Throttle vs. attitude priorisation used when landing +simIn.param.ATC.THR_MIX_MAX = getParamVal(sid, 'ATC_THR_MIX_MAX'); % Throttle vs. attitude priorisation during active flights +simIn.param.ATC.THR_MIX_DFLT = single(0.5); % Default value for the priorization of throttle use between attitude control and throttle demand by pilot (or autopilot). Defined in AC_AttitudeControl.h, line 44 +if thr_man + simIn.init.ATC.THR_MIX = simIn.param.ATC.THR_MIX_MAN; +else + simIn.init.ATC.THR_MIX = simIn.param.ATC.THR_MIX_DFLT; +end +simIn.param.MOT.HOVER_LEARN = getParamVal(sid, 'MOT_HOVER_LEARN'); % Enable/Disable automatic learning of hover throttle (0=Disabled, 1=Learn, 2=Learn and Save +simIn.param.MOT.THST_HOVER = getParamVal(sid, 'MOT_THST_HOVER'); % Motor thrust needed to hover. Default value of _throttle_hover. +simIn.param.MOT.THST_HOVER = simIn.param.MOT.THST_HOVER(1); % Assign first value of array to default value which is the correct value in the case, that the parameter is defined twice in the param file. +simIn.param.MOT.THST_HOVER_TC = single(10.0); % Time constant used to update estimated hover throttle, found as AP_MOTORS_THST_HOVER_TC in AP_MotorsMulticopter.h +simIn.param.MOT.THST_HOVER_MIN = single(0.125); % Minimum possible hover throttle, found as AP_MOTORS_THST_HOVER_MIN in AP_MotorsMulticopter.h +simIn.param.MOT.THST_HOVER_MAX = single(0.6875); % Maximum possible hover throttle, found as AP_MOTORS_THST_HOVER_MAX in AP_MotorsMulticopter.h +simIn.param.MOT.BAT_VOLT_MAX = getParamVal(sid, 'MOT_BAT_VOLT_MAX'); % Maximum voltage above which no additional scaling on thrust is performed +simIn.param.MOT.BAT_VOLT_MIN = getParamVal(sid, 'MOT_BAT_VOLT_MIN'); % Minimum voltage below which no additional scaling on thrust is performed +simIn.param.MOT.BAT_CURR_MAX = getParamVal(sid, 'MOT_BAT_CURR_MAX'); % Maximum current over which maximum throttle is limited (and no further scaling is performed) +simIn.param.MOT.THST_EXPO = getParamVal(sid, 'MOT_THST_EXPO'); % Motor thrust curve exponent (0.0 for linear to 1.0 for second order curve) +simIn.param.MOT.BAT_CURR_TC = getParamVal(sid, 'MOT_BAT_CURR_TC'); % Time constant used to limit the maximum current +simIn.param.MOT.YAW_HEADROOM = getParamVal(sid, 'MOT_YAW_HEADROOM'); % Yaw control is goven at least this PWM in microseconds range + +% Throttle inputs +iVec = (sid.CTUN.TimeS >= tStart & sid.CTUN.TimeS <= tEnd); +simIn.signals.CTUN.Time = single(sid.CTUN.TimeS(iVec)--tStart); +simIn.signals.CTUN.ThrIn = single(sid.CTUN.ThI(iVec)); % Throttle In, pilots input to Attitude Control (attitude_control->get_throttle_in()) +simIn.signals.CTUN.ThrOut = single(sid.CTUN.ThO(iVec)); % Throttle Out, throttle given to motor mixer after filtering (motors->get_throttle()) +simIn.signals.CTUN.AngBst = single(sid.CTUN.ABst(iVec)); % Extra amount of throttle, added to throttle_in in AC_AttitudeControl_Multi::get_throttle_boosted() +simIn.signals.CTUN.ThrHov = single(sid.CTUN.ThH(iVec)); % Estimated throttle required to hover throttle in range 0-1 (AP_MotorsMulticopter::get_throttle_hover()) + +% Throttle inital values +if simIn.param.rateCtrlVal || simIn.param.attCtrlVal || simIn.param.mdlVal || simIn.param.altCtrlVal + simIn.init.CTUN.ThrOut = single(sid.CTUN.ThO(1)); + simIn.init.CTUN.ThrHov = single(sid.CTUN.ThH(1)); +else + simIn.init.CTUN.ThrOut = single(0); + simIn.init.CTUN.ThrHov = single(simIn.param.MOT.THST_HOVER); +end + +% Altitude signals +simIn.signals.CTUN.DSAlt = single(sid.CTUN.DSAlt(iVec)); % Desired rangefinder altitude +simIn.signals.CTUN.DAlt = single(sid.CTUN.DAlt(iVec)); % Desired altitude +simIn.signals.CTUN.Alt = single(sid.CTUN.Alt(iVec)); % Achieved altitude (inav) +simIn.signals.CTUN.SAlt = single(sid.CTUN.SAlt(iVec)); % Achieved rangefinder altitude +simIn.signals.CTUN.TAlt = single(sid.CTUN.TAlt(iVec)); % Terrain altitude +simIn.signals.CTUN.BAlt = single(sid.CTUN.BAlt(iVec)); % Barometric altitude +simIn.signals.CTUN.CRt = single(sid.CTUN.CRt(iVec)); % Climb rate inav +simIn.signals.CTUN.DCRt = single(sid.CTUN.DCRt(iVec)); % Desired climb rate + +% Altitude inital values +simIn.init.CTUN.Alt = single(sid.CTUN.Alt(1)); +simIn.init.CTUN.CRt = single(sid.CTUN.CRt(1)*0.01); + +% Intermediate throttle calculation quantities - only read if message +% exists +if isfield(sid, 'MOTQ') + iVec = (sid.MOTQ.TimeS >= tStart & sid.MOTQ.TimeS <= tEnd); + simIn.signals.MOTQ.Time = single(sid.MOTQ.TimeS(iVec)-tStart); + simIn.signals.MOTQ.ThrAvgMax = single(sid.MOTQ.ThAvgMax(iVec)); + simIn.signals.MOTQ.ThrThstMaxMeas = single(sid.MOTQ.ThThstMax(iVec)); + simIn.signals.MOTQ.CompGain = single(sid.MOTQ.CompGain(iVec)); + simIn.signals.MOTQ.AirDensityRatio = single(sid.MOTQ.AirDensRat(iVec)); + simIn.signals.MOTQ.ThrMixOut = single(sid.MOTQ.ThrOut(iVec)); +else + iVec = (sid.CTUN.TimeS >= tStart & sid.CTUN.TimeS <= tEnd); + simIn.signals.MOTQ.Time = single(sid.CTUN.TimeS(iVec)-tStart); + simIn.signals.MOTQ.ThrAvgMax = single(zeros(length(simIn.signals.MOTQ.Time),1)); + simIn.signals.MOTQ.ThrThstMaxMeas = single(zeros(length(simIn.signals.MOTQ.Time),1)); + simIn.signals.MOTQ.CompGain = single(zeros(length(simIn.signals.MOTQ.Time),1)); + simIn.signals.MOTQ.AirDensityRatio = single(zeros(length(simIn.signals.MOTQ.Time),1)); + simIn.signals.MOTQ.ThrMixOut = single(zeros(length(simIn.signals.MOTQ.Time),1)); +end + + +% Battery inputs +iVec = (sid.BAT.TimeS >= tStart & sid.BAT.TimeS <= tEnd); +simIn.signals.BAT.Time = single(sid.BAT.TimeS(iVec)-tStart); +simIn.signals.BAT.RestVoltEst = single(sid.BAT.VoltR(iVec)); % Estimated resting voltage of the battery +simIn.signals.BAT.Curr = single(sid.BAT.Curr(iVec)); % Measured battery current +simIn.signals.BAT.Res = single(sid.BAT.Res(iVec)); % Estimated battery resistance +simIn.signals.BAT.Volt = single(sid.BAT.Volt(iVec)); % Measured voltage resistance + +% Battery inital values +if simIn.param.rateCtrlVal || simIn.param.attCtrlVal || simIn.param.mdlVal || simIn.param.altCtrlVal + simIn.init.BAT.RestVoltEst = single(sid.BAT.VoltR(1)); +else + simIn.init.BAT.RestVoltEst = single(0); +end + +% Baro inputs +iVec = (sid.BARO.TimeS >= tStart & sid.BARO.TimeS <= tEnd); +simIn.signals.BARO.Time = single(sid.BARO.TimeS(iVec)-tStart); +simIn.signals.BARO.Alt = single(sid.BARO.Alt(iVec)); % Calculated altitude by the barometer +simIn.signals.BARO.AirPress = single(sid.BARO.Press(iVec)); % Measured atmospheric pressure by the barometer +simIn.signals.BARO.GndTemp = single(sid.BARO.GndTemp(iVec)); % Temperature on ground, specified by parameter or measured while on ground + +% Attitude controller outputs +iVec = (sid.MOTB.TimeS >= tStart & sid.MOTB.TimeS <= tEnd); +simIn.signals.MOTB.Time = single(sid.MOTB.TimeS(iVec)-tStart); +simIn.signals.MOTB.LiftMax = single(sid.MOTB.LiftMax(iVec)); % Maximum motor compensation gain, calculated in AP_MotorsMulticopter::update_lift_max_from_batt_voltage() +simIn.signals.MOTB.ThrLimit = single(sid.MOTB.ThLimit(iVec)); % Throttle limit set due to battery current limitations, calculated in AP_MotorsMulticopter::get_current_limit_max_throttle() +simIn.signals.MOTB.ThrAvMx = single(sid.MOTB.ThrAvMx(iVec)); % Throttle average max + +% SID Inputs +% Create array for sid signals, each element containing the signal struct +if (mode == 25) + iVec = (sid.SIDD.TimeS >= tStart & sid.SIDD.TimeS <= tEnd); + for i=1:13 + simIn.signals.SIDD.Time{i} = single(sid.SIDD.TimeS(iVec)-tStart); + if (i == axis) + simIn.signals.SIDD.Chirp{i} = single(sid.SIDD.Targ(iVec)); % SID test signal + else + simIn.signals.SIDD.Chirp{i} = single(zeros(length(simIn.signals.SIDD.Time{i}),1)); + end + end + simIn.signals.SIDD.AccX = single(sid.SIDD.Ax(iVec)); + simIn.signals.SIDD.AccY = single(sid.SIDD.Ay(iVec)); + simIn.signals.SIDD.AccZ = single(sid.SIDD.Az(iVec)); + simIn.signals.SIDD.GyrX = single(sid.SIDD.Gx(iVec)); + simIn.signals.SIDD.GyrY = single(sid.SIDD.Gy(iVec)); + simIn.signals.SIDD.GyrZ = single(sid.SIDD.Gz(iVec)); +else + iVec = (sid.RATE.TimeS >= tStart & sid.RATE.TimeS <= tEnd); + for i=1:13 + simIn.signals.SIDD.Time{i} = single(sid.RATE.TimeS(iVec)-tStart); + simIn.signals.SIDD.Chirp{i} = single(zeros(length(simIn.signals.SIDD.Time{i}),1)); + end + simIn.signals.SIDD.AccX = single(zeros(length(simIn.signals.SIDD.Time{1}),1)); + simIn.signals.SIDD.AccY = single(zeros(length(simIn.signals.SIDD.Time{1}),1)); + simIn.signals.SIDD.AccZ = single(zeros(length(simIn.signals.SIDD.Time{1}),1)); + simIn.signals.SIDD.GyrX = single(zeros(length(simIn.signals.SIDD.Time{1}),1)); + simIn.signals.SIDD.GyrY = single(zeros(length(simIn.signals.SIDD.Time{1}),1)); + simIn.signals.SIDD.GyrZ = single(zeros(length(simIn.signals.SIDD.Time{1}),1)); +end + +%% Roll Rate Controller +iVec = (sid.PIDR.TimeS >= tStart & sid.PIDR.TimeS <= tEnd); +simIn.signals.PIDR.Time = single(sid.PIDR.TimeS(iVec)-tStart); +% Inputs +simIn.signals.PIDR.Tar = single(sid.PIDR.Tar(iVec)); % target values filtered +simIn.signals.PIDR.Act = single(sid.PIDR.Act(iVec)); % actual values +simIn.signals.PIDR.Err = single(sid.PIDR.Err(iVec)); % error values +if simIn.param.rateCtrlVal || simIn.param.attCtrlVal || simIn.param.mdlVal + % Clock of Slew Limiter in ms + % Use tracked logging time of PID message in validation modes + simIn.signals.PIDR.ClockDMod = single(1000*simIn.signals.PIDR.Time); +else + simIn.signals.PIDR.ClockDMod = single(1000 * simIn.param.dt * (0:length(simIn.signals.PIDR.Time)-1)'); +end + +% Outputs +simIn.signals.PIDR.FF = single(sid.PIDR.FF(iVec)); +simIn.signals.PIDR.P = single(sid.PIDR.P(iVec)); +simIn.signals.PIDR.I = single(sid.PIDR.I(iVec)); +simIn.signals.PIDR.D = single(sid.PIDR.D(iVec)); +simIn.signals.PIDR.DMod = single(sid.PIDR.Dmod(iVec)); +simIn.signals.PIDR.ILimit = single(sid.PIDR.Limit(iVec)); +simIn.signals.PIDR.SRate = single(sid.PIDR.SRate(iVec)); % Output slew rate of the slew limiter, stored in _output_slew_rate in AC_PID.cpp, line 161 + +% parameters - Read from PARM.Value cell array with logical indexing +simIn.param.PIDR.TC = getParamVal(sid, 'ATC_INPUT_TC'); +simIn.param.PIDR.FLTT_f = getParamVal(sid, 'ATC_RAT_RLL_FLTT'); +simIn.param.PIDR.FLTE_f = getParamVal(sid, 'ATC_RAT_RLL_FLTE'); +simIn.param.PIDR.FLTD_f = getParamVal(sid, 'ATC_RAT_RLL_FLTD'); +simIn.param.PIDR.P = getParamVal(sid, 'ATC_RAT_RLL_P'); +simIn.param.PIDR.I = getParamVal(sid, 'ATC_RAT_RLL_I'); +simIn.param.PIDR.D = getParamVal(sid, 'ATC_RAT_RLL_D'); +simIn.param.PIDR.IMAX = getParamVal(sid, 'ATC_RAT_RLL_IMAX'); +simIn.param.PIDR.FF = getParamVal(sid, 'ATC_RAT_RLL_FF'); %0.05; +simIn.param.PIDR.SR_MAX = getParamVal(sid, 'ATC_RAT_RLL_SMAX'); %5.0; +simIn.param.PIDR.SR_TAU = single(1.0); % Slew Rate Tau - not yet available as a parameter of the copter. Set to 1.0 by default (AC_PID.h, line 24). +simIn.param.PIDR.SR_FLT_f = single(25.0); % Slew Rate lowpass filter cutoff frequency. Defined in SlewLimiter.h, line 14. + +% Inital inputs +if simIn.param.rateCtrlVal || simIn.param.attCtrlVal || simIn.param.mdlVal + simIn.init.PIDR.P = single(sid.PIDR.P(1)); + simIn.init.PIDR.I = single(sid.PIDR.I(1)); + simIn.init.PIDR.D = single(sid.PIDR.D(1)); + simIn.init.PIDR.Tar = single(sid.RATE.RDes(1)*pi/180); % Convert to radian due to conversion to degree for logging (AP_AHRS_View::Write_Rate) + simIn.init.PIDR.TarFilt = single(sid.PIDR.Tar(1)); + simIn.init.PIDR.ErrFilt = single(sid.PIDR.Err(1)); + simIn.init.PIDR.SROut = single(sid.PIDR.SRate(1)); % Initial value of the slew rate determined by the slew limiter. Used for both modifier_slew_rate and output_slew_rate. + if (sid.PIDR.D(1) ~= 0) % Prevent division by zero + simIn.init.PIDR.DerFilt = single(sid.PIDR.D(1))/simIn.param.PIDR.D; + else + simIn.init.PIDR.DerFilt = single(0); + end +else % Set to zero if we do not want to validate model with test run + simIn.init.PIDR.P = single(0); + simIn.init.PIDR.I = single(0); + simIn.init.PIDR.D = single(0); + simIn.init.PIDR.Tar = single(0); + simIn.init.PIDR.TarFilt = single(0); + simIn.init.PIDR.ErrFilt = single(0); + simIn.init.PIDR.DerFilt = single(0); + simIn.init.PIDR.SROut = single(0); +end + +%% Pitch Rate Controller +iVec = (sid.PIDP.TimeS >= tStart & sid.PIDP.TimeS <= tEnd); +simIn.signals.PIDP.Time = single(sid.PIDP.TimeS(iVec)-tStart); +% Inputs +simIn.signals.PIDP.Tar = single(sid.PIDP.Tar(iVec)); % target values filtered +simIn.signals.PIDP.Act = single(sid.PIDP.Act(iVec)); % actual values +simIn.signals.PIDP.Err = single(sid.PIDP.Err(iVec)); % error values +if simIn.param.rateCtrlVal || simIn.param.attCtrlVal || simIn.param.mdlVal + % Clock of Slew Limiter + % Use tracked logging time of PID message in validation modes + simIn.signals.PIDP.ClockDMod = single(1000 * simIn.signals.PIDP.Time); +else + simIn.signals.PIDP.ClockDMod = single(1000 * simIn.param.dt * (0:length(simIn.signals.PIDP.Time)-1)'); +end + +% Outputs +simIn.signals.PIDP.FF = single(sid.PIDP.FF(iVec)); +simIn.signals.PIDP.P = single(sid.PIDP.P(iVec)); +simIn.signals.PIDP.I = single(sid.PIDP.I(iVec)); +simIn.signals.PIDP.D = single(sid.PIDP.D(iVec)); +simIn.signals.PIDP.DMod = single(sid.PIDP.Dmod(iVec)); +simIn.signals.PIDP.ILimit = single(sid.PIDP.Limit(iVec)); +simIn.signals.PIDP.SRate = single(sid.PIDP.SRate(iVec)); % Output slew rate of the slew limiter, stored in _output_slew_rate in AC_PID.cpp, line 161 + +% Parameters - Read from PARM.Value cell array with logical indexing +simIn.param.PIDP.TC = getParamVal(sid, 'ATC_INPUT_TC'); +simIn.param.PIDP.FLTT_f = getParamVal(sid, 'ATC_RAT_PIT_FLTT'); +simIn.param.PIDP.FLTE_f = getParamVal(sid, 'ATC_RAT_PIT_FLTE'); +simIn.param.PIDP.FLTD_f = getParamVal(sid, 'ATC_RAT_PIT_FLTD'); +simIn.param.PIDP.P = getParamVal(sid, 'ATC_RAT_PIT_P'); +simIn.param.PIDP.I = getParamVal(sid, 'ATC_RAT_PIT_I'); +simIn.param.PIDP.D = getParamVal(sid, 'ATC_RAT_PIT_D'); +simIn.param.PIDP.IMAX = getParamVal(sid, 'ATC_RAT_PIT_IMAX'); +simIn.param.PIDP.FF = getParamVal(sid, 'ATC_RAT_PIT_FF'); +simIn.param.PIDP.SR_MAX = getParamVal(sid, 'ATC_RAT_PIT_SMAX'); +simIn.param.PIDP.SR_TAU = single(1.0); % Slew Rate Tau - not yet available as a parameter of the copter. Set to 1.0 by default (AC_PID.h, line 24). +simIn.param.PIDP.SR_FLT_f = single(25.0); % Slew Rate lowpass filter cutoff frequency. Defined in SlewLimiter.h, line 14. + +% Inital inputs +if simIn.param.rateCtrlVal || simIn.param.attCtrlVal || simIn.param.mdlVal + simIn.init.PIDP.P = single(sid.PIDP.P(1)); + simIn.init.PIDP.I = single(sid.PIDP.I(1)); + simIn.init.PIDP.D = single(sid.PIDP.D(1)); + simIn.init.PIDP.Tar = single(sid.RATE.PDes(1)*pi/180); % Convert to radian due to conversion to degree for logging (AP_AHRS_View::Write_Rate) + simIn.init.PIDP.TarFilt = single(sid.PIDP.Tar(1)); + simIn.init.PIDP.ErrFilt = single(sid.PIDP.Err(1)); + simIn.init.PIDP.SrOut = single(sid.PIDP.SRate(1)); % Initial value of the slew rate determined by the slew limiter. Used for both modifier_slew_rate and output_slew_rate. + if (simIn.param.PIDP.D ~= 0) + simIn.init.PIDP.DerFilt = single(sid.PIDP.D(1))/simIn.param.PIDP.D; + else + simIn.init.PIDP.DerFilt = single(0); + end +else + simIn.init.PIDP.P = single(0); + simIn.init.PIDP.I = single(0); + simIn.init.PIDP.D = single(0); + simIn.init.PIDP.Tar = single(0); + simIn.init.PIDP.TarFilt = single(0); + simIn.init.PIDP.ErrFilt = single(0); + simIn.init.PIDP.DerFilt = single(0); + simIn.init.PIDP.SrOut = single(0); +end + +%% Yaw Rate Controller +iVec = (sid.PIDY.TimeS >= tStart & sid.PIDY.TimeS <= tEnd); +simIn.signals.PIDY.Time = single(sid.PIDY.TimeS(iVec)-tStart); +% Inputs +simIn.signals.PIDY.Tar = single(sid.PIDY.Tar(iVec)); % target values filtered +simIn.signals.PIDY.Act = single(sid.PIDY.Act(iVec)); % actual values +simIn.signals.PIDY.Err = single(sid.PIDY.Err(iVec)); % error values +if simIn.param.rateCtrlVal || simIn.param.attCtrlVal || simIn.param.mdlVal + % Clock of Slew Limiter + % Use tracked logging time of PID message in validation modes + simIn.signals.PIDY.ClockDMod = single(1000 * simIn.signals.PIDY.Time); +else + simIn.signals.PIDY.ClockDMod = single(1000 * simIn.param.dt * (0:length(simIn.signals.PIDY.Time)-1)'); +end + +% Outputs +simIn.signals.PIDY.FF = single(sid.PIDY.FF(iVec)); +simIn.signals.PIDY.P = single(sid.PIDY.P(iVec)); +simIn.signals.PIDY.I = single(sid.PIDY.I(iVec)); +simIn.signals.PIDY.D = single(sid.PIDY.D(iVec)); +simIn.signals.PIDY.DMod = single(sid.PIDY.Dmod(iVec)); +simIn.signals.PIDY.ILimit = single(sid.PIDY.Limit(iVec)); +simIn.signals.PIDY.SRate = single(sid.PIDY.SRate(iVec)); % Output slew rate of the slew limiter, stored in _output_slew_rate in AC_PID.cpp, line 161 + +% Parameters - Read from PARM.Value cell array with logical indexing +simIn.param.PIDY.TC = getParamVal(sid, 'ATC_INPUT_TC'); +simIn.param.PIDY.FLTT_f = getParamVal(sid, 'ATC_RAT_YAW_FLTT'); +simIn.param.PIDY.FLTE_f = getParamVal(sid, 'ATC_RAT_YAW_FLTE'); +simIn.param.PIDY.FLTD_f = getParamVal(sid, 'ATC_RAT_YAW_FLTD'); +simIn.param.PIDY.P = getParamVal(sid, 'ATC_RAT_YAW_P'); +simIn.param.PIDY.I = getParamVal(sid, 'ATC_RAT_YAW_I'); +simIn.param.PIDY.D = getParamVal(sid, 'ATC_RAT_YAW_D'); +simIn.param.PIDY.IMAX = getParamVal(sid, 'ATC_RAT_YAW_IMAX'); +simIn.param.PIDY.FF = getParamVal(sid, 'ATC_RAT_YAW_FF'); +simIn.param.PIDY.SR_MAX = getParamVal(sid, 'ATC_RAT_YAW_SMAX'); +simIn.param.PIDY.SR_TAU = single(1.0); % Slew Rate Tau - not yet available as a parameter of the copter. Set to 1.0 by default (AC_PID.h, line 24). +simIn.param.PIDY.SR_FLT_f = single(25.0); % Slew Rate lowpass filter cutoff frequency. Defined in SlewLimiter.h, line 14. + +% Inital inputs +if simIn.param.rateCtrlVal || simIn.param.attCtrlVal || simIn.param.mdlVal + simIn.init.PIDY.P = single(sid.PIDY.P(1)); + simIn.init.PIDY.I = single(sid.PIDY.I(1)); + simIn.init.PIDY.D = single(sid.PIDY.D(1)); + simIn.init.PIDY.Tar = single(sid.RATE.PDes(1)*pi/180); % Convert to radian due to conversion to degree for logging (AP_AHRS_View::Write_Rate) + simIn.init.PIDY.TarFilt = single(sid.PIDY.Tar(1)); + simIn.init.PIDY.ErrFilt = single(sid.PIDY.Err(1)); + simIn.init.PIDY.SrOut = single(sid.PIDY.SRate(1)); % Initial value of the slew rate determined by the slew limiter. Used for both modifier_slew_rate and output_slew_rate. + if (simIn.param.PIDY.D ~= 0) + simIn.init.PIDY.DerFilt = single(sid.PIDY.D(1))/simIn.param.PIDY.D; + else + simIn.init.PIDY.DerFilt = single(0); + end +else + simIn.init.PIDY.P = single(0); + simIn.init.PIDY.I = single(0); + simIn.init.PIDY.D = single(0); + simIn.init.PIDY.Tar = single(0); + simIn.init.PIDY.TarFilt = single(0); + simIn.init.PIDY.ErrFilt = single(0); + simIn.init.PIDY.DerFilt = single(0); + simIn.init.PIDY.SrOut = single(0); +end + +%% RATE message +iVec = (sid.RATE.TimeS >= tStart & sid.RATE.TimeS <= tEnd); +simIn.signals.RATE.Time = single(sid.RATE.TimeS(iVec)-tStart); + +% Roll +simIn.signals.RATE.ROut = single(sid.RATE.ROut(iVec)); % Rate Controller total output (except FF) +% Rate Controller target (deg/s): Logged signal in val phase, step in opt phase. +if simIn.param.rateCtrlVal || simIn.param.attCtrlVal || simIn.param.mdlVal + simIn.signals.RATE.RDes = single(sid.RATE.RDes(iVec)); +elseif simIn.param.optCtrl && axis == 10 + simIn.signals.RATE.RDes = single((simIn.signals.RATE.Time > OPT.stepTime)'*OPT.stepMag); % Step at 5s +else + simIn.signals.RATE.RDes = single(zeros(numel(simIn.signals.RATE.Time), 1)); % Set to zero if axis not optimized +end + +% Pitch +simIn.signals.RATE.POut = single(sid.RATE.POut(iVec)); +% Rate Controller target (deg/s): Logged signal in val phase, step in opt phase +if simIn.param.rateCtrlVal || simIn.param.attCtrlVal || simIn.param.mdlVal + simIn.signals.RATE.PDes = single(sid.RATE.PDes(iVec)); +elseif simIn.param.optCtrl && axis == 11 + simIn.signals.RATE.PDes = single((simIn.signals.RATE.Time > OPT.stepTime)'*OPT.stepMag); % Step at 5s +else + simIn.signals.RATE.PDes = single(zeros(numel(simIn.signals.RATE.Time), 1)); % Set to zero if axis not optimized +end + +% Yaw +simIn.signals.RATE.YOut = single(sid.RATE.YOut(iVec)); +% Rate Controller target (deg/s): Logged signal in val phase, step in opt phase +if simIn.param.rateCtrlVal || simIn.param.attCtrlVal || simIn.param.mdlVal + simIn.signals.RATE.YDes = single(sid.RATE.YDes(iVec)); +elseif simIn.param.optCtrl && axis == 12 + simIn.signals.RATE.YDes = single((simIn.signals.RATE.Time > OPT.stepTime)'*OPT.stepMag); % Step at 5s +else + simIn.signals.RATE.YDes = single(zeros(numel(simIn.signals.RATE.Time), 1)); % Set to zero if axis not optimized +end + +% Throttle +simIn.signals.RATE.AOut = single(sid.RATE.AOut(iVec)); % Throttle command to motors +simIn.signals.RATE.A = single(sid.RATE.A(iVec)); % Vertical acceleration in earth frame + +%% Position Controller +% Default definitions +simIn.param.PSCD.THR_DZ = getParamVal(sid, 'THR_DZ'); % Deadzone above and below mid throttle in PWM microseconds. Used in Althold, Loiter, PosHold. Defined in Parameters.cpp +simIn.param.PSCD.VEL_MAX_DOWN_DFLT = single(-150); % Default descent rate in cm/s, defined in AC_PosControl.h, line 27 +simIn.param.PSCD.VEL_MAX_UP_DFLT = single(250); % Default climb rate in cm/s, defined in AC_PosControl.h, line 28 +simIn.param.PSCD.ACC_MAX_Z_DFLT = single(250); % Default vertical acceleration cm/s/s, defined in AC_PosControl.h, line 30 +simIn.param.PSCD.JERK_MAX_Z_DFLT = single(500); % Default vertical jerk, defined as m/s/s/s in AC_PosControl.h, line 31. Converted to cm/s/s/s in AC_PosControl.cpp, line 318. + +simIn.param.PSCD.VEL_MAX_DN = getParamVal(sid, 'PILOT_SPEED_DN'); % Maximum vertical descending velocity in cm/s, defined in parameters.cpp, line 906 +simIn.param.PSCD.VEL_MAX_UP = getParamVal(sid, 'PILOT_SPEED_UP'); % Maximum vertical ascending velocity in cm/s, defined in parameters.cpp, line 223 +simIn.param.PSCD.ACC_MAX_Z = getParamVal(sid, 'PILOT_ACCEL_Z'); % Maximum vertical acceleration used when pilot is controlling the altitude, parameters.cpp, line 232 +simIn.param.PSCD.JERK_MAX_Z = getParamVal(sid, 'PSC_JERK_Z'); % Jerk limit of vertical kinematic path generation in m/s^3. Determines how quickly aircraft changes acceleration target +simIn.param.PSCD.OVERSPEED_GAIN_Z = single(2); % gain controlling rate at which z-axis speed is brought back within SPEED_UP and SPEED_DOWN range, defined in AC_PosControl.h +%% Position Controller z + +% Parameters z position controller +simIn.param.PSCD.P_POS = getParamVal(sid, 'PSC_POSZ_P'); % P gain of the vertical position controller + +% Parameters z velocity controller +simIn.param.PSCD.P_VEL = getParamVal(sid, 'PSC_VELZ_P'); % P gain of the vertical velocity controller +simIn.param.PSCD.I_VEL = getParamVal(sid, 'PSC_VELZ_I'); % I gain of the vertical velocity controller +simIn.param.PSCD.D_VEL = getParamVal(sid, 'PSC_VELZ_D'); % D gain of the vertical velocity controller +simIn.param.PSCD.IMAX_VEL = getParamVal(sid, 'PSC_VELZ_IMAX'); % I gain maximu vertical velocity controller +simIn.param.PSCD.FF_VEL = getParamVal(sid, 'PSC_VELZ_FF'); % Feed Forward gain of the vertical velocity controller +simIn.param.PSCD.FLTE_VEL = getParamVal(sid, 'PSC_VELZ_FLTE'); % Cutoff frequency of the error filter (in Hz) +simIn.param.PSCD.FLTD_VEL = getParamVal(sid, 'PSC_VELZ_FLTD'); % Cutoff frequency of the D term filter (in Hz) +simIn.param.PSCD.CTRL_RATIO_INIT = single(2.0); % Initial value of _vel_z_control_ratio, defined in PosControl.h, line 456 + +% Parameters z acceleration controller +simIn.param.PIDA.P = getParamVal(sid, 'PSC_ACCZ_P'); % P gain of the vertical acceleration controller +simIn.param.PIDA.I = getParamVal(sid, 'PSC_ACCZ_I'); % I gain of the vertical acceleration controller +simIn.param.PIDA.D = getParamVal(sid, 'PSC_ACCZ_D'); % D gain of the vertical acceleration controller +simIn.param.PIDA.IMAX = getParamVal(sid, 'PSC_ACCZ_IMAX'); % I gain maximu vertical acceleration controller +simIn.param.PIDA.FF = getParamVal(sid, 'PSC_ACCZ_FF'); % Feed Forward gain of the vertical acceleration controller +simIn.param.PIDA.FLTE_f = getParamVal(sid, 'PSC_ACCZ_FLTE'); % Cutoff frequency of the error filter (in Hz) +simIn.param.PIDA.FLTD_f = getParamVal(sid, 'PSC_ACCZ_FLTD'); % Cutoff frequency of the D term filter (in Hz) +simIn.param.PIDA.FLTT_f = getParamVal(sid, 'PSC_ACCZ_FLTT'); % Cutoff frequency of the target filter (in Hz) +simIn.param.PIDA.SR_MAX = getParamVal(sid, 'PSC_ACCZ_SMAX'); % Upper limit of the slew rate produced by combined P and D gains +simIn.param.PIDA.SR_TAU = single(1.0); % Slew Rate Tau - not yet available as a parameter of the copter. Set to 1.0 by default (AC_PID.h, line 24). +simIn.param.PIDA.SR_FLT_f = single(25.0); % Slew Rate lowpass filter cutoff frequency. Defined in SlewLimiter.h, line 14. + +% Read signals for z position controller if PSCD message was logged +if isfield(sid, 'PSCD') + % Signals of PSCD message + iVec = (sid.PSCD.TimeS >= tStart & sid.PSCD.TimeS <= tEnd); + simIn.signals.PSCD.Time = single(sid.PSCD.TimeS(iVec)-tStart); + % Inputs - Multiply by 100 to get cm as used in controller + % Inversion of signals necessary due to inverted logging + simIn.signals.PSCD.zPosTar = single(-sid.PSCD.TPD(iVec)*100); % Target z-Position, calculated in set_pos_target_z_from_climb_rate_cm() + simIn.signals.PSCD.zPosAct = single(-sid.PSCD.PD(iVec)*100); % Actual z-Position, obtained from INAV + simIn.signals.PSCD.zVelDes = single(-sid.PSCD.DVD(iVec)*100); % Desired z-Velocity, calculated in set_pos_target_z_from_climb_rate_cm() + simIn.signals.PSCD.zVelAct = single(-sid.PSCD.VD(iVec)*100); % Actual z-Velocity, obtained from INAV + simIn.signals.PSCD.zVelTar = single(-sid.PSCD.TVD(iVec)*100); % Target z-Velocity, calculated in update_z_controller() + simIn.signals.PSCD.zAccDes = single(-sid.PSCD.DAD(iVec)*100); % Desired z-Acceleration, calculated in set_pos_target_z_from_climb_rate_cm() + simIn.signals.PSCD.zAccAct = single(-sid.PSCD.AD(iVec)*100); % Actual z-Acceleration, obtained from AHRS + simIn.signals.PSCD.zAccTar = single(-sid.PSCD.TAD(iVec)*100); % Target z-Acceleration, calculated in update_z_controller() + + % Signals of PIDA message + iVec = (sid.PIDA.TimeS >= tStart & sid.PIDA.TimeS <= tEnd); + simIn.signals.PIDA.Time = single(sid.PIDA.TimeS(iVec)-tStart); + % Inputs PID z acceleration + simIn.signals.PIDA.Err = single(sid.PIDA.Err(iVec)); % Error between target and actual z-acceleration + simIn.signals.PIDA.Tar = single(sid.PIDA.Tar(iVec)); + simIn.signals.PIDA.Act = single(sid.PIDA.Act(iVec)); + if simIn.param.rateCtrlVal || simIn.param.attCtrlVal || simIn.param.mdlVal || simIn.param.altCtrlVal + % Clock of Slew Limiter + % Use tracked logging time of PID message in validation modes + simIn.signals.PIDA.ClockDMod = single(1000 * simIn.signals.PIDA.Time); + else + simIn.signals.PIDA.ClockDMod = single(1000 * simIn.param.dt * (0:length(simIn.signals.PIDA.Time)-1)'); + end + % Outputs PID z acceleration + simIn.signals.PIDA.FF = single(sid.PIDA.FF(iVec)); + simIn.signals.PIDA.P = single(sid.PIDA.P(iVec)); + simIn.signals.PIDA.I = single(sid.PIDA.I(iVec)); + simIn.signals.PIDA.D = single(sid.PIDA.D(iVec)); + simIn.signals.PIDA.DMod = single(sid.PIDA.Dmod(iVec)); + simIn.signals.PIDA.ILimit = single(sid.PIDA.Limit(iVec)); + simIn.signals.PIDA.SRate = single(sid.PIDA.SRate(iVec)); + + % Inital inputs + if simIn.param.rateCtrlVal || simIn.param.attCtrlVal || simIn.param.mdlVal || simIn.param.altCtrlVal + % Initial actual values - in meter + simIn.init.PSCD.posAct = single(-sid.PSCD.PD(1)); + simIn.init.PSCD.velAct = single(-sid.PSCD.VD(1)); + simIn.init.PSCD.accAct = single(-sid.PSCD.AD(1)); + + % Init the position controller to the current position, velocity + % and acceleration (from AC_PosControl::init_z()) in cm + simIn.init.PIDA.posTar = single(-sid.PSCD.TPD(1)*100); + simIn.init.PIDA.velDes = single(-sid.PSCD.DVD(1)*100); + simIn.init.PIDA.accDes = single(min(max(-sid.PSCD.DAD(1)*100, -simIn.param.PSCD.ACC_MAX_Z_DFLT) ,simIn.param.PSCD.ACC_MAX_Z_DFLT)); + + simIn.init.PIDA.P = single(sid.PIDA.P(1)); + simIn.init.PIDA.I = single(simIn.signals.CTUN.ThrIn(1) - simIn.signals.CTUN.ThrHov(1)) * 1000 ... + - simIn.param.PIDA.P * (-sid.PSCD.TAD(1)*100 - (-sid.PSCD.AD(1))*100) ... + - simIn.param.PIDA.FF * sid.PIDA.Tar(1); % Integrator init. according to AC_PosControl::init_z_controller() + simIn.init.PIDA.D = single(sid.PIDA.D(1)); + simIn.init.PIDA.TarFilt = single(sid.PIDA.Tar(1)); + simIn.init.PIDA.ErrFilt = single(sid.PIDA.Err(1)); + simIn.init.PIDA.SROut = single(sid.PIDA.SRate(1)); % Initial value of the slew rate determined by the slew limiter. Used for both modifier_slew_rate and output_slew_rate. + if (simIn.param.PIDA.D ~= 0) + simIn.init.PIDA.DerFilt = single(sid.PIDA.D(1))/PSC_ACC_Z.param.D; % Divide through D gain to obtain inital D input + else + simIn.init.PIDA.DerFilt = single(0); + end + else + % Initial actual values + simIn.init.PSCD.posAct = single(0); + simIn.init.PSCD.velAct = single(0); + simIn.init.PSCD.accAct = single(0); + + simIn.init.PIDA.posTar = single(0); + simIn.init.PIDA.velDes = single(0); + simIn.init.PIDA.accDes = single(0); + + simIn.init.PIDA.P = single(0); + simIn.init.PIDA.I = single(0); + simIn.init.PIDA.D = single(0); + simIn.init.PIDA.TarFilt = single(0); + simIn.init.PIDA.ErrFilt = single(0); + simIn.init.PIDA.DerFilt = single(0); + simIn.init.PIDA.SROut = single(0); + end +else + % Set all signals to zero, if PSCD message was not logged and z + % controller has been deactivated + iVec = (sid.RATE.TimeS >= tStart & sid.RATE.TimeS <= tEnd); + simIn.signals.PSCD.Time = single(sid.RATE.TimeS(iVec)-tStart); + simIn.signals.PSCD.zPosTar = single(zeros(length(simIn.signals.PSCD.Time),1)); % Target z-Position, calculated in set_pos_target_z_from_climb_rate_cm() + simIn.signals.PSCD.zPosAct = single(zeros(length(simIn.signals.PSCD.Time),1)); % Actual z-Position, obtained from INAV + simIn.signals.PSCD.zVelDes = single(zeros(length(simIn.signals.PSCD.Time),1)); % Desired z-Velocity, calculated in set_pos_target_z_from_climb_rate_cm() + simIn.signals.PSCD.zVelAct = single(zeros(length(simIn.signals.PSCD.Time),1)); % Actual z-Velocity, obtained from INAV + simIn.signals.PSCD.zVelTar = single(zeros(length(simIn.signals.PSCD.Time),1)); % Target z-Velocity, calculated in update_z_controller() + simIn.signals.PSCD.zAccDes = single(zeros(length(simIn.signals.PSCD.Time),1)); % Desired z-Acceleration, calculated in set_pos_target_z_from_climb_rate_cm() + simIn.signals.PSCD.zAccAct = single(zeros(length(simIn.signals.PSCD.Time),1)); % Actual z-Acceleration, obtained from AHRS + simIn.signals.PSCD.zAccTar = single(zeros(length(simIn.signals.PSCD.Time),1)); % Target z-Acceleration, calculated in update_z_controller() + + % Signals of PIDA message + simIn.signals.PIDA.Time = single(simIn.signals.RATE.Time)-tStart; + % Inputs PID z acceleration + simIn.signals.PIDA.Err = single(zeros(length(simIn.signals.PIDA.Time),1)); % Error between target and actual z-acceleration + simIn.signals.PIDA.ClockDMod = single(zeros(length(simIn.signals.PIDA.Time),1)); % Clock of Slew Limiter + + % Outputs PID z acceleration + simIn.signals.PIDA.FF = single(zeros(length(simIn.signals.PIDA.Time),1)); + simIn.signals.PIDA.P = single(zeros(length(simIn.signals.PIDA.Time),1)); + simIn.signals.PIDA.I = single(zeros(length(simIn.signals.PIDA.Time),1)); + simIn.signals.PIDA.D = single(zeros(length(simIn.signals.PIDA.Time),1)); + simIn.signals.PIDA.DMod = single(zeros(length(simIn.signals.PIDA.Time),1)); + simIn.signals.PIDA.ILimit = single(zeros(length(simIn.signals.PIDA.Time),1)); + simIn.signals.PIDA.SRate = single(zeros(length(simIn.signals.PIDA.Time),1)); + simIn.signals.PIDA.Act = single(zeros(length(simIn.signals.PIDA.Time),1)); + simIn.signals.PIDA.Tar = single(zeros(length(simIn.signals.PIDA.Time),1)); + + % Initial inputs + % Initial actual values + simIn.init.PSCD.posAct = single(0); + simIn.init.PSCD.velAct = single(0); + simIn.init.PSCD.accAct = single(0); + + simIn.init.PIDA.posTar = single(0); + simIn.init.PIDA.velDes = single(0); + simIn.init.PIDA.accDes = single(0); + + simIn.init.PIDA.P = single(0); + simIn.init.PIDA.I = single(0); + simIn.init.PIDA.D = single(0); + simIn.init.PIDA.TarFilt = single(0); + simIn.init.PIDA.ErrFilt = single(0); + simIn.init.PIDA.DerFilt = single(0); + simIn.init.PIDA.SROut = single(0); +end + + +% Real Flight Signals of PID z velocity - only load if log messages +% exists +if isfield(sid, 'PCVZ') + iVec = (sid.PCVZ.TimeS >= tStart & sid.PCVZ.TimeS <= tEnd); + simIn.signals.PCVZ.Time = single(sid.PCVZ.TimeS(iVec)-tStart); + simIn.signals.PCVZ.Err = single(sid.PCVZ.Err(iVec)); + simIn.signals.PCVZ.P = single(sid.PCVZ.P(iVec)); + simIn.signals.PCVZ.I = single(sid.PCVZ.I(iVec)); + simIn.signals.PCVZ.D = single(sid.PCVZ.D(iVec)); + simIn.signals.PCVZ.FF = single(sid.PCVZ.FF(iVec)); +else % Set to zero otherwise + iVec = (sid.RATE.TimeS >= tStart & sid.RATE.TimeS <= tEnd); + simIn.signals.PCVZ.Time = single(sid.RATE.TimeS(iVec)-tStart); + simIn.signals.PCVZ.Err = single(zeros(length(simIn.signals.PCVZ.Time),1)); + simIn.signals.PCVZ.P = single(zeros(length(simIn.signals.PCVZ.Time),1)); + simIn.signals.PCVZ.I = single(zeros(length(simIn.signals.PCVZ.Time),1)); + simIn.signals.PCVZ.D = single(zeros(length(simIn.signals.PCVZ.Time),1)); + simIn.signals.PCVZ.FF = single(zeros(length(simIn.signals.PCVZ.Time),1)); +end + +%% Load identified plant models data +if simIn.param.optCtrl || simIn.param.mdlVal && exist('idModel', 'var') + % Roll + if isempty(findobj(idModel, 'axis', 'RLL')) + simIn.models.RollAxis = idpoly(tf(1, [1 1], simIn.param.dt)); + else + model = findobj(idModel, 'axis', 'RLL'); + % If more than one model is found, let user choose + if length(model) > 1 + mdlIdx = input('More than one model found for the roll axis. Input index of desired model: '); + else + mdlIdx = 1; + end + simIn.models.RollAxis = idss(c2d(model(mdlIdx).tfModel, simIn.param.dt)); + % Decrease delay to account for the additional feedback delay + simIn.models.RollAxis.InputDelay = simIn.models.RollAxis.InputDelay-1; + end + % Pitch + if isempty(findobj(idModel, 'axis', 'PIT')) + simIn.models.PitchAxis = idpoly(tf(1, [1 1], simIn.param.dt)); + else + model = findobj(idModel, 'axis', 'PIT'); + % If more than one model is found, let user choose + if length(model) > 1 + mdlIdx = input('More than one model found for the pitch axis. Input index of desired model: '); + else + mdlIdx = 1; + end + simIn.models.PitchAxis = idss(c2d(model(mdlIdx).tfModel, simIn.param.dt)); + simIn.models.PitchAxis.InputDelay = simIn.models.PitchAxis.InputDelay-1; + end + % Yaw + if isempty(findobj(idModel, 'axis', 'YAW')) + simIn.models.YawAxis = idpoly(tf(1, [1 1], simIn.param.dt)); + else + model = findobj(idModel, 'axis', 'YAW'); + % If more than one model is found, let user choose + if length(model) > 1 + mdlIdx = input('More than one model found for the yaw axis. Input index of desired model: '); + else + mdlIdx = 1; + end + simIn.models.YawAxis = idss(c2d(model(mdlIdx).tfModel, simIn.param.dt)); + simIn.models.YawAxis.InputDelay = simIn.models.YawAxis.InputDelay-1; + end + % Vertical Motion - Throttle + if isempty(findobj(idModel, 'axis', 'THR')) + simIn.models.RollAxis = idpoly(tf(1, [1 1], simIn.param.dt)); + else + model = findobj(idModel, 'axis', 'THR'); + % If more than one model is found, let user choose + if length(model) > 1 + mdlIdx = input('More than one model found for the vertical axis. Input index of desired model: '); + else + mdlIdx = 1; + end + simIn.models.VerticalAxis = idss(c2d(model(mdlIdx).tfModel, simIn.param.dt)); + % Decrease delay to account for the additional feedback delay + simIn.models.VerticalAxis.InputDelay = simIn.models.VerticalAxis.InputDelay-1; + end +else % Create dummy models of optimization is not active + simIn.models.RollAxis = idpoly(tf(1, [1 1], simIn.param.dt)); + simIn.models.PitchAxis = idpoly(tf(1, [1 1], simIn.param.dt)); + simIn.models.YawAxis = idpoly(tf(1, [1 1], simIn.param.dt)); + simIn.models.VerticalAxis = idpoly(tf(1, [1 1], simIn.param.dt)); +end + +% Initial values +if simIn.param.mdlVal && mode == 25 + simIn.models.RollInit = single(sid.SIDD.Gx(1)*pi/180); + simIn.models.PitchInit = single(sid.SIDD.Gy(1)*pi/180); + simIn.models.YawInit = single(sid.SIDD.Gz(1)*pi/180); + simIn.models.VerticalOutInit = single(sid.SIDD.Az(1)); + simIn.models.VerticalInInit = single(sid.RATE.AOut(1)); +else + simIn.models.RollInit = single(0); + simIn.models.PitchInit = single(0); + simIn.models.YawInit = single(0); + simIn.models.VerticalOutInit = single(-9.81); + simIn.models.VerticalInInit = single(sid.RATE.AOut(1)); +end + +%% Delete all irrelevant data +clear i dist start thr_man rel_msg mode param_names msgs tEnd tStart simInMode +clear phase_des runOutsideLoop mdlIdx pitchCh rollCh yawCh iVec Fs axis dt +clear simInMode thrCh diff --git a/Tools/simulink/arducopter/simulink_model.PNG b/Tools/simulink/arducopter/simulink_model.PNG new file mode 100644 index 00000000000..f563e87eb77 Binary files /dev/null and b/Tools/simulink/arducopter/simulink_model.PNG differ diff --git a/Tools/vagrant/initvagrant-desktop.sh b/Tools/vagrant/initvagrant-desktop.sh old mode 100644 new mode 100755 index b21df34ee34..702c78d5b08 --- a/Tools/vagrant/initvagrant-desktop.sh +++ b/Tools/vagrant/initvagrant-desktop.sh @@ -14,7 +14,14 @@ fi apt-get update -apt-get install -y ubuntu-desktop +RELEASE_CODENAME=$(lsb_release -c -s) + +PACKAGES="ubuntu-desktop" +if [ ${RELEASE_CODENAME} == 'jammy' ]; then + PACKAGES="$PACKAGES dbus-x11" +fi + +apt-get install -y $PACKAGES GDB_CONF="/etc/gdm3/custom.conf" perl -pe 's/# AutomaticLoginEnable = true/AutomaticLoginEnable = true/' -i "$GDB_CONF" @@ -37,6 +44,11 @@ sudo -u "$VAGRANT_USER" dbus-launch gsettings set org.gnome.desktop.session idle sudo -u "$VAGRANT_USER" mkdir -p /home/"$VAGRANT_USER"/.config echo "yes" | sudo -u "$VAGRANT_USER" dd of=/home/"$VAGRANT_USER"/.config/gnome-initial-setup-done +# sssd is missing config: +if [ ${RELEASE_CODENAME} == 'jammy' ]; then + systemctl disable sssd +fi + # start the graphical environment right now: systemctl isolate graphical.target diff --git a/Tools/vagrant/initvagrant-trusty64.sh b/Tools/vagrant/initvagrant-trusty64.sh old mode 100644 new mode 100755 diff --git a/Tools/vagrant/initvagrant.sh b/Tools/vagrant/initvagrant.sh index ac843f203f0..4548e6af600 100755 --- a/Tools/vagrant/initvagrant.sh +++ b/Tools/vagrant/initvagrant.sh @@ -61,6 +61,17 @@ echo "source $BASHRC_GIT" | # link a half-way decent .mavinit.scr into place: sudo --login -u $VAGRANT_USER ln -sf /vagrant/Tools/vagrant/mavinit.scr /home/$VAGRANT_USER/.mavinit.scr +RELEASE_CODENAME=$(lsb_release -c -s) + +# no multipath available, stop mutlipathd complaining about lack of data: +if [ ${RELEASE_CODENAME} == 'jammy' ]; then + cat >>/etc/multipath.conf < +#include extern const AP_HAL::HAL& hal; #if APM_BUILD_TYPE(APM_BUILD_ArduPlane) // default gains for Plane # define AC_ATTITUDE_CONTROL_INPUT_TC_DEFAULT 0.2f // Soft + #define AC_ATTITUDE_CONTROL_ANGLE_LIMIT_MIN 5.0 // Min lean angle so that vehicle can maintain limited control #else // default gains for Copter and Sub # define AC_ATTITUDE_CONTROL_INPUT_TC_DEFAULT 0.15f // Medium + #define AC_ATTITUDE_CONTROL_ANGLE_LIMIT_MIN 10.0 // Min lean angle so that vehicle can maintain limited control #endif +AC_AttitudeControl *AC_AttitudeControl::_singleton; + // table of user settable parameters const AP_Param::GroupInfo AC_AttitudeControl::var_info[] = { @@ -191,9 +196,9 @@ void AC_AttitudeControl::reset_rate_controller_I_terms() // reset rate controller I terms smoothly to zero in 0.5 seconds void AC_AttitudeControl::reset_rate_controller_I_terms_smoothly() { - get_rate_roll_pid().relax_integrator(0.0, AC_ATTITUDE_RATE_RELAX_TC); - get_rate_pitch_pid().relax_integrator(0.0, AC_ATTITUDE_RATE_RELAX_TC); - get_rate_yaw_pid().relax_integrator(0.0, AC_ATTITUDE_RATE_RELAX_TC); + get_rate_roll_pid().relax_integrator(0.0, _dt, AC_ATTITUDE_RATE_RELAX_TC); + get_rate_pitch_pid().relax_integrator(0.0, _dt, AC_ATTITUDE_RATE_RELAX_TC); + get_rate_yaw_pid().relax_integrator(0.0, _dt, AC_ATTITUDE_RATE_RELAX_TC); } // The attitude controller works around the concept of the desired attitude, target attitude @@ -219,7 +224,7 @@ void AC_AttitudeControl::reset_rate_controller_I_terms_smoothly() // trust vector drops below 2*AC_ATTITUDE_THRUST_ERROR_ANGLE. At this point the heading is also corrected. // Command a Quaternion attitude with feedforward and smoothing -// attitude_desired_quat: is updated on each time_step (_dt) by the integral of the angular velocity +// attitude_desired_quat: is updated on each time_step by the integral of the angular velocity void AC_AttitudeControl::input_quaternion(Quaternion& attitude_desired_quat, Vector3f ang_vel_target) { Quaternion attitude_error_quat = _attitude_target.inverse() * attitude_desired_quat; @@ -283,7 +288,7 @@ void AC_AttitudeControl::input_euler_angle_roll_pitch_euler_rate_yaw(float euler // When yaw acceleration limiting is enabled, the yaw input shaper constrains angular acceleration about the yaw axis, slewing // the output rate towards the input rate. - _euler_rate_target.z = input_shaping_ang_vel(_euler_rate_target.z, euler_yaw_rate, euler_accel.z, _dt); + _euler_rate_target.z = input_shaping_ang_vel(_euler_rate_target.z, euler_yaw_rate, euler_accel.z, _dt, _rate_y_tc); // Convert euler angle derivative of desired attitude into a body-frame angular velocity vector for feedforward euler_rate_to_ang_vel(_euler_angle_target, _euler_rate_target, _ang_vel_target); @@ -384,9 +389,9 @@ void AC_AttitudeControl::input_euler_rate_roll_pitch_yaw(float euler_roll_rate_c // When acceleration limiting is enabled, the input shaper constrains angular acceleration, slewing // the output rate towards the input rate. - _euler_rate_target.x = input_shaping_ang_vel(_euler_rate_target.x, euler_roll_rate, euler_accel.x, _dt); - _euler_rate_target.y = input_shaping_ang_vel(_euler_rate_target.y, euler_pitch_rate, euler_accel.y, _dt); - _euler_rate_target.z = input_shaping_ang_vel(_euler_rate_target.z, euler_yaw_rate, euler_accel.z, _dt); + _euler_rate_target.x = input_shaping_ang_vel(_euler_rate_target.x, euler_roll_rate, euler_accel.x, _dt, _rate_rp_tc); + _euler_rate_target.y = input_shaping_ang_vel(_euler_rate_target.y, euler_pitch_rate, euler_accel.y, _dt, _rate_rp_tc); + _euler_rate_target.z = input_shaping_ang_vel(_euler_rate_target.z, euler_yaw_rate, euler_accel.z, _dt, _rate_y_tc); // Convert euler angle derivative of desired attitude into a body-frame angular velocity vector for feedforward euler_rate_to_ang_vel(_euler_angle_target, _euler_rate_target, _ang_vel_target); @@ -424,9 +429,9 @@ void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw(float roll_rate_bf_cds, fl // Compute acceleration-limited body frame rates // When acceleration limiting is enabled, the input shaper constrains angular acceleration about the axis, slewing // the output rate towards the input rate. - _ang_vel_target.x = input_shaping_ang_vel(_ang_vel_target.x, roll_rate_rads, get_accel_roll_max_radss(), _dt); - _ang_vel_target.y = input_shaping_ang_vel(_ang_vel_target.y, pitch_rate_rads, get_accel_pitch_max_radss(), _dt); - _ang_vel_target.z = input_shaping_ang_vel(_ang_vel_target.z, yaw_rate_rads, get_accel_yaw_max_radss(), _dt); + _ang_vel_target.x = input_shaping_ang_vel(_ang_vel_target.x, roll_rate_rads, get_accel_roll_max_radss(), _dt, _rate_rp_tc); + _ang_vel_target.y = input_shaping_ang_vel(_ang_vel_target.y, pitch_rate_rads, get_accel_pitch_max_radss(), _dt, _rate_rp_tc); + _ang_vel_target.z = input_shaping_ang_vel(_ang_vel_target.z, yaw_rate_rads, get_accel_yaw_max_radss(), _dt, _rate_y_tc); // Convert body-frame angular velocity into euler angle derivative of desired attitude ang_vel_to_euler_rate(_euler_angle_target, _ang_vel_target, _euler_rate_target); @@ -457,9 +462,9 @@ void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw_2(float roll_rate_bf_cds, // Compute acceleration-limited body frame rates // When acceleration limiting is enabled, the input shaper constrains angular acceleration about the axis, slewing // the output rate towards the input rate. - _ang_vel_target.x = input_shaping_ang_vel(_ang_vel_target.x, roll_rate_rads, get_accel_roll_max_radss(), _dt); - _ang_vel_target.y = input_shaping_ang_vel(_ang_vel_target.y, pitch_rate_rads, get_accel_pitch_max_radss(), _dt); - _ang_vel_target.z = input_shaping_ang_vel(_ang_vel_target.z, yaw_rate_rads, get_accel_yaw_max_radss(), _dt); + _ang_vel_target.x = input_shaping_ang_vel(_ang_vel_target.x, roll_rate_rads, get_accel_roll_max_radss(), _dt, _rate_rp_tc); + _ang_vel_target.y = input_shaping_ang_vel(_ang_vel_target.y, pitch_rate_rads, get_accel_pitch_max_radss(), _dt, _rate_rp_tc); + _ang_vel_target.z = input_shaping_ang_vel(_ang_vel_target.z, yaw_rate_rads, get_accel_yaw_max_radss(), _dt, _rate_y_tc); // Update the unused targets attitude based on current attitude to condition mode change _ahrs.get_quat_body_to_ned(_attitude_target); @@ -496,9 +501,9 @@ void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw_3(float roll_rate_bf_cds, // Compute acceleration-limited body frame rates // When acceleration limiting is enabled, the input shaper constrains angular acceleration about the axis, slewing // the output rate towards the input rate. - _ang_vel_target.x = input_shaping_ang_vel(_ang_vel_target.x, roll_rate_rads, get_accel_roll_max_radss(), _dt); - _ang_vel_target.y = input_shaping_ang_vel(_ang_vel_target.y, pitch_rate_rads, get_accel_pitch_max_radss(), _dt); - _ang_vel_target.z = input_shaping_ang_vel(_ang_vel_target.z, yaw_rate_rads, get_accel_yaw_max_radss(), _dt); + _ang_vel_target.x = input_shaping_ang_vel(_ang_vel_target.x, roll_rate_rads, get_accel_roll_max_radss(), _dt, _rate_rp_tc); + _ang_vel_target.y = input_shaping_ang_vel(_ang_vel_target.y, pitch_rate_rads, get_accel_pitch_max_radss(), _dt, _rate_rp_tc); + _ang_vel_target.z = input_shaping_ang_vel(_ang_vel_target.z, yaw_rate_rads, get_accel_yaw_max_radss(), _dt, _rate_y_tc); // Retrieve quaternion body attitude Quaternion attitude_body; @@ -549,10 +554,15 @@ void AC_AttitudeControl::input_angle_step_bf_roll_pitch_yaw(float roll_angle_ste } // Command a thrust vector and heading rate -void AC_AttitudeControl::input_thrust_vector_rate_heading(const Vector3f& thrust_vector, float heading_rate_cds) +void AC_AttitudeControl::input_thrust_vector_rate_heading(const Vector3f& thrust_vector, float heading_rate_cds, bool slew_yaw) { // Convert from centidegrees on public interface to radians - const float heading_rate = radians(heading_rate_cds * 0.01f); + float heading_rate = radians(heading_rate_cds * 0.01f); + if (slew_yaw) { + // a zero _angle_vel_yaw_max means that setting is disabled + const float slew_yaw_max_rads = get_slew_yaw_max_rads(); + heading_rate = constrain_float(heading_rate, -slew_yaw_max_rads, slew_yaw_max_rads); + } // calculate the attitude target euler angles _attitude_target.to_euler(_euler_angle_target.x, _euler_angle_target.y, _euler_angle_target.z); @@ -575,10 +585,10 @@ void AC_AttitudeControl::input_thrust_vector_rate_heading(const Vector3f& thrust // When yaw acceleration limiting is enabled, the yaw input shaper constrains angular acceleration about the yaw axis, slewing // the output rate towards the input rate. - _ang_vel_target.z = input_shaping_ang_vel(_ang_vel_target.z, heading_rate, get_accel_yaw_max_radss(), _dt); + _ang_vel_target.z = input_shaping_ang_vel(_ang_vel_target.z, heading_rate, get_accel_yaw_max_radss(), _dt, _rate_y_tc); // Limit the angular velocity - ang_vel_limit(_ang_vel_target, radians(_ang_vel_roll_max), radians(_ang_vel_pitch_max), get_slew_yaw_max_rads()); + ang_vel_limit(_ang_vel_target, radians(_ang_vel_roll_max), radians(_ang_vel_pitch_max), radians(_ang_vel_yaw_max)); } else { Quaternion yaw_quat; yaw_quat.from_axis_angle(Vector3f{0.0f, 0.0f, heading_rate * _dt}); @@ -810,12 +820,18 @@ float AC_AttitudeControl::input_shaping_angle(float error_angle, float input_tc, } // Acceleration is limited directly to smooth the beginning of the curve. - return input_shaping_ang_vel(target_ang_vel, desired_ang_vel, accel_max, dt); + return input_shaping_ang_vel(target_ang_vel, desired_ang_vel, accel_max, dt, 0.0f); } -// limits the acceleration and deceleration of a velocity request -float AC_AttitudeControl::input_shaping_ang_vel(float target_ang_vel, float desired_ang_vel, float accel_max, float dt) +// Shapes the velocity request based on a rate time constant. The angular acceleration and deceleration is limited. +float AC_AttitudeControl::input_shaping_ang_vel(float target_ang_vel, float desired_ang_vel, float accel_max, float dt, float input_tc) { + if (is_positive(input_tc)) { + // Calculate the acceleration to smoothly achieve rate. Jerk is not limited. + float error_rate = desired_ang_vel - target_ang_vel; + float desired_ang_accel = sqrt_controller(error_rate, 1.0f / MAX(input_tc, 0.01f), 0.0f, dt); + desired_ang_vel = target_ang_vel + desired_ang_accel * dt; + } // Acceleration is limited directly to smooth the beginning of the curve. if (is_positive(accel_max)) { float delta_ang_vel = accel_max * dt; @@ -834,8 +850,10 @@ void AC_AttitudeControl::input_shaping_rate_predictor(const Vector2f &error_angl target_ang_vel.x = input_shaping_angle(wrap_PI(error_angle.x), _input_tc, get_accel_roll_max_radss(), target_ang_vel.x, dt); target_ang_vel.y = input_shaping_angle(wrap_PI(error_angle.y), _input_tc, get_accel_pitch_max_radss(), target_ang_vel.y, dt); } else { - target_ang_vel.x = _p_angle_roll.get_p(wrap_PI(error_angle.x)); - target_ang_vel.y = _p_angle_pitch.get_p(wrap_PI(error_angle.y)); + const float angleP_roll = _p_angle_roll.kP() * _angle_P_scale.x; + const float angleP_pitch = _p_angle_pitch.kP() * _angle_P_scale.y; + target_ang_vel.x = angleP_roll * wrap_PI(error_angle.x); + target_ang_vel.y = angleP_pitch * wrap_PI(error_angle.y); } // Limit the angular velocity correction Vector3f ang_vel(target_ang_vel.x, target_ang_vel.y, 0.0f); @@ -973,25 +991,33 @@ Vector3f AC_AttitudeControl::update_ang_vel_target_from_att_error(const Vector3f { Vector3f rate_target_ang_vel; // Compute the roll angular velocity demand from the roll angle error + const float angleP_roll = _p_angle_roll.kP() * _angle_P_scale.x; if (_use_sqrt_controller && !is_zero(get_accel_roll_max_radss())) { - rate_target_ang_vel.x = sqrt_controller(attitude_error_rot_vec_rad.x, _p_angle_roll.kP(), constrain_float(get_accel_roll_max_radss() / 2.0f, AC_ATTITUDE_ACCEL_RP_CONTROLLER_MIN_RADSS, AC_ATTITUDE_ACCEL_RP_CONTROLLER_MAX_RADSS), _dt); + rate_target_ang_vel.x = sqrt_controller(attitude_error_rot_vec_rad.x, angleP_roll, constrain_float(get_accel_roll_max_radss() / 2.0f, AC_ATTITUDE_ACCEL_RP_CONTROLLER_MIN_RADSS, AC_ATTITUDE_ACCEL_RP_CONTROLLER_MAX_RADSS), _dt); } else { - rate_target_ang_vel.x = _p_angle_roll.kP() * attitude_error_rot_vec_rad.x; + rate_target_ang_vel.x = angleP_roll * attitude_error_rot_vec_rad.x; } // Compute the pitch angular velocity demand from the pitch angle error + const float angleP_pitch = _p_angle_pitch.kP() * _angle_P_scale.y; if (_use_sqrt_controller && !is_zero(get_accel_pitch_max_radss())) { - rate_target_ang_vel.y = sqrt_controller(attitude_error_rot_vec_rad.y, _p_angle_pitch.kP(), constrain_float(get_accel_pitch_max_radss() / 2.0f, AC_ATTITUDE_ACCEL_RP_CONTROLLER_MIN_RADSS, AC_ATTITUDE_ACCEL_RP_CONTROLLER_MAX_RADSS), _dt); + rate_target_ang_vel.y = sqrt_controller(attitude_error_rot_vec_rad.y, angleP_pitch, constrain_float(get_accel_pitch_max_radss() / 2.0f, AC_ATTITUDE_ACCEL_RP_CONTROLLER_MIN_RADSS, AC_ATTITUDE_ACCEL_RP_CONTROLLER_MAX_RADSS), _dt); } else { - rate_target_ang_vel.y = _p_angle_pitch.kP() * attitude_error_rot_vec_rad.y; + rate_target_ang_vel.y = angleP_pitch * attitude_error_rot_vec_rad.y; } // Compute the yaw angular velocity demand from the yaw angle error + const float angleP_yaw = _p_angle_yaw.kP() * _angle_P_scale.z; if (_use_sqrt_controller && !is_zero(get_accel_yaw_max_radss())) { - rate_target_ang_vel.z = sqrt_controller(attitude_error_rot_vec_rad.z, _p_angle_yaw.kP(), constrain_float(get_accel_yaw_max_radss() / 2.0f, AC_ATTITUDE_ACCEL_Y_CONTROLLER_MIN_RADSS, AC_ATTITUDE_ACCEL_Y_CONTROLLER_MAX_RADSS), _dt); + rate_target_ang_vel.z = sqrt_controller(attitude_error_rot_vec_rad.z, angleP_yaw, constrain_float(get_accel_yaw_max_radss() / 2.0f, AC_ATTITUDE_ACCEL_Y_CONTROLLER_MIN_RADSS, AC_ATTITUDE_ACCEL_Y_CONTROLLER_MAX_RADSS), _dt); } else { - rate_target_ang_vel.z = _p_angle_yaw.kP() * attitude_error_rot_vec_rad.z; + rate_target_ang_vel.z = angleP_yaw * attitude_error_rot_vec_rad.z; } + + // reset angle P scaling, saving used value for logging + _angle_P_scale_used = _angle_P_scale; + _angle_P_scale = Vector3f{1,1,1}; + return rate_target_ang_vel; } @@ -1010,9 +1036,9 @@ void AC_AttitudeControl::accel_limiting(bool enable_limits) _accel_yaw_max.load(); } } else { - _accel_roll_max = 0.0f; - _accel_pitch_max = 0.0f; - _accel_yaw_max = 0.0f; + _accel_roll_max.set(0.0f); + _accel_pitch_max.set(0.0f); + _accel_yaw_max.set(0.0f); } } @@ -1026,7 +1052,8 @@ float AC_AttitudeControl::get_althold_lean_angle_max_cd() const // Return roll rate step size in centidegrees/s that results in maximum output after 4 time steps float AC_AttitudeControl::max_rate_step_bf_roll() { - float alpha = MIN(get_rate_roll_pid().get_filt_E_alpha(), get_rate_roll_pid().get_filt_D_alpha()); + float dt_average = AP::scheduler().get_filtered_loop_time(); + float alpha = MIN(get_rate_roll_pid().get_filt_E_alpha(dt_average), get_rate_roll_pid().get_filt_D_alpha(dt_average)); float alpha_remaining = 1 - alpha; // todo: When a thrust_max is available we should replace 0.5f with 0.5f * _motors.thrust_max float throttle_hover = constrain_float(_motors.get_throttle_hover(), 0.1f, 0.5f); @@ -1040,7 +1067,8 @@ float AC_AttitudeControl::max_rate_step_bf_roll() // Return pitch rate step size in centidegrees/s that results in maximum output after 4 time steps float AC_AttitudeControl::max_rate_step_bf_pitch() { - float alpha = MIN(get_rate_pitch_pid().get_filt_E_alpha(), get_rate_pitch_pid().get_filt_D_alpha()); + float dt_average = AP::scheduler().get_filtered_loop_time(); + float alpha = MIN(get_rate_pitch_pid().get_filt_E_alpha(dt_average), get_rate_pitch_pid().get_filt_D_alpha(dt_average)); float alpha_remaining = 1 - alpha; // todo: When a thrust_max is available we should replace 0.5f with 0.5f * _motors.thrust_max float throttle_hover = constrain_float(_motors.get_throttle_hover(), 0.1f, 0.5f); @@ -1054,7 +1082,8 @@ float AC_AttitudeControl::max_rate_step_bf_pitch() // Return yaw rate step size in centidegrees/s that results in maximum output after 4 time steps float AC_AttitudeControl::max_rate_step_bf_yaw() { - float alpha = MIN(get_rate_yaw_pid().get_filt_E_alpha(), get_rate_yaw_pid().get_filt_D_alpha()); + float dt_average = AP::scheduler().get_filtered_loop_time(); + float alpha = MIN(get_rate_yaw_pid().get_filt_E_alpha(dt_average), get_rate_yaw_pid().get_filt_D_alpha(dt_average)); float alpha_remaining = 1 - alpha; // todo: When a thrust_max is available we should replace 0.5f with 0.5f * _motors.thrust_max float throttle_hover = constrain_float(_motors.get_throttle_hover(), 0.1f, 0.5f); @@ -1129,3 +1158,14 @@ bool AC_AttitudeControl::pre_arm_checks(const char *param_prefix, } return true; } + +/* + get the slew rate for roll, pitch and yaw, for oscillation + detection in lua scripts +*/ +void AC_AttitudeControl::get_rpy_srate(float &roll_srate, float &pitch_srate, float &yaw_srate) +{ + roll_srate = get_rate_roll_pid().get_pid_info().slew_rate; + pitch_srate = get_rate_pitch_pid().get_pid_info().slew_rate; + yaw_srate = get_rate_yaw_pid().get_pid_info().slew_rate; +} diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.h b/libraries/AC_AttitudeControl/AC_AttitudeControl.h index 9e357ff54c0..887dabc4fda 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.h @@ -35,7 +35,6 @@ #define AC_ATTITUDE_CONTROL_ANGLE_LIMIT_TC_DEFAULT 1.0f // Time constant used to limit lean angle so that vehicle does not lose altitude #define AC_ATTITUDE_CONTROL_ANGLE_LIMIT_THROTTLE_MAX 0.8f // Max throttle used to limit lean angle so that vehicle does not lose altitude -#define AC_ATTITUDE_CONTROL_ANGLE_LIMIT_MIN 10.0f // Min lean angle so that vehicle can maintain limited control #define AC_ATTITUDE_CONTROL_MIN_DEFAULT 0.1f // minimum throttle mix default #define AC_ATTITUDE_CONTROL_MAN_DEFAULT 0.1f // manual throttle mix default @@ -50,12 +49,10 @@ class AC_AttitudeControl { public: AC_AttitudeControl( AP_AHRS_View &ahrs, const AP_Vehicle::MultiCopter &aparm, - AP_Motors& motors, - float dt) : + AP_Motors& motors) : _p_angle_roll(AC_ATTITUDE_CONTROL_ANGLE_P), _p_angle_pitch(AC_ATTITUDE_CONTROL_ANGLE_P), _p_angle_yaw(AC_ATTITUDE_CONTROL_ANGLE_P), - _dt(dt), _angle_boost(0), _use_sqrt_controller(true), _throttle_rpy_mix_desired(AC_ATTITUDE_CONTROL_THR_MIX_DEFAULT), @@ -64,12 +61,23 @@ class AC_AttitudeControl { _aparm(aparm), _motors(motors) { + _singleton = this; AP_Param::setup_object_defaults(this, var_info); } + static AC_AttitudeControl *get_singleton(void) { + return _singleton; + } + // Empty destructor to suppress compiler warning virtual ~AC_AttitudeControl() {} + // set_dt / get_dt - dt is the time since the last time the attitude controllers were updated + // _dt should be set based on the time of the last IMU read used by these controllers + // the attitude controller should run updates for active controllers on each loop to ensure normal operation + void set_dt(float dt) { _dt = dt; } + float get_dt() const { return _dt; } + // pid accessors AC_P& get_angle_roll_p() { return _p_angle_roll; } AC_P& get_angle_pitch_p() { return _p_angle_pitch; } @@ -83,7 +91,7 @@ class AC_AttitudeControl { float get_accel_roll_max_radss() const { return radians(_accel_roll_max * 0.01f); } // Sets the roll acceleration limit in centidegrees/s/s - void set_accel_roll_max_cdss(float accel_roll_max) { _accel_roll_max = accel_roll_max; } + void set_accel_roll_max_cdss(float accel_roll_max) { _accel_roll_max.set(accel_roll_max); } // Sets and saves the roll acceleration limit in centidegrees/s/s void save_accel_roll_max_cdss(float accel_roll_max) { _accel_roll_max.set_and_save(accel_roll_max); } @@ -93,7 +101,7 @@ class AC_AttitudeControl { float get_accel_pitch_max_radss() const { return radians(_accel_pitch_max * 0.01f); } // Sets the pitch acceleration limit in centidegrees/s/s - void set_accel_pitch_max_cdss(float accel_pitch_max) { _accel_pitch_max = accel_pitch_max; } + void set_accel_pitch_max_cdss(float accel_pitch_max) { _accel_pitch_max.set(accel_pitch_max); } // Sets and saves the pitch acceleration limit in centidegrees/s/s void save_accel_pitch_max_cdss(float accel_pitch_max) { _accel_pitch_max.set_and_save(accel_pitch_max); } @@ -103,7 +111,7 @@ class AC_AttitudeControl { float get_accel_yaw_max_radss() const { return radians(_accel_yaw_max * 0.01f); } // Sets the yaw acceleration limit in centidegrees/s/s - void set_accel_yaw_max_cdss(float accel_yaw_max) { _accel_yaw_max = accel_yaw_max; } + void set_accel_yaw_max_cdss(float accel_yaw_max) { _accel_yaw_max.set(accel_yaw_max); } // Sets and saves the yaw acceleration limit in centidegrees/s/s void save_accel_yaw_max_cdss(float accel_yaw_max) { _accel_yaw_max.set_and_save(accel_yaw_max); } @@ -124,7 +132,7 @@ class AC_AttitudeControl { float get_input_tc() const { return _input_tc; } // set the rate control input smoothing time constant - void set_input_tc(float input_tc) { _input_tc = constrain_float(input_tc, 0.0f, 1.0f); } + void set_input_tc(float input_tc) { _input_tc.set(constrain_float(input_tc, 0.0f, 1.0f)); } // Ensure attitude controller have zero errors to relax rate controller output void relax_attitude_controllers(); @@ -179,7 +187,7 @@ class AC_AttitudeControl { virtual void input_angle_step_bf_roll_pitch_yaw(float roll_angle_step_bf_cd, float pitch_angle_step_bf_cd, float yaw_angle_step_bf_cd); // Command a thrust vector in the earth frame and a heading angle and/or rate - virtual void input_thrust_vector_rate_heading(const Vector3f& thrust_vector, float heading_rate_cds); + virtual void input_thrust_vector_rate_heading(const Vector3f& thrust_vector, float heading_rate_cds, bool slew_yaw = true); virtual void input_thrust_vector_heading(const Vector3f& thrust_vector, float heading_angle_cd, float heading_rate_cds); void input_thrust_vector_heading(const Vector3f& thrust_vector, float heading_cd) {input_thrust_vector_heading(thrust_vector, heading_cd, 0.0f);} @@ -264,8 +272,11 @@ class AC_AttitudeControl { // Return angular velocity in radians used in the angular velocity controller Vector3f rate_bf_targets() const { return _ang_vel_body + _sysid_ang_vel_body; } + // return the angular velocity of the target (setpoint) attitude rad/s + const Vector3f& get_rate_ef_targets() const { return _euler_rate_target; } + // Enable or disable body-frame feed forward - void bf_feedforward(bool enable_or_disable) { _rate_bf_ff_enabled = enable_or_disable; } + void bf_feedforward(bool enable_or_disable) { _rate_bf_ff_enabled.set(enable_or_disable); } // Enable or disable body-frame feed forward and save void bf_feedforward_save(bool enable_or_disable) { _rate_bf_ff_enabled.set_and_save(enable_or_disable); } @@ -302,8 +313,8 @@ class AC_AttitudeControl { static float input_shaping_angle(float error_angle, float input_tc, float accel_max, float target_ang_vel, float desired_ang_vel, float max_ang_vel, float dt); static float input_shaping_angle(float error_angle, float input_tc, float accel_max, float target_ang_vel, float dt){ return input_shaping_angle(error_angle, input_tc, accel_max, target_ang_vel, 0.0f, 0.0f, dt); } - // limits the acceleration and deceleration of a velocity request - static float input_shaping_ang_vel(float target_ang_vel, float desired_ang_vel, float accel_max, float dt); + // Shapes the velocity request based on a rate time constant. The angular acceleration and deceleration is limited. + static float input_shaping_ang_vel(float target_ang_vel, float desired_ang_vel, float accel_max, float dt, float input_tc); // calculates the expected angular velocity correction from an angle error based on the AC_AttitudeControl settings. // This function can be used to predict the delay associated with angle requests. @@ -362,6 +373,28 @@ class AC_AttitudeControl { // enable inverted flight on backends that support it virtual void set_inverted_flight(bool inverted) {} + + // get the slew rate value for roll, pitch and yaw, for oscillation detection in lua scripts + void get_rpy_srate(float &roll_srate, float &pitch_srate, float &yaw_srate); + + // Sets the roll and pitch rate shaping time constant + void set_roll_pitch_rate_tc(float input_tc) { _rate_rp_tc = input_tc; } + + // Sets the yaw rate shaping time constant + void set_yaw_rate_tc(float input_tc) { _rate_y_tc = input_tc; } + + // setup a one loop angle P scale multiplier. This replaces any previous scale applied + // so should only be used when only one source of scaling is needed + void set_angle_P_scale(const Vector3f &angle_P_scale) { _angle_P_scale = angle_P_scale; } + + // setup a one loop angle P scale multiplier, multiplying by any + // previously applied scale from this loop. This allows for more + // than one type of scale factor to be applied for different + // purposes + void set_angle_P_scale_mult(const Vector3f &angle_P_scale) { _angle_P_scale *= angle_P_scale; } + + // get the value of the angle P scale that was used in the last loop, for logging + const Vector3f &get_angle_P_scale_logging(void) const { return _angle_P_scale_used; } // User settable parameters static const struct AP_Param::GroupInfo var_info[]; @@ -437,12 +470,12 @@ class AC_AttitudeControl { // velocity controller. Vector3f _ang_vel_body; - // This is the the angular velocity in radians per second in the body frame, added to the output angular + // This is the angular velocity in radians per second in the body frame, added to the output angular // attitude controller by the System Identification Mode. // It is reset to zero immediately after it is used. Vector3f _sysid_ang_vel_body; - // This is the the unitless value added to the output of the PID by the System Identification Mode. + // This is the unitless value added to the output of the PID by the System Identification Mode. // It is reset to zero immediately after it is used. Vector3f _actuator_sysid; @@ -478,11 +511,23 @@ class AC_AttitudeControl { // Yaw feed forward percent to allow zero yaw actuator output during extreme roll and pitch corrections float _feedforward_scalar = 1.0f; + // rate controller input smoothing time constant + float _rate_rp_tc; + float _rate_y_tc; + + // angle P scaling vector for roll, pitch, yaw + Vector3f _angle_P_scale{1,1,1}; + + // angle scale used for last loop, used for logging + Vector3f _angle_P_scale_used; + // References to external libraries const AP_AHRS_View& _ahrs; const AP_Vehicle::MultiCopter &_aparm; AP_Motors& _motors; + static AC_AttitudeControl *_singleton; + protected: /* state of control monitoring diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp index 7d99b4d43ef..371b5001bdc 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp @@ -387,13 +387,13 @@ void AC_AttitudeControl_Heli::rate_bf_to_motor_roll_pitch(const Vector3f &rate_r if (_flags_heli.leaky_i) { _pid_rate_roll.update_leaky_i(AC_ATTITUDE_HELI_RATE_INTEGRATOR_LEAK_RATE); } - float roll_pid = _pid_rate_roll.update_all(rate_roll_target_rads, rate_rads.x, _motors.limit.roll) + _actuator_sysid.x; + float roll_pid = _pid_rate_roll.update_all(rate_roll_target_rads, rate_rads.x, _dt, _motors.limit.roll) + _actuator_sysid.x; if (_flags_heli.leaky_i) { _pid_rate_pitch.update_leaky_i(AC_ATTITUDE_HELI_RATE_INTEGRATOR_LEAK_RATE); } - float pitch_pid = _pid_rate_pitch.update_all(rate_pitch_target_rads, rate_rads.y, _motors.limit.pitch) + _actuator_sysid.y; + float pitch_pid = _pid_rate_pitch.update_all(rate_pitch_target_rads, rate_rads.y, _dt, _motors.limit.pitch) + _actuator_sysid.y; // use pid library to calculate ff float roll_ff = _pid_rate_roll.get_ff(); @@ -449,7 +449,7 @@ float AC_AttitudeControl_Heli::rate_target_to_motor_yaw(float rate_yaw_actual_ra _pid_rate_yaw.update_leaky_i(AC_ATTITUDE_HELI_RATE_INTEGRATOR_LEAK_RATE); } - float pid = _pid_rate_yaw.update_all(rate_target_rads, rate_yaw_actual_rads, _motors.limit.yaw) + _actuator_sysid.z; + float pid = _pid_rate_yaw.update_all(rate_target_rads, rate_yaw_actual_rads, _dt, _motors.limit.yaw) + _actuator_sysid.z; // use pid library to calculate ff float vff = _pid_rate_yaw.get_ff()*_feedforward_scalar; diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h index a8028839518..1d6e5bb9c48 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h @@ -33,12 +33,11 @@ class AC_AttitudeControl_Heli : public AC_AttitudeControl { public: AC_AttitudeControl_Heli( AP_AHRS_View &ahrs, const AP_Vehicle::MultiCopter &aparm, - AP_MotorsHeli& motors, - float dt) : - AC_AttitudeControl(ahrs, aparm, motors, dt), - _pid_rate_roll(AC_ATC_HELI_RATE_RP_P, AC_ATC_HELI_RATE_RP_I, AC_ATC_HELI_RATE_RP_D, AC_ATC_HELI_RATE_RP_FF, AC_ATC_HELI_RATE_RP_IMAX, AC_ATTITUDE_HELI_RATE_RP_FF_FILTER, AC_ATC_HELI_RATE_RP_FILT_HZ, 0.0f, dt), - _pid_rate_pitch(AC_ATC_HELI_RATE_RP_P, AC_ATC_HELI_RATE_RP_I, AC_ATC_HELI_RATE_RP_D, AC_ATC_HELI_RATE_RP_FF, AC_ATC_HELI_RATE_RP_IMAX, AC_ATTITUDE_HELI_RATE_RP_FF_FILTER, AC_ATC_HELI_RATE_RP_FILT_HZ, 0.0f, dt), - _pid_rate_yaw(AC_ATC_HELI_RATE_YAW_P, AC_ATC_HELI_RATE_YAW_I, AC_ATC_HELI_RATE_YAW_D, AC_ATC_HELI_RATE_YAW_FF, AC_ATC_HELI_RATE_YAW_IMAX, AC_ATTITUDE_HELI_RATE_Y_FF_FILTER, AC_ATC_HELI_RATE_YAW_FILT_HZ, 0.0f, dt) + AP_MotorsHeli& motors) : + AC_AttitudeControl(ahrs, aparm, motors), + _pid_rate_roll(AC_ATC_HELI_RATE_RP_P, AC_ATC_HELI_RATE_RP_I, AC_ATC_HELI_RATE_RP_D, AC_ATC_HELI_RATE_RP_FF, AC_ATC_HELI_RATE_RP_IMAX, AC_ATTITUDE_HELI_RATE_RP_FF_FILTER, AC_ATC_HELI_RATE_RP_FILT_HZ, 0.0f), + _pid_rate_pitch(AC_ATC_HELI_RATE_RP_P, AC_ATC_HELI_RATE_RP_I, AC_ATC_HELI_RATE_RP_D, AC_ATC_HELI_RATE_RP_FF, AC_ATC_HELI_RATE_RP_IMAX, AC_ATTITUDE_HELI_RATE_RP_FF_FILTER, AC_ATC_HELI_RATE_RP_FILT_HZ, 0.0f), + _pid_rate_yaw(AC_ATC_HELI_RATE_YAW_P, AC_ATC_HELI_RATE_YAW_I, AC_ATC_HELI_RATE_YAW_D, AC_ATC_HELI_RATE_YAW_FF, AC_ATC_HELI_RATE_YAW_IMAX, AC_ATTITUDE_HELI_RATE_Y_FF_FILTER, AC_ATC_HELI_RATE_YAW_FILT_HZ, 0.0f) { AP_Param::setup_object_defaults(this, var_info); diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp index 0ac8e41b90b..deb26aa6ec5 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp @@ -235,12 +235,12 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = { AP_GROUPEND }; -AC_AttitudeControl_Multi::AC_AttitudeControl_Multi(AP_AHRS_View &ahrs, const AP_Vehicle::MultiCopter &aparm, AP_MotorsMulticopter& motors, float dt) : - AC_AttitudeControl(ahrs, aparm, motors, dt), +AC_AttitudeControl_Multi::AC_AttitudeControl_Multi(AP_AHRS_View &ahrs, const AP_Vehicle::MultiCopter &aparm, AP_MotorsMulticopter& motors) : + AC_AttitudeControl(ahrs, aparm, motors), _motors_multi(motors), - _pid_rate_roll(AC_ATC_MULTI_RATE_RP_P, AC_ATC_MULTI_RATE_RP_I, AC_ATC_MULTI_RATE_RP_D, 0.0f, AC_ATC_MULTI_RATE_RP_IMAX, AC_ATC_MULTI_RATE_RP_FILT_HZ, 0.0f, AC_ATC_MULTI_RATE_RP_FILT_HZ, dt), - _pid_rate_pitch(AC_ATC_MULTI_RATE_RP_P, AC_ATC_MULTI_RATE_RP_I, AC_ATC_MULTI_RATE_RP_D, 0.0f, AC_ATC_MULTI_RATE_RP_IMAX, AC_ATC_MULTI_RATE_RP_FILT_HZ, 0.0f, AC_ATC_MULTI_RATE_RP_FILT_HZ, dt), - _pid_rate_yaw(AC_ATC_MULTI_RATE_YAW_P, AC_ATC_MULTI_RATE_YAW_I, AC_ATC_MULTI_RATE_YAW_D, 0.0f, AC_ATC_MULTI_RATE_YAW_IMAX, AC_ATC_MULTI_RATE_RP_FILT_HZ, AC_ATC_MULTI_RATE_YAW_FILT_HZ, 0.0f, dt) + _pid_rate_roll(AC_ATC_MULTI_RATE_RP_P, AC_ATC_MULTI_RATE_RP_I, AC_ATC_MULTI_RATE_RP_D, 0.0f, AC_ATC_MULTI_RATE_RP_IMAX, AC_ATC_MULTI_RATE_RP_FILT_HZ, 0.0f, AC_ATC_MULTI_RATE_RP_FILT_HZ), + _pid_rate_pitch(AC_ATC_MULTI_RATE_RP_P, AC_ATC_MULTI_RATE_RP_I, AC_ATC_MULTI_RATE_RP_D, 0.0f, AC_ATC_MULTI_RATE_RP_IMAX, AC_ATC_MULTI_RATE_RP_FILT_HZ, 0.0f, AC_ATC_MULTI_RATE_RP_FILT_HZ), + _pid_rate_yaw(AC_ATC_MULTI_RATE_YAW_P, AC_ATC_MULTI_RATE_YAW_I, AC_ATC_MULTI_RATE_YAW_D, 0.0f, AC_ATC_MULTI_RATE_YAW_IMAX, AC_ATC_MULTI_RATE_RP_FILT_HZ, AC_ATC_MULTI_RATE_YAW_FILT_HZ, 0.0f) { AP_Param::setup_object_defaults(this, var_info); } @@ -322,6 +322,20 @@ void AC_AttitudeControl_Multi::update_throttle_rpy_mix() } else if (_throttle_rpy_mix > _throttle_rpy_mix_desired) { // reduce more slowly (from 0.9 to 0.1 in 1.6 seconds) _throttle_rpy_mix -= MIN(0.5f * _dt, _throttle_rpy_mix - _throttle_rpy_mix_desired); + + // if the mix is still higher than that being used, reset immediately + const float throttle_hover = _motors.get_throttle_hover(); + const float throttle_in = _motors.get_throttle(); + const float throttle_out = MAX(_motors.get_throttle_out(), throttle_in); + float mix_used; + // since throttle_out >= throttle_in at this point we don't need to check throttle_in < throttle_hover + if (throttle_out < throttle_hover) { + mix_used = (throttle_out - throttle_in) / (throttle_hover - throttle_in); + } else { + mix_used = throttle_out / throttle_hover; + } + + _throttle_rpy_mix = MIN(_throttle_rpy_mix, MAX(mix_used, _throttle_rpy_mix_desired)); } _throttle_rpy_mix = constrain_float(_throttle_rpy_mix, 0.1f, AC_ATTITUDE_CONTROL_MAX); } @@ -335,13 +349,13 @@ void AC_AttitudeControl_Multi::rate_controller_run() Vector3f gyro_latest = _ahrs.get_gyro_latest(); - _motors.set_roll(get_rate_roll_pid().update_all(_ang_vel_body.x, gyro_latest.x, _motors.limit.roll) + _actuator_sysid.x); + _motors.set_roll(get_rate_roll_pid().update_all(_ang_vel_body.x, gyro_latest.x, _dt, _motors.limit.roll) + _actuator_sysid.x); _motors.set_roll_ff(get_rate_roll_pid().get_ff()); - _motors.set_pitch(get_rate_pitch_pid().update_all(_ang_vel_body.y, gyro_latest.y, _motors.limit.pitch) + _actuator_sysid.y); + _motors.set_pitch(get_rate_pitch_pid().update_all(_ang_vel_body.y, gyro_latest.y, _dt, _motors.limit.pitch) + _actuator_sysid.y); _motors.set_pitch_ff(get_rate_pitch_pid().get_ff()); - _motors.set_yaw(get_rate_yaw_pid().update_all(_ang_vel_body.z, gyro_latest.z, _motors.limit.yaw) + _actuator_sysid.z); + _motors.set_yaw(get_rate_yaw_pid().update_all(_ang_vel_body.z, gyro_latest.z, _dt, _motors.limit.yaw) + _actuator_sysid.z); _motors.set_yaw_ff(get_rate_yaw_pid().get_ff()*_feedforward_scalar); _sysid_ang_vel_body.zero(); diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h index 28bccb33cfe..8fd11d5b4d4 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h @@ -41,7 +41,7 @@ class AC_AttitudeControl_Multi : public AC_AttitudeControl { public: - AC_AttitudeControl_Multi(AP_AHRS_View &ahrs, const AP_Vehicle::MultiCopter &aparm, AP_MotorsMulticopter& motors, float dt); + AC_AttitudeControl_Multi(AP_AHRS_View &ahrs, const AP_Vehicle::MultiCopter &aparm, AP_MotorsMulticopter& motors); // empty destructor to suppress compiler warning virtual ~AC_AttitudeControl_Multi() {} diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.cpp index 5cea0ab08b0..6a2c75f2a8c 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.cpp @@ -49,7 +49,7 @@ void AC_AttitudeControl_Multi_6DoF::input_euler_angle_roll_pitch_yaw(float euler } // Command a thrust vector and heading rate -void AC_AttitudeControl_Multi_6DoF::input_thrust_vector_rate_heading(const Vector3f& thrust_vector, float heading_rate_cds) +void AC_AttitudeControl_Multi_6DoF::input_thrust_vector_rate_heading(const Vector3f& thrust_vector, float heading_rate_cds, bool slew_yaw) { // convert thrust vector to a roll and pitch angles // this negates the advantage of using thrust vector control, but works just fine diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.h b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.h index 76deec376ff..68929acd534 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.h @@ -5,8 +5,8 @@ class AC_AttitudeControl_Multi_6DoF : public AC_AttitudeControl_Multi { public: - AC_AttitudeControl_Multi_6DoF(AP_AHRS_View &ahrs, const AP_Vehicle::MultiCopter &aparm, AP_MotorsMulticopter& motors, float dt): - AC_AttitudeControl_Multi(ahrs,aparm,motors,dt) { + AC_AttitudeControl_Multi_6DoF(AP_AHRS_View &ahrs, const AP_Vehicle::MultiCopter &aparm, AP_MotorsMulticopter& motors): + AC_AttitudeControl_Multi(ahrs,aparm,motors) { if (_singleton != nullptr) { AP_HAL::panic("Can only be one AC_AttitudeControl_Multi_6DoF"); @@ -33,7 +33,7 @@ class AC_AttitudeControl_Multi_6DoF : public AC_AttitudeControl_Multi { void input_euler_angle_roll_pitch_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_angle_cd, bool slew_yaw) override; // Command a thrust vector in the earth frame and a heading angle and/or rate - void input_thrust_vector_rate_heading(const Vector3f& thrust_vector, float heading_rate_cds) override; + void input_thrust_vector_rate_heading(const Vector3f& thrust_vector, float heading_rate_cds, bool slew_yaw = true) override; void input_thrust_vector_heading(const Vector3f& thrust_vector, float heading_angle_cd, float heading_rate_cds) override; /* diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp index bd0e6e30e55..a511e1de7d3 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp @@ -259,12 +259,12 @@ const AP_Param::GroupInfo AC_AttitudeControl_Sub::var_info[] = { AP_GROUPEND }; -AC_AttitudeControl_Sub::AC_AttitudeControl_Sub(AP_AHRS_View &ahrs, const AP_Vehicle::MultiCopter &aparm, AP_MotorsMulticopter& motors, float dt) : - AC_AttitudeControl(ahrs, aparm, motors, dt), +AC_AttitudeControl_Sub::AC_AttitudeControl_Sub(AP_AHRS_View &ahrs, const AP_Vehicle::MultiCopter &aparm, AP_MotorsMulticopter& motors) : + AC_AttitudeControl(ahrs, aparm, motors), _motors_multi(motors), - _pid_rate_roll(AC_ATC_SUB_RATE_RP_P, AC_ATC_SUB_RATE_RP_I, AC_ATC_SUB_RATE_RP_D, 0.0f, AC_ATC_SUB_RATE_RP_IMAX, AC_ATC_SUB_RATE_RP_FILT_HZ, 0.0f, AC_ATC_SUB_RATE_RP_FILT_HZ, dt), - _pid_rate_pitch(AC_ATC_SUB_RATE_RP_P, AC_ATC_SUB_RATE_RP_I, AC_ATC_SUB_RATE_RP_D, 0.0f, AC_ATC_SUB_RATE_RP_IMAX, AC_ATC_SUB_RATE_RP_FILT_HZ, 0.0f, AC_ATC_SUB_RATE_RP_FILT_HZ, dt), - _pid_rate_yaw(AC_ATC_SUB_RATE_YAW_P, AC_ATC_SUB_RATE_YAW_I, AC_ATC_SUB_RATE_YAW_D, 0.0f, AC_ATC_SUB_RATE_YAW_IMAX, AC_ATC_SUB_RATE_YAW_FILT_HZ, 0.0f, AC_ATC_SUB_RATE_YAW_FILT_HZ, dt) + _pid_rate_roll(AC_ATC_SUB_RATE_RP_P, AC_ATC_SUB_RATE_RP_I, AC_ATC_SUB_RATE_RP_D, 0.0f, AC_ATC_SUB_RATE_RP_IMAX, AC_ATC_SUB_RATE_RP_FILT_HZ, 0.0f, AC_ATC_SUB_RATE_RP_FILT_HZ), + _pid_rate_pitch(AC_ATC_SUB_RATE_RP_P, AC_ATC_SUB_RATE_RP_I, AC_ATC_SUB_RATE_RP_D, 0.0f, AC_ATC_SUB_RATE_RP_IMAX, AC_ATC_SUB_RATE_RP_FILT_HZ, 0.0f, AC_ATC_SUB_RATE_RP_FILT_HZ), + _pid_rate_yaw(AC_ATC_SUB_RATE_YAW_P, AC_ATC_SUB_RATE_YAW_I, AC_ATC_SUB_RATE_YAW_D, 0.0f, AC_ATC_SUB_RATE_YAW_IMAX, AC_ATC_SUB_RATE_YAW_FILT_HZ, 0.0f, AC_ATC_SUB_RATE_YAW_FILT_HZ) { AP_Param::setup_object_defaults(this, var_info); @@ -356,9 +356,9 @@ void AC_AttitudeControl_Sub::rate_controller_run() update_throttle_rpy_mix(); Vector3f gyro_latest = _ahrs.get_gyro_latest(); - _motors.set_roll(get_rate_roll_pid().update_all(_ang_vel_body.x, gyro_latest.x, _motors.limit.roll)); - _motors.set_pitch(get_rate_pitch_pid().update_all(_ang_vel_body.y, gyro_latest.y, _motors.limit.pitch)); - _motors.set_yaw(get_rate_yaw_pid().update_all(_ang_vel_body.z, gyro_latest.z, _motors.limit.yaw)); + _motors.set_roll(get_rate_roll_pid().update_all(_ang_vel_body.x, gyro_latest.x, _dt, _motors.limit.roll)); + _motors.set_pitch(get_rate_pitch_pid().update_all(_ang_vel_body.y, gyro_latest.y, _dt, _motors.limit.pitch)); + _motors.set_yaw(get_rate_yaw_pid().update_all(_ang_vel_body.z, gyro_latest.z, _dt, _motors.limit.yaw)); control_monitor_update(); } diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.h b/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.h index b460daf26be..6b7fb3bca41 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.h @@ -25,7 +25,7 @@ class AC_AttitudeControl_Sub : public AC_AttitudeControl { public: - AC_AttitudeControl_Sub(AP_AHRS_View &ahrs, const AP_Vehicle::MultiCopter &aparm, AP_MotorsMulticopter& motors, float dt); + AC_AttitudeControl_Sub(AP_AHRS_View &ahrs, const AP_Vehicle::MultiCopter &aparm, AP_MotorsMulticopter& motors); // empty destructor to suppress compiler warning virtual ~AC_AttitudeControl_Sub() {} diff --git a/libraries/AC_AttitudeControl/AC_CommandModel.cpp b/libraries/AC_AttitudeControl/AC_CommandModel.cpp new file mode 100644 index 00000000000..6646161e1af --- /dev/null +++ b/libraries/AC_AttitudeControl/AC_CommandModel.cpp @@ -0,0 +1,49 @@ +#include "AC_CommandModel.h" +#include + +// The Commmand Model class holds parameters that shape the pilot desired angular rate input. This class can +// be expanded to hold the methods that shape the pilot desired input. + +extern const AP_HAL::HAL& hal; + +// table of user settable parameters +const AP_Param::GroupInfo AC_CommandModel::var_info[] = { + + // @Param: RATE + // @DisplayName: Maximum Controlled Rate + // @Description: Sets the maximum rate commanded. + // @Units: deg/s + // @Range: 1 360 + // @User: Standard + AP_GROUPINFO("RATE", 1, AC_CommandModel, rate, 202.5), + + // @Param: EXPO + // @DisplayName: Controlled Expo + // @Description: Controlled expo to allow faster rotation when stick at edges + // @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High + // @Range: -0.5 1.0 + // @User: Advanced + AP_GROUPINFO("EXPO", 2, AC_CommandModel, expo, 0), + + // @Param: RATE_TC + // @DisplayName: Rate control input time constant + // @Description: Rate control input time constant. Low numbers lead to sharper response, higher numbers to softer response + // @Units: s + // @Range: 0 1 + // @Increment: 0.01 + // @Values: 0.5:Very Soft, 0.2:Soft, 0.15:Medium, 0.1:Crisp, 0.05:Very Crisp + // @User: Standard + AP_GROUPINFO("RATE_TC", 3, AC_CommandModel, rate_tc, 0.05f), + + AP_GROUPEND +}; + +// Constructor +AC_CommandModel::AC_CommandModel(float initial_rate, float initial_expo, float initial_tc) +{ + AP_Param::setup_object_defaults(this, var_info); + rate.set_and_default(initial_rate); + expo.set_and_default(initial_expo); + rate_tc.set_and_default(initial_tc); +} + diff --git a/libraries/AC_AttitudeControl/AC_CommandModel.h b/libraries/AC_AttitudeControl/AC_CommandModel.h new file mode 100644 index 00000000000..dd99031474d --- /dev/null +++ b/libraries/AC_AttitudeControl/AC_CommandModel.h @@ -0,0 +1,33 @@ +#pragma once + +/// @file AC_CommandModel.h +/// @brief ArduCopter Command Model Library + +#include + +/* + Command model parameters + */ + +class AC_CommandModel { +public: + AC_CommandModel(float initial_rate, float initial_expo, float initial_tc); + + // Accessors for parameters + float get_rate_tc() const { return rate_tc; } + float get_rate() const { return rate; } + float get_expo() const { return expo; } + + // Set the max rate + void set_rate(float input) { rate.set(input); } + + // var_info for holding Parameter information + static const struct AP_Param::GroupInfo var_info[]; + +protected: + AP_Float rate_tc; // rate time constant + AP_Float rate; // maximum rate + AP_Float expo; // expo shaping + +}; + diff --git a/libraries/AC_AttitudeControl/AC_PosControl.cpp b/libraries/AC_AttitudeControl/AC_PosControl.cpp index 0f8b6e7c48b..1ed4ea3d5d2 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.cpp +++ b/libraries/AC_AttitudeControl/AC_PosControl.cpp @@ -2,6 +2,9 @@ #include "AC_PosControl.h" #include #include +#include // motors library +#include +#include extern const AP_HAL::HAL& hal; @@ -18,10 +21,10 @@ extern const AP_HAL::HAL& hal; # define POSCONTROL_ACC_Z_IMAX 800 // vertical acceleration controller IMAX gain default # define POSCONTROL_ACC_Z_FILT_HZ 10.0f // vertical acceleration controller input filter default # define POSCONTROL_ACC_Z_DT 0.02f // vertical acceleration controller dt default - # define POSCONTROL_POS_XY_P 1.0f // horizontal position controller P gain default - # define POSCONTROL_VEL_XY_P 1.4f // horizontal velocity controller P gain default - # define POSCONTROL_VEL_XY_I 0.7f // horizontal velocity controller I gain default - # define POSCONTROL_VEL_XY_D 0.35f // horizontal velocity controller D gain default + # define POSCONTROL_POS_XY_P 0.5f // horizontal position controller P gain default + # define POSCONTROL_VEL_XY_P 0.7f // horizontal velocity controller P gain default + # define POSCONTROL_VEL_XY_I 0.35f // horizontal velocity controller I gain default + # define POSCONTROL_VEL_XY_D 0.17f // horizontal velocity controller D gain default # define POSCONTROL_VEL_XY_IMAX 1000.0f // horizontal velocity controller IMAX gain default # define POSCONTROL_VEL_XY_FILT_HZ 5.0f // horizontal velocity controller input filter # define POSCONTROL_VEL_XY_FILT_D_HZ 5.0f // horizontal velocity controller input filter for D @@ -298,17 +301,16 @@ const AP_Param::GroupInfo AC_PosControl::var_info[] = { // their values. // AC_PosControl::AC_PosControl(AP_AHRS_View& ahrs, const AP_InertialNav& inav, - const AP_Motors& motors, AC_AttitudeControl& attitude_control, float dt) : + const AP_Motors& motors, AC_AttitudeControl& attitude_control) : _ahrs(ahrs), _inav(inav), _motors(motors), _attitude_control(attitude_control), - _p_pos_z(POSCONTROL_POS_Z_P, dt), - _pid_vel_z(POSCONTROL_VEL_Z_P, 0.0f, 0.0f, 0.0f, POSCONTROL_VEL_Z_IMAX, POSCONTROL_VEL_Z_FILT_HZ, POSCONTROL_VEL_Z_FILT_D_HZ, dt), - _pid_accel_z(POSCONTROL_ACC_Z_P, POSCONTROL_ACC_Z_I, POSCONTROL_ACC_Z_D, 0.0f, POSCONTROL_ACC_Z_IMAX, 0.0f, POSCONTROL_ACC_Z_FILT_HZ, 0.0f, dt), - _p_pos_xy(POSCONTROL_POS_XY_P, dt), - _pid_vel_xy(POSCONTROL_VEL_XY_P, POSCONTROL_VEL_XY_I, POSCONTROL_VEL_XY_D, 0.0f, POSCONTROL_VEL_XY_IMAX, POSCONTROL_VEL_XY_FILT_HZ, POSCONTROL_VEL_XY_FILT_D_HZ, dt), - _dt(dt), + _p_pos_z(POSCONTROL_POS_Z_P), + _pid_vel_z(POSCONTROL_VEL_Z_P, 0.0f, 0.0f, 0.0f, POSCONTROL_VEL_Z_IMAX, POSCONTROL_VEL_Z_FILT_HZ, POSCONTROL_VEL_Z_FILT_D_HZ), + _pid_accel_z(POSCONTROL_ACC_Z_P, POSCONTROL_ACC_Z_I, POSCONTROL_ACC_Z_D, 0.0f, POSCONTROL_ACC_Z_IMAX, 0.0f, POSCONTROL_ACC_Z_FILT_HZ, 0.0f), + _p_pos_xy(POSCONTROL_POS_XY_P), + _pid_vel_xy(POSCONTROL_VEL_XY_P, POSCONTROL_VEL_XY_I, POSCONTROL_VEL_XY_D, 0.0f, POSCONTROL_VEL_XY_IMAX, POSCONTROL_VEL_XY_FILT_HZ, POSCONTROL_VEL_XY_FILT_D_HZ), _vel_max_down_cms(POSCONTROL_SPEED_DOWN), _vel_max_up_cms(POSCONTROL_SPEED_UP), _vel_max_xy_cms(POSCONTROL_SPEED), @@ -342,8 +344,9 @@ void AC_PosControl::input_pos_xyz(const Vector3p& pos, float pos_offset_z, float _accel_desired.z -= _accel_offset_z; // calculated increased maximum acceleration and jerk if over speed - float accel_max_z_cmss = _accel_max_z_cmss * calculate_overspeed_gain(); - float jerk_max_z_cmsss = _jerk_max_z_cmsss * calculate_overspeed_gain(); + const float overspeed_gain = calculate_overspeed_gain(); + const float accel_max_z_cmss = _accel_max_z_cmss * overspeed_gain; + const float jerk_max_z_cmsss = _jerk_max_z_cmsss * overspeed_gain; update_pos_vel_accel_xy(_pos_target.xy(), _vel_desired.xy(), _accel_desired.xy(), _dt, _limit_vector.xy(), _p_pos_xy.get_error(), _pid_vel_xy.get_error()); @@ -446,26 +449,37 @@ void AC_PosControl::init_xy_controller_stopping_point() get_stopping_point_xy_cm(_pos_target.xy()); _vel_desired.xy().zero(); _accel_desired.xy().zero(); - - _pid_vel_xy.set_integrator(_accel_target); } // relax_velocity_controller_xy - initialise the position controller to the current position and velocity with decaying acceleration. /// This function decays the output acceleration by 95% every half second to achieve a smooth transition to zero requested acceleration. void AC_PosControl::relax_velocity_controller_xy() { + // decay acceleration and therefore current attitude target to zero + // this will be reset by init_xy_controller() if !is_active_xy() + if (is_positive(_dt)) { + float decay = 1.0 - _dt / (_dt + POSCONTROL_RELAX_TC); + _accel_target.xy() *= decay; + } + init_xy_controller(); +} - // decay resultant acceleration and therefore current attitude target to zero - float decay = 1.0 - _dt / (_dt + POSCONTROL_RELAX_TC); +/// reduce response for landing +void AC_PosControl::soften_for_landing_xy() +{ + // decay position error to zero + if (is_positive(_dt)) { + _pos_target.xy() += (_inav.get_position_xy_cm().topostype() - _pos_target.xy()) * (_dt / (_dt + POSCONTROL_RELAX_TC)); + } - _accel_target.xy() *= decay; - _pid_vel_xy.set_integrator(_accel_target - _accel_desired); + // Prevent I term build up in xy velocity controller. + // Note that this flag is reset on each loop in update_xy_controller() + set_externally_limited_xy(); } /// init_xy_controller - initialise the position controller to the current position, velocity, acceleration and attitude. /// This function is the default initialisation for any position control that provides position, velocity and acceleration. -/// This function is private and contains all the shared xy axis initialisation functions void AC_PosControl::init_xy_controller() { // set roll, pitch lean angle targets to current attitude @@ -474,6 +488,7 @@ void AC_PosControl::init_xy_controller() _pitch_target = att_target_euler_cd.y; _yaw_target = att_target_euler_cd.z; // todo: this should be thrust vector heading, not yaw. _yaw_rate_target = 0.0f; + _angle_max_override_cd = 0.0; _pos_target.xy() = _inav.get_position_xy_cm().topostype(); @@ -484,24 +499,26 @@ void AC_PosControl::init_xy_controller() // Set desired accel to zero because raw acceleration is prone to noise _accel_desired.xy().zero(); - lean_angles_to_accel_xy(_accel_target.x, _accel_target.y); + if (!is_active_xy()) { + lean_angles_to_accel_xy(_accel_target.x, _accel_target.y); + } // limit acceleration using maximum lean angles float angle_max = MIN(_attitude_control.get_althold_lean_angle_max_cd(), get_lean_angle_max_cd()); - float accel_max = GRAVITY_MSS * 100.0f * tanf(ToRad(angle_max * 0.01f)); + float accel_max = angle_to_accel(angle_max * 0.01) * 100.0; _accel_target.xy().limit_length(accel_max); // initialise I terms from lean angles _pid_vel_xy.reset_filter(); // initialise the I term to _accel_target - _accel_desired // _accel_desired is zero and can be removed from the equation - _pid_vel_xy.set_integrator(_accel_target); + _pid_vel_xy.set_integrator(_accel_target.xy() - _vel_target.xy() * _pid_vel_xy.ff()); // initialise ekf xy reset handler init_ekf_xy_reset(); // initialise z_controller time out - _last_update_xy_us = AP_HAL::micros64(); + _last_update_xy_us = AP::ins().get_last_update_usec(); } /// input_accel_xy - calculate a jerk limited path from the current position, velocity and acceleration to an input acceleration. @@ -569,10 +586,11 @@ void AC_PosControl::stop_vel_xy_stabilisation() _pid_vel_xy.reset_I(); } -// is_active_xy - returns true if the xy position controller has been run in the previous 5 loop times +// is_active_xy - returns true if the xy position controller has bee n run in the previous 5 loop times bool AC_PosControl::is_active_xy() const { - return ((AP_HAL::micros64() - _last_update_xy_us) <= _dt * 5000000.0); + const uint32_t dt_us = AP::ins().get_last_update_usec() - _last_update_xy_us; + return dt_us <= _dt * 1500000.0; } /// update_xy_controller - runs the horizontal position controller correcting position, velocity and acceleration errors. @@ -592,7 +610,7 @@ void AC_PosControl::update_xy_controller() INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); } } - _last_update_xy_us = AP_HAL::micros64(); + _last_update_xy_us = AP::ins().get_last_update_usec(); float ahrsGndSpdLimit, ahrsControlScaleXY; AP::ahrs().getControlLimits(ahrsGndSpdLimit, ahrsControlScaleXY); @@ -610,7 +628,7 @@ void AC_PosControl::update_xy_controller() // Velocity Controller const Vector2f &curr_vel = _inav.get_velocity_xy_cms(); - Vector2f accel_target = _pid_vel_xy.update_all(_vel_target.xy(), curr_vel, _limit_vector.xy()); + Vector2f accel_target = _pid_vel_xy.update_all(_vel_target.xy(), curr_vel, _dt, _limit_vector.xy()); // acceleration to correct for velocity error and scale PID output to compensate for optical flow measurement induced EKF noise accel_target *= ahrsControlScaleXY; @@ -625,7 +643,7 @@ void AC_PosControl::update_xy_controller() // limit acceleration using maximum lean angles float angle_max = MIN(_attitude_control.get_althold_lean_angle_max_cd(), get_lean_angle_max_cd()); - float accel_max = GRAVITY_MSS * 100.0f * tanf(ToRad(angle_max * 0.01f)); + float accel_max = angle_to_accel(angle_max * 0.01) * 100; // Define the limit vector before we constrain _accel_target _limit_vector.xy() = _accel_target.xy(); if (!limit_accel_xy(_vel_desired.xy(), _accel_target.xy(), accel_max)) { @@ -720,7 +738,7 @@ void AC_PosControl::relax_z_controller(float throttle_setting) // init_z_controller has set the accel PID I term to generate the current throttle set point // Use relax_integrator to decay the throttle set point to throttle_setting - _pid_accel_z.relax_integrator((throttle_setting - _motors.get_throttle_hover()) * 1000.0f, POSCONTROL_RELAX_TC); + _pid_accel_z.relax_integrator((throttle_setting - _motors.get_throttle_hover()) * 1000.0f, _dt, POSCONTROL_RELAX_TC); } /// init_z_controller - initialise the position controller to the current position, velocity, acceleration and attitude. @@ -761,13 +779,11 @@ void AC_PosControl::init_z_controller() init_ekf_z_reset(); // initialise z_controller time out - _last_update_z_us = AP_HAL::micros64(); + _last_update_z_us = AP::ins().get_last_update_usec(); } -/// input_vel_accel_z - calculate a jerk limited path from the current position, velocity and acceleration to an input velocity and acceleration. -/// The vel is projected forwards in time based on a time step of dt and acceleration accel. +/// input_accel_z - calculate a jerk limited path from the current position, velocity and acceleration to an input acceleration. /// The function takes the current position, velocity, and acceleration and calculates the required jerk limited adjustment to the acceleration for the next time dt. -/// The function alters the vel to be the kinematic path based on accel void AC_PosControl::input_accel_z(float accel) { // calculated increased maximum jerk if over speed @@ -783,16 +799,12 @@ void AC_PosControl::input_accel_z(float accel) /// The function takes the current position, velocity, and acceleration and calculates the required jerk limited adjustment to the acceleration for the next time dt. /// The kinematic path is constrained by the maximum acceleration and jerk set using the function set_max_speed_accel_z. /// The parameter limit_output specifies if the velocity and acceleration limits are applied to the sum of commanded and correction values or just correction. -void AC_PosControl::input_vel_accel_z(float &vel, float accel, bool ignore_descent_limit, bool limit_output) +void AC_PosControl::input_vel_accel_z(float &vel, float accel, bool limit_output) { - if (ignore_descent_limit) { - // turn off limits in the negative z direction - _limit_vector.z = MAX(_limit_vector.z, 0.0f); - } - // calculated increased maximum acceleration and jerk if over speed - float accel_max_z_cmss = _accel_max_z_cmss * calculate_overspeed_gain(); - float jerk_max_z_cmsss = _jerk_max_z_cmsss * calculate_overspeed_gain(); + const float overspeed_gain = calculate_overspeed_gain(); + const float accel_max_z_cmss = _accel_max_z_cmss * overspeed_gain; + const float jerk_max_z_cmsss = _jerk_max_z_cmsss * overspeed_gain; // adjust desired alt if motors have not hit their limits update_pos_vel_accel(_pos_target.z, _vel_desired.z, _accel_desired.z, _dt, _limit_vector.z, _p_pos_z.get_error(), _pid_vel_z.get_error()); @@ -816,7 +828,7 @@ void AC_PosControl::set_pos_target_z_from_climb_rate_cm(float vel) _accel_desired.z -= _accel_offset_z; float vel_temp = vel; - input_vel_accel_z(vel_temp, 0, false); + input_vel_accel_z(vel_temp, 0.0); // update the vertical position, velocity and acceleration offsets update_pos_offset_z(_pos_offset_target_z); @@ -832,7 +844,12 @@ void AC_PosControl::set_pos_target_z_from_climb_rate_cm(float vel) /// ignore_descent_limit turns off output saturation handling to aid in landing detection. ignore_descent_limit should be false unless landing. void AC_PosControl::land_at_climb_rate_cm(float vel, bool ignore_descent_limit) { - input_vel_accel_z(vel, 0, ignore_descent_limit); + if (ignore_descent_limit) { + // turn off limits in the negative z direction + _limit_vector.z = MAX(_limit_vector.z, 0.0f); + } + + input_vel_accel_z(vel, 0.0); } /// input_pos_vel_accel_z - calculate a jerk limited path from the current position, velocity and acceleration to an input position velocity and acceleration. @@ -843,8 +860,9 @@ void AC_PosControl::land_at_climb_rate_cm(float vel, bool ignore_descent_limit) void AC_PosControl::input_pos_vel_accel_z(float &pos, float &vel, float accel, bool limit_output) { // calculated increased maximum acceleration and jerk if over speed - float accel_max_z_cmss = _accel_max_z_cmss * calculate_overspeed_gain(); - float jerk_max_z_cmsss = _jerk_max_z_cmsss * calculate_overspeed_gain(); + const float overspeed_gain = calculate_overspeed_gain(); + const float accel_max_z_cmss = _accel_max_z_cmss * overspeed_gain; + const float jerk_max_z_cmsss = _jerk_max_z_cmsss * overspeed_gain; // adjust desired altitude if motors have not hit their limits update_pos_vel_accel(_pos_target.z, _vel_desired.z, _accel_desired.z, _dt, _limit_vector.z, _p_pos_z.get_error(), _pid_vel_z.get_error()); @@ -871,7 +889,6 @@ void AC_PosControl::set_alt_target_with_slew(float pos) /// update_pos_offset_z - updates the vertical offsets used by terrain following void AC_PosControl::update_pos_offset_z(float pos_offset_z) { - postype_t p_offset_z = _pos_offset_z; update_pos_vel_accel(p_offset_z, _vel_offset_z, _accel_offset_z, _dt, MIN(_limit_vector.z, 0.0f), _p_pos_z.get_error(), _pid_vel_z.get_error()); _pos_offset_z = p_offset_z; @@ -887,7 +904,8 @@ void AC_PosControl::update_pos_offset_z(float pos_offset_z) // is_active_z - returns true if the z position controller has been run in the previous 5 loop times bool AC_PosControl::is_active_z() const { - return ((AP_HAL::micros64() - _last_update_z_us) <= _dt * 5000000.0); + const uint32_t dt_us = AP::ins().get_last_update_usec() - _last_update_z_us; + return dt_us <= _dt * 1500000.0; } /// update_z_controller - runs the vertical position controller correcting position, velocity and acceleration errors. @@ -907,7 +925,7 @@ void AC_PosControl::update_z_controller() INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); } } - _last_update_z_us = AP_HAL::micros64(); + _last_update_z_us = AP::ins().get_last_update_usec(); // calculate the target velocity correction float pos_target_zf = _pos_target.z; @@ -923,7 +941,7 @@ void AC_PosControl::update_z_controller() // Velocity Controller const float curr_vel_z = _inav.get_velocity_z_up_cms(); - _accel_target.z = _pid_vel_z.update_all(_vel_target.z, curr_vel_z, _motors.limit.throttle_lower, _motors.limit.throttle_upper); + _accel_target.z = _pid_vel_z.update_all(_vel_target.z, curr_vel_z, _dt, _motors.limit.throttle_lower, _motors.limit.throttle_upper); _accel_target.z *= AP::ahrs().getControlScaleZ(); // add feed forward component @@ -942,7 +960,7 @@ void AC_PosControl::update_z_controller() if (_vibe_comp_enabled) { thr_out = get_throttle_with_vibration_override(); } else { - thr_out = _pid_accel_z.update_all(_accel_target.z, z_accel_meas, (_motors.limit.throttle_lower || _motors.limit.throttle_upper)) * 0.001f; + thr_out = _pid_accel_z.update_all(_accel_target.z, z_accel_meas, _dt, (_motors.limit.throttle_lower || _motors.limit.throttle_upper)) * 0.001f; thr_out += _pid_accel_z.get_ff() * 0.001f; } thr_out += _motors.get_throttle_hover(); @@ -977,6 +995,9 @@ void AC_PosControl::update_z_controller() /// get_lean_angle_max_cd - returns the maximum lean angle the autopilot may request float AC_PosControl::get_lean_angle_max_cd() const { + if (is_positive(_angle_max_override_cd)) { + return _angle_max_override_cd; + } if (!is_positive(_lean_angle_max)) { return _attitude_control.lean_angle_max_cd(); } @@ -1011,9 +1032,9 @@ Vector3f AC_PosControl::lean_angles_to_accel(const Vector3f& att_target_euler) c const float cos_yaw = cosf(att_target_euler.z); return Vector3f{ - (GRAVITY_MSS * 100) * (-cos_yaw * sin_pitch * cos_roll - sin_yaw * sin_roll) / MAX(cos_roll * cos_pitch, 0.1f), - (GRAVITY_MSS * 100) * (-sin_yaw * sin_pitch * cos_roll + cos_yaw * sin_roll) / MAX(cos_roll * cos_pitch, 0.1f), - (GRAVITY_MSS * 100) + (GRAVITY_MSS * 100.0f) * (-cos_yaw * sin_pitch * cos_roll - sin_yaw * sin_roll) / MAX(cos_roll * cos_pitch, 0.1f), + (GRAVITY_MSS * 100.0f) * (-sin_yaw * sin_pitch * cos_roll + cos_yaw * sin_roll) / MAX(cos_roll * cos_pitch, 0.1f), + (GRAVITY_MSS * 100.0f) }; } @@ -1157,9 +1178,9 @@ void AC_PosControl::accel_to_lean_angles(float accel_x_cmss, float accel_y_cmss, const float accel_right = -accel_x_cmss * _ahrs.sin_yaw() + accel_y_cmss * _ahrs.cos_yaw(); // update angle targets that will be passed to stabilize controller - pitch_target = atanf(-accel_forward / (GRAVITY_MSS * 100.0f)) * (18000.0f / M_PI); + pitch_target = accel_to_angle(-accel_forward * 0.01) * 100; float cos_pitch_target = cosf(pitch_target * M_PI / 18000.0f); - roll_target = atanf(accel_right * cos_pitch_target / (GRAVITY_MSS * 100.0f)) * (18000.0f / M_PI); + roll_target = accel_to_angle((accel_right * cos_pitch_target)*0.01) * 100; } // lean_angles_to_accel_xy - convert roll, pitch lean target angles to NE frame accelerations in cm/s/s diff --git a/libraries/AC_AttitudeControl/AC_PosControl.h b/libraries/AC_AttitudeControl/AC_PosControl.h index d19de899613..17e394c87e2 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.h +++ b/libraries/AC_AttitudeControl/AC_PosControl.h @@ -12,8 +12,6 @@ #include // PID library (2-axis) #include // Inertial Navigation library #include "AC_AttitudeControl.h" // Attitude control library -#include // motors library -#include // common vehicle parameters // position controller default definitions @@ -42,9 +40,14 @@ class AC_PosControl /// Constructor AC_PosControl(AP_AHRS_View& ahrs, const AP_InertialNav& inav, - const AP_Motors& motors, AC_AttitudeControl& attitude_control, float dt); + const class AP_Motors& motors, AC_AttitudeControl& attitude_control); - /// get_dt - gets time delta in seconds for all position controllers + + + /// set_dt / get_dt - dt is the time since the last time the position controllers were updated + /// _dt should be set based on the time of the last IMU read used by these controllers + /// the position controller should run updates for active controllers on each loop to ensure normal operation + void set_dt(float dt) { _dt = dt; } float get_dt() const { return _dt; } /// get_shaping_jerk_xy_cmsss - gets the jerk limit of the xy kinematic path generation in cm/s/s/s @@ -96,6 +99,9 @@ class AC_PosControl /// This function decays the output acceleration by 95% every half second to achieve a smooth transition to zero requested acceleration. void relax_velocity_controller_xy(); + /// reduce response for landing + void soften_for_landing_xy(); + // init_xy_controller - initialise the position controller to the current position, velocity, acceleration and attitude. /// This function is the default initialisation for any position control that provides position, velocity and acceleration. /// This function is private and contains all the shared xy axis initialisation functions @@ -196,7 +202,7 @@ class AC_PosControl /// The kinematic path is constrained by the maximum acceleration and jerk set using the function set_max_speed_accel_z. /// The function alters the vel to be the kinematic path based on accel /// The parameter limit_output specifies if the velocity and acceleration limits are applied to the sum of commanded and correction values or just correction. - virtual void input_vel_accel_z(float &vel, float accel, bool ignore_descent_limit, bool limit_output = true); + virtual void input_vel_accel_z(float &vel, float accel, bool limit_output = true); /// set_pos_target_z_from_climb_rate_cm - adjusts target up or down using a commanded climb rate in cm/s /// using the default position control kinematic path. @@ -340,6 +346,12 @@ class AC_PosControl /// get_lean_angle_max_cd - returns the maximum lean angle the autopilot may request float get_lean_angle_max_cd() const; + /* + set_lean_angle_max_cd - set the maximum lean angle. A value of zero means to use the ANGLE_MAX parameter. + This is reset to zero on init_xy_controller() + */ + void set_lean_angle_max_cd(float angle_max_cd) { _angle_max_override_cd = angle_max_cd; } + /// Other @@ -380,6 +392,9 @@ class AC_PosControl /// aircraft when in standby. void standby_xyz_reset(); + // get earth-frame Z-axis acceleration with gravity removed in cm/s/s with +ve being up + float get_z_accel_cmss() const { return -(_ahrs.get_accel_ef().z + GRAVITY_MSS) * 100.0f; } + static const struct AP_Param::GroupInfo var_info[]; protected: @@ -387,9 +402,6 @@ class AC_PosControl // get throttle using vibration-resistant calculation (uses feed forward with manually calculated gain) float get_throttle_with_vibration_override(); - // get earth-frame Z-axis acceleration with gravity removed in cm/s/s with +ve being up - float get_z_accel_cmss() const { return -(_ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f; } - // lean_angles_to_accel - convert roll, pitch lean angles to lat/lon frame accelerations in cm/s/s void accel_to_lean_angles(float accel_x_cmss, float accel_y_cmss, float& roll_target, float& pitch_target) const; @@ -411,7 +423,7 @@ class AC_PosControl // references to inertial nav and ahrs libraries AP_AHRS_View& _ahrs; const AP_InertialNav& _inav; - const AP_Motors& _motors; + const class AP_Motors& _motors; AC_AttitudeControl& _attitude_control; // parameters @@ -425,7 +437,7 @@ class AC_PosControl AC_PID _pid_accel_z; // Z axis acceleration controller to convert desired acceleration to throttle output // internal variables - float _dt; // time difference (in seconds) between calls from the main program + float _dt; // time difference (in seconds) since the last loop time uint64_t _last_update_xy_us; // system time (in microseconds) since last update_xy_controller call uint64_t _last_update_z_us; // system time (in microseconds) since last update_z_controller call float _vel_max_xy_cms; // max horizontal speed in cm/s used for kinematic shaping @@ -463,6 +475,9 @@ class AC_PosControl // high vibration handling bool _vibe_comp_enabled; // true when high vibration compensation is on + // angle max override, if zero then use ANGLE_MAX parameter + float _angle_max_override_cd; + // return true if on a real vehicle or SITL with lock-step scheduling bool has_good_timing(void) const; }; diff --git a/libraries/AC_AttitudeControl/AC_PosControl_Sub.cpp b/libraries/AC_AttitudeControl/AC_PosControl_Sub.cpp deleted file mode 100644 index 0b88e82afbb..00000000000 --- a/libraries/AC_AttitudeControl/AC_PosControl_Sub.cpp +++ /dev/null @@ -1,37 +0,0 @@ -#include "AC_PosControl_Sub.h" - -/// input_accel_z - calculate a jerk limited path from the current position, velocity and acceleration to an input acceleration. -/// The function takes the current position, velocity, and acceleration and calculates the required jerk limited adjustment to the acceleration for the next time dt. -/// The kinematic path is constrained by the maximum acceleration and jerk set using the function set_max_speed_accel_z. -/// The parameter limit_output specifies if the velocity and acceleration limits are applied to the sum of commanded and correction values or just correction. -void AC_PosControl_Sub::input_vel_accel_z(float &vel, const float accel, bool force_descend, bool limit_output) -{ - // check for ekf z position reset - handle_ekf_z_reset(); - - // limit desired velocity to prevent breeching altitude limits - if (_alt_min < 0 && _alt_min < _alt_max && _alt_max < 100 && _pos_target.z < _alt_min) { - vel = constrain_float(vel, - sqrt_controller(_alt_min-_pos_target.z, 0.0f, _accel_max_z_cmss, 0.0f), - sqrt_controller(_alt_max-_pos_target.z, 0.0f, _accel_max_z_cmss, 0.0f)); - } - - // calculated increased maximum acceleration and jerk if over speed - float accel_max_z_cmss = _accel_max_z_cmss * calculate_overspeed_gain(); - float jerk_max_xy_cmsss = _jerk_max_xy_cmsss * calculate_overspeed_gain(); - - // adjust desired alt if motors have not hit their limits - update_pos_vel_accel(_pos_target.z, _vel_desired.z, _accel_desired.z, _dt, _limit_vector.z, _p_pos_z.get_error(), _pid_vel_z.get_error()); - - // prevent altitude target from breeching altitude limits - if (is_negative(_alt_min) && _alt_min < _alt_max && _alt_max < 100 && _pos_target.z < _alt_min) { - _pos_target.z = constrain_float(_pos_target.z, _alt_min, _alt_max); - } - - shape_vel_accel(vel, accel, - _vel_desired.z, _accel_desired.z, - -accel_max_z_cmss, accel_max_z_cmss, - jerk_max_xy_cmsss, _dt, limit_output); - - update_vel_accel(vel, accel, _dt, 0.0, 0.0); -} diff --git a/libraries/AC_AttitudeControl/AC_PosControl_Sub.h b/libraries/AC_AttitudeControl/AC_PosControl_Sub.h deleted file mode 100644 index 3d9c4f5f59a..00000000000 --- a/libraries/AC_AttitudeControl/AC_PosControl_Sub.h +++ /dev/null @@ -1,30 +0,0 @@ -#pragma once - -#include "AC_PosControl.h" - -#define POSCONTROL_JERK_RATIO 1.0f // Defines the time it takes to reach the requested acceleration - -class AC_PosControl_Sub : public AC_PosControl { -public: - using AC_PosControl::AC_PosControl; - - /// set_alt_max - sets maximum altitude above the ekf origin in cm - /// only enforced when set_pos_target_z_from_climb_rate_cm is used - /// set to zero to disable limit - void set_alt_max(float alt) { _alt_max = alt; } - - /// set_alt_min - sets the minimum altitude (maximum depth) in cm - /// only enforced when set_pos_target_z_from_climb_rate_cm is used - /// set to zero to disable limit - void set_alt_min(float alt) { _alt_min = alt; } - - /// input_accel_z - calculate a jerk limited path from the current position, velocity and acceleration to an input acceleration. - /// The function takes the current position, velocity, and acceleration and calculates the required jerk limited adjustment to the acceleration for the next time dt. - /// The kinematic path is constrained by the maximum acceleration and jerk set using the function set_max_speed_accel_z. - /// The parameter limit_output specifies if the velocity and acceleration limits are applied to the sum of commanded and correction values or just correction. - void input_vel_accel_z(float &vel, float accel, bool force_descend, bool limit_output = true) override; - -private: - float _alt_max; // max altitude - should be updated from the main code with altitude limit from fence - float _alt_min; // min altitude - should be updated from the main code with altitude limit from fence -}; diff --git a/libraries/AC_AttitudeControl/AC_WeatherVane.cpp b/libraries/AC_AttitudeControl/AC_WeatherVane.cpp index 3db207935ee..1f5ecc24cfd 100644 --- a/libraries/AC_AttitudeControl/AC_WeatherVane.cpp +++ b/libraries/AC_AttitudeControl/AC_WeatherVane.cpp @@ -10,10 +10,12 @@ #define WVANE_PARAM_ENABLED 1 #define WVANE_PARAM_SPD_MAX_DEFAULT 0 #define WVANE_PARAM_VELZ_MAX_DEFAULT 0 + #define WVANE_PARAM_GAIN_DEFAULT 0 #else #define WVANE_PARAM_ENABLED 0 #define WVANE_PARAM_SPD_MAX_DEFAULT 2 #define WVANE_PARAM_VELZ_MAX_DEFAULT 1 + #define WVANE_PARAM_GAIN_DEFAULT 1 #endif @@ -32,7 +34,7 @@ const AP_Param::GroupInfo AC_WeatherVane::var_info[] = { // @Range: 0.5 4 // @Increment: 0.1 // @User: Standard - AP_GROUPINFO("GAIN", 2, AC_WeatherVane, _gain, 1.0), + AP_GROUPINFO("GAIN", 2, AC_WeatherVane, _gain, WVANE_PARAM_GAIN_DEFAULT), // @Param: ANG_MIN // @DisplayName: Weathervaning min angle @@ -45,7 +47,7 @@ const AP_Param::GroupInfo AC_WeatherVane::var_info[] = { // @Param: HGT_MIN // @DisplayName: Weathervaning min height - // @Description{Copter}: Above this height weathervaning is permitted. If a range finder is fitted or if terrain is enabled, this parameter sets height AGL. Otherwise, this parameter sets height above home. Set zero to ignore minimum height requirement to activate weathervaning. + // @Description: Above this height weathervaning is permitted. If a range finder is fitted or if terrain is enabled, this parameter sets height AGL. Otherwise, this parameter sets height above home. Set zero to ignore minimum height requirement to activate weathervaning. // @Description{Plane}: Above this height weathervaning is permitted. If RNGFND_LANDING is enabled or terrain is enabled then this parameter sets height AGL. Otherwise this parameter sets height above home. Set zero to ignore minimum height requirement to activate weathervaning // @Units: m // @Range: 0 50 @@ -85,6 +87,13 @@ const AP_Param::GroupInfo AC_WeatherVane::var_info[] = { // @User: Standard AP_GROUPINFO("LAND", 8, AC_WeatherVane, _landing_direction, -1), + // @Param: OPTIONS + // @DisplayName: Weathervaning options + // @Description: Options impacting weathervaning behaviour + // @Bitmask: 0:Use pitch when nose or tail-in for faster weathervaning + // @User: Standard + AP_GROUPINFO("OPTIONS", 9, AC_WeatherVane, _options, 0), + AP_GROUPEND }; @@ -98,8 +107,8 @@ AC_WeatherVane::AC_WeatherVane(void) bool AC_WeatherVane::get_yaw_out(float &yaw_output, const int16_t pilot_yaw, const float hgt, const float roll_cdeg, const float pitch_cdeg, const bool is_takeoff, const bool is_landing) { Direction dir = (Direction)_direction.get(); - if ((dir == Direction::OFF) || !allowed || (pilot_yaw != 0)) { - // parameter disabled + if ((dir == Direction::OFF) || !allowed || (pilot_yaw != 0) || !is_positive(_gain)) { + // parameter disabled, or 0 gain // disabled temporarily // dont't override pilot reset(); @@ -157,14 +166,18 @@ bool AC_WeatherVane::get_yaw_out(float &yaw_output, const int16_t pilot_yaw, con const float deadzone_cdeg = _min_dz_ang_deg*100.0; float output = 0.0; const char* dir_string = ""; + + // should we enable pitch input for nose-in and tail-in? + const bool pitch_enable = (uint8_t(_options.get()) & uint8_t(Options::PITCH_ENABLE)) != 0; + switch (dir) { case Direction::OFF: reset(); return false; case Direction::NOSE_IN: - if (is_positive(pitch_cdeg)) { - output = fabsf(roll_cdeg) + pitch_cdeg; + if (pitch_enable && is_positive(pitch_cdeg - deadzone_cdeg)) { + output = fabsf(roll_cdeg) + (pitch_cdeg - deadzone_cdeg); } else { output = MAX(fabsf(roll_cdeg) - deadzone_cdeg, 0.0); } @@ -191,8 +204,8 @@ bool AC_WeatherVane::get_yaw_out(float &yaw_output, const int16_t pilot_yaw, con break; case Direction::TAIL_IN: - if (is_negative(pitch_cdeg)) { - output = fabsf(roll_cdeg) - pitch_cdeg; + if (pitch_enable && is_negative(pitch_cdeg + deadzone_cdeg)) { + output = fabsf(roll_cdeg) - (pitch_cdeg + deadzone_cdeg); } else { output = MAX(fabsf(roll_cdeg) - deadzone_cdeg, 0.0); } diff --git a/libraries/AC_AttitudeControl/AC_WeatherVane.h b/libraries/AC_AttitudeControl/AC_WeatherVane.h index b0cb57f8a2d..fdfa765ab13 100644 --- a/libraries/AC_AttitudeControl/AC_WeatherVane.h +++ b/libraries/AC_AttitudeControl/AC_WeatherVane.h @@ -31,6 +31,10 @@ class AC_WeatherVane { TAIL_IN = 4, // backwards, for tailsitters, makes it easier to descend }; + enum class Options { + PITCH_ENABLE = (1<<0), + }; + // Paramaters AP_Int8 _direction; AP_Float _gain; @@ -40,6 +44,7 @@ class AC_WeatherVane { AP_Float _max_vel_z; AP_Int8 _landing_direction; AP_Int8 _takeoff_direction; + AP_Int16 _options; float last_output; bool active_msg_sent; diff --git a/libraries/AC_AttitudeControl/ControlMonitor.cpp b/libraries/AC_AttitudeControl/ControlMonitor.cpp index 37fadc2600c..5efdb1606c5 100644 --- a/libraries/AC_AttitudeControl/ControlMonitor.cpp +++ b/libraries/AC_AttitudeControl/ControlMonitor.cpp @@ -1,6 +1,7 @@ #include "AC_AttitudeControl.h" #include #include +#include /* code to monitor and report on the rate controllers, allowing for @@ -24,15 +25,15 @@ void AC_AttitudeControl::control_monitor_filter_pid(float value, float &rms) */ void AC_AttitudeControl::control_monitor_update(void) { - const AP_Logger::PID_Info &iroll = get_rate_roll_pid().get_pid_info(); + const AP_PIDInfo &iroll = get_rate_roll_pid().get_pid_info(); control_monitor_filter_pid(iroll.P + iroll.FF, _control_monitor.rms_roll_P); control_monitor_filter_pid(iroll.D, _control_monitor.rms_roll_D); - const AP_Logger::PID_Info &ipitch = get_rate_pitch_pid().get_pid_info(); + const AP_PIDInfo &ipitch = get_rate_pitch_pid().get_pid_info(); control_monitor_filter_pid(ipitch.P + ipitch.FF, _control_monitor.rms_pitch_P); control_monitor_filter_pid(ipitch.D, _control_monitor.rms_pitch_D); - const AP_Logger::PID_Info &iyaw = get_rate_yaw_pid().get_pid_info(); + const AP_PIDInfo &iyaw = get_rate_yaw_pid().get_pid_info(); control_monitor_filter_pid(iyaw.P + iyaw.D + iyaw.FF, _control_monitor.rms_yaw); } diff --git a/libraries/AC_AutoTune/AC_AutoTune.cpp b/libraries/AC_AutoTune/AC_AutoTune.cpp index eb1e13a7fb0..a9b1f316879 100644 --- a/libraries/AC_AutoTune/AC_AutoTune.cpp +++ b/libraries/AC_AutoTune/AC_AutoTune.cpp @@ -1,6 +1,8 @@ #include "AC_AutoTune.h" -#include + +#include #include +#include #define AUTOTUNE_PILOT_OVERRIDE_TIMEOUT_MS 500 // restart tuning if pilot has left sticks in middle for 2 seconds #if APM_BUILD_TYPE(APM_BUILD_ArduPlane) @@ -196,29 +198,32 @@ void AC_AutoTune::run() const bool zero_rp_input = is_zero(target_roll_cd) && is_zero(target_pitch_cd); const uint32_t now = AP_HAL::millis(); - if (!zero_rp_input || !is_zero(target_yaw_rate_cds) || !is_zero(target_climb_rate_cms)) { - if (!pilot_override) { - pilot_override = true; - // set gains to their original values - load_gains(GAIN_ORIGINAL); - attitude_control->use_sqrt_controller(true); - } - // reset pilot override time - override_time = now; - if (!zero_rp_input) { - // only reset position on roll or pitch input - have_position = false; - } - } else if (pilot_override) { - // check if we should resume tuning after pilot's override - if (now - override_time > AUTOTUNE_PILOT_OVERRIDE_TIMEOUT_MS) { - pilot_override = false; // turn off pilot override - // set gains to their intra-test values (which are very close to the original gains) - // load_gains(GAIN_INTRA_TEST); //I think we should be keeping the originals here to let the I term settle quickly - step = WAITING_FOR_LEVEL; // set tuning step back from beginning - step_start_time_ms = now; - level_start_time_ms = now; - desired_yaw_cd = ahrs_view->yaw_sensor; + + if (mode != SUCCESS) { + if (!zero_rp_input || !is_zero(target_yaw_rate_cds) || !is_zero(target_climb_rate_cms)) { + if (!pilot_override) { + pilot_override = true; + // set gains to their original values + load_gains(GAIN_ORIGINAL); + attitude_control->use_sqrt_controller(true); + } + // reset pilot override time + override_time = now; + if (!zero_rp_input) { + // only reset position on roll or pitch input + have_position = false; + } + } else if (pilot_override) { + // check if we should resume tuning after pilot's override + if (now - override_time > AUTOTUNE_PILOT_OVERRIDE_TIMEOUT_MS) { + pilot_override = false; // turn off pilot override + // set gains to their intra-test values (which are very close to the original gains) + // load_gains(GAIN_INTRA_TEST); //I think we should be keeping the originals here to let the I term settle quickly + step = WAITING_FOR_LEVEL; // set tuning step back from beginning + step_start_time_ms = now; + level_start_time_ms = now; + desired_yaw_cd = ahrs_view->yaw_sensor; + } } } if (pilot_override) { diff --git a/libraries/AC_AutoTune/AC_AutoTune.h b/libraries/AC_AutoTune/AC_AutoTune.h index 6cc7ac16ac0..c907f9955e5 100644 --- a/libraries/AC_AutoTune/AC_AutoTune.h +++ b/libraries/AC_AutoTune/AC_AutoTune.h @@ -18,7 +18,6 @@ */ #pragma once -#include #include #include #include @@ -231,6 +230,15 @@ class AC_AutoTune }; void load_gains(enum GainType gain_type); + // autotune modes (high level states) + enum TuneMode { + UNINITIALISED = 0, // autotune has never been run + TUNING = 1, // autotune is testing gains + SUCCESS = 2, // tuning has completed, user is flight testing the new gains + FAILED = 3, // tuning has failed, user is flying on original gains + }; + TuneMode mode; // see TuneMode for what modes are allowed + // copies of object pointers to make code a bit clearer AC_AttitudeControl *attitude_control; AC_PosControl *pos_control; @@ -301,15 +309,6 @@ class AC_AutoTune // returns true if vehicle is close to level bool currently_level(); - // autotune modes (high level states) - enum TuneMode { - UNINITIALISED = 0, // autotune has never been run - TUNING = 1, // autotune is testing gains - SUCCESS = 2, // tuning has completed, user is flight testing the new gains - FAILED = 3, // tuning has failed, user is flying on original gains - }; - - TuneMode mode; // see TuneMode for what modes are allowed bool pilot_override; // true = pilot is overriding controls so we suspend tuning temporarily bool use_poshold; // true = enable position hold bool have_position; // true = start_position is value diff --git a/libraries/AC_AutoTune/AC_AutoTune_FreqResp.h b/libraries/AC_AutoTune/AC_AutoTune_FreqResp.h index 5e7d8c89ee6..95e18567659 100644 --- a/libraries/AC_AutoTune/AC_AutoTune_FreqResp.h +++ b/libraries/AC_AutoTune/AC_AutoTune_FreqResp.h @@ -4,7 +4,6 @@ Gain and phase determination algorithm */ -#include #include #define AUTOTUNE_DWELL_CYCLES 6 diff --git a/libraries/AC_AutoTune/AC_AutoTune_Heli.cpp b/libraries/AC_AutoTune/AC_AutoTune_Heli.cpp index eb860971fdf..f7f75b902b6 100644 --- a/libraries/AC_AutoTune/AC_AutoTune_Heli.cpp +++ b/libraries/AC_AutoTune/AC_AutoTune_Heli.cpp @@ -19,6 +19,8 @@ #include "AC_AutoTune_Heli.h" +#include + #define AUTOTUNE_TESTING_STEP_TIMEOUT_MS 5000U // timeout for tuning mode's testing step #define AUTOTUNE_RD_STEP 0.0005f // minimum increment when increasing/decreasing Rate D term @@ -124,26 +126,26 @@ void AC_AutoTune_Heli::test_init() if (test_phase[12] > 0.0f && test_phase[12] < 180.0f) { freq_cnt = 12; // start with freq found for sweep where phase was 180 deg - } else if (!is_zero(sweep.ph180_freq)) { + } else if (!is_zero(sweep.ph180.freq)) { freq_cnt = 12; - test_freq[freq_cnt] = sweep.ph180_freq - 0.25f * 3.14159f * 2.0f; + test_freq[freq_cnt] = sweep.ph180.freq - 0.25f * 3.14159f * 2.0f; // otherwise start at min freq to step up in dwell frequency until phase > 160 deg } else { freq_cnt = 0; test_freq[freq_cnt] = min_sweep_freq; } - curr_test_freq = test_freq[freq_cnt]; - start_freq = curr_test_freq; - stop_freq = curr_test_freq; + curr_test.freq = test_freq[freq_cnt]; + start_freq = curr_test.freq; + stop_freq = curr_test.freq; // MAX_GAINS and RD_UP both start with a sweep initially but if it has been completed then start dwells at the freq for 180 deg phase } else { - if (!is_zero(sweep.ph180_freq)) { + if (!is_zero(sweep.ph180.freq)) { freq_cnt = 12; - test_freq[freq_cnt] = sweep.ph180_freq - 0.25f * 3.14159f * 2.0f; - curr_test_freq = test_freq[freq_cnt]; - start_freq = curr_test_freq; - stop_freq = curr_test_freq; + test_freq[freq_cnt] = sweep.ph180.freq - 0.25f * 3.14159f * 2.0f; + curr_test.freq = test_freq[freq_cnt]; + start_freq = curr_test.freq; + stop_freq = curr_test.freq; if (tune_type == MAX_GAINS) { reset_maxgains_update_gain_variables(); } @@ -155,12 +157,12 @@ void AC_AutoTune_Heli::test_init() } if (!is_equal(start_freq,stop_freq)) { // initialize determine_gain function whenever test is initialized - freqresp_rate.init(AC_AutoTune_FreqResp::InputType::SWEEP, AC_AutoTune_FreqResp::ResponseType::RATE); - dwell_test_init(start_freq, stop_freq); + freqresp.init(AC_AutoTune_FreqResp::InputType::SWEEP, AC_AutoTune_FreqResp::ResponseType::RATE); + dwell_test_init(start_freq, stop_freq, stop_freq, RATE); } else { // initialize determine_gain function whenever test is initialized - freqresp_rate.init(AC_AutoTune_FreqResp::InputType::DWELL, AC_AutoTune_FreqResp::ResponseType::RATE); - dwell_test_init(start_freq, start_freq); + freqresp.init(AC_AutoTune_FreqResp::InputType::DWELL, AC_AutoTune_FreqResp::ResponseType::RATE); + dwell_test_init(start_freq, stop_freq, start_freq, RATE); } if (!is_zero(start_freq)) { // 4 seconds is added to allow aircraft to achieve start attitude. Then the time to conduct the dwells is added to it. @@ -170,12 +172,12 @@ void AC_AutoTune_Heli::test_init() case SP_UP: // initialize start frequency if (is_zero(start_freq)) { - if (!is_zero(sweep.maxgain_freq)) { + if (!is_zero(sweep.maxgain.freq)) { freq_cnt = 12; - test_freq[freq_cnt] = sweep.maxgain_freq - 0.25f * 3.14159f * 2.0f; - curr_test_freq = test_freq[freq_cnt]; - start_freq = curr_test_freq; - stop_freq = curr_test_freq; + test_freq[freq_cnt] = sweep.maxgain.freq - 0.25f * 3.14159f * 2.0f; + curr_test.freq = test_freq[freq_cnt]; + start_freq = curr_test.freq; + stop_freq = curr_test.freq; test_accel_max = 0.0f; } else { start_freq = min_sweep_freq; @@ -185,12 +187,12 @@ void AC_AutoTune_Heli::test_init() if (!is_equal(start_freq,stop_freq)) { // initialize determine gain function - freqresp_angle.init(AC_AutoTune_FreqResp::InputType::SWEEP, AC_AutoTune_FreqResp::ResponseType::ANGLE); - angle_dwell_test_init(start_freq, stop_freq); + freqresp.init(AC_AutoTune_FreqResp::InputType::SWEEP, AC_AutoTune_FreqResp::ResponseType::ANGLE); + dwell_test_init(start_freq, stop_freq, stop_freq, ANGLE); } else { // initialize determine gain function - freqresp_angle.init(AC_AutoTune_FreqResp::InputType::DWELL, AC_AutoTune_FreqResp::ResponseType::ANGLE); - angle_dwell_test_init(start_freq, start_freq); + freqresp.init(AC_AutoTune_FreqResp::InputType::DWELL, AC_AutoTune_FreqResp::ResponseType::ANGLE); + dwell_test_init(start_freq, stop_freq, start_freq, ANGLE); } // TODO add time limit for sweep test @@ -211,11 +213,10 @@ void AC_AutoTune_Heli::test_run(AxisType test_axis, const float dir_sign) { // if tune complete or beyond frequency range or no max allowed gains then exit testing if (tune_type == TUNE_COMPLETE || - (tune_type == RP_UP && max_rate_p.max_allowed <= 0.0f) || - (tune_type == RD_UP && max_rate_d.max_allowed <= 0.0f) || + ((tune_type == RP_UP || tune_type == RD_UP) && (max_rate_p.max_allowed <= 0.0f || max_rate_d.max_allowed <= 0.0f)) || ((tune_type == MAX_GAINS || tune_type == RP_UP || tune_type == RD_UP || tune_type == SP_UP) && exceeded_freq_range(start_freq))){ - load_gains(GAIN_INTRA_TEST); + load_gains(GAIN_ORIGINAL); attitude_control->use_sqrt_controller(true); @@ -224,15 +225,16 @@ void AC_AutoTune_Heli::test_run(AxisType test_axis, const float dir_sign) // hold level attitude attitude_control->input_euler_angle_roll_pitch_yaw(roll_cd, pitch_cd, desired_yaw_cd, true); - if ((tune_type == RP_UP && max_rate_p.max_allowed <= 0.0f) || (tune_type == RD_UP && max_rate_d.max_allowed <= 0.0f)) { - gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: Max Gains Failed, Skip Rate P/D Tuning"); - counter = AUTOTUNE_SUCCESS_COUNT; - step = UPDATE_GAINS; + if ((tune_type == RP_UP || tune_type == RD_UP) && (max_rate_p.max_allowed <= 0.0f || max_rate_d.max_allowed <= 0.0f)) { + gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: Max Gain Determination Failed"); + mode = FAILED; + AP::logger().Write_Event(LogEvent::AUTOTUNE_FAILED); + update_gcs(AUTOTUNE_MESSAGE_FAILED); } else if ((tune_type == MAX_GAINS || tune_type == RP_UP || tune_type == RD_UP || tune_type == SP_UP) && exceeded_freq_range(start_freq)){ gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: Exceeded frequency range"); - AP::logger().Write_Event(LogEvent::AUTOTUNE_REACHED_LIMIT); - counter = AUTOTUNE_SUCCESS_COUNT; - step = UPDATE_GAINS; + mode = FAILED; + AP::logger().Write_Event(LogEvent::AUTOTUNE_FAILED); + update_gcs(AUTOTUNE_MESSAGE_FAILED); } else if (tune_type == TUNE_COMPLETE) { counter = AUTOTUNE_SUCCESS_COUNT; step = UPDATE_GAINS; @@ -246,13 +248,13 @@ void AC_AutoTune_Heli::test_run(AxisType test_axis, const float dir_sign) break; case RP_UP: case RD_UP: - dwell_test_run(1, start_freq, stop_freq, test_gain[freq_cnt], test_phase[freq_cnt]); + dwell_test_run(1, start_freq, stop_freq, test_gain[freq_cnt], test_phase[freq_cnt], RATE); break; case MAX_GAINS: - dwell_test_run(0, start_freq, stop_freq, test_gain[freq_cnt], test_phase[freq_cnt]); + dwell_test_run(0, start_freq, stop_freq, test_gain[freq_cnt], test_phase[freq_cnt], RATE); break; case SP_UP: - angle_dwell_test_run(start_freq, stop_freq, test_gain[freq_cnt], test_phase[freq_cnt]); + dwell_test_run(1, start_freq, stop_freq, test_gain[freq_cnt], test_phase[freq_cnt], ANGLE); break; default: step = UPDATE_GAINS; @@ -280,7 +282,7 @@ void AC_AutoTune_Heli::do_gcs_announcements() } else { gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: Sweep"); if (settle_time == 0) { - gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: freq=%f gain=%f phase=%f", (double)(curr_test_freq), (double)(curr_test_gain), (double)(curr_test_phase)); + gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: freq=%f gain=%f phase=%f", (double)(curr_test.freq), (double)(curr_test.gain), (double)(curr_test.phase)); } } break; @@ -330,38 +332,23 @@ void AC_AutoTune_Heli::do_post_test_gcs_announcements() { gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: ff=%f", (double)tune_rff); break; case RP_UP: - if (is_equal(start_freq,stop_freq)) { - // announce results of dwell - gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: freq=%f gain=%f", (double)(test_freq[freq_cnt]), (double)(test_gain[freq_cnt])); - gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: ph=%f rate_p=%f", (double)(test_phase[freq_cnt]), (double)(tune_rp)); - } else { - gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: max_freq=%f max_gain=%f", (double)(sweep.maxgain_freq), (double)(sweep.maxgain_gain)); - gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: ph180_freq=%f ph180_gain=%f", (double)(sweep.ph180_freq), (double)(sweep.ph180_gain)); - } - break; case RD_UP: - // announce results of dwell - gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: freq=%f gain=%f", (double)(test_freq[freq_cnt]), (double)(test_gain[freq_cnt])); - gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: ph=%f rate_d=%f", (double)(test_phase[freq_cnt]), (double)(tune_rd)); - break; case SP_UP: - if (is_equal(start_freq,stop_freq)) { - // announce results of dwell and update - gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: freq=%f gain=%f", (double)(test_freq[freq_cnt]), (double)(test_gain[freq_cnt])); - gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: phase=%f angle_p=%f", (double)(test_phase[freq_cnt]), (double)(tune_sp)); - gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: tune_accel=%f max_accel=%f", (double)(tune_accel), (double)(test_accel_max)); - } else { - gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: max_freq=%f max_gain=%f", (double)(sweep.maxgain_freq), (double)(sweep.maxgain_gain)); - gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: ph180_freq=%f ph180_gain=%f", (double)(sweep.ph180_freq), (double)(sweep.ph180_gain)); - } - break; case MAX_GAINS: if (is_equal(start_freq,stop_freq)) { - // announce results of dwell and update - gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: freq=%f gain=%f ph=%f", (double)(test_freq[freq_cnt]), (double)(test_gain[freq_cnt]), (double)(test_phase[freq_cnt])); + // announce results of dwell + gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: freq=%f gain=%f", (double)(test_freq[freq_cnt]), (double)(test_gain[freq_cnt])); + gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: ph=%f", (double)(test_phase[freq_cnt])); + if (tune_type == RP_UP) { + gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: rate_p=%f", (double)(tune_rp)); + } else if (tune_type == RD_UP) { + gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: rate_d=%f", (double)(tune_rd)); + } else if (tune_type == SP_UP) { + gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: angle_p=%f tune_accel=%f max_accel=%f", (double)(tune_sp), (double)(tune_accel), (double)(test_accel_max)); + } } else { - gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: max_freq=%f max_gain=%f", (double)(sweep.maxgain_freq), (double)(sweep.maxgain_gain)); - gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: ph180_freq=%f ph180_gain=%f", (double)(sweep.ph180_freq), (double)(sweep.ph180_gain)); + gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: max_freq=%f max_gain=%f", (double)(sweep.maxgain.freq), (double)(sweep.maxgain.gain)); + gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: ph180_freq=%f ph180_gain=%f", (double)(sweep.ph180.freq), (double)(sweep.ph180.gain)); } break; default: @@ -437,35 +424,13 @@ void AC_AutoTune_Heli::load_orig_gains() { attitude_control->bf_feedforward(orig_bf_feedforward); if (roll_enabled()) { - attitude_control->get_rate_roll_pid().kP(orig_roll_rp); - attitude_control->get_rate_roll_pid().kI(orig_roll_ri); - attitude_control->get_rate_roll_pid().kD(orig_roll_rd); - attitude_control->get_rate_roll_pid().ff(orig_roll_rff); - attitude_control->get_rate_roll_pid().filt_T_hz(orig_roll_fltt); - attitude_control->get_rate_roll_pid().slew_limit(orig_roll_smax); - attitude_control->get_angle_roll_p().kP(orig_roll_sp); - attitude_control->set_accel_roll_max_cdss(orig_roll_accel); + load_gain_set(ROLL, orig_roll_rp, orig_roll_ri, orig_roll_rd, orig_roll_rff, orig_roll_sp, orig_roll_accel, orig_roll_fltt, 0.0f, orig_roll_smax); } if (pitch_enabled()) { - attitude_control->get_rate_pitch_pid().kP(orig_pitch_rp); - attitude_control->get_rate_pitch_pid().kI(orig_pitch_ri); - attitude_control->get_rate_pitch_pid().kD(orig_pitch_rd); - attitude_control->get_rate_pitch_pid().ff(orig_pitch_rff); - attitude_control->get_rate_pitch_pid().filt_T_hz(orig_pitch_fltt); - attitude_control->get_rate_pitch_pid().slew_limit(orig_pitch_smax); - attitude_control->get_angle_pitch_p().kP(orig_pitch_sp); - attitude_control->set_accel_pitch_max_cdss(orig_pitch_accel); + load_gain_set(PITCH, orig_pitch_rp, orig_pitch_ri, orig_pitch_rd, orig_pitch_rff, orig_pitch_sp, orig_pitch_accel, orig_pitch_fltt, 0.0f, orig_pitch_smax); } if (yaw_enabled()) { - attitude_control->get_rate_yaw_pid().kP(orig_yaw_rp); - attitude_control->get_rate_yaw_pid().kI(orig_yaw_ri); - attitude_control->get_rate_yaw_pid().kD(orig_yaw_rd); - attitude_control->get_rate_yaw_pid().ff(orig_yaw_rff); - attitude_control->get_rate_yaw_pid().filt_E_hz(orig_yaw_rLPF); - attitude_control->get_rate_yaw_pid().filt_T_hz(orig_yaw_fltt); - attitude_control->get_rate_yaw_pid().slew_limit(orig_yaw_smax); - attitude_control->get_angle_yaw_p().kP(orig_yaw_sp); - attitude_control->set_accel_yaw_max_cdss(orig_yaw_accel); + load_gain_set(YAW, orig_yaw_rp, orig_yaw_ri, orig_yaw_rd, orig_yaw_rff, orig_yaw_sp, orig_yaw_accel, orig_yaw_fltt, orig_yaw_rLPF, orig_yaw_smax); } } @@ -478,30 +443,14 @@ void AC_AutoTune_Heli::load_tuned_gains() attitude_control->set_accel_pitch_max_cdss(0.0f); } if (roll_enabled()) { - attitude_control->get_rate_roll_pid().kP(tune_roll_rp); - attitude_control->get_rate_roll_pid().kI(tune_roll_rff*AUTOTUNE_FFI_RATIO_FINAL); - attitude_control->get_rate_roll_pid().kD(tune_roll_rd); - attitude_control->get_rate_roll_pid().ff(tune_roll_rff); - attitude_control->get_angle_roll_p().kP(tune_roll_sp); - attitude_control->set_accel_roll_max_cdss(tune_roll_accel); + load_gain_set(ROLL, tune_roll_rp, tune_roll_rff*AUTOTUNE_FFI_RATIO_FINAL, tune_roll_rd, tune_roll_rff, tune_roll_sp, tune_roll_accel, orig_roll_fltt, 0.0f, orig_roll_smax); } if (pitch_enabled()) { - attitude_control->get_rate_pitch_pid().kP(tune_pitch_rp); - attitude_control->get_rate_pitch_pid().kI(tune_pitch_rff*AUTOTUNE_FFI_RATIO_FINAL); - attitude_control->get_rate_pitch_pid().kD(tune_pitch_rd); - attitude_control->get_rate_pitch_pid().ff(tune_pitch_rff); - attitude_control->get_angle_pitch_p().kP(tune_pitch_sp); - attitude_control->set_accel_pitch_max_cdss(tune_pitch_accel); + load_gain_set(PITCH, tune_pitch_rp, tune_pitch_rff*AUTOTUNE_FFI_RATIO_FINAL, tune_pitch_rd, tune_pitch_rff, tune_pitch_sp, tune_pitch_accel, orig_pitch_fltt, 0.0f, orig_pitch_smax); } if (yaw_enabled()) { if (!is_zero(tune_yaw_rp)) { - attitude_control->get_rate_yaw_pid().kP(tune_yaw_rp); - attitude_control->get_rate_yaw_pid().kI(tune_yaw_rp*AUTOTUNE_YAW_PI_RATIO_FINAL); - attitude_control->get_rate_yaw_pid().kD(tune_yaw_rd); - attitude_control->get_rate_yaw_pid().ff(tune_yaw_rff); - attitude_control->get_rate_yaw_pid().filt_E_hz(tune_yaw_rLPF); - attitude_control->get_angle_yaw_p().kP(tune_yaw_sp); - attitude_control->set_accel_yaw_max_cdss(tune_yaw_accel); + load_gain_set(YAW, tune_yaw_rp, tune_yaw_rp*AUTOTUNE_YAW_PI_RATIO_FINAL, tune_yaw_rd, tune_yaw_rff, tune_yaw_sp, tune_yaw_accel, orig_yaw_fltt, tune_yaw_rLPF, orig_yaw_smax); } } } @@ -514,35 +463,13 @@ void AC_AutoTune_Heli::load_intra_test_gains() // sanity check the gains attitude_control->bf_feedforward(true); if (roll_enabled()) { - attitude_control->get_rate_roll_pid().kP(orig_roll_rp); - attitude_control->get_rate_roll_pid().kI(orig_roll_rff * AUTOTUNE_FFI_RATIO_FOR_TESTING); - attitude_control->get_rate_roll_pid().kD(orig_roll_rd); - attitude_control->get_rate_roll_pid().ff(orig_roll_rff); - attitude_control->get_rate_roll_pid().filt_T_hz(orig_roll_fltt); - attitude_control->get_rate_roll_pid().slew_limit(orig_roll_smax); - attitude_control->get_angle_roll_p().kP(orig_roll_sp); - attitude_control->set_accel_roll_max_cdss(orig_roll_accel); + load_gain_set(ROLL, orig_roll_rp, orig_roll_rff * AUTOTUNE_FFI_RATIO_FOR_TESTING, orig_roll_rd, orig_roll_rff, orig_roll_sp, orig_roll_accel, orig_roll_fltt, 0.0f, orig_roll_smax); } if (pitch_enabled()) { - attitude_control->get_rate_pitch_pid().kP(orig_pitch_rp); - attitude_control->get_rate_pitch_pid().kI(orig_pitch_rff * AUTOTUNE_FFI_RATIO_FOR_TESTING); - attitude_control->get_rate_pitch_pid().kD(orig_pitch_rd); - attitude_control->get_rate_pitch_pid().ff(orig_pitch_rff); - attitude_control->get_rate_pitch_pid().filt_T_hz(orig_pitch_fltt); - attitude_control->get_rate_pitch_pid().slew_limit(orig_pitch_smax); - attitude_control->get_angle_pitch_p().kP(orig_pitch_sp); - attitude_control->set_accel_pitch_max_cdss(orig_pitch_accel); + load_gain_set(PITCH, orig_pitch_rp, orig_pitch_rff * AUTOTUNE_FFI_RATIO_FOR_TESTING, orig_pitch_rd, orig_pitch_rff, orig_pitch_sp, orig_pitch_accel, orig_pitch_fltt, 0.0f, orig_pitch_smax); } if (yaw_enabled()) { - attitude_control->get_rate_yaw_pid().kP(orig_yaw_rp); - attitude_control->get_rate_yaw_pid().kI(orig_yaw_rp*AUTOTUNE_PI_RATIO_FOR_TESTING); - attitude_control->get_rate_yaw_pid().kD(orig_yaw_rd); - attitude_control->get_rate_yaw_pid().ff(orig_yaw_rff); - attitude_control->get_rate_yaw_pid().filt_T_hz(orig_yaw_fltt); - attitude_control->get_rate_yaw_pid().slew_limit(orig_yaw_smax); - attitude_control->get_rate_yaw_pid().filt_E_hz(orig_yaw_rLPF); - attitude_control->get_angle_yaw_p().kP(orig_yaw_sp); - attitude_control->set_accel_yaw_max_cdss(orig_yaw_accel); + load_gain_set(YAW, orig_yaw_rp, orig_yaw_rp*AUTOTUNE_PI_RATIO_FOR_TESTING, orig_yaw_rd, orig_yaw_rff, orig_yaw_sp, orig_yaw_accel, orig_yaw_fltt, orig_yaw_rLPF, orig_yaw_smax); } } @@ -550,55 +477,81 @@ void AC_AutoTune_Heli::load_intra_test_gains() // called by control_attitude() just before it beings testing a gain (i.e. just before it twitches) void AC_AutoTune_Heli::load_test_gains() { + float rate_p, rate_i, rate_d; switch (axis) { case ROLL: if (tune_type == SP_UP) { - attitude_control->get_rate_roll_pid().kI(orig_roll_ri); + rate_i = orig_roll_ri; } else { // freeze integrator to hold trim by making i term small during rate controller tuning - attitude_control->get_rate_roll_pid().kI(0.01f * orig_roll_ri); + rate_i = 0.01f * orig_roll_ri; } if (tune_type == MAX_GAINS && !is_zero(tune_roll_rff)) { - attitude_control->get_rate_roll_pid().kP(0.0f); - attitude_control->get_rate_roll_pid().kD(0.0f); + rate_p = 0.0f; + rate_d = 0.0f; } else { - attitude_control->get_rate_roll_pid().kP(tune_roll_rp); - attitude_control->get_rate_roll_pid().kD(tune_roll_rd); + rate_p = tune_roll_rp; + rate_d = tune_roll_rd; } - attitude_control->get_rate_roll_pid().ff(tune_roll_rff); - attitude_control->get_rate_roll_pid().filt_T_hz(orig_roll_fltt); - attitude_control->get_rate_roll_pid().slew_limit(0.0f); - attitude_control->get_angle_roll_p().kP(tune_roll_sp); + load_gain_set(ROLL, rate_p, rate_i, rate_d, tune_roll_rff, tune_roll_sp, tune_roll_accel, orig_roll_fltt, 0.0f, 0.0f); break; case PITCH: if (tune_type == SP_UP) { - attitude_control->get_rate_pitch_pid().kI(orig_pitch_ri); + rate_i = orig_pitch_ri; } else { // freeze integrator to hold trim by making i term small during rate controller tuning - attitude_control->get_rate_pitch_pid().kI(0.01f * orig_pitch_ri); + rate_i = 0.01f * orig_pitch_ri; } if (tune_type == MAX_GAINS && !is_zero(tune_pitch_rff)) { - attitude_control->get_rate_pitch_pid().kP(0.0f); - attitude_control->get_rate_pitch_pid().kD(0.0f); + rate_p = 0.0f; + rate_d = 0.0f; } else { - attitude_control->get_rate_pitch_pid().kP(tune_pitch_rp); - attitude_control->get_rate_pitch_pid().kD(tune_pitch_rd); + rate_p = tune_pitch_rp; + rate_d = tune_pitch_rd; } - attitude_control->get_rate_pitch_pid().ff(tune_pitch_rff); - attitude_control->get_rate_pitch_pid().filt_T_hz(orig_pitch_fltt); - attitude_control->get_rate_pitch_pid().slew_limit(0.0f); - attitude_control->get_angle_pitch_p().kP(tune_pitch_sp); + load_gain_set(PITCH, rate_p, rate_i, rate_d, tune_pitch_rff, tune_pitch_sp, tune_pitch_accel, orig_pitch_fltt, 0.0f, 0.0f); break; case YAW: // freeze integrator to hold trim by making i term small during rate controller tuning - attitude_control->get_rate_yaw_pid().kP(tune_yaw_rp); - attitude_control->get_rate_yaw_pid().kI(tune_yaw_rp*0.01f); - attitude_control->get_rate_yaw_pid().kD(tune_yaw_rd); - attitude_control->get_rate_yaw_pid().ff(tune_yaw_rff); - attitude_control->get_rate_yaw_pid().filt_E_hz(tune_yaw_rLPF); - attitude_control->get_rate_yaw_pid().filt_T_hz(orig_yaw_fltt); - attitude_control->get_rate_yaw_pid().slew_limit(0.0f); - attitude_control->get_angle_yaw_p().kP(tune_yaw_sp); + load_gain_set(YAW, tune_yaw_rp, tune_yaw_rp*0.01f, tune_yaw_rd, tune_yaw_rff, tune_yaw_sp, tune_yaw_accel, orig_yaw_fltt, tune_yaw_rLPF, 0.0f); + break; + } +} + +// load gains +void AC_AutoTune_Heli::load_gain_set(AxisType s_axis, float rate_p, float rate_i, float rate_d, float rate_ff, float angle_p, float max_accel, float rate_fltt, float rate_flte, float smax) +{ + switch (s_axis) { + case ROLL: + attitude_control->get_rate_roll_pid().kP(rate_p); + attitude_control->get_rate_roll_pid().kI(rate_i); + attitude_control->get_rate_roll_pid().kD(rate_d); + attitude_control->get_rate_roll_pid().ff(rate_ff); + attitude_control->get_rate_roll_pid().filt_T_hz(rate_fltt); + attitude_control->get_rate_roll_pid().slew_limit(smax); + attitude_control->get_angle_roll_p().kP(angle_p); + attitude_control->set_accel_roll_max_cdss(max_accel); + break; + case PITCH: + attitude_control->get_rate_pitch_pid().kP(rate_p); + attitude_control->get_rate_pitch_pid().kI(rate_i); + attitude_control->get_rate_pitch_pid().kD(rate_d); + attitude_control->get_rate_pitch_pid().ff(rate_ff); + attitude_control->get_rate_pitch_pid().filt_T_hz(rate_fltt); + attitude_control->get_rate_pitch_pid().slew_limit(smax); + attitude_control->get_angle_pitch_p().kP(angle_p); + attitude_control->set_accel_pitch_max_cdss(max_accel); + break; + case YAW: + attitude_control->get_rate_yaw_pid().kP(rate_p); + attitude_control->get_rate_yaw_pid().kI(rate_i); + attitude_control->get_rate_yaw_pid().kD(rate_d); + attitude_control->get_rate_yaw_pid().ff(rate_ff); + attitude_control->get_rate_yaw_pid().filt_T_hz(rate_fltt); + attitude_control->get_rate_yaw_pid().slew_limit(smax); + attitude_control->get_rate_yaw_pid().filt_E_hz(rate_flte); + attitude_control->get_angle_yaw_p().kP(angle_p); + attitude_control->set_accel_yaw_max_cdss(max_accel); break; } } @@ -620,22 +573,13 @@ void AC_AutoTune_Heli::save_tuning_gains() // sanity check the rate P values if ((axes_completed & AUTOTUNE_AXIS_BITMASK_ROLL) && roll_enabled()) { - // rate roll gains - attitude_control->get_rate_roll_pid().kP(tune_roll_rp); - attitude_control->get_rate_roll_pid().kI(tune_roll_rff*AUTOTUNE_FFI_RATIO_FINAL); - attitude_control->get_rate_roll_pid().kD(tune_roll_rd); - attitude_control->get_rate_roll_pid().ff(tune_roll_rff); - attitude_control->get_rate_roll_pid().filt_T_hz(orig_roll_fltt); - attitude_control->get_rate_roll_pid().slew_limit(orig_roll_smax); + load_gain_set(ROLL, tune_roll_rp, tune_roll_rff*AUTOTUNE_FFI_RATIO_FINAL, tune_roll_rd, tune_roll_rff, tune_roll_sp, tune_roll_accel, orig_roll_fltt, 0.0f, orig_roll_smax); + // save rate roll gains attitude_control->get_rate_roll_pid().save_gains(); - // stabilize roll - attitude_control->get_angle_roll_p().kP(tune_roll_sp); + // save stabilize roll attitude_control->get_angle_roll_p().save_gains(); - // acceleration roll - attitude_control->save_accel_roll_max_cdss(tune_roll_accel); - // resave pids to originals in case the autotune is run again orig_roll_rp = attitude_control->get_rate_roll_pid().kP(); orig_roll_ri = attitude_control->get_rate_roll_pid().kI(); @@ -646,22 +590,13 @@ void AC_AutoTune_Heli::save_tuning_gains() } if ((axes_completed & AUTOTUNE_AXIS_BITMASK_PITCH) && pitch_enabled()) { - // rate pitch gains - attitude_control->get_rate_pitch_pid().kP(tune_pitch_rp); - attitude_control->get_rate_pitch_pid().kI(tune_pitch_rff*AUTOTUNE_FFI_RATIO_FINAL); - attitude_control->get_rate_pitch_pid().kD(tune_pitch_rd); - attitude_control->get_rate_pitch_pid().ff(tune_pitch_rff); - attitude_control->get_rate_pitch_pid().filt_T_hz(orig_pitch_fltt); - attitude_control->get_rate_pitch_pid().slew_limit(orig_pitch_smax); + load_gain_set(PITCH, tune_pitch_rp, tune_pitch_rff*AUTOTUNE_FFI_RATIO_FINAL, tune_pitch_rd, tune_pitch_rff, tune_pitch_sp, tune_pitch_accel, orig_pitch_fltt, 0.0f, orig_pitch_smax); + // save rate pitch gains attitude_control->get_rate_pitch_pid().save_gains(); - // stabilize pitch - attitude_control->get_angle_pitch_p().kP(tune_pitch_sp); + // save stabilize pitch attitude_control->get_angle_pitch_p().save_gains(); - // acceleration pitch - attitude_control->save_accel_pitch_max_cdss(tune_pitch_accel); - // resave pids to originals in case the autotune is run again orig_pitch_rp = attitude_control->get_rate_pitch_pid().kP(); orig_pitch_ri = attitude_control->get_rate_pitch_pid().kI(); @@ -672,23 +607,13 @@ void AC_AutoTune_Heli::save_tuning_gains() } if ((axes_completed & AUTOTUNE_AXIS_BITMASK_YAW) && yaw_enabled() && !is_zero(tune_yaw_rp)) { - // rate yaw gains - attitude_control->get_rate_yaw_pid().kP(tune_yaw_rp); - attitude_control->get_rate_yaw_pid().kI(tune_yaw_rp*AUTOTUNE_YAW_PI_RATIO_FINAL); - attitude_control->get_rate_yaw_pid().kD(tune_yaw_rd); - attitude_control->get_rate_yaw_pid().ff(tune_yaw_rff); - attitude_control->get_rate_yaw_pid().filt_T_hz(orig_yaw_fltt); - attitude_control->get_rate_yaw_pid().slew_limit(orig_yaw_smax); - attitude_control->get_rate_yaw_pid().filt_E_hz(orig_yaw_rLPF); + load_gain_set(YAW, tune_yaw_rp, tune_yaw_rp*AUTOTUNE_YAW_PI_RATIO_FINAL, tune_yaw_rd, tune_yaw_rff, tune_yaw_sp, tune_yaw_accel, orig_yaw_fltt, orig_yaw_rLPF, orig_yaw_smax); + // save rate yaw gains attitude_control->get_rate_yaw_pid().save_gains(); - // stabilize yaw - attitude_control->get_angle_yaw_p().kP(tune_yaw_sp); + // save stabilize yaw attitude_control->get_angle_yaw_p().save_gains(); - // acceleration yaw - attitude_control->save_accel_yaw_max_cdss(tune_yaw_accel); - // resave pids to originals in case the autotune is run again orig_yaw_rp = attitude_control->get_rate_yaw_pid().kP(); orig_yaw_ri = attitude_control->get_rate_yaw_pid().kI(); @@ -925,181 +850,231 @@ void AC_AutoTune_Heli::rate_ff_test_run(float max_angle_cd, float target_rate_cd } -void AC_AutoTune_Heli::dwell_test_init(float start_frq, float filt_freq) +void AC_AutoTune_Heli::dwell_test_init(float start_frq, float stop_frq, float filt_freq, DwellType dwell_type) { - rotation_rate_filt.reset(0); + dwell_start_time_ms = 0.0f; + settle_time = 200; + rotation_rate_filt.set_cutoff_frequency(filt_freq); - command_filt.reset(0); command_filt.set_cutoff_frequency(filt_freq); - target_rate_filt.reset(0); target_rate_filt.set_cutoff_frequency(filt_freq); + + rotation_rate_filt.reset(0); + command_filt.reset(0); + target_rate_filt.reset(0); + rotation_rate = 0.0f; + command_out = 0.0f; filt_target_rate = 0.0f; - dwell_start_time_ms = 0.0f; - settle_time = 200; - if (!is_equal(start_freq, stop_freq)) { - reset_sweep_variables(); - curr_test_gain = 0.0f; - curr_test_phase = 0.0f; - } // filter at lower frequency to remove steady state filt_command_reading.set_cutoff_frequency(0.2f * start_frq); filt_gyro_reading.set_cutoff_frequency(0.2f * start_frq); filt_tgt_rate_reading.set_cutoff_frequency(0.2f * start_frq); - filt_pit_roll_cd.set_cutoff_frequency(0.2f * start_frq); - filt_heading_error_cd.set_cutoff_frequency(0.2f * start_frq); filt_att_fdbk_from_velxy_cd.set_cutoff_frequency(0.2f * start_frq); - // save the trim output from PID controller - float ff_term = 0.0f; - float p_term = 0.0f; - switch (axis) { - case ROLL: - trim_meas_rate = ahrs_view->get_gyro().x; - ff_term = attitude_control->get_rate_roll_pid().get_ff(); - p_term = attitude_control->get_rate_roll_pid().get_p(); - break; - case PITCH: - trim_meas_rate = ahrs_view->get_gyro().y; - ff_term = attitude_control->get_rate_pitch_pid().get_ff(); - p_term = attitude_control->get_rate_pitch_pid().get_p(); - break; - case YAW: - trim_meas_rate = ahrs_view->get_gyro().z; - ff_term = attitude_control->get_rate_yaw_pid().get_ff(); - p_term = attitude_control->get_rate_yaw_pid().get_p(); - break; + if (dwell_type == RATE) { + filt_pit_roll_cd.set_cutoff_frequency(0.2f * start_frq); + filt_heading_error_cd.set_cutoff_frequency(0.2f * start_frq); + + // save the trim output from PID controller + float ff_term = 0.0f; + float p_term = 0.0f; + switch (axis) { + case ROLL: + trim_meas_rate = ahrs_view->get_gyro().x; + ff_term = attitude_control->get_rate_roll_pid().get_ff(); + p_term = attitude_control->get_rate_roll_pid().get_p(); + break; + case PITCH: + trim_meas_rate = ahrs_view->get_gyro().y; + ff_term = attitude_control->get_rate_pitch_pid().get_ff(); + p_term = attitude_control->get_rate_pitch_pid().get_p(); + break; + case YAW: + trim_meas_rate = ahrs_view->get_gyro().z; + ff_term = attitude_control->get_rate_yaw_pid().get_ff(); + p_term = attitude_control->get_rate_yaw_pid().get_p(); + break; + } + trim_pff_out = ff_term + p_term; + } + + if (!is_equal(start_frq, stop_frq)) { + reset_sweep_variables(); + curr_test.gain = 0.0f; + curr_test.phase = 0.0f; } - trim_pff_out = ff_term + p_term; + + chirp_input.init(sweep_time_ms * 0.001f, start_frq / M_2PI, stop_frq / M_2PI, 0.0f, 0.0001f * sweep_time_ms, 0.0f); + } -void AC_AutoTune_Heli::dwell_test_run(uint8_t freq_resp_input, float start_frq, float stop_frq, float &dwell_gain, float &dwell_phase) +void AC_AutoTune_Heli::dwell_test_run(uint8_t freq_resp_input, float start_frq, float stop_frq, float &dwell_gain, float &dwell_phase, DwellType dwell_type) { float gyro_reading = 0.0f; float command_reading = 0.0f; float tgt_rate_reading = 0.0f; - float tgt_attitude = 2.5f * 0.01745f; + float tgt_attitude; const uint32_t now = AP_HAL::millis(); + float target_angle_cd; float target_rate_cds; - float sweep_time_ms = 23000; + float dwell_freq = start_frq; + float target_rate_mag_cds; const float att_hold_gain = 4.5f; - Vector3f attitude_cd; - float dwell_freq = start_frq; float cycle_time_ms = 0; if (!is_zero(dwell_freq)) { - cycle_time_ms = 1000.0f * 2.0f * M_PI / dwell_freq; + cycle_time_ms = 1000.0f * M_2PI / dwell_freq; + } + + if (dwell_type == RATE) { + // keep controller from requesting too high of a rate + tgt_attitude = 2.5f * 0.01745f; + target_rate_mag_cds = dwell_freq * tgt_attitude * 5730.0f; + if (target_rate_mag_cds > 5000.0f) { + target_rate_mag_cds = 5000.0f; + } + } else { + tgt_attitude = 5.0f * 0.01745f; + // adjust target attitude based on input_tc so amplitude decrease with increased frequency is minimized + const float freq_co = 1.0f / attitude_control->get_input_tc(); + const float added_ampl = (safe_sqrt(powf(dwell_freq,2.0) + powf(freq_co,2.0)) / freq_co) - 1.0f; + tgt_attitude = constrain_float(0.08725f * (1.0f + 0.2f * added_ampl), 0.08725f, 0.5235f); } - attitude_cd = Vector3f((float)ahrs_view->roll_sensor, (float)ahrs_view->pitch_sensor, (float)ahrs_view->yaw_sensor); + // body frame calculation of velocity Vector3f velocity_ned, velocity_bf; if (ahrs_view->get_velocity_NED(velocity_ned)) { velocity_bf.x = velocity_ned.x * ahrs_view->cos_yaw() + velocity_ned.y * ahrs_view->sin_yaw(); velocity_bf.y = -velocity_ned.x * ahrs_view->sin_yaw() + velocity_ned.y * ahrs_view->cos_yaw(); } - // keep controller from requesting too high of a rate - float target_rate_mag_cds = dwell_freq * tgt_attitude * 5730.0f; - if (target_rate_mag_cds > 5000.0f) { - target_rate_mag_cds = 5000.0f; - } + Vector3f attitude_cd = Vector3f((float)ahrs_view->roll_sensor, (float)ahrs_view->pitch_sensor, (float)ahrs_view->yaw_sensor); if (settle_time == 0) { - // give gentler start for the dwell - if ((float)(now - dwell_start_time_ms) < 0.5f * cycle_time_ms) { - target_rate_cds = -0.5f * target_rate_mag_cds * sinf(dwell_freq * (now - dwell_start_time_ms) * 0.001); + if (dwell_type == RATE) { + target_rate_cds = -chirp_input.update((now - dwell_start_time_ms) * 0.001, target_rate_mag_cds); + filt_pit_roll_cd.apply(Vector2f(attitude_cd.x,attitude_cd.y), AP::scheduler().get_loop_period_s()); + filt_heading_error_cd.apply(wrap_180_cd(trim_attitude_cd.z - attitude_cd.z), AP::scheduler().get_loop_period_s()); } else { - if (is_equal(start_frq,stop_frq)) { - target_rate_cds = - target_rate_mag_cds * cosf(dwell_freq * (now - dwell_start_time_ms - 0.25f * cycle_time_ms) * 0.001); - } else { - target_rate_cds = waveform((now - dwell_start_time_ms - 0.5f * cycle_time_ms) * 0.001, (sweep_time_ms - 0.5f * cycle_time_ms) * 0.001f, target_rate_mag_cds, start_frq, stop_frq); - dwell_freq = waveform_freq_rads; - } + target_angle_cd = -chirp_input.update((now - dwell_start_time_ms) * 0.001, tgt_attitude * 5730.0f); } - filt_pit_roll_cd.apply(Vector2f(attitude_cd.x,attitude_cd.y), AP::scheduler().get_loop_period_s()); - filt_heading_error_cd.apply(wrap_180_cd(trim_attitude_cd.z - attitude_cd.z), AP::scheduler().get_loop_period_s()); - Vector2f att_fdbk = Vector2f(-5730.0f * vel_hold_gain * velocity_bf.y, 5730.0f * vel_hold_gain * velocity_bf.x); + const Vector2f att_fdbk { + -5730.0f * vel_hold_gain * velocity_bf.y, + 5730.0f * vel_hold_gain * velocity_bf.x + }; filt_att_fdbk_from_velxy_cd.apply(att_fdbk, AP::scheduler().get_loop_period_s()); + dwell_freq = chirp_input.get_frequency_rads(); } else { - target_rate_cds = 0.0f; - settle_time--; + if (dwell_type == RATE) { + target_rate_cds = 0.0f; + trim_command = command_out; + trim_attitude_cd = attitude_cd; + filt_pit_roll_cd.reset(Vector2f(attitude_cd.x,attitude_cd.y)); + filt_heading_error_cd.reset(0.0f); + } else { + target_angle_cd = 0.0f; + trim_yaw_tgt_reading = (float)attitude_control->get_att_target_euler_cd().z; + trim_yaw_heading_reading = (float)ahrs_view->yaw_sensor; + } dwell_start_time_ms = now; - trim_command = command_out; - trim_attitude_cd = attitude_cd; - filt_pit_roll_cd.reset(Vector2f(attitude_cd.x,attitude_cd.y)); - filt_heading_error_cd.reset(0.0f); filt_att_fdbk_from_velxy_cd.reset(Vector2f(0.0f,0.0f)); + settle_time--; } - // limit rate correction for position hold - Vector3f trim_rate_cds; - trim_rate_cds.x = att_hold_gain * ((trim_attitude_cd.x + filt_att_fdbk_from_velxy_cd.get().x) - filt_pit_roll_cd.get().x); - trim_rate_cds.y = att_hold_gain * ((trim_attitude_cd.y + filt_att_fdbk_from_velxy_cd.get().y) - filt_pit_roll_cd.get().y); - trim_rate_cds.z = att_hold_gain * filt_heading_error_cd.get(); - trim_rate_cds.x = constrain_float(trim_rate_cds.x, -15000.0f, 15000.0f); - trim_rate_cds.y = constrain_float(trim_rate_cds.y, -15000.0f, 15000.0f); - trim_rate_cds.z = constrain_float(trim_rate_cds.z, -15000.0f, 15000.0f); - - switch (axis) { - case ROLL: - gyro_reading = ahrs_view->get_gyro().x; - command_reading = motors->get_roll(); - tgt_rate_reading = attitude_control->rate_bf_targets().x; - if (settle_time == 0) { - float ff_rate_contr = 0.0f; - if (tune_roll_rff > 0.0f) { - ff_rate_contr = 5730.0f * trim_command / tune_roll_rff; - } - trim_rate_cds.x += ff_rate_contr; - attitude_control->input_rate_bf_roll_pitch_yaw(0.0f, trim_rate_cds.y, 0.0f); - attitude_control->rate_bf_roll_target(target_rate_cds + trim_rate_cds.x); - } else { - attitude_control->input_rate_bf_roll_pitch_yaw(0.0f, 0.0f, 0.0f); - if (!is_zero(attitude_control->get_rate_roll_pid().ff() + attitude_control->get_rate_roll_pid().kP())) { - float trim_tgt_rate_cds = 5730.0f * (trim_pff_out + trim_meas_rate * attitude_control->get_rate_roll_pid().kP()) / (attitude_control->get_rate_roll_pid().ff() + attitude_control->get_rate_roll_pid().kP()); - attitude_control->rate_bf_roll_target(trim_tgt_rate_cds); + if (dwell_type == RATE) { + // limit rate correction for position hold + Vector3f trim_rate_cds { + constrain_float(att_hold_gain * ((trim_attitude_cd.x + filt_att_fdbk_from_velxy_cd.get().x) - filt_pit_roll_cd.get().x), -15000.0f, 15000.0f), + constrain_float(att_hold_gain * ((trim_attitude_cd.y + filt_att_fdbk_from_velxy_cd.get().y) - filt_pit_roll_cd.get().y), -15000.0f, 15000.0f), + constrain_float(att_hold_gain * filt_heading_error_cd.get(), -15000.0f, 15000.0f) + }; + switch (axis) { + case ROLL: + gyro_reading = ahrs_view->get_gyro().x; + command_reading = motors->get_roll(); + tgt_rate_reading = attitude_control->rate_bf_targets().x; + if (settle_time == 0) { + float ff_rate_contr = 0.0f; + if (tune_roll_rff > 0.0f) { + ff_rate_contr = 5730.0f * trim_command / tune_roll_rff; + } + trim_rate_cds.x += ff_rate_contr; + attitude_control->input_rate_bf_roll_pitch_yaw(0.0f, trim_rate_cds.y, 0.0f); + attitude_control->rate_bf_roll_target(target_rate_cds + trim_rate_cds.x); + } else { + attitude_control->input_rate_bf_roll_pitch_yaw(0.0f, 0.0f, 0.0f); + if (!is_zero(attitude_control->get_rate_roll_pid().ff() + attitude_control->get_rate_roll_pid().kP())) { + float trim_tgt_rate_cds = 5730.0f * (trim_pff_out + trim_meas_rate * attitude_control->get_rate_roll_pid().kP()) / (attitude_control->get_rate_roll_pid().ff() + attitude_control->get_rate_roll_pid().kP()); + attitude_control->rate_bf_roll_target(trim_tgt_rate_cds); + } } - } - break; - case PITCH: - gyro_reading = ahrs_view->get_gyro().y; - command_reading = motors->get_pitch(); - tgt_rate_reading = attitude_control->rate_bf_targets().y; - if (settle_time == 0) { - float ff_rate_contr = 0.0f; - if (tune_pitch_rff > 0.0f) { - ff_rate_contr = 5730.0f * trim_command / tune_pitch_rff; + break; + case PITCH: + gyro_reading = ahrs_view->get_gyro().y; + command_reading = motors->get_pitch(); + tgt_rate_reading = attitude_control->rate_bf_targets().y; + if (settle_time == 0) { + float ff_rate_contr = 0.0f; + if (tune_pitch_rff > 0.0f) { + ff_rate_contr = 5730.0f * trim_command / tune_pitch_rff; + } + trim_rate_cds.y += ff_rate_contr; + attitude_control->input_rate_bf_roll_pitch_yaw(trim_rate_cds.x, 0.0f, 0.0f); + attitude_control->rate_bf_pitch_target(target_rate_cds + trim_rate_cds.y); + } else { + attitude_control->input_rate_bf_roll_pitch_yaw(0.0f, 0.0f, 0.0f); + if (!is_zero(attitude_control->get_rate_pitch_pid().ff() + attitude_control->get_rate_pitch_pid().kP())) { + float trim_tgt_rate_cds = 5730.0f * (trim_pff_out + trim_meas_rate * attitude_control->get_rate_pitch_pid().kP()) / (attitude_control->get_rate_pitch_pid().ff() + attitude_control->get_rate_pitch_pid().kP()); + attitude_control->rate_bf_pitch_target(trim_tgt_rate_cds); + } } - trim_rate_cds.y += ff_rate_contr; - attitude_control->input_rate_bf_roll_pitch_yaw(trim_rate_cds.x, 0.0f, 0.0f); - attitude_control->rate_bf_pitch_target(target_rate_cds + trim_rate_cds.y); - } else { - attitude_control->input_rate_bf_roll_pitch_yaw(0.0f, 0.0f, 0.0f); - if (!is_zero(attitude_control->get_rate_pitch_pid().ff() + attitude_control->get_rate_pitch_pid().kP())) { - float trim_tgt_rate_cds = 5730.0f * (trim_pff_out + trim_meas_rate * attitude_control->get_rate_pitch_pid().kP()) / (attitude_control->get_rate_pitch_pid().ff() + attitude_control->get_rate_pitch_pid().kP()); - attitude_control->rate_bf_pitch_target(trim_tgt_rate_cds); + break; + case YAW: + gyro_reading = ahrs_view->get_gyro().z; + command_reading = motors->get_yaw(); + tgt_rate_reading = attitude_control->rate_bf_targets().z; + if (settle_time == 0) { + float rp_rate_contr = 0.0f; + if (tune_yaw_rp > 0.0f) { + rp_rate_contr = 5730.0f * trim_command / tune_yaw_rp; + } + trim_rate_cds.z += rp_rate_contr; + attitude_control->input_rate_bf_roll_pitch_yaw(trim_rate_cds.x, trim_rate_cds.y, 0.0f); + attitude_control->rate_bf_yaw_target(target_rate_cds + trim_rate_cds.z); + } else { + attitude_control->input_rate_bf_roll_pitch_yaw(0.0f, 0.0f, 0.0f); + if (!is_zero(attitude_control->get_rate_yaw_pid().ff() + attitude_control->get_rate_yaw_pid().kP())) { + float trim_tgt_rate_cds = 5730.0f * (trim_pff_out + trim_meas_rate * attitude_control->get_rate_yaw_pid().kP()) / (attitude_control->get_rate_yaw_pid().ff() + attitude_control->get_rate_yaw_pid().kP()); + attitude_control->rate_bf_yaw_target(trim_tgt_rate_cds); + } } + break; } - break; - case YAW: - gyro_reading = ahrs_view->get_gyro().z; - command_reading = motors->get_yaw(); - tgt_rate_reading = attitude_control->rate_bf_targets().z; - if (settle_time == 0) { - float rp_rate_contr = 0.0f; - if (tune_yaw_rp > 0.0f) { - rp_rate_contr = 5730.0f * trim_command / tune_yaw_rp; - } - trim_rate_cds.z += rp_rate_contr; - attitude_control->input_rate_bf_roll_pitch_yaw(trim_rate_cds.x, trim_rate_cds.y, 0.0f); - attitude_control->rate_bf_yaw_target(target_rate_cds + trim_rate_cds.z); - } else { - attitude_control->input_rate_bf_roll_pitch_yaw(0.0f, 0.0f, 0.0f); - if (!is_zero(attitude_control->get_rate_yaw_pid().ff() + attitude_control->get_rate_yaw_pid().kP())) { - float trim_tgt_rate_cds = 5730.0f * (trim_pff_out + trim_meas_rate * attitude_control->get_rate_yaw_pid().kP()) / (attitude_control->get_rate_yaw_pid().ff() + attitude_control->get_rate_yaw_pid().kP()); - attitude_control->rate_bf_yaw_target(trim_tgt_rate_cds); - } + } else { + const Vector2f trim_angle_cd { + constrain_float(filt_att_fdbk_from_velxy_cd.get().x, -2000.0f, 2000.0f), + constrain_float(filt_att_fdbk_from_velxy_cd.get().y, -2000.0f, 2000.0f) + }; + switch (axis) { + case ROLL: + attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_angle_cd + trim_angle_cd.x, trim_angle_cd.y, 0.0f); + command_reading = motors->get_roll(); + tgt_rate_reading = ((float)attitude_control->get_att_target_euler_cd().x) / 5730.0f; + gyro_reading = ((float)ahrs_view->roll_sensor) / 5730.0f; + break; + case PITCH: + attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(trim_angle_cd.x, target_angle_cd + trim_angle_cd.y, 0.0f); + command_reading = motors->get_pitch(); + tgt_rate_reading = ((float)attitude_control->get_att_target_euler_cd().y) / 5730.0f; + gyro_reading = ((float)ahrs_view->pitch_sensor) / 5730.0f; + break; + case YAW: + command_reading = motors->get_yaw(); + tgt_rate_reading = (wrap_180_cd((float)attitude_control->get_att_target_euler_cd().z - trim_yaw_tgt_reading)) / 5730.0f; + gyro_reading = (wrap_180_cd((float)ahrs_view->yaw_sensor - trim_yaw_heading_reading)) / 5730.0f; + attitude_control->input_euler_angle_roll_pitch_yaw(trim_angle_cd.x, trim_angle_cd.y, wrap_180_cd(trim_yaw_tgt_reading + target_angle_cd), false); + break; } - break; } if (settle_time == 0) { @@ -1114,303 +1089,67 @@ void AC_AutoTune_Heli::dwell_test_run(uint8_t freq_resp_input, float start_frq, // looks at gain and phase of input rate to output rate rotation_rate = rotation_rate_filt.apply((gyro_reading - filt_gyro_reading.get()), - AP::scheduler().get_loop_period_s()); + AP::scheduler().get_loop_period_s()); filt_target_rate = target_rate_filt.apply((tgt_rate_reading - filt_tgt_rate_reading.get()), - AP::scheduler().get_loop_period_s()); + AP::scheduler().get_loop_period_s()); command_out = command_filt.apply((command_reading - filt_command_reading.get()), - AP::scheduler().get_loop_period_s()); + AP::scheduler().get_loop_period_s()); - // wait for dwell to start before determining gain and phase or just start if sweep + // wait for dwell to start before determining gain and phase if ((float)(now - dwell_start_time_ms) > 6.25f * cycle_time_ms || (!is_equal(start_frq,stop_frq) && settle_time == 0)) { if (freq_resp_input == 1) { - freqresp_rate.update(command_out,filt_target_rate,rotation_rate, dwell_freq); + freqresp.update(command_out,filt_target_rate,rotation_rate, dwell_freq); } else { - freqresp_rate.update(command_out,command_out,rotation_rate, dwell_freq); + freqresp.update(command_out,command_out,rotation_rate, dwell_freq); } - if (freqresp_rate.is_cycle_complete()) { + + if (freqresp.is_cycle_complete()) { if (!is_equal(start_frq,stop_frq)) { - curr_test_freq = freqresp_rate.get_freq(); - curr_test_gain = freqresp_rate.get_gain(); - curr_test_phase = freqresp_rate.get_phase(); + curr_test.freq = freqresp.get_freq(); + curr_test.gain = freqresp.get_gain(); + curr_test.phase = freqresp.get_phase(); + if (dwell_type == ANGLE) {test_accel_max = freqresp.get_accel_max();} // reset cycle_complete to allow indication of next cycle - freqresp_rate.reset_cycle_complete(); + freqresp.reset_cycle_complete(); // log sweep data Log_AutoTuneSweep(); } else { - dwell_gain = freqresp_rate.get_gain(); - dwell_phase = freqresp_rate.get_phase(); + dwell_gain = freqresp.get_gain(); + dwell_phase = freqresp.get_phase(); + if (dwell_type == ANGLE) {test_accel_max = freqresp.get_accel_max();} } - } } // set sweep data if a frequency sweep is being conducted if (!is_equal(start_frq,stop_frq) && (float)(now - dwell_start_time_ms) > 2.5f * cycle_time_ms) { // track sweep phase to prevent capturing 180 deg and 270 deg data after phase has wrapped. - if (curr_test_phase > 180.0f && sweep.progress == 0) { + if (curr_test.phase > 180.0f && sweep.progress == 0) { sweep.progress = 1; - } else if (curr_test_phase > 270.0f && sweep.progress == 1) { + } else if (curr_test.phase > 270.0f && sweep.progress == 1) { sweep.progress = 2; } - if (curr_test_phase <= 160.0f && curr_test_phase >= 150.0f && sweep.progress == 0) { - sweep.ph180_freq = curr_test_freq; - sweep.ph180_gain = curr_test_gain; - sweep.ph180_phase = curr_test_phase; + if (curr_test.phase <= 160.0f && curr_test.phase >= 150.0f && sweep.progress == 0) { + sweep.ph180 = curr_test; } - if (curr_test_phase <= 250.0f && curr_test_phase >= 240.0f && sweep.progress == 1) { - sweep.ph270_freq = curr_test_freq; - sweep.ph270_gain = curr_test_gain; - sweep.ph270_phase = curr_test_phase; + if (curr_test.phase <= 250.0f && curr_test.phase >= 240.0f && sweep.progress == 1) { + sweep.ph270 = curr_test; } - if (curr_test_gain > sweep.maxgain_gain) { - sweep.maxgain_gain = curr_test_gain; - sweep.maxgain_freq = curr_test_freq; - sweep.maxgain_phase = curr_test_phase; + if (curr_test.gain > sweep.maxgain.gain) { + sweep.maxgain = curr_test; } if (now - step_start_time_ms >= sweep_time_ms + 200) { // we have passed the maximum stop time step = UPDATE_GAINS; } - } else { - if (now - step_start_time_ms >= step_time_limit_ms || freqresp_rate.is_cycle_complete()) { + if (now - step_start_time_ms >= step_time_limit_ms || freqresp.is_cycle_complete()) { // we have passed the maximum stop time step = UPDATE_GAINS; } } } -void AC_AutoTune_Heli::angle_dwell_test_init(float start_frq, float filt_freq) -{ - rotation_rate_filt.set_cutoff_frequency(filt_freq); - command_filt.set_cutoff_frequency(filt_freq); - target_rate_filt.set_cutoff_frequency(filt_freq); - dwell_start_time_ms = 0.0f; - settle_time = 200; - switch (axis) { - case ROLL: - rotation_rate_filt.reset(((float)ahrs_view->roll_sensor) / 5730.0f); - command_filt.reset(motors->get_roll()); - target_rate_filt.reset(((float)attitude_control->get_att_target_euler_cd().x) / 5730.0f); - rotation_rate = ((float)ahrs_view->roll_sensor) / 5730.0f; - command_out = motors->get_roll(); - filt_target_rate = ((float)attitude_control->get_att_target_euler_cd().x) / 5730.0f; - break; - case PITCH: - rotation_rate_filt.reset(((float)ahrs_view->pitch_sensor) / 5730.0f); - command_filt.reset(motors->get_pitch()); - target_rate_filt.reset(((float)attitude_control->get_att_target_euler_cd().y) / 5730.0f); - rotation_rate = ((float)ahrs_view->pitch_sensor) / 5730.0f; - command_out = motors->get_pitch(); - filt_target_rate = ((float)attitude_control->get_att_target_euler_cd().y) / 5730.0f; - break; - case YAW: - // yaw angle will be centered on zero by removing trim heading - rotation_rate_filt.reset(0.0f); - command_filt.reset(motors->get_yaw()); - target_rate_filt.reset(0.0f); - rotation_rate = 0.0f; - command_out = motors->get_yaw(); - filt_target_rate = 0.0f; - break; - } - - // filter at lower frequency to remove steady state - filt_command_reading.set_cutoff_frequency(0.2f * start_frq); - filt_gyro_reading.set_cutoff_frequency(0.2f * start_frq); - filt_tgt_rate_reading.set_cutoff_frequency(0.2f * start_frq); - filt_att_fdbk_from_velxy_cd.set_cutoff_frequency(0.2f * start_frq); - - if (!is_equal(start_freq, stop_freq)) { - reset_sweep_variables(); - curr_test_gain = 0.0f; - curr_test_phase = 0.0f; - } -} - -void AC_AutoTune_Heli::angle_dwell_test_run(float start_frq, float stop_frq, float &dwell_gain, float &dwell_phase) -{ - float gyro_reading = 0.0f; - float command_reading = 0.0f; - float tgt_rate_reading = 0.0f; - float tgt_attitude = 5.0f * 0.01745f; - const uint32_t now = AP_HAL::millis(); - float target_angle_cd; - float sweep_time_ms = 23000; - float dwell_freq = start_frq; - - // adjust target attitude based on input_tc so amplitude decrease with increased frequency is minimized - const float freq_co = 1.0f / attitude_control->get_input_tc(); - const float added_ampl = (safe_sqrt(powf(dwell_freq,2.0) + powf(freq_co,2.0)) / freq_co) - 1.0f; - tgt_attitude = constrain_float(0.08725f * (1.0f + 0.2f * added_ampl), 0.08725f, 0.5235f); - - float cycle_time_ms = 0; - if (!is_zero(dwell_freq)) { - cycle_time_ms = 1000.0f * 6.28f / dwell_freq; - } - - // body frame calculation of velocity - Vector3f velocity_ned, velocity_bf; - if (ahrs_view->get_velocity_NED(velocity_ned)) { - velocity_bf.x = velocity_ned.x * ahrs_view->cos_yaw() + velocity_ned.y * ahrs_view->sin_yaw(); - velocity_bf.y = -velocity_ned.x * ahrs_view->sin_yaw() + velocity_ned.y * ahrs_view->cos_yaw(); - } - - if (settle_time == 0) { - // give gentler start for the dwell - if ((float)(now - dwell_start_time_ms) < 0.5f * cycle_time_ms) { - target_angle_cd = 0.5f * tgt_attitude * 5730.0f * (cosf(dwell_freq * (now - dwell_start_time_ms) * 0.001) - 1.0f); - } else { - if (is_equal(start_frq,stop_frq)) { - target_angle_cd = -tgt_attitude * 5730.0f * sinf(dwell_freq * (now - dwell_start_time_ms - 0.25f * cycle_time_ms) * 0.001); - } else { - target_angle_cd = -waveform((now - dwell_start_time_ms - 0.25f * cycle_time_ms) * 0.001, (sweep_time_ms - 0.25f * cycle_time_ms) * 0.001f, tgt_attitude * 5730.0f, start_frq, stop_frq); - dwell_freq = waveform_freq_rads; - } - } - Vector2f att_fdbk = Vector2f(-5730.0f * vel_hold_gain * velocity_bf.y, 5730.0f * vel_hold_gain * velocity_bf.x); - filt_att_fdbk_from_velxy_cd.apply(att_fdbk, AP::scheduler().get_loop_period_s()); - } else { - target_angle_cd = 0.0f; - trim_yaw_tgt_reading = (float)attitude_control->get_att_target_euler_cd().z; - trim_yaw_heading_reading = (float)ahrs_view->yaw_sensor; - settle_time--; - dwell_start_time_ms = now; - filt_att_fdbk_from_velxy_cd.reset(Vector2f(0.0f,0.0f)); - } - - Vector2f trim_angle_cd; - trim_angle_cd.x = constrain_float(filt_att_fdbk_from_velxy_cd.get().x, -2000.0f, 2000.0f); - trim_angle_cd.y = constrain_float(filt_att_fdbk_from_velxy_cd.get().y, -2000.0f, 2000.0f); - switch (axis) { - case ROLL: - attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_angle_cd + trim_angle_cd.x, trim_angle_cd.y, 0.0f); - command_reading = motors->get_roll(); - tgt_rate_reading = ((float)attitude_control->get_att_target_euler_cd().x) / 5730.0f; - gyro_reading = ((float)ahrs_view->roll_sensor) / 5730.0f; - break; - case PITCH: - attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(trim_angle_cd.x, target_angle_cd + trim_angle_cd.y, 0.0f); - command_reading = motors->get_pitch(); - tgt_rate_reading = ((float)attitude_control->get_att_target_euler_cd().y) / 5730.0f; - gyro_reading = ((float)ahrs_view->pitch_sensor) / 5730.0f; - break; - case YAW: - command_reading = motors->get_yaw(); - tgt_rate_reading = (wrap_180_cd((float)attitude_control->get_att_target_euler_cd().z - trim_yaw_tgt_reading)) / 5730.0f; - gyro_reading = (wrap_180_cd((float)ahrs_view->yaw_sensor - trim_yaw_heading_reading)) / 5730.0f; - attitude_control->input_euler_angle_roll_pitch_yaw(trim_angle_cd.x, trim_angle_cd.y, wrap_180_cd(trim_yaw_tgt_reading + target_angle_cd), false); - break; - } - - if (settle_time == 0) { - filt_command_reading.apply(command_reading, AP::scheduler().get_loop_period_s()); - filt_gyro_reading.apply(gyro_reading, AP::scheduler().get_loop_period_s()); - filt_tgt_rate_reading.apply(tgt_rate_reading, AP::scheduler().get_loop_period_s()); - } else { - filt_command_reading.reset(command_reading); - filt_gyro_reading.reset(gyro_reading); - filt_tgt_rate_reading.reset(tgt_rate_reading); - } - - // looks at gain and phase of input rate to output rate - rotation_rate = rotation_rate_filt.apply((gyro_reading - filt_gyro_reading.get()), - AP::scheduler().get_loop_period_s()); - filt_target_rate = target_rate_filt.apply((tgt_rate_reading - filt_tgt_rate_reading.get()), - AP::scheduler().get_loop_period_s()); - command_out = command_filt.apply((command_reading - filt_command_reading.get()), - AP::scheduler().get_loop_period_s()); - - // wait for dwell to start before determining gain and phase - if ((float)(now - dwell_start_time_ms) > 6.25f * cycle_time_ms || (!is_equal(start_frq,stop_frq) && settle_time == 0)) { - freqresp_angle.update(command_out, filt_target_rate, rotation_rate, dwell_freq); - if (freqresp_angle.is_cycle_complete()) { - if (!is_equal(start_frq,stop_frq)) { - curr_test_freq = freqresp_angle.get_freq(); - curr_test_gain = freqresp_angle.get_gain(); - curr_test_phase = freqresp_angle.get_phase(); - test_accel_max = freqresp_angle.get_accel_max(); - // reset cycle_complete to allow indication of next cycle - freqresp_angle.reset_cycle_complete(); - // log sweep data - Log_AutoTuneSweep(); - } else { - dwell_gain = freqresp_angle.get_gain(); - dwell_phase = freqresp_angle.get_phase(); - test_accel_max = freqresp_angle.get_accel_max(); - } - } - } - - // set sweep data if a frequency sweep is being conducted - if (!is_equal(start_frq,stop_frq)) { - if (curr_test_phase <= 160.0f && curr_test_phase >= 150.0f) { - sweep.ph180_freq = curr_test_freq; - sweep.ph180_gain = curr_test_gain; - sweep.ph180_phase = curr_test_phase; - } - if (curr_test_phase <= 250.0f && curr_test_phase >= 240.0f) { - sweep.ph270_freq = curr_test_freq; - sweep.ph270_gain = curr_test_gain; - sweep.ph270_phase = curr_test_phase; - } - if (curr_test_gain > sweep.maxgain_gain) { - sweep.maxgain_gain = curr_test_gain; - sweep.maxgain_freq = curr_test_freq; - sweep.maxgain_phase = curr_test_phase; - } - if (now - step_start_time_ms >= sweep_time_ms + 200) { - // we have passed the maximum stop time - step = UPDATE_GAINS; - } - } else { - if (now - step_start_time_ms >= step_time_limit_ms || freqresp_angle.is_cycle_complete()) { - // we have passed the maximum stop time - step = UPDATE_GAINS; - } - } -} - -// init_test - initialises the test -float AC_AutoTune_Heli::waveform(float time, float time_record, float waveform_magnitude, float wMin, float wMax) -{ - float time_fade_in = 0.0f; // Time to reach maximum amplitude of chirp - float time_fade_out = 0.1 * time_record; // Time to reach zero amplitude after chirp finishes - float time_const_freq = 0.0f; - - float window; - float output; - - float B = logf(wMax / wMin); - - if (time <= 0.0f) { - window = 0.0f; - } else if (time <= time_fade_in) { - window = 0.5 - 0.5 * cosf(M_PI * time / time_fade_in); - } else if (time <= time_record - time_fade_out) { - window = 1.0; - } else if (time <= time_record) { - window = 0.5 - 0.5 * cosf(M_PI * (time - (time_record - time_fade_out)) / time_fade_out + M_PI); - } else { - window = 0.0; - } - - if (time <= 0.0f) { - waveform_freq_rads = wMin; - output = 0.0f; - } else if (time <= time_const_freq) { - waveform_freq_rads = wMin; - output = window * waveform_magnitude * sinf(wMin * time - wMin * time_const_freq); - } else if (time <= time_record) { - waveform_freq_rads = wMin * expf(B * (time - time_const_freq) / (time_record - time_const_freq)); - output = window * waveform_magnitude * sinf((wMin * (time_record - time_const_freq) / B) * (expf(B * (time - time_const_freq) / (time_record - time_const_freq)) - 1)); - } else { - waveform_freq_rads = wMax; - output = 0.0f; - } - return output; -} - // update gains for the rate p up tune type void AC_AutoTune_Heli::updating_rate_p_up_all(AxisType test_axis) { @@ -1614,25 +1353,25 @@ void AC_AutoTune_Heli::updating_rate_p_up(float &tune_p, float *freq, float *gai frq_cnt++; if (frq_cnt == 12) { freq[frq_cnt] = freq[rp_prev_good_frq_cnt]; - curr_test_freq = freq[frq_cnt]; + curr_test.freq = freq[frq_cnt]; } else { freq[frq_cnt] = freq[frq_cnt-1] + test_freq_incr; - curr_test_freq = freq[frq_cnt]; + curr_test.freq = freq[frq_cnt]; } } else if (is_equal(start_freq,stop_freq)) { if (phase[frq_cnt] > 180.0f) { - curr_test_freq = curr_test_freq - 0.5 * test_freq_incr; - freq[frq_cnt] = curr_test_freq; + curr_test.freq = curr_test.freq - 0.5 * test_freq_incr; + freq[frq_cnt] = curr_test.freq; } else if (phase[frq_cnt] < 160.0f) { - curr_test_freq = curr_test_freq + 0.5 * test_freq_incr; - freq[frq_cnt] = curr_test_freq; + curr_test.freq = curr_test.freq + 0.5 * test_freq_incr; + freq[frq_cnt] = curr_test.freq; } else if (phase[frq_cnt] <= 180.0f && phase[frq_cnt] >= 160.0f) { if (gain[frq_cnt] < max_resp_gain && tune_p < 0.6f * max_gain_p.max_allowed) { tune_p += 0.05f * max_gain_p.max_allowed; } else { counter = AUTOTUNE_SUCCESS_COUNT; - // reset curr_test_freq and frq_cnt for next test - curr_test_freq = freq[0]; + // reset curr_test.freq and frq_cnt for next test + curr_test.freq = freq[0]; frq_cnt = 0; tune_p -= 0.05f * max_gain_p.max_allowed; tune_p = constrain_float(tune_p,0.0f,0.6f * max_gain_p.max_allowed); @@ -1643,8 +1382,8 @@ void AC_AutoTune_Heli::updating_rate_p_up(float &tune_p, float *freq, float *gai if (counter == AUTOTUNE_SUCCESS_COUNT) { start_freq = 0.0f; //initializes next test that uses dwell test } else { - start_freq = curr_test_freq; - stop_freq = curr_test_freq; + start_freq = curr_test.freq; + stop_freq = curr_test.freq; } } @@ -1655,15 +1394,15 @@ void AC_AutoTune_Heli::updating_rate_d_up(float &tune_d, float *freq, float *gai // frequency sweep was conducted. check to see if freq for 180 deg phase was determined and start there if it was if (!is_equal(start_freq,stop_freq)) { - if (!is_zero(sweep.ph180_freq)) { - freq[frq_cnt] = sweep.ph180_freq - 0.5f * test_freq_incr; + if (!is_zero(sweep.ph180.freq)) { + freq[frq_cnt] = sweep.ph180.freq - 0.5f * test_freq_incr; frq_cnt = 12; freq_cnt_max = frq_cnt; } else { frq_cnt = 1; freq[frq_cnt] = min_sweep_freq; } - curr_test_freq = freq[frq_cnt]; + curr_test.freq = freq[frq_cnt]; } // if sweep failed to find frequency for 180 phase then use dwell to find frequency if (frq_cnt < 12 && is_equal(start_freq,stop_freq)) { @@ -1679,26 +1418,26 @@ void AC_AutoTune_Heli::updating_rate_d_up(float &tune_d, float *freq, float *gai frq_cnt++; if (frq_cnt == 12) { freq[frq_cnt] = freq[rd_prev_good_frq_cnt]; - curr_test_freq = freq[frq_cnt]; + curr_test.freq = freq[frq_cnt]; } else { freq[frq_cnt] = freq[frq_cnt-1] + test_freq_incr; - curr_test_freq = freq[frq_cnt]; + curr_test.freq = freq[frq_cnt]; } } else if (is_equal(start_freq,stop_freq)) { if (phase[frq_cnt] > 180.0f) { - curr_test_freq = curr_test_freq - 0.5 * test_freq_incr; - freq[frq_cnt] = curr_test_freq; + curr_test.freq = curr_test.freq - 0.5 * test_freq_incr; + freq[frq_cnt] = curr_test.freq; } else if (phase[frq_cnt] < 160.0f) { - curr_test_freq = curr_test_freq + 0.5 * test_freq_incr; - freq[frq_cnt] = curr_test_freq; + curr_test.freq = curr_test.freq + 0.5 * test_freq_incr; + freq[frq_cnt] = curr_test.freq; } else if (phase[frq_cnt] <= 180.0f && phase[frq_cnt] >= 160.0f) { if ((gain[frq_cnt] < rd_prev_gain || is_zero(rd_prev_gain)) && tune_d < 0.6f * max_gain_d.max_allowed) { tune_d += 0.05f * max_gain_d.max_allowed; rd_prev_gain = gain[frq_cnt]; } else { counter = AUTOTUNE_SUCCESS_COUNT; - // reset curr_test_freq and frq_cnt for next test - curr_test_freq = freq[0]; + // reset curr_test.freq and frq_cnt for next test + curr_test.freq = freq[0]; frq_cnt = 0; rd_prev_gain = 0.0f; tune_d -= 0.05f * max_gain_d.max_allowed; @@ -1710,8 +1449,8 @@ void AC_AutoTune_Heli::updating_rate_d_up(float &tune_d, float *freq, float *gai start_freq = 0.0f; //initializes next test that uses dwell test reset_sweep_variables(); } else { - start_freq = curr_test_freq; - stop_freq = curr_test_freq; + start_freq = curr_test.freq; + stop_freq = curr_test.freq; } } @@ -1722,16 +1461,16 @@ void AC_AutoTune_Heli::updating_angle_p_up(float &tune_p, float *freq, float *ga float gain_incr = 0.5f; if (!is_equal(start_freq,stop_freq)) { - if (!is_zero(sweep.maxgain_freq)) { + if (!is_zero(sweep.maxgain.freq)) { frq_cnt = 12; - freq[frq_cnt] = sweep.maxgain_freq - 0.5f * test_freq_incr; + freq[frq_cnt] = sweep.maxgain.freq - 0.5f * test_freq_incr; freq_cnt_max = frq_cnt; } else { frq_cnt = 1; freq[frq_cnt] = min_sweep_freq; freq_cnt_max = 0; } - curr_test_freq = freq[frq_cnt]; + curr_test.freq = freq[frq_cnt]; } if (freq_cnt < 12 && is_equal(start_freq,stop_freq)) { if (gain[freq_cnt] > max_resp_gain && tune_p > AUTOTUNE_SP_MIN) { @@ -1755,10 +1494,10 @@ void AC_AutoTune_Heli::updating_angle_p_up(float &tune_p, float *freq, float *ga freq_cnt++; if (freq_cnt == 12) { freq[freq_cnt] = freq[freq_cnt_max]; - curr_test_freq = freq[freq_cnt]; + curr_test.freq = freq[freq_cnt]; } else { freq[freq_cnt] = freq[freq_cnt-1] + test_freq_incr; - curr_test_freq = freq[freq_cnt]; + curr_test.freq = freq[freq_cnt]; } } @@ -1778,7 +1517,7 @@ void AC_AutoTune_Heli::updating_angle_p_up(float &tune_p, float *freq, float *ga AP::logger().Write_Event(LogEvent::AUTOTUNE_REACHED_LIMIT); } } - curr_test_freq = freq[freq_cnt]; + curr_test.freq = freq[freq_cnt]; sp_prev_gain = gain[freq_cnt]; } else if (gain[freq_cnt] > 1.1f * max_resp_gain && tune_p > AUTOTUNE_SP_MIN && !find_peak) { tune_p -= gain_incr; @@ -1790,7 +1529,7 @@ void AC_AutoTune_Heli::updating_angle_p_up(float &tune_p, float *freq, float *ga find_peak = false; phase_max = phase[freq_cnt]; } - curr_test_freq = freq[freq_cnt]; + curr_test.freq = freq[freq_cnt]; sp_prev_gain = gain[freq_cnt]; } else { // adjust tuning gain so max response gain is not exceeded @@ -1804,11 +1543,11 @@ void AC_AutoTune_Heli::updating_angle_p_up(float &tune_p, float *freq, float *ga if (counter == AUTOTUNE_SUCCESS_COUNT) { start_freq = 0.0f; //initializes next test that uses dwell test reset_sweep_variables(); - curr_test_freq = freq[0]; + curr_test.freq = freq[0]; freq_cnt = 0; } else { - start_freq = curr_test_freq; - stop_freq = curr_test_freq; + start_freq = curr_test.freq; + stop_freq = curr_test.freq; } } @@ -1819,14 +1558,14 @@ void AC_AutoTune_Heli::updating_max_gains(float *freq, float *gain, float *phase if (!is_equal(start_freq,stop_freq)) { frq_cnt = 2; - if (!is_zero(sweep.ph180_freq)) { - freq[frq_cnt] = sweep.ph180_freq - 0.5f * test_freq_incr; + if (!is_zero(sweep.ph180.freq)) { + freq[frq_cnt] = sweep.ph180.freq - 0.5f * test_freq_incr; } else { freq[frq_cnt] = min_sweep_freq; } - curr_test_freq = freq[frq_cnt]; - start_freq = curr_test_freq; - stop_freq = curr_test_freq; + curr_test.freq = freq[frq_cnt]; + start_freq = curr_test.freq; + stop_freq = curr_test.freq; } else if (frq_cnt < 12 && is_equal(start_freq,stop_freq)) { if (frq_cnt > 2 && phase[frq_cnt] > 161.0f && phase[frq_cnt] < 270.0f && @@ -1849,11 +1588,11 @@ void AC_AutoTune_Heli::updating_max_gains(float *freq, float *gain, float *phase found_max_p = true; find_middle = false; - if (!is_zero(sweep.ph270_freq)) { + if (!is_zero(sweep.ph270.freq)) { // set freq cnt back to reinitialize process frq_cnt = 1; // set to 1 because it will be incremented // set frequency back at least one test_freq_incr as it will be added - freq[1] = sweep.ph270_freq - 1.5f * test_freq_incr; + freq[1] = sweep.ph270.freq - 1.5f * test_freq_incr; } } if (frq_cnt > 2 && phase[frq_cnt] > 251.0f && phase[frq_cnt] < 360.0f && @@ -1884,7 +1623,7 @@ void AC_AutoTune_Heli::updating_max_gains(float *freq, float *gain, float *phase if (frq_cnt == 12) { counter = AUTOTUNE_SUCCESS_COUNT; // reset variables for next test - curr_test_freq = freq[0]; + curr_test.freq = freq[0]; frq_cnt = 0; start_freq = 0.0f; //initializes next test that uses dwell test reset_sweep_variables(); @@ -1904,9 +1643,9 @@ void AC_AutoTune_Heli::updating_max_gains(float *freq, float *gain, float *phase } else { freq[frq_cnt] = freq[frq_cnt-1] + test_freq_incr; } - curr_test_freq = freq[frq_cnt]; - start_freq = curr_test_freq; - stop_freq = curr_test_freq; + curr_test.freq = freq[frq_cnt]; + start_freq = curr_test.freq; + stop_freq = curr_test.freq; } } if (found_max_p && found_max_d) { @@ -1948,7 +1687,7 @@ void AC_AutoTune_Heli::Log_AutoTuneDetails() // log autotune frequency response data void AC_AutoTune_Heli::Log_AutoTuneSweep() { - Log_Write_AutoTuneSweep(curr_test_freq, curr_test_gain, curr_test_phase); + Log_Write_AutoTuneSweep(curr_test.freq, curr_test.gain, curr_test.phase); } // @LoggerMessage: ATNH @@ -2074,14 +1813,8 @@ void AC_AutoTune_Heli::reset_update_gain_variables() // reset the max_gains update gain variables void AC_AutoTune_Heli::reset_maxgains_update_gain_variables() { - max_rate_p.freq = 0.0f; - max_rate_p.gain = 0.0f; - max_rate_p.phase = 0.0f; - max_rate_p.max_allowed = 0.0f; - max_rate_d.freq = 0.0f; - max_rate_d.gain = 0.0f; - max_rate_d.phase = 0.0f; - max_rate_d.max_allowed = 0.0f; + max_rate_p = {}; + max_rate_d = {}; found_max_p = false; found_max_d = false; find_middle = false; @@ -2091,15 +1824,10 @@ void AC_AutoTune_Heli::reset_maxgains_update_gain_variables() // reset the max_gains update gain variables void AC_AutoTune_Heli::reset_sweep_variables() { - sweep.ph180_freq = 0.0f; - sweep.ph180_gain = 0.0f; - sweep.ph180_phase = 0.0f; - sweep.ph270_freq = 0.0f; - sweep.ph270_gain = 0.0f; - sweep.ph270_phase = 0.0f; - sweep.maxgain_gain = 0.0f; - sweep.maxgain_freq = 0.0f; - sweep.maxgain_phase = 0.0f; + sweep.ph180 = {}; + sweep.ph270 = {}; + sweep.maxgain = {}; + sweep.progress = 0; } diff --git a/libraries/AC_AutoTune/AC_AutoTune_Heli.h b/libraries/AC_AutoTune/AC_AutoTune_Heli.h index 5e574638fa9..07c791afe5f 100644 --- a/libraries/AC_AutoTune/AC_AutoTune_Heli.h +++ b/libraries/AC_AutoTune/AC_AutoTune_Heli.h @@ -19,6 +19,7 @@ #pragma once #include "AC_AutoTune.h" +#include class AC_AutoTune_Heli : public AC_AutoTune { @@ -41,6 +42,9 @@ class AC_AutoTune_Heli : public AC_AutoTune // backup original gains and prepare for start of tuning void backup_gains_and_initialise() override; + // load gains + void load_gain_set(AxisType s_axis, float rate_p, float rate_i, float rate_d, float rate_ff, float angle_p, float max_accel, float rate_fltt, float rate_flte, float smax); + // switch to use original gains void load_orig_gains() override; @@ -136,20 +140,21 @@ class AC_AutoTune_Heli : public AC_AutoTune // max gain data for rate d tuning max_gain_data max_rate_d; + // dwell type identifies whether the dwell is ran on rate or angle + enum DwellType { + RATE = 0, + ANGLE = 1, + }; + // Feedforward test used to determine Rate FF gain void rate_ff_test_init(); void rate_ff_test_run(float max_angle_cds, float target_rate_cds, float dir_sign); - // dwell test used to perform frequency dwells for rate gains - void dwell_test_init(float start_frq, float filt_freq); - void dwell_test_run(uint8_t freq_resp_input, float start_frq, float stop_frq, float &dwell_gain, float &dwell_phase); - - // dwell test used to perform frequency dwells for angle gains - void angle_dwell_test_init(float start_frq, float filt_freq); - void angle_dwell_test_run(float start_frq, float stop_frq, float &dwell_gain, float &dwell_phase); + // initialize dwell test or angle dwell test variables + void dwell_test_init(float start_frq, float stop_frq, float filt_freq, DwellType dwell_type); - // generates waveform for frequency sweep excitations - float waveform(float time, float time_record, float waveform_magnitude, float wMin, float wMax); + // dwell test used to perform frequency dwells for rate gains + void dwell_test_run(uint8_t freq_resp_input, float start_frq, float stop_frq, float &dwell_gain, float &dwell_phase, DwellType dwell_type); // updating_rate_ff_up - adjust FF to ensure the target is reached // FF is adjusted until rate requested is acheived @@ -201,15 +206,9 @@ class AC_AutoTune_Heli : public AC_AutoTune // flag for finding the peak of the gain response bool find_peak; - // updating angle P up yaw - // counter value of previous good frequency - uint8_t sp_prev_good_frq_cnt; - // updating rate P up // counter value of previous good frequency uint8_t rp_prev_good_frq_cnt; - // previous gain - float rp_prev_gain; // updating rate D up // counter value of previous good frequency @@ -228,9 +227,15 @@ class AC_AutoTune_Heli : public AC_AutoTune float test_phase[20]; // frequency response phase for each dwell test iteration float dwell_start_time_ms; // start time in ms of dwell test uint8_t freq_cnt_max; // counter number for frequency that produced max gain response - float curr_test_freq; // current test frequency - float curr_test_gain; // current test frequency response gain - float curr_test_phase; // current test frequency response phase + + // sweep_info contains information about a specific test's sweep results + struct sweep_info { + float freq; + float gain; + float phase; + }; + sweep_info curr_test; + Vector3f start_angles; // aircraft attitude at the start of test uint32_t settle_time; // time in ms for allowing aircraft to stabilize before initiating test uint32_t phase_out_time; // time in ms to phase out response @@ -263,19 +268,18 @@ class AC_AutoTune_Heli : public AC_AutoTune // sweep_data tracks the overall characteristics in the response to the frequency sweep struct sweep_data { - float maxgain_freq; - float maxgain_gain; - float maxgain_phase; - float ph180_freq; - float ph180_gain; - float ph180_phase; - float ph270_freq; - float ph270_gain; - float ph270_phase; + sweep_info maxgain; + sweep_info ph180; + sweep_info ph270; + uint8_t progress; // set based on phase of frequency response. 0 - start; 1 - reached 180 deg; 2 - reached 270 deg; }; sweep_data sweep; + // fix the frequency sweep time to 23 seconds + const float sweep_time_ms = 23000; + + // parameters AP_Int8 axis_bitmask; // axes to be tuned AP_Int8 seq_bitmask; // tuning sequence bitmask @@ -284,8 +288,8 @@ class AC_AutoTune_Heli : public AC_AutoTune AP_Float max_resp_gain; // maximum response gain AP_Float vel_hold_gain; // gain for velocity hold - // freqresp object for the rate frequency response tests - AC_AutoTune_FreqResp freqresp_rate; - // freqresp object for the angle frequency response tests - AC_AutoTune_FreqResp freqresp_angle; + // freqresp object for the frequency response tests + AC_AutoTune_FreqResp freqresp; + + Chirp chirp_input; }; diff --git a/libraries/AC_AutoTune/AC_AutoTune_Multi.cpp b/libraries/AC_AutoTune/AC_AutoTune_Multi.cpp index dce6ca01d51..f75101c333b 100644 --- a/libraries/AC_AutoTune/AC_AutoTune_Multi.cpp +++ b/libraries/AC_AutoTune/AC_AutoTune_Multi.cpp @@ -1,5 +1,7 @@ #include "AC_AutoTune_Multi.h" +#include + /* * autotune support for multicopters * @@ -49,7 +51,7 @@ #define AUTOTUNE_RLPF_MAX 5.0f // maximum Rate Yaw filter value #define AUTOTUNE_RP_MIN 0.01f // minimum Rate P value #define AUTOTUNE_RP_MAX 2.0f // maximum Rate P value -#define AUTOTUNE_SP_MAX 20.0f // maximum Stab P value +#define AUTOTUNE_SP_MAX 40.0f // maximum Stab P value #define AUTOTUNE_SP_MIN 0.5f // maximum Stab P value #define AUTOTUNE_RP_ACCEL_MIN 4000.0f // Minimum acceleration for Roll and Pitch #define AUTOTUNE_Y_ACCEL_MIN 1000.0f // Minimum acceleration for Yaw @@ -131,7 +133,7 @@ void AC_AutoTune_Multi::backup_gains_and_initialise() { AC_AutoTune::backup_gains_and_initialise(); - aggressiveness = constrain_float(aggressiveness, 0.05f, 0.2f); + aggressiveness.set(constrain_float(aggressiveness, 0.05f, 0.2f)); orig_bf_feedforward = attitude_control->get_bf_feedforward(); diff --git a/libraries/AC_Autorotation/AC_Autorotation.cpp b/libraries/AC_Autorotation/AC_Autorotation.cpp index 3e74e80ac1d..d6c7c8ea3c9 100644 --- a/libraries/AC_Autorotation/AC_Autorotation.cpp +++ b/libraries/AC_Autorotation/AC_Autorotation.cpp @@ -143,7 +143,7 @@ void AC_Autorotation::init_hs_controller() _healthy_rpm_counter = 0; // Protect against divide by zero - _param_head_speed_set_point = MAX(_param_head_speed_set_point,500); + _param_head_speed_set_point.set(MAX(_param_head_speed_set_point,500)); } @@ -213,7 +213,7 @@ float AC_Autorotation::get_rpm(bool update_counter) if (rpm != nullptr) { //Check requested rpm instance to ensure either 0 or 1. Always defaults to 0. if ((_param_rpm_instance > 1) || (_param_rpm_instance < 0)) { - _param_rpm_instance = 0; + _param_rpm_instance.set(0); } //Get RPM value @@ -366,7 +366,7 @@ void AC_Autorotation::update_forward_speed_controller(void) _accel_out_last = _accel_out; // update angle targets that will be passed to stabilize controller - _pitch_target = atanf(-_accel_out/(GRAVITY_MSS * 100.0f))*(18000.0f/M_PI); + _pitch_target = accel_to_angle(-_accel_out*0.01) * 100; } diff --git a/libraries/AC_Autorotation/AC_Autorotation.h b/libraries/AC_Autorotation/AC_Autorotation.h index 0ae16bc1cac..d89fe88dc42 100644 --- a/libraries/AC_Autorotation/AC_Autorotation.h +++ b/libraries/AC_Autorotation/AC_Autorotation.h @@ -8,9 +8,6 @@ #include #include #include -#include -#include -#include class AC_Autorotation diff --git a/libraries/AC_Avoidance/AC_Avoid.cpp b/libraries/AC_Avoidance/AC_Avoid.cpp index 59c05576a50..43a0a175666 100644 --- a/libraries/AC_Avoidance/AC_Avoid.cpp +++ b/libraries/AC_Avoidance/AC_Avoid.cpp @@ -67,12 +67,12 @@ const AP_Param::GroupInfo AC_Avoid::var_info[] = { // @User: Standard AP_GROUPINFO("MARGIN", 4, AC_Avoid, _margin, 2.0f), - // @Param{Copter}: BEHAVE + // @Param{Copter, Rover}: BEHAVE // @DisplayName: Avoidance behaviour // @Description: Avoidance behaviour (slide or stop) // @Values: 0:Slide,1:Stop // @User: Standard - AP_GROUPINFO_FRAME("BEHAVE", 5, AC_Avoid, _behavior, AP_AVOID_BEHAVE_DEFAULT, AP_PARAM_FRAME_COPTER | AP_PARAM_FRAME_HELI | AP_PARAM_FRAME_TRICOPTER), + AP_GROUPINFO_FRAME("BEHAVE", 5, AC_Avoid, _behavior, AP_AVOID_BEHAVE_DEFAULT, AP_PARAM_FRAME_COPTER | AP_PARAM_FRAME_HELI | AP_PARAM_FRAME_TRICOPTER | AP_PARAM_FRAME_ROVER), // @Param: BACKUP_SPD // @DisplayName: Avoidance maximum backup speed @@ -132,6 +132,7 @@ void AC_Avoid::adjust_velocity_fence(float kP, float accel_cmss, Vector3f &desir // maximum component of desired backup velocity in each quadrant Vector2f quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel; +#if AP_FENCE_ENABLED if ((_enabled & AC_AVOID_STOP_AT_FENCE) > 0) { // Store velocity needed to back away from fence Vector2f backup_vel_fence; @@ -152,6 +153,7 @@ void AC_Avoid::adjust_velocity_fence(float kP, float accel_cmss, Vector3f &desir adjust_velocity_exclusion_circles(kP, accel_cmss_limited, desired_velocity_xy_cms, backup_vel_fence, dt); find_max_quadrant_velocity(backup_vel_fence, quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel); } +#endif // AP_FENCE_ENABLED if ((_enabled & AC_AVOID_STOP_AT_BEACON_FENCE) > 0) { // Store velocity needed to back away from beacon fence @@ -363,6 +365,7 @@ void AC_Avoid::adjust_velocity_z(float kP, float accel_cmss, float& climb_rate_c const AP_AHRS &_ahrs = AP::ahrs(); +#if AP_FENCE_ENABLED // calculate distance below fence AC_Fence *fence = AP::fence(); if ((_enabled & AC_AVOID_STOP_AT_FENCE) > 0 && fence && (fence->get_enabled_fences() & AC_FENCE_TYPE_ALT_MAX) > 0) { @@ -373,6 +376,7 @@ void AC_Avoid::adjust_velocity_z(float kP, float accel_cmss, float& climb_rate_c alt_diff = fence->get_safe_alt_max() + veh_alt; limit_alt = true; } +#endif // calculate distance to (e.g.) optical flow altitude limit // AHRS values are always in metres @@ -657,6 +661,8 @@ float AC_Avoid::get_max_speed(float kP, float accel_cmss, float distance_cm, flo } } +#if AP_FENCE_ENABLED + /* * Adjusts the desired velocity for the circular fence. */ @@ -1080,6 +1086,7 @@ void AC_Avoid::adjust_velocity_exclusion_circles(float kP, float accel_cmss, Vec // desired backup velocity is sum of maximum velocity component in each quadrant backup_vel = quad_1_back_vel + quad_2_back_vel + quad_3_back_vel + quad_4_back_vel; } +#endif // AP_FENCE_ENABLED /* * Adjusts the desired velocity for the beacon fence. @@ -1102,9 +1109,11 @@ void AC_Avoid::adjust_velocity_beacon_fence(float kP, float accel_cmss, Vector2f // adjust velocity using beacon float margin = 0; +#if AP_FENCE_ENABLED if (AP::fence()) { margin = AP::fence()->get_margin(); } +#endif adjust_velocity_polygon(kP, accel_cmss, desired_vel_cms, backup_vel, boundary, num_points, margin, dt, true); } diff --git a/libraries/AC_Avoidance/AP_OABendyRuler.cpp b/libraries/AC_Avoidance/AP_OABendyRuler.cpp index ba38ddd6e24..f6387a6b3a9 100644 --- a/libraries/AC_Avoidance/AP_OABendyRuler.cpp +++ b/libraries/AC_Avoidance/AP_OABendyRuler.cpp @@ -93,7 +93,7 @@ bool AP_OABendyRuler::update(const Location& current_loc, const Location& destin const float distance_to_dest = current_loc.get_distance(destination); // make sure user has set a meaningful value for _lookahead - _lookahead = MAX(_lookahead,1.0f); + _lookahead.set(MAX(_lookahead,1.0f)); // lookahead distance is adjusted dynamically based on avoidance results _current_lookahead = constrain_float(_current_lookahead, _lookahead * 0.5f, _lookahead); @@ -456,6 +456,7 @@ float AP_OABendyRuler::calc_avoidance_margin(const Location &start, const Locati // on success returns true and updates margin bool AP_OABendyRuler::calc_margin_from_circular_fence(const Location &start, const Location &end, float &margin) const { +#if AP_FENCE_ENABLED // exit immediately if polygon fence is not enabled const AC_Fence *fence = AC_Fence::get_singleton(); if (fence == nullptr) { @@ -476,12 +477,16 @@ bool AP_OABendyRuler::calc_margin_from_circular_fence(const Location &start, con // margin is fence radius minus the longer of start or end distance margin = fence_radius_plus_margin - sqrtf(MAX(start_dist_sq, end_dist_sq)); return true; +#else + return false; +#endif // AP_FENCE_ENABLED } // calculate minimum distance between a path and the altitude fence // on success returns true and updates margin bool AP_OABendyRuler::calc_margin_from_alt_fence(const Location &start, const Location &end, float &margin) const -{ +{ +#if AP_FENCE_ENABLED // exit immediately if polygon fence is not enabled const AC_Fence *fence = AC_Fence::get_singleton(); if (fence == nullptr) { @@ -508,12 +513,16 @@ bool AP_OABendyRuler::calc_margin_from_alt_fence(const Location &start, const Lo margin = MIN(margin_start,margin_end); return true; +#else + return false; +#endif // AP_FENCE_ENABLED } // calculate minimum distance between a path and all inclusion and exclusion polygons // on success returns true and updates margin bool AP_OABendyRuler::calc_margin_from_inclusion_and_exclusion_polygons(const Location &start, const Location &end, float &margin) const { +#if AP_FENCE_ENABLED const AC_Fence *fence = AC_Fence::get_singleton(); if (fence == nullptr) { return false; @@ -574,12 +583,16 @@ bool AP_OABendyRuler::calc_margin_from_inclusion_and_exclusion_polygons(const Lo } return margin_updated; +#else + return false; +#endif // AP_FENCE_ENABLED } // calculate minimum distance between a path and all inclusion and exclusion circles // on success returns true and updates margin bool AP_OABendyRuler::calc_margin_from_inclusion_and_exclusion_circles(const Location &start, const Location &end, float &margin) const { +#if AP_FENCE_ENABLED // exit immediately if fence is not enabled const AC_Fence *fence = AC_Fence::get_singleton(); if (fence == nullptr) { @@ -650,6 +663,9 @@ bool AP_OABendyRuler::calc_margin_from_inclusion_and_exclusion_circles(const Loc } return margin_updated; +#else + return false; +#endif // AP_FENCE_ENABLED } // calculate minimum distance between a path and proximity sensor obstacles diff --git a/libraries/AC_Avoidance/AP_OABendyRuler.h b/libraries/AC_Avoidance/AP_OABendyRuler.h index ed5127c5d41..b90b7d6cbb8 100644 --- a/libraries/AC_Avoidance/AP_OABendyRuler.h +++ b/libraries/AC_Avoidance/AP_OABendyRuler.h @@ -3,7 +3,6 @@ #include #include #include -#include /* * BendyRuler avoidance algorithm for avoiding the polygon and circular fence and dynamic objects detected by the proximity sensor @@ -12,9 +11,7 @@ class AP_OABendyRuler { public: AP_OABendyRuler(); - /* Do not allow copies */ - AP_OABendyRuler(const AP_OABendyRuler &other) = delete; - AP_OABendyRuler &operator=(const AP_OABendyRuler&) = delete; + CLASS_NO_COPY(AP_OABendyRuler); /* Do not allow copies */ // send configuration info stored in front end parameters void set_config(float margin_max) { _margin_max = MAX(margin_max, 0.0f); } diff --git a/libraries/AC_Avoidance/AP_OADatabase.cpp b/libraries/AC_Avoidance/AP_OADatabase.cpp index e569336ec58..1cf518a42a4 100644 --- a/libraries/AC_Avoidance/AP_OADatabase.cpp +++ b/libraries/AC_Avoidance/AP_OADatabase.cpp @@ -186,6 +186,11 @@ void AP_OADatabase::init_queue() } _queue.items = new ObjectBuffer(_queue.size); + if (_queue.items != nullptr && _queue.items->get_size() == 0) { + // allocation failed + delete _queue.items; + _queue.items = nullptr; + } } void AP_OADatabase::init_database() diff --git a/libraries/AC_Avoidance/AP_OADatabase.h b/libraries/AC_Avoidance/AP_OADatabase.h index edf9df7b32c..ec5d6b0bd73 100644 --- a/libraries/AC_Avoidance/AP_OADatabase.h +++ b/libraries/AC_Avoidance/AP_OADatabase.h @@ -1,6 +1,6 @@ #pragma once -#include +#include #include #include #include @@ -10,9 +10,7 @@ class AP_OADatabase { AP_OADatabase(); - /* Do not allow copies */ - AP_OADatabase(const AP_OADatabase &other) = delete; - AP_OADatabase &operator=(const AP_OADatabase&) = delete; + CLASS_NO_COPY(AP_OADatabase); /* Do not allow copies */ // get singleton instance static AP_OADatabase *get_singleton() { diff --git a/libraries/AC_Avoidance/AP_OADijkstra.cpp b/libraries/AC_Avoidance/AP_OADijkstra.cpp index 11cc432536c..a8fd70867cc 100644 --- a/libraries/AC_Avoidance/AP_OADijkstra.cpp +++ b/libraries/AC_Avoidance/AP_OADijkstra.cpp @@ -17,6 +17,9 @@ #include "AP_OAPathPlanner.h" #include + +#if AP_FENCE_ENABLED + #include #include @@ -959,3 +962,5 @@ bool AP_OADijkstra::convert_node_to_point(const AP_OAVisGraph::OAItemID& id, Vec // we should never reach here but just in case return false; } +#endif // AP_FENCE_ENABLED + diff --git a/libraries/AC_Avoidance/AP_OADijkstra.h b/libraries/AC_Avoidance/AP_OADijkstra.h index 9a5ac410991..f95405ad711 100644 --- a/libraries/AC_Avoidance/AP_OADijkstra.h +++ b/libraries/AC_Avoidance/AP_OADijkstra.h @@ -3,7 +3,6 @@ #include #include #include -#include #include "AP_OAVisGraph.h" /* @@ -15,9 +14,7 @@ class AP_OADijkstra { AP_OADijkstra(AP_Int16 &options); - /* Do not allow copies */ - AP_OADijkstra(const AP_OADijkstra &other) = delete; - AP_OADijkstra &operator=(const AP_OADijkstra&) = delete; + CLASS_NO_COPY(AP_OADijkstra); /* Do not allow copies */ // set fence margin (in meters) used when creating "safe positions" within the polygon fence void set_fence_margin(float margin) { _polyfence_margin = MAX(margin, 0.0f); } diff --git a/libraries/AC_Avoidance/AP_OAPathPlanner.cpp b/libraries/AC_Avoidance/AP_OAPathPlanner.cpp index 84a9d47d4de..a142a1773c0 100644 --- a/libraries/AC_Avoidance/AP_OAPathPlanner.cpp +++ b/libraries/AC_Avoidance/AP_OAPathPlanner.cpp @@ -93,14 +93,18 @@ void AP_OAPathPlanner::init() } break; case OA_PATHPLAN_DIJKSTRA: +#if AP_FENCE_ENABLED if (_oadijkstra == nullptr) { _oadijkstra = new AP_OADijkstra(_options); } +#endif break; case OA_PATHPLAN_DJIKSTRA_BENDYRULER: +#if AP_FENCE_ENABLED if (_oadijkstra == nullptr) { _oadijkstra = new AP_OADijkstra(_options); } +#endif if (_oabendyruler == nullptr) { _oabendyruler = new AP_OABendyRuler(); AP_Param::load_object_from_eeprom(_oabendyruler, AP_OABendyRuler::var_info); @@ -298,6 +302,7 @@ void AP_OAPathPlanner::avoidance_thread() } case OA_PATHPLAN_DIJKSTRA: { +#if AP_FENCE_ENABLED if (_oadijkstra == nullptr) { continue; } @@ -315,6 +320,7 @@ void AP_OAPathPlanner::avoidance_thread() break; } path_planner_used = OAPathPlannerUsed::Dijkstras; +#endif break; } @@ -332,12 +338,15 @@ void AP_OAPathPlanner::avoidance_thread() break; } else { // cleared all obstacles, trigger Dijkstra's to calculate path based on current deviated position +#if AP_FENCE_ENABLED if (proximity_only == false) { _oadijkstra->recalculate_path(); } +#endif // only use proximity avoidance now for BendyRuler proximity_only = true; } +#if AP_FENCE_ENABLED _oadijkstra->set_fence_margin(_margin_max); const AP_OADijkstra::AP_OADijkstra_State dijkstra_state = _oadijkstra->update(avoidance_request2.current_loc, avoidance_request2.destination, origin_new, destination_new); switch (dijkstra_state) { @@ -352,6 +361,7 @@ void AP_OAPathPlanner::avoidance_thread() break; } path_planner_used = OAPathPlannerUsed::Dijkstras; +#endif break; } diff --git a/libraries/AC_Avoidance/AP_OAPathPlanner.h b/libraries/AC_Avoidance/AP_OAPathPlanner.h index 4b12a58f780..1641377773e 100644 --- a/libraries/AC_Avoidance/AP_OAPathPlanner.h +++ b/libraries/AC_Avoidance/AP_OAPathPlanner.h @@ -3,7 +3,8 @@ #include #include #include -#include +#include + #include "AP_OABendyRuler.h" #include "AP_OADijkstra.h" #include "AP_OADatabase.h" diff --git a/libraries/AC_Avoidance/AP_OAVisGraph.h b/libraries/AC_Avoidance/AP_OAVisGraph.h index bb2227a00f9..800fbff4070 100644 --- a/libraries/AC_Avoidance/AP_OAVisGraph.h +++ b/libraries/AC_Avoidance/AP_OAVisGraph.h @@ -2,7 +2,6 @@ #include #include -#include /* * Visibility graph used by Dijkstra's algorithm for path planning around fence, stay-out zones and moving obstacles @@ -11,9 +10,7 @@ class AP_OAVisGraph { public: AP_OAVisGraph(); - /* Do not allow copies */ - AP_OAVisGraph(const AP_OAVisGraph &other) = delete; - AP_OAVisGraph &operator=(const AP_OAVisGraph&) = delete; + CLASS_NO_COPY(AP_OAVisGraph); /* Do not allow copies */ // types of items held in graph enum OAType : uint8_t { diff --git a/libraries/AC_CustomControl/AC_CustomControl.cpp b/libraries/AC_CustomControl/AC_CustomControl.cpp new file mode 100644 index 00000000000..147dedd198b --- /dev/null +++ b/libraries/AC_CustomControl/AC_CustomControl.cpp @@ -0,0 +1,186 @@ +#include + +#include "AC_CustomControl.h" + +#if AP_CUSTOMCONTROL_ENABLED + + +#include "AC_CustomControl_Backend.h" +// #include "AC_CustomControl_Empty.h" +#include "AC_CustomControl_PID.h" + +// table of user settable parameters +const AP_Param::GroupInfo AC_CustomControl::var_info[] = { + // @Param: _TYPE + // @DisplayName: Custom control type + // @Description: Custom control type to be used + // @Values: 0:None, 1:Empty, 2:PID + // @RebootRequired: True + // @User: Advanced + AP_GROUPINFO_FLAGS("_TYPE", 1, AC_CustomControl, _controller_type, 0, AP_PARAM_FLAG_ENABLE), + + // @Param: _AXIS_MASK + // @DisplayName: Custom Controller bitmask + // @Description: Custom Controller bitmask to chose which axis to run + // @Bitmask: 0:Roll, 1:Pitch, 2:Yaw + // @User: Advanced + AP_GROUPINFO("_AXIS_MASK", 2, AC_CustomControl, _custom_controller_mask, 0), + + // parameters for empty controller. only used as a template, no need for param table + // AP_SUBGROUPVARPTR(_backend, "1_", 6, AC_CustomControl, _backend_var_info[0]), + + // parameters for PID controller + AP_SUBGROUPVARPTR(_backend, "2_", 7, AC_CustomControl, _backend_var_info[1]), + + AP_GROUPEND +}; + +const struct AP_Param::GroupInfo *AC_CustomControl::_backend_var_info[CUSTOMCONTROL_MAX_TYPES]; + +AC_CustomControl::AC_CustomControl(AP_AHRS_View*& ahrs, AC_AttitudeControl_Multi*& att_control, AP_MotorsMulticopter*& motors, float dt) : + _dt(dt), + _ahrs(ahrs), + _att_control(att_control), + _motors(motors) +{ + AP_Param::setup_object_defaults(this, var_info); +} + +void AC_CustomControl::init(void) +{ + switch (CustomControlType(_controller_type)) + { + case CustomControlType::CONT_NONE: + break; + case CustomControlType::CONT_EMPTY: // This is template backend. Don't initialize it. + // This is template backend. Don't initialize it. + // _backend = new AC_CustomControl_Empty(*this, _ahrs, _att_control, _motors, _dt); + // _backend_var_info[get_type()] = AC_CustomControl_Empty::var_info; + break; + case CustomControlType::CONT_PID: + _backend = new AC_CustomControl_PID(*this, _ahrs, _att_control, _motors, _dt); + _backend_var_info[get_type()] = AC_CustomControl_PID::var_info; + break; + default: + return; + } + + if (_backend && _backend_var_info[get_type()]) { + AP_Param::load_object_from_eeprom(_backend, _backend_var_info[get_type()]); + } +} + +// run custom controller if it is activated by RC switch and appropriate type is selected +void AC_CustomControl::update(void) +{ + if (is_safe_to_run()) { + Vector3f motor_out_rpy; + + motor_out_rpy = _backend->update(); + + motor_set(motor_out_rpy); + } +} + +// choose which axis to apply custom controller output +void AC_CustomControl::motor_set(Vector3f rpy) { + if (_custom_controller_mask & (uint8_t)CustomControlOption::ROLL) { + _motors->set_roll(rpy.x); + _att_control->get_rate_roll_pid().set_integrator(0.0); + } + if (_custom_controller_mask & (uint8_t)CustomControlOption::PITCH) { + _motors->set_pitch(rpy.y); + _att_control->get_rate_pitch_pid().set_integrator(0.0); + } + if (_custom_controller_mask & (uint8_t)CustomControlOption::YAW) { + _motors->set_yaw(rpy.z); + _att_control->get_rate_yaw_pid().set_integrator(0.0); + } +} + +// move main controller's target to current states, reset filters, +// and move integrator to motor output +// to allow smooth transition to the primary controller +void AC_CustomControl::reset_main_att_controller(void) +{ + // reset attitude and rate target, if feedforward is enabled + if (_att_control->get_bf_feedforward()) { + _att_control->relax_attitude_controllers(); + } + + _att_control->get_rate_roll_pid().set_integrator(0.0); + _att_control->get_rate_pitch_pid().set_integrator(0.0); + _att_control->get_rate_yaw_pid().set_integrator(0.0); +} + +void AC_CustomControl::set_custom_controller(bool enabled) +{ + // double logging switch makes the state change very clear in the log + log_switch(); + + _custom_controller_active = false; + + // don't allow accidental main controller reset without active custom controller + if (_controller_type == CustomControlType::CONT_NONE) { + gcs().send_text(MAV_SEVERITY_INFO, "Custom controller is not enabled"); + return; + } + + // controller type is out of range + if (_controller_type > CUSTOMCONTROL_MAX_TYPES) { + gcs().send_text(MAV_SEVERITY_INFO, "Custom controller type is out of range"); + return; + } + + // backend is not created + if (_backend == nullptr) { + gcs().send_text(MAV_SEVERITY_INFO, "Reboot to enable selected custom controller"); + return; + } + + if (_custom_controller_mask == 0 && enabled) { + gcs().send_text(MAV_SEVERITY_INFO, "Axis mask is not set"); + return; + } + + // reset main controller + if (!enabled) { + gcs().send_text(MAV_SEVERITY_INFO, "Custom controller is OFF"); + // don't reset if the empty backend is selected + if (_controller_type > CustomControlType::CONT_EMPTY) { + reset_main_att_controller(); + } + } + + if (enabled && _controller_type > CustomControlType::CONT_NONE) { + // reset custom controller filter, integrator etc. + _backend->reset(); + gcs().send_text(MAV_SEVERITY_INFO, "Custom controller is ON"); + } + + _custom_controller_active = enabled; + + // log successful switch + log_switch(); +} + +// check that RC switch is on, backend is not changed mid flight and controller type is selected +bool AC_CustomControl::is_safe_to_run(void) { + if (_custom_controller_active && (_controller_type > CustomControlType::CONT_NONE) + && (_controller_type <= CUSTOMCONTROL_MAX_TYPES) && _backend != nullptr) + { + return true; + } + + return false; +} + +// log when the custom controller is switch into +void AC_CustomControl::log_switch(void) { + AP::logger().Write("CC", "TimeUS,Type,Act","QBB", + AP_HAL::micros64(), + _controller_type, + _custom_controller_active); +} + +#endif diff --git a/libraries/AC_CustomControl/AC_CustomControl.h b/libraries/AC_CustomControl/AC_CustomControl.h new file mode 100644 index 00000000000..c11a51fb008 --- /dev/null +++ b/libraries/AC_CustomControl/AC_CustomControl.h @@ -0,0 +1,72 @@ +#pragma once + +/// @file AC_CustomControl.h +/// @brief ArduCopter custom control library + +#include +#include +#include +#include +#include +#include + +#if AP_CUSTOMCONTROL_ENABLED + +#ifndef CUSTOMCONTROL_MAX_TYPES +#define CUSTOMCONTROL_MAX_TYPES 2 +#endif + +class AC_CustomControl_Backend; + +class AC_CustomControl { +public: + AC_CustomControl(AP_AHRS_View*& ahrs, AC_AttitudeControl_Multi*& _att_control, AP_MotorsMulticopter*& motors, float dt); + + CLASS_NO_COPY(AC_CustomControl); /* Do not allow copies */ + + void init(void); + void update(void); + void motor_set(Vector3f motor_out); + void set_custom_controller(bool enabled); + void reset_main_att_controller(void); + bool is_safe_to_run(void); + void log_switch(void); + + // zero index controller type param, only use it to acces _backend or _backend_var_info array + uint8_t get_type() { return _controller_type > 0 ? (_controller_type - 1) : 0; }; + + // User settable parameters + static const struct AP_Param::GroupInfo var_info[]; + static const struct AP_Param::GroupInfo *_backend_var_info[CUSTOMCONTROL_MAX_TYPES]; + +protected: + // add custom controller here + enum class CustomControlType : uint8_t { + CONT_NONE = 0, + CONT_EMPTY = 1, + CONT_PID = 2, + }; // controller that should be used + + enum class CustomControlOption { + ROLL = 1 << 0, + PITCH = 1 << 1, + YAW = 1 << 2, + }; + + // Intersampling period in seconds + float _dt; + bool _custom_controller_active; + + // References to external libraries + AP_AHRS_View*& _ahrs; + AC_AttitudeControl_Multi*& _att_control; + AP_MotorsMulticopter*& _motors; + + AP_Enum _controller_type; + AP_Int8 _custom_controller_mask; + +private: + AC_CustomControl_Backend *_backend; +}; + +#endif diff --git a/libraries/AC_CustomControl/AC_CustomControl_Backend.h b/libraries/AC_CustomControl/AC_CustomControl_Backend.h new file mode 100644 index 00000000000..d9c537d3454 --- /dev/null +++ b/libraries/AC_CustomControl/AC_CustomControl_Backend.h @@ -0,0 +1,34 @@ +#pragma once + +#include "AC_CustomControl.h" + +#if AP_CUSTOMCONTROL_ENABLED + +class AC_CustomControl_Backend +{ +public: + AC_CustomControl_Backend(AC_CustomControl& frontend, AP_AHRS_View*& ahrs, AC_AttitudeControl_Multi*& att_control, AP_MotorsMulticopter*& motors, float dt) : + _frontend(frontend), + _ahrs(ahrs), + _att_control(att_control), + _motors(motors) + {} + + // empty destructor to suppress compiler warning + virtual ~AC_CustomControl_Backend() {} + + // update controller, return roll, pitch, yaw controller output + virtual Vector3f update() = 0; + + // reset controller to avoid build up or abrupt response upon switch, ex: integrator, filter + virtual void reset() = 0; + +protected: + // References to external libraries + AP_AHRS_View*& _ahrs; + AC_AttitudeControl_Multi*& _att_control; + AP_MotorsMulticopter*& _motors; + AC_CustomControl& _frontend; +}; + +#endif diff --git a/libraries/AC_CustomControl/AC_CustomControl_Empty.cpp b/libraries/AC_CustomControl/AC_CustomControl_Empty.cpp new file mode 100644 index 00000000000..d11caabc7ec --- /dev/null +++ b/libraries/AC_CustomControl/AC_CustomControl_Empty.cpp @@ -0,0 +1,72 @@ +#include "AC_CustomControl_Empty.h" + +#if CUSTOMCONTROL_EMPTY_ENABLED + +#include + +// table of user settable parameters +const AP_Param::GroupInfo AC_CustomControl_Empty::var_info[] = { + // @Param: PARAM1 + // @DisplayName: Empty param1 + // @Description: Dumy parameter for empty custom controller backend + // @User: Advanced + AP_GROUPINFO("PARAM1", 1, AC_CustomControl_Empty, param1, 0.0f), + + // @Param: PARAM2 + // @DisplayName: Empty param2 + // @Description: Dumy parameter for empty custom controller backend + // @User: Advanced + AP_GROUPINFO("PARAM2", 2, AC_CustomControl_Empty, param2, 0.0f), + + // @Param: PARAM3 + // @DisplayName: Empty param3 + // @Description: Dumy parameter for empty custom controller backend + // @User: Advanced + AP_GROUPINFO("PARAM3", 3, AC_CustomControl_Empty, param3, 0.0f), + + AP_GROUPEND +}; + +// initialize in the constructor +AC_CustomControl_Empty::AC_CustomControl_Empty(AC_CustomControl& frontend, AP_AHRS_View*& ahrs, AC_AttitudeControl_Multi*& att_control, AP_MotorsMulticopter*& motors, float dt) : + AC_CustomControl_Backend(frontend, ahrs, att_control, motors, dt) +{ + AP_Param::setup_object_defaults(this, var_info); +} + +// update controller +// return roll, pitch, yaw controller output +Vector3f AC_CustomControl_Empty::update(void) +{ + // reset controller based on spool state + switch (_motors->get_spool_state()) { + case AP_Motors::SpoolState::SHUT_DOWN: + case AP_Motors::SpoolState::GROUND_IDLE: + // We are still at the ground. Reset custom controller to avoid + // build up, ex: integrator + reset(); + break; + + case AP_Motors::SpoolState::THROTTLE_UNLIMITED: + case AP_Motors::SpoolState::SPOOLING_UP: + case AP_Motors::SpoolState::SPOOLING_DOWN: + // we are off the ground + break; + } + + // arducopter main attitude controller already runned + // we don't need to do anything else + + gcs().send_text(MAV_SEVERITY_INFO, "empty custom controller working"); + + // return what arducopter main controller outputted + return Vector3f(_motors->get_roll(), _motors->get_pitch(), _motors->get_yaw()); +} + +// reset controller to avoid build up on the ground +// or to provide bumpless transfer from arducopter main controller +void AC_CustomControl_Empty::reset(void) +{ +} + +#endif diff --git a/libraries/AC_CustomControl/AC_CustomControl_Empty.h b/libraries/AC_CustomControl/AC_CustomControl_Empty.h new file mode 100644 index 00000000000..692815f1cc5 --- /dev/null +++ b/libraries/AC_CustomControl/AC_CustomControl_Empty.h @@ -0,0 +1,29 @@ +#pragma once + +#include "AC_CustomControl_Backend.h" + +#ifndef CUSTOMCONTROL_EMPTY_ENABLED + #define CUSTOMCONTROL_EMPTY_ENABLED AP_CUSTOMCONTROL_ENABLED +#endif + +#if CUSTOMCONTROL_EMPTY_ENABLED + +class AC_CustomControl_Empty : public AC_CustomControl_Backend { +public: + AC_CustomControl_Empty(AC_CustomControl& frontend, AP_AHRS_View*& ahrs, AC_AttitudeControl_Multi*& att_control, AP_MotorsMulticopter*& motors, float dt); + + + Vector3f update(void) override; + void reset(void) override; + + // user settable parameters + static const struct AP_Param::GroupInfo var_info[]; + +protected: + // declare parameters here + AP_Float param1; + AP_Float param2; + AP_Float param3; +}; + +#endif diff --git a/libraries/AC_CustomControl/AC_CustomControl_PID.cpp b/libraries/AC_CustomControl/AC_CustomControl_PID.cpp new file mode 100644 index 00000000000..94b61bfc276 --- /dev/null +++ b/libraries/AC_CustomControl/AC_CustomControl_PID.cpp @@ -0,0 +1,313 @@ +#include "AC_CustomControl_PID.h" + +#if CUSTOMCONTROL_PID_ENABLED + +// table of user settable parameters +const AP_Param::GroupInfo AC_CustomControl_PID::var_info[] = { + // @Param: ANG_RLL_P + // @DisplayName: Roll axis angle controller P gain + // @Description: Roll axis angle controller P gain. Converts the error between the desired roll angle and actual angle to a desired roll rate + // @Range: 3.000 12.000 + // @Range{Sub}: 0.0 12.000 + // @User: Standard + AP_SUBGROUPINFO(_p_angle_roll2, "ANG_RLL_", 1, AC_CustomControl_PID, AC_P), + + // @Param: ANG_PIT_P + // @DisplayName: Pitch axis angle controller P gain + // @Description: Pitch axis angle controller P gain. Converts the error between the desired pitch angle and actual angle to a desired pitch rate + // @Range: 3.000 12.000 + // @Range{Sub}: 0.0 12.000 + // @User: Standard + AP_SUBGROUPINFO(_p_angle_pitch2, "ANG_PIT_", 2, AC_CustomControl_PID, AC_P), + + // @Param: ANG_YAW_P + // @DisplayName: Yaw axis angle controller P gain + // @Description: Yaw axis angle controller P gain. Converts the error between the desired yaw angle and actual angle to a desired yaw rate + // @Range: 3.000 12.000 + // @Range{Sub}: 0.0 6.000 + // @User: Standard + AP_SUBGROUPINFO(_p_angle_yaw2, "ANG_YAW_", 3, AC_CustomControl_PID, AC_P), + + + // @Param: RAT_RLL_P + // @DisplayName: Roll axis rate controller P gain + // @Description: Roll axis rate controller P gain. Converts the difference between desired roll rate and actual roll rate into a motor speed output + // @Range: 0.01 0.5 + // @Increment: 0.005 + // @User: Standard + + // @Param: RAT_RLL_I + // @DisplayName: Roll axis rate controller I gain + // @Description: Roll axis rate controller I gain. Corrects long-term difference in desired roll rate vs actual roll rate + // @Range: 0.01 2.0 + // @Increment: 0.01 + // @User: Standard + + // @Param: RAT_RLL_IMAX + // @DisplayName: Roll axis rate controller I gain maximum + // @Description: Roll axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output + // @Range: 0 1 + // @Increment: 0.01 + // @User: Standard + + // @Param: RAT_RLL_D + // @DisplayName: Roll axis rate controller D gain + // @Description: Roll axis rate controller D gain. Compensates for short-term change in desired roll rate vs actual roll rate + // @Range: 0.0 0.05 + // @Increment: 0.001 + // @User: Standard + + // @Param: RAT_RLL_FF + // @DisplayName: Roll axis rate controller feed forward + // @Description: Roll axis rate controller feed forward + // @Range: 0 0.5 + // @Increment: 0.001 + // @User: Standard + + // @Param: RAT_RLL_FLTT + // @DisplayName: Roll axis rate controller target frequency in Hz + // @Description: Roll axis rate controller target frequency in Hz + // @Range: 5 100 + // @Increment: 1 + // @Units: Hz + // @User: Standard + + // @Param: RAT_RLL_FLTE + // @DisplayName: Roll axis rate controller error frequency in Hz + // @Description: Roll axis rate controller error frequency in Hz + // @Range: 0 100 + // @Increment: 1 + // @Units: Hz + // @User: Standard + + // @Param: RAT_RLL_FLTD + // @DisplayName: Roll axis rate controller derivative frequency in Hz + // @Description: Roll axis rate controller derivative frequency in Hz + // @Range: 5 100 + // @Increment: 1 + // @Units: Hz + // @User: Standard + + // @Param: RAT_RLL_SMAX + // @DisplayName: Roll slew rate limit + // @Description: Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature. + // @Range: 0 200 + // @Increment: 0.5 + // @User: Advanced + AP_SUBGROUPINFO(_pid_atti_rate_roll, "RAT_RLL_", 4, AC_CustomControl_PID, AC_PID), + + // @Param: RAT_PIT_P + // @DisplayName: Pitch axis rate controller P gain + // @Description: Pitch axis rate controller P gain. Converts the difference between desired pitch rate and actual pitch rate into a motor speed output + // @Range: 0.01 0.50 + // @Increment: 0.005 + // @User: Standard + + // @Param: RAT_PIT_I + // @DisplayName: Pitch axis rate controller I gain + // @Description: Pitch axis rate controller I gain. Corrects long-term difference in desired pitch rate vs actual pitch rate + // @Range: 0.01 2.0 + // @Increment: 0.01 + // @User: Standard + + // @Param: RAT_PIT_IMAX + // @DisplayName: Pitch axis rate controller I gain maximum + // @Description: Pitch axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output + // @Range: 0 1 + // @Increment: 0.01 + // @User: Standard + + // @Param: RAT_PIT_D + // @DisplayName: Pitch axis rate controller D gain + // @Description: Pitch axis rate controller D gain. Compensates for short-term change in desired pitch rate vs actual pitch rate + // @Range: 0.0 0.05 + // @Increment: 0.001 + // @User: Standard + + // @Param: RAT_PIT_FF + // @DisplayName: Pitch axis rate controller feed forward + // @Description: Pitch axis rate controller feed forward + // @Range: 0 0.5 + // @Increment: 0.001 + // @User: Standard + + // @Param: RAT_PIT_FLTT + // @DisplayName: Pitch axis rate controller target frequency in Hz + // @Description: Pitch axis rate controller target frequency in Hz + // @Range: 5 100 + // @Increment: 1 + // @Units: Hz + // @User: Standard + + // @Param: RAT_PIT_FLTE + // @DisplayName: Pitch axis rate controller error frequency in Hz + // @Description: Pitch axis rate controller error frequency in Hz + // @Range: 0 100 + // @Increment: 1 + // @Units: Hz + // @User: Standard + + // @Param: RAT_PIT_FLTD + // @DisplayName: Pitch axis rate controller derivative frequency in Hz + // @Description: Pitch axis rate controller derivative frequency in Hz + // @Range: 5 100 + // @Increment: 1 + // @Units: Hz + // @User: Standard + + // @Param: RAT_PIT_SMAX + // @DisplayName: Pitch slew rate limit + // @Description: Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature. + // @Range: 0 200 + // @Increment: 0.5 + // @User: Advanced + AP_SUBGROUPINFO(_pid_atti_rate_pitch, "RAT_PIT_", 5, AC_CustomControl_PID, AC_PID), + + + // @Param: RAT_YAW_P + // @DisplayName: Yaw axis rate controller P gain + // @Description: Yaw axis rate controller P gain. Converts the difference between desired yaw rate and actual yaw rate into a motor speed output + // @Range: 0.10 2.50 + // @Increment: 0.005 + // @User: Standard + + // @Param: RAT_YAW_I + // @DisplayName: Yaw axis rate controller I gain + // @Description: Yaw axis rate controller I gain. Corrects long-term difference in desired yaw rate vs actual yaw rate + // @Range: 0.010 1.0 + // @Increment: 0.01 + // @User: Standard + + // @Param: RAT_YAW_IMAX + // @DisplayName: Yaw axis rate controller I gain maximum + // @Description: Yaw axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output + // @Range: 0 1 + // @Increment: 0.01 + // @User: Standard + + // @Param: RAT_YAW_D + // @DisplayName: Yaw axis rate controller D gain + // @Description: Yaw axis rate controller D gain. Compensates for short-term change in desired yaw rate vs actual yaw rate + // @Range: 0.000 0.02 + // @Increment: 0.001 + // @User: Standard + + // @Param: RAT_YAW_FF + // @DisplayName: Yaw axis rate controller feed forward + // @Description: Yaw axis rate controller feed forward + // @Range: 0 0.5 + // @Increment: 0.001 + // @User: Standard + + // @Param: RAT_YAW_FLTT + // @DisplayName: Yaw axis rate controller target frequency in Hz + // @Description: Yaw axis rate controller target frequency in Hz + // @Range: 1 50 + // @Increment: 1 + // @Units: Hz + // @User: Standard + + // @Param: RAT_YAW_FLTE + // @DisplayName: Yaw axis rate controller error frequency in Hz + // @Description: Yaw axis rate controller error frequency in Hz + // @Range: 0 20 + // @Increment: 1 + // @Units: Hz + // @User: Standard + + // @Param: RAT_YAW_FLTD + // @DisplayName: Yaw axis rate controller derivative frequency in Hz + // @Description: Yaw axis rate controller derivative frequency in Hz + // @Range: 5 50 + // @Increment: 1 + // @Units: Hz + // @User: Standard + + // @Param: RAT_YAW_SMAX + // @DisplayName: Yaw slew rate limit + // @Description: Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature. + // @Range: 0 200 + // @Increment: 0.5 + // @User: Advanced + AP_SUBGROUPINFO(_pid_atti_rate_yaw, "RAT_YAW_", 6, AC_CustomControl_PID, AC_PID), + + AP_GROUPEND +}; + +AC_CustomControl_PID::AC_CustomControl_PID(AC_CustomControl& frontend, AP_AHRS_View*& ahrs, AC_AttitudeControl_Multi*& att_control, AP_MotorsMulticopter*& motors, float dt) : + AC_CustomControl_Backend(frontend, ahrs, att_control, motors, dt), + _p_angle_roll2(AC_ATTITUDE_CONTROL_ANGLE_P * 0.90f), + _p_angle_pitch2(AC_ATTITUDE_CONTROL_ANGLE_P * 0.90f), + _p_angle_yaw2(AC_ATTITUDE_CONTROL_ANGLE_P * 0.90f), + _pid_atti_rate_roll(AC_ATC_MULTI_RATE_RP_P * 0.90f, AC_ATC_MULTI_RATE_RP_I * 0.90f, AC_ATC_MULTI_RATE_RP_D * 0.90f, 0.0f, AC_ATC_MULTI_RATE_RP_IMAX * 0.90f, AC_ATC_MULTI_RATE_RP_FILT_HZ * 0.90f, 0.0f, AC_ATC_MULTI_RATE_RP_FILT_HZ * 0.90f, dt), + _pid_atti_rate_pitch(AC_ATC_MULTI_RATE_RP_P * 0.90f, AC_ATC_MULTI_RATE_RP_I * 0.90f, AC_ATC_MULTI_RATE_RP_D * 0.90f, 0.0f, AC_ATC_MULTI_RATE_RP_IMAX * 0.90f, AC_ATC_MULTI_RATE_RP_FILT_HZ * 0.90f, 0.0f, AC_ATC_MULTI_RATE_RP_FILT_HZ * 0.90f, dt), + _pid_atti_rate_yaw(AC_ATC_MULTI_RATE_YAW_P * 0.90f, AC_ATC_MULTI_RATE_YAW_I * 0.90f, AC_ATC_MULTI_RATE_YAW_D * 0.90f, 0.0f, AC_ATC_MULTI_RATE_YAW_IMAX * 0.90f, AC_ATC_MULTI_RATE_RP_FILT_HZ * 0.90f, AC_ATC_MULTI_RATE_YAW_FILT_HZ * 0.90f, 0.0f, dt) +{ + AP_Param::setup_object_defaults(this, var_info); +} + +Vector3f AC_CustomControl_PID::update() +{ + // reset controller based on spool state + switch (_motors->get_spool_state()) { + case AP_Motors::SpoolState::SHUT_DOWN: + case AP_Motors::SpoolState::GROUND_IDLE: + // We are still at the ground. Reset custom controller to avoid + // build up, ex: integrator + reset(); + break; + + case AP_Motors::SpoolState::THROTTLE_UNLIMITED: + case AP_Motors::SpoolState::SPOOLING_UP: + case AP_Motors::SpoolState::SPOOLING_DOWN: + // we are off the ground + break; + } + + // run custom controller after here + Quaternion attitude_body, attitude_target; + _ahrs->get_quat_body_to_ned(attitude_body); + + attitude_target = _att_control->get_attitude_target_quat(); + // This vector represents the angular error to rotate the thrust vector using x and y and heading using z + Vector3f attitude_error; + float _thrust_angle, _thrust_error_angle; + _att_control->thrust_heading_rotation_angles(attitude_target, attitude_body, attitude_error, _thrust_angle, _thrust_error_angle); + + // recalculate ang vel feedforward from attitude target model + // rotation from the target frame to the body frame + Quaternion rotation_target_to_body = attitude_body.inverse() * attitude_target; + // target angle velocity vector in the body frame + Vector3f ang_vel_body_feedforward = rotation_target_to_body * _att_control->get_attitude_target_ang_vel(); + + // run attitude controller + Vector3f target_rate; + target_rate[0] = _p_angle_roll2.kP() * attitude_error.x + ang_vel_body_feedforward[0]; + target_rate[1] = _p_angle_pitch2.kP() * attitude_error.y + ang_vel_body_feedforward[1]; + target_rate[2] = _p_angle_yaw2.kP() * attitude_error.z + ang_vel_body_feedforward[2]; + + // run rate controller + Vector3f gyro_latest = _ahrs->get_gyro_latest(); + Vector3f motor_out; + motor_out.x = _pid_atti_rate_roll.update_all(target_rate[0], gyro_latest[0], 1); + motor_out.y = _pid_atti_rate_pitch.update_all(target_rate[1], gyro_latest[1], 1); + motor_out.z = _pid_atti_rate_yaw.update_all(target_rate[2], gyro_latest[2], 1); + + return motor_out; +} + +// This example uses exact same controller architecture as ArduCopter attitude controller without all the safe guard against saturation. +// The gains are scaled 0.9 times to better detect switch over response. +// Note that integrator are not reset correctly as it is done in reset_main_att_controller inside AC_CustomControl.cpp +// This is done intentionally to demonstrate switch over performance of two exact controller with different reset handling. +void AC_CustomControl_PID::reset(void) +{ + _pid_atti_rate_roll.reset_I(); + _pid_atti_rate_pitch.reset_I(); + _pid_atti_rate_yaw.reset_I(); + _pid_atti_rate_roll.reset_filter(); + _pid_atti_rate_pitch.reset_filter(); + _pid_atti_rate_yaw.reset_filter(); +} + +#endif diff --git a/libraries/AC_CustomControl/AC_CustomControl_PID.h b/libraries/AC_CustomControl/AC_CustomControl_PID.h new file mode 100644 index 00000000000..9740061aad7 --- /dev/null +++ b/libraries/AC_CustomControl/AC_CustomControl_PID.h @@ -0,0 +1,41 @@ +#pragma once + +#include +#include +#include +#include + +#include "AC_CustomControl_Backend.h" + +#ifndef CUSTOMCONTROL_PID_ENABLED + #define CUSTOMCONTROL_PID_ENABLED AP_CUSTOMCONTROL_ENABLED +#endif + +#if CUSTOMCONTROL_PID_ENABLED + +class AC_CustomControl_PID : public AC_CustomControl_Backend { +public: + AC_CustomControl_PID(AC_CustomControl& frontend, AP_AHRS_View*& ahrs, AC_AttitudeControl_Multi*& att_control, AP_MotorsMulticopter*& motors, float dt); + + // run lowest level body-frame rate controller and send outputs to the motors + Vector3f update() override; + void reset(void) override; + + // user settable parameters + static const struct AP_Param::GroupInfo var_info[]; + +protected: + // put controller related variable here + + // angle P controller objects + AC_P _p_angle_roll2; + AC_P _p_angle_pitch2; + AC_P _p_angle_yaw2; + + // rate PID controller objects + AC_PID _pid_atti_rate_roll; + AC_PID _pid_atti_rate_pitch; + AC_PID _pid_atti_rate_yaw; +}; + +#endif diff --git a/libraries/AC_CustomControl/README.md b/libraries/AC_CustomControl/README.md new file mode 100644 index 00000000000..f1cf85fa10c --- /dev/null +++ b/libraries/AC_CustomControl/README.md @@ -0,0 +1,258 @@ +# Custom Controller + +Custom controller library allows you to implement and easily run your own controller inside ArduPilot in a systematic way. Original-primary-mains means existing controller and custom-secondary means new controller. This library aimed to not interfere with other parts of the main controller or vehicle level code. The controller output is sent to the control allocation library, known as the mixer, the same way the main controller does. + +## Features + +- In-flight switching between main and custom controller with RC switch, option 109. +- Bitmask to choose which axis to use the custom controller output +- Filter, integrator reset mechanism when switching between controller +  - Bumpless transfer when switching from custom to the main controller +- Ground and in-flight spool state separation to avoid build-up during arming and take-off with the custom controller +- Frontend-backend separation that allows adding a new controller with very little overhead +- Flag to compile out custom controller related code on hardware, --enable-custom-controller +- Proper parameter table implementation that allows adding new custom controller parameter table without corruption +- Single parameter to switch between different custom controllers, reboot required +- Multiple checks to avoid accidentally running mis-un/configured custom controller with RC switch +- Custom controller parameters start with `CC_` in the GCS. + +The frontend library has the following parameters + +- `CC_TYPE`: choose which custom controller backend to use, reboot required. +  - Setting it to 0 will turn this feature off, GCS will not display parameters related to the custom controller +- `CC_AXIS_MASK`: choose which axis to use custom controller output +  - This is a bitmask type parameter. Set 7 to use all output + + +## Interaction With Main Controller + +The custom controller update function is called after the main rate controller is run and before the motor output library is called. This placement allows overriding motor library mixer input, namely `_roll_in`, `_pitch_in`, `_yaw_in` values, without causing functional change inside the motor library. This is the same way the main controller sends its output to the control allocation library, known as a mixer. This reduces latency to the minimum level. + +The custom controller library uses the same target attitude as the main controller. Most of the code inside AC_AttitudeControl library is related to input shapings such as how to interpret pilot commands depending on the flight mode or high-level position controller output. For example, in STABILIZE mode pilot RC commands are scaled based on maximum lean angle and yaw rate parameters, these values are passed to `input_euler_angle_roll_pitch_euler_rate_yaw` function. The pilot command is fed into a first-order input shaping algorithm to smooth out any jitter due to RC link and to generate an acceleration-limited attitude target. Later, attitude controller `attitude_controller_run_quat` is called and attitude error is calculated based on acceleration limited `_attitude_target` value, and target rate is generated. Even if acceleration limiting is turned off by setting `ATC_RATE_FF_ENAB` to 0, the target attitude is still presented with `_attitude_target` variable. + +Every input shaping function inside `AC_AttitudeControl` calls `attitude_controller_run_quat` at the end to run the attitude controller, except when flying in ACRO mode with the acro option set to rate only. Even in this case `_attitude_target` is updated properly and pilot command can be accessed via `rate_bf_targets()` function. + +By default, the input shaping algorithm is turned on. This produces kinematically consistent attitude target and rate feed-forward values. Take a look at the custom PID backend to see how rate feed-forward is added to attitude controller output. It is advised to use the rate feed-forward value if `ATC_RATE_FF_ENAB` is enabled, otherwise the pilot might feel significant lag between RC command and vehicle response. + +After running the custom controller, mixer input is sent to the motor library via `set_roll`, `set_pitch`, `set_yaw` functions. + +### Bumpless Transfer +When switching from the custom controller to the main controller it is important to reset the main controller target, error, d-term filters and set each axis integrator properly. Otherwise, a sudden jump in the controller error signal or motor output will be observed, which could result in a jerky motion. To allow a smooth transition between controllers, the main controller reset function is called when switching out of the custom controller which reset all three axis of the main controller. + +The attitude target and rate target are also made equal to the current attitude and gyro rate to make the error signal grow from zero. In order to avoid impulse input to the controller, the target resetting is not performed when the feedforward is disabled by setting `ATC_RATE_FF_ENAB` parameter to 0. + +The reset is performed inside `reset_main_atti_controller` function. An example of reset per axis is given here. + +```C++ +_atti_control->get_rate_roll_pid().reset_filter(); +_atti_control->get_rate_roll_pid().set_integrator(_atti_control->rate_bf_targets().x - gyro_latest.x, _motors->get_roll()); +``` + +## Backend Type +Currently, there 4 custom controller backend available. These are +- Empty backend `CC_TYPE` = 1 +- PID backend `CC_TYPE` = 2 + +### Empty Controller - `CC_TYPE` = 1 +The empty controller does not do any calculations. It is created to make it easier to copy and implement your new controller. The main controller is not reset when switching from an empty controller. + +### PID Controller - `CC_TYPE` = 2 +PID controller backend has the same controller architecture as the main controller. It doesn't have any safeguarding mechanism such as acceleration limiting or rate limiting. The default gains are scaled 0.9 times to differentiate the custom controller response from the main one. Since this controller does not have acceleration limiting, specifically a square root controller, it would be safer to give a gentle command while flying with it. Although it has the same architecture as the main one, a proper reset functionality is not implemented intentionally to make it easier to detect the effect of improper resetting. + +## How To Use It +The custom controller is enabled by default in SITL. You can test it using PID backend. + +1. Compile and run the default SITL model. In the GCS, choose the custom controller type, assign axis mask and set which RC switch to activate the custom controller. Reboot autopilot. For example in mavproxy, +``` +param set CC_TYPE 2 +param set CC_AXIS_MASK 7 +param set RC6_OPTION 109 +reboot +``` + +2. Run the following command to display backend parameters. These would be under `CC2_` for PID backend. +``` +param set CC2* +``` + +3. Arm and take-off. While at the hover flight, switch RC6 to high. In mavproxy, you can do this with +``` +rc 6 2000 +``` + +4. You should be prompted with `Custom controller is ON` message on GCS to indicate that the custom controller is running. + +5. Set RC6 to low to switch back to the main controller. You should be prompted with `Custom controller is OFF` message on GCS. + + +### Real Flight Testing +It is recommended that you always arm, take-off, land, and disarm while the main controller is running. You should switch to the custom controller while the vehicle is hovering steadily. This will reduce the effect of improper filter resetting. You should arm and take off with the custom controller only if proper ground idling is implemented. + +To test it on hardware compile with "--enable-custom-controller" flag. +```C++ +./waf configure --board CubeOrange copter --enable-custom-controller +``` + +### Post Flight Logs +Switching in and out of custom controller logged under the "CC" in log tree. You can see the time and duration the custom controller is active under "CC.Act" + +## How To Add New Custom Controller +You can add your own custom controller backend with the following steps. Let's assume we are adding the 5th custom controller. + +1. Generate a copy of `AC_CustomControl_Empty.cpp` and `AC_CustomControl_Empty.h` within `AC_CustomControl` folder. The folder tree would look like this, +``` +AC_CustomControl.cpp +AC_CustomControl.h +AC_CustomControl_Backend.h +AC_CustomControl_Empty.cpp +AC_CustomControl_Empty.h +AC_CustomControl_Empty - Copy.cpp +AC_CustomControl_Empty - Copy.h +. +. +. +``` + +PID and README files are omitted to keep it simple. + +2. Change `Empty - Copy` suffix with your own choice, let's called it `XYZ`, which would look like +``` +AC_CustomControl.cpp +AC_CustomControl.h +AC_CustomControl_Backend.h +AC_CustomControl_Empty.cpp +AC_CustomControl_Empty.h +AC_CustomControl_XYZ.cpp +AC_CustomControl_XYZ.h +. +. +. +``` + +3. Change every class name, function definition etc. from `AC_CustomControl_Empty` to `AC_CustomControl_XYZ` inside `AC_CustomControl_XYZ.cpp` and `AC_CustomControl_XYZ.h` files. This would look like this for the header file +```C++ +#pragma once + +#include "AC_CustomControl_Backend.h" + +class AC_CustomControl_XYZ : public AC_CustomControl_Backend { +public: + AC_CustomControl_XYZ(AC_CustomControl &frontend, AP_AHRS_View*& ahrs, AC_AttitudeControl_Multi*& atti_control, AP_MotorsMulticopter*& motors, float dt); + + + Vector3f update(void) override; + void reset(void) override; + + // user settable parameters + static const struct AP_Param::GroupInfo var_info[]; + +protected: + // declare parameters here + AP_Float param1; + AP_Float param2; + AP_Float param3; +}; +``` + +4. Increase the maximum number of custom control variables by one and update the custom control type enum + +from +```C++ +#define CUSTOMCONTROL_MAX_TYPES 2 +``` +to +```C++ +#define CUSTOMCONTROL_MAX_TYPES 3 +``` + +```C++ +enum class CustomControlType : uint8_t { + CONT_NONE = 0, + CONT_EMPTY = 1, + CONT_PID = 2, + CONT_XYZ = 3, +}; // controller that should be used +``` + +5. Add a new backend header in `AC_CustomControl.cpp` file. Place it under other backend includes. +```C++ +#include "AC_CustomControl_Backend.h" +#include "AC_CustomControl_Empty.h" +#include "AC_CustomControl_PID.h" +#include "AC_CustomControl_XYZ.h" +``` + +6. Add new backend parameter in `AC_CustomControl.cpp` file. Increment `_backend`, `_backend_var_info` array index by one and also increment backend parameter prefix and parameter table index by one. Place it under the other backend's parameters. +```C++ +. +. +. + // parameters for empty controller + AP_SUBGROUPVARPTR(_backend, "1_", 6, AC_CustomControl, _backend_var_info[0]), + + // parameters for PID controller + AP_SUBGROUPVARPTR(_backend, "2_", 7, AC_CustomControl, _backend_var_info[1]), + + // parameters for XYZ controller + AP_SUBGROUPVARPTR(_backend, "3_", 8, AC_CustomControl, _backend_var_info[2]), + + AP_GROUPEND +}; +``` + +7. Allow creating new backend class in `AC_CustomControl.cpp` file inside `init` function. +```C++ +. +. +. +case CustomControlType::CONT_PID: + _backend = new AC_CustomControl_PID(*this, _ahrs, _atti_control, _motors, _dt); + _backend_var_info[get_type()] = AC_CustomControl_PID::var_info; + break; +case CustomControlType::CONT_XYZ: + _backend = new AC_CustomControl_XYZ(*this, _ahrs, _atti_control, _motors, _dt); + _backend_var_info[get_type()] = AC_CustomControl_XYZ::var_info; + break; +default: + return; +} +``` + +8. This is the bare minimum to compile and run your custom controller. You can add controller related code to `AC_CustomControl_XYZ` file without changing anything else. + +9. You can add new parameters by following the directions in this [Adding a parameter to a library](https://ardupilot.org/dev/docs/code-overview-adding-a-new-parameter.html#adding-a-parameter-to-a-library) wiki page. + +10. Initialize the class object in the backend's constructor. For example in PID backend +```C++ + // put controller related variable here + + // angle P controller objects + AC_P _p_angle_roll2; + AC_P _p_angle_pitch2; + AC_P _p_angle_yaw2; + + // rate PID controller objects + AC_PID _pid_atti_rate_roll; + AC_PID _pid_atti_rate_pitch; + AC_PID _pid_atti_rate_yaw; +``` +above P or PID classes are initialized in the backend's constructors, +```C++ +AC_CustomControl_PID::AC_CustomControl_PID(AC_CustomControl &frontend, AP_AHRS_View*& ahrs, AC_AttitudeControl_Multi*& atti_control, AP_MotorsMulticopter*& motors, float dt) : + AC_CustomControl_Backend(frontend, ahrs, atti_control, motors, dt), + _p_angle_roll2(AC_ATTITUDE_CONTROL_ANGLE_P * 0.90f), + _p_angle_pitch2(AC_ATTITUDE_CONTROL_ANGLE_P * 0.90f), + _p_angle_yaw2(AC_ATTITUDE_CONTROL_ANGLE_P * 0.90f), + _pid_atti_rate_roll(AC_ATC_MULTI_RATE_RP_P * 0.90f, AC_ATC_MULTI_RATE_RP_I * 0.90f, AC_ATC_MULTI_RATE_RP_D * 0.90f, 0.0f, AC_ATC_MULTI_RATE_RP_IMAX * 0.90f, AC_ATC_MULTI_RATE_RP_FILT_HZ * 0.90f, 0.0f, AC_ATC_MULTI_RATE_RP_FILT_HZ * 0.90f, dt), + _pid_atti_rate_pitch(AC_ATC_MULTI_RATE_RP_P * 0.90f, AC_ATC_MULTI_RATE_RP_I * 0.90f, AC_ATC_MULTI_RATE_RP_D * 0.90f, 0.0f, AC_ATC_MULTI_RATE_RP_IMAX * 0.90f, AC_ATC_MULTI_RATE_RP_FILT_HZ * 0.90f, 0.0f, AC_ATC_MULTI_RATE_RP_FILT_HZ * 0.90f, dt), + _pid_atti_rate_yaw(AC_ATC_MULTI_RATE_YAW_P * 0.90f, AC_ATC_MULTI_RATE_YAW_I * 0.90f, AC_ATC_MULTI_RATE_YAW_D * 0.90f, 0.0f, AC_ATC_MULTI_RATE_YAW_IMAX * 0.90f, AC_ATC_MULTI_RATE_RP_FILT_HZ * 0.90f, AC_ATC_MULTI_RATE_YAW_FILT_HZ * 0.90f, 0.0f, dt) +{ + AP_Param::setup_object_defaults(this, var_info); +} +``` + +11. Add your controller inside `update` function of `AC_CustomControl_XYZ.cpp` file. This function returns a 3-dimensional vector consisting of roll pitch yaw mixer input, respectively. + +12. Add reset functionality inside `reset` function of `AC_CustomControl_XYZ.cpp` file. It is user's responsibility to add proper controller resetting functionality. This highly depends on the controller and it should not be copy-pasted from another backend without testing it in SITL. + +13. You can access target attitude and target rate values using `atti_control->get_attitude_target_quat()` and `atti_control->rate_bf_targets()` functions, respectively. You can also access latest gyro measurement using `_ahrs->get_gyro_latest()` function. Take a look at other backends diff --git a/libraries/AC_Fence/AC_Fence.cpp b/libraries/AC_Fence/AC_Fence.cpp index 41bc03fae6c..e94658ee26a 100644 --- a/libraries/AC_Fence/AC_Fence.cpp +++ b/libraries/AC_Fence/AC_Fence.cpp @@ -1,5 +1,15 @@ #include "AC_Fence.h" +#if AP_FENCE_ENABLED + +#include + +#ifndef AC_FENCE_DUMMY_METHODS_ENABLED +#define AC_FENCE_DUMMY_METHODS_ENABLED (!(APM_BUILD_TYPE(APM_BUILD_Rover) | APM_BUILD_COPTER_OR_HELI | APM_BUILD_TYPE(APM_BUILD_ArduPlane) | APM_BUILD_TYPE(APM_BUILD_ArduSub) | (AP_FENCE_ENABLED == 1))) +#endif + +#if !AC_FENCE_DUMMY_METHODS_ENABLED + #include #include #include @@ -14,6 +24,22 @@ extern const AP_HAL::HAL& hal; #define AC_FENCE_TYPE_DEFAULT AC_FENCE_TYPE_ALT_MAX | AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON #endif +// default boundaries +#define AC_FENCE_ALT_MAX_DEFAULT 100.0f // default max altitude is 100m +#define AC_FENCE_ALT_MIN_DEFAULT -10.0f // default maximum depth in meters +#define AC_FENCE_CIRCLE_RADIUS_DEFAULT 300.0f // default circular fence radius is 300m +#define AC_FENCE_ALT_MAX_BACKUP_DISTANCE 20.0f // after fence is broken we recreate the fence 20m further up +#define AC_FENCE_ALT_MIN_BACKUP_DISTANCE 20.0f // after fence is broken we recreate the fence 20m further down +#define AC_FENCE_MARGIN_DEFAULT 2.0f // default distance in meters that autopilot's should maintain from the fence to avoid a breach +#define AC_FENCE_MANUAL_RECOVERY_TIME_MIN 10000 // pilot has 10seconds to recover during which time the autopilot will not attempt to re-take control + +#if APM_BUILD_TYPE(APM_BUILD_ArduPlane) +#define AC_FENCE_CIRCLE_RADIUS_BACKUP_DISTANCE 100.0 // after fence is broken we recreate the fence 50m further out +#else +#define AC_FENCE_CIRCLE_RADIUS_BACKUP_DISTANCE 20.0 // after fence is broken we recreate the fence 20m further out +#endif + + const AP_Param::GroupInfo AC_Fence::var_info[] = { // @Param: ENABLE // @DisplayName: Fence enable/disable @@ -99,15 +125,22 @@ const AP_Param::GroupInfo AC_Fence::var_info[] = { // @User: Standard AP_GROUPINFO_FRAME("RET_ALT", 9, AC_Fence, _ret_altitude, 0.0f, AP_PARAM_FRAME_PLANE), - // @Param: AUTOENABLE + // @Param{Plane}: AUTOENABLE // @DisplayName: Fence Auto-Enable // @Description: Auto-enable of fence - // @Values{Plane}: 0:AutoEnableOff,1:AutoEnableOnTakeoff,2:AutoEnableDisableFloorOnLanding,3:AutoEnableOnlyWhenArmed + // @Values: 0:AutoEnableOff,1:AutoEnableOnTakeoff,2:AutoEnableDisableFloorOnLanding,3:AutoEnableOnlyWhenArmed // @Range: 0 3 // @Increment: 1 // @User: Standard AP_GROUPINFO_FRAME("AUTOENABLE", 10, AC_Fence, _auto_enabled, static_cast(AutoEnable::ALWAYS_DISABLED), AP_PARAM_FRAME_PLANE), + // @Param{Plane}: OPTIONS + // @DisplayName: Fence options + // @Description: 0:Disable mode change following fence action until fence breach is cleared + // @Bitmask: 0:Disable mode change following fence action until fence breach is cleared + // @User: Standard + AP_GROUPINFO_FRAME("OPTIONS", 11, AC_Fence, _options, static_cast(OPTIONS::DISABLE_MODE_CHANGE), AP_PARAM_FRAME_PLANE), + AP_GROUPEND }; @@ -131,7 +164,7 @@ void AC_Fence::enable(bool value) } else if (!_enabled && value) { AP::logger().Write_Event(LogEvent::FENCE_ENABLE); } - _enabled = value; + _enabled.set(value); if (!value) { clear_breach(AC_FENCE_TYPE_ALT_MIN | AC_FENCE_TYPE_ALT_MAX | AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON); disable_floor(); @@ -510,14 +543,14 @@ uint8_t AC_Fence::check() { uint8_t ret = 0; + // clear any breach from a non-enabled fence + clear_breach(~_enabled_fences); + // return immediately if disabled if ((!_enabled && !_auto_enabled) || !_enabled_fences) { return 0; } - // clear any breach from a non-enabled fence - clear_breach(~_enabled_fences); - // check if pilot is attempting to recover manually if (_manual_recovery_start_ms != 0) { // we ignore any fence breaches during the manual recovery period which is about 10 seconds @@ -693,6 +726,46 @@ const AC_PolyFence_loader &AC_Fence::polyfence() const return _poly_loader; } + +#else // build type is not appropriate; provide a dummy implementation: +const AP_Param::GroupInfo AC_Fence::var_info[] = { AP_GROUPEND }; + +AC_Fence::AC_Fence() {}; + +void AC_Fence::enable(bool value) {}; + +void AC_Fence::disable_floor() {}; + +void AC_Fence::auto_enable_fence_after_takeoff() {}; +void AC_Fence::auto_disable_fence_for_landing() {}; + +bool AC_Fence::present() const { return false; } + +uint8_t AC_Fence::get_enabled_fences() const { return 0; } + +bool AC_Fence::pre_arm_check(const char* &fail_msg) const { return true; } + +uint8_t AC_Fence::check() { return 0; } +bool AC_Fence::check_destination_within_fence(const Location& loc) { return true; } +float AC_Fence::get_breach_distance(uint8_t fence_type) const { return 0.0; } + +void AC_Fence::manual_recovery_start() {} + +bool AC_Fence::sys_status_present() const { return false; } +bool AC_Fence::sys_status_enabled() const { return false; } +bool AC_Fence::sys_status_failed() const { return false; } + +AC_PolyFence_loader &AC_Fence::polyfence() +{ + return _poly_loader; +} +const AC_PolyFence_loader &AC_Fence::polyfence() const +{ + return _poly_loader; +} + +#endif // #if AC_FENCE_DUMMY_METHODS_ENABLED + // singleton instance AC_Fence *AC_Fence::_singleton; @@ -705,3 +778,5 @@ AC_Fence *fence() } } + +#endif // AP_FENCE_ENABLED diff --git a/libraries/AC_Fence/AC_Fence.h b/libraries/AC_Fence/AC_Fence.h index dd13c8ab579..0a967310a8a 100644 --- a/libraries/AC_Fence/AC_Fence.h +++ b/libraries/AC_Fence/AC_Fence.h @@ -1,12 +1,14 @@ #pragma once +#include "AC_Fence_config.h" + +#if AP_FENCE_ENABLED + #include #include #include #include -#include #include -#include // bit masks for enabled fence types. Used for TYPE parameter #define AC_FENCE_TYPE_ALT_MAX 1 // high alt fence which usually initiates an RTL @@ -24,18 +26,8 @@ #define AC_FENCE_ACTION_GUIDED 6 // guided mode, with target waypoint as fence return point #define AC_FENCE_ACTION_GUIDED_THROTTLE_PASS 7 // guided mode, but pilot retains manual throttle control -// default boundaries -#define AC_FENCE_ALT_MAX_DEFAULT 100.0f // default max altitude is 100m -#define AC_FENCE_ALT_MIN_DEFAULT -10.0f // default maximum depth in meters -#define AC_FENCE_CIRCLE_RADIUS_DEFAULT 300.0f // default circular fence radius is 300m -#define AC_FENCE_ALT_MAX_BACKUP_DISTANCE 20.0f // after fence is broken we recreate the fence 20m further up -#define AC_FENCE_ALT_MIN_BACKUP_DISTANCE 20.0f // after fence is broken we recreate the fence 20m further down -#define AC_FENCE_CIRCLE_RADIUS_BACKUP_DISTANCE 20.0f // after fence is broken we recreate the fence 20m further out -#define AC_FENCE_MARGIN_DEFAULT 2.0f // default distance in meters that autopilot's should maintain from the fence to avoid a breach - // give up distance #define AC_FENCE_GIVE_UP_DISTANCE 100.0f // distance outside the fence at which we should give up and just land. Note: this is not used by library directly but is intended to be used by the main code -#define AC_FENCE_MANUAL_RECOVERY_TIME_MIN 10000 // pilot has 10seconds to recover during which time the autopilot will not attempt to re-take control class AC_Fence { @@ -105,7 +97,7 @@ class AC_Fence uint8_t check(); // returns true if the destination is within fence (used to reject waypoints outside the fence) - bool check_destination_within_fence(const Location& loc); + bool check_destination_within_fence(const class Location& loc); /// get_breaches - returns bit mask of the fence types that have been breached uint8_t get_breaches() const { return _breached_fences; } @@ -154,6 +146,13 @@ class AC_Fence AC_PolyFence_loader &polyfence(); const AC_PolyFence_loader &polyfence() const; + enum class OPTIONS { + DISABLE_MODE_CHANGE = 1 << 0, + }; + bool option_enabled(OPTIONS opt) const { + return (_options.get() & int16_t(opt)) != 0; + } + static const struct AP_Param::GroupInfo var_info[]; private: @@ -194,6 +193,7 @@ class AC_Fence AP_Int8 _total; // number of polygon points saved in eeprom AP_Int8 _ret_rally; // return to fence return point or rally point/home AP_Int16 _ret_altitude; // return to this altitude + AP_Int16 _options; // options bitmask, see OPTIONS enum // backup fences float _alt_max_backup; // backup altitude upper limit in meters used to refire the breach if the vehicle continues to move further away @@ -226,3 +226,5 @@ class AC_Fence namespace AP { AC_Fence *fence(); }; + +#endif // AP_FENCE_ENABLED diff --git a/libraries/AC_Fence/AC_Fence_config.h b/libraries/AC_Fence/AC_Fence_config.h new file mode 100644 index 00000000000..5c8494f7ad1 --- /dev/null +++ b/libraries/AC_Fence/AC_Fence_config.h @@ -0,0 +1,11 @@ +#pragma once + +#include + +// Enabled 0 is compiled out +// Enabled 1 is always enabled on all vehicles +// Enabled 2 is enabled with dummy methods for tracker and blimp + +#ifndef AP_FENCE_ENABLED +#define AP_FENCE_ENABLED 2 +#endif diff --git a/libraries/AC_Fence/AC_PolyFence_loader.cpp b/libraries/AC_Fence/AC_PolyFence_loader.cpp index e2aac27ef47..7b354270696 100644 --- a/libraries/AC_Fence/AC_PolyFence_loader.cpp +++ b/libraries/AC_Fence/AC_PolyFence_loader.cpp @@ -1,7 +1,18 @@ #include "AC_PolyFence_loader.h" +#if AP_FENCE_ENABLED + +#include + +#ifndef AC_FENCE_DUMMY_METHODS_ENABLED +#define AC_FENCE_DUMMY_METHODS_ENABLED (!(APM_BUILD_TYPE(APM_BUILD_Rover) | APM_BUILD_COPTER_OR_HELI | APM_BUILD_TYPE(APM_BUILD_ArduPlane) | APM_BUILD_TYPE(APM_BUILD_ArduSub) | (AP_FENCE_ENABLED == 1))) +#endif + +#if !AC_FENCE_DUMMY_METHODS_ENABLED + #include #include +#include #include @@ -286,7 +297,7 @@ bool AC_PolyFence_loader::format() bool AC_PolyFence_loader::convert_to_new_storage() { // sanity check total - _total = constrain_int16(_total, 0, max_items()); + _total.set(constrain_int16(_total, 0, max_items())); // FIXME: ensure the fence was closed and don't load it if it was not if (_total < 5) { // fence was invalid. Just format it and move on @@ -1170,6 +1181,9 @@ bool AC_PolyFence_loader::write_fence(const AC_PolyFenceItem *new_items, uint16_ gcs().send_text(MAV_SEVERITY_DEBUG, "Fence Indexed OK"); #endif + // start logger logging new fence + AP::logger().Write_Fence(); + void_index(); // this may be completely bogus total. If we are storing an @@ -1662,3 +1676,33 @@ void AC_PolyFence_loader::update() return; } } + +#else // build type is not appropriate; provide a dummy implementation: + +void AC_PolyFence_loader::init() {}; + +bool AC_PolyFence_loader::get_item(const uint16_t seq, AC_PolyFenceItem &item) { return false; } + +Vector2f* AC_PolyFence_loader::get_exclusion_polygon(uint16_t index, uint16_t &num_points) const { return nullptr; } +Vector2f* AC_PolyFence_loader::get_inclusion_polygon(uint16_t index, uint16_t &num_points) const { return nullptr; } + +bool AC_PolyFence_loader::get_exclusion_circle(uint8_t index, Vector2f ¢er_pos_cm, float &radius) const { return false; } +bool AC_PolyFence_loader::get_inclusion_circle(uint8_t index, Vector2f ¢er_pos_cm, float &radius) const { return false; } + +void AC_PolyFence_loader::handle_msg(GCS_MAVLINK &link, const mavlink_message_t& msg) {}; + +bool AC_PolyFence_loader::breached() const { return false; } +bool AC_PolyFence_loader::breached(const Location& loc) const { return false; } + +uint16_t AC_PolyFence_loader::max_items() const { return 0; } + +bool AC_PolyFence_loader::write_fence(const AC_PolyFenceItem *new_items, uint16_t count) { return false; } + +void AC_PolyFence_loader::update() {}; + +#if AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT +bool AC_PolyFence_loader::get_return_point(Vector2l &ret) { return false; } +#endif + +#endif // #if AC_FENCE_DUMMY_METHODS_ENABLED +#endif // AP_FENCE_ENABLED diff --git a/libraries/AC_Fence/AC_PolyFence_loader.h b/libraries/AC_Fence/AC_PolyFence_loader.h index 4427cc646aa..a8d172e569d 100644 --- a/libraries/AC_Fence/AC_PolyFence_loader.h +++ b/libraries/AC_Fence/AC_PolyFence_loader.h @@ -1,11 +1,7 @@ #pragma once -#include -#include +#include "AC_Fence_config.h" #include -#include - -#define AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT 1 // CIRCLE_INCLUSION_INT stores the radius an a 32-bit integer in // metres. This was a bug, and CIRCLE_INCLUSION was created to store @@ -37,6 +33,14 @@ class AC_PolyFenceItem { float radius; }; +#if AP_FENCE_ENABLED + +#include +#include +#include + +#define AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT 1 + class AC_PolyFence_loader { @@ -434,3 +438,5 @@ class AC_PolyFence_loader uint16_t fence_storage_space_required(const AC_PolyFenceItem *new_items, uint16_t count); }; + +#endif // AP_FENCE_ENABLED diff --git a/libraries/AC_Fence/LogStructure.h b/libraries/AC_Fence/LogStructure.h new file mode 100644 index 00000000000..071fc23f4bc --- /dev/null +++ b/libraries/AC_Fence/LogStructure.h @@ -0,0 +1,38 @@ +#pragma once + +#include +#include "AC_Fence_config.h" + +#define LOG_IDS_FROM_FENCE \ + LOG_FENCE_MSG + +// @LoggerMessage: FNCE +// @Description: currently loaded Geo Fence points +// @Field: TimeUS: Time since system startup +// @Field: Tot: total number of stored items +// @Field: Seq: index in current sequence +// @Field: Type: point type +// @Field: Lat: point latitude +// @Field: Lng: point longitude +// @Field: Count: vertex cound in polygon if applicable +// @Field: Radius: radius of circle if applicable + +struct PACKED log_Fence { + LOG_PACKET_HEADER; + uint64_t time_us; + uint8_t total; + uint8_t sequence; + uint8_t type; + int32_t latitude; + int32_t longitude; + uint8_t vertex_count; + float radius; +}; + +#if !AP_FENCE_ENABLED +#define LOG_STRUCTURE_FROM_FENCE +#else +#define LOG_STRUCTURE_FROM_FENCE \ + { LOG_FENCE_MSG, sizeof(log_Fence), \ + "FNCE", "QBBBLLBf", "TimeUS,Tot,Seq,Type,Lat,Lng,Count,Radius", "s---DU-m", "F---GG--" }, +#endif diff --git a/libraries/AC_InputManager/AC_InputManager_Heli.cpp b/libraries/AC_InputManager/AC_InputManager_Heli.cpp index fc46fbe0a31..f78bc1bdd07 100644 --- a/libraries/AC_InputManager/AC_InputManager_Heli.cpp +++ b/libraries/AC_InputManager/AC_InputManager_Heli.cpp @@ -67,20 +67,20 @@ float AC_InputManager_Heli::get_pilot_desired_collective(int16_t control_in) // calculate stabilize collective value which scales pilot input to reduced collective range // code implements a 3-segment curve with knee points at 40% and 60% throttle input if (control_in < 400){ // control_in ranges from 0 to 1000 - slope_low = _heli_stab_col_min / 100.0f; - slope_high = _heli_stab_col_low / 100.0f; + slope_low = _heli_stab_col_min * 0.01f; + slope_high = _heli_stab_col_low * 0.01f; slope_range = 0.4f; - slope_run = control_in / 1000.0f; + slope_run = control_in * 0.001f; } else if(control_in <600){ // control_in ranges from 0 to 1000 - slope_low = _heli_stab_col_low / 100.0f; - slope_high = _heli_stab_col_high / 100.0f; + slope_low = _heli_stab_col_low * 0.01f; + slope_high = _heli_stab_col_high * 0.01f; slope_range = 0.2f; - slope_run = (control_in - 400) / 1000.0f; // control_in ranges from 0 to 1000 + slope_run = (control_in - 400) * 0.001f; // control_in ranges from 0 to 1000 } else { - slope_low = _heli_stab_col_high / 100.0f; - slope_high = _heli_stab_col_max / 100.0f; + slope_low = _heli_stab_col_high * 0.01f; + slope_high = _heli_stab_col_max * 0.01f; slope_range = 0.4f; - slope_run = (control_in - 600) / 1000.0f; // control_in ranges from 0 to 1000 + slope_run = (control_in - 600) * 0.001f; // control_in ranges from 0 to 1000 } scalar = (slope_high - slope_low)/slope_range; @@ -91,11 +91,11 @@ float AC_InputManager_Heli::get_pilot_desired_collective(int16_t control_in) // calculate expo-scaled acro collective // range check expo if (_acro_col_expo > 1.0f) { - _acro_col_expo = 1.0f; + _acro_col_expo.set(1.0f); } if (_acro_col_expo <= 0.0f) { - acro_col_out = control_in / 1000.0f; // control_in ranges from 0 to 1000 + acro_col_out = control_in * 0.001f; // control_in ranges from 0 to 1000 } else { // expo variables float col_in, col_in3, col_out; diff --git a/libraries/AC_PID/AC_HELI_PID.cpp b/libraries/AC_PID/AC_HELI_PID.cpp index 9236c01568f..f514a955d21 100644 --- a/libraries/AC_PID/AC_HELI_PID.cpp +++ b/libraries/AC_PID/AC_HELI_PID.cpp @@ -73,8 +73,8 @@ const AP_Param::GroupInfo AC_HELI_PID::var_info[] = { }; /// Constructor for PID -AC_HELI_PID::AC_HELI_PID(float initial_p, float initial_i, float initial_d, float initial_ff, float initial_imax, float initial_filt_T_hz, float initial_filt_E_hz, float initial_filt_D_hz, float dt) : - AC_PID(initial_p, initial_i, initial_d, initial_ff, initial_imax, initial_filt_T_hz, initial_filt_E_hz, initial_filt_D_hz, dt) +AC_HELI_PID::AC_HELI_PID(float initial_p, float initial_i, float initial_d, float initial_ff, float initial_imax, float initial_filt_T_hz, float initial_filt_E_hz, float initial_filt_D_hz) : + AC_PID(initial_p, initial_i, initial_d, initial_ff, initial_imax, initial_filt_T_hz, initial_filt_E_hz, initial_filt_D_hz) { _last_requested_rate = 0; } @@ -84,7 +84,7 @@ AC_HELI_PID::AC_HELI_PID(float initial_p, float initial_i, float initial_d, floa void AC_HELI_PID::update_leaky_i(float leak_rate) { - if (!is_zero(_ki) && !is_zero(_dt)){ + if (!is_zero(_ki)){ // integrator does not leak down below Leak Min if (_integrator > _leak_min){ diff --git a/libraries/AC_PID/AC_HELI_PID.h b/libraries/AC_PID/AC_HELI_PID.h index 8a6b7274a41..0ed7737f181 100644 --- a/libraries/AC_PID/AC_HELI_PID.h +++ b/libraries/AC_PID/AC_HELI_PID.h @@ -17,7 +17,7 @@ class AC_HELI_PID : public AC_PID { public: /// Constructor for PID - AC_HELI_PID(float initial_p, float initial_i, float initial_d, float initial_ff, float initial_imax, float initial_filt_T_hz, float initial_filt_E_hz, float initial_filt_D_hz, float dt); + AC_HELI_PID(float initial_p, float initial_i, float initial_d, float initial_ff, float initial_imax, float initial_filt_T_hz, float initial_filt_E_hz, float initial_filt_D_hz); CLASS_NO_COPY(AC_HELI_PID); diff --git a/libraries/AC_PID/AC_P.h b/libraries/AC_PID/AC_P.h index 3ec46816615..706cf55e9a1 100644 --- a/libraries/AC_PID/AC_P.h +++ b/libraries/AC_PID/AC_P.h @@ -23,7 +23,7 @@ class AC_P { AC_P(const float &initial_p = 0.0f) { AP_Param::setup_object_defaults(this, var_info); - _kp = initial_p; + _kp.set_and_default(initial_p); } CLASS_NO_COPY(AC_P); @@ -54,7 +54,7 @@ class AC_P { //@{ /// Overload the function call operator to permit relatively easy initialisation - void operator() (const float p) { _kp = p; } + void operator() (const float p) { _kp.set(p); } // accessors AP_Float &kP() { return _kp; } diff --git a/libraries/AC_PID/AC_PI.cpp b/libraries/AC_PID/AC_PI.cpp index d3624eafb4f..c28a998780d 100644 --- a/libraries/AC_PID/AC_PI.cpp +++ b/libraries/AC_PID/AC_PI.cpp @@ -30,9 +30,9 @@ AC_PI::AC_PI(float initial_p, float initial_i, float initial_imax) // load parameter values from eeprom AP_Param::setup_object_defaults(this, var_info); - kP.set(initial_p); - kI.set(initial_i); - imax.set(initial_imax); + kP.set_and_default(initial_p); + kI.set_and_default(initial_i); + imax.set_and_default(initial_imax); } float AC_PI::update(float measurement, float target, float dt) diff --git a/libraries/AC_PID/AC_PID.cpp b/libraries/AC_PID/AC_PID.cpp index f3f38d0957b..bd628108c57 100644 --- a/libraries/AC_PID/AC_PID.cpp +++ b/libraries/AC_PID/AC_PID.cpp @@ -69,22 +69,21 @@ const AP_Param::GroupInfo AC_PID::var_info[] = { // Constructor AC_PID::AC_PID(float initial_p, float initial_i, float initial_d, float initial_ff, float initial_imax, float initial_filt_T_hz, float initial_filt_E_hz, float initial_filt_D_hz, - float dt, float initial_srmax, float initial_srtau): - _dt(dt) + float initial_srmax, float initial_srtau) { // load parameter values from eeprom AP_Param::setup_object_defaults(this, var_info); - _kp = initial_p; - _ki = initial_i; - _kd = initial_d; - _kff = initial_ff; - _kimax = fabsf(initial_imax); - filt_T_hz(initial_filt_T_hz); - filt_E_hz(initial_filt_E_hz); - filt_D_hz(initial_filt_D_hz); - _slew_rate_max.set(initial_srmax); - _slew_rate_tau.set(initial_srtau); + _kp.set_and_default(initial_p); + _ki.set_and_default(initial_i); + _kd.set_and_default(initial_d); + _kff.set_and_default(initial_ff); + _kimax.set_and_default(initial_imax); + _filt_T_hz.set_and_default(initial_filt_T_hz); + _filt_E_hz.set_and_default(initial_filt_E_hz); + _filt_D_hz.set_and_default(initial_filt_D_hz); + _slew_rate_max.set_and_default(initial_srmax); + _slew_rate_tau.set_and_default(initial_srtau); // reset input filter to first value received _flags._reset_filter = true; @@ -96,13 +95,6 @@ AC_PID::AC_PID(float initial_p, float initial_i, float initial_d, float initial_ _slew_limit_scale = 1; } -// set_dt - set time step in seconds -void AC_PID::set_dt(float dt) -{ - // set dt and calculate the input filter alpha - _dt = dt; -} - // filt_T_hz - set target filter hz void AC_PID::filt_T_hz(float hz) { @@ -131,7 +123,7 @@ void AC_PID::slew_limit(float smax) // target and error are filtered // the derivative is then calculated and filtered // the integral is then updated based on the setting of the limit flag -float AC_PID::update_all(float target, float measurement, bool limit) +float AC_PID::update_all(float target, float measurement, float dt, bool limit) { // don't process inf or NaN if (!isfinite(target) || !isfinite(measurement)) { @@ -146,24 +138,24 @@ float AC_PID::update_all(float target, float measurement, bool limit) _derivative = 0.0f; } else { float error_last = _error; - _target += get_filt_T_alpha() * (target - _target); - _error += get_filt_E_alpha() * ((_target - measurement) - _error); + _target += get_filt_T_alpha(dt) * (target - _target); + _error += get_filt_E_alpha(dt) * ((_target - measurement) - _error); // calculate and filter derivative - if (_dt > 0.0f) { - float derivative = (_error - error_last) / _dt; - _derivative += get_filt_D_alpha() * (derivative - _derivative); + if (is_positive(dt)) { + float derivative = (_error - error_last) / dt; + _derivative += get_filt_D_alpha(dt) * (derivative - _derivative); } } // update I term - update_i(limit); + update_i(dt, limit); float P_out = (_error * _kp); float D_out = (_derivative * _kd); // calculate slew limit modifier for P+D - _pid_info.Dmod = _slew_limiter.modifier((_pid_info.P + _pid_info.D) * _slew_limit_scale, _dt); + _pid_info.Dmod = _slew_limiter.modifier((_pid_info.P + _pid_info.D) * _slew_limit_scale, dt); _pid_info.slew_rate = _slew_limiter.get_slew_rate(); P_out *= _pid_info.Dmod; @@ -184,7 +176,7 @@ float AC_PID::update_all(float target, float measurement, bool limit) // the integral is then updated based on the setting of the limit flag // Target and Measured must be set manually for logging purposes. // todo: remove function when it is no longer used. -float AC_PID::update_error(float error, bool limit) +float AC_PID::update_error(float error, float dt, bool limit) { // don't process inf or NaN if (!isfinite(error)) { @@ -200,23 +192,23 @@ float AC_PID::update_error(float error, bool limit) _derivative = 0.0f; } else { float error_last = _error; - _error += get_filt_E_alpha() * (error - _error); + _error += get_filt_E_alpha(dt) * (error - _error); // calculate and filter derivative - if (_dt > 0.0f) { - float derivative = (_error - error_last) / _dt; - _derivative += get_filt_D_alpha() * (derivative - _derivative); + if (is_positive(dt)) { + float derivative = (_error - error_last) / dt; + _derivative += get_filt_D_alpha(dt) * (derivative - _derivative); } } // update I term - update_i(limit); + update_i(dt, limit); float P_out = (_error * _kp); float D_out = (_derivative * _kd); // calculate slew limit modifier for P+D - _pid_info.Dmod = _slew_limiter.modifier((_pid_info.P + _pid_info.D) * _slew_limit_scale, _dt); + _pid_info.Dmod = _slew_limiter.modifier((_pid_info.P + _pid_info.D) * _slew_limit_scale, dt); _pid_info.slew_rate = _slew_limiter.get_slew_rate(); P_out *= _pid_info.Dmod; @@ -233,12 +225,12 @@ float AC_PID::update_error(float error, bool limit) // update_i - update the integral // If the limit flag is set the integral is only allowed to shrink -void AC_PID::update_i(bool limit) +void AC_PID::update_i(float dt, bool limit) { - if (!is_zero(_ki) && is_positive(_dt)) { + if (!is_zero(_ki) && is_positive(dt)) { // Ensure that integrator can only be reduced if the output is saturated if (!limit || ((is_positive(_integrator) && is_negative(_error)) || (is_negative(_integrator) && is_positive(_error)))) { - _integrator += ((float)_error * _ki) * _dt; + _integrator += ((float)_error * _ki) * dt; _integrator = constrain_float(_integrator, -_kimax, _kimax); } } else { @@ -272,6 +264,7 @@ float AC_PID::get_ff() void AC_PID::reset_I() { _integrator = 0.0; + _pid_info.I = 0.0; } void AC_PID::load_gains() @@ -281,7 +274,7 @@ void AC_PID::load_gains() _kd.load(); _kff.load(); _kimax.load(); - _kimax = fabsf(_kimax); + _kimax.set(fabsf(_kimax)); _filt_T_hz.load(); _filt_E_hz.load(); _filt_D_hz.load(); @@ -301,41 +294,34 @@ void AC_PID::save_gains() } /// Overload the function call operator to permit easy initialisation -void AC_PID::operator()(float p_val, float i_val, float d_val, float ff_val, float imax_val, float input_filt_T_hz, float input_filt_E_hz, float input_filt_D_hz, float dt) +void AC_PID::operator()(float p_val, float i_val, float d_val, float ff_val, float imax_val, float input_filt_T_hz, float input_filt_E_hz, float input_filt_D_hz) { - _kp = p_val; - _ki = i_val; - _kd = d_val; - _kff = ff_val; - _kimax = fabsf(imax_val); - _filt_T_hz = input_filt_T_hz; - _filt_E_hz = input_filt_E_hz; - _filt_D_hz = input_filt_D_hz; - _dt = dt; + _kp.set(p_val); + _ki.set(i_val); + _kd.set(d_val); + _kff.set(ff_val); + _kimax.set(fabsf(imax_val)); + _filt_T_hz.set(input_filt_T_hz); + _filt_E_hz.set(input_filt_E_hz); + _filt_D_hz.set(input_filt_D_hz); } // get_filt_T_alpha - get the target filter alpha -float AC_PID::get_filt_T_alpha() const +float AC_PID::get_filt_T_alpha(float dt) const { - return get_filt_alpha(_filt_T_hz); + return calc_lowpass_alpha_dt(dt, _filt_T_hz); } // get_filt_E_alpha - get the error filter alpha -float AC_PID::get_filt_E_alpha() const +float AC_PID::get_filt_E_alpha(float dt) const { - return get_filt_alpha(_filt_E_hz); + return calc_lowpass_alpha_dt(dt, _filt_E_hz); } // get_filt_D_alpha - get the derivative filter alpha -float AC_PID::get_filt_D_alpha() const +float AC_PID::get_filt_D_alpha(float dt) const { - return get_filt_alpha(_filt_D_hz); -} - -// get_filt_alpha - calculate a filter alpha -float AC_PID::get_filt_alpha(float filt_hz) const -{ - return calc_lowpass_alpha_dt(_dt, filt_hz); + return calc_lowpass_alpha_dt(dt, _filt_D_hz); } void AC_PID::set_integrator(float target, float measurement, float integrator) @@ -355,9 +341,11 @@ void AC_PID::set_integrator(float integrator) _pid_info.I = _integrator; } -void AC_PID::relax_integrator(float integrator, float time_constant) +void AC_PID::relax_integrator(float integrator, float dt, float time_constant) { integrator = constrain_float(integrator, -_kimax, _kimax); - _integrator = _integrator + (integrator - _integrator) * (_dt / (_dt + time_constant)); + if (is_positive(dt)) { + _integrator = _integrator + (integrator - _integrator) * (dt / (dt + time_constant)); + } _pid_info.I = _integrator; } diff --git a/libraries/AC_PID/AC_PID.h b/libraries/AC_PID/AC_PID.h index c3a968dda90..8e4f735c4c1 100644 --- a/libraries/AC_PID/AC_PID.h +++ b/libraries/AC_PID/AC_PID.h @@ -7,7 +7,6 @@ #include #include #include -#include #include #define AC_PID_TFILT_HZ_DEFAULT 0.0f // default input filter frequency @@ -15,6 +14,8 @@ #define AC_PID_DFILT_HZ_DEFAULT 20.0f // default input filter frequency #define AC_PID_RESET_TC 0.16f // Time constant for integrator reset decay to zero +#include "AP_PIDInfo.h" + /// @class AC_PID /// @brief Copter PID control class class AC_PID { @@ -22,18 +23,15 @@ class AC_PID { // Constructor for PID AC_PID(float initial_p, float initial_i, float initial_d, float initial_ff, float initial_imax, float initial_filt_T_hz, float initial_filt_E_hz, float initial_filt_D_hz, - float dt, float initial_srmax=0, float initial_srtau=1.0); + float initial_srmax=0, float initial_srtau=1.0); CLASS_NO_COPY(AC_PID); - // set_dt - set time step in seconds - void set_dt(float dt); - // update_all - set target and measured inputs to PID controller and calculate outputs // target and error are filtered // the derivative is then calculated and filtered // the integral is then updated based on the setting of the limit flag - float update_all(float target, float measurement, bool limit = false); + float update_all(float target, float measurement, float dt, bool limit = false); // update_error - set error input to PID controller and calculate outputs // target is set to zero and error is set and filtered @@ -41,11 +39,11 @@ class AC_PID { // the integral is then updated based on the setting of the limit flag // Target and Measured must be set manually for logging purposes. // todo: remove function when it is no longer used. - float update_error(float error, bool limit = false); + float update_error(float error, float dt, bool limit = false); // update_i - update the integral // if the limit flag is set the integral is only allowed to shrink - void update_i(bool limit); + void update_i(float dt, bool limit); // get_pid - get results from pid controller float get_pid() const; @@ -70,7 +68,7 @@ class AC_PID { void save_gains(); /// operator function call for easy initialisation - void operator()(float p_val, float i_val, float d_val, float ff_val, float imax_val, float input_filt_T_hz, float input_filt_E_hz, float input_filt_D_hz, float dt); + void operator()(float p_val, float i_val, float d_val, float ff_val, float imax_val, float input_filt_T_hz, float input_filt_E_hz, float input_filt_D_hz); // get accessors AP_Float &kP() { return _kp; } @@ -84,10 +82,9 @@ class AC_PID { AP_Float &slew_limit() { return _slew_rate_max; } float imax() const { return _kimax.get(); } - float get_filt_alpha(float filt_hz) const; - float get_filt_T_alpha() const; - float get_filt_E_alpha() const; - float get_filt_D_alpha() const; + float get_filt_T_alpha(float dt) const; + float get_filt_E_alpha(float dt) const; + float get_filt_D_alpha(float dt) const; // set accessors void kP(const float v) { _kp.set(v); } @@ -108,7 +105,7 @@ class AC_PID { void set_integrator(float target, float measurement, float i); void set_integrator(float error, float i); void set_integrator(float i); - void relax_integrator(float integrator, float time_constant); + void relax_integrator(float integrator, float dt, float time_constant); // set slew limiter scale factor void set_slew_limit_scale(int8_t scale) { _slew_limit_scale = scale; } @@ -116,7 +113,7 @@ class AC_PID { // return current slew rate of slew limiter. Will return 0 if SMAX is zero float get_slew_rate(void) const { return _slew_limiter.get_slew_rate(); } - const AP_Logger::PID_Info& get_pid_info(void) const { return _pid_info; } + const AP_PIDInfo& get_pid_info(void) const { return _pid_info; } // parameter var table static const struct AP_Param::GroupInfo var_info[]; @@ -148,12 +145,11 @@ class AC_PID { } _flags; // internal variables - float _dt; // timestep in seconds float _integrator; // integrator value float _target; // target value to enable filtering float _error; // error value to enable filtering float _derivative; // derivative value to enable filtering int8_t _slew_limit_scale; - AP_Logger::PID_Info _pid_info; + AP_PIDInfo _pid_info; }; diff --git a/libraries/AC_PID/AC_PID_2D.cpp b/libraries/AC_PID/AC_PID_2D.cpp index 4e5a91d91c8..99d188bec79 100644 --- a/libraries/AC_PID/AC_PID_2D.cpp +++ b/libraries/AC_PID/AC_PID_2D.cpp @@ -50,19 +50,18 @@ const AP_Param::GroupInfo AC_PID_2D::var_info[] = { }; // Constructor -AC_PID_2D::AC_PID_2D(float initial_kP, float initial_kI, float initial_kD, float initial_kFF, float initial_imax, float initial_filt_E_hz, float initial_filt_D_hz, float dt) : - _dt(dt) +AC_PID_2D::AC_PID_2D(float initial_kP, float initial_kI, float initial_kD, float initial_kFF, float initial_imax, float initial_filt_E_hz, float initial_filt_D_hz) { // load parameter values from eeprom AP_Param::setup_object_defaults(this, var_info); - _kp = initial_kP; - _ki = initial_kI; - _kd = initial_kD; - _kff = initial_kFF; - _kimax = fabsf(initial_imax); - filt_E_hz(initial_filt_E_hz); - filt_D_hz(initial_filt_D_hz); + _kp.set_and_default(initial_kP); + _ki.set_and_default(initial_kI); + _kd.set_and_default(initial_kD); + _kff.set_and_default(initial_kFF); + _kimax.set_and_default(initial_imax); + _filt_E_hz.set_and_default(initial_filt_E_hz); + _filt_D_hz.set_and_default(initial_filt_D_hz); // reset input filter to first value received _reset_filter = true; @@ -72,7 +71,7 @@ AC_PID_2D::AC_PID_2D(float initial_kP, float initial_kI, float initial_kD, float // target and error are filtered // the derivative is then calculated and filtered // the integral is then updated if it does not increase in the direction of the limit vector -Vector2f AC_PID_2D::update_all(const Vector2f &target, const Vector2f &measurement, const Vector2f &limit) +Vector2f AC_PID_2D::update_all(const Vector2f &target, const Vector2f &measurement, float dt, const Vector2f &limit) { // don't process inf or NaN if (target.is_nan() || target.is_inf() || @@ -89,17 +88,17 @@ Vector2f AC_PID_2D::update_all(const Vector2f &target, const Vector2f &measureme _derivative.zero(); } else { Vector2f error_last{_error}; - _error += ((_target - measurement) - _error) * get_filt_E_alpha(); + _error += ((_target - measurement) - _error) * get_filt_E_alpha(dt); // calculate and filter derivative - if (_dt > 0.0f) { - const Vector2f derivative{(_error - error_last) / _dt}; - _derivative += (derivative - _derivative) * get_filt_D_alpha(); + if (is_positive(dt)) { + const Vector2f derivative{(_error - error_last) / dt}; + _derivative += (derivative - _derivative) * get_filt_D_alpha(dt); } } // update I term - update_i(limit); + update_i(dt, limit); _pid_info_x.target = _target.x; _pid_info_x.actual = measurement.x; @@ -120,19 +119,19 @@ Vector2f AC_PID_2D::update_all(const Vector2f &target, const Vector2f &measureme return _error * _kp + _integrator + _derivative * _kd + _target * _kff; } -Vector2f AC_PID_2D::update_all(const Vector3f &target, const Vector3f &measurement, const Vector3f &limit) +Vector2f AC_PID_2D::update_all(const Vector3f &target, const Vector3f &measurement, float dt, const Vector3f &limit) { - return update_all(Vector2f{target.x, target.y}, Vector2f{measurement.x, measurement.y}, Vector2f{limit.x, limit.y}); + return update_all(Vector2f{target.x, target.y}, Vector2f{measurement.x, measurement.y}, dt, Vector2f{limit.x, limit.y}); } // update_i - update the integral // If the limit is set the integral is only allowed to reduce in the direction of the limit -void AC_PID_2D::update_i(const Vector2f &limit) +void AC_PID_2D::update_i(float dt, const Vector2f &limit) { _pid_info_x.limit = false; _pid_info_y.limit = false; - Vector2f delta_integrator = (_error * _ki) * _dt; + Vector2f delta_integrator = (_error * _ki) * dt; float integrator_length = _integrator.length(); _integrator += delta_integrator; // do not let integrator increase in length if delta_integrator is in the direction of limit @@ -166,6 +165,13 @@ Vector2f AC_PID_2D::get_ff() return _target * _kff; } +void AC_PID_2D::reset_I() +{ + _integrator.zero(); + _pid_info_x.I = 0.0; + _pid_info_y.I = 0.0; +} + // save_gains - save gains to eeprom void AC_PID_2D::save_gains() { @@ -179,15 +185,15 @@ void AC_PID_2D::save_gains() } // get the target filter alpha -float AC_PID_2D::get_filt_E_alpha() const +float AC_PID_2D::get_filt_E_alpha(float dt) const { - return calc_lowpass_alpha_dt(_dt, _filt_E_hz); + return calc_lowpass_alpha_dt(dt, _filt_E_hz); } // get the derivative filter alpha -float AC_PID_2D::get_filt_D_alpha() const +float AC_PID_2D::get_filt_D_alpha(float dt) const { - return calc_lowpass_alpha_dt(_dt, _filt_D_hz); + return calc_lowpass_alpha_dt(dt, _filt_D_hz); } void AC_PID_2D::set_integrator(const Vector2f& target, const Vector2f& measurement, const Vector2f& i) diff --git a/libraries/AC_PID/AC_PID_2D.h b/libraries/AC_PID/AC_PID_2D.h index 7f17d534fe9..549152a9905 100644 --- a/libraries/AC_PID/AC_PID_2D.h +++ b/libraries/AC_PID/AC_PID_2D.h @@ -7,7 +7,7 @@ #include #include #include -#include +#include /// @class AC_PID_2D /// @brief Copter PID control class @@ -15,23 +15,20 @@ class AC_PID_2D { public: // Constructor for PID - AC_PID_2D(float initial_kP, float initial_kI, float initial_kD, float initial_kFF, float initial_imax, float initial_filt_hz, float initial_filt_d_hz, float dt); + AC_PID_2D(float initial_kP, float initial_kI, float initial_kD, float initial_kFF, float initial_imax, float initial_filt_hz, float initial_filt_d_hz); CLASS_NO_COPY(AC_PID_2D); - // set time step in seconds - void set_dt(float dt) { _dt = dt; } - // update_all - set target and measured inputs to PID controller and calculate outputs // target and error are filtered // the derivative is then calculated and filtered // the integral is then updated if it does not increase in the direction of the limit vector - Vector2f update_all(const Vector2f &target, const Vector2f &measurement, const Vector2f &limit); - Vector2f update_all(const Vector3f &target, const Vector3f &measurement, const Vector3f &limit); + Vector2f update_all(const Vector2f &target, const Vector2f &measurement, float dt, const Vector2f &limit); + Vector2f update_all(const Vector3f &target, const Vector3f &measurement, float dt, const Vector3f &limit); // update the integral // if the limit flag is set the integral is only allowed to shrink - void update_i(const Vector2f &limit); + void update_i(float dt, const Vector2f &limit); // get results from pid controller Vector2f get_p() const; @@ -41,7 +38,7 @@ class AC_PID_2D { const Vector2f& get_error() const { return _error; } // reset the integrator - void reset_I() { _integrator.zero(); }; + void reset_I(); // reset_filter - input and D term filter will be reset to the next value provided to set_input() void reset_filter() { _reset_filter = true; } @@ -57,8 +54,8 @@ class AC_PID_2D { AP_Float &filt_E_hz() { return _filt_E_hz; } AP_Float &filt_D_hz() { return _filt_D_hz; } float imax() const { return _kimax.get(); } - float get_filt_E_alpha() const; - float get_filt_D_alpha() const; + float get_filt_E_alpha(float dt) const; + float get_filt_D_alpha(float dt) const; // set accessors void kP(float v) { _kp.set(v); } @@ -75,8 +72,8 @@ class AC_PID_2D { void set_integrator(const Vector3f& i) { set_integrator(Vector2f{i.x, i.y}); } void set_integrator(const Vector2f& i); - const AP_Logger::PID_Info& get_pid_info_x(void) const { return _pid_info_x; } - const AP_Logger::PID_Info& get_pid_info_y(void) const { return _pid_info_y; } + const AP_PIDInfo& get_pid_info_x(void) const { return _pid_info_x; } + const AP_PIDInfo& get_pid_info_y(void) const { return _pid_info_y; } // parameter var table static const struct AP_Param::GroupInfo var_info[]; @@ -93,13 +90,12 @@ class AC_PID_2D { AP_Float _filt_D_hz; // PID derivative filter frequency in Hz // internal variables - float _dt; // timestep in seconds Vector2f _target; // target value to enable filtering Vector2f _error; // error value to enable filtering Vector2f _derivative; // last derivative from low-pass filter Vector2f _integrator; // integrator value bool _reset_filter; // true when input filter should be reset during next call to update_all - AP_Logger::PID_Info _pid_info_x; - AP_Logger::PID_Info _pid_info_y; + AP_PIDInfo _pid_info_x; + AP_PIDInfo _pid_info_y; }; diff --git a/libraries/AC_PID/AC_PID_Basic.cpp b/libraries/AC_PID/AC_PID_Basic.cpp index 8fade0595c4..ce192cf1403 100644 --- a/libraries/AC_PID/AC_PID_Basic.cpp +++ b/libraries/AC_PID/AC_PID_Basic.cpp @@ -52,34 +52,33 @@ const AP_Param::GroupInfo AC_PID_Basic::var_info[] = { }; // Constructor -AC_PID_Basic::AC_PID_Basic(float initial_p, float initial_i, float initial_d, float initial_ff, float initial_imax, float initial_filt_E_hz, float initial_filt_D_hz, float dt) : - _dt(dt) +AC_PID_Basic::AC_PID_Basic(float initial_p, float initial_i, float initial_d, float initial_ff, float initial_imax, float initial_filt_E_hz, float initial_filt_D_hz) { // load parameter values from eeprom AP_Param::setup_object_defaults(this, var_info); - _kp = initial_p; - _ki = initial_i; - _kd = initial_d; - _kff = initial_ff; - _kimax = fabsf(initial_imax); - filt_E_hz(initial_filt_E_hz); - filt_D_hz(initial_filt_D_hz); + _kp.set_and_default(initial_p); + _ki.set_and_default(initial_i); + _kd.set_and_default(initial_d); + _kff.set_and_default(initial_ff); + _kimax.set_and_default(initial_imax); + _filt_E_hz.set_and_default(initial_filt_E_hz); + _filt_D_hz.set_and_default(initial_filt_D_hz); // reset input filter to first value received _reset_filter = true; } -float AC_PID_Basic::update_all(float target, float measurement, bool limit) +float AC_PID_Basic::update_all(float target, float measurement, float dt, bool limit) { - return update_all(target, measurement, (limit && is_negative(_integrator)), (limit && is_positive(_integrator))); + return update_all(target, measurement, dt, (limit && is_negative(_integrator)), (limit && is_positive(_integrator))); } // update_all - set target and measured inputs to PID controller and calculate outputs // target and error are filtered // the derivative is then calculated and filtered // the integral is then updated based on the setting of the limit flag -float AC_PID_Basic::update_all(float target, float measurement, bool limit_neg, bool limit_pos) +float AC_PID_Basic::update_all(float target, float measurement, float dt, bool limit_neg, bool limit_pos) { // don't process inf or NaN if (!isfinite(target) || isnan(target) || @@ -97,17 +96,17 @@ float AC_PID_Basic::update_all(float target, float measurement, bool limit_neg, _derivative = 0.0f; } else { float error_last = _error; - _error += get_filt_E_alpha() * ((_target - measurement) - _error); + _error += get_filt_E_alpha(dt) * ((_target - measurement) - _error); // calculate and filter derivative - if (is_positive(_dt)) { - float derivative = (_error - error_last) / _dt; - _derivative += get_filt_D_alpha() * (derivative - _derivative); + if (is_positive(dt)) { + float derivative = (_error - error_last) / dt; + _derivative += get_filt_D_alpha(dt) * (derivative - _derivative); } } // update I term - update_i(limit_neg, limit_pos); + update_i(dt, limit_neg, limit_pos); const float P_out = _error * _kp; const float D_out = _derivative * _kd; @@ -126,12 +125,12 @@ float AC_PID_Basic::update_all(float target, float measurement, bool limit_neg, // update_i - update the integral // if limit_neg is true, the integral can only increase // if limit_pos is true, the integral can only decrease -void AC_PID_Basic::update_i(bool limit_neg, bool limit_pos) +void AC_PID_Basic::update_i(float dt, bool limit_neg, bool limit_pos) { if (!is_zero(_ki)) { // Ensure that integrator can only be reduced if the output is saturated if (!((limit_neg && is_negative(_error)) || (limit_pos && is_positive(_error)))) { - _integrator += ((float)_error * _ki) * _dt; + _integrator += ((float)_error * _ki) * dt; _integrator = constrain_float(_integrator, -_kimax, _kimax); } } else { @@ -139,6 +138,12 @@ void AC_PID_Basic::update_i(bool limit_neg, bool limit_pos) } } +void AC_PID_Basic::reset_I() +{ + _integrator = 0.0; + _pid_info.I = 0.0; +} + // save_gains - save gains to eeprom void AC_PID_Basic::save_gains() { @@ -152,15 +157,15 @@ void AC_PID_Basic::save_gains() } // get_filt_T_alpha - get the target filter alpha -float AC_PID_Basic::get_filt_E_alpha() const +float AC_PID_Basic::get_filt_E_alpha(float dt) const { - return calc_lowpass_alpha_dt(_dt, _filt_E_hz); + return calc_lowpass_alpha_dt(dt, _filt_E_hz); } // get_filt_D_alpha - get the derivative filter alpha -float AC_PID_Basic::get_filt_D_alpha() const +float AC_PID_Basic::get_filt_D_alpha(float dt) const { - return calc_lowpass_alpha_dt(_dt, _filt_D_hz); + return calc_lowpass_alpha_dt(dt, _filt_D_hz); } void AC_PID_Basic::set_integrator(float target, float measurement, float i) @@ -176,4 +181,5 @@ void AC_PID_Basic::set_integrator(float error, float i) void AC_PID_Basic::set_integrator(float i) { _integrator = constrain_float(i, -_kimax, _kimax); + _pid_info.I = _integrator; } diff --git a/libraries/AC_PID/AC_PID_Basic.h b/libraries/AC_PID/AC_PID_Basic.h index 65143a26a23..25d24ba4852 100644 --- a/libraries/AC_PID/AC_PID_Basic.h +++ b/libraries/AC_PID/AC_PID_Basic.h @@ -5,7 +5,7 @@ #include #include -#include +#include "AP_PIDInfo.h" /// @class AC_PID_Basic /// @brief Copter PID control class @@ -13,21 +13,18 @@ class AC_PID_Basic { public: // Constructor for PID - AC_PID_Basic(float initial_p, float initial_i, float initial_d, float initial_ff, float initial_imax, float initial_filt_E_hz, float initial_filt_D_hz, float dt); - - // set time step in seconds - void set_dt(float dt) { _dt = dt; } + AC_PID_Basic(float initial_p, float initial_i, float initial_d, float initial_ff, float initial_imax, float initial_filt_E_hz, float initial_filt_D_hz); // set target and measured inputs to PID controller and calculate outputs // target and error are filtered // the derivative is then calculated and filtered // the integral is then updated based on the setting of the limit flag - float update_all(float target, float measurement, bool limit = false) WARN_IF_UNUSED; - float update_all(float target, float measurement, bool limit_neg, bool limit_pos) WARN_IF_UNUSED; + float update_all(float target, float measurement, float dt, bool limit = false) WARN_IF_UNUSED; + float update_all(float target, float measurement, float dt, bool limit_neg, bool limit_pos) WARN_IF_UNUSED; // update the integral // if the limit flags are set the integral is only allowed to shrink - void update_i(bool limit_neg, bool limit_pos); + void update_i(float dt, bool limit_neg, bool limit_pos); // get results from pid controller float get_p() const WARN_IF_UNUSED { return _error * _kp; } @@ -37,7 +34,7 @@ class AC_PID_Basic { float get_error() const WARN_IF_UNUSED { return _error; } // reset the integrator - void reset_I() { _integrator = 0.0f; } + void reset_I(); // input and D term filter will be reset to the next value provided to set_input() void reset_filter() { _reset_filter = true; } @@ -53,8 +50,8 @@ class AC_PID_Basic { AP_Float &filt_E_hz() WARN_IF_UNUSED { return _filt_E_hz; } AP_Float &filt_D_hz() WARN_IF_UNUSED { return _filt_D_hz; } float imax() const WARN_IF_UNUSED { return _kimax.get(); } - float get_filt_E_alpha() const WARN_IF_UNUSED; - float get_filt_D_alpha() const WARN_IF_UNUSED; + float get_filt_E_alpha(float dt) const WARN_IF_UNUSED; + float get_filt_D_alpha(float dt) const WARN_IF_UNUSED; // set accessors void kP(float v) { _kp.set(v); } @@ -70,7 +67,7 @@ class AC_PID_Basic { void set_integrator(float error, float i); void set_integrator(float i); - const AP_Logger::PID_Info& get_pid_info(void) const WARN_IF_UNUSED { return _pid_info; } + const AP_PIDInfo& get_pid_info(void) const WARN_IF_UNUSED { return _pid_info; } // parameter var table static const struct AP_Param::GroupInfo var_info[]; @@ -87,12 +84,11 @@ class AC_PID_Basic { AP_Float _filt_D_hz; // PID derivative filter frequency in Hz // internal variables - float _dt; // timestep in seconds float _target; // target value to enable filtering float _error; // error value to enable filtering float _derivative; // last derivative for low-pass filter float _integrator; // integrator value bool _reset_filter; // true when input filter should be reset during next call to set_input - AP_Logger::PID_Info _pid_info; + AP_PIDInfo _pid_info; }; diff --git a/libraries/AC_PID/AC_PI_2D.cpp b/libraries/AC_PID/AC_PI_2D.cpp index 45c38145d0d..c4f98657236 100644 --- a/libraries/AC_PID/AC_PI_2D.cpp +++ b/libraries/AC_PID/AC_PI_2D.cpp @@ -36,9 +36,10 @@ AC_PI_2D::AC_PI_2D(float initial_p, float initial_i, float initial_imax, float i // load parameter values from eeprom AP_Param::setup_object_defaults(this, var_info); - _kp = initial_p; - _ki = initial_i; - _imax = fabsf(initial_imax); + _kp.set_and_default(initial_p); + _ki.set_and_default(initial_i); + _imax.set_and_default(initial_imax); + _filt_hz.set_and_default(initial_filt_hz); filt_hz(initial_filt_hz); // reset input filter to first value received @@ -59,7 +60,7 @@ void AC_PI_2D::filt_hz(float hz) _filt_hz.set(fabsf(hz)); // sanity check _filt_hz - _filt_hz = MAX(_filt_hz, AC_PI_2D_FILT_HZ_MIN); + _filt_hz.set(MAX(_filt_hz, AC_PI_2D_FILT_HZ_MIN)); // calculate the input filter alpha calc_filt_alpha(); @@ -134,7 +135,7 @@ void AC_PI_2D::load_gains() _kp.load(); _ki.load(); _imax.load(); - _imax = fabsf(_imax); + _imax.set(fabsf(_imax)); _filt_hz.load(); // calculate the input filter alpha @@ -153,10 +154,10 @@ void AC_PI_2D::save_gains() /// Overload the function call operator to permit easy initialisation void AC_PI_2D::operator() (float p, float i, float imaxval, float input_filt_hz, float dt) { - _kp = p; - _ki = i; - _imax = fabsf(imaxval); - _filt_hz = input_filt_hz; + _kp.set(p); + _ki.set(i); + _imax.set(fabsf(imaxval)); + _filt_hz.set(input_filt_hz); _dt = dt; // calculate the input filter alpha calc_filt_alpha(); diff --git a/libraries/AC_PID/AC_P_1D.cpp b/libraries/AC_PID/AC_P_1D.cpp index 164c0a47722..69670839d56 100644 --- a/libraries/AC_PID/AC_P_1D.cpp +++ b/libraries/AC_PID/AC_P_1D.cpp @@ -13,13 +13,12 @@ const AP_Param::GroupInfo AC_P_1D::var_info[] = { }; // Constructor -AC_P_1D::AC_P_1D(float initial_p, float dt) : - _dt(dt) +AC_P_1D::AC_P_1D(float initial_p) { // load parameter values from eeprom AP_Param::setup_object_defaults(this, var_info); - _kp = initial_p; + _kp.set_and_default(initial_p); } // update_all - set target and measured inputs to P controller and calculate outputs @@ -38,7 +37,7 @@ float AC_P_1D::update_all(float &target, float measurement) } // MIN(_Dxy_max, _D2xy_max / _kxy_P) limits the max accel to the point where max jerk is exceeded - return sqrt_controller(_error, _kp, _D1_max, _dt); + return sqrt_controller(_error, _kp, _D1_max, 0.0); } // set_limits - sets the maximum error to limit output and first and second derivative of output diff --git a/libraries/AC_PID/AC_P_1D.h b/libraries/AC_PID/AC_P_1D.h index 5285ebce79f..1cdb56e799a 100644 --- a/libraries/AC_PID/AC_P_1D.h +++ b/libraries/AC_PID/AC_P_1D.h @@ -12,13 +12,10 @@ class AC_P_1D { public: // constructor - AC_P_1D(float initial_p, float dt); + AC_P_1D(float initial_p); CLASS_NO_COPY(AC_P_1D); - // set time step in seconds - void set_dt(float dt) { _dt = dt; } - // update_all - set target and measured inputs to P controller and calculate outputs // target and measurement are filtered float update_all(float &target, float measurement) WARN_IF_UNUSED; @@ -56,7 +53,6 @@ class AC_P_1D { AP_Float _kp; // internal variables - float _dt; // time step in seconds float _error; // time step in seconds float _error_min; // error limit in negative direction float _error_max; // error limit in positive direction diff --git a/libraries/AC_PID/AC_P_2D.cpp b/libraries/AC_PID/AC_P_2D.cpp index f7478100fc0..4cc2df4f63e 100644 --- a/libraries/AC_PID/AC_P_2D.cpp +++ b/libraries/AC_PID/AC_P_2D.cpp @@ -13,13 +13,12 @@ const AP_Param::GroupInfo AC_P_2D::var_info[] = { }; // Constructor -AC_P_2D::AC_P_2D(float initial_p, float dt) : - _dt(dt) +AC_P_2D::AC_P_2D(float initial_p) { // load parameter values from eeprom AP_Param::setup_object_defaults(this, var_info); - _kp = initial_p; + _kp.set_and_default(initial_p); } // update_all - set target and measured inputs to P controller and calculate outputs @@ -36,7 +35,7 @@ Vector2f AC_P_2D::update_all(postype_t &target_x, postype_t &target_y, const Vec } // MIN(_Dmax, _D2max / _kp) limits the max accel to the point where max jerk is exceeded - return sqrt_controller(_error, _kp, _D1_max, _dt); + return sqrt_controller(_error, _kp, _D1_max, 0.0); } // set_limits - sets the maximum error to limit output and first and second derivative of output diff --git a/libraries/AC_PID/AC_P_2D.h b/libraries/AC_PID/AC_P_2D.h index 40cf3793317..d0dd7921724 100644 --- a/libraries/AC_PID/AC_P_2D.h +++ b/libraries/AC_PID/AC_P_2D.h @@ -12,13 +12,10 @@ class AC_P_2D { public: // constructor - AC_P_2D(float initial_p, float dt); + AC_P_2D(float initial_p); CLASS_NO_COPY(AC_P_2D); - // set time step in seconds - void set_dt(float dt) { _dt = dt; } - // set target and measured inputs to P controller and calculate outputs Vector2f update_all(postype_t &target_x, postype_t &target_y, const Vector2f &measurement) WARN_IF_UNUSED; @@ -58,7 +55,6 @@ class AC_P_2D { AP_Float _kp; // internal variables - float _dt; // time step in seconds Vector2f _error; // time step in seconds float _error_max; // error limit in positive direction float _D1_max; // maximum first derivative of output diff --git a/libraries/AC_PID/AP_PIDInfo.h b/libraries/AC_PID/AP_PIDInfo.h new file mode 100644 index 00000000000..98a05f879d0 --- /dev/null +++ b/libraries/AC_PID/AP_PIDInfo.h @@ -0,0 +1,20 @@ +#pragma once + +// This structure provides information on the internal member data of +// a PID. It provides an abstract way to pass PID information around, +// useful for logging and sending mavlink messages. + +// It is also used to pass PID information into controllers... + +struct AP_PIDInfo { + float target; + float actual; + float error; + float P; + float I; + float D; + float FF; + float Dmod; + float slew_rate; + bool limit; +}; diff --git a/libraries/AC_PID/examples/AC_PID_test/AC_PID_test.cpp b/libraries/AC_PID/examples/AC_PID_test/AC_PID_test.cpp index 0574fdcad97..bc641acd80c 100644 --- a/libraries/AC_PID/examples/AC_PID_test/AC_PID_test.cpp +++ b/libraries/AC_PID/examples/AC_PID_test/AC_PID_test.cpp @@ -70,8 +70,8 @@ void setup() void loop() { // setup (unfortunately must be done here as we cannot create a global AC_PID object) - AC_PID pid(TEST_P, TEST_I, TEST_D, 0.0f, TEST_IMAX * 100.0f, 0.0f, 0.0f, TEST_FILTER, TEST_DT); - AC_HELI_PID heli_pid(TEST_P, TEST_I, TEST_D, TEST_INITIAL_FF, TEST_IMAX * 100, 0.0f, 0.0f, TEST_FILTER, TEST_DT); + AC_PID pid(TEST_P, TEST_I, TEST_D, 0.0f, TEST_IMAX * 100.0f, 0.0f, 0.0f, TEST_FILTER); + AC_HELI_PID heli_pid(TEST_P, TEST_I, TEST_D, TEST_INITIAL_FF, TEST_IMAX * 100, 0.0f, 0.0f, TEST_FILTER); // display PID gains hal.console->printf("P %f I %f D %f imax %f\n", (double)pid.kP(), (double)pid.kI(), (double)pid.kD(), (double)pid.imax()); @@ -91,7 +91,7 @@ void loop() rc().read_input(); // poll the radio for new values const uint16_t radio_in = c->get_radio_in(); const int16_t error = radio_in - radio_trim; - pid.update_error(error); + pid.update_error(error, TEST_DT); const float control_P = pid.get_p(); const float control_I = pid.get_i(); const float control_D = pid.get_d(); diff --git a/libraries/AC_PrecLand/AC_PrecLand.cpp b/libraries/AC_PrecLand/AC_PrecLand.cpp index 945b95bbab1..8dcb7ba836f 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand.cpp @@ -7,10 +7,17 @@ #include "AC_PrecLand_IRLock.h" #include "AC_PrecLand_SITL_Gazebo.h" #include "AC_PrecLand_SITL.h" +#include #include extern const AP_HAL::HAL& hal; +#if APM_BUILD_TYPE(APM_BUILD_Rover) + # define AC_PRECLAND_ORIENT_DEFAULT Rotation::ROTATION_NONE +#else + # define AC_PRECLAND_ORIENT_DEFAULT Rotation::ROTATION_PITCH_270 +#endif + static const uint32_t EKF_INIT_TIME_MS = 2000; // EKF initialisation requires this many milliseconds of good sensor data static const uint32_t EKF_INIT_SENSOR_MIN_UPDATE_MS = 500; // Sensor must update within this many ms during EKF init, else init will fail static const uint32_t LANDING_TARGET_TIMEOUT_MS = 2000; // Sensor must update within this many ms, else prec landing will be switched off @@ -165,10 +172,18 @@ const AP_Param::GroupInfo AC_PrecLand::var_info[] = { // @Param: OPTIONS // @DisplayName: Precision Landing Extra Options // @Description: Precision Landing Extra Options - // @Bitmask: 0: Moving Landing Target + // @Bitmask: 0: Moving Landing Target, 1: Allow Precision Landing after manual reposition // @User: Advanced AP_GROUPINFO("OPTIONS", 17, AC_PrecLand, _options, 0), + // @Param: ORIENT + // @DisplayName: Camera Orientation + // @Description: Orientation of camera/sensor on body + // @Values: 0:Forward, 4:Back, 25:Down + // @User: Advanced + // @RebootRequired: True + AP_GROUPINFO_FRAME("ORIENT", 18, AC_PrecLand, _orient, AC_PRECLAND_ORIENT_DEFAULT, AP_PARAM_FRAME_ROVER), + AP_GROUPEND }; @@ -202,7 +217,7 @@ void AC_PrecLand::init(uint16_t update_rate_hz) // create inertial history buffer // constrain lag parameter to be within bounds - _lag = constrain_float(_lag, 0.02f, 0.25f); + _lag.set(constrain_float(_lag, 0.02f, 0.25f)); // calculate inertial buffer size from lag and minimum of main loop rate and update_rate_hz argument const uint16_t inertial_buffer_size = MAX((uint16_t)roundf(_lag * MIN(update_rate_hz, AP::scheduler().get_loop_rate_hz())), 1); @@ -241,6 +256,9 @@ void AC_PrecLand::init(uint16_t update_rate_hz) if (_backend != nullptr) { _backend->init(); } + + _approach_vector_body.x = 1; + _approach_vector_body.rotate(_orient); } // update - give chance to driver to get updates from sensor @@ -590,6 +608,21 @@ bool AC_PrecLand::retrieve_los_meas(Vector3f& target_vec_unit_body) // Apply sensor yaw alignment rotation target_vec_unit_body.rotate_xy(radians(_yaw_align*0.01f)); } + + + // rotate vector based on sensor oriention to get correct body frame vector + if (_orient != ROTATION_PITCH_270) { + // by default, the vector is constructed downwards in body frame + // hence, we do not do any rotation if the orientation is downwards + // if it is some other orientation, we first bring the vector to forward + // and then we rotate it to desired orientation + // because the rotations are measured with respect to a vector pointing towards front in body frame + // for eg, if orientation is back, i.e., ROTATION_YAW_180, + // the vector is first brought to front and then rotation by YAW 180 to take it to the back of vehicle + target_vec_unit_body.rotate(ROTATION_PITCH_90); // bring vector to front + target_vec_unit_body.rotate(_orient); // rotate it to desired orientation + } + return true; } else { return false; @@ -602,11 +635,13 @@ bool AC_PrecLand::construct_pos_meas_using_rangefinder(float rangefinder_alt_m, if (retrieve_los_meas(target_vec_unit_body)) { const struct inertial_data_frame_s *inertial_data_delayed = (*_inertial_history)[0]; + const bool target_vec_valid = target_vec_unit_body.projected(_approach_vector_body).dot(_approach_vector_body) > 0.0f; const Vector3f target_vec_unit_ned = inertial_data_delayed->Tbn * target_vec_unit_body; - const bool target_vec_valid = target_vec_unit_ned.z > 0.0f; + const Vector3f approach_vector_NED = inertial_data_delayed->Tbn * _approach_vector_body; const bool alt_valid = (rangefinder_alt_valid && rangefinder_alt_m > 0.0f) || (_backend->distance_to_target() > 0.0f); if (target_vec_valid && alt_valid) { - float dist, alt; + // distance to target and distance to target along approach vector + float dist_to_target, dist_to_target_along_av; // figure out ned camera orientation w.r.t its offset Vector3f cam_pos_ned; if (!_cam_offset.get().is_zero()) { @@ -616,13 +651,12 @@ bool AC_PrecLand::construct_pos_meas_using_rangefinder(float rangefinder_alt_m, } if (_backend->distance_to_target() > 0.0f) { // sensor has provided distance to landing target - dist = _backend->distance_to_target(); - alt = dist * target_vec_unit_ned.z; + dist_to_target = _backend->distance_to_target(); } else { // sensor only knows the horizontal location of the landing target // rely on rangefinder for the vertical target - alt = MAX(rangefinder_alt_m - cam_pos_ned.z, 0.0f); - dist = alt / target_vec_unit_ned.z; + dist_to_target_along_av = MAX(rangefinder_alt_m - cam_pos_ned.projected(approach_vector_NED).length(), 0.0f); + dist_to_target = dist_to_target_along_av / target_vec_unit_ned.projected(approach_vector_NED).length(); } // Compute camera position relative to IMU @@ -630,7 +664,7 @@ bool AC_PrecLand::construct_pos_meas_using_rangefinder(float rangefinder_alt_m, const Vector3f cam_pos_ned_rel_imu = cam_pos_ned - accel_pos_ned; // Compute target position relative to IMU - _target_pos_rel_meas_NED = Vector3f{target_vec_unit_ned.x*dist, target_vec_unit_ned.y*dist, alt} + cam_pos_ned_rel_imu; + _target_pos_rel_meas_NED = (target_vec_unit_ned * dist_to_target) + cam_pos_ned_rel_imu; // store the current relative down position so that if we need to retry landing, we know at this height landing target can be found const AP_AHRS &_ahrs = AP::ahrs(); diff --git a/libraries/AC_PrecLand/AC_PrecLand.h b/libraries/AC_PrecLand/AC_PrecLand.h index 26db39b21c3..b91105f9d0b 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.h +++ b/libraries/AC_PrecLand/AC_PrecLand.h @@ -54,6 +54,9 @@ class AC_PrecLand // vehicle has to be closer than this many cm's to the target before descending towards target float get_max_xy_error_before_descending_cm() const { return _xy_max_dist_desc * 100.0f; } + // returns orientation of sensor + Rotation get_orient() const { return _orient; } + // returns ekf outlier count uint32_t ekf_outlier_count() const { return _outlier_reject_count; } @@ -107,6 +110,8 @@ class AC_PrecLand float get_min_retry_time_sec() const { return _retry_timeout_sec; } AC_PrecLand_StateMachine::RetryAction get_retry_behaviour() const { return static_cast(_retry_behave.get()); } + bool allow_precland_after_reposition() const { return _options & PLND_OPTION_PRECLAND_AFTER_REPOSITION; } + // parameter var table static const struct AP_Param::GroupInfo var_info[]; @@ -128,6 +133,7 @@ class AC_PrecLand enum PLndOptions { PLND_OPTION_DISABLED = 0, PLND_OPTION_MOVING_TARGET = (1 << 0), + PLND_OPTION_PRECLAND_AFTER_REPOSITION = (1 << 1), }; // check the status of the target @@ -174,6 +180,7 @@ class AC_PrecLand AP_Float _sensor_min_alt; // PrecLand minimum height required for detecting target AP_Float _sensor_max_alt; // PrecLand maximum height the sensor can detect target AP_Int16 _options; // Bitmask for extra options + AP_Enum _orient; // Orientation of camera/sensor uint32_t _last_update_ms; // system time in millisecond when update was last called bool _target_acquired; // true if target has been seen recently after estimator is initialized @@ -186,6 +193,7 @@ class AC_PrecLand uint32_t _outlier_reject_count; // mini-EKF's outlier counter (3 consecutive outliers lead to EKF accepting updates) Vector3f _target_pos_rel_meas_NED; // target's relative position as 3D vector + Vector3f _approach_vector_body; // unit vector in landing approach direction (in body frame) Vector3f _last_target_pos_rel_origin_NED; // stores the last known location of the target horizontally, and the height of the vehicle where it detected this target in meters NED Vector3f _last_vehicle_pos_NED; // stores the position of the vehicle when landing target was last detected in m and NED diff --git a/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp b/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp index f8125dee157..e65ff1d6861 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp @@ -1,4 +1,5 @@ #include +#include #include "AC_PrecLand_Companion.h" // perform any required initialisation of backend @@ -46,9 +47,28 @@ void AC_PrecLand_Companion::handle_msg(const mavlink_landing_target_t &packet, u { _distance_to_target = packet.distance; - // compute unit vector towards target - _los_meas_body = Vector3f(-tanf(packet.angle_y), tanf(packet.angle_x), 1.0f); - _los_meas_body /= _los_meas_body.length(); + if (packet.position_valid == 1) { + if (packet.frame == MAV_FRAME_BODY_FRD) { + if (_distance_to_target > 0) { + _los_meas_body = Vector3f(packet.x, packet.y, packet.z); + _los_meas_body /= _distance_to_target; + } else { + // distance to target must be positive + return; + } + } else { + //we do not support this frame + if (!_wrong_frame_msg_sent) { + _wrong_frame_msg_sent = true; + gcs().send_text(MAV_SEVERITY_INFO,"Plnd: Frame not supported "); + } + return; + } + } else { + // compute unit vector towards target + _los_meas_body = Vector3f(-tanf(packet.angle_y), tanf(packet.angle_x), 1.0f); + _los_meas_body /= _los_meas_body.length(); + } _los_meas_time_ms = timestamp_ms; _have_los_meas = true; diff --git a/libraries/AC_PrecLand/AC_PrecLand_Companion.h b/libraries/AC_PrecLand/AC_PrecLand_Companion.h index b773f4d2b82..67af707a9bd 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_Companion.h +++ b/libraries/AC_PrecLand/AC_PrecLand_Companion.h @@ -44,4 +44,5 @@ class AC_PrecLand_Companion : public AC_PrecLand_Backend Vector3f _los_meas_body; // unit vector in body frame pointing towards target bool _have_los_meas; // true if there is a valid measurement from the camera uint32_t _los_meas_time_ms; // system time in milliseconds when los was measured + bool _wrong_frame_msg_sent; }; diff --git a/libraries/AC_PrecLand/AC_PrecLand_SITL.cpp b/libraries/AC_PrecLand/AC_PrecLand_SITL.cpp index 0ed7ca7e8fb..b71a4d1c26b 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_SITL.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand_SITL.cpp @@ -19,7 +19,17 @@ void AC_PrecLand_SITL::update() const Vector3d position = _sitl->precland_sim.get_target_position(); const Matrix3d body_to_ned = AP::ahrs().get_rotation_body_to_ned().todouble(); _los_meas_body = body_to_ned.mul_transpose(-position).tofloat(); + _distance_to_target = _sitl->precland_sim.option_enabled(SITL::SIM_Precland::Option::ENABLE_TARGET_DISTANCE) ? _los_meas_body.length() : 0.0f; _los_meas_body /= _los_meas_body.length(); + + if (_frontend._orient != Rotation::ROTATION_PITCH_270) { + // rotate body frame vector based on orientation + // this is done to have homogeneity among backends + // frontend rotates it back to get correct body frame vector + _los_meas_body.rotate_inverse(_frontend._orient); + _los_meas_body.rotate_inverse(ROTATION_PITCH_90); + } + _have_los_meas = true; _los_meas_time_ms = _sitl->precland_sim.last_update_ms(); } else { @@ -33,7 +43,6 @@ bool AC_PrecLand_SITL::have_los_meas() { return AP_HAL::millis() - _los_meas_time_ms < 1000; } - // provides a unit vector towards the target in body frame // returns same as have_los_meas() bool AC_PrecLand_SITL::get_los_body(Vector3f& ret) { diff --git a/libraries/AC_PrecLand/AC_PrecLand_SITL.h b/libraries/AC_PrecLand/AC_PrecLand_SITL.h index 82e2efc97b4..ee6fd526edf 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_SITL.h +++ b/libraries/AC_PrecLand/AC_PrecLand_SITL.h @@ -32,11 +32,15 @@ class AC_PrecLand_SITL : public AC_PrecLand_Backend // return true if there is a valid los measurement available bool have_los_meas() override; + // returns distance to target in meters (0 means distance is not known) + float distance_to_target() override { return _distance_to_target; } + private: SITL::SIM *_sitl; // sitl instance pointer Vector3f _los_meas_body; // unit vector in body frame pointing towards target uint32_t _los_meas_time_ms; // system time in milliseconds when los was measured bool _have_los_meas; // true if there is a valid measurement from the camera + float _distance_to_target; // distance to target in meters }; #endif diff --git a/libraries/AC_PrecLand/AC_PrecLand_StateMachine.h b/libraries/AC_PrecLand/AC_PrecLand_StateMachine.h index 7993202dbe4..b72b0e8d72e 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_StateMachine.h +++ b/libraries/AC_PrecLand/AC_PrecLand_StateMachine.h @@ -1,7 +1,6 @@ #pragma once #include -#include // This class constantly monitors what the status of the landing target is // If it is not in sight, depending on user parameters, it decides what measures can be taken to bring the target back in sight @@ -17,8 +16,7 @@ class AC_PrecLand_StateMachine { }; // Do not allow copies - AC_PrecLand_StateMachine(const AC_PrecLand_StateMachine &other) = delete; - AC_PrecLand_StateMachine &operator=(const AC_PrecLand_StateMachine&) = delete; + CLASS_NO_COPY(AC_PrecLand_StateMachine); // Initialize the state machine. This is called everytime vehicle switches mode void init(); diff --git a/libraries/AC_WPNav/AC_Circle.cpp b/libraries/AC_WPNav/AC_Circle.cpp index 000d8dae586..59877b4e61e 100644 --- a/libraries/AC_WPNav/AC_Circle.cpp +++ b/libraries/AC_WPNav/AC_Circle.cpp @@ -3,6 +3,8 @@ #include #include "AC_Circle.h" +#include + extern const AP_HAL::HAL& hal; const AP_Param::GroupInfo AC_Circle::var_info[] = { @@ -133,12 +135,12 @@ void AC_Circle::set_center(const Location& center) void AC_Circle::set_rate(float deg_per_sec) { if (!is_equal(deg_per_sec, _rate.get())) { - _rate = deg_per_sec; + _rate.set(deg_per_sec); } } /// set_circle_rate - set circle rate in degrees per second -void AC_Circle::set_radius(float radius_cm) +void AC_Circle::set_radius_cm(float radius_cm) { _radius = constrain_float(radius_cm, 0, AC_CIRCLE_RADIUS_MAX); } diff --git a/libraries/AC_WPNav/AC_Circle.h b/libraries/AC_WPNav/AC_Circle.h index 59d4b0acd71..f0ce1237535 100644 --- a/libraries/AC_WPNav/AC_Circle.h +++ b/libraries/AC_WPNav/AC_Circle.h @@ -44,8 +44,8 @@ class AC_Circle /// get_radius - returns radius of circle in cm float get_radius() const { return is_positive(_radius)?_radius:_radius_parm; } - /// set_radius - sets circle radius in cm - void set_radius(float radius_cm); + /// set_radius_cm - sets circle radius in cm + void set_radius_cm(float radius_cm); /// get_rate - returns target rate in deg/sec held in RATE parameter float get_rate() const { return _rate; } diff --git a/libraries/AC_WPNav/AC_Loiter.cpp b/libraries/AC_WPNav/AC_Loiter.cpp index 30f506529ad..c1f9dbd8928 100644 --- a/libraries/AC_WPNav/AC_Loiter.cpp +++ b/libraries/AC_WPNav/AC_Loiter.cpp @@ -19,7 +19,7 @@ const AP_Param::GroupInfo AC_Loiter::var_info[] = { // @Param: ANG_MAX // @DisplayName: Loiter pilot angle max // @Description{Copter, Sub}: Loiter maximum pilot requested lean angle. Set to zero for 2/3 of PSC_ANGLE_MAX/ANGLE_MAX. The maximum vehicle lean angle is still limited by PSC_ANGLE_MAX/ANGLE_MAX - // @Description{Plane}: Loiter maximum pilot requested lean angle. Set to zero for 2/3 of Q_P_ANGLE_MAX/Q_ANGLE_MAX. The maximum vehicle lean angle is still limited by Q_P_ANGLE_MAX/Q_ANGLE_MAX + // @Description: Loiter maximum pilot requested lean angle. Set to zero for 2/3 of Q_P_ANGLE_MAX/Q_ANGLE_MAX. The maximum vehicle lean angle is still limited by Q_P_ANGLE_MAX/Q_ANGLE_MAX // @Units: deg // @Range: 0 45 // @Increment: 1 @@ -118,8 +118,8 @@ void AC_Loiter::init_target() _pos_control.set_correction_speed_accel_xy(LOITER_VEL_CORRECTION_MAX, _accel_cmss); _pos_control.set_pos_error_max_xy_cm(LOITER_POS_CORRECTION_MAX); - // initialise position controller - _pos_control.init_xy_controller(); + // initialise position controller and move target accelerations smoothly towards zero + _pos_control.relax_velocity_controller_xy(); // initialise predicted acceleration and angles from the position controller _predicted_accel.x = _pos_control.get_accel_target_cmss().x; @@ -132,24 +132,17 @@ void AC_Loiter::init_target() /// reduce response for landing void AC_Loiter::soften_for_landing() { - const Vector3f& curr_pos = _inav.get_position_neu_cm(); - - // set target position to current position - _pos_control.set_pos_target_xy_cm(curr_pos.x, curr_pos.y); - - // also prevent I term build up in xy velocity controller. Note - // that this flag is reset on each loop, in update_xy_controller() - _pos_control.set_externally_limited_xy(); + _pos_control.soften_for_landing_xy(); } /// set pilot desired acceleration in centi-degrees // dt should be the time (in seconds) since the last call to this function void AC_Loiter::set_pilot_desired_acceleration(float euler_roll_angle_cd, float euler_pitch_angle_cd) { - const float dt = _pos_control.get_dt(); + const float dt = _attitude_control.get_dt(); // Convert from centidegrees on public interface to radians - const float euler_roll_angle = radians(euler_roll_angle_cd*0.01f); - const float euler_pitch_angle = radians(euler_pitch_angle_cd*0.01f); + const float euler_roll_angle = radians(euler_roll_angle_cd * 0.01f); + const float euler_pitch_angle = radians(euler_pitch_angle_cd * 0.01f); // convert our desired attitude to an acceleration vector assuming we are not accelerating vertically const Vector3f desired_euler {euler_roll_angle, euler_pitch_angle, _ahrs.yaw}; @@ -195,33 +188,35 @@ float AC_Loiter::get_angle_max_cd() const /// run the loiter controller void AC_Loiter::update(bool avoidance_on) { - calc_desired_velocity(_pos_control.get_dt(), avoidance_on); + calc_desired_velocity(avoidance_on); _pos_control.update_xy_controller(); } // sanity check parameters void AC_Loiter::sanity_check_params() { - _speed_cms = MAX(_speed_cms, LOITER_SPEED_MIN); - _accel_cmss = MIN(_accel_cmss, GRAVITY_MSS * 100.0f * tanf(ToRad(_attitude_control.lean_angle_max_cd() * 0.01f))); + _speed_cms.set(MAX(_speed_cms, LOITER_SPEED_MIN)); + _accel_cmss.set(MIN(_accel_cmss, GRAVITY_MSS * 100.0f * tanf(ToRad(_attitude_control.lean_angle_max_cd() * 0.01f)))); } /// calc_desired_velocity - updates desired velocity (i.e. feed forward) with pilot requested acceleration and fake wind resistance /// updated velocity sent directly to position controller -void AC_Loiter::calc_desired_velocity(float nav_dt, bool avoidance_on) +void AC_Loiter::calc_desired_velocity(bool avoidance_on) { float ekfGndSpdLimit, ahrsControlScaleXY; AP::ahrs().getControlLimits(ekfGndSpdLimit, ahrsControlScaleXY); + const float dt = _pos_control.get_dt(); + // calculate a loiter speed limit which is the minimum of the value set by the LOITER_SPEED // parameter and the value set by the EKF to observe optical flow limits - float gnd_speed_limit_cms = MIN(_speed_cms, ekfGndSpdLimit*100.0f); + float gnd_speed_limit_cms = MIN(_speed_cms, ekfGndSpdLimit * 100.0f); gnd_speed_limit_cms = MAX(gnd_speed_limit_cms, LOITER_SPEED_MIN); - float pilot_acceleration_max = GRAVITY_MSS*100.0f * tanf(radians(get_angle_max_cd()*0.01f)); + float pilot_acceleration_max = angle_to_accel(get_angle_max_cd() * 0.01) * 100; - // range check nav_dt - if (nav_dt < 0) { + // range check dt + if (is_negative(dt)) { return; } @@ -230,39 +225,34 @@ void AC_Loiter::calc_desired_velocity(float nav_dt, bool avoidance_on) Vector2f desired_vel{desired_vel_3d.x,desired_vel_3d.y}; // update the desired velocity using our predicted acceleration - desired_vel.x += _predicted_accel.x * nav_dt; - desired_vel.y += _predicted_accel.y * nav_dt; + desired_vel.x += _predicted_accel.x * dt; + desired_vel.y += _predicted_accel.y * dt; Vector2f loiter_accel_brake; float desired_speed = desired_vel.length(); if (!is_zero(desired_speed)) { - Vector2f desired_vel_norm = desired_vel/desired_speed; - - // TODO: consider using a velocity squared relationship like - // pilot_acceleration_max*(desired_speed/gnd_speed_limit_cms)^2; - // the drag characteristic of a multirotor should be examined to generate a curve - // we could add a expo function here to fine tune it + Vector2f desired_vel_norm = desired_vel / desired_speed; // calculate a drag acceleration based on the desired speed. - float drag_decel = pilot_acceleration_max*desired_speed/gnd_speed_limit_cms; + float drag_decel = pilot_acceleration_max * desired_speed / gnd_speed_limit_cms; // calculate a braking acceleration if sticks are at zero float loiter_brake_accel = 0.0f; if (_desired_accel.is_zero()) { - if ((AP_HAL::millis()-_brake_timer) > _brake_delay * 1000.0f) { + if ((AP_HAL::millis() - _brake_timer) > _brake_delay * 1000.0f) { float brake_gain = _pos_control.get_vel_xy_pid().kP() * 0.5f; - loiter_brake_accel = constrain_float(sqrt_controller(desired_speed, brake_gain, _brake_jerk_max_cmsss, nav_dt), 0.0f, _brake_accel_cmss); + loiter_brake_accel = constrain_float(sqrt_controller(desired_speed, brake_gain, _brake_jerk_max_cmsss, dt), 0.0f, _brake_accel_cmss); } } else { loiter_brake_accel = 0.0f; _brake_timer = AP_HAL::millis(); } - _brake_accel += constrain_float(loiter_brake_accel-_brake_accel, -_brake_jerk_max_cmsss*nav_dt, _brake_jerk_max_cmsss*nav_dt); - loiter_accel_brake = desired_vel_norm*_brake_accel; + _brake_accel += constrain_float(loiter_brake_accel - _brake_accel, -_brake_jerk_max_cmsss * dt, _brake_jerk_max_cmsss * dt); + loiter_accel_brake = desired_vel_norm * _brake_accel; // update the desired velocity using the drag and braking accelerations - desired_speed = MAX(desired_speed-(drag_decel+_brake_accel)*nav_dt,0.0f); - desired_vel = desired_vel_norm*desired_speed; + desired_speed = MAX(desired_speed - (drag_decel + _brake_accel) * dt, 0.0f); + desired_vel = desired_vel_norm * desired_speed; } // add braking to the desired acceleration @@ -282,7 +272,7 @@ void AC_Loiter::calc_desired_velocity(float nav_dt, bool avoidance_on) AC_Avoid *_avoid = AP::ac_avoid(); if (_avoid != nullptr) { Vector3f avoidance_vel_3d{desired_vel.x, desired_vel.y, 0.0f}; - _avoid->adjust_velocity(avoidance_vel_3d, _pos_control.get_pos_xy_p().kP(), _accel_cmss, _pos_control.get_pos_z_p().kP(), _pos_control.get_max_accel_z_cmss(), nav_dt); + _avoid->adjust_velocity(avoidance_vel_3d, _pos_control.get_pos_xy_p().kP(), _accel_cmss, _pos_control.get_pos_z_p().kP(), _pos_control.get_max_accel_z_cmss(), dt); desired_vel = Vector2f{avoidance_vel_3d.x, avoidance_vel_3d.y}; } } @@ -292,7 +282,7 @@ void AC_Loiter::calc_desired_velocity(float nav_dt, bool avoidance_on) Vector2p target_pos = _pos_control.get_pos_target_cm().xy(); // update the target position using our predicted velocity - target_pos += (desired_vel * nav_dt).topostype(); + target_pos += (desired_vel * dt).topostype(); // send adjusted feed forward acceleration and velocity back to the Position Controller _pos_control.set_pos_vel_accel_xy(target_pos, desired_vel, _desired_accel); diff --git a/libraries/AC_WPNav/AC_Loiter.h b/libraries/AC_WPNav/AC_Loiter.h index 9418c3a136b..02e8085877b 100644 --- a/libraries/AC_WPNav/AC_Loiter.h +++ b/libraries/AC_WPNav/AC_Loiter.h @@ -64,7 +64,7 @@ class AC_Loiter /// updates desired velocity (i.e. feed forward) with pilot requested acceleration and fake wind resistance /// updated velocity sent directly to position controller - void calc_desired_velocity(float nav_dt, bool avoidance_on = true); + void calc_desired_velocity(bool avoidance_on = true); // references and pointers to external libraries const AP_InertialNav& _inav; diff --git a/libraries/AC_WPNav/AC_WPNav.cpp b/libraries/AC_WPNav/AC_WPNav.cpp index 2fb251efd27..6dac14085e2 100644 --- a/libraries/AC_WPNav/AC_WPNav.cpp +++ b/libraries/AC_WPNav/AC_WPNav.cpp @@ -4,7 +4,6 @@ extern const AP_HAL::HAL& hal; // maximum velocities and accelerations -#define WPNAV_ACCELERATION 250.0f // maximum horizontal acceleration in cm/s/s that wp navigation will request #define WPNAV_WP_SPEED 1000.0f // default horizontal speed between waypoints in cm/s #define WPNAV_WP_SPEED_MIN 20.0f // minimum horizontal speed between waypoints in cm/s #define WPNAV_WP_RADIUS 200.0f // default waypoint radius in cm @@ -143,15 +142,12 @@ AC_WPNav::TerrainSource AC_WPNav::get_terrain_source() const /// wp_and_spline_init - initialise straight line and spline waypoint controllers /// speed_cms should be a positive value or left at zero to use the default speed -/// updates target roll, pitch targets and I terms based on vehicle lean angles +/// stopping_point should be the vehicle's stopping point (equal to the starting point of the next segment) if know or left as zero /// should be called once before the waypoint controller is used but does not need to be called before subsequent updates to destination -void AC_WPNav::wp_and_spline_init(float speed_cms) +void AC_WPNav::wp_and_spline_init(float speed_cms, Vector3f stopping_point) { - - // sanity check parameters - // check _wp_accel_cmss is reasonable - const float wp_accel_cmss = MIN(_wp_accel_cmss, GRAVITY_MSS * 100.0f * tanf(ToRad(_attitude_control.lean_angle_max_cd() * 0.01f))); - _wp_accel_cmss.set_and_save_ifchanged((_wp_accel_cmss <= 0) ? WPNAV_ACCELERATION : wp_accel_cmss); + // set corner acceleration based on maximum lean angle + _scurve_accel_corner = angle_to_accel(_pos_control.get_lean_angle_max_cd() * 0.01) * 100; // check _wp_radius_cm is reasonable _wp_radius_cm.set_and_save_ifchanged(MAX(_wp_radius_cm, WPNAV_WP_RADIUS_MIN)); @@ -168,36 +164,40 @@ void AC_WPNav::wp_and_spline_init(float speed_cms) _wp_desired_speed_xy_cms = MAX(_wp_desired_speed_xy_cms, WPNAV_WP_SPEED_MIN); // initialise position controller speed and acceleration - _pos_control.set_max_speed_accel_xy(_wp_desired_speed_xy_cms, _wp_accel_cmss); - _pos_control.set_correction_speed_accel_xy(_wp_desired_speed_xy_cms, _wp_accel_cmss); + _pos_control.set_max_speed_accel_xy(_wp_desired_speed_xy_cms, get_wp_acceleration()); + _pos_control.set_correction_speed_accel_xy(_wp_desired_speed_xy_cms, get_wp_acceleration()); _pos_control.set_max_speed_accel_z(-get_default_speed_down(), _wp_speed_up_cms, _wp_accel_z_cmss); _pos_control.set_correction_speed_accel_z(-get_default_speed_down(), _wp_speed_up_cms, _wp_accel_z_cmss); // calculate scurve jerk and jerk time if (!is_positive(_wp_jerk)) { - _wp_jerk = _wp_accel_cmss; + _wp_jerk.set(get_wp_acceleration()); } - calc_scurve_jerk_and_jerk_time(); + calc_scurve_jerk_and_snap(); _scurve_prev_leg.init(); _scurve_this_leg.init(); _scurve_next_leg.init(); _track_scalar_dt = 1.0f; - // set flag so get_yaw() returns current heading target - _flags.reached_destination = false; + _flags.reached_destination = true; _flags.fast_waypoint = false; // initialise origin and destination to stopping point - Vector3f stopping_point; - get_wp_stopping_point(stopping_point); + if (stopping_point.is_zero()) { + get_wp_stopping_point(stopping_point); + } _origin = _destination = stopping_point; _terrain_alt = false; _this_leg_is_spline = false; // initialise the terrain velocity to the current maximum velocity - _terrain_vel = _wp_desired_speed_xy_cms; - _terrain_accel = 0.0; + _offset_vel = _wp_desired_speed_xy_cms; + _offset_accel = 0.0; + _paused = false; + + // mark as active + _wp_last_update = AP_HAL::millis(); } /// set_speed_xy - allows main code to pass target horizontal velocity for wp navigation @@ -205,15 +205,15 @@ void AC_WPNav::set_speed_xy(float speed_cms) { // range check target speed and protect against divide by zero if (speed_cms >= WPNAV_WP_SPEED_MIN && is_positive(_wp_desired_speed_xy_cms)) { - // update terrain following speed scalar - _terrain_vel = speed_cms * _terrain_vel / _wp_desired_speed_xy_cms; + // update horizontal velocity speed offset scalar + _offset_vel = speed_cms * _offset_vel / _wp_desired_speed_xy_cms; // initialize the desired wp speed _wp_desired_speed_xy_cms = speed_cms; // update position controller speed and acceleration - _pos_control.set_max_speed_accel_xy(_wp_desired_speed_xy_cms, _wp_accel_cmss); - _pos_control.set_correction_speed_accel_xy(_wp_desired_speed_xy_cms, _wp_accel_cmss); + _pos_control.set_max_speed_accel_xy(_wp_desired_speed_xy_cms, get_wp_acceleration()); + _pos_control.set_correction_speed_accel_xy(_wp_desired_speed_xy_cms, get_wp_acceleration()); // change track speed update_track_with_speed_accel_limits(); @@ -333,8 +333,8 @@ bool AC_WPNav::set_wp_destination(const Vector3f& destination, bool terrain_alt) } else { _scurve_this_leg.calculate_track(_origin, _destination, _pos_control.get_max_speed_xy_cms(), _pos_control.get_max_speed_up_cms(), _pos_control.get_max_speed_down_cms(), - _wp_accel_cmss, _wp_accel_z_cmss, - _scurve_jerk_time, _scurve_jerk * 100.0f); + get_wp_acceleration(), _wp_accel_z_cmss, + _scurve_snap * 100.0f, _scurve_jerk * 100.0f); if (!is_zero(origin_speed)) { // rebuild start of scurve if we have a non-zero origin speed _scurve_this_leg.set_origin_speed_max(origin_speed); @@ -361,8 +361,8 @@ bool AC_WPNav::set_wp_destination_next(const Vector3f& destination, bool terrain _scurve_next_leg.calculate_track(_destination, destination, _pos_control.get_max_speed_xy_cms(), _pos_control.get_max_speed_up_cms(), _pos_control.get_max_speed_down_cms(), - _wp_accel_cmss, _wp_accel_z_cmss, - _scurve_jerk_time, _scurve_jerk * 100.0f); + get_wp_acceleration(), _wp_accel_z_cmss, + _scurve_snap * 100.0f, _scurve_jerk * 100.0); if (_this_leg_is_spline) { const float this_leg_dest_speed_max = _spline_this_leg.get_destination_speed_max(); const float next_leg_origin_speed_max = _scurve_next_leg.set_origin_speed_max(this_leg_dest_speed_max); @@ -459,14 +459,14 @@ bool AC_WPNav::advance_wp_target_along_track(float dt) // get current position and adjust altitude to origin and destination's frame (i.e. _frame) const Vector3f &curr_pos = _inav.get_position_neu_cm() - Vector3f{0, 0, terr_offset}; - - // Use _track_scalar_dt to slow down S-Curve time to prevent target moving too far in front of aircraft Vector3f curr_target_vel = _pos_control.get_vel_desired_cms(); curr_target_vel.z -= _pos_control.get_vel_offset_z_cms(); + // Use _track_scalar_dt to slow down progression of the position target moving too far in front of aircraft + // _track_scalar_dt does not scale the velocity or acceleration float track_scaler_dt = 1.0f; // check target velocity is non-zero - if (is_positive(curr_target_vel.length())) { + if (is_positive(curr_target_vel.length_squared())) { Vector3f track_direction = curr_target_vel.normalized(); const float track_error = _pos_control.get_pos_error_cm().dot(track_direction); const float track_velocity = _inav.get_velocity_neu_cms().dot(track_direction); @@ -474,19 +474,21 @@ bool AC_WPNav::advance_wp_target_along_track(float dt) track_scaler_dt = constrain_float(0.05f + (track_velocity - _pos_control.get_pos_xy_p().kP() * track_error) / curr_target_vel.length(), 0.1f, 1.0f); } - float vel_time_scalar = 1.0; + // Use vel_scaler_dt to slow down the trajectory time + // vel_scaler_dt scales the velocity and acceleration to be kinematically constent + float vel_scaler_dt = 1.0; if (is_positive(_wp_desired_speed_xy_cms)) { - update_vel_accel(_terrain_vel, _terrain_accel, dt, 0.0, 0.0); - shape_vel_accel( _wp_desired_speed_xy_cms * offset_z_scaler, 0.0, - _terrain_vel, _terrain_accel, - -_wp_accel_cmss, _wp_accel_cmss, _pos_control.get_shaping_jerk_xy_cmsss(), dt, true); - vel_time_scalar = _terrain_vel / _wp_desired_speed_xy_cms; + update_vel_accel(_offset_vel, _offset_accel, dt, 0.0, 0.0); + const float vel_input = !_paused ? _wp_desired_speed_xy_cms * offset_z_scaler : 0.0; + shape_vel_accel(vel_input, 0.0, _offset_vel, _offset_accel, -get_wp_acceleration(), get_wp_acceleration(), + _pos_control.get_shaping_jerk_xy_cmsss(), dt, true); + vel_scaler_dt = _offset_vel / _wp_desired_speed_xy_cms; } // change s-curve time speed with a time constant of maximum acceleration / maximum jerk float track_scaler_tc = 1.0f; if (!is_zero(_wp_jerk)) { - track_scaler_tc = 0.01f * _wp_accel_cmss/_wp_jerk; + track_scaler_tc = 0.01f * get_wp_acceleration()/_wp_jerk; } _track_scalar_dt += (track_scaler_dt - _track_scalar_dt) * (dt / track_scaler_tc); @@ -497,16 +499,23 @@ bool AC_WPNav::advance_wp_target_along_track(float dt) if (!_this_leg_is_spline) { // update target position, velocity and acceleration target_pos = _origin; - s_finished = _scurve_this_leg.advance_target_along_track(_scurve_prev_leg, _scurve_next_leg, _wp_radius_cm, _flags.fast_waypoint, _track_scalar_dt * vel_time_scalar * dt, target_pos, target_vel, target_accel); + s_finished = _scurve_this_leg.advance_target_along_track(_scurve_prev_leg, _scurve_next_leg, _wp_radius_cm, _scurve_accel_corner, _flags.fast_waypoint, _track_scalar_dt * vel_scaler_dt * dt, target_pos, target_vel, target_accel); } else { // splinetarget_vel target_vel = curr_target_vel; - _spline_this_leg.advance_target_along_track(_track_scalar_dt * vel_time_scalar * dt, target_pos, target_vel); + _spline_this_leg.advance_target_along_track(_track_scalar_dt * vel_scaler_dt * dt, target_pos, target_vel); s_finished = _spline_this_leg.reached_destination(); } - target_vel *= vel_time_scalar; - target_accel *= sq(vel_time_scalar); + Vector3f accel_offset; + if (is_positive(target_vel.length_squared())) { + Vector3f track_direction = target_vel.normalized(); + accel_offset = track_direction * _offset_accel * target_vel.length() / _wp_desired_speed_xy_cms; + } + + target_vel *= vel_scaler_dt; + target_accel *= sq(vel_scaler_dt); + target_accel += accel_offset; // convert final_target.z to altitude above the ekf origin target_pos.z += _pos_control.get_pos_offset_z_cm(); @@ -542,7 +551,7 @@ void AC_WPNav::update_track_with_speed_accel_limits() // update this leg if (_this_leg_is_spline) { _spline_this_leg.set_speed_accel(_pos_control.get_max_speed_xy_cms(), _pos_control.get_max_speed_up_cms(), _pos_control.get_max_speed_down_cms(), - _wp_accel_cmss, _wp_accel_z_cmss); + get_wp_acceleration(), _wp_accel_z_cmss); } else { _scurve_this_leg.set_speed_max(_pos_control.get_max_speed_xy_cms(), _pos_control.get_max_speed_up_cms(), _pos_control.get_max_speed_down_cms()); } @@ -550,7 +559,7 @@ void AC_WPNav::update_track_with_speed_accel_limits() // update next leg if (_next_leg_is_spline) { _spline_next_leg.set_speed_accel(_pos_control.get_max_speed_xy_cms(), _pos_control.get_max_speed_up_cms(), _pos_control.get_max_speed_down_cms(), - _wp_accel_cmss, _wp_accel_z_cmss); + get_wp_acceleration(), _wp_accel_z_cmss); } else { _scurve_next_leg.set_speed_max(_pos_control.get_max_speed_xy_cms(), _pos_control.get_max_speed_up_cms(), _pos_control.get_max_speed_down_cms()); } @@ -857,8 +866,8 @@ bool AC_WPNav::get_vector_NEU(const Location &loc, Vector3f &vec, bool &terrain_ } // helper function to calculate scurve jerk and jerk_time values -// updates _scurve_jerk and _scurve_jerk_time -void AC_WPNav::calc_scurve_jerk_and_jerk_time() +// updates _scurve_jerk and _scurve_snap +void AC_WPNav::calc_scurve_jerk_and_snap() { // calculate jerk _scurve_jerk = MIN(_attitude_control.get_ang_vel_roll_max_rads() * GRAVITY_MSS, _attitude_control.get_ang_vel_pitch_max_rads() * GRAVITY_MSS); @@ -868,14 +877,14 @@ void AC_WPNav::calc_scurve_jerk_and_jerk_time() _scurve_jerk = MIN(_scurve_jerk, _wp_jerk); } - // calculate jerk time - // Jounce (the rate of change of jerk) uses the attitude control input time constant because multicopters + // calculate maximum snap + // Snap (the rate of change of jerk) uses the attitude control input time constant because multicopters // lean to accelerate. This means the change in angle is equivalent to the change in acceleration - const float jounce = MIN(_attitude_control.get_accel_roll_max_radss() * GRAVITY_MSS, _attitude_control.get_accel_pitch_max_radss() * GRAVITY_MSS); - if (is_positive(jounce)) { - _scurve_jerk_time = MAX(_attitude_control.get_input_tc(), 0.5f * _scurve_jerk * M_PI / jounce); - } else { - _scurve_jerk_time = MAX(_attitude_control.get_input_tc(), 0.1f); + _scurve_snap = (_scurve_jerk * M_PI) / (2.0 * MAX(_attitude_control.get_input_tc(), 0.1f)); + const float snap = MIN(_attitude_control.get_accel_roll_max_radss(), _attitude_control.get_accel_pitch_max_radss()) * GRAVITY_MSS; + if (is_positive(snap)) { + _scurve_snap = MIN(_scurve_snap, snap); } - _scurve_jerk_time *= 2.0f; + // reduce maximum snap by a factor of two from what the aircraft is capable of + _scurve_snap *= 0.5; } diff --git a/libraries/AC_WPNav/AC_WPNav.h b/libraries/AC_WPNav/AC_WPNav.h index 4a4432aff83..cab29d87572 100644 --- a/libraries/AC_WPNav/AC_WPNav.h +++ b/libraries/AC_WPNav/AC_WPNav.h @@ -12,6 +12,9 @@ #include #include // Stop at fence library +// maximum velocities and accelerations +#define WPNAV_ACCELERATION 250.0f // maximum horizontal acceleration in cm/s/s that wp navigation will request + class AC_WPNav { public: @@ -52,11 +55,18 @@ class AC_WPNav /// speed_cms is the desired max speed to travel between waypoints. should be a positive value or omitted to use the default speed /// updates target roll, pitch targets and I terms based on vehicle lean angles /// should be called once before the waypoint controller is used but does not need to be called before subsequent updates to destination - void wp_and_spline_init(float speed_cms = 0.0f); + void wp_and_spline_init(float speed_cms = 0.0f, Vector3f stopping_point = Vector3f{}); /// set current target horizontal speed during wp navigation void set_speed_xy(float speed_cms); + /// set pause or resume during wp navigation + void set_pause() { _paused = true; } + void set_resume() { _paused = false; } + + /// get paused status + bool paused() { return _paused; } + /// set current target climb or descent rate during wp navigation void set_speed_up(float speed_up_cms); void set_speed_down(float speed_down_cms); @@ -74,7 +84,7 @@ class AC_WPNav float get_accel_z() const { return _wp_accel_z_cmss; } /// get_wp_acceleration - returns acceleration in cm/s/s during missions - float get_wp_acceleration() const { return _wp_accel_cmss.get(); } + float get_wp_acceleration() const { return (is_positive(_wp_accel_cmss)) ? _wp_accel_cmss : WPNAV_ACCELERATION; } /// get_wp_destination waypoint using position vector /// x,y are distance from ekf origin in cm @@ -213,8 +223,8 @@ class AC_WPNav } _flags; // helper function to calculate scurve jerk and jerk_time values - // updates _scurve_jerk and _scurve_jerk_time - void calc_scurve_jerk_and_jerk_time(); + // updates _scurve_jerk and _scurve_snap + void calc_scurve_jerk_and_snap(); // references and pointers to external libraries const AP_InertialNav& _inav; @@ -240,8 +250,9 @@ class AC_WPNav SCurve _scurve_prev_leg; // previous scurve trajectory used to blend with current scurve trajectory SCurve _scurve_this_leg; // current scurve trajectory SCurve _scurve_next_leg; // next scurve trajectory used to blend with current scurve trajectory + float _scurve_accel_corner; // scurve maximum corner acceleration in m/s/s float _scurve_jerk; // scurve jerk max in m/s/s/s - float _scurve_jerk_time; // scurve jerk time (time in seconds for jerk to increase from zero _scurve_jerk) + float _scurve_snap; // scurve snap in m/s/s/s/s // spline curves SplineCurve _spline_this_leg; // spline curve for current segment @@ -257,8 +268,9 @@ class AC_WPNav Vector3f _origin; // starting point of trip to next waypoint in cm from ekf origin Vector3f _destination; // target destination in cm from ekf origin float _track_scalar_dt; // time compression multiplier to slow the progress along the track - float _terrain_vel; // maximum horizontal velocity used to ensure the aircraft can maintain height above terrain - float _terrain_accel; // acceleration value used to change _terrain_vel + float _offset_vel; // horizontal velocity reference used to slow the aircraft for pause and to ensure the aircraft can maintain height above terrain + float _offset_accel; // horizontal acceleration reference used to slow the aircraft for pause and to ensure the aircraft can maintain height above terrain + bool _paused; // flag for pausing waypoint controller // terrain following variables bool _terrain_alt; // true if origin and destination.z are alt-above-terrain, false if alt-above-ekf-origin diff --git a/libraries/APM_Control/AP_AutoTune.cpp b/libraries/APM_Control/AP_AutoTune.cpp index b283d47329f..27a52909cfc 100644 --- a/libraries/APM_Control/AP_AutoTune.cpp +++ b/libraries/APM_Control/AP_AutoTune.cpp @@ -25,6 +25,7 @@ #include #include #include +#include extern const AP_HAL::HAL& hal; @@ -163,7 +164,7 @@ const char *AP_AutoTune::axis_string(void) const /* one update cycle of the autotuner */ -void AP_AutoTune::update(AP_Logger::PID_Info &pinfo, float scaler, float angle_err_deg) +void AP_AutoTune::update(AP_PIDInfo &pinfo, float scaler, float angle_err_deg) { if (!running) { return; @@ -414,7 +415,11 @@ void AP_AutoTune::update(AP_Logger::PID_Info &pinfo, float scaler, float angle_e rpid.ff().set(FF); rpid.kP().set(P); rpid.kD().set(D); - rpid.kI().set(MAX(P*AUTOTUNE_I_RATIO, (FF / TRIM_TCONST))); + if (type == AUTOTUNE_ROLL) { // for roll set I = smaller of FF or P + rpid.kI().set(MIN(P, (FF / TRIM_TCONST))); + } else { // for pitch/yaw naturally damped axes) set I usually = FF to get 1 sec I closure + rpid.kI().set(MAX(P*AUTOTUNE_I_RATIO, (FF / TRIM_TCONST))); + } // setup filters to be suitable for time constant and gyro filter rpid.filt_T_hz().set(10.0/(current.tau * 2 * M_PI)); diff --git a/libraries/APM_Control/AP_AutoTune.h b/libraries/APM_Control/AP_AutoTune.h index 3030fed6a9b..1f3ba380111 100644 --- a/libraries/APM_Control/AP_AutoTune.h +++ b/libraries/APM_Control/AP_AutoTune.h @@ -1,10 +1,10 @@ #pragma once -#include #include -#include + +#include #include -#include +#include class AP_AutoTune { @@ -43,7 +43,7 @@ class AP_AutoTune // constructor - AP_AutoTune(ATGains &_gains, ATType type, const AP_Vehicle::FixedWing &parms, AC_PID &rpid); + AP_AutoTune(ATGains &_gains, ATType type, const AP_Vehicle::FixedWing &parms, class AC_PID &rpid); // called when autotune mode is entered void start(void); @@ -54,7 +54,7 @@ class AP_AutoTune // update called whenever autotune mode is active. This is // called at the main loop rate - void update(AP_Logger::PID_Info &pid_info, float scaler, float angle_err_deg); + void update(struct AP_PIDInfo &pid_info, float scaler, float angle_err_deg); // are we running? bool running; @@ -62,7 +62,7 @@ class AP_AutoTune private: // the current gains ATGains ¤t; - AC_PID &rpid; + class AC_PID &rpid; // what type of autotune is this ATType type; diff --git a/libraries/APM_Control/AP_PitchController.cpp b/libraries/APM_Control/AP_PitchController.cpp index 181ad2c65f7..bcf6419503d 100644 --- a/libraries/APM_Control/AP_PitchController.cpp +++ b/libraries/APM_Control/AP_PitchController.cpp @@ -155,8 +155,6 @@ float AP_PitchController::_get_rate_out(float desired_rate, float scaler, bool d float rate_y = _ahrs.get_gyro().y; float old_I = rate_pid.get_i(); - rate_pid.set_dt(dt); - bool underspeed = aspeed <= 0.5*float(aparm.airspeed_min); if (underspeed) { limit_I = true; @@ -167,7 +165,7 @@ float AP_PitchController::_get_rate_out(float desired_rate, float scaler, bool d // // note that we run AC_PID in radians so that the normal scaling // range for IMAX in AC_PID applies (usually an IMAX value less than 1.0) - rate_pid.update_all(radians(desired_rate) * scaler * scaler, rate_y * scaler * scaler, limit_I); + rate_pid.update_all(radians(desired_rate) * scaler * scaler, rate_y * scaler * scaler, dt, limit_I); if (underspeed) { // when underspeed we lock the integrator @@ -356,7 +354,7 @@ void AP_PitchController::reset_I() void AP_PitchController::convert_pid() { AP_Float &ff = rate_pid.ff(); - if (ff.configured_in_storage()) { + if (ff.configured()) { return; } diff --git a/libraries/APM_Control/AP_PitchController.h b/libraries/APM_Control/AP_PitchController.h index 94553bbe66b..1b6f989669d 100644 --- a/libraries/APM_Control/AP_PitchController.h +++ b/libraries/APM_Control/AP_PitchController.h @@ -3,7 +3,6 @@ #include #include #include "AP_AutoTune.h" -#include #include #include @@ -34,7 +33,7 @@ class AP_PitchController void autotune_start(void); void autotune_restore(void); - const AP_Logger::PID_Info& get_pid_info(void) const + const AP_PIDInfo& get_pid_info(void) const { return _pid_info; } @@ -45,6 +44,7 @@ class AP_PitchController AP_Float &kI(void) { return rate_pid.kI(); } AP_Float &kD(void) { return rate_pid.kD(); } AP_Float &kFF(void) { return rate_pid.ff(); } + AP_Float &tau(void) { return gains.tau; } void convert_pid(); @@ -56,10 +56,10 @@ class AP_PitchController AP_Int16 _max_rate_neg; AP_Float _roll_ff; float _last_out; - AC_PID rate_pid{0.04, 0.15, 0, 0.345, 0.666, 3, 0, 12, 0.02, 150, 1}; + AC_PID rate_pid{0.04, 0.15, 0, 0.345, 0.666, 3, 0, 12, 150, 1}; float angle_err_deg; - AP_Logger::PID_Info _pid_info; + AP_PIDInfo _pid_info; float _get_rate_out(float desired_rate, float scaler, bool disable_integrator, float aspeed, bool ground_mode); float _get_coordination_rate_offset(float &aspeed, bool &inverted) const; diff --git a/libraries/APM_Control/AP_RollController.cpp b/libraries/APM_Control/AP_RollController.cpp index 3e0a433b3be..547cf1c1baf 100644 --- a/libraries/APM_Control/AP_RollController.cpp +++ b/libraries/APM_Control/AP_RollController.cpp @@ -140,8 +140,6 @@ float AP_RollController::_get_rate_out(float desired_rate, float scaler, bool di float aspeed; float old_I = rate_pid.get_i(); - rate_pid.set_dt(dt); - if (!_ahrs.airspeed_estimate(aspeed)) { aspeed = 0; } @@ -155,7 +153,7 @@ float AP_RollController::_get_rate_out(float desired_rate, float scaler, bool di // // note that we run AC_PID in radians so that the normal scaling // range for IMAX in AC_PID applies (usually an IMAX value less than 1.0) - rate_pid.update_all(radians(desired_rate) * scaler * scaler, rate_x * scaler * scaler, limit_I); + rate_pid.update_all(radians(desired_rate) * scaler * scaler, rate_x * scaler * scaler, dt, limit_I); if (underspeed) { // when underspeed we lock the integrator @@ -258,7 +256,7 @@ void AP_RollController::reset_I() void AP_RollController::convert_pid() { AP_Float &ff = rate_pid.ff(); - if (ff.configured_in_storage()) { + if (ff.configured()) { return; } float old_ff=0, old_p=1.0, old_i=0.3, old_d=0.08; diff --git a/libraries/APM_Control/AP_RollController.h b/libraries/APM_Control/AP_RollController.h index fda999d861f..4fe57824b7e 100644 --- a/libraries/APM_Control/AP_RollController.h +++ b/libraries/APM_Control/AP_RollController.h @@ -3,7 +3,6 @@ #include #include #include "AP_AutoTune.h" -#include #include #include @@ -34,7 +33,7 @@ class AP_RollController void autotune_start(void); void autotune_restore(void); - const AP_Logger::PID_Info& get_pid_info(void) const + const AP_PIDInfo& get_pid_info(void) const { return _pid_info; } @@ -52,6 +51,7 @@ class AP_RollController AP_Float &kI(void) { return rate_pid.kI(); } AP_Float &kD(void) { return rate_pid.kD(); } AP_Float &kFF(void) { return rate_pid.ff(); } + AP_Float &tau(void) { return gains.tau; } void convert_pid(); @@ -61,10 +61,10 @@ class AP_RollController AP_AutoTune *autotune; bool failed_autotune_alloc; float _last_out; - AC_PID rate_pid{0.08, 0.15, 0, 0.345, 0.666, 3, 0, 12, 0.02, 150, 1}; + AC_PID rate_pid{0.08, 0.15, 0, 0.345, 0.666, 3, 0, 12, 150, 1}; float angle_err_deg; - AP_Logger::PID_Info _pid_info; + AP_PIDInfo _pid_info; float _get_rate_out(float desired_rate, float scaler, bool disable_integrator, bool ground_mode); }; diff --git a/libraries/APM_Control/AP_SteerController.cpp b/libraries/APM_Control/AP_SteerController.cpp index 055de44101d..cedb1e68ead 100644 --- a/libraries/APM_Control/AP_SteerController.cpp +++ b/libraries/APM_Control/AP_SteerController.cpp @@ -235,7 +235,7 @@ int32_t AP_SteerController::get_steering_out_lat_accel(float desired_accel) int32_t AP_SteerController::get_steering_out_angle_error(int32_t angle_err) { if (_tau < 0.1f) { - _tau = 0.1f; + _tau.set(0.1f); } // Calculate the desired steering rate (deg/sec) from the angle error diff --git a/libraries/APM_Control/AP_SteerController.h b/libraries/APM_Control/AP_SteerController.h index 6ecb9380242..301919f3a5c 100644 --- a/libraries/APM_Control/AP_SteerController.h +++ b/libraries/APM_Control/AP_SteerController.h @@ -2,7 +2,7 @@ #include #include -#include +#include class AP_SteerController { public: @@ -44,7 +44,7 @@ class AP_SteerController { static const struct AP_Param::GroupInfo var_info[]; - const AP_Logger::PID_Info& get_pid_info(void) const { return _pid_info; } + const class AP_PIDInfo& get_pid_info(void) const { return _pid_info; } void set_reverse(bool reverse) { _reverse = reverse; @@ -65,7 +65,7 @@ class AP_SteerController { AP_Float _deratefactor; AP_Float _mindegree; - AP_Logger::PID_Info _pid_info {}; + AP_PIDInfo _pid_info {}; bool _reverse; }; diff --git a/libraries/APM_Control/AP_YawController.cpp b/libraries/APM_Control/AP_YawController.cpp index b72608c9e3e..7e4b3c86ad5 100644 --- a/libraries/APM_Control/AP_YawController.cpp +++ b/libraries/APM_Control/AP_YawController.cpp @@ -164,6 +164,7 @@ int32_t AP_YawController::get_servo_out(float scaler, bool disable_integrator) uint32_t dt = tnow - _last_t; if (_last_t == 0 || dt > 1000) { dt = 0; + _pid_info.I = 0; } _last_t = tnow; @@ -173,7 +174,7 @@ int32_t AP_YawController::get_servo_out(float scaler, bool disable_integrator) aspd_min = 1; } - float delta_time = (float) dt / 1000.0f; + float delta_time = (float) dt * 0.001f; // Calculate yaw rate required to keep up with a constant height coordinated turn float aspeed; @@ -278,8 +279,6 @@ float AP_YawController::get_rate_out(float desired_rate, float scaler, bool disa float aspeed; float old_I = rate_pid.get_i(); - rate_pid.set_dt(dt); - if (!_ahrs.airspeed_estimate(aspeed)) { aspeed = 0; } @@ -293,7 +292,7 @@ float AP_YawController::get_rate_out(float desired_rate, float scaler, bool disa // // note that we run AC_PID in radians so that the normal scaling // range for IMAX in AC_PID applies (usually an IMAX value less than 1.0) - rate_pid.update_all(radians(desired_rate) * scaler * scaler, rate_z * scaler * scaler, limit_I); + rate_pid.update_all(radians(desired_rate) * scaler * scaler, rate_z * scaler * scaler, dt, limit_I); if (underspeed) { // when underspeed we lock the integrator @@ -343,9 +342,17 @@ float AP_YawController::get_rate_out(float desired_rate, float scaler, bool disa void AP_YawController::reset_I() { + _pid_info.I = 0; + rate_pid.reset_I(); _integrator = 0; } +void AP_YawController::reset_rate_PID() +{ + rate_pid.reset_I(); + rate_pid.reset_filter(); +} + /* start an autotune */ @@ -353,7 +360,7 @@ void AP_YawController::autotune_start(void) { if (autotune == nullptr && rate_control_enabled()) { // the autotuner needs a time constant. Use an assumed tconst of 0.5 - gains.tau = 0.5; + gains.tau.set(0.5); gains.rmax_pos.set(90); autotune = new AP_AutoTune(gains, AP_AutoTune::AUTOTUNE_YAW, aparm, rate_pid); diff --git a/libraries/APM_Control/AP_YawController.h b/libraries/APM_Control/AP_YawController.h index c0039ec707d..80b99c79a44 100644 --- a/libraries/APM_Control/AP_YawController.h +++ b/libraries/APM_Control/AP_YawController.h @@ -2,7 +2,6 @@ #include #include -#include #include #include "AP_AutoTune.h" @@ -27,6 +26,8 @@ class AP_YawController void reset_I(); + void reset_rate_PID(); + /* reduce the integrator, used when we have a low scale factor in a quadplane hover */ @@ -36,7 +37,7 @@ class AP_YawController _pid_info.I *= 0.995f; } - const AP_Logger::PID_Info& get_pid_info(void) const + const AP_PIDInfo& get_pid_info(void) const { return _pid_info; } @@ -44,6 +45,7 @@ class AP_YawController // start/stop auto tuner void autotune_start(void); void autotune_restore(void); + static const struct AP_Param::GroupInfo var_info[]; @@ -55,7 +57,7 @@ class AP_YawController AP_Float _K_FF; AP_Int16 _imax; AP_Int8 _rate_enable; - AC_PID rate_pid{0.04, 0.15, 0, 0.15, 0.666, 3, 0, 12, 0.02, 150, 1}; + AC_PID rate_pid{0.04, 0.15, 0, 0.15, 0.666, 3, 0, 12, 150, 1}; uint32_t _last_t; float _last_out; @@ -69,5 +71,5 @@ class AP_YawController AP_AutoTune *autotune; bool failed_autotune_alloc; - AP_Logger::PID_Info _pid_info; + AP_PIDInfo _pid_info; }; diff --git a/libraries/APM_Control/AR_AttitudeControl.cpp b/libraries/APM_Control/AR_AttitudeControl.cpp index 5de227c70c9..5a3255ea296 100644 --- a/libraries/APM_Control/AR_AttitudeControl.cpp +++ b/libraries/APM_Control/AR_AttitudeControl.cpp @@ -39,7 +39,10 @@ #define AR_ATTCONTROL_PITCH_THR_D 0.03f #define AR_ATTCONTROL_PITCH_THR_IMAX 1.0f #define AR_ATTCONTROL_PITCH_THR_FILT 10.0f -#define AR_ATTCONTROL_BAL_SPEED_FF 1.0f +#define AR_ATTCONTROL_BAL_PITCH_FF 0.4f +#define AR_ATTCONTROL_PITCH_LIM_TC 0.5f // pitch limit default time constant +#define AR_ATTCONTROL_PITCH_RELAX_RATIO 0.5f // pitch limit relaxed 2x slower than it is limited +#define AR_ATTCONTROL_PITCH_LIM_THR_THRESH 0.60 // pitch limiting starts if throttle exceeds 60% #define AR_ATTCONTROL_DT 0.02f #define AR_ATTCONTROL_TIMEOUT_MS 200 #define AR_ATTCONTROL_HEEL_SAIL_P 1.0f @@ -319,7 +322,7 @@ const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = { // @Param: _BAL_FLTT // @DisplayName: Pitch control Target filter frequency in Hz - // @Description: Target filter frequency in Hz + // @Description: Pitch control Target filter frequency in Hz // @Range: 0.000 100.000 // @Increment: 0.1 // @Units: Hz @@ -327,7 +330,7 @@ const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = { // @Param: _BAL_FLTE // @DisplayName: Pitch control Error filter frequency in Hz - // @Description: Error filter frequency in Hz + // @Description: Pitch control Error filter frequency in Hz // @Range: 0.000 100.000 // @Increment: 0.1 // @Units: Hz @@ -335,7 +338,7 @@ const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = { // @Param: _BAL_FLTD // @DisplayName: Pitch control Derivative term filter frequency in Hz - // @Description: Derivative filter frequency in Hz + // @Description: Pitch control Derivative filter frequency in Hz // @Range: 0.000 100.000 // @Increment: 0.1 // @Units: Hz @@ -343,20 +346,20 @@ const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = { // @Param: _BAL_SMAX // @DisplayName: Pitch control slew rate limit - // @Description: Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature. + // @Description: Pitch control upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature. // @Range: 0 200 // @Increment: 0.5 // @User: Advanced AP_SUBGROUPINFO(_pitch_to_throttle_pid, "_BAL_", 10, AR_AttitudeControl, AC_PID), - // @Param: _BAL_SPD_FF - // @DisplayName: Pitch control feed forward from speed - // @Description: Pitch control feed forward from speed - // @Range: 0.0 10.0 + // @Param: _BAL_PIT_FF + // @DisplayName: Pitch control feed forward from current pitch angle + // @Description: Pitch control feed forward from current pitch angle + // @Range: 0.0 1.0 // @Increment: 0.01 // @User: Standard - AP_GROUPINFO("_BAL_SPD_FF", 11, AR_AttitudeControl, _pitch_to_throttle_speed_ff, AR_ATTCONTROL_BAL_SPEED_FF), + AP_GROUPINFO("_BAL_PIT_FF", 11, AR_AttitudeControl, _pitch_to_throttle_ff, AR_ATTCONTROL_BAL_PITCH_FF), // @Param: _SAIL_P // @DisplayName: Sail Heel control P gain @@ -443,15 +446,31 @@ const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = { // @User: Standard AP_GROUPINFO("_TURN_MAX_G", 13, AR_AttitudeControl, _turn_lateral_G_max, 0.6f), + // @Param: _BAL_LIM_TC + // @DisplayName: Pitch control limit time constant + // @Description: Pitch control limit time constant to protect against falling. Lower values limit pitch more quickly, higher values limit more slowly. Set to 0 to disable + // @Range: 0.0 5.0 + // @Increment: 0.01 + // @User: Standard + AP_GROUPINFO("_BAL_LIM_TC", 14, AR_AttitudeControl, _pitch_limit_tc, AR_ATTCONTROL_PITCH_LIM_TC), + + // @Param: _BAL_LIM_THR + // @DisplayName: Pitch control limit throttle threshold + // @Description: Pitch control limit throttle threshold. Pitch angle will be limited if throttle crosses this threshold (from 0 to 1) + // @Range: 0.0 1.0 + // @Increment: 0.01 + // @User: Standard + AP_GROUPINFO("_BAL_LIM_THR", 15, AR_AttitudeControl, _pitch_limit_throttle_thresh, AR_ATTCONTROL_PITCH_LIM_THR_THRESH), + AP_GROUPEND }; AR_AttitudeControl::AR_AttitudeControl() : _steer_angle_p(AR_ATTCONTROL_STEER_ANG_P), - _steer_rate_pid(AR_ATTCONTROL_STEER_RATE_P, AR_ATTCONTROL_STEER_RATE_I, AR_ATTCONTROL_STEER_RATE_D, AR_ATTCONTROL_STEER_RATE_FF, AR_ATTCONTROL_STEER_RATE_IMAX, 0.0f, AR_ATTCONTROL_STEER_RATE_FILT, 0.0f, AR_ATTCONTROL_DT), - _throttle_speed_pid(AR_ATTCONTROL_THR_SPEED_P, AR_ATTCONTROL_THR_SPEED_I, AR_ATTCONTROL_THR_SPEED_D, 0.0f, AR_ATTCONTROL_THR_SPEED_IMAX, 0.0f, AR_ATTCONTROL_THR_SPEED_FILT, 0.0f, AR_ATTCONTROL_DT), - _pitch_to_throttle_pid(AR_ATTCONTROL_PITCH_THR_P, AR_ATTCONTROL_PITCH_THR_I, AR_ATTCONTROL_PITCH_THR_D, 0.0f, AR_ATTCONTROL_PITCH_THR_IMAX, 0.0f, AR_ATTCONTROL_PITCH_THR_FILT, 0.0f, AR_ATTCONTROL_DT), - _sailboat_heel_pid(AR_ATTCONTROL_HEEL_SAIL_P, AR_ATTCONTROL_HEEL_SAIL_I, AR_ATTCONTROL_HEEL_SAIL_D, 0.0f, AR_ATTCONTROL_HEEL_SAIL_IMAX, 0.0f, AR_ATTCONTROL_HEEL_SAIL_FILT, 0.0f, AR_ATTCONTROL_DT) + _steer_rate_pid(AR_ATTCONTROL_STEER_RATE_P, AR_ATTCONTROL_STEER_RATE_I, AR_ATTCONTROL_STEER_RATE_D, AR_ATTCONTROL_STEER_RATE_FF, AR_ATTCONTROL_STEER_RATE_IMAX, 0.0f, AR_ATTCONTROL_STEER_RATE_FILT, 0.0f), + _throttle_speed_pid(AR_ATTCONTROL_THR_SPEED_P, AR_ATTCONTROL_THR_SPEED_I, AR_ATTCONTROL_THR_SPEED_D, 0.0f, AR_ATTCONTROL_THR_SPEED_IMAX, 0.0f, AR_ATTCONTROL_THR_SPEED_FILT, 0.0f), + _pitch_to_throttle_pid(AR_ATTCONTROL_PITCH_THR_P, AR_ATTCONTROL_PITCH_THR_I, AR_ATTCONTROL_PITCH_THR_D, 0.0f, AR_ATTCONTROL_PITCH_THR_IMAX, 0.0f, AR_ATTCONTROL_PITCH_THR_FILT, 0.0f), + _sailboat_heel_pid(AR_ATTCONTROL_HEEL_SAIL_P, AR_ATTCONTROL_HEEL_SAIL_I, AR_ATTCONTROL_HEEL_SAIL_D, 0.0f, AR_ATTCONTROL_HEEL_SAIL_IMAX, 0.0f, AR_ATTCONTROL_HEEL_SAIL_FILT, 0.0f) { AP_Param::setup_object_defaults(this, var_info); } @@ -547,10 +566,7 @@ float AR_AttitudeControl::get_steering_out_rate(float desired_rate, bool motor_l _desired_turn_rate = constrain_float(_desired_turn_rate, -turn_rate_max, turn_rate_max); } - // set PID's dt - _steer_rate_pid.set_dt(dt); - - float output = _steer_rate_pid.update_all(_desired_turn_rate, AP::ahrs().get_yaw_rate_earth(), (motor_limit_left || motor_limit_right)); + float output = _steer_rate_pid.update_all(_desired_turn_rate, AP::ahrs().get_yaw_rate_earth(), dt, (motor_limit_left || motor_limit_right)); output += _steer_rate_pid.get_ff(); // constrain and return final output return output; @@ -629,17 +645,14 @@ float AR_AttitudeControl::get_throttle_out_speed(float desired_speed, bool motor // acceleration limit desired speed _desired_speed = get_desired_speed_accel_limited(desired_speed, dt); - // set PID's dt - _throttle_speed_pid.set_dt(dt); - // calculate base throttle (protect against divide by zero) float throttle_base = 0.0f; if (is_positive(cruise_speed) && is_positive(cruise_throttle)) { - throttle_base = desired_speed * (cruise_throttle / cruise_speed); + throttle_base = _desired_speed * (cruise_throttle / cruise_speed); } // calculate final output - float throttle_out = _throttle_speed_pid.update_all(desired_speed, speed, (motor_limit_low || motor_limit_high || _throttle_limit_low || _throttle_limit_high)); + float throttle_out = _throttle_speed_pid.update_all(_desired_speed, speed, dt, (motor_limit_low || motor_limit_high || _throttle_limit_low || _throttle_limit_high)); throttle_out += _throttle_speed_pid.get_ff(); throttle_out += throttle_base; @@ -654,10 +667,10 @@ float AR_AttitudeControl::get_throttle_out_speed(float desired_speed, bool motor // protect against reverse output being sent to the motors unless braking has been enabled if (!_brake_enable) { // if both desired speed and actual speed are positive, do not allow negative values - if ((desired_speed >= 0.0f) && (throttle_out <= 0.0f)) { + if ((_desired_speed >= 0.0f) && (throttle_out <= 0.0f)) { throttle_out = 0.0f; _throttle_limit_low = true; - } else if ((desired_speed <= 0.0f) && (throttle_out >= 0.0f)) { + } else if ((_desired_speed <= 0.0f) && (throttle_out >= 0.0f)) { throttle_out = 0.0f; _throttle_limit_high = true; } @@ -715,9 +728,10 @@ float AR_AttitudeControl::get_throttle_out_stop(bool motor_limit_low, bool motor } // balancebot pitch to throttle controller -// returns a throttle output from -100 to +100 given a desired pitch angle and vehicle's current speed (from wheel encoders) -// desired_pitch is in radians, veh_speed_pct is supplied as a percentage (-100 to +100) of vehicle's top speed -float AR_AttitudeControl::get_throttle_out_from_pitch(float desired_pitch, float vehicle_speed_pct, bool motor_limit_low, bool motor_limit_high, float dt) +// returns a throttle output from -1 to +1 given a desired pitch angle (in radians) +// pitch_max should be the user defined max pitch angle (in radians) +// motor_limit should be true if the motors have hit their upper or lower limit +float AR_AttitudeControl::get_throttle_out_from_pitch(float desired_pitch, float pitch_max, bool motor_limit, float dt) { // sanity check dt dt = constrain_float(dt, 0.0f, 1.0f); @@ -727,17 +741,47 @@ float AR_AttitudeControl::get_throttle_out_from_pitch(float desired_pitch, float if ((_balance_last_ms == 0) || ((now - _balance_last_ms) > AR_ATTCONTROL_TIMEOUT_MS)) { _pitch_to_throttle_pid.reset_filter(); _pitch_to_throttle_pid.reset_I(); + _pitch_limit_low = -pitch_max; + _pitch_limit_high = pitch_max; } _balance_last_ms = now; - // set PID's dt - _pitch_to_throttle_pid.set_dt(dt); + // limit desired pitch to protect against falling + const bool pitch_limit_active = (_pitch_limit_tc >= 0.01) && (_pitch_limit_throttle_thresh > 0); + if (pitch_limit_active) { + desired_pitch = constrain_float(desired_pitch, _pitch_limit_low, _pitch_limit_high); + _pitch_limited = (desired_pitch <= _pitch_limit_low || desired_pitch >= _pitch_limit_high); + } else { + _pitch_limited = false; + } + + // initialise output to feed forward from current pitch angle + const float pitch_rad = AP::ahrs().pitch; + float output = sinf(pitch_rad) * _pitch_to_throttle_ff; - // add feed forward from speed - float output = vehicle_speed_pct * 0.01f * _pitch_to_throttle_speed_ff; - output += _pitch_to_throttle_pid.update_all(desired_pitch, AP::ahrs().pitch, (motor_limit_low || motor_limit_high)); + // add regular PID control + output += _pitch_to_throttle_pid.update_all(desired_pitch, pitch_rad, dt, motor_limit); output += _pitch_to_throttle_pid.get_ff(); + // update pitch limits for next iteration + // note: pitch is positive when leaning backwards, negative when leaning forward + if (pitch_limit_active) { + const float pitch_limit_incr = 1.0/_pitch_limit_tc * dt * pitch_max; + const float pitch_relax_incr = pitch_limit_incr * AR_ATTCONTROL_PITCH_RELAX_RATIO; + if (output <= -_pitch_limit_throttle_thresh) { + // very low negative throttle output means we must lower pitch_high (e.g. reduce leaning backwards) + _pitch_limit_high = MAX(_pitch_limit_high - pitch_limit_incr, 0); + } else { + _pitch_limit_high = MIN(_pitch_limit_high + pitch_relax_incr, pitch_max); + } + if (output >= _pitch_limit_throttle_thresh) { + // very high positive throttle output means we must raise pitch_low (reduce leaning forwards) + _pitch_limit_low = MIN(_pitch_limit_low + pitch_limit_incr, 0); + } else { + _pitch_limit_low = MAX(_pitch_limit_low - pitch_relax_incr, -pitch_max); + } + } + // constrain and return final output return output; } @@ -768,10 +812,7 @@ float AR_AttitudeControl::get_sail_out_from_heel(float desired_heel, float dt) } _heel_controller_last_ms = now; - // set PID's dt - _sailboat_heel_pid.set_dt(dt); - - _sailboat_heel_pid.update_all(desired_heel, fabsf(AP::ahrs().roll)); + _sailboat_heel_pid.update_all(desired_heel, fabsf(AP::ahrs().roll), dt); // get feed-forward const float ff = _sailboat_heel_pid.get_ff(); diff --git a/libraries/APM_Control/AR_AttitudeControl.h b/libraries/APM_Control/AR_AttitudeControl.h index d466f1c4e02..57d15526599 100644 --- a/libraries/APM_Control/AR_AttitudeControl.h +++ b/libraries/APM_Control/AR_AttitudeControl.h @@ -67,9 +67,14 @@ class AR_AttitudeControl { float get_throttle_out_stop(bool motor_limit_low, bool motor_limit_high, float cruise_speed, float cruise_throttle, float dt, bool &stopped); // balancebot pitch to throttle controller - // returns a throttle output from -100 to +100 given a desired pitch angle and vehicle's current speed (from wheel encoders) - // desired_pitch is in radians, veh_speed_pct is supplied as a percentage (-100 to +100) of vehicle's top speed - float get_throttle_out_from_pitch(float desired_pitch, float veh_speed_pct, bool motor_limit_low, bool motor_limit_high, float dt); + // returns a throttle output from -1 to +1 given a desired pitch angle (in radians) + // pitch_max should be the user defined max pitch angle (in radians) + // motor_limit should be true if the motors have hit their upper or lower limit + float get_throttle_out_from_pitch(float desired_pitch, float pitch_max, bool motor_limit, float dt); + + // returns true if the pitch angle has been limited to prevent falling over + // pitch limit protection is implemented within get_throttle_out_from_pitch + bool pitch_limited() const { return _pitch_limited; } // get latest desired pitch in radians for reporting purposes float get_desired_pitch() const; @@ -82,7 +87,7 @@ class AR_AttitudeControl { AC_PID& get_steering_rate_pid() { return _steer_rate_pid; } AC_PID& get_pitch_to_throttle_pid() { return _pitch_to_throttle_pid; } AC_PID& get_sailboat_heel_pid() { return _sailboat_heel_pid; } - const AP_Logger::PID_Info& get_throttle_speed_pid_info() const { return _throttle_speed_pid_info; } + const AP_PIDInfo& get_throttle_speed_pid_info() const { return _throttle_speed_pid_info; } // get forward speed in m/s (earth-frame horizontal velocity but only along vehicle x-axis). returns true on success bool get_forward_speed(float &speed) const; @@ -121,7 +126,9 @@ class AR_AttitudeControl { AC_PID _steer_rate_pid; // steering rate controller AC_PID _throttle_speed_pid; // throttle speed controller AC_PID _pitch_to_throttle_pid;// balancebot pitch controller - AP_Float _pitch_to_throttle_speed_ff; // balancebot feed forward from speed + AP_Float _pitch_to_throttle_ff; // balancebot feed forward from current pitch angle + AP_Float _pitch_limit_tc; // balancebot pitch limit protection time constant + AP_Float _pitch_limit_throttle_thresh; // balancebot pitch limit throttle threshold (in the range 0 to 1.0) AP_Float _throttle_accel_max; // speed/throttle control acceleration (and deceleration) maximum in m/s/s. 0 to disable limits AP_Float _throttle_decel_max; // speed/throttle control deceleration maximum in m/s/s. 0 to use ATC_ACCEL_MAX for deceleration @@ -143,10 +150,13 @@ class AR_AttitudeControl { uint32_t _stop_last_ms; // system time the vehicle was at a complete stop bool _throttle_limit_low; // throttle output was limited from going too low (used to reduce i-term buildup) bool _throttle_limit_high; // throttle output was limited from going too high (used to reduce i-term buildup) - AP_Logger::PID_Info _throttle_speed_pid_info; // local copy of throttle_speed controller's PID info to allow reporting of unusual FF + AP_PIDInfo _throttle_speed_pid_info; // local copy of throttle_speed controller's PID info to allow reporting of unusual FF // balancebot pitch control - uint32_t _balance_last_ms = 0; + uint32_t _balance_last_ms = 0; // system time that get_throttle_out_from_pitch was last called + float _pitch_limit_low = 0; // min desired pitch (in radians) used to protect against falling over + float _pitch_limit_high = 0; // max desired pitch (in radians) used to protect against falling over + bool _pitch_limited = false; // true if pitch was limited on last call to get_throttle_out_from_pitch // Sailboat heel control AC_PID _sailboat_heel_pid; // Sailboat heel angle pid controller diff --git a/libraries/APM_Control/AR_PosControl.cpp b/libraries/APM_Control/AR_PosControl.cpp new file mode 100644 index 00000000000..6e1817ded5e --- /dev/null +++ b/libraries/APM_Control/AR_PosControl.cpp @@ -0,0 +1,385 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +#include "AR_PosControl.h" + +#include +#include +#include +#include +#include +#include + +extern const AP_HAL::HAL& hal; + +#define AR_POSCON_TIMEOUT_MS 100 // timeout after 0.1 sec +#define AR_POSCON_POS_P 0.2f // default position P gain +#define AR_POSCON_VEL_P 1.0f // default velocity P gain +#define AR_POSCON_VEL_I 0.0f // default velocity I gain +#define AR_POSCON_VEL_D 0.0f // default velocity D gain +#define AR_POSCON_VEL_FF 0.0f // default velocity FF gain +#define AR_POSCON_VEL_IMAX 1.0f // default velocity IMAX +#define AR_POSCON_VEL_FILT 5.0f // default velocity filter +#define AR_POSCON_VEL_FILT_D 5.0f // default velocity D term filter +#define AR_POSCON_DT 0.02f // default dt for PID controllers + +const AP_Param::GroupInfo AR_PosControl::var_info[] = { + + // @Param: _POS_P + // @DisplayName: Position controller P gain + // @Description: Position controller P gain. Converts the distance to the target location into a desired speed which is then passed to the loiter latitude rate controller + // @Range: 0.500 2.000 + // @User: Standard + AP_SUBGROUPINFO(_p_pos, "_POS_", 1, AR_PosControl, AC_P_2D), + + // @Param: _VEL_P + // @DisplayName: Velocity (horizontal) P gain + // @Description: Velocity (horizontal) P gain. Converts the difference between desired and actual velocity to a target acceleration + // @Range: 0.1 6.0 + // @Increment: 0.1 + // @User: Advanced + + // @Param: _VEL_I + // @DisplayName: Velocity (horizontal) I gain + // @Description: Velocity (horizontal) I gain. Corrects long-term difference between desired and actual velocity to a target acceleration + // @Range: 0.02 1.00 + // @Increment: 0.01 + // @User: Advanced + + // @Param: _VEL_D + // @DisplayName: Velocity (horizontal) D gain + // @Description: Velocity (horizontal) D gain. Corrects short-term changes in velocity + // @Range: 0.00 1.00 + // @Increment: 0.001 + // @User: Advanced + + // @Param: _VEL_IMAX + // @DisplayName: Velocity (horizontal) integrator maximum + // @Description: Velocity (horizontal) integrator maximum. Constrains the target acceleration that the I gain will output + // @Range: 0 4500 + // @Increment: 10 + // @Units: cm/s/s + // @User: Advanced + + // @Param: _VEL_FLTE + // @DisplayName: Velocity (horizontal) input filter + // @Description: Velocity (horizontal) input filter. This filter (in Hz) is applied to the input for P and I terms + // @Range: 0 100 + // @Units: Hz + // @User: Advanced + + // @Param: _VEL_FLTD + // @DisplayName: Velocity (horizontal) input filter + // @Description: Velocity (horizontal) input filter. This filter (in Hz) is applied to the input for D term + // @Range: 0 100 + // @Units: Hz + // @User: Advanced + + // @Param: _VEL_FF + // @DisplayName: Velocity (horizontal) feed forward gain + // @Description: Velocity (horizontal) feed forward gain. Converts the difference between desired velocity to a target acceleration + // @Range: 0 6 + // @Increment: 0.01 + // @User: Advanced + AP_SUBGROUPINFO(_pid_vel, "_VEL_", 2, AR_PosControl, AC_PID_2D), + + AP_GROUPEND +}; + +AR_PosControl::AR_PosControl(AR_AttitudeControl& atc) : + _atc(atc), + _p_pos(AR_POSCON_POS_P), + _pid_vel(AR_POSCON_VEL_P, AR_POSCON_VEL_I, AR_POSCON_VEL_D, AR_POSCON_VEL_FF, AR_POSCON_VEL_IMAX, AR_POSCON_VEL_FILT, AR_POSCON_VEL_FILT_D) +{ + AP_Param::setup_object_defaults(this, var_info); +} + +// update navigation +void AR_PosControl::update(float dt) +{ + // exit immediately if no current location, destination or disarmed + Vector2f curr_pos_NE; + Vector3f curr_vel_NED; + if (!hal.util->get_soft_armed() || !AP::ahrs().get_relative_position_NE_origin(curr_pos_NE) || + !AP::ahrs().get_velocity_NED(curr_vel_NED)) { + _desired_speed = _atc.get_desired_speed_accel_limited(0.0f, dt); + _desired_lat_accel = 0.0f; + _desired_turn_rate_rads = 0.0f; + return; + } + + // check for ekf xy position reset + handle_ekf_xy_reset(); + + // if no recent calls reset velocity controller + if (!is_active()) { + _pid_vel.reset_I(); + _pid_vel.reset_filter(); + } + _last_update_ms = AP_HAL::millis(); + + // calculate position error and convert to desired velocity + _vel_target.zero(); + if (_pos_target_valid) { + Vector2p pos_target = _pos_target; + _vel_target = _p_pos.update_all(pos_target.x, pos_target.y, curr_pos_NE); + } + + // calculation velocity error + if (_vel_desired_valid) { + // add target velocity to desired velocity from position error + _vel_target += _vel_desired; + } + + // limit velocity to maximum speed + _vel_target.limit_length(get_speed_max()); + + // Limit the velocity to prevent fence violations + bool backing_up = false; + AC_Avoid *avoid = AP::ac_avoid(); + if (avoid != nullptr) { + Vector3f vel_3d_cms{_vel_target.x * 100.0f, _vel_target.y * 100.0f, 0.0f}; + const float accel_max_cmss = MIN(_accel_max, _lat_accel_max) * 100.0; + avoid->adjust_velocity(vel_3d_cms, backing_up, _p_pos.kP(), accel_max_cmss, _p_pos.kP(), accel_max_cmss, dt); + _vel_target.x = vel_3d_cms.x * 0.01; + _vel_target.y = vel_3d_cms.y * 0.01; + } + + // calculate desired acceleration + // To-Do: fixup _limit_vel used below + _accel_target = _pid_vel.update_all(_vel_target, curr_vel_NED.xy(), dt, _limit_vel); + if (_accel_desired_valid) { + _accel_target += _accel_desired; + } + + // convert desired acceleration to desired forward-back speed, desired lateral speed and desired turn rate + + // rotate acceleration into body frame using current heading + const Vector2f accel_target_FR = AP::ahrs().earth_to_body2D(_accel_target); + + // calculate minimum turn speed which is the max speed the vehicle could turn through the corner + // given the vehicle's turn radius and half its max lateral acceleration + // todo: remove MAX of zero when safe_sqrt fixed + float turn_speed_min = MAX(safe_sqrt(_atc.get_turn_lat_accel_max() * 0.5 * _turn_radius), 0); + + // rotate target velocity from earth-frame to body frame + const Vector2f vel_target_FR = AP::ahrs().earth_to_body2D(_vel_target); + + // desired speed is normally the forward component (only) of the target velocity + // but we do not let it fall below the minimum turn speed unless the vehicle is slowing down + const float abs_des_speed_min = MIN(_vel_target.length(), turn_speed_min); + float des_speed; + if (_reversed != backing_up) { + // if reversed or backing up desired speed will be negative + des_speed = MIN(-abs_des_speed_min, vel_target_FR.x); + } else { + des_speed = MAX(abs_des_speed_min, vel_target_FR.x); + } + _desired_speed = _atc.get_desired_speed_accel_limited(des_speed, dt); + + // calculate turn rate from desired lateral acceleration + _desired_lat_accel = accel_target_FR.y; + _desired_turn_rate_rads = _atc.get_turn_rate_from_lat_accel(_desired_lat_accel, _desired_speed); +} + +// true if update has been called recently +bool AR_PosControl::is_active() const +{ + return ((AP_HAL::millis() - _last_update_ms) < AR_POSCON_TIMEOUT_MS); +} + +// set limits +void AR_PosControl::set_limits(float speed_max, float accel_max, float lat_accel_max, float jerk_max) +{ + _speed_max = MAX(speed_max, 0); + _accel_max = MAX(accel_max, 0); + _lat_accel_max = MAX(lat_accel_max, 0); + _jerk_max = MAX(jerk_max, 0); + + // set position P controller limits + _p_pos.set_limits(_speed_max, MIN(_accel_max, _lat_accel_max), _jerk_max); +} + +// setter to allow vehicle code to provide turn related param values to this library (should be updated regularly) +void AR_PosControl::set_turn_params(float turn_radius, bool pivot_possible) +{ + if (pivot_possible) { + _turn_radius = 0; + } else { + _turn_radius = turn_radius; + } +} + +// initialise the position controller to the current position, velocity, acceleration and attitude +// this should be called before the input shaping methods are used +bool AR_PosControl::init() +{ + // get current position and velocity from AHRS + Vector2f pos_NE; + Vector3f vel_NED; + if (!AP::ahrs().get_relative_position_NE_origin(pos_NE) || !AP::ahrs().get_velocity_NED(vel_NED)) { + return false; + } + + // set target position to current position + _pos_target.x = pos_NE.x; + _pos_target.y = pos_NE.y; + + // set target velocity and acceleration + _vel_desired = vel_NED.xy(); + _vel_target.zero(); + _accel_desired = AP::ahrs().get_accel_ef().xy(); + _accel_target.zero(); + + // clear reversed setting + _reversed = false; + + // initialise ekf xy reset handler + init_ekf_xy_reset(); + + return true; +} + +// methods to adjust position, velocity and acceleration targets smoothly using input shaping +// pos should be the target position as an offset from the EKF origin (in meters) +// dt should be the update rate in seconds +void AR_PosControl::input_pos_target(const Vector2p &pos, float dt) +{ + // adjust target position, velocity and acceleration forward by dt + update_pos_vel_accel_xy(_pos_target, _vel_desired, _accel_desired, dt, Vector2f(), Vector2f(), Vector2f()); + + // call shape_pos_vel_accel_xy to pull target towards final destination + Vector2f vel; + Vector2f accel; + const float accel_max = MIN(_accel_max, _lat_accel_max); + shape_pos_vel_accel_xy(pos, vel, accel, _pos_target, _vel_desired, _accel_desired, + _speed_max, accel_max, _jerk_max, dt, false); + + // set flags so update will consume target position, desired velocity and desired acceleration + _pos_target_valid = true; + _vel_desired_valid = true; + _accel_desired_valid = true; +} + +// set target position, desired velocity and acceleration. These should be from an externally created path and are not "input shaped" +void AR_PosControl::set_pos_vel_accel_target(const Vector2p &pos, const Vector2f &vel, const Vector2f &accel) +{ + _pos_target = pos; + _vel_desired = vel; + _accel_desired = accel; + _pos_target_valid = true; + _vel_desired_valid = true; + _accel_desired_valid = true; +} + +// returns desired velocity vector (i.e. feed forward) in cm/s in lat and lon direction +Vector2f AR_PosControl::get_desired_velocity() const +{ + if (_vel_desired_valid) { + return _vel_desired; + } + return Vector2f(); +} + +// return desired acceleration vector in m/s in lat and lon direction +Vector2f AR_PosControl::get_desired_accel() const +{ + if (_accel_desired_valid) { + return _accel_desired; + } + return Vector2f(); +} + +/// get position error as a vector from the current position to the target position +Vector2p AR_PosControl::get_pos_error() const +{ + // return zero error is not active or no position estimate + Vector2f curr_pos_NE; + if (!is_active() ||!AP::ahrs().get_relative_position_NE_origin(curr_pos_NE)) { + return Vector2p{}; + } + + // get current position + return (_pos_target - curr_pos_NE.topostype()); +} + +// write PSC logs +void AR_PosControl::write_log() +{ + // exit immediately if not active + if (!is_active()) { + return; + } + + // exit immediately if no position or velocity estimate + Vector3f curr_pos_NED; + Vector3f curr_vel_NED; + if (!AP::ahrs().get_relative_position_NED_origin(curr_pos_NED) || !AP::ahrs().get_velocity_NED(curr_vel_NED)) { + return; + } + + // get acceleration + const Vector3f curr_accel_NED = AP::ahrs().get_accel_ef() * 100.0; + + // convert position to required format + Vector2f pos_target_2d_cm = get_pos_target().tofloat() * 100.0; + + AP::logger().Write_PSCN(pos_target_2d_cm.x, // position target + curr_pos_NED.x * 100.0, // position + _vel_desired.x * 100.0, // desired velocity + _vel_target.x * 100.0, // target velocity + curr_vel_NED.x * 100.0, // velocity + _accel_desired.x * 100.0, // desired accel + _accel_target.x * 100.0, // target accel + curr_accel_NED.x); // accel + AP::logger().Write_PSCE(pos_target_2d_cm.y, // position target + curr_pos_NED.y * 100.0, // position + _vel_desired.y * 100.0, // desired velocity + _vel_target.y * 100.0, // target velocity + curr_vel_NED.y * 100.0, // velocity + _accel_desired.y * 100.0, // desired accel + _accel_target.y * 100.0, // target accel + curr_accel_NED.y); // accel +} + +/// initialise ekf xy position reset check +void AR_PosControl::init_ekf_xy_reset() +{ + Vector2f pos_shift; + _ekf_xy_reset_ms = AP::ahrs().getLastPosNorthEastReset(pos_shift); +} + +/// handle_ekf_xy_reset - check for ekf position reset and adjust loiter or brake target position +void AR_PosControl::handle_ekf_xy_reset() +{ + // check for position shift + Vector2f pos_shift; + uint32_t reset_ms = AP::ahrs().getLastPosNorthEastReset(pos_shift); + if (reset_ms != _ekf_xy_reset_ms) { + Vector2f pos_NE; + if (!AP::ahrs().get_relative_position_NE_origin(pos_NE)) { + return; + } + _pos_target = (pos_NE + _p_pos.get_error()).topostype(); + + Vector3f vel_NED; + if (!AP::ahrs().get_velocity_NED(vel_NED)) { + return; + } + _vel_desired = vel_NED.xy() + _pid_vel.get_error(); + + _ekf_xy_reset_ms = reset_ms; + } +} diff --git a/libraries/APM_Control/AR_PosControl.h b/libraries/APM_Control/AR_PosControl.h new file mode 100644 index 00000000000..6e57077f046 --- /dev/null +++ b/libraries/APM_Control/AR_PosControl.h @@ -0,0 +1,121 @@ +#pragma once + +#include +#include +#include // P library (2-axis) +#include // PID library (2-axis) + +class AR_PosControl { +public: + + // constructor + AR_PosControl(AR_AttitudeControl& atc); + + // update navigation + void update(float dt); + + // true if update has been called recently + bool is_active() const; + + // set speed, acceleration and jerk limits + void set_limits(float speed_max, float accel_max, float lat_accel_max, float jerk_max); + + // setter to allow vehicle code to provide turn related param values to this library (should be updated regularly) + void set_turn_params(float turn_radius, bool pivot_possible); + + // set reversed + void set_reversed(bool reversed) { _reversed = reversed; } + + // accessor for _reversed + bool get_reversed() { return _reversed; } + + // get limits + float get_speed_max() const { return _speed_max; } + float get_accel_max() const { return _accel_max; } + float get_lat_accel_max() const { return _lat_accel_max; } + float get_jerk_max() const { return _jerk_max; } + + // initialise the position controller to the current position, velocity, acceleration and attitude + // this should be called before the input shaping methods are used + // return true on success, false if targets cannot be initialised + bool init(); + + // adjust position, velocity and acceleration targets smoothly using input shaping + // pos should be the target position as an offset from the EKF origin (in meters) + // dt should be the update rate in seconds + // init should be called once before starting to use these methods + void input_pos_target(const Vector2p &pos, float dt); + + // set target position, desired velocity and acceleration. These should be from an externally created path and are not "input shaped" + void set_pos_vel_accel_target(const Vector2p &pos, const Vector2f &vel, const Vector2f &accel); + + // get outputs for forward-back speed (in m/s), lateral speed (in m/s) and turn rate (in rad/sec) + float get_desired_speed() const { return _desired_speed; } + float get_desired_turn_rate_rads() const { return _desired_turn_rate_rads; } + float get_desired_lat_accel() const { return _desired_lat_accel; } + + // get position target + const Vector2p& get_pos_target() const { return _pos_target; } + + // returns desired velocity vector (i.e. feed forward) in m/s in NE frame + Vector2f get_desired_velocity() const; + + // return desired acceleration vector in m/s in NE frame + Vector2f get_desired_accel() const; + + /// get position error as a vector from the current position to the target position + Vector2p get_pos_error() const; + + // get pid controllers + AC_P_2D& get_pos_p() { return _p_pos; } + AC_PID_2D& get_vel_pid() { return _pid_vel; } + + // write PSC logs + void write_log(); + + // parameter var table + static const struct AP_Param::GroupInfo var_info[]; + +private: + + // initialise and check for ekf position resets + void init_ekf_xy_reset(); + void handle_ekf_xy_reset(); + + // references + AR_AttitudeControl &_atc; // rover attitude control library + + // parameters + AC_P_2D _p_pos; // position P controller to convert distance error to desired velocity + AC_PID_2D _pid_vel; // velocity PID controller to convert velocity error to desired acceleration + + // limits + float _speed_max; // maximum forward speed in m/s + float _accel_max; // maximum forward/back acceleration in m/s/s + float _lat_accel_max; // lateral acceleration maximum in m/s/s + float _jerk_max; // maximum jerk in m/s/s/s (used for both forward and lateral input shaping) + float _turn_radius; // vehicle turn radius in meters + Vector2f _limit_vel; // To-Do: explain what this is + + // position and velocity targets + Vector2p _pos_target; // position target as an offset (in meters) from the EKF origin + Vector2f _vel_desired; // desired velocity in m/s in NE frame. This is the "feed forward" provided by SCurves + Vector2f _vel_target; // velocity target in m/s in NE frame + Vector2f _accel_desired; // desired accel in m/s/s in NE frame. This is the "feed forward" provided by SCurves + Vector2f _accel_target; // accel target in m/s/s in NE frame + bool _pos_target_valid; // true if _pos_target is valid + bool _vel_desired_valid; // true if _vel_desired is valid + bool _accel_desired_valid; // true if _accel_desired is valid + + // variables for navigation + uint32_t _last_update_ms; // system time of last call to update + bool _reversed; // true if vehicle should move in reverse towards target + + // main outputs + float _desired_speed; // desired forward_back speed in m/s + float _desired_turn_rate_rads; // desired turn-rate in rad/sec (negative is counter clockwise, positive is clockwise) + float _desired_lat_accel; // desired lateral acceleration (for reporting only) + + // ekf reset handling + uint32_t _ekf_xy_reset_ms; // system time of last recorded ekf xy position reset +}; diff --git a/libraries/AP_ADC/AP_ADC_ADS1115.cpp b/libraries/AP_ADC/AP_ADC_ADS1115.cpp index b098c889a52..21f124a88d1 100644 --- a/libraries/AP_ADC/AP_ADC_ADS1115.cpp +++ b/libraries/AP_ADC/AP_ADC_ADS1115.cpp @@ -192,7 +192,7 @@ float AP_ADC_ADS1115::_convert_register_data_to_mv(int16_t word) const break; default: pga = 0.0f; - hal.console->printf("Wrong gain"); + DEV_PRINTF("Wrong gain"); AP_HAL::panic("ADS1115: wrong gain selected"); break; } diff --git a/libraries/AP_ADSB/AP_ADSB.cpp b/libraries/AP_ADSB/AP_ADSB.cpp index 98e867f3566..421bd5c8285 100644 --- a/libraries/AP_ADSB/AP_ADSB.cpp +++ b/libraries/AP_ADSB/AP_ADSB.cpp @@ -26,6 +26,7 @@ #include "AP_ADSB_uAvionix_MAVLink.h" #include "AP_ADSB_uAvionix_UCP.h" #include "AP_ADSB_Sagetech.h" +#include "AP_ADSB_Sagetech_MXS.h" #include #include #include @@ -55,7 +56,7 @@ const AP_Param::GroupInfo AP_ADSB::var_info[] = { // @Param: TYPE // @DisplayName: ADSB Type // @Description: Type of ADS-B hardware for ADSB-in and ADSB-out configuration and operation. If any type is selected then MAVLink based ADSB-in messages will always be enabled - // @Values: 0:Disabled,1:uAvionix-MAVLink,2:Sagetech,3:uAvionix-UCP + // @Values: 0:Disabled,1:uAvionix-MAVLink,2:Sagetech,3:uAvionix-UCP,4:Sagetech MX Series // @User: Standard // @RebootRequired: True AP_GROUPINFO_FLAGS("TYPE", 0, AP_ADSB, _type[0], 0, AP_PARAM_FLAG_ENABLE), @@ -159,7 +160,8 @@ const AP_Param::GroupInfo AP_ADSB::var_info[] = { // @Param: OPTIONS // @DisplayName: ADS-B Options - // @Bitmask: 0:Ping200X Send GPS,1:Squawk 7400 on RC failsafe,2:Squawk 7400 on GCS failsafe + // @Description: Options for emergency failsafe codes and device capabilities + // @Bitmask: 0:Ping200X Send GPS,1:Squawk 7400 on RC failsafe,2:Squawk 7400 on GCS failsafe,3:Sagetech MXS use External Config // @User: Advanced AP_GROUPINFO("OPTIONS", 15, AP_ADSB, _options, 0), @@ -189,7 +191,7 @@ void AP_ADSB::init(void) { if (in_state.vehicle_list == nullptr) { // sanity check param - in_state.list_size_param = constrain_int16(in_state.list_size_param, 1, INT16_MAX); + in_state.list_size_param.set(constrain_int16(in_state.list_size_param, 1, INT16_MAX)); in_state.vehicle_list = new adsb_vehicle_t[in_state.list_size_param]; @@ -260,7 +262,6 @@ void AP_ADSB::detect_instance(uint8_t instance) #if HAL_ADSB_UAVIONIX_MAVLINK_ENABLED if (AP_ADSB_uAvionix_MAVLink::detect()) { _backend[instance] = new AP_ADSB_uAvionix_MAVLink(*this, instance); - return; } #endif break; @@ -269,7 +270,6 @@ void AP_ADSB::detect_instance(uint8_t instance) #if HAL_ADSB_UCP_ENABLED if (AP_ADSB_uAvionix_UCP::detect()) { _backend[instance] = new AP_ADSB_uAvionix_UCP(*this, instance); - return; } #endif break; @@ -278,11 +278,19 @@ void AP_ADSB::detect_instance(uint8_t instance) #if HAL_ADSB_SAGETECH_ENABLED if (AP_ADSB_Sagetech::detect()) { _backend[instance] = new AP_ADSB_Sagetech(*this, instance); - return; + } +#endif + break; + + case Type::Sagetech_MXS: +#if HAL_ADSB_SAGETECH_MXS_ENABLED + if (AP_ADSB_Sagetech_MXS::detect()) { + _backend[instance] = new AP_ADSB_Sagetech_MXS(*this, instance); } #endif break; } + } // get instance type from instance @@ -343,7 +351,7 @@ void AP_ADSB::update(void) // param changed, check that it's a valid octal if (!is_valid_callsign(out_state.cfg.squawk_octal_param)) { // invalid, reset it to default - out_state.cfg.squawk_octal_param = ADSB_SQUAWK_OCTAL_DEFAULT; + out_state.cfg.squawk_octal_param.set(ADSB_SQUAWK_OCTAL_DEFAULT); } out_state.cfg.squawk_octal = (uint16_t)out_state.cfg.squawk_octal_param; } @@ -367,10 +375,9 @@ void AP_ADSB::update(void) #ifndef ADSB_STATIC_CALLSIGN if (!out_state.cfg.was_set_externally) { - set_callsign("PING", true); + set_callsign("ARDU", true); } #endif - gcs().send_text(MAV_SEVERITY_INFO, "ADSB: Using ICAO_id %d and Callsign %s", (int)out_state.cfg.ICAO_id, out_state.cfg.callsign); out_state.last_config_ms = 0; // send now } @@ -610,16 +617,16 @@ void AP_ADSB::handle_out_cfg(const mavlink_uavionix_adsb_out_cfg_t &packet) out_state.cfg.was_set_externally = true; out_state.cfg.ICAO_id = packet.ICAO; - out_state.cfg.ICAO_id_param = out_state.cfg.ICAO_id_param_prev = packet.ICAO & 0x00FFFFFFFF; + out_state.cfg.ICAO_id_param.set(out_state.cfg.ICAO_id_param_prev = packet.ICAO & 0x00FFFFFFFF); // May contain a non-null value at the end so accept it as-is with memcpy instead of strcpy memcpy(out_state.cfg.callsign, packet.callsign, sizeof(out_state.cfg.callsign)); - out_state.cfg.emitterType = packet.emitterType; - out_state.cfg.lengthWidth = packet.aircraftSize; - out_state.cfg.gpsOffsetLat = packet.gpsOffsetLat; - out_state.cfg.gpsOffsetLon = packet.gpsOffsetLon; - out_state.cfg.rfSelect = packet.rfSelect; + out_state.cfg.emitterType.set(packet.emitterType); + out_state.cfg.lengthWidth.set(packet.aircraftSize); + out_state.cfg.gpsOffsetLat.set(packet.gpsOffsetLat); + out_state.cfg.gpsOffsetLon.set(packet.gpsOffsetLon); + out_state.cfg.rfSelect.set(packet.rfSelect); out_state.cfg.stall_speed_cm = packet.stallSpeed; // guard against string with non-null end char @@ -673,7 +680,7 @@ void AP_ADSB::handle_transceiver_report(const mavlink_channel_t chan, const mavl void AP_ADSB::send_adsb_out_status(const mavlink_channel_t chan) const { for (uint8_t i=0; i < ADSB_MAX_INSTANCES; i++) { - if (_type[i] == (int8_t)(AP_ADSB::Type::uAvionix_UCP)) { + if (_type[i] == (int8_t)(AP_ADSB::Type::uAvionix_UCP) || (int8_t)(AP_ADSB::Type::Sagetech_MXS)) { mavlink_msg_uavionix_adsb_out_status_send_struct(chan, &out_state.tx_status); return; } @@ -848,6 +855,29 @@ void AP_ADSB::write_log(const adsb_vehicle_t &vehicle) const AP::logger().WriteBlock(&pkt, sizeof(pkt)); } +/** +* @brief Convert base 8 or 16 to decimal. Used to convert an octal/hexadecimal value stored on a GCS as a string field in different format, but then transmitted over mavlink as a float which is always a decimal. +* baseIn: base of input number +* inputNumber: value currently in base "baseIn" to be converted to base "baseOut" +* +* Example: convert ADSB squawk octal "1200" stored in memory as 0x0280 to 0x04B0 +* uint16_t squawk_decimal = convertMathBase(8, squawk_octal); +*/ +uint32_t AP_ADSB::convert_base_to_decimal(const uint8_t baseIn, uint32_t inputNumber) +{ + // Our only sensible input bases are 16 and 8 + if (baseIn != 8 && baseIn != 16) { + return inputNumber; + } + uint32_t outputNumber = 0; + for (uint8_t i=0; i < 10; i++) { + outputNumber += (inputNumber % 10) * powf(baseIn, i); + inputNumber /= 10; + if (inputNumber == 0) break; + } + return outputNumber; +} + AP_ADSB *AP::ADSB() { return AP_ADSB::get_singleton(); diff --git a/libraries/AP_ADSB/AP_ADSB.h b/libraries/AP_ADSB/AP_ADSB.h index a04f59b8f68..8797803a21b 100644 --- a/libraries/AP_ADSB/AP_ADSB.h +++ b/libraries/AP_ADSB/AP_ADSB.h @@ -21,7 +21,6 @@ Tom Pittenger, November 2015 */ -#include #include #ifndef HAL_ADSB_ENABLED @@ -38,6 +37,8 @@ #define ADSB_BITBASK_RF_CAPABILITIES_UAT_IN (1 << 0) #define ADSB_BITBASK_RF_CAPABILITIES_1090ES_IN (1 << 1) +#define ADSB_BITBASK_RF_CAPABILITIES_UAT_OUT (1 << 2) +#define ADSB_BITBASK_RF_CAPABILITIES_1090ES_OUT (1 << 3) class AP_ADSB_Backend; @@ -47,6 +48,7 @@ class AP_ADSB { friend class AP_ADSB_uAvionix_MAVLink; friend class AP_ADSB_uAvionix_UCP; friend class AP_ADSB_Sagetech; + friend class AP_ADSB_Sagetech_MXS; // constructor AP_ADSB(); @@ -66,6 +68,7 @@ class AP_ADSB { uAvionix_MAVLink = 1, Sagetech = 2, uAvionix_UCP = 3, + Sagetech_MXS = 4, }; struct adsb_vehicle_t { @@ -78,6 +81,7 @@ class AP_ADSB { Ping200X_Send_GPS = (1<<0), Squawk_7400_FS_RC = (1<<1), Squawk_7400_FS_GCS = (1<<2), + SagteTech_MXS_External_Config = (1<<3), }; // for holding parameters @@ -146,12 +150,17 @@ class AP_ADSB { bool get_vehicle_by_ICAO(const uint32_t icao, adsb_vehicle_t &vehicle) const; uint32_t get_special_ICAO_target() const { return (uint32_t)_special_ICAO_target; }; - void set_special_ICAO_target(const uint32_t new_icao_target) { _special_ICAO_target = (int32_t)new_icao_target; }; + void set_special_ICAO_target(const uint32_t new_icao_target) { _special_ICAO_target.set((int32_t)new_icao_target); }; bool is_special_vehicle(uint32_t icao) const { return _special_ICAO_target != 0 && (_special_ICAO_target == (int32_t)icao); } // confirm a value is a valid callsign static bool is_valid_callsign(uint16_t octal) WARN_IF_UNUSED; + // Convert base 8 or 16 to decimal. Used to convert an octal/hexadecimal value + // stored on a GCS as a string field in different format, but then transmitted + // over mavlink as a float which is always a decimal. + static uint32_t convert_base_to_decimal(const uint8_t baseIn, uint32_t inputNumber); + // Trigger a Mode 3/A transponder IDENT. This should only be done when requested to do so by an Air Traffic Controller. // See wikipedia for IDENT explaination https://en.wikipedia.org/wiki/Transponder_(aeronautics) bool ident_start() { diff --git a/libraries/AP_ADSB/AP_ADSB_Backend.cpp b/libraries/AP_ADSB/AP_ADSB_Backend.cpp index 78ba4601260..3797694300d 100644 --- a/libraries/AP_ADSB/AP_ADSB_Backend.cpp +++ b/libraries/AP_ADSB/AP_ADSB_Backend.cpp @@ -1,30 +1,30 @@ -/* - This program is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - This program is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with this program. If not, see . - */ - -#include "AP_ADSB_Backend.h" - -#if HAL_ADSB_ENABLED - -/* - base class constructor. -*/ -AP_ADSB_Backend::AP_ADSB_Backend(AP_ADSB &frontend, uint8_t instance) : - _frontend(frontend), - _instance(instance) -{ -} - -#endif // HAL_ADSB_ENABLED - +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +#include "AP_ADSB_Backend.h" + +#if HAL_ADSB_ENABLED + +/* + base class constructor. +*/ +AP_ADSB_Backend::AP_ADSB_Backend(AP_ADSB &frontend, uint8_t instance) : + _frontend(frontend), + _instance(instance) +{ +} + +#endif // HAL_ADSB_ENABLED + diff --git a/libraries/AP_ADSB/AP_ADSB_Sagetech.cpp b/libraries/AP_ADSB/AP_ADSB_Sagetech.cpp index d1d902dbcda..6e610f9e901 100644 --- a/libraries/AP_ADSB/AP_ADSB_Sagetech.cpp +++ b/libraries/AP_ADSB/AP_ADSB_Sagetech.cpp @@ -1,553 +1,530 @@ -/* - Copyright (C) 2020 Kraus Hamdani Aerospace Inc. All rights reserved. - - This program is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - This program is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with this program. If not, see . - */ - -#include "AP_ADSB_Sagetech.h" - -#if HAL_ADSB_SAGETECH_ENABLED -#include -#include -#include -#include -#include -#include -#include -#include - -#define SAGETECH_SCALER_LATLNG (1.0f/2.145767E-5f) // 180/(2^23) -#define SAGETECH_SCALER_KNOTS_TO_CMS ((KNOTS_TO_M_PER_SEC/0.125f) * 100.0f) -#define SAGETECH_SCALER_ALTITUDE (1.0f/0.015625f) -#define SAGETECH_SCALER_HEADING_CM ((360.0f/256.0f) * 100.0f) - -#define SAGETECH_VALIDFLAG_LATLNG (1U<<0) -#define SAGETECH_VALIDFLAG_ALTITUDE (1U<<1) -#define SAGETECH_VALIDFLAG_VELOCITY (1U<<2) -#define SAGETECH_VALIDFLAG_GND_SPEED (1U<<3) -#define SAGETECH_VALIDFLAG_HEADING (1U<<4) -#define SAGETECH_VALIDFLAG_V_RATE_GEO (1U<<5) -#define SAGETECH_VALIDFLAG_V_RATE_BARO (1U<<6) -#define SAGETECH_VALIDFLAG_EST_LATLNG (1U<<7) -#define SAGETECH_VALIDFLAG_EST_VELOCITY (1U<<8) - -// detect if any port is configured as Sagetech -bool AP_ADSB_Sagetech::detect() -{ - return AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_ADSB, 0); -} - -// Init, called once after class is constructed -bool AP_ADSB_Sagetech::init() -{ - _port = AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_ADSB, 0); - - return (_port != nullptr); -} - -void AP_ADSB_Sagetech::update() -{ - if (_port == nullptr) { - return; - } - - const uint32_t now_ms = AP_HAL::millis(); - - // ----------------------------- - // read any available data on serial port - // ----------------------------- - uint32_t nbytes = MIN(_port->available(), 10 * PAYLOAD_XP_MAX_SIZE); - while (nbytes-- > 0) { - const int16_t data = (uint8_t)_port->read(); - if (data < 0) { - break; - } - if (parse_byte_XP((uint8_t)data)) { - handle_packet_XP(message_in.packet); - } - } // while nbytes - - - // ----------------------------- - // handle timers for generating data - // ----------------------------- - if (!last_packet_initialize_ms || (now_ms - last_packet_initialize_ms >= 5000)) { - last_packet_initialize_ms = now_ms; - send_packet(MsgType_XP::Installation_Set); - - } else if (!last_packet_PreFlight_ms || (now_ms - last_packet_PreFlight_ms >= 8200)) { - last_packet_PreFlight_ms = now_ms; - // TODO: allow callsign to not require a reboot - send_packet(MsgType_XP::Preflight_Set); - - } else if (now_ms - last_packet_Operating_ms >= 1000 && ( - last_packet_Operating_ms == 0 || // send once at boot - // send as data changes - last_operating_squawk != _frontend.out_state.cfg.squawk_octal || - abs(last_operating_alt - _frontend._my_loc.alt) > 1555 || // 1493cm == 49ft. The output resolution is 100ft per bit - last_operating_rf_select != _frontend.out_state.cfg.rfSelect)) - { - last_packet_Operating_ms = now_ms; - last_operating_squawk = _frontend.out_state.cfg.squawk_octal; - last_operating_alt = _frontend._my_loc.alt; - last_operating_rf_select = _frontend.out_state.cfg.rfSelect; - send_packet(MsgType_XP::Operating_Set); - - } else if (now_ms - last_packet_GPS_ms >= (_frontend.out_state.is_flying ? 200 : 1000)) { - // 1Hz when not flying, 5Hz when flying - last_packet_GPS_ms = now_ms; - send_packet(MsgType_XP::GPS_Set); - } -} - -void AP_ADSB_Sagetech::send_packet(const MsgType_XP type) -{ - switch (type) { - case MsgType_XP::Installation_Set: - send_msg_Installation(); - break; - case MsgType_XP::Preflight_Set: - send_msg_PreFlight(); - break; - case MsgType_XP::Operating_Set: - send_msg_Operating(); - break; - case MsgType_XP::GPS_Set: - send_msg_GPS(); - break; - default: - break; - } -} - -void AP_ADSB_Sagetech::request_packet(const MsgType_XP type) -{ - // set all bytes in packet to 0 via {} so we only need to set the ones we need to - Packet_XP pkt {}; - - pkt.type = MsgType_XP::Request; - pkt.id = 0; - pkt.payload_length = 4; - - pkt.payload[0] = static_cast(type); - - send_msg(pkt); -} - - -void AP_ADSB_Sagetech::handle_packet_XP(const Packet_XP &msg) -{ - switch (msg.type) { - case MsgType_XP::ACK: - handle_ack(msg); - break; - - case MsgType_XP::Installation_Response: - case MsgType_XP::Preflight_Response: - case MsgType_XP::Status_Response: - // TODO add support for these - break; - - case MsgType_XP::ADSB_StateVector_Report: - case MsgType_XP::ADSB_ModeStatus_Report: - case MsgType_XP::TISB_StateVector_Report: - case MsgType_XP::TISB_ModeStatus_Report: - case MsgType_XP::TISB_CorasePos_Report: - case MsgType_XP::TISB_ADSB_Mgr_Report: - handle_adsb_in_msg(msg); - break; - - case MsgType_XP::Installation_Set: - case MsgType_XP::Preflight_Set: - case MsgType_XP::Operating_Set: - case MsgType_XP::GPS_Set: - case MsgType_XP::Request: - // these are out-bound only and are not expected to be received - case MsgType_XP::INVALID: - break; - } -} - -void AP_ADSB_Sagetech::handle_ack(const Packet_XP &msg) -{ - // ACK received! - const uint8_t system_state = msg.payload[2]; - transponder_type = (Transponder_Type)msg.payload[6]; - - const uint8_t prev_transponder_mode = last_ack_transponder_mode; - last_ack_transponder_mode = (system_state >> 6) & 0x03; - if (prev_transponder_mode != last_ack_transponder_mode) { - static const char *mode_names[] = {"OFF", "STBY", "ON", "ON-ALT"}; - if (last_ack_transponder_mode < ARRAY_SIZE(mode_names)) { - gcs().send_text(MAV_SEVERITY_INFO, "ADSB: RF Mode: %s", mode_names[last_ack_transponder_mode]); - } - } -} - -void AP_ADSB_Sagetech::handle_adsb_in_msg(const Packet_XP &msg) -{ - AP_ADSB::adsb_vehicle_t vehicle {}; - - vehicle.last_update_ms = AP_HAL::millis(); - - switch (msg.type) { - case MsgType_XP::ADSB_StateVector_Report: { // 0x91 - const uint16_t validFlags = le16toh_ptr(&msg.payload[8]); - vehicle.info.ICAO_address = le24toh_ptr(&msg.payload[10]); - - if (validFlags & SAGETECH_VALIDFLAG_LATLNG) { - vehicle.info.lat = ((int32_t)le24toh_ptr(&msg.payload[20])) * SAGETECH_SCALER_LATLNG; - vehicle.info.lon = ((int32_t)le24toh_ptr(&msg.payload[23])) * SAGETECH_SCALER_LATLNG; - vehicle.info.flags |= ADSB_FLAGS_VALID_COORDS; - } - - if (validFlags & SAGETECH_VALIDFLAG_ALTITUDE) { - vehicle.info.altitude = (int32_t)le24toh_ptr(&msg.payload[26]); - vehicle.info.flags |= ADSB_FLAGS_VALID_ALTITUDE; - } - - if (validFlags & SAGETECH_VALIDFLAG_VELOCITY) { - const float velNS = ((int32_t)le16toh_ptr(&msg.payload[29])) * SAGETECH_SCALER_KNOTS_TO_CMS; - const float velEW = ((int32_t)le16toh_ptr(&msg.payload[31])) * SAGETECH_SCALER_KNOTS_TO_CMS; - vehicle.info.hor_velocity = Vector2f(velEW, velNS).length(); - vehicle.info.flags |= ADSB_FLAGS_VALID_VELOCITY; - } - - if (validFlags & SAGETECH_VALIDFLAG_HEADING) { - vehicle.info.heading = ((float)msg.payload[29]) * SAGETECH_SCALER_HEADING_CM; - vehicle.info.flags |= ADSB_FLAGS_VALID_HEADING; - } - - if ((validFlags & SAGETECH_VALIDFLAG_V_RATE_GEO) || (validFlags & SAGETECH_VALIDFLAG_V_RATE_BARO)) { - vehicle.info.ver_velocity = (int16_t)le16toh_ptr(&msg.payload[38]); - vehicle.info.flags |= ADSB_FLAGS_VERTICAL_VELOCITY_VALID; - } - - _frontend.handle_adsb_vehicle(vehicle); - break; - } - case MsgType_XP::ADSB_ModeStatus_Report: // 0x92 - vehicle.info.ICAO_address = le24toh_ptr(&msg.payload[9]); - - if (msg.payload[16] != 0) { - // if string is non-null, consider it valid - memcpy(&vehicle.info, &msg.payload[16], 8); - vehicle.info.flags |= ADSB_FLAGS_VALID_CALLSIGN; - } - - _frontend.handle_adsb_vehicle(vehicle); - break; - case MsgType_XP::TISB_StateVector_Report: - case MsgType_XP::TISB_ModeStatus_Report: - case MsgType_XP::TISB_CorasePos_Report: - case MsgType_XP::TISB_ADSB_Mgr_Report: - // TODO - return; - - default: - return; - } - -} - -// handling inbound byte and process it in the state machine -// return true when a full packet has been received -bool AP_ADSB_Sagetech::parse_byte_XP(const uint8_t data) -{ - switch (message_in.state) { - default: - case ParseState::WaitingFor_Start: - if (data == 0xA5) { - message_in.state = ParseState::WaitingFor_AssmAddr; - } - break; - case ParseState::WaitingFor_AssmAddr: - message_in.state = (data == 0x01) ? ParseState::WaitingFor_MsgType : ParseState::WaitingFor_Start; - break; - case ParseState::WaitingFor_MsgType: - message_in.packet.type = static_cast(data); - message_in.state = ParseState::WaitingFor_MsgId; - break; - case ParseState::WaitingFor_MsgId: - message_in.packet.id = data; - message_in.state = ParseState::WaitingFor_PayloadLen; - break; - case ParseState::WaitingFor_PayloadLen: - message_in.packet.payload_length = data; - message_in.index = 0; - message_in.state = (data == 0) ? ParseState::WaitingFor_ChecksumFletcher : ParseState::WaitingFor_PayloadContents; - break; - - case ParseState::WaitingFor_PayloadContents: - message_in.packet.payload[message_in.index++] = data; - if (message_in.index >= message_in.packet.payload_length) { - message_in.state = ParseState::WaitingFor_ChecksumFletcher; - message_in.index = 0; - } - break; - - case ParseState::WaitingFor_ChecksumFletcher: - message_in.packet.checksumFletcher = data; - message_in.state = ParseState::WaitingFor_Checksum; - break; - case ParseState::WaitingFor_Checksum: - message_in.packet.checksum = data; - message_in.state = ParseState::WaitingFor_End; - if (checksum_verify_XP(message_in.packet)) { - handle_packet_XP(message_in.packet); - } - break; - - case ParseState::WaitingFor_End: - // we don't care if the end value matches - message_in.state = ParseState::WaitingFor_Start; - break; - } - return false; -} - -// compute Sum and FletcherSum values into a single value -// returns uint16_t with MSByte as Sum and LSByte FletcherSum -uint16_t AP_ADSB_Sagetech::checksum_generate_XP(Packet_XP &msg) const -{ - uint8_t sum = 0; - uint8_t sumFletcher = 0; - - const uint8_t header_message_format[5] { - 0xA5, // start - 0x01, // assembly address - static_cast(msg.type), - msg.id, - msg.payload_length - }; - - for (uint8_t i=0; i<5; i++) { - sum += header_message_format[i]; - sumFletcher += sum; - } - for (uint8_t i=0; i(msg.type), - msg.id, - msg.payload_length - }; - const uint8_t message_format_tail[3] { - msg.checksumFletcher, - msg.checksum, - 0x5A // end - }; - - if (_port != nullptr) { - _port->write(message_format_header, sizeof(message_format_header)); - _port->write(msg.payload, msg.payload_length); - _port->write(message_format_tail, sizeof(message_format_tail)); - } -} - -void AP_ADSB_Sagetech::send_msg_Installation() -{ - Packet_XP pkt {}; - - pkt.type = MsgType_XP::Installation_Set; - pkt.payload_length = 28; // 28== 0x1C - - // Mode C = 3, Mode S = 0 - pkt.id = (transponder_type == Transponder_Type::Mode_C) ? 3 : 0; - -// // convert a decimal 123456 to 0x123456 - // TODO: do a proper conversion. The param contains "131313" but what gets transmitted over the air is 0x200F1. - const uint32_t icao_hex = convert_base_to_decimal(16, _frontend.out_state.cfg.ICAO_id_param); - put_le24_ptr(&pkt.payload[0], icao_hex); - - memcpy(&pkt.payload[3], &_frontend.out_state.cfg.callsign, 8); - - pkt.payload[11] = 0; // airspeed MAX - - pkt.payload[12] = 0; // COM Port 0 baud, fixed at 57600 - pkt.payload[13] = 0; // COM Port 1 baud, fixed at 57600 - pkt.payload[14] = 0; // COM Port 2 baud, fixed at 57600 - - pkt.payload[15] = 1; // GPS from COM port 0 (this port) - pkt.payload[16] = 1; // GPS Integrity - - pkt.payload[17] = _frontend.out_state.cfg.emitterType / 8; // Emitter Set - pkt.payload[18] = _frontend.out_state.cfg.emitterType & 0x0F; // Emitter Type - - pkt.payload[19] = _frontend.out_state.cfg.lengthWidth; // Aircraft Size - - pkt.payload[20] = 0; // Altitude Encoder Offset - pkt.payload[21] = 0; // Altitude Encoder Offset - - pkt.payload[22] = 0x07; // ADSB In Control, enable reading everything - pkt.payload[23] = 30; // ADSB In Report max length COM Port 0 (this one) - pkt.payload[24] = 0; // ADSB In Report max length COM Port 1 - - send_msg(pkt); -} - -void AP_ADSB_Sagetech::send_msg_PreFlight() -{ - Packet_XP pkt {}; - - pkt.type = MsgType_XP::Preflight_Set; - pkt.id = 0; - pkt.payload_length = 10; - - memcpy(&pkt.payload[0], &_frontend.out_state.cfg.callsign, 8); - - memset(&pkt.payload[8], 0, 2); - - send_msg(pkt); -} - -void AP_ADSB_Sagetech::send_msg_Operating() -{ - Packet_XP pkt {}; - - pkt.type = MsgType_XP::Operating_Set; - pkt.id = 0; - pkt.payload_length = 8; - - // squawk - // param is saved as native octal so we need convert back to - // decimal because Sagetech will convert it back to octal - uint16_t squawk = convert_base_to_decimal(8, last_operating_squawk); - put_le16_ptr(&pkt.payload[0], squawk); - - // altitude - if (_frontend.out_state.cfg.rf_capable & 0x01) { - const float alt_meters = last_operating_alt * 0.01f; - const int32_t alt_feet = (int32_t)(alt_meters * FEET_TO_METERS); - const int16_t alt_feet_adj = (alt_feet + 50) / 100; // 1 = 100 feet, 1 = 149 feet, 5 = 500 feet - put_le16_ptr(&pkt.payload[2], alt_feet_adj); - - } else { - // use integrated altitude - recommend by sagetech - pkt.payload[2] = 0x80; - pkt.payload[3] = 0x00; - } - - // RF mode - pkt.payload[4] = last_operating_rf_select; - send_msg(pkt); -} - -void AP_ADSB_Sagetech::send_msg_GPS() -{ - Packet_XP pkt {}; - - pkt.type = MsgType_XP::GPS_Set; - pkt.payload_length = 52; - pkt.id = 0; - - const int32_t longitude = _frontend._my_loc.lng; - const int32_t latitude = _frontend._my_loc.lat; - - // longitude and latitude - // NOTE: these MUST be done in double or else we get roundoff in the maths - const double lon_deg = longitude * (double)1.0e-7 * (longitude < 0 ? -1 : 1); - const double lon_minutes = (lon_deg - int(lon_deg)) * 60; - snprintf((char*)&pkt.payload[0], 12, "%03u%02u.%05u", (unsigned)lon_deg, (unsigned)lon_minutes, unsigned((lon_minutes - (int)lon_minutes) * 1.0E5)); - - const double lat_deg = latitude * (double)1.0e-7 * (latitude < 0 ? -1 : 1); - const double lat_minutes = (lat_deg - int(lat_deg)) * 60; - snprintf((char*)&pkt.payload[11], 11, "%02u%02u.%05u", (unsigned)lat_deg, (unsigned)lat_minutes, unsigned((lat_minutes - (int)lat_minutes) * 1.0E5)); - - // ground speed - const Vector2f speed = AP::ahrs().groundspeed_vector(); - float speed_knots = speed.length() * M_PER_SEC_TO_KNOTS; - snprintf((char*)&pkt.payload[21], 7, "%03u.%02u", (unsigned)speed_knots, unsigned((speed_knots - (int)speed_knots) * 1.0E2)); - - // heading - float heading = wrap_360(degrees(speed.angle())); - snprintf((char*)&pkt.payload[27], 10, "%03u.%04u", unsigned(heading), unsigned((heading - (int)heading) * 1.0E4)); - - // hemisphere - uint8_t hemisphere = 0; - hemisphere |= (latitude >= 0) ? 0x01 : 0; // isNorth - hemisphere |= (longitude >= 0) ? 0x02 : 0; // isEast - hemisphere |= (AP::gps().status() < AP_GPS::GPS_OK_FIX_2D) ? 0x80 : 0; // isInvalid - pkt.payload[35] = hemisphere; - - // time - uint64_t time_usec; - if (AP::rtc().get_utc_usec(time_usec)) { - // not completely accurate, our time includes leap seconds and time_t should be without - const time_t time_sec = time_usec / 1000000; - struct tm* tm = gmtime(&time_sec); - - // format time string - snprintf((char*)&pkt.payload[36], 11, "%02u%02u%06.3f", tm->tm_hour, tm->tm_min, tm->tm_sec + (time_usec % 1000000) * 1.0e-6); - } else { - memset(&pkt.payload[36],' ', 10); - } - - send_msg(pkt); -} - -/* - * Convert base 8 or 16 to decimal. Used to convert an octal/hexadecimal value stored on a GCS as a string field in different format, but then transmitted over mavlink as a float which is always a decimal. - * baseIn: base of input number - * inputNumber: value currently in base "baseIn" to be converted to base "baseOut" - * - * Example: convert ADSB squawk octal "1200" stored in memory as 0x0280 to 0x04B0 - * uint16_t squawk_decimal = convertMathBase(8, squawk_octal); - */ -uint32_t AP_ADSB_Sagetech::convert_base_to_decimal(const uint8_t baseIn, uint32_t inputNumber) -{ - // Our only sensible input bases are 16 and 8 - if (baseIn != 8 && baseIn != 16) { - return inputNumber; - } - - uint32_t outputNumber = 0; - for (uint8_t i=0; inputNumber != 0; i++) { - outputNumber += (inputNumber % 10) * powf(10, i); - inputNumber /= 10; - } - return outputNumber; -} - -#endif // HAL_ADSB_SAGETECH_ENABLED - +/* + Copyright (C) 2020 Kraus Hamdani Aerospace Inc. All rights reserved. + + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +#include "AP_ADSB_Sagetech.h" + +#if HAL_ADSB_SAGETECH_ENABLED +#include +#include +#include +#include +#include +#include +#include +#include + +#define SAGETECH_SCALER_LATLNG (1.0f/2.145767E-5f) // 180/(2^23) +#define SAGETECH_SCALER_KNOTS_TO_CMS ((KNOTS_TO_M_PER_SEC/0.125f) * 100.0f) +#define SAGETECH_SCALER_ALTITUDE (1.0f/0.015625f) +#define SAGETECH_SCALER_HEADING_CM ((360.0f/256.0f) * 100.0f) + +#define SAGETECH_VALIDFLAG_LATLNG (1U<<0) +#define SAGETECH_VALIDFLAG_ALTITUDE (1U<<1) +#define SAGETECH_VALIDFLAG_VELOCITY (1U<<2) +#define SAGETECH_VALIDFLAG_GND_SPEED (1U<<3) +#define SAGETECH_VALIDFLAG_HEADING (1U<<4) +#define SAGETECH_VALIDFLAG_V_RATE_GEO (1U<<5) +#define SAGETECH_VALIDFLAG_V_RATE_BARO (1U<<6) +#define SAGETECH_VALIDFLAG_EST_LATLNG (1U<<7) +#define SAGETECH_VALIDFLAG_EST_VELOCITY (1U<<8) + +// detect if any port is configured as Sagetech +bool AP_ADSB_Sagetech::detect() +{ + return AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_ADSB, 0); +} + +// Init, called once after class is constructed +bool AP_ADSB_Sagetech::init() +{ + _port = AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_ADSB, 0); + + return (_port != nullptr); +} + +void AP_ADSB_Sagetech::update() +{ + if (_port == nullptr) { + return; + } + + const uint32_t now_ms = AP_HAL::millis(); + + // ----------------------------- + // read any available data on serial port + // ----------------------------- + uint32_t nbytes = MIN(_port->available(), 10 * PAYLOAD_XP_MAX_SIZE); + while (nbytes-- > 0) { + const int16_t data = (uint8_t)_port->read(); + if (data < 0) { + break; + } + if (parse_byte_XP((uint8_t)data)) { + handle_packet_XP(message_in.packet); + } + } // while nbytes + + + // ----------------------------- + // handle timers for generating data + // ----------------------------- + if (!last_packet_initialize_ms || (now_ms - last_packet_initialize_ms >= 5000)) { + last_packet_initialize_ms = now_ms; + send_packet(MsgType_XP::Installation_Set); + + } else if (!last_packet_PreFlight_ms || (now_ms - last_packet_PreFlight_ms >= 8200)) { + last_packet_PreFlight_ms = now_ms; + // TODO: allow callsign to not require a reboot + send_packet(MsgType_XP::Preflight_Set); + + } else if (now_ms - last_packet_Operating_ms >= 1000 && ( + last_packet_Operating_ms == 0 || // send once at boot + // send as data changes + last_operating_squawk != _frontend.out_state.cfg.squawk_octal || + abs(last_operating_alt - _frontend._my_loc.alt) > 1555 || // 1493cm == 49ft. The output resolution is 100ft per bit + last_operating_rf_select != _frontend.out_state.cfg.rfSelect)) + { + last_packet_Operating_ms = now_ms; + last_operating_squawk = _frontend.out_state.cfg.squawk_octal; + last_operating_alt = _frontend._my_loc.alt; + last_operating_rf_select = _frontend.out_state.cfg.rfSelect; + send_packet(MsgType_XP::Operating_Set); + + } else if (now_ms - last_packet_GPS_ms >= (_frontend.out_state.is_flying ? 200 : 1000)) { + // 1Hz when not flying, 5Hz when flying + last_packet_GPS_ms = now_ms; + send_packet(MsgType_XP::GPS_Set); + } +} + +void AP_ADSB_Sagetech::send_packet(const MsgType_XP type) +{ + switch (type) { + case MsgType_XP::Installation_Set: + send_msg_Installation(); + break; + case MsgType_XP::Preflight_Set: + send_msg_PreFlight(); + break; + case MsgType_XP::Operating_Set: + send_msg_Operating(); + break; + case MsgType_XP::GPS_Set: + send_msg_GPS(); + break; + default: + break; + } +} + +void AP_ADSB_Sagetech::request_packet(const MsgType_XP type) +{ + // set all bytes in packet to 0 via {} so we only need to set the ones we need to + Packet_XP pkt {}; + + pkt.type = MsgType_XP::Request; + pkt.id = 0; + pkt.payload_length = 4; + + pkt.payload[0] = static_cast(type); + + send_msg(pkt); +} + + +void AP_ADSB_Sagetech::handle_packet_XP(const Packet_XP &msg) +{ + switch (msg.type) { + case MsgType_XP::ACK: + handle_ack(msg); + break; + + case MsgType_XP::Installation_Response: + case MsgType_XP::Preflight_Response: + case MsgType_XP::Status_Response: + // TODO add support for these + break; + + case MsgType_XP::ADSB_StateVector_Report: + case MsgType_XP::ADSB_ModeStatus_Report: + case MsgType_XP::TISB_StateVector_Report: + case MsgType_XP::TISB_ModeStatus_Report: + case MsgType_XP::TISB_CorasePos_Report: + case MsgType_XP::TISB_ADSB_Mgr_Report: + handle_adsb_in_msg(msg); + break; + + case MsgType_XP::Installation_Set: + case MsgType_XP::Preflight_Set: + case MsgType_XP::Operating_Set: + case MsgType_XP::GPS_Set: + case MsgType_XP::Request: + // these are out-bound only and are not expected to be received + case MsgType_XP::INVALID: + break; + } +} + +void AP_ADSB_Sagetech::handle_ack(const Packet_XP &msg) +{ + // ACK received! + const uint8_t system_state = msg.payload[2]; + transponder_type = (Transponder_Type)msg.payload[6]; + + const uint8_t prev_transponder_mode = last_ack_transponder_mode; + last_ack_transponder_mode = (system_state >> 6) & 0x03; + if (prev_transponder_mode != last_ack_transponder_mode) { + static const char *mode_names[] = {"OFF", "STBY", "ON", "ON-ALT"}; + if (last_ack_transponder_mode < ARRAY_SIZE(mode_names)) { + gcs().send_text(MAV_SEVERITY_INFO, "ADSB: RF Mode: %s", mode_names[last_ack_transponder_mode]); + } + } +} + +void AP_ADSB_Sagetech::handle_adsb_in_msg(const Packet_XP &msg) +{ + AP_ADSB::adsb_vehicle_t vehicle {}; + + vehicle.last_update_ms = AP_HAL::millis(); + + switch (msg.type) { + case MsgType_XP::ADSB_StateVector_Report: { // 0x91 + const uint16_t validFlags = le16toh_ptr(&msg.payload[8]); + vehicle.info.ICAO_address = le24toh_ptr(&msg.payload[10]); + + if (validFlags & SAGETECH_VALIDFLAG_LATLNG) { + vehicle.info.lat = ((int32_t)le24toh_ptr(&msg.payload[20])) * SAGETECH_SCALER_LATLNG; + vehicle.info.lon = ((int32_t)le24toh_ptr(&msg.payload[23])) * SAGETECH_SCALER_LATLNG; + vehicle.info.flags |= ADSB_FLAGS_VALID_COORDS; + } + + if (validFlags & SAGETECH_VALIDFLAG_ALTITUDE) { + vehicle.info.altitude = (int32_t)le24toh_ptr(&msg.payload[26]); + vehicle.info.flags |= ADSB_FLAGS_VALID_ALTITUDE; + } + + if (validFlags & SAGETECH_VALIDFLAG_VELOCITY) { + const float velNS = ((int32_t)le16toh_ptr(&msg.payload[29])) * SAGETECH_SCALER_KNOTS_TO_CMS; + const float velEW = ((int32_t)le16toh_ptr(&msg.payload[31])) * SAGETECH_SCALER_KNOTS_TO_CMS; + vehicle.info.hor_velocity = Vector2f(velEW, velNS).length(); + vehicle.info.flags |= ADSB_FLAGS_VALID_VELOCITY; + } + + if (validFlags & SAGETECH_VALIDFLAG_HEADING) { + vehicle.info.heading = ((float)msg.payload[29]) * SAGETECH_SCALER_HEADING_CM; + vehicle.info.flags |= ADSB_FLAGS_VALID_HEADING; + } + + if ((validFlags & SAGETECH_VALIDFLAG_V_RATE_GEO) || (validFlags & SAGETECH_VALIDFLAG_V_RATE_BARO)) { + vehicle.info.ver_velocity = (int16_t)le16toh_ptr(&msg.payload[38]); + vehicle.info.flags |= ADSB_FLAGS_VERTICAL_VELOCITY_VALID; + } + + _frontend.handle_adsb_vehicle(vehicle); + break; + } + case MsgType_XP::ADSB_ModeStatus_Report: // 0x92 + vehicle.info.ICAO_address = le24toh_ptr(&msg.payload[9]); + + if (msg.payload[16] != 0) { + // if string is non-null, consider it valid + memcpy(&vehicle.info, &msg.payload[16], 8); + vehicle.info.flags |= ADSB_FLAGS_VALID_CALLSIGN; + } + + _frontend.handle_adsb_vehicle(vehicle); + break; + case MsgType_XP::TISB_StateVector_Report: + case MsgType_XP::TISB_ModeStatus_Report: + case MsgType_XP::TISB_CorasePos_Report: + case MsgType_XP::TISB_ADSB_Mgr_Report: + // TODO + return; + + default: + return; + } + +} + +// handling inbound byte and process it in the state machine +// return true when a full packet has been received +bool AP_ADSB_Sagetech::parse_byte_XP(const uint8_t data) +{ + switch (message_in.state) { + default: + case ParseState::WaitingFor_Start: + if (data == 0xA5) { + message_in.state = ParseState::WaitingFor_AssmAddr; + } + break; + case ParseState::WaitingFor_AssmAddr: + message_in.state = (data == 0x01) ? ParseState::WaitingFor_MsgType : ParseState::WaitingFor_Start; + break; + case ParseState::WaitingFor_MsgType: + message_in.packet.type = static_cast(data); + message_in.state = ParseState::WaitingFor_MsgId; + break; + case ParseState::WaitingFor_MsgId: + message_in.packet.id = data; + message_in.state = ParseState::WaitingFor_PayloadLen; + break; + case ParseState::WaitingFor_PayloadLen: + message_in.packet.payload_length = data; + message_in.index = 0; + message_in.state = (data == 0) ? ParseState::WaitingFor_ChecksumFletcher : ParseState::WaitingFor_PayloadContents; + break; + + case ParseState::WaitingFor_PayloadContents: + message_in.packet.payload[message_in.index++] = data; + if (message_in.index >= message_in.packet.payload_length) { + message_in.state = ParseState::WaitingFor_ChecksumFletcher; + message_in.index = 0; + } + break; + + case ParseState::WaitingFor_ChecksumFletcher: + message_in.packet.checksumFletcher = data; + message_in.state = ParseState::WaitingFor_Checksum; + break; + case ParseState::WaitingFor_Checksum: + message_in.packet.checksum = data; + message_in.state = ParseState::WaitingFor_End; + if (checksum_verify_XP(message_in.packet)) { + handle_packet_XP(message_in.packet); + } + break; + + case ParseState::WaitingFor_End: + // we don't care if the end value matches + message_in.state = ParseState::WaitingFor_Start; + break; + } + return false; +} + +// compute Sum and FletcherSum values into a single value +// returns uint16_t with MSByte as Sum and LSByte FletcherSum +uint16_t AP_ADSB_Sagetech::checksum_generate_XP(Packet_XP &msg) const +{ + uint8_t sum = 0; + uint8_t sumFletcher = 0; + + const uint8_t header_message_format[5] { + 0xA5, // start + 0x01, // assembly address + static_cast(msg.type), + msg.id, + msg.payload_length + }; + + for (uint8_t i=0; i<5; i++) { + sum += header_message_format[i]; + sumFletcher += sum; + } + for (uint8_t i=0; i(msg.type), + msg.id, + msg.payload_length + }; + const uint8_t message_format_tail[3] { + msg.checksumFletcher, + msg.checksum, + 0x5A // end + }; + + if (_port != nullptr) { + _port->write(message_format_header, sizeof(message_format_header)); + _port->write(msg.payload, msg.payload_length); + _port->write(message_format_tail, sizeof(message_format_tail)); + } +} + +void AP_ADSB_Sagetech::send_msg_Installation() +{ + Packet_XP pkt {}; + + pkt.type = MsgType_XP::Installation_Set; + pkt.payload_length = 28; // 28== 0x1C + + // Mode C = 3, Mode S = 0 + pkt.id = (transponder_type == Transponder_Type::Mode_C) ? 3 : 0; + +// // convert a decimal 123456 to 0x123456 + // TODO: do a proper conversion. The param contains "131313" but what gets transmitted over the air is 0x200F1. + const uint32_t icao_hex = AP_ADSB::convert_base_to_decimal(16, _frontend.out_state.cfg.ICAO_id_param); + put_le24_ptr(&pkt.payload[0], icao_hex); + + memcpy(&pkt.payload[3], &_frontend.out_state.cfg.callsign, 8); + + pkt.payload[11] = 0; // airspeed MAX + + pkt.payload[12] = 0; // COM Port 0 baud, fixed at 57600 + pkt.payload[13] = 0; // COM Port 1 baud, fixed at 57600 + pkt.payload[14] = 0; // COM Port 2 baud, fixed at 57600 + + pkt.payload[15] = 1; // GPS from COM port 0 (this port) + pkt.payload[16] = 1; // GPS Integrity + + pkt.payload[17] = _frontend.out_state.cfg.emitterType / 8; // Emitter Set + pkt.payload[18] = _frontend.out_state.cfg.emitterType & 0x0F; // Emitter Type + + pkt.payload[19] = _frontend.out_state.cfg.lengthWidth; // Aircraft Size + + pkt.payload[20] = 0; // Altitude Encoder Offset + pkt.payload[21] = 0; // Altitude Encoder Offset + + pkt.payload[22] = 0x07; // ADSB In Control, enable reading everything + pkt.payload[23] = 30; // ADSB In Report max length COM Port 0 (this one) + pkt.payload[24] = 0; // ADSB In Report max length COM Port 1 + + send_msg(pkt); +} + +void AP_ADSB_Sagetech::send_msg_PreFlight() +{ + Packet_XP pkt {}; + + pkt.type = MsgType_XP::Preflight_Set; + pkt.id = 0; + pkt.payload_length = 10; + + memcpy(&pkt.payload[0], &_frontend.out_state.cfg.callsign, 8); + + memset(&pkt.payload[8], 0, 2); + + send_msg(pkt); +} + +void AP_ADSB_Sagetech::send_msg_Operating() +{ + Packet_XP pkt {}; + + pkt.type = MsgType_XP::Operating_Set; + pkt.id = 0; + pkt.payload_length = 8; + + // squawk + // param is saved as native octal so we need convert back to + // decimal because Sagetech will convert it back to octal + const uint16_t squawk = AP_ADSB::convert_base_to_decimal(8, last_operating_squawk); + put_le16_ptr(&pkt.payload[0], squawk); + + // altitude + if (_frontend.out_state.cfg.rf_capable & 0x01) { + const float alt_meters = last_operating_alt * 0.01f; + const int32_t alt_feet = (int32_t)(alt_meters * FEET_TO_METERS); + const int16_t alt_feet_adj = (alt_feet + 50) / 100; // 1 = 100 feet, 1 = 149 feet, 5 = 500 feet + put_le16_ptr(&pkt.payload[2], alt_feet_adj); + + } else { + // use integrated altitude - recommend by sagetech + pkt.payload[2] = 0x80; + pkt.payload[3] = 0x00; + } + + // RF mode + pkt.payload[4] = last_operating_rf_select; + send_msg(pkt); +} + +void AP_ADSB_Sagetech::send_msg_GPS() +{ + Packet_XP pkt {}; + + pkt.type = MsgType_XP::GPS_Set; + pkt.payload_length = 52; + pkt.id = 0; + + const int32_t longitude = _frontend._my_loc.lng; + const int32_t latitude = _frontend._my_loc.lat; + + // longitude and latitude + // NOTE: these MUST be done in double or else we get roundoff in the maths + const double lon_deg = longitude * (double)1.0e-7 * (longitude < 0 ? -1 : 1); + const double lon_minutes = (lon_deg - int(lon_deg)) * 60; + snprintf((char*)&pkt.payload[0], 12, "%03u%02u.%05u", (unsigned)lon_deg, (unsigned)lon_minutes, unsigned((lon_minutes - (int)lon_minutes) * 1.0E5)); + + const double lat_deg = latitude * (double)1.0e-7 * (latitude < 0 ? -1 : 1); + const double lat_minutes = (lat_deg - int(lat_deg)) * 60; + snprintf((char*)&pkt.payload[11], 11, "%02u%02u.%05u", (unsigned)lat_deg, (unsigned)lat_minutes, unsigned((lat_minutes - (int)lat_minutes) * 1.0E5)); + + // ground speed + const Vector2f speed = AP::ahrs().groundspeed_vector(); + float speed_knots = speed.length() * M_PER_SEC_TO_KNOTS; + snprintf((char*)&pkt.payload[21], 7, "%03u.%02u", (unsigned)speed_knots, unsigned((speed_knots - (int)speed_knots) * 1.0E2)); + + // heading + float heading = wrap_360(degrees(speed.angle())); + snprintf((char*)&pkt.payload[27], 10, "%03u.%04u", unsigned(heading), unsigned((heading - (int)heading) * 1.0E4)); + + // hemisphere + uint8_t hemisphere = 0; + hemisphere |= (latitude >= 0) ? 0x01 : 0; // isNorth + hemisphere |= (longitude >= 0) ? 0x02 : 0; // isEast + hemisphere |= (AP::gps().status() < AP_GPS::GPS_OK_FIX_2D) ? 0x80 : 0; // isInvalid + pkt.payload[35] = hemisphere; + + // time + uint64_t time_usec; + if (AP::rtc().get_utc_usec(time_usec)) { + // not completely accurate, our time includes leap seconds and time_t should be without + const time_t time_sec = time_usec / 1000000; + struct tm* tm = gmtime(&time_sec); + + // format time string + snprintf((char*)&pkt.payload[36], 11, "%02u%02u%06.3f", tm->tm_hour, tm->tm_min, tm->tm_sec + (time_usec % 1000000) * 1.0e-6); + } else { + memset(&pkt.payload[36],' ', 10); + } + + send_msg(pkt); +} + +#endif // HAL_ADSB_SAGETECH_ENABLED + diff --git a/libraries/AP_ADSB/AP_ADSB_Sagetech.h b/libraries/AP_ADSB/AP_ADSB_Sagetech.h index c295f7514e8..ee84f5260ea 100644 --- a/libraries/AP_ADSB/AP_ADSB_Sagetech.h +++ b/libraries/AP_ADSB/AP_ADSB_Sagetech.h @@ -1,161 +1,156 @@ -#pragma once - -/* - This program is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - This program is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with this program. If not, see . - */ - -#include "AP_ADSB_Backend.h" - -#ifndef HAL_ADSB_SAGETECH_ENABLED -#define HAL_ADSB_SAGETECH_ENABLED HAL_ADSB_ENABLED -#endif - -#if HAL_ADSB_SAGETECH_ENABLED -class AP_ADSB_Sagetech : public AP_ADSB_Backend { -public: - using AP_ADSB_Backend::AP_ADSB_Backend; - - // init - performs any required initialisation for this instance - bool init() override; - - // update - should be called periodically - void update() override; - - // static detection function - static bool detect(); - -private: - - static const uint32_t PAYLOAD_XP_MAX_SIZE = 52; - - enum class SystemStateBits { - Error_Transponder = (1U<<0), - Altitidue_Source = (1U<<1), - Error_GPS = (1U<<2), - Error_ICAO = (1U<<3), - Error_Over_Temperature = (1U<<4), - Error_Extended_Squitter = (1U<<5), - Mode_Transponder = (3U<<6), // 2 bit status: - }; - - enum class Transponder_Type { - Mode_C = 0x00, - Mode_S_ADSB_OUT = 0x01, - Mode_S_ADSB_OUT_and_IN = 0x02, - Unknown = 0xFF, - }; - - enum class MsgType_XP { - INVALID = 0, - Installation_Set = 0x01, - Preflight_Set = 0x02, - Operating_Set = 0x03, - GPS_Set = 0x04, - Request = 0x05, - - ACK = 0x80, - Installation_Response = 0x81, - Preflight_Response = 0x82, - Status_Response = 0x83, - ADSB_StateVector_Report = 0x91, - ADSB_ModeStatus_Report = 0x92, - TISB_StateVector_Report = 0x93, - TISB_ModeStatus_Report = 0x94, - TISB_CorasePos_Report = 0x95, - TISB_ADSB_Mgr_Report = 0x96, - }; - - enum class ParseState { - WaitingFor_Start, - WaitingFor_AssmAddr, - WaitingFor_MsgType, - WaitingFor_MsgId, - WaitingFor_PayloadLen, - WaitingFor_PayloadContents, - WaitingFor_ChecksumFletcher, - WaitingFor_Checksum, - WaitingFor_End, - }; - - struct Packet_XP { - const uint8_t start = 0xA5; - const uint8_t assemAddr = 0x01; - MsgType_XP type; - uint8_t id; - uint8_t payload_length; - uint8_t payload[PAYLOAD_XP_MAX_SIZE]; - uint8_t checksumFletcher; - uint8_t checksum; - const uint8_t end = 0x5A; - }; - - struct { - ParseState state; - uint8_t index; - Packet_XP packet; - } message_in; - - // compute Sum and FletcherSum values - uint16_t checksum_generate_XP(Packet_XP &msg) const; - bool checksum_verify_XP(Packet_XP &msg) const; - void checksum_assign_XP(Packet_XP &msg); - - - // handling inbound byte and process it in the state machine - bool parse_byte_XP(const uint8_t data); - - // handle inbound packet - void handle_packet_XP(const Packet_XP &msg); - - // send message to serial port - void send_msg(Packet_XP &msg); - - // handle inbound msgs - void handle_adsb_in_msg(const Packet_XP &msg); - void handle_ack(const Packet_XP &msg); - - // send messages to to transceiver - void send_msg_Installation(); - void send_msg_PreFlight(); - void send_msg_Operating(); - void send_msg_GPS(); - - // send packet by type - void send_packet(const MsgType_XP type); - - // send msg to request a packet by type - void request_packet(const MsgType_XP type); - - // Convert base 8 or 16 to decimal. Used to convert an octal/hexadecimal value - // stored on a GCS as a string field in different format, but then transmitted - // over mavlink as a float which is always a decimal. - uint32_t convert_base_to_decimal(const uint8_t baseIn, uint32_t inputNumber); - - // timers for each out-bound packet - uint32_t last_packet_initialize_ms; - uint32_t last_packet_PreFlight_ms; - uint32_t last_packet_GPS_ms; - uint32_t last_packet_Operating_ms; - - // cached variables to compare against params so we can send msg on param change. - uint16_t last_operating_squawk; - int32_t last_operating_alt; - uint8_t last_operating_rf_select; - - // track status changes in acks - uint8_t last_ack_transponder_mode; - Transponder_Type transponder_type = Transponder_Type::Unknown; -}; -#endif // HAL_ADSB_SAGETECH_ENABLED - +#pragma once + +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +#include "AP_ADSB_Backend.h" + +#ifndef HAL_ADSB_SAGETECH_ENABLED +#define HAL_ADSB_SAGETECH_ENABLED HAL_ADSB_ENABLED +#endif + +#if HAL_ADSB_SAGETECH_ENABLED +class AP_ADSB_Sagetech : public AP_ADSB_Backend { +public: + using AP_ADSB_Backend::AP_ADSB_Backend; + + // init - performs any required initialisation for this instance + bool init() override; + + // update - should be called periodically + void update() override; + + // static detection function + static bool detect(); + +private: + + static const uint32_t PAYLOAD_XP_MAX_SIZE = 52; + + enum class SystemStateBits { + Error_Transponder = (1U<<0), + Altitidue_Source = (1U<<1), + Error_GPS = (1U<<2), + Error_ICAO = (1U<<3), + Error_Over_Temperature = (1U<<4), + Error_Extended_Squitter = (1U<<5), + Mode_Transponder = (3U<<6), // 2 bit status: + }; + + enum class Transponder_Type { + Mode_C = 0x00, + Mode_S_ADSB_OUT = 0x01, + Mode_S_ADSB_OUT_and_IN = 0x02, + Unknown = 0xFF, + }; + + enum class MsgType_XP { + INVALID = 0, + Installation_Set = 0x01, + Preflight_Set = 0x02, + Operating_Set = 0x03, + GPS_Set = 0x04, + Request = 0x05, + + ACK = 0x80, + Installation_Response = 0x81, + Preflight_Response = 0x82, + Status_Response = 0x83, + ADSB_StateVector_Report = 0x91, + ADSB_ModeStatus_Report = 0x92, + TISB_StateVector_Report = 0x93, + TISB_ModeStatus_Report = 0x94, + TISB_CorasePos_Report = 0x95, + TISB_ADSB_Mgr_Report = 0x96, + }; + + enum class ParseState { + WaitingFor_Start, + WaitingFor_AssmAddr, + WaitingFor_MsgType, + WaitingFor_MsgId, + WaitingFor_PayloadLen, + WaitingFor_PayloadContents, + WaitingFor_ChecksumFletcher, + WaitingFor_Checksum, + WaitingFor_End, + }; + + struct Packet_XP { + const uint8_t start = 0xA5; + const uint8_t assemAddr = 0x01; + MsgType_XP type; + uint8_t id; + uint8_t payload_length; + uint8_t payload[PAYLOAD_XP_MAX_SIZE]; + uint8_t checksumFletcher; + uint8_t checksum; + const uint8_t end = 0x5A; + }; + + struct { + ParseState state; + uint8_t index; + Packet_XP packet; + } message_in; + + // compute Sum and FletcherSum values + uint16_t checksum_generate_XP(Packet_XP &msg) const; + bool checksum_verify_XP(Packet_XP &msg) const; + void checksum_assign_XP(Packet_XP &msg); + + + // handling inbound byte and process it in the state machine + bool parse_byte_XP(const uint8_t data); + + // handle inbound packet + void handle_packet_XP(const Packet_XP &msg); + + // send message to serial port + void send_msg(Packet_XP &msg); + + // handle inbound msgs + void handle_adsb_in_msg(const Packet_XP &msg); + void handle_ack(const Packet_XP &msg); + + // send messages to transceiver + void send_msg_Installation(); + void send_msg_PreFlight(); + void send_msg_Operating(); + void send_msg_GPS(); + + // send packet by type + void send_packet(const MsgType_XP type); + + // send msg to request a packet by type + void request_packet(const MsgType_XP type); + + // timers for each out-bound packet + uint32_t last_packet_initialize_ms; + uint32_t last_packet_PreFlight_ms; + uint32_t last_packet_GPS_ms; + uint32_t last_packet_Operating_ms; + + // cached variables to compare against params so we can send msg on param change. + uint16_t last_operating_squawk; + int32_t last_operating_alt; + uint8_t last_operating_rf_select; + + // track status changes in acks + uint8_t last_ack_transponder_mode; + Transponder_Type transponder_type = Transponder_Type::Unknown; +}; +#endif // HAL_ADSB_SAGETECH_ENABLED + diff --git a/libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.cpp b/libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.cpp new file mode 100644 index 00000000000..2cc0544b028 --- /dev/null +++ b/libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.cpp @@ -0,0 +1,786 @@ +/* + * Copyright (C) 2022 Sagetech Avionics Inc. All rights reserved. + * + * This file is free software: you can redistribute it and/or modify it + * under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program. If not, see . + * + * SDK specification + * https://github.com/Sagetech-Avionics/sagetech-mxs-sdk/blob/main/doc/pdf/ICD02373_MXS_Host_ICD.pdf + * + * Authors: Chuck Faber, Tom Pittenger +*/ + + +#include "AP_ADSB_Sagetech_MXS.h" + +#if HAL_ADSB_SAGETECH_MXS_ENABLED +#include +#include +#include +#include +#include +#include + +#define SAGETECH_USE_MXS_SDK !APM_BUILD_TYPE(APM_BUILD_UNKNOWN) + +#define MXS_INIT_TIMEOUT 20000 + +#define SAGETECH_SCALE_CM_TO_FEET (0.0328084f) +#define SAGETECH_SCALE_FEET_TO_MM (304.8f) +#define SAGETECH_SCALE_KNOTS_TO_CM_PER_SEC (51.4444f) +#define SAGETECH_SCALE_FT_PER_MIN_TO_CM_PER_SEC (0.508f) +#define SAGETECH_SCALE_M_PER_SEC_TO_FT_PER_MIN (196.85f) +#define CLIMB_RATE_LIMIT 16448 + +#define SAGETECH_INSTALL_MSG_RATE 5000 +#define SAGETECH_OPERATING_MSG_RATE 1000 +#define SAGETECH_FLIGHT_ID_MSG_RATE 8200 +#define SAGETECH_GPS_MSG_RATE_FLYING 200 +#define SAGETECH_GPS_MSG_RATE_GROUNDED 1000 +#define SAGETECH_TARGETREQ_MSG_RATE 1000 +#define SAGETECH_HFOM_UNKNOWN (19000.0f) +#define SAGETECH_VFOM_UNKNOWN (151.0f) +#define SAGETECH_HPL_UNKNOWN (38000.0f) + +bool AP_ADSB_Sagetech_MXS::detect() +{ + return AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_ADSB, 0); +} + + +bool AP_ADSB_Sagetech_MXS::init() +{ + _port = AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_ADSB, 0); + if (_port == nullptr) { + return false; + } + return true; +} + +void AP_ADSB_Sagetech_MXS::update() +{ + if (_port == nullptr) { + return; + } + + // ----------------------------- + // read any available data on serial port + // ----------------------------- + uint32_t nbytes = MIN(_port->available(), 10 * PAYLOAD_MXS_MAX_SIZE); + while (nbytes-- > 0) { + const int16_t data = _port->read(); + if (data < 0) { + break; + } + parse_byte((uint8_t)data); + } + + const uint32_t now_ms = AP_HAL::millis(); + + // ----------------------------- + // handle timers for generating data + // ----------------------------- + if (!mxs_state.init) { + if (!last.packet_initialize_ms || (now_ms - last.packet_initialize_ms >= SAGETECH_INSTALL_MSG_RATE)) { + last.packet_initialize_ms = now_ms; + + if (_frontend._options & uint32_t(AP_ADSB::AdsbOption::SagteTech_MXS_External_Config)) { + // request the device's configuration + send_data_req(dataInstall); + + } else { + // auto configure based on autopilot's saved parameters + auto_config_operating(); + auto_config_installation(); + auto_config_flightid(); + send_targetreq_msg(); + _frontend.out_state.cfg.rf_capable.set_and_notify(rf_capable_flags_default); // Set the RF Capability to 1090ES TX and RX + mxs_state.init = true; + } + + } else if (last.packet_initialize_ms > MXS_INIT_TIMEOUT && !mxs_state.init_failed) { + gcs().send_text(MAV_SEVERITY_CRITICAL, "ADSB Sagetech MXS: Initialization Timeout. Failed to initialize."); + mxs_state.init_failed = true; + } + + // before init is done, don't run any other update() tasks + return; + } + + if ((now_ms - last.packet_initialize_ms >= SAGETECH_INSTALL_MSG_RATE) && + (mxs_state.inst.icao != (uint32_t)_frontend.out_state.cfg.ICAO_id_param.get() || + mxs_state.inst.emitter != convert_emitter_type_to_sg(_frontend.out_state.cfg.emitterType.get()) || + mxs_state.inst.size != _frontend.out_state.cfg.lengthWidth.get() || + mxs_state.inst.maxSpeed != convert_airspeed_knots_to_sg(_frontend.out_state.cfg.maxAircraftSpeed_knots) + )) { + last.packet_initialize_ms = now_ms; + send_install_msg(); + + } else if (!last.packet_PreFlight_ms || (now_ms - last.packet_PreFlight_ms >= SAGETECH_FLIGHT_ID_MSG_RATE)) { + last.packet_PreFlight_ms = now_ms; + send_flight_id_msg(); + + } else if (!last.packet_Operating_ms || // Send once at boot + now_ms - last.packet_Operating_ms >= SAGETECH_OPERATING_MSG_RATE || // Send Operating Message every second + last.operating_squawk != _frontend.out_state.ctrl.squawkCode || // Or anytime Operating data changes + last.operating_squawk != _frontend.out_state.cfg.squawk_octal || + abs(last.operating_alt - _frontend._my_loc.alt) > 1555 || // 1493cm == 49ft. The output resolution is 100ft per bit + last.operating_rf_select != _frontend.out_state.cfg.rfSelect || // The following booleans control the MXS OpMode + last.modeAEnabled != _frontend.out_state.ctrl.modeAEnabled || + last.modeCEnabled != _frontend.out_state.ctrl.modeCEnabled || + last.modeSEnabled != _frontend.out_state.ctrl.modeSEnabled + ) { + + if (last.operating_squawk != _frontend.out_state.ctrl.squawkCode) { + last.operating_squawk = _frontend.out_state.ctrl.squawkCode; + _frontend.out_state.cfg.squawk_octal_param.set_and_notify(last.operating_squawk); + } else if (last.operating_squawk != _frontend.out_state.cfg.squawk_octal) { + last.operating_squawk = _frontend.out_state.cfg.squawk_octal; + _frontend.out_state.ctrl.squawkCode = last.operating_squawk; + } + last.operating_rf_select = _frontend.out_state.cfg.rfSelect; + last.modeAEnabled = _frontend.out_state.ctrl.modeAEnabled; + last.modeCEnabled = _frontend.out_state.ctrl.modeCEnabled; + last.modeSEnabled = _frontend.out_state.ctrl.modeSEnabled; + + last.operating_alt = _frontend._my_loc.alt; + last.packet_Operating_ms = now_ms; + send_operating_msg(); + + } else if (now_ms - last.packet_GPS_ms >= (_frontend.out_state.is_flying ? SAGETECH_GPS_MSG_RATE_FLYING : SAGETECH_GPS_MSG_RATE_GROUNDED)) { + last.packet_GPS_ms = now_ms; + send_gps_msg(); + + } else if ((now_ms - last.packet_targetReq >= SAGETECH_TARGETREQ_MSG_RATE) && + ((mxs_state.treq.icao != (uint32_t)_frontend._special_ICAO_target) || (mxs_state.treq.maxTargets != (uint16_t)_frontend.in_state.list_size_param))) { + send_targetreq_msg(); + } +} + +void AP_ADSB_Sagetech_MXS::handle_packet(const Packet &msg) +{ +#if SAGETECH_USE_MXS_SDK + switch (msg.type) { + case MsgType::ACK: + if(sgDecodeAck((uint8_t*) &msg, &mxs_state.ack)) { + handle_ack(mxs_state.ack); + } + break; + + case MsgType::Installation_Response: + if (!mxs_state.init && sgDecodeInstall((uint8_t*)&msg, &mxs_state.inst)) { + // If not doing auto-config, get the current configuration of the MXS + // Fill out configuration parameters with preconfigured values + if (mxs_state.ack.opMode == modeOff) { // If the last ACK showed an OFF state, turn off all rfSelect bits. + _frontend.out_state.cfg.rfSelect.set_and_notify(0); + } else if (mxs_state.ack.opMode == modeStby) { + _frontend.out_state.ctrl.modeAEnabled = false; + _frontend.out_state.ctrl.modeCEnabled = false; + _frontend.out_state.ctrl.modeSEnabled = false; + _frontend.out_state.ctrl.es1090TxEnabled = false; + } else if (mxs_state.ack.opMode == modeOn) { + _frontend.out_state.ctrl.modeAEnabled = true; + _frontend.out_state.ctrl.modeCEnabled = false; + _frontend.out_state.ctrl.modeSEnabled = true; + _frontend.out_state.ctrl.es1090TxEnabled = true; + } else if (mxs_state.ack.opMode == modeAlt) { + _frontend.out_state.ctrl.modeAEnabled = true; + _frontend.out_state.ctrl.modeCEnabled = true; + _frontend.out_state.ctrl.modeSEnabled = true; + _frontend.out_state.ctrl.es1090TxEnabled = true; + } + _frontend.out_state.cfg.ICAO_id_param.set_and_notify(mxs_state.inst.icao); + _frontend.out_state.cfg.lengthWidth.set_and_notify(mxs_state.inst.size); + _frontend.out_state.cfg.emitterType.set_and_notify(convert_sg_emitter_type_to_adsb(mxs_state.inst.emitter)); + + _frontend.out_state.cfg.rf_capable.set_and_notify(rf_capable_flags_default); // Set the RF Capability to UAT and 1090ES TX and RX + + mxs_state.init = true; + } + break; + + case MsgType::FlightID_Response: { + sg_flightid_t flightId {}; + if (sgDecodeFlightId((uint8_t*) &msg, &flightId)) { + _frontend.set_callsign(flightId.flightId, false); + } + break; + } + + // ADSB Messages + case MsgType::ADSB_StateVector_Report: { + sg_svr_t svr {}; + if (sgDecodeSVR((uint8_t*) &msg, &svr)) { + handle_svr(svr); + } + break; + } + + case MsgType::ADSB_ModeStatus_Report: { + sg_msr_t msr {}; + if (sgDecodeMSR((uint8_t*) &msg, &msr)) { + handle_msr(msr); + } + break; + } + + case MsgType::Data_Request: + case MsgType::Target_Request: + case MsgType::Mode: + case MsgType::Installation: + case MsgType::FlightID: + case MsgType::Operating: + case MsgType::GPS_Data: + case MsgType::Status_Response: + case MsgType::Version_Response: + case MsgType::Serial_Number_Response: + case MsgType::Mode_Settings: + case MsgType::Target_Summary_Report: + case MsgType::RESERVED_0x84: + case MsgType::RESERVED_0x85: + case MsgType::RESERVED_0x8D: + case MsgType::ADSB_Target_State_Report: + case MsgType::ADSB_Air_Ref_Vel_Report: + // unhandled or intended for out-bound only + break; + } +#endif // SAGETECH_USE_MXS_SDK +} + +bool AP_ADSB_Sagetech_MXS::parse_byte(const uint8_t data) +{ + switch (message_in.state) { + default: + case ParseState::WaitingFor_Start: + if (data == START_BYTE) { + message_in.checksum = data; // initialize checksum here + message_in.state = ParseState::WaitingFor_MsgType; + } + break; + case ParseState::WaitingFor_MsgType: + message_in.checksum += data; + message_in.packet.type = static_cast(data); + message_in.state = ParseState::WaitingFor_MsgId; + break; + case ParseState::WaitingFor_MsgId: + message_in.checksum += data; + message_in.packet.id = data; + message_in.state = ParseState::WaitingFor_PayloadLen; + break; + case ParseState::WaitingFor_PayloadLen: + message_in.checksum += data; + message_in.packet.payload_length = data; + message_in.index = 0; + message_in.state = (data == 0) ? ParseState::WaitingFor_Checksum : ParseState::WaitingFor_PayloadContents; + break; + case ParseState::WaitingFor_PayloadContents: + message_in.checksum += data; + message_in.packet.payload[message_in.index++] = data; + if (message_in.index >= message_in.packet.payload_length) { + message_in.state = ParseState::WaitingFor_Checksum; + } + break; + case ParseState::WaitingFor_Checksum: + message_in.state = ParseState::WaitingFor_Start; + if (message_in.checksum == data) { + // append the checksum to the payload and zero out the payload index + message_in.packet.payload[message_in.index] = data; + message_in.index = 0; + handle_packet(message_in.packet); + } + break; + } + return false; +} + +void AP_ADSB_Sagetech_MXS::msg_write(const uint8_t *data, const uint16_t len) const +{ + if (_port != nullptr) { + _port->write(data, len); + } +} + +void AP_ADSB_Sagetech_MXS::auto_config_operating() +{ +// Configure the Default Operation Message Data + mxs_state.op.squawk = AP_ADSB::convert_base_to_decimal(8, _frontend.out_state.cfg.squawk_octal); + mxs_state.op.opMode = sg_op_mode_t::modeOff; // MXS needs to start in OFF mode to accept installation message + mxs_state.op.savePowerUp = true; // Save power-up state in non-volatile + mxs_state.op.enableSqt = true; // Enable extended squitters + mxs_state.op.enableXBit = false; // Enable the x-bit + mxs_state.op.milEmergency = false; // Broadcast a military emergency + mxs_state.op.emergcType = (sg_emergc_t)_frontend.out_state.ctrl.emergencyState; // Enumerated civilian emergency type + + mxs_state.op.altUseIntrnl = true; // True = Report altitude from internal pressure sensor (will ignore other bits in the field) + mxs_state.op.altHostAvlbl = false; + mxs_state.op.altRes25 = !mxs_state.inst.altRes100; // Host Altitude Resolution from install + + int32_t height; + if (_frontend._my_loc.initialised() && _frontend._my_loc.get_alt_cm(Location::AltFrame::ABSOLUTE, height)) { + mxs_state.op.altitude = height * SAGETECH_SCALE_CM_TO_FEET; // Height above sealevel in feet + } else { + mxs_state.op.altitude = 0; + } + + mxs_state.op.identOn = false; + + float vertRate; + if (AP::ahrs().get_vert_pos_rate(vertRate)) { + mxs_state.op.climbRate = vertRate * SAGETECH_SCALE_M_PER_SEC_TO_FT_PER_MIN; + mxs_state.op.climbValid = true; + } else { + mxs_state.op.climbValid = false; + mxs_state.op.climbRate = -CLIMB_RATE_LIMIT; + } + + const Vector2f speed = AP::ahrs().groundspeed_vector(); + if (!speed.is_nan() && !speed.is_zero()) { + mxs_state.op.headingValid = true; + mxs_state.op.airspdValid = true; + } else { + mxs_state.op.headingValid = false; + mxs_state.op.airspdValid = false; + } + const uint16_t speed_knots = speed.length() * M_PER_SEC_TO_KNOTS; + double heading = wrap_360(degrees(speed.angle())); + mxs_state.op.airspd = speed_knots; + mxs_state.op.heading = heading; + + last.msg.type = SG_MSG_TYPE_HOST_OPMSG; + +#if SAGETECH_USE_MXS_SDK + uint8_t txComBuffer[SG_MSG_LEN_OPMSG] {}; + sgEncodeOperating(txComBuffer, &mxs_state.op, ++last.msg.id); + msg_write(txComBuffer, SG_MSG_LEN_OPMSG); +#endif +} + +void AP_ADSB_Sagetech_MXS::auto_config_installation() +{ + // Configure the Default Installation Message Data + mxs_state.inst.icao = (uint32_t) _frontend.out_state.cfg.ICAO_id_param; + snprintf(mxs_state.inst.reg, 8, "%-7s", "TEST01Z"); + + mxs_state.inst.com0 = sg_baud_t::baud230400; + mxs_state.inst.com1 = sg_baud_t::baud57600; + + mxs_state.inst.eth.ipAddress = 0; + mxs_state.inst.eth.subnetMask = 0; + mxs_state.inst.eth.portNumber = 0; + + mxs_state.inst.sil = sg_sil_t::silUnknown; + mxs_state.inst.sda = sg_sda_t::sdaUnknown; + mxs_state.inst.emitter = convert_emitter_type_to_sg(_frontend.out_state.cfg.emitterType.get()); + mxs_state.inst.size = (sg_size_t)_frontend.out_state.cfg.lengthWidth.get(); + mxs_state.inst.maxSpeed = convert_airspeed_knots_to_sg(_frontend.out_state.cfg.maxAircraftSpeed_knots); + mxs_state.inst.altOffset = 0; // Alt encoder offset is legacy field that should always be 0. + mxs_state.inst.antenna = sg_antenna_t::antBottom; + + mxs_state.inst.altRes100 = true; + mxs_state.inst.hdgTrueNorth = false; + mxs_state.inst.airspeedTrue = false; + mxs_state.inst.heater = true; // Heater should always be connected. + mxs_state.inst.wowConnected = true; + + last.msg.type = SG_MSG_TYPE_HOST_INSTALL; + +#if SAGETECH_USE_MXS_SDK + uint8_t txComBuffer[SG_MSG_LEN_INSTALL] {}; + sgEncodeInstall(txComBuffer, &mxs_state.inst, ++last.msg.id); + msg_write(txComBuffer, SG_MSG_LEN_INSTALL); +#endif +} + +void AP_ADSB_Sagetech_MXS::auto_config_flightid() +{ + if (!strlen(_frontend.out_state.cfg.callsign)) { + snprintf(mxs_state.fid.flightId, sizeof(mxs_state.fid.flightId), "%-8s", "TESTMXS0"); + } else { + snprintf(mxs_state.fid.flightId, sizeof(mxs_state.fid.flightId), "%-8s", _frontend.out_state.cfg.callsign); + } + last.msg.type = SG_MSG_TYPE_HOST_FLIGHT; + +#if SAGETECH_USE_MXS_SDK + uint8_t txComBuffer[SG_MSG_LEN_FLIGHT] {}; + sgEncodeFlightId(txComBuffer, &mxs_state.fid, ++last.msg.id); + msg_write(txComBuffer, SG_MSG_LEN_FLIGHT); +#endif +} + +void AP_ADSB_Sagetech_MXS::handle_ack(const sg_ack_t ack) +{ + if ((ack.ackId != last.msg.id) || (ack.ackType != last.msg.type)) { + // gcs().send_text(MAV_SEVERITY_WARNING, "ADSB Sagetech MXS: ACK: Message %d of type %02x not acknowledged.", last.msg.id, last.msg.type); + } + // System health + if (ack.failXpdr && !last.failXpdr) { + gcs().send_text(MAV_SEVERITY_WARNING, "ADSB Sagetech MXS: Transponder Failure"); + _frontend.out_state.tx_status.fault |= UAVIONIX_ADSB_OUT_STATUS_FAULT_TX_SYSTEM_FAIL; + } + if (ack.failSystem && !last.failSystem) { + gcs().send_text(MAV_SEVERITY_WARNING, "ADSB Sagetech MXS: System Failure"); + _frontend.out_state.tx_status.fault |= UAVIONIX_ADSB_OUT_STATUS_FAULT_TX_SYSTEM_FAIL; + } + last.failXpdr = ack.failXpdr; + last.failSystem = ack.failSystem; +} + +void AP_ADSB_Sagetech_MXS::handle_svr(const sg_svr_t svr) +{ + if (svr.addrType != svrAdrIcaoUnknown && svr.addrType != svrAdrIcao && svr.addrType != svrAdrIcaoSurface) { + // invalid icao + return; + } + + AP_ADSB::adsb_vehicle_t vehicle; + if (!_frontend.get_vehicle_by_ICAO(svr.addr, vehicle)) { + // new vehicle + memset(&vehicle, 0, sizeof(vehicle)); + vehicle.info.ICAO_address = svr.addr; + } + + vehicle.info.flags &= ~ADSB_FLAGS_VALID_SQUAWK; + + if (svr.validity.position) { + vehicle.info.lat = (int32_t) (svr.lat * 1e7); + vehicle.info.lon = (int32_t) (svr.lon * 1e7); + vehicle.info.flags |= ADSB_FLAGS_VALID_COORDS; + } + if (svr.validity.geoAlt) { + vehicle.info.altitude_type = ADSB_ALTITUDE_TYPE_GEOMETRIC; + vehicle.info.altitude = svr.airborne.geoAlt * SAGETECH_SCALE_FEET_TO_MM; // Convert from feet to mm + vehicle.info.flags |= ADSB_FLAGS_VALID_ALTITUDE; + } + if (svr.validity.baroAlt) { + vehicle.info.altitude_type = ADSB_ALTITUDE_TYPE_PRESSURE_QNH; + vehicle.info.altitude = svr.airborne.baroAlt * SAGETECH_SCALE_FEET_TO_MM; // Convert from feet to mm + vehicle.info.flags |= ADSB_FLAGS_VALID_ALTITUDE; + } + if (svr.validity.surfSpeed) { + vehicle.info.hor_velocity = svr.surface.speed * SAGETECH_SCALE_KNOTS_TO_CM_PER_SEC; // Convert from knots to cm/s + vehicle.info.flags |= ADSB_FLAGS_VALID_VELOCITY; + } + if (svr.validity.surfHeading) { + vehicle.info.heading = svr.surface.heading * 100; + vehicle.info.flags |= ADSB_FLAGS_VALID_HEADING; + } + if (svr.validity.airSpeed) { + vehicle.info.hor_velocity = svr.airborne.speed * SAGETECH_SCALE_KNOTS_TO_CM_PER_SEC; // Convert from knots to cm/s + vehicle.info.heading = svr.airborne.heading * 100; + vehicle.info.flags |= ADSB_FLAGS_VALID_VELOCITY; + vehicle.info.flags |= ADSB_FLAGS_VALID_HEADING; + } + if (svr.validity.geoVRate || svr.validity.baroVRate) { + vehicle.info.ver_velocity = svr.airborne.vrate * SAGETECH_SCALE_FT_PER_MIN_TO_CM_PER_SEC; // Convert from ft/min to cm/s + vehicle.info.flags |= ADSB_FLAGS_VERTICAL_VELOCITY_VALID; + } + + vehicle.last_update_ms = AP_HAL::millis(); + _frontend.handle_adsb_vehicle(vehicle); +} + +void AP_ADSB_Sagetech_MXS::handle_msr(const sg_msr_t msr) +{ + AP_ADSB::adsb_vehicle_t vehicle; + if (!_frontend.get_vehicle_by_ICAO(msr.addr, vehicle)) { + // new vehicle is not allowed here because we don't know the lat/lng + // yet and we don't allow lat/lng of (0,0) so it will get rejected anyway + return; + } + + if (strlen(msr.callsign)) { + snprintf(vehicle.info.callsign, sizeof(vehicle.info.callsign), "%-8s", msr.callsign); + vehicle.info.flags |= ADSB_FLAGS_VALID_CALLSIGN; + } else { + vehicle.info.flags &= ~ADSB_FLAGS_VALID_CALLSIGN; + } + + vehicle.last_update_ms = AP_HAL::millis(); + _frontend.handle_adsb_vehicle(vehicle); +} + +void AP_ADSB_Sagetech_MXS::send_data_req(const sg_datatype_t dataReqType) +{ + sg_datareq_t dataReq {}; + dataReq.reqType = dataReqType; + last.msg.type = SG_MSG_TYPE_HOST_DATAREQ; + +#if SAGETECH_USE_MXS_SDK + uint8_t txComBuffer[SG_MSG_LEN_DATAREQ] {}; + sgEncodeDataReq(txComBuffer, &dataReq, ++last.msg.id); + msg_write(txComBuffer, SG_MSG_LEN_DATAREQ); +#else + (void)dataReq; +#endif +} + +void AP_ADSB_Sagetech_MXS::send_install_msg() +{ + // MXS must be in OFF mode to change ICAO or Registration + if (mxs_state.op.opMode != modeOff) { + // gcs().send_text(MAV_SEVERITY_WARNING, "ADSB Sagetech MXS: unable to send installation data while not in OFF mode."); + return; + } + + mxs_state.inst.icao = (uint32_t)_frontend.out_state.cfg.ICAO_id_param.get(); + mxs_state.inst.emitter = convert_emitter_type_to_sg(_frontend.out_state.cfg.emitterType.get()); + mxs_state.inst.size = (sg_size_t)_frontend.out_state.cfg.lengthWidth.get(); + mxs_state.inst.maxSpeed = convert_airspeed_knots_to_sg(_frontend.out_state.cfg.maxAircraftSpeed_knots); + mxs_state.inst.antenna = sg_antenna_t::antBottom; + + last.msg.type = SG_MSG_TYPE_HOST_INSTALL; + +#if SAGETECH_USE_MXS_SDK + uint8_t txComBuffer[SG_MSG_LEN_INSTALL] {}; + sgEncodeInstall(txComBuffer, &mxs_state.inst, ++last.msg.id); + msg_write(txComBuffer, SG_MSG_LEN_INSTALL); +#endif +} + +void AP_ADSB_Sagetech_MXS::send_flight_id_msg() +{ + if (!strlen((char*) _frontend.out_state.ctrl.callsign)) { + return; + } + snprintf(mxs_state.fid.flightId, sizeof(mxs_state.fid.flightId), "%-8s", (char*) _frontend.out_state.ctrl.callsign); + + last.msg.type = SG_MSG_TYPE_HOST_FLIGHT; + +#if SAGETECH_USE_MXS_SDK + uint8_t txComBuffer[SG_MSG_LEN_FLIGHT] {}; + sgEncodeFlightId(txComBuffer, &mxs_state.fid, ++last.msg.id); + msg_write(txComBuffer, SG_MSG_LEN_FLIGHT); +#endif +} + +void AP_ADSB_Sagetech_MXS::send_operating_msg() +{ + if (!_frontend.out_state.ctrl.modeAEnabled && !_frontend.out_state.ctrl.modeCEnabled && + !_frontend.out_state.ctrl.modeSEnabled && !_frontend.out_state.ctrl.es1090TxEnabled) { + mxs_state.op.opMode = modeStby; + } + if (_frontend.out_state.ctrl.modeAEnabled && !_frontend.out_state.ctrl.modeCEnabled && + _frontend.out_state.ctrl.modeSEnabled && _frontend.out_state.ctrl.es1090TxEnabled) { + mxs_state.op.opMode = modeOn; + } + if (_frontend.out_state.ctrl.modeAEnabled && _frontend.out_state.ctrl.modeCEnabled && + _frontend.out_state.ctrl.modeSEnabled && _frontend.out_state.ctrl.es1090TxEnabled) { + mxs_state.op.opMode = modeAlt; + } + if ((_frontend.out_state.cfg.rfSelect & 1) == 0) { + mxs_state.op.opMode = modeOff; + } + + mxs_state.op.squawk = AP_ADSB::convert_base_to_decimal(8, last.operating_squawk); + mxs_state.op.emergcType = (sg_emergc_t) _frontend.out_state.ctrl.emergencyState; + + int32_t height; + if (_frontend._my_loc.initialised() && _frontend._my_loc.get_alt_cm(Location::AltFrame::ABSOLUTE, height)) { + mxs_state.op.altitude = height * SAGETECH_SCALE_CM_TO_FEET; // Height above sealevel in feet + } else { + mxs_state.op.altitude = 0; + } + + float vertRate; + if (AP::ahrs().get_vert_pos_rate(vertRate)) { + mxs_state.op.climbRate = vertRate * SAGETECH_SCALE_M_PER_SEC_TO_FT_PER_MIN; + mxs_state.op.climbValid = true; + } else { + mxs_state.op.climbValid = false; + mxs_state.op.climbRate = -CLIMB_RATE_LIMIT; + } + + const Vector2f speed = AP::ahrs().groundspeed_vector(); + if (!speed.is_nan() && !speed.is_zero()) { + mxs_state.op.headingValid = true; + mxs_state.op.airspdValid = true; + } else { + mxs_state.op.headingValid = false; + mxs_state.op.airspdValid = false; + } + const uint16_t speed_knots = (speed.length() * M_PER_SEC_TO_KNOTS); + const double heading = wrap_360(degrees(speed.angle())); + + mxs_state.op.airspd = speed_knots; + mxs_state.op.heading = heading; + + mxs_state.op.identOn = _frontend.out_state.ctrl.identActive; + _frontend.out_state.ctrl.identActive = false; // only send identButtonActive once per request + + last.msg.type = SG_MSG_TYPE_HOST_OPMSG; + +#if SAGETECH_USE_MXS_SDK + uint8_t txComBuffer[SG_MSG_LEN_OPMSG] {}; + sgEncodeOperating(txComBuffer, &mxs_state.op, ++last.msg.id); + msg_write(txComBuffer, SG_MSG_LEN_OPMSG); +#endif +} + +void AP_ADSB_Sagetech_MXS::send_gps_msg() +{ + sg_gps_t gps {}; + const AP_GPS &ap_gps = AP::gps(); + float hAcc, vAcc, velAcc; + + gps.hpl = SAGETECH_HPL_UNKNOWN; // HPL over 37,040m means unknown + gps.hfom = ap_gps.horizontal_accuracy(hAcc) ? hAcc : SAGETECH_HFOM_UNKNOWN; // HFOM over 18,520 specifies unknown + gps.vfom = ap_gps.vertical_accuracy(vAcc) ? vAcc : SAGETECH_VFOM_UNKNOWN; // VFOM over 150 specifies unknown + gps.nacv = sg_nacv_t::nacvUnknown; + if (ap_gps.speed_accuracy(velAcc)) { + if (velAcc >= 10.0 || velAcc < 0) { + gps.nacv = sg_nacv_t::nacvUnknown; + } + else if (velAcc >= 3.0) { + gps.nacv = sg_nacv_t::nacv10dot0; + } + else if (velAcc >= 1.0) { + gps.nacv = sg_nacv_t::nacv3dot0; + } + else if (velAcc >= 0.3) { + gps.nacv = sg_nacv_t::nacv1dot0; + } + else { //if (velAcc >= 0.0) + gps.nacv = sg_nacv_t::nacv0dot3; + } + } + + // Get Vehicle Longitude and Latitude and Convert to string + const int32_t longitude = _frontend._my_loc.lng; + const int32_t latitude = _frontend._my_loc.lat; + const double lon_deg = longitude * (double)1.0e-7 * (longitude < 0 ? -1 : 1); + const double lon_minutes = (lon_deg - int(lon_deg)) * 60; + snprintf((char*)&gps.longitude, 12, "%03u%02u.%05u", (unsigned)lon_deg, (unsigned)lon_minutes, unsigned((lon_minutes - (int)lon_minutes) * 1.0E5)); + + const double lat_deg = latitude * (double)1.0e-7 * (latitude < 0 ? -1 : 1); + const double lat_minutes = (lat_deg - int(lat_deg)) * 60; + snprintf((char*)&gps.latitude, 11, "%02u%02u.%05u", (unsigned)lat_deg, (unsigned)lat_minutes, unsigned((lat_minutes - (int)lat_minutes) * 1.0E5)); + + const Vector2f speed = AP::ahrs().groundspeed_vector(); + const float speed_knots = speed.length() * M_PER_SEC_TO_KNOTS; + snprintf((char*)&gps.grdSpeed, 7, "%03u.%02u", (unsigned)speed_knots, unsigned((speed_knots - (int)speed_knots) * 1.0E2)); + + const float heading = wrap_360(degrees(speed.angle())); + snprintf((char*)&gps.grdTrack, 9, "%03u.%04u", unsigned(heading), unsigned((heading - (int)heading) * 1.0E4)); + + + gps.latNorth = (latitude >= 0 ? true: false); + gps.lngEast = (longitude >= 0 ? true: false); + + gps.gpsValid = (AP::gps().status() < AP_GPS::GPS_OK_FIX_2D) ? false : true; // If the status is not OK, gpsValid is false. + + uint64_t time_usec; + if (AP::rtc().get_utc_usec(time_usec)) { + const time_t time_sec = time_usec * 1E-6; + struct tm* tm = gmtime(&time_sec); + + snprintf((char*)&gps.timeOfFix, 11, "%02u%02u%06.3f", tm->tm_hour, tm->tm_min, tm->tm_sec + (time_usec % 1000000) * 1.0e-6); + } else { + strncpy(gps.timeOfFix, " . ", 11); + } + + int32_t height; + if (_frontend._my_loc.initialised() && _frontend._my_loc.get_alt_cm(Location::AltFrame::ABOVE_TERRAIN, height)) { + gps.height = height * 0.01; + } else { + gps.height = 0.0; + } + + last.msg.type = SG_MSG_TYPE_HOST_GPS; + +#if SAGETECH_USE_MXS_SDK + uint8_t txComBuffer[SG_MSG_LEN_GPS] {}; + sgEncodeGPS(txComBuffer, &gps, ++last.msg.id); + msg_write(txComBuffer, SG_MSG_LEN_GPS); +#else + (void)gps; +#endif +} + +void AP_ADSB_Sagetech_MXS::send_targetreq_msg() +{ + mxs_state.treq.reqType = sg_reporttype_t::reportAuto; + mxs_state.treq.transmitPort = sg_transmitport_t::transmitCom1; + mxs_state.treq.maxTargets = _frontend.in_state.list_size_param; + mxs_state.treq.icao = _frontend._special_ICAO_target.get(); + mxs_state.treq.stateVector = true; + mxs_state.treq.modeStatus = true; + mxs_state.treq.targetState = false; + mxs_state.treq.airRefVel = false; + mxs_state.treq.tisb = false; + mxs_state.treq.military = false; + mxs_state.treq.commA = false; + mxs_state.treq.ownship = true; + + last.msg.type = SG_MSG_TYPE_HOST_TARGETREQ; + +#if SAGETECH_USE_MXS_SDK + uint8_t txComBuffer[SG_MSG_LEN_TARGETREQ] {}; + sgEncodeTargetReq(txComBuffer, &mxs_state.treq, ++last.msg.id); + msg_write(txComBuffer, SG_MSG_LEN_TARGETREQ); +#endif +} + +sg_emitter_t AP_ADSB_Sagetech_MXS::convert_emitter_type_to_sg(const uint8_t emitterType) const +{ + uint8_t result = SG_EMIT_OFFSET_D; + + if (emitterType < 8) { + result = emitterType; + } else if (emitterType < 13 && emitterType >= 8) { + result = (emitterType - 8) + SG_EMIT_OFFSET_B; + } else if (emitterType < 16 && emitterType >= 14) { + result = (emitterType - 14) + (SG_EMIT_OFFSET_B + 6); // Subtracting 14 because SG emitter types don't include the reserved state at value 13. + } else if (emitterType < 21 && emitterType >= 16) { + result = (emitterType - 16) + SG_EMIT_OFFSET_C; + } + return (sg_emitter_t)result; +} + +uint8_t AP_ADSB_Sagetech_MXS::convert_sg_emitter_type_to_adsb(const sg_emitter_t sgEmitterType) const +{ + if (sgEmitterType < SG_EMIT_OFFSET_B) { + return sgEmitterType; + } else if ((sgEmitterType < (SG_EMIT_OFFSET_B + 6)) && (sgEmitterType >= SG_EMIT_OFFSET_B)) { + return (sgEmitterType - SG_EMIT_OFFSET_B) + 8; + } else if ((sgEmitterType < SG_EMIT_OFFSET_C) && (sgEmitterType >= SG_EMIT_OFFSET_B + 6)) { + return (sgEmitterType - (SG_EMIT_OFFSET_B + 6)) + 14; // Starts at UAV = 14 + } else if ((sgEmitterType < SG_EMIT_OFFSET_D) && (sgEmitterType >= SG_EMIT_OFFSET_C)) { + return (sgEmitterType - SG_EMIT_OFFSET_C) + 16; + } else { + return 0; + } +} + +sg_airspeed_t AP_ADSB_Sagetech_MXS::convert_airspeed_knots_to_sg(const float maxAirSpeed) const +{ + const int32_t airspeed = (int) maxAirSpeed; + + if (airspeed < 0) { + return sg_airspeed_t::speedUnknown; + } else if (airspeed < 75) { + return sg_airspeed_t::speed75kt; + } else if (airspeed < 150) { + return sg_airspeed_t::speed150kt; + } else if (airspeed < 300) { + return sg_airspeed_t::speed300kt; + } else if (airspeed < 600) { + return sg_airspeed_t::speed600kt; + } else if (airspeed < 1200) { + return sg_airspeed_t::speed1200kt; + } else { //if (airspeed >= 1200) + return sg_airspeed_t::speedGreater; + } +} + +#endif // HAL_ADSB_SAGETECH_MXS_ENABLED + diff --git a/libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.h b/libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.h new file mode 100644 index 00000000000..ec669cf39da --- /dev/null +++ b/libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.h @@ -0,0 +1,270 @@ +/* + * Copyright (C) 2022 Sagetech Avionics Inc. All rights reserved. + * + * This file is free software: you can redistribute it and/or modify it + * under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program. If not, see . + * + * SDK specification + * https://github.com/Sagetech-Avionics/sagetech-mxs-sdk/blob/main/doc/pdf/ICD02373_MXS_Host_ICD.pdf + * + * Authors: Chuck Faber, Tom Pittenger +*/ + +#pragma once + +#include "AP_ADSB_Backend.h" + +#ifndef HAL_ADSB_SAGETECH_MXS_ENABLED + // this feature is only enabled by default by select hardware + #define HAL_ADSB_SAGETECH_MXS_ENABLED HAL_ADSB_ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_SITL +#endif + +#if HAL_ADSB_SAGETECH_MXS_ENABLED + +#include "sagetech-sdk/sagetech_mxs.h" + +class AP_ADSB_Sagetech_MXS : public AP_ADSB_Backend { +public: + using AP_ADSB_Backend::AP_ADSB_Backend; + + /** + * @brief Performs required initialization for this instance + * + * @return true if initialization successful + */ + bool init() override; + + /** + * @brief The main callback function (Called with freq of 10Hz) that sends + * appropriate message types at specific times. + * + * Read Byte from Serial Port Buffer (10Hz) + * Send installation message (every 5 seconds) + * Send Flight ID (every 8.2 s) + * Send Operating Message (every second) + * Send GPS data (flying: 5Hz, not flying: 1Hz) + * + */ + void update() override; + + /** + * @brief Detect if a port is configured as Sagetech + * + * @return true + * @return false + */ + static bool detect(); + +private: + + static const uint32_t PAYLOAD_MXS_MAX_SIZE = 255; + static const uint8_t START_BYTE = 0xAA; + static const uint8_t rf_capable_flags_default = + ADSB_BITBASK_RF_CAPABILITIES_1090ES_IN | + ADSB_BITBASK_RF_CAPABILITIES_1090ES_OUT; + + + enum class MsgType : uint8_t { + Installation = SG_MSG_TYPE_HOST_INSTALL, + FlightID = SG_MSG_TYPE_HOST_FLIGHT, + Operating = SG_MSG_TYPE_HOST_OPMSG, + GPS_Data = SG_MSG_TYPE_HOST_GPS, + Data_Request = SG_MSG_TYPE_HOST_DATAREQ, + // RESERVED 0x06 - 0x0A + Target_Request = SG_MSG_TYPE_HOST_TARGETREQ, + Mode = SG_MSG_TYPE_HOST_MODE, + // RESERVED 0x0D - 0xC1 + ACK = SG_MSG_TYPE_XPNDR_ACK, + Installation_Response = SG_MSG_TYPE_XPNDR_INSTALL, + FlightID_Response = SG_MSG_TYPE_XPNDR_FLIGHT, + Status_Response = SG_MSG_TYPE_XPNDR_STATUS, + RESERVED_0x84 = 0x84, + RESERVED_0x85 = 0x85, + Mode_Settings = SG_MSG_TYPE_XPNDR_MODE, + RESERVED_0x8D = 0x8D, + Version_Response = SG_MSG_TYPE_XPNDR_VERSION, + Serial_Number_Response = SG_MSG_TYPE_XPNDR_SERIALNUM, + Target_Summary_Report = SG_MSG_TYPE_ADSB_TSUMMARY, + + ADSB_StateVector_Report = SG_MSG_TYPE_ADSB_SVR, + ADSB_ModeStatus_Report = SG_MSG_TYPE_ADSB_MSR, + ADSB_Target_State_Report= SG_MSG_TYPE_ADSB_TSTATE, + ADSB_Air_Ref_Vel_Report = SG_MSG_TYPE_ADSB_ARVR, + }; + + enum class ParseState { + WaitingFor_Start, + WaitingFor_MsgType, + WaitingFor_MsgId, + WaitingFor_PayloadLen, + WaitingFor_PayloadContents, + WaitingFor_Checksum, + }; + + struct __attribute__((packed)) Packet { + const uint8_t start = SG_MSG_START_BYTE; + MsgType type; + uint8_t id; + uint8_t payload_length; + uint8_t payload[PAYLOAD_MXS_MAX_SIZE]; + }; + + struct { + ParseState state; + uint8_t index; + Packet packet; + uint8_t checksum; + } message_in; + + /** + * @brief Given the dataReqType, send the appropriate data request message + * + * @param dataReqType + */ + void send_data_req(const sg_datatype_t dataReqType); + + /** + * @brief Takes incoming packets, gets their message type, and + * appropriately handles them with the correct callbacks. + * + * @param msg Message packet received, cast into Packet type. + */ + void handle_packet(const Packet &msg); + + /** + * @brief Sends data received from ADSB State Vector Report to AutoPilot + * + * @param svr + */ + void handle_svr(const sg_svr_t svr); + + /** + * @brief Handle a received ADSB mode status report and updates the vehicle list + * + * @param msr Sagetech SDK Mode Status Report type + */ + void handle_msr(const sg_msr_t msr); + + + /** + * @brief Handles an incoming byte and processes it through the state + * machine to determine if end of message is reached. + * + * @param data : incoming byte + * @return false : if not yet reached packet termination + */ + bool parse_byte(const uint8_t data); + + /** + * @brief Takes a raw buffer and writes it out to the device port. + * + * @param data : pointer to data buffer + * @param len : number of bytes to write + */ + void msg_write(const uint8_t *data, const uint16_t len) const; + + + /** + * @brief Callback for sending an installation message. + * + */ + void send_install_msg(); + + /** + * @brief Callback for sending a FlightID message + * + */ + void send_flight_id_msg(); + + /** + * @brief Callback for sending an operating message. + * + */ + void send_operating_msg(); + + /** + * @brief Callback for sending a GPS data message + * + */ + void send_gps_msg(); + + /** + * @brief Callback for sending a Target Request message + * + */ + void send_targetreq_msg(); + + /** + * @brief Convert the AP_ADSB uint8_t Emitter Type to the Sagetech Emitter Type definition + * + * @param emitterType + * @return sg_emitter_t + */ + sg_emitter_t convert_emitter_type_to_sg(const uint8_t emitterType) const; + + /** + * @brief Convert the float maxAirSpeed value to the Sagetech Max Airspeed Type + * + * @param maxAirSpeed + * @return sg_airspeed_t + */ + sg_airspeed_t convert_airspeed_knots_to_sg(const float maxAirSpeed) const; + + /** + * @brief Converts a Sagetech Emitter type value to the values used by ADSB. + * + * @return uint8_t + */ + uint8_t convert_sg_emitter_type_to_adsb(const sg_emitter_t sgEmitterType) const; + + void auto_config_operating(); + void auto_config_installation(); + void auto_config_flightid(); + void handle_ack(const sg_ack_t ack); + + struct { + // timers for each out-bound packet + uint32_t packet_initialize_ms; + uint32_t packet_PreFlight_ms; + uint32_t packet_GPS_ms; + uint32_t packet_Operating_ms; + uint32_t packet_targetReq; + + // cached variables to compare against params so we can send msg on param change. + uint16_t operating_squawk; + int32_t operating_alt; + uint8_t operating_rf_select; + bool modeAEnabled; + bool modeCEnabled; + bool modeSEnabled; + bool failXpdr; + bool failSystem; + uint8_t callsign[8]; + struct { + uint8_t id; + uint8_t type; + } msg; + } last; + + struct { + bool init; + bool init_failed; + sg_operating_t op; + sg_install_t inst; + sg_targetreq_t treq; + sg_flightid_t fid; + sg_ack_t ack; + } mxs_state; +}; +#endif // HAL_ADSB_SAGETECH_MXS_ENABLED + diff --git a/libraries/AP_ADSB/AP_ADSB_uAvionix_MAVLink.cpp b/libraries/AP_ADSB/AP_ADSB_uAvionix_MAVLink.cpp index fe5feee924b..14a3b048082 100644 --- a/libraries/AP_ADSB/AP_ADSB_uAvionix_MAVLink.cpp +++ b/libraries/AP_ADSB/AP_ADSB_uAvionix_MAVLink.cpp @@ -1,256 +1,256 @@ -/* - This program is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - This program is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with this program. If not, see . - */ - -#include "AP_ADSB_uAvionix_MAVLink.h" - -#if HAL_ADSB_UAVIONIX_MAVLINK_ENABLED -#include // for sprintf -#include -#include -#include -#include -#include - -#define ADSB_CHAN_TIMEOUT_MS 15000 - - -extern const AP_HAL::HAL& hal; - -// detect if an port is configured as MAVLink -bool AP_ADSB_uAvionix_MAVLink::detect() -{ - // this actually requires SerialProtocol_MAVLink or SerialProtocol_MAVLink2 but - // we can't have a running system with that, so its safe to assume it's already defined - return true; -} - -void AP_ADSB_uAvionix_MAVLink::update() -{ - const uint32_t now = AP_HAL::millis(); - - // send static configuration data to transceiver, every 5s - if (_frontend.out_state.chan_last_ms > 0 && now - _frontend.out_state.chan_last_ms > ADSB_CHAN_TIMEOUT_MS) { - // haven't gotten a heartbeat health status packet in a while, assume hardware failure - // TODO: reset out_state.chan - _frontend.out_state.chan = -1; - gcs().send_text(MAV_SEVERITY_ERROR, "ADSB: Transceiver heartbeat timed out"); - } else if (_frontend.out_state.chan >= 0 && !_frontend._my_loc.is_zero() && _frontend.out_state.chan < MAVLINK_COMM_NUM_BUFFERS) { - const mavlink_channel_t chan = (mavlink_channel_t)(MAVLINK_COMM_0 + _frontend.out_state.chan); - if (now - _frontend.out_state.last_config_ms >= 5000 && HAVE_PAYLOAD_SPACE(chan, UAVIONIX_ADSB_OUT_CFG)) { - _frontend.out_state.last_config_ms = now; - send_configure(chan); - } // last_config_ms - - // send dynamic data to transceiver at 5Hz - if (now - _frontend.out_state.last_report_ms >= 200 && HAVE_PAYLOAD_SPACE(chan, UAVIONIX_ADSB_OUT_DYNAMIC)) { - _frontend.out_state.last_report_ms = now; - send_dynamic_out(chan); - } // last_report_ms - } // chan_last_ms -} - -void AP_ADSB_uAvionix_MAVLink::send_dynamic_out(const mavlink_channel_t chan) const -{ - const AP_GPS &gps = AP::gps(); - const Vector3f &gps_velocity = gps.velocity(); - - const int32_t latitude = _frontend._my_loc.lat; - const int32_t longitude = _frontend._my_loc.lng; - const int32_t altGNSS = _frontend._my_loc.alt * 10; // convert cm to mm - const int16_t velVert = -1.0f * gps_velocity.z * 1E2; // convert m/s to cm/s - const int16_t nsVog = gps_velocity.x * 1E2; // convert m/s to cm/s - const int16_t ewVog = gps_velocity.y * 1E2; // convert m/s to cm/s - const uint8_t fixType = gps.status(); // this lines up perfectly with our enum - const uint8_t emStatus = 0; // TODO: implement this ENUM. no emergency = 0 - const uint8_t numSats = gps.num_sats(); - const uint16_t squawk = _frontend.out_state.cfg.squawk_octal; - - uint32_t accHoriz = UINT_MAX; - float accHoriz_f; - if (gps.horizontal_accuracy(accHoriz_f)) { - accHoriz = accHoriz_f * 1E3; // convert m to mm - } - - uint16_t accVert = USHRT_MAX; - float accVert_f; - if (gps.vertical_accuracy(accVert_f)) { - accVert = accVert_f * 1E2; // convert m to cm - } - - uint16_t accVel = USHRT_MAX; - float accVel_f; - if (gps.speed_accuracy(accVel_f)) { - accVel = accVel_f * 1E3; // convert m/s to mm/s - } - - uint16_t state = 0; - if (_frontend.out_state.is_in_auto_mode) { - state |= UAVIONIX_ADSB_OUT_DYNAMIC_STATE_AUTOPILOT_ENABLED; - } - if (!_frontend.out_state.is_flying) { - state |= UAVIONIX_ADSB_OUT_DYNAMIC_STATE_ON_GROUND; - } - - // TODO: confirm this sets utcTime correctly - const uint64_t gps_time = gps.time_epoch_usec(); - const uint32_t utcTime = gps_time / 1000000ULL; - - const AP_Baro &baro = AP::baro(); - int32_t altPres = INT_MAX; - if (baro.healthy()) { - // Altitude difference between sea level pressure and current pressure. Result in millimeters - altPres = baro.get_altitude_difference(SSL_AIR_PRESSURE, baro.get_pressure()) * 1E3; // convert m to mm; - } - - - - mavlink_msg_uavionix_adsb_out_dynamic_send( - chan, - utcTime, - latitude, - longitude, - altGNSS, - fixType, - numSats, - altPres, - accHoriz, - accVert, - accVel, - velVert, - nsVog, - ewVog, - emStatus, - state, - squawk); -} - - -/* - * To expand functionality in their HW, uAvionix has extended a few of the unused MAVLink bits to pack in more new features - * This function will override the MSB byte of the 24bit ICAO address. To ensure an invalid >24bit ICAO is never broadcasted, - * this function is used to create the encoded verison without ever writing to the actual ICAO number. It's created on-demand - */ -uint32_t AP_ADSB_uAvionix_MAVLink::encode_icao(const uint32_t icao_id) const -{ - // utilize the upper unused 8bits of the icao with special flags. - // This encoding is required for uAvionix devices that break the MAVLink spec. - - // ensure the user assignable icao is 24 bits - uint32_t encoded_icao = icao_id & 0x00FFFFFF; - - encoded_icao &= ~0x20000000; // useGnssAltitude should always be FALSE - encoded_icao |= 0x10000000; // csidLogic should always be TRUE - - //SIL/SDA are special fields that should be set to 0 with only expert user adjustment - encoded_icao &= ~0x03000000; // SDA should always be FALSE - encoded_icao &= ~0x0C000000; // SIL should always be FALSE - - return encoded_icao; -} - -/* - * To expand functionality in their HW, uAvionix has extended a few of the unused MAVLink bits to pack in more new features - * This function will override the usually-null ending char of the callsign. It always encodes the last byte [8], even if - * the callsign string is less than 9 chars and there are other zero-padded nulls. - */ -uint8_t AP_ADSB_uAvionix_MAVLink::get_encoded_callsign_null_char() -{ -// Encoding of the 8bit null char -// (LSB) - knots -// bit.1 - knots -// bit.2 - knots -// bit.3 - (unused) -// bit.4 - flag - ADSB_BITBASK_RF_CAPABILITIES_1090ES_IN -// bit.5 - flag - ADSB_BITBASK_RF_CAPABILITIES_UAT_IN -// bit.6 - flag - 0 = callsign is treated as callsign, 1 = callsign is treated as flightPlanID/Squawk -// (MSB) - (unused) - - uint8_t encoded_null = 0; - - if (_frontend.out_state.cfg.maxAircraftSpeed_knots <= 0) { - // not set or unknown. no bits set - } else if (_frontend.out_state.cfg.maxAircraftSpeed_knots <= 75) { - encoded_null |= 0x01; - } else if (_frontend.out_state.cfg.maxAircraftSpeed_knots <= 150) { - encoded_null |= 0x02; - } else if (_frontend.out_state.cfg.maxAircraftSpeed_knots <= 300) { - encoded_null |= 0x03; - } else if (_frontend.out_state.cfg.maxAircraftSpeed_knots <= 600) { - encoded_null |= 0x04; - } else if (_frontend.out_state.cfg.maxAircraftSpeed_knots <= 1200) { - encoded_null |= 0x05; - } else { - encoded_null |= 0x06; - } - - - if (_frontend.out_state.cfg.rf_capable & ADSB_BITBASK_RF_CAPABILITIES_1090ES_IN) { - encoded_null |= 0x10; - } - if (_frontend.out_state.cfg.rf_capable & ADSB_BITBASK_RF_CAPABILITIES_UAT_IN) { - encoded_null |= 0x20; - } - - - /* - If the user has an 8 digit flightPlanID assigned from a filed flight plan, this should be assigned to FlightPlanID, (assigned by remote app) - else if the user has an assigned squawk code from ATC this should be converted from 4 digit octal to 4 character alpha string and assigned to FlightPlanID, - else if a tail number is known it should be set to the tail number of the aircraft, (assigned by remote app) - else it should be left blank (all 0's) - */ - - // using the above logic, we must always assign the squawk. once we get configured - // externally then get_encoded_callsign_null_char() stops getting called - snprintf(_frontend.out_state.cfg.callsign, 5, "%04d", unsigned(_frontend.out_state.cfg.squawk_octal) & 0x1FFF); - memset(&_frontend.out_state.cfg.callsign[4], 0, 5); // clear remaining 5 chars - encoded_null |= 0x40; - - return encoded_null; -} - -/* - * populate and send MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG - */ -void AP_ADSB_uAvionix_MAVLink::send_configure(const mavlink_channel_t chan) -{ - // MAVLink spec says the 9 byte callsign field is 8 byte string with 9th byte as null. - // Here we temporarily set some flags in that null char to signify the callsign - // may be a flightplanID instead - int8_t callsign[sizeof(_frontend.out_state.cfg.callsign)]; - uint32_t icao; - - memcpy(callsign, _frontend.out_state.cfg.callsign, sizeof(_frontend.out_state.cfg.callsign)); - - if (_frontend.out_state.cfg.was_set_externally) { - // take values as-is - icao = _frontend.out_state.cfg.ICAO_id; - } else { - callsign[MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG_FIELD_CALLSIGN_LEN-1] = (int8_t)get_encoded_callsign_null_char(); - icao = encode_icao((uint32_t)_frontend.out_state.cfg.ICAO_id); - } - - mavlink_msg_uavionix_adsb_out_cfg_send( - chan, - icao, - (const char*)callsign, - (uint8_t)_frontend.out_state.cfg.emitterType, - (uint8_t)_frontend.out_state.cfg.lengthWidth, - (uint8_t)_frontend.out_state.cfg.gpsOffsetLat, - (uint8_t)_frontend.out_state.cfg.gpsOffsetLon, - _frontend.out_state.cfg.stall_speed_cm, - (uint8_t)_frontend.out_state.cfg.rfSelect); -} - -#endif // HAL_ADSB_ENABLED +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +#include "AP_ADSB_uAvionix_MAVLink.h" + +#if HAL_ADSB_UAVIONIX_MAVLINK_ENABLED +#include // for sprintf +#include +#include +#include +#include +#include + +#define ADSB_CHAN_TIMEOUT_MS 15000 + + +extern const AP_HAL::HAL& hal; + +// detect if an port is configured as MAVLink +bool AP_ADSB_uAvionix_MAVLink::detect() +{ + // this actually requires SerialProtocol_MAVLink or SerialProtocol_MAVLink2 but + // we can't have a running system with that, so its safe to assume it's already defined + return true; +} + +void AP_ADSB_uAvionix_MAVLink::update() +{ + const uint32_t now = AP_HAL::millis(); + + // send static configuration data to transceiver, every 5s + if (_frontend.out_state.chan_last_ms > 0 && now - _frontend.out_state.chan_last_ms > ADSB_CHAN_TIMEOUT_MS) { + // haven't gotten a heartbeat health status packet in a while, assume hardware failure + // TODO: reset out_state.chan + _frontend.out_state.chan = -1; + gcs().send_text(MAV_SEVERITY_ERROR, "ADSB: Transceiver heartbeat timed out"); + } else if (_frontend.out_state.chan >= 0 && !_frontend._my_loc.is_zero() && _frontend.out_state.chan < MAVLINK_COMM_NUM_BUFFERS) { + const mavlink_channel_t chan = (mavlink_channel_t)(MAVLINK_COMM_0 + _frontend.out_state.chan); + if (now - _frontend.out_state.last_config_ms >= 5000 && HAVE_PAYLOAD_SPACE(chan, UAVIONIX_ADSB_OUT_CFG)) { + _frontend.out_state.last_config_ms = now; + send_configure(chan); + } // last_config_ms + + // send dynamic data to transceiver at 5Hz + if (now - _frontend.out_state.last_report_ms >= 200 && HAVE_PAYLOAD_SPACE(chan, UAVIONIX_ADSB_OUT_DYNAMIC)) { + _frontend.out_state.last_report_ms = now; + send_dynamic_out(chan); + } // last_report_ms + } // chan_last_ms +} + +void AP_ADSB_uAvionix_MAVLink::send_dynamic_out(const mavlink_channel_t chan) const +{ + const AP_GPS &gps = AP::gps(); + const Vector3f &gps_velocity = gps.velocity(); + + const int32_t latitude = _frontend._my_loc.lat; + const int32_t longitude = _frontend._my_loc.lng; + const int32_t altGNSS = _frontend._my_loc.alt * 10; // convert cm to mm + const int16_t velVert = -1.0f * gps_velocity.z * 1E2; // convert m/s to cm/s + const int16_t nsVog = gps_velocity.x * 1E2; // convert m/s to cm/s + const int16_t ewVog = gps_velocity.y * 1E2; // convert m/s to cm/s + const uint8_t fixType = gps.status(); // this lines up perfectly with our enum + const uint8_t emStatus = 0; // TODO: implement this ENUM. no emergency = 0 + const uint8_t numSats = gps.num_sats(); + const uint16_t squawk = _frontend.out_state.cfg.squawk_octal; + + uint32_t accHoriz = UINT_MAX; + float accHoriz_f; + if (gps.horizontal_accuracy(accHoriz_f)) { + accHoriz = accHoriz_f * 1E3; // convert m to mm + } + + uint16_t accVert = USHRT_MAX; + float accVert_f; + if (gps.vertical_accuracy(accVert_f)) { + accVert = accVert_f * 1E2; // convert m to cm + } + + uint16_t accVel = USHRT_MAX; + float accVel_f; + if (gps.speed_accuracy(accVel_f)) { + accVel = accVel_f * 1E3; // convert m/s to mm/s + } + + uint16_t state = 0; + if (_frontend.out_state.is_in_auto_mode) { + state |= UAVIONIX_ADSB_OUT_DYNAMIC_STATE_AUTOPILOT_ENABLED; + } + if (!_frontend.out_state.is_flying) { + state |= UAVIONIX_ADSB_OUT_DYNAMIC_STATE_ON_GROUND; + } + + // TODO: confirm this sets utcTime correctly + const uint64_t gps_time = gps.time_epoch_usec(); + const uint32_t utcTime = gps_time / 1000000ULL; + + const AP_Baro &baro = AP::baro(); + int32_t altPres = INT_MAX; + if (baro.healthy()) { + // Altitude difference between sea level pressure and current pressure. Result in millimeters + altPres = baro.get_altitude_difference(SSL_AIR_PRESSURE, baro.get_pressure()) * 1E3; // convert m to mm; + } + + + + mavlink_msg_uavionix_adsb_out_dynamic_send( + chan, + utcTime, + latitude, + longitude, + altGNSS, + fixType, + numSats, + altPres, + accHoriz, + accVert, + accVel, + velVert, + nsVog, + ewVog, + emStatus, + state, + squawk); +} + + +/* + * To expand functionality in their HW, uAvionix has extended a few of the unused MAVLink bits to pack in more new features + * This function will override the MSB byte of the 24bit ICAO address. To ensure an invalid >24bit ICAO is never broadcasted, + * this function is used to create the encoded verison without ever writing to the actual ICAO number. It's created on-demand + */ +uint32_t AP_ADSB_uAvionix_MAVLink::encode_icao(const uint32_t icao_id) const +{ + // utilize the upper unused 8bits of the icao with special flags. + // This encoding is required for uAvionix devices that break the MAVLink spec. + + // ensure the user assignable icao is 24 bits + uint32_t encoded_icao = icao_id & 0x00FFFFFF; + + encoded_icao &= ~0x20000000; // useGnssAltitude should always be FALSE + encoded_icao |= 0x10000000; // csidLogic should always be TRUE + + //SIL/SDA are special fields that should be set to 0 with only expert user adjustment + encoded_icao &= ~0x03000000; // SDA should always be FALSE + encoded_icao &= ~0x0C000000; // SIL should always be FALSE + + return encoded_icao; +} + +/* + * To expand functionality in their HW, uAvionix has extended a few of the unused MAVLink bits to pack in more new features + * This function will override the usually-null ending char of the callsign. It always encodes the last byte [8], even if + * the callsign string is less than 9 chars and there are other zero-padded nulls. + */ +uint8_t AP_ADSB_uAvionix_MAVLink::get_encoded_callsign_null_char() +{ +// Encoding of the 8bit null char +// (LSB) - knots +// bit.1 - knots +// bit.2 - knots +// bit.3 - (unused) +// bit.4 - flag - ADSB_BITBASK_RF_CAPABILITIES_1090ES_IN +// bit.5 - flag - ADSB_BITBASK_RF_CAPABILITIES_UAT_IN +// bit.6 - flag - 0 = callsign is treated as callsign, 1 = callsign is treated as flightPlanID/Squawk +// (MSB) - (unused) + + uint8_t encoded_null = 0; + + if (_frontend.out_state.cfg.maxAircraftSpeed_knots <= 0) { + // not set or unknown. no bits set + } else if (_frontend.out_state.cfg.maxAircraftSpeed_knots <= 75) { + encoded_null |= 0x01; + } else if (_frontend.out_state.cfg.maxAircraftSpeed_knots <= 150) { + encoded_null |= 0x02; + } else if (_frontend.out_state.cfg.maxAircraftSpeed_knots <= 300) { + encoded_null |= 0x03; + } else if (_frontend.out_state.cfg.maxAircraftSpeed_knots <= 600) { + encoded_null |= 0x04; + } else if (_frontend.out_state.cfg.maxAircraftSpeed_knots <= 1200) { + encoded_null |= 0x05; + } else { + encoded_null |= 0x06; + } + + + if (_frontend.out_state.cfg.rf_capable & ADSB_BITBASK_RF_CAPABILITIES_1090ES_IN) { + encoded_null |= 0x10; + } + if (_frontend.out_state.cfg.rf_capable & ADSB_BITBASK_RF_CAPABILITIES_UAT_IN) { + encoded_null |= 0x20; + } + + + /* + If the user has an 8 digit flightPlanID assigned from a filed flight plan, this should be assigned to FlightPlanID, (assigned by remote app) + else if the user has an assigned squawk code from ATC this should be converted from 4 digit octal to 4 character alpha string and assigned to FlightPlanID, + else if a tail number is known it should be set to the tail number of the aircraft, (assigned by remote app) + else it should be left blank (all 0's) + */ + + // using the above logic, we must always assign the squawk. once we get configured + // externally then get_encoded_callsign_null_char() stops getting called + snprintf(_frontend.out_state.cfg.callsign, 5, "%04d", unsigned(_frontend.out_state.cfg.squawk_octal) & 0x1FFF); + memset(&_frontend.out_state.cfg.callsign[4], 0, 5); // clear remaining 5 chars + encoded_null |= 0x40; + + return encoded_null; +} + +/* + * populate and send MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG + */ +void AP_ADSB_uAvionix_MAVLink::send_configure(const mavlink_channel_t chan) +{ + // MAVLink spec says the 9 byte callsign field is 8 byte string with 9th byte as null. + // Here we temporarily set some flags in that null char to signify the callsign + // may be a flightplanID instead + int8_t callsign[sizeof(_frontend.out_state.cfg.callsign)]; + uint32_t icao; + + memcpy(callsign, _frontend.out_state.cfg.callsign, sizeof(_frontend.out_state.cfg.callsign)); + + if (_frontend.out_state.cfg.was_set_externally) { + // take values as-is + icao = _frontend.out_state.cfg.ICAO_id; + } else { + callsign[MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG_FIELD_CALLSIGN_LEN-1] = (int8_t)get_encoded_callsign_null_char(); + icao = encode_icao((uint32_t)_frontend.out_state.cfg.ICAO_id); + } + + mavlink_msg_uavionix_adsb_out_cfg_send( + chan, + icao, + (const char*)callsign, + (uint8_t)_frontend.out_state.cfg.emitterType, + (uint8_t)_frontend.out_state.cfg.lengthWidth, + (uint8_t)_frontend.out_state.cfg.gpsOffsetLat, + (uint8_t)_frontend.out_state.cfg.gpsOffsetLon, + _frontend.out_state.cfg.stall_speed_cm, + (uint8_t)_frontend.out_state.cfg.rfSelect); +} + +#endif // HAL_ADSB_ENABLED diff --git a/libraries/AP_ADSB/AP_ADSB_uAvionix_MAVLink.h b/libraries/AP_ADSB/AP_ADSB_uAvionix_MAVLink.h index 6e1f699af6d..59ec7f3d7e7 100644 --- a/libraries/AP_ADSB/AP_ADSB_uAvionix_MAVLink.h +++ b/libraries/AP_ADSB/AP_ADSB_uAvionix_MAVLink.h @@ -1,44 +1,44 @@ -#pragma once - -/* - This program is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - This program is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with this program. If not, see . - */ - -#include "AP_ADSB_Backend.h" - -#ifndef HAL_ADSB_UAVIONIX_MAVLINK_ENABLED -#define HAL_ADSB_UAVIONIX_MAVLINK_ENABLED HAL_ADSB_ENABLED -#endif - -#if HAL_ADSB_UAVIONIX_MAVLINK_ENABLED -class AP_ADSB_uAvionix_MAVLink : public AP_ADSB_Backend { -public: - using AP_ADSB_Backend::AP_ADSB_Backend; - - void update() override; - - // static detection function - static bool detect(); - -private: - // send static and dynamic data to ADSB transceiver - void send_configure(const mavlink_channel_t chan); - void send_dynamic_out(const mavlink_channel_t chan) const; - - // special helpers for uAvionix workarounds - uint32_t encode_icao(const uint32_t icao_id) const; - uint8_t get_encoded_callsign_null_char(void); -}; -#endif // HAL_ADSB_ENABLED - +#pragma once + +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +#include "AP_ADSB_Backend.h" + +#ifndef HAL_ADSB_UAVIONIX_MAVLINK_ENABLED +#define HAL_ADSB_UAVIONIX_MAVLINK_ENABLED HAL_ADSB_ENABLED +#endif + +#if HAL_ADSB_UAVIONIX_MAVLINK_ENABLED +class AP_ADSB_uAvionix_MAVLink : public AP_ADSB_Backend { +public: + using AP_ADSB_Backend::AP_ADSB_Backend; + + void update() override; + + // static detection function + static bool detect(); + +private: + // send static and dynamic data to ADSB transceiver + void send_configure(const mavlink_channel_t chan); + void send_dynamic_out(const mavlink_channel_t chan) const; + + // special helpers for uAvionix workarounds + uint32_t encode_icao(const uint32_t icao_id) const; + uint8_t get_encoded_callsign_null_char(void); +}; +#endif // HAL_ADSB_ENABLED + diff --git a/libraries/AP_ADSB/sagetech-sdk/LICENSE b/libraries/AP_ADSB/sagetech-sdk/LICENSE new file mode 100644 index 00000000000..f49a4e16e68 --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/LICENSE @@ -0,0 +1,201 @@ + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + APPENDIX: How to apply the Apache License to your work. + + To apply the Apache License to your work, attach the following + boilerplate notice, with the fields enclosed by brackets "[]" + replaced with your own identifying information. (Don't include + the brackets!) The text should be enclosed in the appropriate + comment syntax for the file format. We also recommend that a + file or class name and description of purpose be included on the + same "printed page" as the copyright notice for easier + identification within third-party archives. + + Copyright [yyyy] [name of copyright owner] + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. \ No newline at end of file diff --git a/libraries/AP_ADSB/sagetech-sdk/README.md b/libraries/AP_ADSB/sagetech-sdk/README.md new file mode 100644 index 00000000000..c0a769e11ef --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/README.md @@ -0,0 +1,6 @@ +# Sagetech SDK +The contents of this folder includes selected functions from the full Sagetech SDK which can be found here: +https://github.com/Sagetech-Avionics/sagetech-mxs-sdk + +## Links +[Host Interface Control Document for MXS](https://github.com/Sagetech-Avionics/sagetech-mxs-sdk/blob/main/doc/pdf/ICD02373_MXS_Host_ICD.pdf) diff --git a/libraries/AP_ADSB/sagetech-sdk/appendChecksum.c b/libraries/AP_ADSB/sagetech-sdk/appendChecksum.c new file mode 100644 index 00000000000..5bc2b485cfd --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/appendChecksum.c @@ -0,0 +1,19 @@ +/** + * @copyright Copyright (c) 2021 Sagetech, Inc. All rights reserved. + * + * @file appendChecksum.c + * @author Jacob.Garrison + * + * @date Mar 2, 2021 + * + */ + +#include "sgUtil.h" + +/* + * Documented in the header file + */ +void appendChecksum(uint8_t *buffer, uint8_t len) +{ + buffer[len - 1] = calcChecksum(buffer, len); +} diff --git a/libraries/AP_ADSB/sagetech-sdk/calcChecksum.c b/libraries/AP_ADSB/sagetech-sdk/calcChecksum.c new file mode 100644 index 00000000000..3b3dc1fc7cd --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/calcChecksum.c @@ -0,0 +1,27 @@ +/** + * @copyright Copyright (c) 2021 Sagetech, Inc. All rights reserved. + * + * @file calcChecksum.c + * @author Jacob.Garrison + * + * @date Mar 2, 2021 + * + */ + +#include "sgUtil.h" + +/* + * Documented in the header file + */ +uint8_t calcChecksum(uint8_t *buffer, uint8_t len) +{ + uint8_t sum = 0x00; + + // Add all bytes excluding checksum + for (uint8_t i = 0; i < len - 1; ++i) + { + sum += buffer[i]; + } + + return sum; +} diff --git a/libraries/AP_ADSB/sagetech-sdk/charArray2Buf.c b/libraries/AP_ADSB/sagetech-sdk/charArray2Buf.c new file mode 100644 index 00000000000..fab3cbb1ef0 --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/charArray2Buf.c @@ -0,0 +1,23 @@ +/** + * @copyright Copyright (c) 2021 Sagetech, Inc. All rights reserved. + * + * @file charArray2Buf.c + * @author Jacob.Garrison + * + * @date Mar 2, 2021 + * + */ + +#include "sgUtil.h" +#include + +/* + * Documented in the header file. + */ +void charArray2Buf(uint8_t *bufferPos, char arr[], uint8_t len) +{ + for (uint8_t i = 0; i < len; ++i) + { + bufferPos[i] = toupper(arr[i]); + } +} diff --git a/libraries/AP_ADSB/sagetech-sdk/float2Buf.c b/libraries/AP_ADSB/sagetech-sdk/float2Buf.c new file mode 100644 index 00000000000..174ea1c17c5 --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/float2Buf.c @@ -0,0 +1,32 @@ +/** + * @copyright Copyright (c) 2021 Sagetech, Inc. All rights reserved. + * + * @file float2Buf.c + * @author Jacob.Garrison + * + * @date Mar 2, 2021 + * + */ + +#include "sgUtil.h" + +/* + * Documented in the header file. + */ +void float2Buf(uint8_t *bufferPos, float value) +{ + const uint16_t FLOAT_SIZE = 4; + + union + { + float val; + unsigned char bytes[FLOAT_SIZE]; + } conversion; + + conversion.val = value; + + for (int i = 0; i < FLOAT_SIZE; ++i) + { + bufferPos[i] = conversion.bytes[i]; + } +} diff --git a/libraries/AP_ADSB/sagetech-sdk/icao2Buf.c b/libraries/AP_ADSB/sagetech-sdk/icao2Buf.c new file mode 100644 index 00000000000..95d6434c1e7 --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/icao2Buf.c @@ -0,0 +1,21 @@ +/** + * @copyright Copyright (c) 2021 Sagetech, Inc. All rights reserved. + * + * @file icao2Buf.c + * @author Jacob.Garrison + * + * @date Mar 2, 2021 + * + */ + +#include "sgUtil.h" + +/* + * Documented in the header file. + */ +void icao2Buf(uint8_t *bufferPos, uint32_t icao) +{ + bufferPos[0] = (icao & 0x00FF0000) >> 16; + bufferPos[1] = (icao & 0x0000FF00) >> 8; + bufferPos[2] = (icao & 0x000000FF); +} diff --git a/libraries/AP_ADSB/sagetech-sdk/sagetech_mxs.h b/libraries/AP_ADSB/sagetech-sdk/sagetech_mxs.h new file mode 100644 index 00000000000..587b1dec396 --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/sagetech_mxs.h @@ -0,0 +1,13 @@ +#pragma once + +#ifdef __cplusplus +extern "C" +{ +#endif + +#include "sg.h" +#include "sgUtil.h" + +#ifdef __cplusplus +} +#endif \ No newline at end of file diff --git a/libraries/AP_ADSB/sagetech-sdk/sg.h b/libraries/AP_ADSB/sagetech-sdk/sg.h new file mode 100644 index 00000000000..a12de19eaf6 --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/sg.h @@ -0,0 +1,954 @@ +/** + * @copyright Copyright (c) 2021 Sagetech, Inc. All rights reserved. + * + * @file sg.h + * @author jimb + * + * @date Feb 10, 2021 + * + * Sagetech protocol for host message building and parsing. + * + * This module performs both the following: + * 1. Parses raw Sagetech host messages defined in the SDIM and + * returns a populated struct dataset of the message type. + * 2. Receives a populated struct dataset of the desired host message + * and returns the corresponding raw message data buffer. + */ + +#ifndef SG_H +#define SG_H + +#include +#include + +/// Host Message Lengths (bytes) +#define SG_MSG_LEN_INSTALL 41 +#define SG_MSG_LEN_FLIGHT 17 +#define SG_MSG_LEN_OPMSG 17 +#define SG_MSG_LEN_GPS 68 +#define SG_MSG_LEN_DATAREQ 9 +#define SG_MSG_LEN_TARGETREQ 12 +#define SG_MSG_LEN_MODE 10 + +/// Host Message Types +#define SG_MSG_TYPE_HOST_INSTALL 0x01 +#define SG_MSG_TYPE_HOST_FLIGHT 0x02 +#define SG_MSG_TYPE_HOST_OPMSG 0x03 +#define SG_MSG_TYPE_HOST_GPS 0x04 +#define SG_MSG_TYPE_HOST_DATAREQ 0x05 +#define SG_MSG_TYPE_HOST_TARGETREQ 0x0B +#define SG_MSG_TYPE_HOST_MODE 0x0C + +/// XPNDR Message Types +#define SG_MSG_TYPE_XPNDR_ACK 0x80 +#define SG_MSG_TYPE_XPNDR_INSTALL 0x81 +#define SG_MSG_TYPE_XPNDR_FLIGHT 0x82 +#define SG_MSG_TYPE_XPNDR_STATUS 0x83 +#define SG_MSG_TYPE_XPNDR_COMMA 0x85 +#define SG_MSG_TYPE_XPNDR_MODE 0x8C +#define SG_MSG_TYPE_XPNDR_VERSION 0x8E +#define SG_MSG_TYPE_XPNDR_SERIALNUM 0x8F + +/// ADS-B Message Types +#define SG_MSG_TYPE_ADSB_TSUMMARY 0x90 +#define SG_MSG_TYPE_ADSB_SVR 0x91 +#define SG_MSG_TYPE_ADSB_MSR 0x92 +#define SG_MSG_TYPE_ADSB_TSTATE 0x97 +#define SG_MSG_TYPE_ADSB_ARVR 0x98 + +/// Start byte for all host messages +#define SG_MSG_START_BYTE 0xAA + +/// Emitter category set byte values +#define SG_EMIT_GROUP_A 0x00 +#define SG_EMIT_GROUP_B 0x01 +#define SG_EMIT_GROUP_C 0x02 +#define SG_EMIT_GROUP_D 0x03 + +/// Emitter category enumeration offsets +#define SG_EMIT_OFFSET_A 0x00 +#define SG_EMIT_OFFSET_B 0x10 +#define SG_EMIT_OFFSET_C 0x20 +#define SG_EMIT_OFFSET_D 0x30 + +/** + * Available COM port baud rates. + */ +typedef enum +{ + baud38400 = 0, + baud600, + baud4800, + baud9600, + baud28800, + baud57600, + baud115200, + baud230400, + baud19200, + baud460800, + baud921600 +} sg_baud_t; + +/** + * Transponder ethernet configuration + */ +typedef struct +{ + uint32_t ipAddress; /// The transponder ip address + uint32_t subnetMask; /// The transponder subnet mask + uint16_t portNumber; /// The transponder port number +} sg_ethernet_t; + +/** + * Available GPS integrity SIL values + */ +typedef enum +{ + silUnknown = 0, + silLow, + silMedium, + silHigh +} sg_sil_t; + +/** + * Available GPS integrity SDA values + */ +typedef enum +{ + sdaUnknown = 0, + sdaMinor, + sdaMajor, + sdaHazardous +} sg_sda_t; + +/** + * Available emitter types + */ +typedef enum +{ + aUnknown = SG_EMIT_OFFSET_A, + aLight, + aSmall, + aLarge, + aHighVortex, + aHeavy, + aPerformance, + aRotorCraft, + bUnknown = SG_EMIT_OFFSET_B, + bGlider, + bAir, + bParachutist, + bUltralight, + bUAV = SG_EMIT_OFFSET_B + 6, + bSpace, + cUnknown = SG_EMIT_OFFSET_C, + cEmergency, + cService, + cPoint, + cCluster, + cLine, + dUnknown = SG_EMIT_OFFSET_D +} sg_emitter_t; + +/** + * Available aircraft sizes in meters + */ +typedef enum +{ + sizeUnknown = 0, /// Dimensions unknown + sizeL15W23, /// Length <= 15m & Width <= 23m + sizeL25W28, /// Length <= 25m & Width <= 28.5m + sizeL25W34, /// Length <= 25m & Width <= 34m + sizeL35W33, /// Length <= 35m & Width <= 33m + sizeL35W38, /// Length <= 35m & Width <= 38m + sizeL45W39, /// Length <= 45m & Width <= 39.5m + sizeL45W45, /// Length <= 45m & Width <= 45m + sizeL55W45, /// Length <= 55m & Width <= 45m + sizeL55W52, /// Length <= 55m & Width <= 52m + sizeL65W59, /// Length <= 65m & Width <= 59.5m + sizeL65W67, /// Length <= 65m & Width <= 67m + sizeL75W72, /// Length <= 75m & Width <= 72.5m + sizeL75W80, /// Length <= 75m & Width <= 80m + sizeL85W80, /// Length <= 85m & Width <= 80m + sizeL85W90 /// Length <= 85m & Width <= 90m +} sg_size_t; + +/** + * Available aircraft maximum airspeeds + */ +typedef enum +{ + speedUnknown = 0, /// Max speed unknown + speed75kt, /// 0 knots < Max speed < 75 knots + speed150kt, /// 75 knots < Max speed < 150 knots + speed300kt, /// 150 knots < Max speed < 300 knots + speed600kt, /// 300 knots < Max speed < 600 knots + speed1200kt, /// 600 knots < Max speed < 1200 knots + speedGreater /// 1200 knots < Max speed +} sg_airspeed_t; + +/** + * Available antenna configurations + */ +typedef enum +{ + antBottom = 1, /// bottom antenna only + antBoth = 3 /// both top and bottom antennae +} sg_antenna_t; + +/** + * The XPNDR Installation Message. + * Host --> XPNDR. + * XPNDR --> Host. + * Use 'strcpy(install.reg, "REGVAL1")' to assign the registration. + */ +typedef struct +{ + uint32_t icao; /// The aircraft's ICAO address + char reg[8]; /// The aircraft's registration (left-justified alphanumeric characters padded with spaces) + sg_baud_t com0; /// The baud rate for COM Port 0 + sg_baud_t com1; /// The baud rate for COM Port 1 + sg_ethernet_t eth; /// The ethernet configuration + sg_sil_t sil; /// The gps integrity SIL parameter + sg_sda_t sda; /// The gps integrity SDA parameter + sg_emitter_t emitter; /// The platform's emitter type + sg_size_t size; /// The platform's dimensions + sg_airspeed_t maxSpeed; /// The platform's maximum airspeed + int16_t altOffset; /// The altitude encoder offset is a legacy field that should always = 0 + sg_antenna_t antenna; /// The antenna configuration + bool altRes100; /// Altitude resolution. true = 100 foot, false = 25 foot + bool hdgTrueNorth; /// Heading type. true = true north, false = magnetic north + bool airspeedTrue; /// Airspeed type. true = true speed, false = indicated speed + bool heater; /// true = heater enabled, false = heater disabled + bool wowConnected; /// Weight on Wheels sensor. true = connected, false = not connected +} sg_install_t; + +/** + * The XPNDR Flight ID Message. + * Host --> XPNDR. + * XPNDR --> Host. + * * Use 'strcpy(id.flightID, "FLIGHTNO")' to assign the flight identification. + */ +typedef struct +{ + char flightId[9]; /// The flight identification (left-justified alphanumeric characters padded with spaces) +} sg_flightid_t; + +/** + * Available transponder operating modes. The enumerated values are + * offset from the host message protocol values. + */ +typedef enum +{ + modeOff = 0, /// 'Off' Mode: Xpdr will not transmit + modeOn, /// 'On' Mode: Full functionality with Altitude = Invalid + modeStby, /// 'Standby' Mode: Reply to lethal interrogations, only + modeAlt /// 'Alt' Mode: Full functionality +} sg_op_mode_t; + +/** + * Available emergency status codes. + */ +typedef enum +{ + emergcNone = 0, /// No Emergency + emergcGeneral, /// General Emergency + emergcMed, /// Lifeguard/Medical Emergency + emergcFuel, /// Minimum Fuel + emergcComm, /// No Communications + emergcIntrfrc, /// Unlawful Interference + emergcDowned /// Downed Aircraft +} sg_emergc_t; + +/** + * The XPNDR Operating Message. + * Host --> XPNDR. + */ +typedef struct +{ + uint16_t squawk; /// 4-digit octal Mode A code + sg_op_mode_t opMode; /// Operational mode + bool savePowerUp; /// Save power-up state in non-volatile + bool enableSqt; /// Enable extended squitters + bool enableXBit; /// Enable the x-bit + bool milEmergency; /// Broadcast a military emergency + sg_emergc_t emergcType; /// Enumerated civilian emergency type + bool identOn; /// Set the identification switch = On + bool altUseIntrnl; /// True = Report altitude from internal pressure sensor (will ignore other bits in the field) + bool altHostAvlbl; /// True = Host Altitude is being provided + bool altRes25; /// Host Altitude Resolution from install message, True = 25 ft, False = 100 ft + int32_t altitude; /// Sea-level altitude in feet. Field is ignored when internal altitude is selected. + bool climbValid; /// Climb rate is provided; + int16_t climbRate; /// Climb rate in ft/min. Limits are +/- 16,448 ft/min. + bool headingValid; /// Heading is valid. + double heading; /// Heading in degrees + bool airspdValid; /// Airspeed is valid. + uint16_t airspd; /// Airspeed in knots. +} sg_operating_t; + +/** + * Avaiable NACp values. + */ +typedef enum +{ + nacpUnknown, /// >= 18.52 km ( 10 nmile) + nacp10dot0, /// < 18.52 km ( 10 nmile) + nacp4dot0, /// < 7.408 km ( 4 nmile) + nacp2dot0, /// < 3.704 km ( 2 nmile) + nacp1dot0, /// < 1.852 km ( 1 nmile) + nacp0dot5, /// < 0.926 km (0.5 nmile) + nacp0dot3, /// < 0.556 km (0.3 nmile) + nacp0dot1, /// < 0.185 km (0.1 nmile) + nacp0dot05, /// < 92.6 m (0.05 nmile) + nacp30, /// < 30.0 m + nacp10, /// < 10.0 m + nacp3 /// < 3.0 m +} sg_nacp_t; + +/** + * Available NACv values (m/s) + */ +typedef enum +{ + nacvUnknown = 0, /// 10 <= NACv (or NACv is unknown) + nacv10dot0, /// 3 <= NACv < 10 + nacv3dot0, /// 1 <= NACv < 3 + nacv1dot0, /// 0.3 <= NACv < 1 + nacv0dot3 /// 0.0 <= NACv < 0.3 +} sg_nacv_t; + +/** + * The XPNDR Simulated GPS Message. + * Host --> XPNDR. + */ +typedef struct +{ + char longitude[12]; /// The absolute value of longitude (degree and decimal minute) + char latitude[11]; /// The absolute value of latitude (degree and decimal minute) + char grdSpeed[7]; /// The GPS over-ground speed (knots) + char grdTrack[9]; /// The GPS track referenced from True North (degrees, clockwise) + bool latNorth; /// The aircraft is in the northern hemisphere + bool lngEast; /// The aircraft is in the eastern hemisphere + bool fdeFail; /// True = A satellite error has occurred + bool gpsValid; /// True = GPS data is valid + char timeOfFix[11]; /// Time, relative to midnight UTC (can optionally be filled spaces) + float height; /// The height above the WGS-84 ellipsoid (meters) + float hpl; /// The Horizontal Protection Limit (meters) + float hfom; /// The Horizontal Figure of Merit (meters) + float vfom; /// The Vertical Figure of Merit (meters) + sg_nacv_t nacv; /// Navigation Accuracy for Velocity (meters/second) +} sg_gps_t; + +/** + * Available data request types + */ +typedef enum +{ + dataInstall = 0x81, /// Installation data + dataFlightID = 0x82, /// Flight Identification data + dataStatus = 0x83, /// Status Response data + dataMode = 0x8C, /// Mode Settings data + dataHealth = 0x8D, /// Health Monitor data + dataVersion = 0x8E, /// Version data + dataSerialNum = 0x8F, /// Serial Number data + dataTOD = 0xD2, /// Time of Day data + dataMode5 = 0xD3, /// Mode 5 Indication data + dataCrypto = 0xD4, /// Crypto Status data + dataMilSettings = 0xD7 /// Military Settings data +} sg_datatype_t; + +/** + * The Data Request message. + * Host --> XPDR. + */ +typedef struct +{ + sg_datatype_t reqType; /// The desired data response + uint8_t resv[3]; +} sg_datareq_t; + +/** + * Available target request types + */ +typedef enum +{ + reportAuto = 0, /// Enable auto output of all target reports + reportSummary, /// Report list of all tracked targets (disables auto-output) + reportIcao, /// Generate reports for specific target, only (disables auto-output) + reportNone /// Disable all target reports +} sg_reporttype_t; + +/** + * Available target report transmission ports + */ +typedef enum +{ + transmitSource = 0, /// Transmit reports on channel where target request was received + transmitCom0, /// Transmit reports on Com0 + transmitCom1, /// Transmit reports on Com1 + transmitEth /// Transmit reports on Ethernet +} sg_transmitport_t; + +/** + * The Target Request message for ADS-B 'in' data. + * Host --> XPDR. + */ +typedef struct +{ + sg_reporttype_t reqType; /// The desired report mode + sg_transmitport_t transmitPort; /// The communication port used for report transmission + uint16_t maxTargets; /// The maximum number of targets to track (max value: 404) + uint32_t icao; /// The desired target's ID, if applicable + bool stateVector; /// Transmit state vector reports + bool modeStatus; /// Transmit mode status reports + bool targetState; /// Transmit target state reports + bool airRefVel; /// Transmit air referenced velocity reports + bool tisb; /// Transmit raw TIS-B message reports (requires auto-output) + bool military; /// Enable tracking of military aircraft + bool commA; /// Transmit Comm-A Reports (requires auto-output) + bool ownship; /// Transmit reports about own aircraft +} sg_targetreq_t; + +/** + * The Mode message. + * Host --> XPDR. + */ +typedef struct +{ + bool reboot; /// Reboot the MX +} sg_mode_t; + +/** + * The XPNDR Acknowledge Message following all host messages. + * XPNDR --> Host. + */ +typedef struct +{ + uint8_t ackType; /// Message type being acknowledged + uint8_t ackId; /// Message ID being acknowledged + bool failXpdr; /// Built-in-test failure + bool failSystem; /// Required system input missing + bool failCrypto; /// Crypto status failure + bool wow; /// Weight-on-wheels indicates aircraft is on-ground + bool maint; /// Maintenance mode enabled + bool isHostAlt; /// False = Pressure sensor altitude, True = Host provided value + sg_op_mode_t opMode; /// Operational mode + int32_t alt; /// Altitude (feet) + bool altValid; /// Altitude is valid +} sg_ack_t; + +/** + * The XPNDR Status Response Message following a Data Request for Status. + * XPNDR --> Host. + */ +typedef struct +{ + uint8_t versionSW; /// SW Version # installed on the XPNDR + uint8_t versionFW; /// FW Version # installed on the XPNDR + uint32_t crc; /// CRC Checksum for the installed XPNDR SW/FW versions + + bool powerUp : 1; /// Integrity of CPU and Non-Volatile data at power-up + bool continuous : 1; /// Set by any other B.I.T. failures during operation + bool processor : 1; /// One-time processor instruction set test at power-up + bool crcValid : 1; /// Calculate then verifies the CRC against the stored value + bool memory : 1; /// Processor RAM is functional + bool calibrated : 1; /// Transponder is calibrated + bool receiver : 1; /// RF signals travel through hardware correctly + bool power53v : 1; /// Voltage at the 53V power supply is correct + bool adc : 1; /// Analog-to-Digital Converter is functional + bool pressure : 1; /// Internal pressure transducer is functional + bool fpga : 1; /// FPGA I/O operations are functional + bool rxLock : 1; /// Rx oscillator reporting PLL Lock at reference frequency + bool txLock : 1; /// Tx oscillator reporting PLL Lock at reference frequency + bool mtSuppress : 1; /// Mutual suppression is operating correctly + bool temp : 1; /// Internal temperature is within range (< 110 C) + bool sqMonitor : 1; /// Squitters are transmitting at their nominal rates + bool txRate : 1; /// Transmission duty cycle is in the safe range + bool sysLatency : 1; /// Systems events occurred within expected time limits + bool txPower : 1; /// Transmission power is in-range + bool voltageIn : 1; /// Input voltage is in-range (10V-32V) + bool icao : 1; /// ICAO Address is valid (fail at '000000' or 'FFFFFF') + bool gps : 1; /// Valid GPS data is received at 1Hz, minimum +} sg_status_t; + +/** + * The XPNDR Health Monitor Response Message. + * XPNDR --> Host. + */ +typedef struct +{ + int8_t socTemp; /// System on a Chip temperature + int8_t rfTemp; /// RF Board temperature + int8_t ptTemp; /// Pressure Transducer temperature +} sg_healthmonitor_t; + +/** + * The XPNDR Version Response Message. + * XPNDR --> Host. + */ +typedef struct +{ + uint8_t swVersion; /// The SW Version major revision number + uint8_t fwVersion; /// The FW Version major revision number + uint16_t swSvnRevision; /// The SW Repository version number + uint16_t fwSvnRevision; /// The FW Repository version number +} sg_version_t; + +/** + * The XPNDR Serial Number Response Message. + * XPNDR --> Host. + */ +typedef struct +{ + char ifSN[33]; /// The Interface Board serial number + char rfSN[33]; /// The RF Board serial number + char xpndrSN[33]; /// The Transponder serial number +} sg_serialnumber_t; + +/// The state vector report type. +typedef enum +{ + svrAirborne = 1, /// Airborne state vector report type. + svrSurface /// Surface state vector report type. +} sg_svr_type_t; + +/// The state vector report participant address type. +typedef enum +{ + svrAdrIcaoUnknown, /// ICAO address unknown emitter category. + svrAdrNonIcaoUnknown, /// Non-ICAO address unknown emitter category. + svrAdrIcao, /// ICAO address aircraft. + svrAdrNonIcao, /// Non-ICAO address aircraft. + svrAdrIcaoSurface, /// ICAO address surface vehicle, fixed ground, tethered obstruction. + svrAdrNonIcaoSurface, /// Non-ICAO address surface vehicle, fixed ground, tethered obstruction. + svrAdrDup, /// Duplicate target of another ICAO address. + svrAdrAdsr /// ADS-R target. +} sg_addr_type_t; + +/// The surface part of a state vector report. +typedef struct +{ + int16_t speed; /// Surface speed. + int16_t heading; /// Surface heading. +} sg_svr_surface_t; + +/// The airborne part of a state vector report. +typedef struct +{ + int16_t velNS; /// The NS speed vector component. [knots] + int16_t velEW; /// The EW speed vector component. [knots] + int16_t speed; /// Speed from N/S and E/W velocity. [knots] + int16_t heading; /// Heading from N/S and E/W velocity. [deg from N] + int32_t geoAlt; /// Geometric altitude. [ft] + int32_t baroAlt; /// Barometric altitude. [ft] + int16_t vrate; /// Vertical rate. [ft/min] + float estLat; /// Estimated latitude. [deg N] + float estLon; /// Estimated longitude. [deg E] +} sg_svr_airborne_t; + +typedef struct +{ + bool baroVRate : 1; /// Barometric vertical rate valid. + bool geoVRate : 1; /// Geometric vertical rate valid. + bool baroAlt : 1; /// Barometric altitude valid. + bool surfHeading : 1; /// Surface heading valid. + bool surfSpeed : 1; /// Surface speed valid. + bool airSpeed : 1; /// Airborne speed and heading valid. + bool geoAlt : 1; /// Geometric altitude valid. + bool position : 1; /// Lat and lon data valid. +} sg_svr_validity_t; + +typedef struct +{ + uint8_t reserved : 6; /// Reserved. + bool estSpeed : 1; /// Estimated N/S and E/W velocity. + bool estPosition : 1; /// Estimated lat/lon position. +} sg_svr_est_validity_t; + +/** + * The XPDR ADS-B state vector report Message. + * Host --> XPDR. + * + * @note The time of applicability values are based on the MX system clock that starts + * at 0 on power up. The time is the floating point number that is the seconds since + * power up. The time number rolls over at 512.0. + */ +typedef struct +{ + sg_svr_type_t type; /// Report type. + union + { + uint8_t flags; + sg_svr_validity_t validity; /// Field validity flags. + }; + union + { + uint8_t eflags; + sg_svr_est_validity_t evalidity; /// Estimated field validity flags. + }; + uint32_t addr; /// Participant address. + sg_addr_type_t addrType; /// Participant address type. + float toaEst; /// Report estimated position and speed time of applicability. + float toaPosition; /// Report position time of applicability. + float toaSpeed; /// Report speed time of applicability. + uint8_t survStatus; /// Surveillance status. + uint8_t mode; /// Report mode. + uint8_t nic; /// Navigation integrity category. + float lat; /// Latitude. + float lon; /// Longitude. + union + { + sg_svr_surface_t surface; /// Surface SVR data. + sg_svr_airborne_t airborne; /// Airborne SVR data. + }; +} sg_svr_t; + +typedef enum +{ + msrTypeV0, + msrTypeV1Airborne, + msrTypeV1Surface, + msrTypeV2Airborne, + msrTypeV2Surface +} sg_msr_type_t; + +typedef struct +{ + uint8_t reserved : 2; + bool priority : 1; + bool sil : 1; + bool nacv : 1; + bool nacp : 1; + bool opmode : 1; + bool capcodes : 1; +} sg_msr_validity_t; + +typedef enum +{ + adsbVerDO260, + adsbVerDO260A, + adsbVerDO260B +} sg_adsb_version_t; + +typedef enum +{ + adsbUnknown, + adsbLight, + adsbSmall = 0x3, + adsbLarge = 0x5, + adsbHighVortex, + adsbHeavy, + adsbPerformance, + adsbRotorcraft = 0x0A, + adsbGlider, + adsbAir, + adsbUnmaned, + adsbSpace, + adsbUltralight, + adsbParachutist, + adsbVehicle_emg = 0x14, + adsbVehicle_serv, + adsbObsticlePoint, + adsbObsticleCluster, + adsbObsticleLinear +} sg_adsb_emitter_t; + +typedef enum +{ + priNone, + priGeneral, + priMedical, + priFuel, + priComm, + priUnlawful, + priDowned +} sg_priority_t; + +typedef enum +{ + tcrNone, + tcrSingle, + tcrMultiple +} sg_tcr_t; + +typedef struct +{ + bool b2low : 1; + bool uat : 1; + bool arv : 1; + bool tsr : 1; + bool adsb : 1; + bool tcas : 1; + sg_tcr_t tcr; +} sg_capability_t; + +typedef enum +{ + gpsLonNodata, + gpsLonSensorSupplied, + gpsLon2m, + gpsLon4m, + gpsLon6m, + gpsLon8m, + gpsLon10m, + gpsLon12m, + gpsLon14m, + gpsLon16m, + gpsLon18m, + gpsLon20m, + gpsLon22m, + gpsLon24m, + gpsLon26m, + gpsLon28m, + gpsLon30m, + gpsLon32m, + gpsLon34m, + gpsLon36m, + gpsLon38m, + gpsLon40m, + gpsLon42m, + gpsLon44m, + gpsLon46m, + gpsLon48m, + gpsLon50m, + gpsLon52m, + gpsLon54m, + gpsLon56m, + gpsLon58m, + gpsLon60m +} sg_gps_lonofs_t; + +typedef enum +{ + gpslatNodata, + gpslatLeft2m, + gpslatLeft4m, + gpslatLeft6m, + gpslatRight0m, + gpslatRight2m, + gpslatRight4m, + gpslatRight6m, +} sg_gps_latofs_t; + +typedef struct +{ + bool gpsLatFmt; + sg_gps_latofs_t gpsLatOfs; + bool gpsLonFmt; + sg_gps_lonofs_t gpsLonOfs; + bool tcasRA : 1; + bool ident : 1; + bool singleAnt : 1; +} sg_adsb_opmode_t; + +typedef enum +{ + gvaUnknown, + gvaLT150m, + gvaLT45m +} sg_gva_t; + +typedef enum +{ + nicGolham, + nicNonGilham +} sg_nicbaro_t; + +typedef enum +{ + svsilUnknown, + svsilPow3, + svsilPow5, + svsilPow7 +} sg_svsil_t; + +typedef struct +{ + sg_nacp_t nacp; + sg_nacv_t nacv; + sg_sda_t sda; + bool silSupp; + sg_svsil_t sil; + sg_gva_t gva; + sg_nicbaro_t nicBaro; +} sg_sv_qual_t; + +typedef enum +{ + trackTrueNorth, + trackMagNorth, + headingTrueNorth, + headingMagNorth +} sg_trackheading_t; + +typedef enum +{ + vrateBaroAlt, + vrateGeoAlt +} sg_vratetype_t; + +/** + * The XPDR ADS-B mode status report Message. + * Host --> XPDR. + * + * @note The time of applicability values are based on the MX system clock that starts + * at 0 on power up. The time is the floating point number that is the seconds since + * power up. The time number rolls over at 512.0. + */ +typedef struct +{ + sg_msr_type_t type; /// Report type. + + union + { + uint8_t flags; + sg_msr_validity_t validity; /// Field validity flags. + }; + + uint32_t addr; /// Participant address. + sg_addr_type_t addrType; /// Participant address type. + + float toa; + sg_adsb_version_t version; + char callsign[9]; + sg_adsb_emitter_t emitter; + sg_size_t size; + sg_priority_t priority; + sg_capability_t capability; + sg_adsb_opmode_t opMode; + sg_sv_qual_t svQuality; + sg_trackheading_t trackHeading; + sg_vratetype_t vrateType; +} sg_msr_t; + +/** + * Convert install message struct to the raw buffer format. + * + * @param[out] buffer An empty buffer to contain the raw install message. + * @param[in] stl The install message struct with fields populated. + * @param[in] msgId The sequence number for the message. + * + * @return true if successful or false on failure. + * + * @warning data in stl parameter must be pre-validated. + */ +bool sgEncodeInstall(uint8_t *buffer, sg_install_t *stl, uint8_t msgId); + +/** + * Convert flight identification struct to the raw buffer format. + * + * @param[out] buffer An empty buffer to contain the raw flight identification message. + * @param[in] id The flight id struct with fields populated. + * @param[in] msgId The sequence number for the message. + * + * @return true if successful or false on failure. + * + * @warning data in id parameter must be pre-validated. + */ +bool sgEncodeFlightId(uint8_t *buffer, sg_flightid_t *id, uint8_t msgId); + +/** + * Convert operating message struct to the raw buffer format. + * + * @param[out] buffer An empty buffer to contain the raw operating message. + * @param[in] op The operating message struct with fields populated. + * @param[in] msgId The sequence number for the message. + * + * @return true if successful or false on failure. + * + * @warning data in op parameter must be pre-validated. + */ +bool sgEncodeOperating(uint8_t *buffer, sg_operating_t *op, uint8_t msgId); + +/* TODO: Create GPS helper functions to convert other data types --> char buffers */ + +/** + * Convert GPS message struct to the raw buffer format. + * + * @param[out] buffer An empty buffer to contain the raw GPS message. + * @param[in] gps The GPS message struct with fields populated. + * @param[in] msgId The sequence number for the message. + * + * @return true if successful or false on failure. + * + * @warning data in gps parameter must be pre-validated. + */ +bool sgEncodeGPS(uint8_t *buffer, sg_gps_t *gps, uint8_t msgId); + +/** + * Convert data request message struct to the raw buffer format. + * + * @param[out] buffer An empty buffer to contain the raw target request message. + * @param[in] data The data request message struct with fields populated. + * @param[in] msgId The sequence number for the message. + * + * @return true if successful or false on failure. + * + * @warning data in data parameter must be pre-validated. + */ +bool sgEncodeDataReq(uint8_t *buffer, sg_datareq_t *data, uint8_t msgId); + +/** + * Convert target request message struct to the raw buffer format. + * + * @param[out] buffer An empty buffer to contain the raw target request message. + * @param[in] tgt The target request message struct with fields populated. + * @param[in] msgId The sequence number for the message. + * + * @return true if successful or false on failure. + * + * @warning data in tgt parameter must be pre-validated. + */ +bool sgEncodeTargetReq(uint8_t *buffer, sg_targetreq_t *tgt, uint8_t msgId); + +/** + * Process the ACK message response from the transponder. + * + * @param[in] buffer The raw ACK message buffer. + * @param[out] ack The parsed message results. + * + * @return true if successful or false on failure. + */ +bool sgDecodeAck(uint8_t *buffer, sg_ack_t *ack); + +/** + * Process the Install message response from the transponder. + * + * @param[in] buffer The raw Install message buffer. + * @param[out] stl The parsed message results. + * + * @return true if successful or false on failure. + */ +bool sgDecodeInstall(uint8_t *buffer, sg_install_t *stl); + +/** + * Process the Flight ID message response from the transponder. + * + * @param[in] buffer The raw Flight ID message buffer. + * @param[out] id The parsed message results. + * + * @return true if successful or false on failure. + */ +bool sgDecodeFlightId(uint8_t *buffer, sg_flightid_t *id); + +/** + * Process the state vector report message. + * + * @param[in] buffer The raw SVR message buffer. + * @param[out] svr The parsed SVR message. + * + * @return true if successful or false on failure. + */ +bool sgDecodeSVR(uint8_t *buffer, sg_svr_t *svr); + +/** + * Process the mode status report message. + * + * @param buffer The raw MSR message buffer. + * @param msr The parsed MSR message. + * + * @return true if successful or false on failure. + */ +bool sgDecodeMSR(uint8_t *buffer, sg_msr_t *msr); + +#endif /* SG_H */ diff --git a/libraries/AP_ADSB/sagetech-sdk/sgDecodeAck.c b/libraries/AP_ADSB/sagetech-sdk/sgDecodeAck.c new file mode 100644 index 00000000000..483c26aa524 --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/sgDecodeAck.c @@ -0,0 +1,74 @@ +/** + * @copyright Copyright (c) 2021 Sagetech, Inc. All rights reserved. + * + * @file sgDecodeAck.c + * @author jimb + * + * @date Feb 10, 2021 + * + * This file receives a raw Acknowledge message buffer and + * parses the payload into a data struct. + */ + +#include +#include +#include + +#include "sg.h" +#include "sgUtil.h" + +#define SG_ACK_XPNDR_FAIL 0x01 +#define SG_ACK_SYSTEM_FAIL 0x02 +#define SG_ACK_CRYPTO_FAIL 0x04 +#define SG_ACK_WOW 0x08 +#define SG_ACK_MAINT 0x10 +#define SG_ACK_ALT_SOURCE 0x20 +#define SG_ACK_OP_MODE 0xC0 + +typedef struct __attribute__((packed)) +{ + uint8_t start; + uint8_t type; + uint8_t id; + uint8_t payloadLen; + uint8_t ackType; + uint8_t ackId; + uint8_t state; + uint8_t alt[3]; + uint8_t checksum; +} ack_t; + +/* + * Documented in the header file. + */ +bool sgDecodeAck(uint8_t *buffer, sg_ack_t *ack) +{ + ack_t sgAck; + memcpy(&sgAck, buffer, sizeof(ack_t)); + + ack->ackType = sgAck.ackType; + ack->ackId = sgAck.ackId; + ack->failXpdr = (sgAck.state & SG_ACK_XPNDR_FAIL) > 0; + ack->failSystem = (sgAck.state & SG_ACK_SYSTEM_FAIL) > 0; + ack->failCrypto = (sgAck.state & SG_ACK_CRYPTO_FAIL) > 0; + ack->wow = (sgAck.state & SG_ACK_WOW) > 0; + ack->maint = (sgAck.state & SG_ACK_MAINT) > 0; + ack->isHostAlt = (sgAck.state & SG_ACK_ALT_SOURCE) > 0; + ack->opMode = (sgAck.state & SG_ACK_OP_MODE) >> 6; + + int32_t int24 = toInt32(sgAck.alt); + + // Bitmask altitude field to determine if alt = invalid + if ((int24 & 0x00FFFFFF) == 0x00800000) + { + ack->alt = 0; + ack->altValid = false; + } + else + { + ack->alt = int24; + ack->altValid = true; + } + + return true; +} diff --git a/libraries/AP_ADSB/sagetech-sdk/sgDecodeFlightId.c b/libraries/AP_ADSB/sagetech-sdk/sgDecodeFlightId.c new file mode 100644 index 00000000000..be9f5775df3 --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/sgDecodeFlightId.c @@ -0,0 +1,41 @@ +/** + * @copyright Copyright (c) 2021 Sagetech, Inc. All rights reserved. + * + * @file sgDecodeFlightId.c + * @author Jacob.Garrison + * + * @date Mar 10, 2021 + * + */ + +#include + +#include "sg.h" +#include "sgUtil.h" + +#define SG_ID_LEN 8 // The number of bytes in the flight id field + +typedef struct __attribute__((packed)) +{ + uint8_t start; + uint8_t type; + uint8_t id; + uint8_t payloadLen; + char flightId[SG_ID_LEN]; + uint8_t rsvd[4]; + uint8_t checksum; +} flightid_t; + +/* + * Documented in the header file. + */ +bool sgDecodeFlightId(uint8_t *buffer, sg_flightid_t *id) +{ + flightid_t sgId; + memcpy(&sgId, buffer, sizeof(flightid_t)); + + strcpy(id->flightId, sgId.flightId); + memset(&id->flightId[SG_ID_LEN], '\0', 1); // Ensure flight id is null-terminated + + return true; +} diff --git a/libraries/AP_ADSB/sagetech-sdk/sgDecodeInstall.c b/libraries/AP_ADSB/sagetech-sdk/sgDecodeInstall.c new file mode 100644 index 00000000000..d227c384cff --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/sgDecodeInstall.c @@ -0,0 +1,84 @@ +/** + * @copyright Copyright (c) 2021 Sagetech, Inc. All rights reserved. + * + * @file sgDecodeInstall.c + * @author Jacob.Garrison + * + * @date Mar 9, 2021 + * + */ + +#include +#include + +#include "sg.h" +#include "sgUtil.h" + +#define SG_REG_LEN 7 // The number of bytes in the registration field + +#define SG_STL_ANTENNA 0x03 +#define SG_STL_ALT_RES 0x08 +#define SG_STL_HDG_TYPE 0x10 +#define SG_STL_SPD_TYPE 0x20 +#define SG_STL_HEATER 0x40 +#define SG_STL_WOW 0x80 + +typedef struct __attribute__((packed)) +{ + uint8_t start; + uint8_t type; + uint8_t id; + uint8_t payloadLen; + uint8_t icao[3]; + char registration[SG_REG_LEN]; + uint8_t rsvd1[2]; + uint8_t com0; + uint8_t com1; + uint8_t ipAddress[4]; + uint8_t subnetMask[4]; + uint8_t port[2]; + uint8_t gpsIntegrity; + uint8_t emitterSet; + uint8_t emitterType; + uint8_t size; + uint8_t maxSpeed; + uint8_t altOffset[2]; + uint8_t rsvd2[2]; + uint8_t config; + uint8_t rsvd3[2]; + uint8_t checksum; +} stl_t; + +/* + * Documented in the header file. + */ +bool sgDecodeInstall(uint8_t *buffer, sg_install_t *stl) +{ + memset(&stl->reg[0], '\0', sizeof(stl->reg)); // Ensure registration is null-terminated + + stl_t sgStl; + memcpy(&sgStl, buffer, sizeof(stl_t)); + + stl->icao = toIcao(sgStl.icao); + strcpy(stl->reg, sgStl.registration); + memset(&stl->reg[SG_REG_LEN], 0, 1); // Ensure registration is null-terminated + stl->com0 = (sg_baud_t)(sgStl.com0); + stl->com1 = (sg_baud_t)(sgStl.com1); + stl->eth.ipAddress = toUint32(sgStl.ipAddress); + stl->eth.subnetMask = toUint32(sgStl.subnetMask); + stl->eth.portNumber = toUint16(sgStl.port); + stl->sil = (sg_sil_t)(sgStl.gpsIntegrity >> 4); + stl->sda = (sg_sda_t)(sgStl.gpsIntegrity & 0x0F); + stl->emitter = (sg_emitter_t)(0x10 * sgStl.emitterSet + sgStl.emitterType); + stl->size = (sg_size_t)sgStl.size; + stl->maxSpeed = (sg_airspeed_t)sgStl.maxSpeed; + stl->altOffset = toUint16(sgStl.altOffset); + stl->antenna = (sg_antenna_t)sgStl.config & SG_STL_ANTENNA; + stl->altRes100 = sgStl.config & SG_STL_ALT_RES; + stl->hdgTrueNorth = sgStl.config & SG_STL_HDG_TYPE; + stl->airspeedTrue = sgStl.config & SG_STL_SPD_TYPE; + stl->heater = sgStl.config & SG_STL_HEATER; + stl->wowConnected = sgStl.config & SG_STL_WOW; + + return true; +} diff --git a/libraries/AP_ADSB/sagetech-sdk/sgDecodeMSR.c b/libraries/AP_ADSB/sagetech-sdk/sgDecodeMSR.c new file mode 100644 index 00000000000..f802d1a0454 --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/sgDecodeMSR.c @@ -0,0 +1,203 @@ +/** + * @copyright Copyright (c) 2020 Sagetech, Inc. All rights reserved. + * + * @file sgDecodeMSR.c + * @author jim.billmeyer + * + * @date Mar 17, 2021 + */ + +#include "sg.h" +#include +#include +#include +#include "sgUtil.h" + +#define MS_PARAM_TOA (1 << 3) +#define MS_PARAM_ADSBVER (1 << 2) +#define MS_PARAM_CALLSIGN (1 << 1) +#define MS_PARAM_CATEMITTER (1 << 0) + +#define MS_PARAM_AVLEN (1 << 7) +#define MS_PARAM_PRIORITY (1 << 6) +#define MS_PARAM_CAPCODES (1 << 5) +#define MS_PARAM_OPMODE (1 << 4) +#define MS_PARAM_NACP (1 << 3) +#define MS_PARAM_NACV (1 << 2) +#define MS_PARAM_SDA (1 << 1) +#define MS_PARAM_GVA (1 << 0) + +#define MS_PARAM_NIC (1 << 7) +#define MS_PARAM_HEADING (1 << 6) +#define MS_PARAM_VRATE (1 << 5) + +#define MS_CAP_B2LOW (1 << 3) +#define MS_CAP_UAT (1 << 1) +#define MS_CAP_TCR ((1 << 2) | (1 << 3)) +#define MS_CAP_TSR (1 << 4) +#define MS_CAP_ARV (1 << 5) +#define MS_CAP_ADSB (1 << 6) +#define MS_CAP_TCAS (1 << 7) + +#define MS_OP_GPS_LATFMT (1 << 7) +#define MS_OP_GPS_LONFMT (1 << 6) +#define MS_OP_TCAS_RA (1 << 5) +#define MS_OP_IDENT (1 << 4) +#define MS_OP_SINGLE_ANT (1 << 2) + +/// the payload offset. +#define PBASE 4 + +/* + * Documented in the header file. + */ +bool sgDecodeMSR(uint8_t *buffer, sg_msr_t *msr) +{ + memset(msr, 0, sizeof(sg_msr_t)); + + uint8_t fields[3]; + memcpy(fields, &buffer[PBASE + 0], 3); + + if (buffer[PBASE + 1] == 0x6E && buffer[PBASE + 2] == 0x60) + { + msr->type = msrTypeV0; + } + else if (buffer[PBASE + 1] == 0x7E && buffer[PBASE + 2] == 0xE0) + { + msr->type = msrTypeV1Airborne; + } + else if (buffer[PBASE + 1] == 0xFE && buffer[PBASE + 2] == 0xE0) + { + msr->type = msrTypeV1Surface; + } + else if (buffer[PBASE + 1] == 0x7F && buffer[PBASE + 2] == 0xE0) + { + msr->type = msrTypeV2Airborne; + } + else if (buffer[PBASE + 1] == 0xFF && buffer[PBASE + 2] == 0xE0) + { + msr->type = msrTypeV2Surface; + } + + msr->flags = buffer[PBASE + 3]; + msr->addr = toInt32(&buffer[PBASE + 4]) & 0xFFFFFF; + msr->addrType = buffer[PBASE + 7] & 0xFF; + + uint8_t ofs = 8; + + if (fields[0] & MS_PARAM_TOA) + { + msr->toa = toTOA(&buffer[PBASE + ofs]); + ofs += 2; + } + + if (fields[0] & MS_PARAM_ADSBVER) + { + msr->version = buffer[PBASE + ofs]; + ofs++; + } + + if (fields[0] & MS_PARAM_CALLSIGN) + { + memset(msr->callsign, 0, 9); + memcpy(msr->callsign, &buffer[PBASE + ofs], 8); + ofs += 8; + } + + if (fields[0] & MS_PARAM_CATEMITTER) + { + msr->emitter = buffer[PBASE + ofs]; + ofs++; + } + + if (fields[1] & MS_PARAM_AVLEN) + { + msr->size = buffer[PBASE + ofs]; + ofs++; + } + + if (fields[1] & MS_PARAM_PRIORITY) + { + msr->priority = buffer[PBASE + ofs]; + ofs++; + } + + if (fields[1] & MS_PARAM_CAPCODES) + { + uint8_t cap = buffer[PBASE + ofs + 0]; + msr->capability.b2low = cap & MS_CAP_B2LOW; + + cap = buffer[PBASE + ofs + 1]; + msr->capability.uat = cap & MS_CAP_UAT; + msr->capability.tcr = (cap & MS_CAP_TCR) >> 2; + msr->capability.tsr = cap & MS_CAP_TSR; + msr->capability.arv = cap & MS_CAP_ARV; + msr->capability.adsb = cap & MS_CAP_ADSB; + msr->capability.tcas = cap & MS_CAP_TCAS; + + ofs += 3; + } + + if (fields[1] & MS_PARAM_OPMODE) + { + uint8_t op = buffer[PBASE + ofs + 0]; + msr->opMode.gpsLatFmt = (op & MS_OP_GPS_LATFMT) == 0; + msr->opMode.gpsLonFmt = (op & MS_OP_GPS_LONFMT) == 0; + msr->opMode.tcasRA = op & MS_OP_TCAS_RA; + msr->opMode.ident = op & MS_OP_IDENT; + msr->opMode.singleAnt = op & MS_OP_SINGLE_ANT; + + op = buffer[PBASE + ofs + 1]; + msr->opMode.gpsLatOfs = op >> 5; + msr->opMode.gpsLonOfs = op & 0x17; + + ofs += 2; + } + + if (fields[1] & MS_PARAM_NACP) + { + msr->svQuality.nacp = buffer[PBASE + ofs]; + ofs++; + } + + if (fields[1] & MS_PARAM_NACV) + { + msr->svQuality.nacv = buffer[PBASE + ofs]; + ofs++; + } + + if (fields[1] & MS_PARAM_SDA) + { + uint8_t sda = buffer[PBASE + ofs]; + msr->svQuality.sda = (sda & 0x18) >> 3; + msr->svQuality.silSupp = (sda & 0x04); + msr->svQuality.sil = (sda & 0x03); + ofs++; + } + + if (fields[1] & MS_PARAM_GVA) + { + msr->svQuality.gva = buffer[PBASE + ofs]; + ofs++; + } + + if (fields[2] & MS_PARAM_NIC) + { + msr->svQuality.nicBaro = buffer[PBASE + ofs]; + ofs++; + } + + if (fields[2] & MS_PARAM_HEADING) + { + msr->trackHeading = buffer[PBASE + ofs]; + ofs++; + } + + if (fields[2] & MS_PARAM_VRATE) + { + msr->vrateType = buffer[PBASE + ofs]; + ofs++; + } + + return true; +} diff --git a/libraries/AP_ADSB/sagetech-sdk/sgDecodeSVR.c b/libraries/AP_ADSB/sagetech-sdk/sgDecodeSVR.c new file mode 100644 index 00000000000..cf158f86bab --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/sgDecodeSVR.c @@ -0,0 +1,242 @@ +/** + * @copyright Copyright (c) 2021 Sagetech, Inc. All rights reserved. + * + * @file sgDecodeSVR.c + * @author jimb + * + * @date Feb 10, 2021 + * + * This file receives a raw ADS-B target state vector report message buffer and + * parses the payload into a data struct. + */ + +#include +#include +#include +#include + +#include "sg.h" +#include "sgUtil.h" +#include "target.h" + +// airborne surface +// -------- -------- +#define SV_PARAM_TOA_EPOS (1 << 3) // x +#define SV_PARAM_TOA_POS (1 << 2) // x x +#define SV_PARAM_TOA_VEL (1 << 1) // x x +#define SV_PARAM_LATLON (1 << 0) // x x + +#define SV_PARAM_GEOALT (1 << 7) // x +#define SV_PARAM_VEL (1 << 6) // x +#define SV_PARAM_SURF_GS (1 << 5) // x +#define SV_PARAM_SURF_HEAD (1 << 4) // x +#define SV_PARAM_BAROALT (1 << 3) // x +#define SV_PARAM_VRATE (1 << 2) // x +#define SV_PARAM_NIC (1 << 1) // x x +#define SV_PARAM_ESTLAT (1 << 0) // x + +#define SV_PARAM_ESTLON (1 << 7) // x +#define SV_PARAM_ESTNVEL (1 << 6) +#define SV_PARAM_ESTEVAL (1 << 5) +#define SV_PARAM_SURV (1 << 4) // x x +#define SV_PARAM_REPORT (1 << 3) // x x + +/// the payload offset. +#define PBASE 4 + +/* + * Documented in the header file. + */ +bool sgDecodeSVR(uint8_t *buffer, sg_svr_t *svr) +{ + // memset(svr, 0, sizeof(sg_svr_t)); + + uint8_t fields[3]; + memcpy(&fields, &buffer[PBASE + 0], 3); + + svr->type = buffer[PBASE + 0] == 0x1F ? svrAirborne : svrSurface; + svr->flags = buffer[PBASE + 3]; + svr->eflags = buffer[PBASE + 4]; + svr->addr = toInt32(&buffer[PBASE + 5]) & 0xFFFFFF; + svr->addrType = buffer[PBASE + 8] & 0xFF; + + uint8_t ofs = 9; + + if (fields[0] & SV_PARAM_TOA_EPOS) + { + svr->toaEst = toTOA(&buffer[PBASE + ofs]); + ofs += 2; + } + if (fields[0] & SV_PARAM_TOA_POS) + { + svr->toaPosition = toTOA(&buffer[PBASE + ofs]); + ofs += 2; + } + if (fields[0] & SV_PARAM_TOA_VEL) + { + svr->toaSpeed = toTOA(&buffer[PBASE + ofs]); + ofs += 2; + } + + if (fields[0] & SV_PARAM_LATLON) + { + if (svr->validity.position) + { + svr->lat = toLatLon(&buffer[PBASE + ofs + 0]); + svr->lon = toLatLon(&buffer[PBASE + ofs + 3]); + } + else + { + svr->lat = 0.0; + svr->lon = 0.0; + } + + ofs += 6; + } + + if (svr->type == svrAirborne) + { + if (fields[1] & SV_PARAM_GEOALT) + { + if (svr->validity.geoAlt) + { + svr->airborne.geoAlt = toAlt(&buffer[PBASE + ofs]); + } + else + { + svr->airborne.geoAlt = 0; + } + + ofs += 3; + } + + if (fields[1] & SV_PARAM_VEL) + { + if (svr->validity.airSpeed) + { + int16_t nvel = toVel(&buffer[PBASE + ofs + 0]); + int16_t evel = toVel(&buffer[PBASE + ofs + 2]); + + svr->airborne.heading = toHeading2((double)nvel, (double)evel); + svr->airborne.speed = sqrt(nvel * nvel + evel * evel); + svr->airborne.velEW = evel; + svr->airborne.velNS = nvel; + } + else + { + svr->airborne.heading = 0; + svr->airborne.speed = 0; + svr->airborne.velEW = 0; + svr->airborne.velNS = 0; + } + + ofs += 4; + } + + if (fields[1] & SV_PARAM_BAROALT) + { + if (svr->validity.baroAlt) + { + svr->airborne.baroAlt = toAlt(&buffer[PBASE + ofs]); + } + else + { + svr->airborne.baroAlt = 0; + } + + ofs += 3; + } + + if (fields[1] & SV_PARAM_VRATE) + { + if (svr->validity.baroVRate || svr->validity.geoVRate) + { + svr->airborne.vrate = toInt16(&buffer[PBASE + ofs]); + } + else + { + svr->airborne.vrate = 0; + } + + ofs += 2; + } + } + else + { + if (fields[1] & SV_PARAM_SURF_GS) + { + if (svr->validity.surfSpeed) + { + svr->surface.speed = toGS(&buffer[PBASE + ofs]); + } + else + { + svr->surface.speed = 0; + } + + ofs += 1; + } + + if (fields[1] & SV_PARAM_SURF_HEAD) + { + if (svr->validity.surfHeading) + { + svr->surface.heading = toHeading(&buffer[PBASE + ofs]); + } + else + { + svr->surface.heading = 0; + } + + ofs += 1; + } + } + + if (fields[1] & SV_PARAM_NIC) + { + svr->nic = buffer[PBASE + ofs]; + + ofs += 1; + } + + if (fields[1] & SV_PARAM_ESTLAT) + { + if (svr->evalidity.estPosition) + { + svr->airborne.estLat = toLatLon(&buffer[PBASE + ofs]); + } + else + { + svr->airborne.estLat = 0; + } + + ofs += 3; + } + + if (fields[2] & SV_PARAM_ESTLON) + { + if (svr->evalidity.estPosition) + { + svr->airborne.estLon = toLatLon(&buffer[PBASE + ofs]); + } + else + { + svr->airborne.estLon = 0; + } + + ofs += 3; + } + + if (fields[2] & SV_PARAM_SURV) + { + svr->survStatus = buffer[PBASE + ofs]; + ofs += 1; + } + + if (fields[2] & SV_PARAM_REPORT) + { + svr->mode = buffer[PBASE + ofs]; + } + + return true; +} diff --git a/libraries/AP_ADSB/sagetech-sdk/sgEncodeDataReq.c b/libraries/AP_ADSB/sagetech-sdk/sgEncodeDataReq.c new file mode 100644 index 00000000000..7e93c3d8d3a --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/sgEncodeDataReq.c @@ -0,0 +1,51 @@ +/** + * @copyright Copyright (c) 2021 Sagetech, Inc. All rights reserved. + * + * @file sgEncodeDataReq.c + * @author Jacob.Garrison + * + * @date Feb 23, 2021 + * + * This file receives a populated data request struct and + * converts it into a data request message buffer. + */ + +#include +#include + +#include "sg.h" +#include "sgUtil.h" + +#define SG_PAYLOAD_LEN_DATAREQ SG_MSG_LEN_DATAREQ - 5 /// the payload length. + +#define PBASE 4 /// the payload offset. + +#define OFFSET_REQ_TYPE 0 /// the requested response message type +#define OFFSET_RSVD_1 1 /// a reserved field +#define OFFSET_RSVD_2 2 /// a reserved field +#define OFFSET_RSVD_3 3 /// a reserved field + +/* + * Documented in the header file. + */ +bool sgEncodeDataReq(uint8_t *buffer, sg_datareq_t *data, uint8_t msgId) +{ + // populate header + buffer[0] = SG_MSG_START_BYTE; + buffer[1] = SG_MSG_TYPE_HOST_DATAREQ; + buffer[2] = msgId; + buffer[3] = SG_PAYLOAD_LEN_DATAREQ; + + // populate Request Type + buffer[PBASE + OFFSET_REQ_TYPE] = data->reqType; + + // populate Reserved fields + buffer[PBASE + OFFSET_RSVD_1] = 0; + buffer[PBASE + OFFSET_RSVD_2] = 0; + buffer[PBASE + OFFSET_RSVD_3] = 0; + + // populate checksum + appendChecksum(buffer, SG_MSG_LEN_DATAREQ); + + return true; +} diff --git a/libraries/AP_ADSB/sagetech-sdk/sgEncodeFlightId.c b/libraries/AP_ADSB/sagetech-sdk/sgEncodeFlightId.c new file mode 100644 index 00000000000..6b5f13061ac --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/sgEncodeFlightId.c @@ -0,0 +1,47 @@ +/** + * @copyright Copyright (c) 2021 Sagetech, Inc. All rights reserved. + * + * @file sgEncodeFlightId.c + * @author Jacob.Garrison + * + * @date Feb 25, 2021 + * + */ + +#include +#include +#include + +#include "sg.h" +#include "sgUtil.h" + +#define SG_PAYLOAD_LEN_FLIGHT SG_MSG_LEN_FLIGHT - 5 /// the payload length. + +#define PBASE 4 /// the payload offset. +#define OFFSET_ID 0 /// the flight id offset in the payload. +#define OFFSET_RSVD 8 /// the reserved field offset in the payload. + +#define ID_LEN 8 /// the length of the flight identification field. + +/* + * Documented in the header file. + */ +bool sgEncodeFlightId(uint8_t *buffer, sg_flightid_t *id, uint8_t msgId) +{ + // populate header + buffer[0] = SG_MSG_START_BYTE; + buffer[1] = SG_MSG_TYPE_HOST_FLIGHT; + buffer[2] = msgId; + buffer[3] = SG_PAYLOAD_LEN_FLIGHT; + + // populate flight identification + charArray2Buf(&buffer[PBASE + OFFSET_ID], id->flightId, ID_LEN); + + // populate reserved field + uint322Buf(&buffer[PBASE + OFFSET_RSVD], 0); + + // populate checksum + appendChecksum(buffer, SG_MSG_LEN_FLIGHT); + + return true; +} diff --git a/libraries/AP_ADSB/sagetech-sdk/sgEncodeGPS.c b/libraries/AP_ADSB/sagetech-sdk/sgEncodeGPS.c new file mode 100644 index 00000000000..7264a38cb23 --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/sgEncodeGPS.c @@ -0,0 +1,92 @@ +/** + * @copyright Copyright (c) 2021 Sagetech, Inc. All rights reserved. + * + * @file sgEncodeGPS.c + * @author Jacob.Garrison + * + * @date Mar 1, 2021 + * + * This file receives a populated GPS message struct and + * converts it into a GPS message buffer. + */ + +#include +#include + +#include "sg.h" +#include "sgUtil.h" + +#define SG_PAYLOAD_LEN_GPS SG_MSG_LEN_GPS - 5 /// the payload length. +#define _UNUSED(x) ((void)(x)) + +#define PBASE 4 /// the payload offset. +#define OFFSET_LONGITUDE 0 /// the longitude offset in the payload. +#define OFFSET_LATITUDE 11 /// the latitude offset in the payload. +#define OFFSET_SPEED 21 /// the ground speed offset in the payload. +#define OFFSET_TRACK 27 /// the ground track offset in the payload. +#define OFFSET_STATUS 35 /// the hemisphere/data status offset in the payload. +#define OFFSET_TIME 36 /// the time of fix offset in the payload. +#define OFFSET_HEIGHT 46 /// the GNSS height offset in the payload. +#define OFFSET_HPL 50 /// the horizontal protection limit offset in the payload. +#define OFFSET_HFOM 54 /// the horizontal figure of merit offset in the payload. +#define OFFSET_VFOM 58 /// the vertical figure of merit offset in the payload. +#define OFFSET_NACV 62 /// the navigation accuracy for velocity offset in the payload. + +#define LEN_LNG 11 /// bytes in the longitude field +#define LEN_LAT 10 /// bytes in the latitude field +#define LEN_SPD 6 /// bytes in the speed over ground field +#define LEN_TRK 8 /// bytes in the ground track field +#define LEN_TIME 10 /// bytes in the time of fix field + +/* + * Documented in the header file. + */ +bool sgEncodeGPS(uint8_t *buffer, sg_gps_t *gps, uint8_t msgId) +{ + // populate header + buffer[0] = SG_MSG_START_BYTE; + buffer[1] = SG_MSG_TYPE_HOST_GPS; + buffer[2] = msgId; + buffer[3] = SG_PAYLOAD_LEN_GPS; + + // populate longitude + charArray2Buf(&buffer[PBASE + OFFSET_LONGITUDE], gps->longitude, LEN_LNG); + + // populate latitude + charArray2Buf(&buffer[PBASE + OFFSET_LATITUDE], gps->latitude, LEN_LAT); + + // populate ground speed + charArray2Buf(&buffer[PBASE + OFFSET_SPEED], gps->grdSpeed, LEN_SPD); + + // populate ground track + charArray2Buf(&buffer[PBASE + OFFSET_TRACK], gps->grdTrack, LEN_TRK); + + // populate hemisphere/data status + buffer[PBASE + OFFSET_STATUS] = !gps->gpsValid << 7 | + gps->fdeFail << 6 | + gps->lngEast << 1 | + gps->latNorth; + + // populate time of fix + charArray2Buf(&buffer[PBASE + OFFSET_TIME], gps->timeOfFix, LEN_TIME); + + // populate gnss height + float2Buf(&buffer[PBASE + OFFSET_HEIGHT], gps->height); + + // populate HPL + float2Buf(&buffer[PBASE + OFFSET_HPL], gps->hpl); + + // populate HFOM + float2Buf(&buffer[PBASE + OFFSET_HFOM], gps->hfom); + + // populate VFOM + float2Buf(&buffer[PBASE + OFFSET_VFOM], gps->vfom); + + // populate NACv + buffer[PBASE + OFFSET_NACV] = gps->nacv << 4; + + // populate checksum + appendChecksum(buffer, SG_MSG_LEN_GPS); + + return true; +} diff --git a/libraries/AP_ADSB/sagetech-sdk/sgEncodeInstall.c b/libraries/AP_ADSB/sagetech-sdk/sgEncodeInstall.c new file mode 100644 index 00000000000..1b2203a2267 --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/sgEncodeInstall.c @@ -0,0 +1,134 @@ +/** + * @copyright Copyright (c) 2021 Sagetech, Inc. All rights reserved. + * + * @file sgEncodeInstall.c + * @author Jacob.Garrison + * + * @date Feb 23, 2021 + * + * This file receives a populated installation message struct and + * converts it into a installation message buffer. + */ + +#include +#include +#include + +#include "sg.h" +#include "sgUtil.h" + +#define SG_PAYLOAD_LEN_INSTALL SG_MSG_LEN_INSTALL - 5 /// the payload length. + +#define PBASE 4 /// the payload offset. +#define OFFSET_ICAO 0 /// the icao address offset in the payload. +#define OFFSET_REG 3 /// the registration offset in the payload. +#define OFFSET_RSVD1 10 /// the first reserved field offset in the payload. +#define OFFSET_COM0 12 /// the COM port 0 offset in the payload. +#define OFFSET_COM1 13 /// the COM port 1 offset in the payload. +#define OFFSET_IP 14 /// the IP address offset in the payload. +#define OFFSET_MASK 18 /// the net mask offset in the payload. +#define OFFSET_PORT 22 /// the port number offset in the payload. +#define OFFSET_GPS 24 /// the GPS integrity offset in the payload. +#define OFFSET_EMIT_SET 25 /// the emitter category offset in the payload. +#define OFFSET_EMIT_TYPE 26 /// the emitter type offset in the payload. +#define OFFSET_SIZE 27 /// the aircraft size offset in the payload. +#define OFFSET_SPEED 28 /// the maximum airspeed offset in the payload. +#define OFFSET_ENCODER 29 /// the altitude-encoder-offset offset in the payload. +#define OFFSET_RSVD2 31 /// the second reserved field offset in the payload. +#define OFFSET_CONFIG 33 /// the configuration offset in the payload. +#define OFFSET_RSVD3 34 /// the third reserved field offset in the payload. + +#define REG_LEN 7 /// the registration field length. +/* + * Documented in the header file. + */ +bool sgEncodeInstall(uint8_t *buffer, sg_install_t *stl, uint8_t msgId) +{ + // populate header + buffer[0] = SG_MSG_START_BYTE; + buffer[1] = SG_MSG_TYPE_HOST_INSTALL; + buffer[2] = msgId; + buffer[3] = SG_PAYLOAD_LEN_INSTALL; + + // populate icao address + icao2Buf(&buffer[PBASE + OFFSET_ICAO], stl->icao); + + // populate aircraft registration + charArray2Buf(&buffer[PBASE + OFFSET_REG], stl->reg, REG_LEN); + + // populate reserved fields + uint162Buf(&buffer[PBASE + OFFSET_RSVD1], 0); + + // populate COM port 0, correct enum offset + buffer[PBASE + OFFSET_COM0] = stl->com0; + + // populate COM port 1, correct enum offset + buffer[PBASE + OFFSET_COM1] = stl->com1; + + // populate IP address + uint322Buf(&buffer[PBASE + OFFSET_IP], stl->eth.ipAddress); + + // populate net mask + uint322Buf(&buffer[PBASE + OFFSET_MASK], stl->eth.subnetMask); + + // populate port number + uint162Buf(&buffer[PBASE + OFFSET_PORT], stl->eth.portNumber); + + // populate gps integrity + buffer[PBASE + OFFSET_GPS] = stl->sil << 4 | + stl->sda; + + // populate emitter category set and type + uint8_t emitSet; + uint8_t emitType; + if (stl->emitter < SG_EMIT_OFFSET_B) // group A + { + emitSet = SG_EMIT_GROUP_A; + emitType = stl->emitter - SG_EMIT_OFFSET_A; + } + else if (stl->emitter < SG_EMIT_OFFSET_C) // group B + { + emitSet = SG_EMIT_GROUP_B; + emitType = stl->emitter - SG_EMIT_OFFSET_B; + } + else if (stl->emitter < SG_EMIT_OFFSET_D) // group C + { + emitSet = SG_EMIT_GROUP_C; + emitType = stl->emitter - SG_EMIT_OFFSET_C; + } + else // group D + { + emitSet = SG_EMIT_GROUP_D; + emitType = stl->emitter - SG_EMIT_OFFSET_D; + } + buffer[PBASE + OFFSET_EMIT_SET] = emitSet; + buffer[PBASE + OFFSET_EMIT_TYPE] = emitType; + + // populate aircraft size + buffer[PBASE + OFFSET_SIZE] = stl->size; + + // populate max airspeed + buffer[PBASE + OFFSET_SPEED] = stl->maxSpeed; + + // populate altitude encoder offset + uint162Buf(&buffer[PBASE + OFFSET_ENCODER], stl->altOffset); + + // populate reserved fields + uint162Buf(&buffer[PBASE + OFFSET_RSVD2], 0); + + // populate install configuration + buffer[PBASE + OFFSET_CONFIG] = stl->wowConnected << 7 | + stl->heater << 6 | + stl->airspeedTrue << 5 | + stl->hdgTrueNorth << 4 | + stl->altRes100 << 3 | + stl->antenna; + + // populate reserved fields + uint162Buf(&buffer[PBASE + OFFSET_RSVD3], 0); + + // populate checksum + appendChecksum(buffer, SG_MSG_LEN_INSTALL); + + return true; +} diff --git a/libraries/AP_ADSB/sagetech-sdk/sgEncodeOperating.c b/libraries/AP_ADSB/sagetech-sdk/sgEncodeOperating.c new file mode 100644 index 00000000000..4a4158154c3 --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/sgEncodeOperating.c @@ -0,0 +1,105 @@ +/** + * @copyright Copyright (c) 2021 Sagetech, Inc. All rights reserved. + * + * @file sgEncodeOperating.c + * @author Jacob.Garrison + * + * @date Feb 15, 2021 + * + * This file receives a populated operating message struct and + * converts it into a operating message buffer. + */ + +#include +#include + +#include "sg.h" +#include "sgUtil.h" + +#define SG_PAYLOAD_LEN_OPMSG SG_MSG_LEN_OPMSG - 5 /// the payload length. + +#define PBASE 4 /// the payload offset. +#define OFFSET_SQUAWK 0 /// the squawk code offset in the payload. +#define OFFSET_CONFIG 2 /// the mode/config offset in the payload. +#define OFFSET_EMRG_ID 3 /// the emergency flag offset in the payload. +#define OFFSET_ALT 4 /// the altitude offset in the payload. +#define OFFSET_RATE 6 /// the climb rate offset in the payload. +#define OFFSET_HEADING 8 /// the heading offset in the payload. +#define OFFSET_AIRSPEED 10 /// the airspeed offset in the payload. + +/* + * Documented in the header file. + */ +bool sgEncodeOperating(uint8_t *buffer, sg_operating_t *op, uint8_t msgId) +{ + // populate header + buffer[0] = SG_MSG_START_BYTE; + buffer[1] = SG_MSG_TYPE_HOST_OPMSG; + buffer[2] = msgId; + buffer[3] = SG_PAYLOAD_LEN_OPMSG; + + // populate Squawk code + uint162Buf(&buffer[PBASE + OFFSET_SQUAWK], op->squawk); + + // populate Mode/Config + buffer[PBASE + OFFSET_CONFIG] = op->milEmergency << 5 | + op->enableXBit << 4 | + op->enableSqt << 3 | + op->savePowerUp << 2 | + op->opMode; + + // populate Emergency/Ident + buffer[PBASE + OFFSET_EMRG_ID] = op->identOn << 3 | + op->emergcType; + + // populate Altitude + uint16_t altCode = 0; + if (op->altUseIntrnl) + { + altCode = 0x8000; + } + else if (op->altHostAvlbl) + { + // 100 foot encoding conversion + altCode = (op->altitude + 1200) / 100; + + if (op->altRes25) + { + altCode *= 4; + } + + // 'Host altitude available' flag + altCode += 0x4000; + } + uint162Buf(&buffer[PBASE + OFFSET_ALT], altCode); + + // populate Altitude Rate + int16_t rate = op->climbRate / 64; + if (!op->climbValid) + { + rate = 0x8000; + } + uint162Buf(&buffer[PBASE + OFFSET_RATE], rate); + + // populate Heading + // conversion: heading * ( pow(2, 15) / 360 ) + uint16_t heading = op->heading * 32768 / 360; + if (op->headingValid) + { + heading += 0x8000; + } + uint162Buf(&buffer[PBASE + OFFSET_HEADING], heading); + + // populate Airspeed + uint16_t airspeed = op->airspd; + if (op->airspdValid) + { + airspeed += 0x8000; + } + uint162Buf(&buffer[PBASE + OFFSET_AIRSPEED], airspeed); + + // populate checksum + appendChecksum(buffer, SG_MSG_LEN_OPMSG); + + return true; +} diff --git a/libraries/AP_ADSB/sagetech-sdk/sgEncodeTargetReq.c b/libraries/AP_ADSB/sagetech-sdk/sgEncodeTargetReq.c new file mode 100644 index 00000000000..c7a29bff7a9 --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/sgEncodeTargetReq.c @@ -0,0 +1,63 @@ +/** + * @copyright Copyright (c) 2021 Sagetech, Inc. All rights reserved. + * + * @file sgEncodeTargetReq.c + * @author Jacob.Garrison + * + * @date Feb 19, 2021 + * + * This file receives a populated target request struct and + * converts it into a target request message buffer. + */ + +#include +#include + +#include "sg.h" +#include "sgUtil.h" + +#define SG_PAYLOAD_LEN_TARGETREQ SG_MSG_LEN_TARGETREQ - 5 /// the payload length. + +#define PBASE 4 /// the payload offset. + +#define OFFSET_REQ_TYPE 0 /// the adsb reporting type and transmit port offset +#define OFFSET_MAX_TARGETS 1 /// the maximum number of targets offset +#define OFFSET_ICAO 3 /// the requested target icao offset +#define OFFSET_REPORTS 6 /// the requested report type offset +/* + * Documented in the header file. + */ +bool sgEncodeTargetReq(uint8_t *buffer, sg_targetreq_t *tgt, uint8_t msgId) +{ + + // populate header + buffer[0] = SG_MSG_START_BYTE; + buffer[1] = SG_MSG_TYPE_HOST_TARGETREQ; + buffer[2] = msgId; + buffer[3] = SG_PAYLOAD_LEN_TARGETREQ; + + // populate Request Type + buffer[PBASE + OFFSET_REQ_TYPE] = tgt->transmitPort << 6 | + tgt->reqType; + + // populate Max Targets + uint162Buf(&buffer[PBASE + OFFSET_MAX_TARGETS], tgt->maxTargets); + + // populate Requested ICAO + icao2Buf(&buffer[PBASE + OFFSET_ICAO], tgt->icao); + + // populated Requested Reports + buffer[PBASE + OFFSET_REPORTS] = tgt->ownship << 7 | + tgt->commA << 6 | + tgt->military << 5 | + tgt->tisb << 4 | + tgt->airRefVel << 3 | + tgt->targetState << 2 | + tgt->modeStatus << 1 | + tgt->stateVector; + + // populate checksum + appendChecksum(buffer, SG_MSG_LEN_TARGETREQ); + + return true; +} diff --git a/libraries/AP_ADSB/sagetech-sdk/sgUtil.h b/libraries/AP_ADSB/sagetech-sdk/sgUtil.h new file mode 100644 index 00000000000..a0d3dd3223f --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/sgUtil.h @@ -0,0 +1,325 @@ +/** + * @copyright Copyright (c) 2021 Sagetech, Inc. All rights reserved. + * + * @file sgUtil.h + * @author jimb + * + * @date Feb 2, 2021 + */ + +#ifndef UTIL_H +#define UTIL_H + +#include + +#ifndef swap16 +#define swap16(data) \ + ((((data) >> 8) & 0x00FF) | (((data) << 8) & 0xFF00)) +#endif + +#ifndef swap24 +#define swap24(data) \ + (((data) >> 16) | ((data)&0x00FF00) | (((data) << 16) & 0xFF0000)) +#endif + +#ifndef swap32 +#define swap32(data) \ + (((data) >> 24) | (((data)&0x00FF0000) >> 8) | (((data)&0x0000FF00) << 8) | ((data) << 24)) +#endif + +#ifndef swap64 +#define swap64(data) \ + (swap32((data & 0x00000000ffffffffULL))) << 32 | swap32(data >> 32)) +#endif + +#ifndef PI +#define PI 3.14159265359 +#endif + +#ifndef toRad +#define toRad(deg) \ + ((deg)*PI / 180.0) +#endif + +#ifndef toDeg +#define toDeg(rad) \ + ((rad)*180 / PI) +#endif + +#ifndef toMeter +#define toMeter(feet) \ + ((feet)*0.3048) +#endif + +#ifndef toFeet +#define toFeet(meter) \ + ((meter)*3.2808) +#endif + +/** + * Converts an array of bytes to a 16 bit integer. + * + * @param bytes The array of bytes to convert. + * + * @return The 16 bit integer. + */ +int16_t toInt16(const uint8_t bytes[]); + +/** + * Converts an array of bytes to a 32 bit integer. + * + * @param bytes The array of bytes to convert. + * + * @return The 32 bit integer. + */ +int32_t toInt32(const uint8_t bytes[]); + +/** + * Converts an array of bytes to a 16 unsigned bit integer. + * + * @param bytes The array of bytes to convert. + * + * @return The 16 bit integer. + */ +uint16_t toUint16(const uint8_t bytes[]); + +/** + * Converts an array of bytes to a 24 bit unsigned integer with leading 0s. + * + * @param bytes The array of bytes to convert. + * + * @return The 24 bit unsigned integer with leading 0s. + */ +uint32_t toUint24(const uint8_t bytes[]); + +/** + * Converts an array of bytes to a 32 bit unsigned integer. + * + * @param bytes The array of bytes to convert. + * + * @return The 32 bit unsigned integer. + */ +uint32_t toUint32(const uint8_t bytes[]); + +/** + * Converts an array of bytes to a distance. + * + * @param bytes The array of bytes to convert. + * + * @return The distance value. + */ +double toDist(const uint8_t *bytes); + +/** + * Converts an array of bytes to a 24 bit unsigned integer with leading 0's. + * + * @param bytes The array of bytes to convert. + * + * @return The 32 bit unsigned integer. + */ +uint32_t toIcao(const uint8_t bytes[]); + +/** + * Converts an array of bytes to a lat/lon floating point number. + * + * @param bytes The array of bytes to convert. + * + * @return The lat/lon value. + */ +double toLatLon(const uint8_t bytes[]); + +/** + * Convert an array to an altitude. + * + * @param bytes The bytes to get the altitude from. + * + * @return The converted altitude. + */ +double toAlt(const uint8_t bytes[]); + +/** + * Converts an array of bytes to an airborne velocity. + * + * @param bytes The bytes to extract the velocity. + * + * @return The converted velocity. + */ +double toVel(const uint8_t bytes[]); + +/** + * Converts the array of bytes to the surface ground speed. + * + * @param bytes The bytes to extract the ground speed. + * + * @return The converted ground speed. + */ +uint8_t toGS(const uint8_t bytes[]); + +/** + * Converts the bytes into the heading value. + * + * @param bytes The bytes holding the heading value. + * + * @return The heading. + */ +double toHeading(const uint8_t bytes[]); + +/** + * Determine heading from y and x speed vectors. + * + * @param y The y speed vector. + * @param x The x speed vector. + * + * @return The resulting heading. + */ +int16_t toHeading2(double y, double x); + +/** + * Convert the array of bytes to a time of applicability (TOA). + * + * @param bytes The bytes to convert to a TOA. + * + * @return The converted TOA. + */ +float toTOA(const uint8_t bytes[]); + +/** + * Convert an array of bytes to a float + * + * @param bufferPos the address of the field's first corresponding buffer byte. + * + * @return The converted float value. + */ + +float toFloat(const uint8_t *bufferPos); + +/** + * Convert an array of bytes to a double + * + * @param bufferPos the address of the field's first corresponding buffer byte. + * + * @return The converted double value. + */ + +double toDouble(const uint8_t *bufferPos); + +/** + * Converts a uint16_t into its host message buffer format + * + * @param bufferPos The address of the field's first corresponding buffer byte. + * @param value The uint16_t to be converted. + * + * no return value, two buffer bytes are filled by reference + */ +void uint162Buf(uint8_t *bufferPos, uint16_t value); + +/** + * Converts a int16_t into its host message buffer format + * + * @param bufferPos The address of the field's first corresponding buffer byte. + * @param value The int32_t to be converted. + * + * no return value, two buffer bytes are filled by reference + */ +void int242Buf(uint8_t *bufferPos, int32_t value); + +/** + * Converts a uint32_t into a 24 bit host message buffer format + * + * @param bufferPos The address of the field's first corresponding buffer byte. + * @param value The int32_t to be converted. + * + * no return value, three buffer bytes are filled by reference + */ +void uint242Buf(uint8_t *bufferPos, uint32_t value); + +/** + * Converts a uint32_t into its host message buffer format + * + * @param bufferPos The address of the field's first corresponding buffer byte. + * @param value The uint32_t to be converted. + * + * no return value, two buffer bytes are filled by reference + */ +void uint322Buf(uint8_t *bufferPos, uint32_t value); + +/** + * Converts a uint32_t containing an ICAO into its 24-bit host message buffer format + * + * @param bufferPos The address of the field's first corresponding buffer byte. + * @param icao The uint32_t ICAO to be converted. + * + * no return value, three buffer bytes are filled by reference + * + * @warning icao parameter must be between 0x000000 and 0xFFFFFF + */ +void icao2Buf(uint8_t *bufferPos, uint32_t icao); + +/** + * Converts an array of characters into its host message buffer format + * + * @param bufferPos The address of the field's first corresponding buffer byte. + * @param arr[] The array of characters. + * @param len The number of characters in the array. + * + * no return value, the specified quantity of buffer bytes are filled by reference + */ +void charArray2Buf(uint8_t *bufferPos, char arr[], uint8_t len); + +/** + * Converts a float into its host message buffer format + * + * @param bufferPos The address of the field's first corresponding buffer byte. + * @param value The float to be converted. + * + * no return value, four buffer bytes are filled by reference + * + * @warning The output of this function depends on the machine's endianness. It is designed + * for Little-Endian machines, only. + */ +void float2Buf(uint8_t *bufferPos, float value); + +/** + * Converts a double into its host message buffer format + * + * @param bufferPos The address of the field's first corresponding buffer byte + * @param value The double to be converted + * + * no return value, eight buffer bytes are filled by reference + * + * @warning The output of this function depends on the machine's endianness. It is designed + * for Little-Endian machines, only + */ +void double2Buf(uint8_t *bufferPos, double value); + +/** + * Converts a double into an encoded lat/lon buffer format. + * + * @param bytes address of the field's first corresponding buffer byte + * @param value the double to be converted. + * + * no return value, 3 buffer bytes are filled by reference. + */ +void latLon2Buf(uint8_t bytes[], double value); + +/** + * Calculate checksum for a host message. + * + * @param buffer The raw message buffer. + * @param len The total quantity of bytes in the buffer + * + * @return The resulting checksum. + */ +uint8_t calcChecksum(uint8_t *buffer, uint8_t len); + +/** + * Add the checksum to a host message. + * + * @param buffer The raw message buffer. + * @param len The total quantity of bytes in the buffer + * + * no return value, final buffer byte is set to the checksum value. + */ +void appendChecksum(uint8_t *buffer, uint8_t len); + +#endif /* UTIL_H */ diff --git a/libraries/AP_ADSB/sagetech-sdk/target.c b/libraries/AP_ADSB/sagetech-sdk/target.c new file mode 100644 index 00000000000..938a54ddcf7 --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/target.c @@ -0,0 +1,142 @@ +/** + * @copyright Copyright (c) 2020 SoftSolutions, Inc. All rights reserved. + * + * @File: target.c + * @Author: jim billmeyer + * + * @date December 11, 2020, 12:50 AM + */ + +#include +#include "target.h" + +static ownship_t ownship; +static target_t targets[XPNDR_ADSB_TARGETS] = { + { + 0, + }, +}; + +/* + * Documented in the header file. + */ +target_t *targetList(void) +{ + return targets; +} + +/* + * Documented in the header file. + */ +ownship_t *targetOwnship(void) +{ + return &ownship; +} + +/* + * Documented in the header file. + */ +target_t *targetFind(uint32_t icao) +{ + for (uint16_t i = 0; i < XPNDR_ADSB_TARGETS; i++) + { + if (icao == targets[i].icao) + { + // clear strike counter and set find flag while preserving the used bit. + targets[i].flag = TARGET_FLAG_FOUND | TARGET_FLAG_USED; + return &targets[i]; + } + } + + return 0; +} + +/* + * Documented in the header file. + */ +void targetPurge(void) +{ + for (uint16_t i = 0; i < XPNDR_ADSB_TARGETS; i++) + { + // the the found flag was not set increment the strike counter. + if ((targets[i].flag & TARGET_FLAG_USED) && ((targets[i].flag & TARGET_FLAG_FOUND) == 0)) + { + uint8_t strikes = (targets[i].flag & 0xFE) >> 2; + strikes++; + + if (strikes > 5) + { + memset(&targets[i], 0, sizeof(target_t)); + } + else + { + // set the strike counter and clear the found flag. + targets[i].flag = strikes << 2 | TARGET_FLAG_USED; + } + } + else + { + // clear the found flag so the target find function can set it + // to signal that the icao address is still in range. + targets[i].flag = targets[i].flag & (TARGET_FLAG_STRIKE_MASK | TARGET_FLAG_USED); + } + } +} + +/* + * Documented in the header file. + */ +void targetAdd(target_t *target) +{ + for (uint16_t i = 0; i < XPNDR_ADSB_TARGETS; i++) + { + if ((targets[i].flag & TARGET_FLAG_USED) == 0x0) + { + memcpy(&targets[i], target, sizeof(target_t)); + targets[i].flag = TARGET_FLAG_USED; + break; + } + } +} + +/* + * Documented in the header file. + */ +targetclimb_t targetClimb(int16_t vrate) +{ + if (abs(vrate) < 500) + { + return trafLevel; + } + else if (vrate > 0) + { + return trafClimb; + } + else + { + return trafDescend; + } +} + +/* + * Documented in the header file. + */ +targetalert_t targetAlert(double dist, + uint16_t alt, + int16_t nvel, + int16_t evel) +{ + if (alt <= 3000) + { + if (dist <= 3.0) + { + return trafResolution; + } + else if (dist <= 6.0) + { + return trafAdvisory; + } + } + + return trafTraffic; +} diff --git a/libraries/AP_ADSB/sagetech-sdk/target.h b/libraries/AP_ADSB/sagetech-sdk/target.h new file mode 100644 index 00000000000..110a8d795b2 --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/target.h @@ -0,0 +1,131 @@ +/** + * @copyright Copyright (c) 2020 Sagetech, Inc. All rights reserved. + * + * @File: target.h + * @Author: jim billmeyer + * + * @date December 11, 2020, 12:49 AM + */ + +#ifndef TARGET_H +#define TARGET_H + +#include +#include +#include + +#define XPNDR_ADSB_TARGETS 400 // change this to the max number of + // target supported in the system. + +typedef enum +{ + trafLevel, + trafClimb, + trafDescend +} targetclimb_t; + +typedef enum +{ + trafTraffic, + trafAdvisory, + trafResolution +} targetalert_t; + +// bit 0 - target found flag. +// bit 1 - target slot in use. +// bits 2-7 - the strike counter. +#define TARGET_FLAG_FOUND 0x01 +#define TARGET_FLAG_USED 0x02 +#define TARGET_FLAG_STRIKE_MASK 0xFC + +typedef struct __attribute__((packed)) +{ + uint32_t icao; + bool airborne; + float bearing; + uint8_t distance; + int8_t altDiff; + int16_t nvel; + int16_t evel; + targetclimb_t climb; + targetalert_t alert; +#ifdef TARGET_SVR + msg_svr_t svr; +#endif + uint8_t flag; // used internally to purge stale targets. +} target_t; + +typedef struct +{ + uint32_t icao; + bool airborne; + float lat; + float lon; + int32_t alt; + int16_t heading; + uint16_t speed; +} ownship_t; + +/** + * Gets the target list. + * + * @return The array of traffic targets. + */ +target_t *targetList(void); + +/** + * Gets the ownship target information. + * + * @return The ownship target info. + */ +ownship_t *targetOwnship(void); + +/** + * Find a target based on its icao number. + * + * @param icao The target's icao number + * + * @return A pointer to the target element or null if not found. + */ +target_t *targetFind(uint32_t icao); + +/** + * Purge the traffic target list of stale traffic. + * + * The traffic gets purged if a find has not been done based + * on a strike counter. + */ +void targetPurge(void); + +/** + * Adds a target to the traffic target list. + * + * @param target The target to add. + */ +void targetAdd(target_t *target); + +/** + * Gets the target climb flag based on the vertical rate. + * + * @param vrate The current vertical rate of climb for the target. + * + * @return The level, climb or descend flag. + */ +targetclimb_t targetClimb(int16_t vrate); + +/** + * Gets the traffic alert flag. + * + * @param dist The distance of the target to the ownship. + * @param alt The altitude difference between the target and ownship. + * @param nvel The NS speed vector of the target. + * @param evel The EW speed vector of the target. + * + * @return The traffic flag based on the parameters. + */ +targetalert_t targetAlert(double dist, + uint16_t alt, + int16_t nvel, + int16_t evel); + +#endif /* TARGET_H */ diff --git a/libraries/AP_ADSB/sagetech-sdk/toAlt.c b/libraries/AP_ADSB/sagetech-sdk/toAlt.c new file mode 100644 index 00000000000..9ca513888ba --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/toAlt.c @@ -0,0 +1,24 @@ +/** + * @copyright Copyright (c) 2021 Sagetech, Inc. All rights reserved. + * + * @file toAlt.c + * @author Jacob.Garrison + * + * @date Mar 2, 2021 + * + */ + +#include "sgUtil.h" + +#define SV_RES_ALT 0.015625 + +/* + * Documented in the header file. + */ +double toAlt(const uint8_t bytes[]) +{ + double value = toInt32(bytes); + value *= SV_RES_ALT; + + return value; +} diff --git a/libraries/AP_ADSB/sagetech-sdk/toGS.c b/libraries/AP_ADSB/sagetech-sdk/toGS.c new file mode 100644 index 00000000000..248d029d1df --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/toGS.c @@ -0,0 +1,58 @@ +/** + * @copyright Copyright (c) 2021 Sagetech, Inc. All rights reserved. + * + * @file toGS.c + * @author Jacob.Garrison + * + * @date Mar 2, 2021 + * + */ + +#include "sgUtil.h" + +/* + * Documented in the header file. + */ +uint8_t toGS(const uint8_t bytes[]) +{ + uint8_t code = bytes[0]; + float gs = 0.0f; + + if (code <= 0x01) + { + gs = 0.0f; + } + else if (code <= 0x08) + { + gs = 1.0f; + } + else if (code <= 0x0C) + { + gs = 1.0f + (code - 0x09) * 0.25f; + } + else if (code <= 0x26) + { + gs = 2.0f + (code - 0x0D) * 0.5f; + } + else if (code <= 0x5D) + { + gs = 15.0f + (code - 0x27) * 1.0f; + } + else if (code <= 0x6C) + { + gs = 70.0f + (code - 0x5E) * 2.0f; + } + else if (code <= 0x7B) + { + gs = 100.0f + (code - 0x6D) * 5.0f; + } + else + { + gs = 176.0f; + } + + // first converting to an 16 bit integer is necessary + // to keep the floating point conversion from + // truncating to 0. + return (uint8_t)((int16_t)gs & 0xFF); +} diff --git a/libraries/AP_ADSB/sagetech-sdk/toHeading.c b/libraries/AP_ADSB/sagetech-sdk/toHeading.c new file mode 100644 index 00000000000..4b178ea1091 --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/toHeading.c @@ -0,0 +1,24 @@ +/** + * @copyright Copyright (c) 2021 Sagetech, Inc. All rights reserved. + * + * @file toHeading.c + * @author Jacob.Garrison + * + * @date Mar 2, 2021 + * + */ + +#include "sgUtil.h" + +#define SV_RES_HEAD 1.40625 + +/* + * Documented in the header file. + */ +double toHeading(const uint8_t bytes[]) +{ + double value = bytes[0]; + value *= SV_RES_HEAD; + + return value; +} diff --git a/libraries/AP_ADSB/sagetech-sdk/toHeading2.c b/libraries/AP_ADSB/sagetech-sdk/toHeading2.c new file mode 100644 index 00000000000..8219fb23ff9 --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/toHeading2.c @@ -0,0 +1,36 @@ +/** + * @copyright Copyright (c) 2021 Sagetech, Inc. All rights reserved. + * + * @file toHeading2.c + * @author Jacob.Garrison + * + * @date Mar 2, 2021 + * + */ + +#include + +#include "sgUtil.h" + +/* + * Documented in the header file. + */ +int16_t toHeading2(double y, double x) +{ + int16_t heading = (toDeg(atan2(y, x)) + 0.5); + heading = 360 - heading + 90; // atan is ccw 0 degrees at x = 1 and y = 0. + + if (heading > 360) + { + heading -= 360; + } + else + { + while (heading < 0) + { + heading += 360; + } + } + + return heading; +} diff --git a/libraries/AP_ADSB/sagetech-sdk/toIcao.c b/libraries/AP_ADSB/sagetech-sdk/toIcao.c new file mode 100644 index 00000000000..090933b1ffd --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/toIcao.c @@ -0,0 +1,21 @@ +/** + * @copyright Copyright (c) 2021 Sagetech, Inc. All rights reserved. + * + * @file toIcao.c + * @author Jacob.Garrison + * + * @date Mar 9, 2021 + * + */ + +#include "sgUtil.h" + +/* + * Documented in the header file. + */ +uint32_t toIcao(const uint8_t bytes[]) +{ + uint32_t icao = (0 << 24) | ((uint32_t)bytes[0] << 16) | ((uint32_t)bytes[1] << 8) | ((uint32_t)bytes[2]); + + return icao; +} diff --git a/libraries/AP_ADSB/sagetech-sdk/toInt16.c b/libraries/AP_ADSB/sagetech-sdk/toInt16.c new file mode 100644 index 00000000000..c88c80d7a9f --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/toInt16.c @@ -0,0 +1,21 @@ +/** + * @copyright Copyright (c) 2021 Sagetech, Inc. All rights reserved. + * + * @file toInt16.c + * @author Jacob.Garrison + * + * @date Mar 2, 2021 + * + */ + +#include "sgUtil.h" + +/* + * Documented in the header file. + */ +int16_t toInt16(const uint8_t bytes[]) +{ + int16_t int16 = ((int16_t)bytes[0] << 8) | bytes[1]; + + return int16; +} diff --git a/libraries/AP_ADSB/sagetech-sdk/toInt32.c b/libraries/AP_ADSB/sagetech-sdk/toInt32.c new file mode 100644 index 00000000000..62466085a0f --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/toInt32.c @@ -0,0 +1,22 @@ +/** + * @copyright Copyright (c) 2021 Sagetech, Inc. All rights reserved. + * + * @file toInt32.c + * @author Jacob.Garrison + * + * @date Mar 2, 2021 + * + */ + +#include "sgUtil.h" + +/* + * Documented in the header file. + */ +int32_t toInt32(const uint8_t bytes[]) +{ + int32_t int32 = ((int32_t)bytes[0] << 24) | ((int32_t)bytes[1] << 16) | ((int32_t)bytes[2] << 8); + int32 = int32 >> 8; + + return int32; +} diff --git a/libraries/AP_ADSB/sagetech-sdk/toLatLon.c b/libraries/AP_ADSB/sagetech-sdk/toLatLon.c new file mode 100644 index 00000000000..90319c71a52 --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/toLatLon.c @@ -0,0 +1,24 @@ +/** + * @copyright Copyright (c) 2021 Sagetech, Inc. All rights reserved. + * + * @file toLatLon.c + * @author Jacob.Garrison + * + * @date Mar 2, 2021 + * + */ + +#include "sgUtil.h" + +#define SV_RES_LATLON 180.0 / 8388608.0 // 180 degrees / 2^23 + +/* + * Documented in the header file. + */ +double toLatLon(const uint8_t bytes[]) +{ + double value = toInt32(bytes); + value *= SV_RES_LATLON; + + return value; +} diff --git a/libraries/AP_ADSB/sagetech-sdk/toTOA.c b/libraries/AP_ADSB/sagetech-sdk/toTOA.c new file mode 100644 index 00000000000..32043d40189 --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/toTOA.c @@ -0,0 +1,20 @@ +/** + * @copyright Copyright (c) 2021 Sagetech, Inc. All rights reserved. + * + * @file toTOA.c + * @author Jacob.Garrison + * + * @date Mar 2, 2021 + * + */ + +#include "sgUtil.h" + +/* + * Documented in the header file. + */ +float toTOA(const uint8_t bytes[]) +{ + float toa = toInt16(bytes) & 0xFFFF; + return toa / 128.0; +} diff --git a/libraries/AP_ADSB/sagetech-sdk/toUint16.c b/libraries/AP_ADSB/sagetech-sdk/toUint16.c new file mode 100644 index 00000000000..d734952dfdb --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/toUint16.c @@ -0,0 +1,21 @@ +/** + * @copyright Copyright (c) 2021 Sagetech, Inc. All rights reserved. + * + * @file toUint16.c + * @author Jacob.Garrison + * + * @date Mar 9, 2021 + * + */ + +#include "sgUtil.h" + +/* + * Documented in the header file. + */ +uint16_t toUint16(const uint8_t bytes[]) +{ + uint16_t uint16 = ((uint16_t) bytes[0] << 8 | (uint16_t) bytes[1]); + + return uint16; +} diff --git a/libraries/AP_ADSB/sagetech-sdk/toUint32.c b/libraries/AP_ADSB/sagetech-sdk/toUint32.c new file mode 100644 index 00000000000..78aee345010 --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/toUint32.c @@ -0,0 +1,21 @@ +/** + * @copyright Copyright (c) 2021 Sagetech, Inc. All rights reserved. + * + * @file toUint32.c + * @author Jacob.Garrison + * + * @date Mar 2, 2021 + * + */ + +#include "sgUtil.h" + +/* + * Documented in the header file. + */ +uint32_t toUint32(const uint8_t bytes[]) +{ + uint32_t uint32 = ((uint32_t) bytes[0] << 24) | ((uint32_t) bytes[1] << 16) | ((uint32_t) bytes[2] << 8) | ((uint32_t) bytes[3]); + + return uint32; +} diff --git a/libraries/AP_ADSB/sagetech-sdk/toVel.c b/libraries/AP_ADSB/sagetech-sdk/toVel.c new file mode 100644 index 00000000000..85eea53a24b --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/toVel.c @@ -0,0 +1,24 @@ +/** + * @copyright Copyright (c) 2021 Sagetech, Inc. All rights reserved. + * + * @file toVel.c + * @author Jacob.Garrison + * + * @date Mar 2, 2021 + * + */ + +#include "sgUtil.h" + +#define SV_RES_VEL 0.125 + +/* + * Documented in the header file. + */ +double toVel(const uint8_t bytes[]) +{ + double value = toInt16(bytes); + value *= SV_RES_VEL; + + return value; +} diff --git a/libraries/AP_ADSB/sagetech-sdk/uint162Buf.c b/libraries/AP_ADSB/sagetech-sdk/uint162Buf.c new file mode 100644 index 00000000000..597742d9a0d --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/uint162Buf.c @@ -0,0 +1,20 @@ +/** + * @copyright Copyright (c) 2021 Sagetech, Inc. All rights reserved. + * + * @file uint162Buf.c + * @author Jacob.Garrison + * + * @date Mar 2, 2021 + * + */ + +#include "sgUtil.h" + +/* + * Documented in the header file. + */ +void uint162Buf(uint8_t *bufferPos, uint16_t value) +{ + bufferPos[0] = value >> 8; + bufferPos[1] = value & 0xFF; +} diff --git a/libraries/AP_ADSB/sagetech-sdk/uint322Buf.c b/libraries/AP_ADSB/sagetech-sdk/uint322Buf.c new file mode 100644 index 00000000000..a2900eea761 --- /dev/null +++ b/libraries/AP_ADSB/sagetech-sdk/uint322Buf.c @@ -0,0 +1,22 @@ +/** + * @copyright Copyright (c) 2021 Sagetech, Inc. All rights reserved. + * + * @file uint322Buf.c + * @author Jacob.Garrison + * + * @date Mar 2, 2021 + * + */ + +#include "sgUtil.h" + +/* + * Documented in the header file. + */ +void uint322Buf(uint8_t *bufferPos, uint32_t value) +{ + bufferPos[0] = (value & 0xFF000000) >> 24; + bufferPos[1] = (value & 0x00FF0000) >> 16; + bufferPos[2] = (value & 0x0000FF00) >> 8; + bufferPos[3] = (value & 0x000000FF); +} diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index ab414a545e4..5e38709ed74 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -22,15 +22,18 @@ #include "AP_AHRS.h" #include "AP_AHRS_View.h" #include +#include #include #include #include +#include #include #include #include #include #include #include +#include #define ATTITUDE_CHECK_THRESH_ROLL_PITCH_RAD radians(10) #define ATTITUDE_CHECK_THRESH_YAW_RAD radians(20) @@ -112,8 +115,8 @@ const AP_Param::GroupInfo AP_AHRS::var_info[] = { // @Param: ORIENTATION // @DisplayName: Board Orientation - // @Description: Overall board orientation relative to the standard orientation for the board type. This rotates the IMU and compass readings to allow the board to be oriented in your vehicle at any 90 or 45 degree angle. The label for each option is specified in the order of rotations for that orientation. This option takes affect on next boot. After changing you will need to re-level your vehicle. - // @Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Yaw45Roll180,10:Yaw90Roll180,11:Yaw135Roll180,12:Pitch180,13:Yaw225Roll180,14:Yaw270Roll180,15:Yaw315Roll180,16:Roll90,17:Yaw45Roll90,18:Yaw90Roll90,19:Yaw135Roll90,20:Roll270,21:Yaw45Roll270,22:Yaw90Roll270,23:Yaw135Roll270,24:Pitch90,25:Pitch270,26:Yaw90Pitch180,27:Yaw270Pitch180,28:Pitch90Roll90,29:Pitch90Roll180,30:Pitch90Roll270,31:Pitch180Roll90,32:Pitch180Roll270,33:Pitch270Roll90,34:Pitch270Roll180,35:Pitch270Roll270,36:Yaw90Pitch180Roll90,37:Yaw270Roll90,38:Yaw293Pitch68Roll180,39:Pitch315,40:Pitch315Roll90,42:Roll45,43:Roll315,100:Custom + // @Description: Overall board orientation relative to the standard orientation for the board type. This rotates the IMU and compass readings to allow the board to be oriented in your vehicle at any 90 or 45 degree angle. The label for each option is specified in the order of rotations for that orientation. This option takes affect on next boot. After changing you will need to re-level your vehicle. Firmware versions 4.2 and prior can use a CUSTOM (100) rotation to set the AHRS_CUSTOM_ROLL/PIT/YAW angles for AHRS orientation. Later versions provide two general custom rotations which can be used, Custom 1 and Custom 2, with CUST_ROT1_ROLL/PIT/YAW or CUST_ROT2_ROLL/PIT/YAW angles. + // @Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Yaw45Roll180,10:Yaw90Roll180,11:Yaw135Roll180,12:Pitch180,13:Yaw225Roll180,14:Yaw270Roll180,15:Yaw315Roll180,16:Roll90,17:Yaw45Roll90,18:Yaw90Roll90,19:Yaw135Roll90,20:Roll270,21:Yaw45Roll270,22:Yaw90Roll270,23:Yaw135Roll270,24:Pitch90,25:Pitch270,26:Yaw90Pitch180,27:Yaw270Pitch180,28:Pitch90Roll90,29:Pitch90Roll180,30:Pitch90Roll270,31:Pitch180Roll90,32:Pitch180Roll270,33:Pitch270Roll90,34:Pitch270Roll180,35:Pitch270Roll270,36:Yaw90Pitch180Roll90,37:Yaw270Roll90,38:Yaw293Pitch68Roll180,39:Pitch315,40:Pitch315Roll90,42:Roll45,43:Roll315,100:Custom 4.1 and older,101:Custom 1,102:Custom 2 // @User: Advanced AP_GROUPINFO("ORIENTATION", 9, AP_AHRS, _board_orientation, 0), @@ -152,7 +155,8 @@ const AP_Param::GroupInfo AP_AHRS::var_info[] = { // @Units: deg // @Increment: 1 // @User: Advanced - AP_GROUPINFO("CUSTOM_ROLL", 15, AP_AHRS, _custom_roll, 0), + + // index 15 // @Param: CUSTOM_PIT // @DisplayName: Board orientation pitch offset @@ -161,7 +165,8 @@ const AP_Param::GroupInfo AP_AHRS::var_info[] = { // @Units: deg // @Increment: 1 // @User: Advanced - AP_GROUPINFO("CUSTOM_PIT", 16, AP_AHRS, _custom_pitch, 0), + + // index 16 // @Param: CUSTOM_YAW // @DisplayName: Board orientation yaw offset @@ -170,7 +175,8 @@ const AP_Param::GroupInfo AP_AHRS::var_info[] = { // @Units: deg // @Increment: 1 // @User: Advanced - AP_GROUPINFO("CUSTOM_YAW", 17, AP_AHRS, _custom_yaw, 0), + + // index 17 AP_GROUPEND }; @@ -225,6 +231,26 @@ void AP_AHRS::init() #if HAL_NMEA_OUTPUT_ENABLED _nmea_out = AP_NMEA_Output::probe(); #endif + +#if !APM_BUILD_TYPE(APM_BUILD_AP_Periph) + // convert to new custom rotaton + // PARAMETER_CONVERSION - Added: Nov-2021 + if (_board_orientation == ROTATION_CUSTOM_OLD) { + _board_orientation.set_and_save(ROTATION_CUSTOM_1); + AP_Param::ConversionInfo info; + if (AP_Param::find_top_level_key_by_pointer(this, info.old_key)) { + info.type = AP_PARAM_FLOAT; + float rpy[3] = {}; + AP_Float rpy_param; + for (info.old_group_element=15; info.old_group_element<=17; info.old_group_element++) { + if (AP_Param::find_old_parameter(&info, &rpy_param)) { + rpy[info.old_group_element-15] = rpy_param.get(); + } + } + AP::custom_rotations().convert(ROTATION_CUSTOM_1, rpy[0], rpy[1], rpy[2]); + } + } +#endif // !APM_BUILD_TYPE(APM_BUILD_AP_Periph) } // updates matrices responsible for rotating vectors from vehicle body @@ -278,6 +304,12 @@ void AP_AHRS::reset_gyro_drift(void) void AP_AHRS::update(bool skip_ins_update) { + // periodically checks to see if we should update the AHRS + // orientation (e.g. based on the AHRS_ORIENTATION parameter) + // allow for runtime change of orientation + // this makes initial config easier + update_orientation(); + if (!skip_ins_update) { // tell the IMU to grab some data AP::ins().update(); @@ -367,7 +399,7 @@ void AP_AHRS::update(bool skip_ins_update) break; #if AP_AHRS_SIM_ENABLED case EKFType::SIM: - shortname = "SITL"; + shortname = "SIM"; break; #endif #if HAL_EXTERNAL_AHRS_ENABLED @@ -406,11 +438,7 @@ void AP_AHRS::copy_estimates_from_backend_estimates(const AP_AHRS_Backend::Estim _gyro_estimate = results.gyro_estimate; _gyro_drift = results.gyro_drift; - // copy earth-frame accelerometer estimates: - for (uint8_t i=0; i=0?primary_imu:_ins.get_primary_gyro(); + const uint8_t primary_accel = primary_imu>=0?primary_imu:_ins.get_primary_accel(); // get gyro bias for primary EKF and change sign to give gyro drift // Note sign convention used by EKF is bias = measurement - truth _gyro_drift.zero(); - EKF2.getGyroBias(-1,_gyro_drift); + EKF2.getGyroBias(_gyro_drift); _gyro_drift = -_gyro_drift; - // calculate corrected gyro estimate for get_gyro() - if (primary_imu == -1 || !_ins.get_gyro_health(primary_imu)) { - // the primary IMU is undefined so use an uncorrected default value from the INS library - _gyro_estimate = _ins.get_gyro(); - } else { - // use the same IMU as the primary EKF and correct for gyro drift - _gyro_estimate = _ins.get_gyro(primary_imu) + _gyro_drift; - } + // use the same IMU as the primary EKF and correct for gyro drift + _gyro_estimate = _ins.get_gyro(primary_gyro) + _gyro_drift; // get z accel bias estimate from active EKF (this is usually for the primary IMU) float &abias = _accel_bias.z; - EKF2.getAccelZBias(-1,abias); + EKF2.getAccelZBias(abias); // This EKF is currently using primary_imu, and abias applies to only that IMU - for (uint8_t i=0; i<_ins.get_accel_count(); i++) { - Vector3f accel = _ins.get_accel(i); - if (i == primary_imu) { - accel.z -= abias; - } - if (_ins.get_accel_health(i)) { - _accel_ef_ekf[i] = _dcm_matrix * get_rotation_autopilot_body_to_vehicle_body() * accel; - } - } - _accel_ef_ekf_blended = _accel_ef_ekf[primary_imu>=0?primary_imu:_ins.get_primary_accel()]; + Vector3f accel = _ins.get_accel(primary_accel); + accel.z -= abias; + _accel_ef = _dcm_matrix * get_rotation_autopilot_body_to_vehicle_body() * accel; + nav_filter_status filt_state; - EKF2.getFilterStatus(-1,filt_state); + EKF2.getFilterStatus(filt_state); update_notify_from_filter_status(filt_state); } } @@ -543,7 +560,7 @@ void AP_AHRS::update_EKF3(void) if (active_EKF_type() == EKFType::THREE) { Vector3f eulers; EKF3.getRotationBodyToNED(_dcm_matrix); - EKF3.getEulerAngles(-1,eulers); + EKF3.getEulerAngles(eulers); roll = eulers.x; pitch = eulers.y; yaw = eulers.z; @@ -555,6 +572,8 @@ void AP_AHRS::update_EKF3(void) // Use the primary EKF to select the primary gyro const int8_t primary_imu = EKF3.getPrimaryCoreIMUIndex(); + const uint8_t primary_gyro = primary_imu>=0?primary_imu:_ins.get_primary_gyro(); + const uint8_t primary_accel = primary_imu>=0?primary_imu:_ins.get_primary_accel(); // get gyro bias for primary EKF and change sign to give gyro drift // Note sign convention used by EKF is bias = measurement - truth @@ -562,34 +581,20 @@ void AP_AHRS::update_EKF3(void) EKF3.getGyroBias(-1,_gyro_drift); _gyro_drift = -_gyro_drift; - // calculate corrected gyro estimate for get_gyro() - if (primary_imu == -1 || !_ins.get_gyro_health(primary_imu)) { - // the primary IMU is undefined so use an uncorrected default value from the INS library - _gyro_estimate = _ins.get_gyro(); - } else { - // use the same IMU as the primary EKF and correct for gyro drift - _gyro_estimate = _ins.get_gyro(primary_imu) + _gyro_drift; - } + // use the same IMU as the primary EKF and correct for gyro drift + _gyro_estimate = _ins.get_gyro(primary_gyro) + _gyro_drift; // get 3-axis accel bias festimates for active EKF (this is usually for the primary IMU) Vector3f &abias = _accel_bias; EKF3.getAccelBias(-1,abias); - // This EKF uses the primary IMU - // Eventually we will run a separate instance of the EKF for each IMU and do the selection and blending of EKF outputs upstream - // update _accel_ef_ekf - for (uint8_t i=0; i<_ins.get_accel_count(); i++) { - Vector3f accel = _ins.get_accel(i); - if (i==_ins.get_primary_accel()) { - accel -= abias; - } - if (_ins.get_accel_health(i)) { - _accel_ef_ekf[i] = _dcm_matrix * accel; - } - } - _accel_ef_ekf_blended = _accel_ef_ekf[_ins.get_primary_accel()]; + // use the primary IMU for accel earth frame + Vector3f accel = _ins.get_accel(primary_accel); + accel -= abias; + _accel_ef = _dcm_matrix * get_rotation_autopilot_body_to_vehicle_body() * accel; + nav_filter_status filt_state; - EKF3.getFilterStatus(-1,filt_state); + EKF3.getFilterStatus(filt_state); update_notify_from_filter_status(filt_state); } } @@ -622,12 +627,8 @@ void AP_AHRS::update_SITL(void) _gyro_estimate = _ins.get_gyro(); - for (uint8_t i=0; istate; + wind = fdm.wind_ef; + } break; #endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: - EKF2.getWind(-1,wind); + EKF2.getWind(wind); break; #endif #if HAL_NAVEKF3_AVAILABLE case EKFType::THREE: - EKF3.getWind(-1,wind); + EKF3.getWind(wind); break; #endif @@ -892,7 +881,7 @@ bool AP_AHRS::airspeed_estimate(float &airspeed_ret) const #if HAL_NAVEKF3_AVAILABLE case EKFType::THREE: - ret = EKF3.getWind(-1,wind_vel); + ret = EKF3.getWind(wind_vel); break; #endif @@ -961,12 +950,42 @@ bool AP_AHRS::airspeed_vector_true(Vector3f &vec) const break; #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: - return EKF2.getAirSpdVec(-1, vec); + return EKF2.getAirSpdVec(vec); +#endif + +#if HAL_NAVEKF3_AVAILABLE + case EKFType::THREE: + return EKF3.getAirSpdVec(vec); +#endif + +#if AP_AHRS_SIM_ENABLED + case EKFType::SIM: + break; +#endif + +#if HAL_EXTERNAL_AHRS_ENABLED + case EKFType::EXTERNAL: + break; +#endif + } + return false; +} + +// return the innovation in m/s, innovation variance in (m/s)^2 and age in msec of the last TAS measurement processed +// returns false if the data is unavailable +bool AP_AHRS::airspeed_health_data(float &innovation, float &innovationVariance, uint32_t &age_ms) const +{ + switch (active_EKF_type()) { + case EKFType::NONE: + break; +#if HAL_NAVEKF2_AVAILABLE + case EKFType::TWO: + break; #endif #if HAL_NAVEKF3_AVAILABLE case EKFType::THREE: - return EKF3.getAirSpdVec(-1, vec); + return EKF3.getAirSpdHealthData(innovation, innovationVariance, age_ms); #endif #if AP_AHRS_SIM_ENABLED @@ -1037,7 +1056,7 @@ bool AP_AHRS::get_quaternion(Quaternion &quat) const if (!_ekf2_started) { return false; } - EKF2.getQuaternion(-1, quat); + EKF2.getQuaternion(quat); break; #endif #if HAL_NAVEKF3_AVAILABLE @@ -1045,7 +1064,7 @@ bool AP_AHRS::get_quaternion(Quaternion &quat) const if (!_ekf3_started) { return false; } - EKF3.getQuaternion(-1, quat); + EKF3.getQuaternion(quat); break; #endif #if AP_AHRS_SIM_ENABLED @@ -1090,14 +1109,14 @@ bool AP_AHRS::get_secondary_attitude(Vector3f &eulers) const #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: // EKF2 is secondary - EKF2.getEulerAngles(-1, eulers); + EKF2.getEulerAngles(eulers); return _ekf2_started; #endif #if HAL_NAVEKF3_AVAILABLE case EKFType::THREE: // EKF3 is secondary - EKF3.getEulerAngles(-1, eulers); + EKF3.getEulerAngles(eulers); return _ekf3_started; #endif @@ -1148,7 +1167,7 @@ bool AP_AHRS::get_secondary_quaternion(Quaternion &quat) const if (!_ekf2_started) { return false; } - EKF2.getQuaternion(-1, quat); + EKF2.getQuaternion(quat); break; #endif @@ -1158,7 +1177,7 @@ bool AP_AHRS::get_secondary_quaternion(Quaternion &quat) const if (!_ekf3_started) { return false; } - EKF3.getQuaternion(-1, quat); + EKF3.getQuaternion(quat); break; #endif @@ -1237,13 +1256,13 @@ Vector2f AP_AHRS::groundspeed_vector(void) #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: - EKF2.getVelNED(-1,vec); + EKF2.getVelNED(vec); return Vector2f(vec.x, vec.y); #endif #if HAL_NAVEKF3_AVAILABLE case EKFType::THREE: - EKF3.getVelNED(-1,vec); + EKF3.getVelNED(vec); return Vector2f(vec.x, vec.y); #endif @@ -1350,13 +1369,13 @@ bool AP_AHRS::get_velocity_NED(Vector3f &vec) const #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: - EKF2.getVelNED(-1,vec); + EKF2.getVelNED(vec); return true; #endif #if HAL_NAVEKF3_AVAILABLE case EKFType::THREE: - EKF3.getVelNED(-1,vec); + EKF3.getVelNED(vec); return true; #endif @@ -1387,13 +1406,13 @@ bool AP_AHRS::get_mag_field_NED(Vector3f &vec) const #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: - EKF2.getMagNED(-1,vec); + EKF2.getMagNED(vec); return true; #endif #if HAL_NAVEKF3_AVAILABLE case EKFType::THREE: - EKF3.getMagNED(-1,vec); + EKF3.getMagNED(vec); return true; #endif @@ -1418,13 +1437,13 @@ bool AP_AHRS::get_mag_field_correction(Vector3f &vec) const #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: - EKF2.getMagXYZ(-1,vec); + EKF2.getMagXYZ(vec); return true; #endif #if HAL_NAVEKF3_AVAILABLE case EKFType::THREE: - EKF3.getMagXYZ(-1,vec); + EKF3.getMagXYZ(vec); return true; #endif @@ -1451,13 +1470,13 @@ bool AP_AHRS::get_vert_pos_rate(float &velocity) const #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: - velocity = EKF2.getPosDownDerivative(-1); + velocity = EKF2.getPosDownDerivative(); return true; #endif #if HAL_NAVEKF3_AVAILABLE case EKFType::THREE: - velocity = EKF3.getPosDownDerivative(-1); + velocity = EKF3.getPosDownDerivative(); return true; #endif @@ -1529,7 +1548,7 @@ bool AP_AHRS::get_relative_position_NED_origin(Vector3f &vec) const case EKFType::TWO: { Vector2f posNE; float posD; - if (EKF2.getPosNE(-1,posNE) && EKF2.getPosD(-1,posD)) { + if (EKF2.getPosNE(posNE) && EKF2.getPosD(posD)) { // position is valid vec.x = posNE.x; vec.y = posNE.y; @@ -1544,7 +1563,7 @@ bool AP_AHRS::get_relative_position_NED_origin(Vector3f &vec) const case EKFType::THREE: { Vector2f posNE; float posD; - if (EKF3.getPosNE(-1,posNE) && EKF3.getPosD(-1,posD)) { + if (EKF3.getPosNE(posNE) && EKF3.getPosD(posD)) { // position is valid vec.x = posNE.x; vec.y = posNE.y; @@ -1620,14 +1639,14 @@ bool AP_AHRS::get_relative_position_NE_origin(Vector2f &posNE) const #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: { - bool position_is_valid = EKF2.getPosNE(-1,posNE); + bool position_is_valid = EKF2.getPosNE(posNE); return position_is_valid; } #endif #if HAL_NAVEKF3_AVAILABLE case EKFType::THREE: { - bool position_is_valid = EKF3.getPosNE(-1,posNE); + bool position_is_valid = EKF3.getPosNE(posNE); return position_is_valid; } #endif @@ -1690,14 +1709,14 @@ bool AP_AHRS::get_relative_position_D_origin(float &posD) const #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: { - bool position_is_valid = EKF2.getPosD(-1,posD); + bool position_is_valid = EKF2.getPosD(posD); return position_is_valid; } #endif #if HAL_NAVEKF3_AVAILABLE case EKFType::THREE: { - bool position_is_valid = EKF3.getPosD(-1,posD); + bool position_is_valid = EKF3.getPosD(posD); return position_is_valid; } #endif @@ -1815,7 +1834,7 @@ AP_AHRS::EKFType AP_AHRS::active_EKF_type(void) const } if (always_use_EKF()) { uint16_t ekf2_faults; - EKF2.getFilterFaults(-1,ekf2_faults); + EKF2.getFilterFaults(ekf2_faults); if (ekf2_faults == 0) { ret = EKFType::TWO; } @@ -1834,7 +1853,7 @@ AP_AHRS::EKFType AP_AHRS::active_EKF_type(void) const } if (always_use_EKF()) { uint16_t ekf3_faults; - EKF3.getFilterFaults(-1,ekf3_faults); + EKF3.getFilterFaults(ekf3_faults); if (ekf3_faults == 0) { ret = EKFType::THREE; } @@ -1871,13 +1890,13 @@ AP_AHRS::EKFType AP_AHRS::active_EKF_type(void) const nav_filter_status filt_state; #if HAL_NAVEKF2_AVAILABLE if (ret == EKFType::TWO) { - EKF2.getFilterStatus(-1,filt_state); + EKF2.getFilterStatus(filt_state); should_use_gps = EKF2.configuredToUseGPSForPosXY(); } #endif #if HAL_NAVEKF3_AVAILABLE if (ret == EKFType::THREE) { - EKF3.getFilterStatus(-1,filt_state); + EKF3.getFilterStatus(filt_state); should_use_gps = EKF3.configuredToUseGPSForPosXY(); } #endif @@ -2052,6 +2071,16 @@ bool AP_AHRS::pre_arm_check(bool requires_position, char *failure_msg, uint8_t f ret = false; } + if (!attitudes_consistent(failure_msg, failure_msg_len)) { + return false; + } + + // ensure we're using the configured backend, but bypass in compass-less cases: + if (ekf_type() != active_EKF_type() && AP::compass().use_for_yaw()) { + hal.util->snprintf(failure_msg, failure_msg_len, "not using configured AHRS type"); + return false; + } + switch (ekf_type()) { #if AP_AHRS_SIM_ENABLED case EKFType::SIM: @@ -2129,13 +2158,13 @@ bool AP_AHRS::get_filter_status(nav_filter_status &status) const #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: - EKF2.getFilterStatus(-1,status); + EKF2.getFilterStatus(status); return true; #endif #if HAL_NAVEKF3_AVAILABLE case EKFType::THREE: - EKF3.getFilterStatus(-1,status); + EKF3.getFilterStatus(status); return true; #endif @@ -2319,7 +2348,7 @@ void AP_AHRS::getCorrectedDeltaVelocityNED(Vector3f& ret, float& dt) const #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: imu_idx = EKF2.getPrimaryCoreIMUIndex(); - EKF2.getAccelZBias(-1,accel_bias.z); + EKF2.getAccelZBias(accel_bias.z); break; #endif #if HAL_NAVEKF3_AVAILABLE @@ -2618,12 +2647,12 @@ bool AP_AHRS::resetHeightDatum(void) } // send a EKF_STATUS_REPORT for current EKF -void AP_AHRS::send_ekf_status_report(mavlink_channel_t chan) const +void AP_AHRS::send_ekf_status_report(GCS_MAVLINK &link) const { switch (ekf_type()) { case EKFType::NONE: // send zero status report - dcm.send_ekf_status_report(chan); + dcm.send_ekf_status_report(link); break; #if AP_AHRS_SIM_ENABLED @@ -2641,26 +2670,26 @@ void AP_AHRS::send_ekf_status_report(mavlink_channel_t chan) const //EKF_CONST_POS_MODE | /* EKF is in constant position mode and does not know it's absolute or relative position. | */ EKF_PRED_POS_HORIZ_REL | /* Set if EKF's predicted horizontal position (relative) estimate is good. | */ EKF_PRED_POS_HORIZ_ABS; /* Set if EKF's predicted horizontal position (absolute) estimate is good. | */ - mavlink_msg_ekf_status_report_send(chan, flags, 0, 0, 0, 0, 0, 0); + mavlink_msg_ekf_status_report_send(link.get_chan(), flags, 0, 0, 0, 0, 0, 0); } break; #endif #if HAL_EXTERNAL_AHRS_ENABLED case EKFType::EXTERNAL: { - AP::externalAHRS().send_status_report(chan); + AP::externalAHRS().send_status_report(link); break; } #endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: - return EKF2.send_status_report(chan); + return EKF2.send_status_report(link); #endif #if HAL_NAVEKF3_AVAILABLE case EKFType::THREE: - return EKF3.send_status_report(chan); + return EKF3.send_status_report(link); #endif } @@ -2677,7 +2706,7 @@ bool AP_AHRS::get_origin(Location &ret) const #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: - if (!EKF2.getOriginLLH(-1,ret)) { + if (!EKF2.getOriginLLH(ret)) { return false; } return true; @@ -2685,7 +2714,7 @@ bool AP_AHRS::get_origin(Location &ret) const #if HAL_NAVEKF3_AVAILABLE case EKFType::THREE: - if (!EKF3.getOriginLLH(-1,ret)) { + if (!EKF3.getOriginLLH(ret)) { return false; } return true; @@ -2785,13 +2814,13 @@ bool AP_AHRS::get_innovations(Vector3f &velInnov, Vector3f &posInnov, Vector3f & #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: // use EKF to get innovations - return EKF2.getInnovations(-1, velInnov, posInnov, magInnov, tasInnov, yawInnov); + return EKF2.getInnovations(velInnov, posInnov, magInnov, tasInnov, yawInnov); #endif #if HAL_NAVEKF3_AVAILABLE case EKFType::THREE: // use EKF to get innovations - return EKF3.getInnovations(-1, velInnov, posInnov, magInnov, tasInnov, yawInnov); + return EKF3.getInnovations(velInnov, posInnov, magInnov, tasInnov, yawInnov); #endif #if AP_AHRS_SIM_ENABLED @@ -2819,7 +2848,7 @@ bool AP_AHRS::is_vibration_affected() const switch (ekf_type()) { #if HAL_NAVEKF3_AVAILABLE case EKFType::THREE: - return EKF3.isVibrationAffected(-1); + return EKF3.isVibrationAffected(); #endif case EKFType::NONE: #if HAL_NAVEKF2_AVAILABLE @@ -2851,7 +2880,7 @@ bool AP_AHRS::get_variances(float &velVar, float &posVar, float &hgtVar, Vector3 case EKFType::TWO: { // use EKF to get variance Vector2f offset; - return EKF2.getVariances(-1, velVar, posVar, hgtVar, magVar, tasVar, offset); + return EKF2.getVariances(velVar, posVar, hgtVar, magVar, tasVar, offset); } #endif @@ -2859,7 +2888,7 @@ bool AP_AHRS::get_variances(float &velVar, float &posVar, float &hgtVar, Vector3 case EKFType::THREE: { // use EKF to get variance Vector2f offset; - return EKF3.getVariances(-1, velVar, posVar, hgtVar, magVar, tasVar, offset); + return EKF3.getVariances(velVar, posVar, hgtVar, magVar, tasVar, offset); } #endif @@ -2900,7 +2929,7 @@ bool AP_AHRS::get_vel_innovations_and_variances_for_source(uint8_t source, Vecto #if HAL_NAVEKF3_AVAILABLE case EKFType::THREE: // use EKF to get variance - return EKF3.getVelInnovationsAndVariancesForSource(-1, (AP_NavEKF_Source::SourceXY)source, innovations, variances); + return EKF3.getVelInnovationsAndVariancesForSource((AP_NavEKF_Source::SourceXY)source, innovations, variances); #endif #if AP_AHRS_SIM_ENABLED @@ -2930,7 +2959,7 @@ uint8_t AP_AHRS::get_active_airspeed_index() const // we only have affinity for EKF3 as of now #if HAL_NAVEKF3_AVAILABLE if (active_EKF_type() == EKFType::THREE) { - uint8_t ret = EKF3.getActiveAirspeed(get_primary_core_index()); + uint8_t ret = EKF3.getActiveAirspeed(); if (ret != 255 && airspeed->healthy(ret)) { return ret; } @@ -2949,8 +2978,9 @@ uint8_t AP_AHRS::get_active_airspeed_index() const uint8_t AP_AHRS::get_primary_IMU_index() const { int8_t imu = -1; - switch (ekf_type()) { + switch (active_EKF_type()) { case EKFType::NONE: + imu = AP::ins().get_primary_gyro(); break; #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: @@ -2979,12 +3009,6 @@ uint8_t AP_AHRS::get_primary_IMU_index() const return imu; } -// get earth-frame accel vector for primary IMU -const Vector3f &AP_AHRS::get_accel_ef() const -{ - return get_accel_ef(get_primary_accel_index()); -} - // return the index of the primary core or -1 if no primary core selected int8_t AP_AHRS::get_primary_core_index() const { @@ -3103,6 +3127,16 @@ void AP_AHRS::set_posvelyaw_source_set(uint8_t source_set_idx) #endif } +//returns active source set used, 0=primary, 1=secondary, 2=tertiary +uint8_t AP_AHRS::get_posvelyaw_source_set() const +{ +#if HAL_NAVEKF3_AVAILABLE + return EKF3.get_active_source_set(); +#else + return 0; +#endif +} + void AP_AHRS::Log_Write() { #if HAL_NAVEKF2_AVAILABLE @@ -3115,7 +3149,7 @@ void AP_AHRS::Log_Write() Write_AHRS2(); Write_POS(); -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#if AP_AHRS_SIM_ENABLED AP::sitl()->Log_Write_SIMSTATE(); #endif } @@ -3181,14 +3215,6 @@ void AP_AHRS::set_alt_measurement_noise(float noise) #endif } -/* - get the current view's rotation, or ROTATION_NONE - */ -enum Rotation AP_AHRS::get_view_rotation(void) const -{ - return _view?_view->get_rotation():ROTATION_NONE; -} - // check if non-compass sensor is providing yaw. Allows compass pre-arm checks to be bypassed const EKFGSF_yaw *AP_AHRS::get_yaw_estimator(void) const { diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index e2d6cd08636..d85749d26cd 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -16,12 +16,13 @@ */ /* - * NavEKF based AHRS (Attitude Heading Reference System) interface for + * AHRS (Attitude Heading Reference System) frontend interface for * ArduPilot * */ -#include +#include +#include #ifndef HAL_NAVEKF2_AVAILABLE // only default to EK2 enabled on boards with over 1M flash @@ -33,17 +34,13 @@ #endif #ifndef AP_AHRS_SIM_ENABLED -#define AP_AHRS_SIM_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL) +#define AP_AHRS_SIM_ENABLED AP_SIM_ENABLED #endif -#include "AP_AHRS.h" - #if AP_AHRS_SIM_ENABLED #include #endif -#include - #include #include #include // definitions shared by inertial and ekf nav filters @@ -82,6 +79,8 @@ class AP_AHRS { return _singleton; } + // periodically checks to see if we should update the AHRS + // orientation (e.g. based on the AHRS_ORIENTATION parameter) // allow for runtime change of orientation // this makes initial config easier void update_orientation(); @@ -106,10 +105,6 @@ class AP_AHRS { // dead-reckoning support bool get_location(struct Location &loc) const; - // for scripting until aliases get sorted out: - bool get_position(struct Location &loc) const { - return get_location(loc); - } // get latest altitude estimate above ground level in meters and validity flag bool get_hagl(float &hagl) const WARN_IF_UNUSED; @@ -160,6 +155,10 @@ class AP_AHRS { // returns false if estimate is unavailable bool airspeed_vector_true(Vector3f &vec) const; + // return the innovation in m/s, innovation variance in (m/s)^2 and age in msec of the last TAS measurement processed + // returns false if the data is unavailable + bool airspeed_health_data(float &innovation, float &innovationVariance, uint32_t &age_ms) const; + // return true if airspeed comes from an airspeed sensor, as // opposed to an IMU estimate bool airspeed_sensor_enabled(void) const; @@ -198,15 +197,13 @@ class AP_AHRS { // return ground speed estimate in meters/second. Used by ground vehicles. float groundspeed(void); - const Vector3f &get_accel_ef(uint8_t i) const; - const Vector3f &get_accel_ef() const; + const Vector3f &get_accel_ef() const { + return _accel_ef; + } // Retrieves the corrected NED delta velocity in use by the inertial navigation void getCorrectedDeltaVelocityNED(Vector3f& ret, float& dt) const; - // blended accelerometer values in the earth frame in m/s/s - const Vector3f &get_accel_ef_blended() const; - // set the EKF's origin location in 10e7 degrees. This should only // be called when the EKF has no absolute position reference (i.e. GPS) // from which to decide the origin on its own @@ -282,9 +279,6 @@ class AP_AHRS { // true if offsets are valid bool getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const; - // check all cores providing consistent attitudes for prearm checks - bool attitudes_consistent(char *failure_msg, const uint8_t failure_msg_len) const; - // return the amount of yaw angle change due to the last yaw angle reset in radians // returns the time of the last yaw angle reset or 0 if no reset has ever occurred uint32_t getLastYawResetAngle(float &yawAng); @@ -309,7 +303,7 @@ class AP_AHRS { bool resetHeightDatum(); // send a EKF_STATUS_REPORT for current EKF - void send_ekf_status_report(mavlink_channel_t chan) const; + void send_ekf_status_report(class GCS_MAVLINK &link) const; // get_hgt_ctrl_limit - get maximum height to be observed by the control loops in meters and a validity flag // this is used to limit height during optical flow navigation @@ -368,6 +362,9 @@ class AP_AHRS { // set position, velocity and yaw sources to either 0=primary, 1=secondary, 2=tertiary void set_posvelyaw_source_set(uint8_t source_set_idx); + //returns index of active source set used, 0=primary, 1=secondary, 2=tertiary + uint8_t get_posvelyaw_source_set() const; + void Log_Write(); // check if non-compass sensor is providing yaw. Allows compass pre-arm checks to be bypassed @@ -379,11 +376,6 @@ class AP_AHRS { // set and save the ALT_M_NSE parameter value void set_alt_measurement_noise(float noise); - // active EKF type for logging - uint8_t get_active_AHRS_type(void) const { - return uint8_t(active_EKF_type()); - } - // get the selected ekf type, for allocation decisions int8_t get_ekf_type(void) const { return _ekf_type; @@ -540,7 +532,7 @@ class AP_AHRS { // convert a vector from body to earth frame Vector3f body_to_earth(const Vector3f &v) const { - return v * get_rotation_body_to_ned(); + return get_rotation_body_to_ned() * v; } // convert a vector from earth to body frame @@ -613,8 +605,8 @@ class AP_AHRS { _vehicle_class = vclass; } - // get the view's rotation, or ROTATION_NONE - enum Rotation get_view_rotation(void) const; + // get the view + AP_AHRS_View *get_view(void) const { return _view; }; // get access to an EKFGSF_yaw estimator const EKFGSF_yaw *get_yaw_estimator(void) const; @@ -641,14 +633,6 @@ class AP_AHRS { AP_Int8 _wind_max; AP_Int8 _board_orientation; AP_Int8 _ekf_type; - AP_Float _custom_roll; - AP_Float _custom_pitch; - AP_Float _custom_yaw; - - /* - * support for custom AHRS orientation, replacing _board_orientation - */ - Matrix3f _custom_rotation; /* * DCM-backend parameters; it takes references to these @@ -688,6 +672,9 @@ class AP_AHRS { return _ekf_flags & FLAG_ALWAYS_USE_EKF; } + // check all cores providing consistent attitudes for prearm checks + bool attitudes_consistent(char *failure_msg, const uint8_t failure_msg_len) const; + /* * Attitude-related private methods and attributes: */ @@ -725,8 +712,7 @@ class AP_AHRS { Vector3f _gyro_drift; Vector3f _gyro_estimate; - Vector3f _accel_ef_ekf[INS_MAX_INSTANCES]; - Vector3f _accel_ef_ekf_blended; + Vector3f _accel_ef; Vector3f _accel_bias; const uint16_t startup_delay_ms = 1000; @@ -789,6 +775,9 @@ class AP_AHRS { Matrix3f _rotation_autopilot_body_to_vehicle_body; Matrix3f _rotation_vehicle_body_to_autopilot_body; + // last time orientation was updated from AHRS_ORIENTATION: + uint32_t last_orientation_update_ms; + // updates matrices responsible for rotating vectors from vehicle body // frame to autopilot body frame from _trim variables void update_trim_rotation_matrices(); diff --git a/libraries/AP_AHRS/AP_AHRS_Backend.cpp b/libraries/AP_AHRS/AP_AHRS_Backend.cpp index 4f95e988d7b..cfe3107a373 100644 --- a/libraries/AP_AHRS/AP_AHRS_Backend.cpp +++ b/libraries/AP_AHRS/AP_AHRS_Backend.cpp @@ -16,10 +16,13 @@ */ #include "AP_AHRS.h" #include "AP_AHRS_View.h" + +#include #include #include #include #include +#include extern const AP_HAL::HAL& hal; @@ -63,18 +66,27 @@ void AP_AHRS::add_trim(float roll_in_radians, float pitch_in_radians, bool save_ } } -// Set the board mounting orientation, may be called while disarmed +// Set the board mounting orientation from AHRS_ORIENTATION parameter void AP_AHRS::update_orientation() { - const enum Rotation orientation = (enum Rotation)_board_orientation.get(); - if (orientation != ROTATION_CUSTOM) { - AP::ins().set_board_orientation(orientation); - AP::compass().set_board_orientation(orientation); - } else { - _custom_rotation.from_euler(radians(_custom_roll), radians(_custom_pitch), radians(_custom_yaw)); - AP::ins().set_board_orientation(orientation, &_custom_rotation); - AP::compass().set_board_orientation(orientation, &_custom_rotation); + const uint32_t now_ms = AP_HAL::millis(); + if (now_ms - last_orientation_update_ms < 1000) { + // only update once/second + return; } + + // never update while armed - unless we've never updated + // (e.g. mid-air reboot or ARMING_REQUIRED=NO on Plane): + if (hal.util->get_soft_armed() && last_orientation_update_ms != 0) { + return; + } + + last_orientation_update_ms = now_ms; + + const enum Rotation orientation = (enum Rotation)_board_orientation.get(); + + AP::ins().set_board_orientation(orientation); + AP::compass().set_board_orientation(orientation); } // return a ground speed estimate in m/s diff --git a/libraries/AP_AHRS/AP_AHRS_Backend.h b/libraries/AP_AHRS/AP_AHRS_Backend.h index a39f66ba45f..ad7b3e13cc8 100644 --- a/libraries/AP_AHRS/AP_AHRS_Backend.h +++ b/libraries/AP_AHRS/AP_AHRS_Backend.h @@ -22,13 +22,9 @@ #include #include -#include #include #include -#include -#include -class OpticalFlow; #define AP_AHRS_TRIM_LIMIT 10.0f // maximum trim angle in degrees #define AP_AHRS_RP_P_MIN 0.05f // minimum value for AHRS_RP_P parameter #define AP_AHRS_YAW_P_MIN 0.05f // minimum value for AHRS_YAW_P parameter @@ -59,8 +55,7 @@ class AP_AHRS_Backend Matrix3f dcm_matrix; Vector3f gyro_estimate; Vector3f gyro_drift; - Vector3f accel_ef[INS_MAX_INSTANCES]; // must be INS_MAX_INSTANCES - Vector3f accel_ef_blended; + Vector3f accel_ef; Vector3f accel_bias; }; @@ -204,10 +199,10 @@ class AP_AHRS_Backend } // - virtual bool set_origin(const Location &loc) { + virtual bool set_origin(const struct Location &loc) { return false; } - virtual bool get_origin(Location &ret) const = 0; + virtual bool get_origin(struct Location &ret) const = 0; // return a position relative to origin in meters, North/East/Down // order. This will only be accurate if have_inertial_nav() is @@ -313,7 +308,7 @@ class AP_AHRS_Backend return false; } - virtual void send_ekf_status_report(mavlink_channel_t chan) const = 0; + virtual void send_ekf_status_report(class GCS_MAVLINK &link) const = 0; // Retrieves the corrected NED delta velocity in use by the inertial navigation virtual void getCorrectedDeltaVelocityNED(Vector3f& ret, float& dt) const { diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.cpp b/libraries/AP_AHRS/AP_AHRS_DCM.cpp index 0cd43a84119..9b148645a47 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.cpp +++ b/libraries/AP_AHRS/AP_AHRS_DCM.cpp @@ -25,6 +25,7 @@ #include #include #include +#include #include extern const AP_HAL::HAL& hal; @@ -84,7 +85,7 @@ AP_AHRS_DCM::update() } // Integrate the DCM matrix using gyro inputs - matrix_update(delta_t); + matrix_update(); // Normalize the DCM matrix normalize(); @@ -121,10 +122,7 @@ void AP_AHRS_DCM::get_results(AP_AHRS_Backend::Estimates &results) results.dcm_matrix = _body_dcm_matrix; results.gyro_estimate = _omega; results.gyro_drift = _omega_I; - - const uint8_t to_copy = MIN(sizeof(results.accel_ef), sizeof(_accel_ef)); - memcpy(results.accel_ef, _accel_ef, to_copy); - results.accel_ef_blended = _accel_ef_blended; + results.accel_ef = _accel_ef; } /* @@ -139,41 +137,28 @@ void AP_AHRS_DCM::backup_attitude(void) } // update the DCM matrix using only the gyros -void -AP_AHRS_DCM::matrix_update(float _G_Dt) +void AP_AHRS_DCM::matrix_update(void) { + // use only the primary gyro so our bias estimate is valid, allowing us to return the right filtered gyro + // for rate controllers + const auto &_ins = AP::ins(); + Vector3f delta_angle; + float dangle_dt; + if (_ins.get_delta_angle(delta_angle, dangle_dt) && dangle_dt > 0) { + _omega = delta_angle / dangle_dt; + _omega += _omega_I; + _dcm_matrix.rotate((_omega + _omega_P + _omega_yaw_P) * dangle_dt); + } + + // now update _omega from the filtered value from the primary IMU. We need to use + // the primary IMU as the notch filters will only be running on one IMU + // note that we do not include the P terms in _omega. This is // because the spin_rate is calculated from _omega.length(), // and including the P terms would give positive feedback into // the _P_gain() calculation, which can lead to a very large P // value - _omega.zero(); - - // average across first two healthy gyros. This reduces noise on - // systems with more than one gyro. We don't use the 3rd gyro - // unless another is unhealthy as 3rd gyro on PH2 has a lot more - // noise - uint8_t healthy_count = 0; - Vector3f delta_angle; - const AP_InertialSensor &_ins = AP::ins(); - for (uint8_t i=0; i<_ins.get_gyro_count(); i++) { - if (_ins.use_gyro(i) && healthy_count < 2) { - Vector3f dangle; - float dangle_dt; - if (_ins.get_delta_angle(i, dangle, dangle_dt)) { - healthy_count++; - delta_angle += dangle; - } - } - } - if (healthy_count > 1) { - delta_angle /= healthy_count; - } - if (_G_Dt > 0) { - _omega = delta_angle / _G_Dt; - _omega += _omega_I; - _dcm_matrix.rotate((_omega + _omega_P + _omega_yaw_P) * _G_Dt); - } + _omega = _ins.get_gyro() + _omega_I; } @@ -264,7 +249,10 @@ AP_AHRS_DCM::check_matrix(void) normalize(); if (_dcm_matrix.is_nan() || - fabsf(_dcm_matrix.c.x) > 10) { + fabsf(_dcm_matrix.c.x) > 10.0) { + // See Issue #20284: regarding the selection of 10.0 for DCM reset + // This won't be lowered without evidence of an issue or mathematical proof & testing of a lower bound + // normalisation didn't fix the problem! We're // in real trouble. All we can do is reset //Serial.printf("ERROR: DCM matrix error. _dcm_matrix.c.x=%f\n", @@ -406,7 +394,7 @@ AP_AHRS_DCM::_P_gain(float spin_rate) float AP_AHRS_DCM::_yaw_gain(void) const { - const float VdotEFmag = _accel_ef[_active_accel_instance].xy().length(); + const float VdotEFmag = _accel_ef.xy().length(); if (VdotEFmag <= 4.0f) { return 0.2f*(4.5f - VdotEFmag); @@ -583,7 +571,7 @@ AP_AHRS_DCM::drift_correction_yaw(void) // sanity check _kp_yaw if (_kp_yaw < AP_AHRS_YAW_P_MIN) { - _kp_yaw = AP_AHRS_YAW_P_MIN; + _kp_yaw.set(AP_AHRS_YAW_P_MIN); } // update the proportional control to drag the @@ -663,9 +651,8 @@ AP_AHRS_DCM::drift_correction(float deltat) const AP_InertialSensor &_ins = AP::ins(); // rotate accelerometer values into the earth frame - uint8_t healthy_count = 0; for (uint8_t i=0; i<_ins.get_accel_count(); i++) { - if (_ins.use_accel(i) && healthy_count < 2) { + if (_ins.use_accel(i)) { /* by using get_delta_velocity() instead of get_accel() the accel value is sampled over the right time delta for @@ -675,26 +662,15 @@ AP_AHRS_DCM::drift_correction(float deltat) float delta_velocity_dt; _ins.get_delta_velocity(i, delta_velocity, delta_velocity_dt); if (delta_velocity_dt > 0) { - _accel_ef[i] = _dcm_matrix * (delta_velocity / delta_velocity_dt); + Vector3f accel_ef = _dcm_matrix * (delta_velocity / delta_velocity_dt); // integrate the accel vector in the earth frame between GPS readings - _ra_sum[i] += _accel_ef[i] * deltat; + _ra_sum[i] += accel_ef * deltat; } - healthy_count++; } } - //update _accel_ef_blended -#if INS_MAX_INSTANCES > 1 - if (_ins.get_accel_count() == 2 && _ins.use_accel(0) && _ins.use_accel(1)) { - const float imu1_weight_target = _active_accel_instance == 0 ? 1.0f : 0.0f; - // slew _imu1_weight over one second - _imu1_weight += constrain_float(imu1_weight_target-_imu1_weight, -deltat, deltat); - _accel_ef_blended = _accel_ef[0] * _imu1_weight + _accel_ef[1] * (1.0f - _imu1_weight); - } else -#endif - { - _accel_ef_blended = _accel_ef[_ins.get_primary_accel()]; - } + // set _accel_ef_blended based on filtered accel + _accel_ef = _dcm_matrix * _ins.get_accel(); // keep a sum of the deltat values, so we know how much time // we have integrated over @@ -923,7 +899,7 @@ AP_AHRS_DCM::drift_correction(float deltat) // sanity check _kp value if (_kp < AP_AHRS_RP_P_MIN) { - _kp = AP_AHRS_RP_P_MIN; + _kp.set(AP_AHRS_RP_P_MIN); } // we now want to calculate _omega_P and _omega_I. The @@ -1274,6 +1250,6 @@ bool AP_AHRS_DCM::get_relative_position_D_origin(float &posD) const return true; } -void AP_AHRS_DCM::send_ekf_status_report(mavlink_channel_t chan) const +void AP_AHRS_DCM::send_ekf_status_report(GCS_MAVLINK &link) const { } diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.h b/libraries/AP_AHRS/AP_AHRS_DCM.h index d7776298cb2..7e9ef951841 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.h +++ b/libraries/AP_AHRS/AP_AHRS_DCM.h @@ -123,7 +123,7 @@ class AP_AHRS_DCM : public AP_AHRS_Backend { bool get_relative_position_NE_origin(Vector2f &posNE) const override; bool get_relative_position_D_origin(float &posD) const override; - void send_ekf_status_report(mavlink_channel_t chan) const override; + void send_ekf_status_report(class GCS_MAVLINK &link) const override; private: @@ -144,11 +144,10 @@ class AP_AHRS_DCM : public AP_AHRS_Backend { static constexpr float _ki_yaw = 0.01f; // accelerometer values in the earth frame in m/s/s - Vector3f _accel_ef[INS_MAX_INSTANCES]; - Vector3f _accel_ef_blended; + Vector3f _accel_ef; // Methods - void matrix_update(float _G_Dt); + void matrix_update(void); void normalize(void); void check_matrix(void); bool renorm(Vector3f const &a, Vector3f &result); diff --git a/libraries/AP_AHRS/AP_AHRS_Logging.cpp b/libraries/AP_AHRS/AP_AHRS_Logging.cpp index 0be7c3956dc..cef4f838f71 100644 --- a/libraries/AP_AHRS/AP_AHRS_Logging.cpp +++ b/libraries/AP_AHRS/AP_AHRS_Logging.cpp @@ -58,7 +58,7 @@ void AP_AHRS::Write_Attitude(const Vector3f &targets) const yaw : (uint16_t)wrap_360_cd(yaw_sensor), error_rp : (uint16_t)(get_error_rp() * 100), error_yaw : (uint16_t)(get_error_yaw() * 100), - active : AP::ahrs().get_active_AHRS_type(), + active : uint8_t(active_EKF_type()), }; AP::logger().WriteBlock(&pkt, sizeof(pkt)); } @@ -134,7 +134,7 @@ void AP_AHRS_View::Write_AttitudeView(const Vector3f &targets) const yaw : (uint16_t)wrap_360_cd(yaw_sensor), error_rp : (uint16_t)(get_error_rp() * 100), error_yaw : (uint16_t)(get_error_yaw() * 100), - active : AP::ahrs().get_active_AHRS_type() + active : uint8_t(AP::ahrs().active_EKF_type()), }; AP::logger().WriteBlock(&pkt, sizeof(pkt)); } @@ -145,9 +145,10 @@ void AP_AHRS_View::Write_Rate(const AP_Motors &motors, const AC_AttitudeControl { const Vector3f &rate_targets = attitude_control.rate_bf_targets(); const Vector3f &accel_target = pos_control.get_accel_target_cmss(); + const auto timeus = AP_HAL::micros64(); const struct log_Rate pkt_rate{ LOG_PACKET_HEADER_INIT(LOG_RATE_MSG), - time_us : AP_HAL::micros64(), + time_us : timeus, control_roll : degrees(rate_targets.x), roll : degrees(get_gyro().x), roll_out : motors.get_roll()+motors.get_roll_ff(), @@ -158,8 +159,23 @@ void AP_AHRS_View::Write_Rate(const AP_Motors &motors, const AC_AttitudeControl yaw : degrees(get_gyro().z), yaw_out : motors.get_yaw()+motors.get_yaw_ff(), control_accel : (float)accel_target.z, - accel : (float)(-(get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f), + accel : (float)(-(get_accel_ef().z + GRAVITY_MSS) * 100.0f), accel_out : motors.get_throttle() }; AP::logger().WriteBlock(&pkt_rate, sizeof(pkt_rate)); + + /* + log P gain scale if not == 1.0 + */ + const Vector3f &scale = attitude_control.get_angle_P_scale_logging(); + if (!is_equal(scale.x,1.0f) || !is_equal(scale.y,1.0f) || !is_equal(scale.z,1.0f)) { + const struct log_ATSC pkt_ATSC { + LOG_PACKET_HEADER_INIT(LOG_ATSC_MSG), + time_us : timeus, + scaleP_x : scale.x, + scaleP_y : scale.y, + scaleP_z : scale.z, + }; + AP::logger().WriteBlock(&pkt_ATSC, sizeof(pkt_ATSC)); + } } diff --git a/libraries/AP_AHRS/AP_AHRS_View.cpp b/libraries/AP_AHRS/AP_AHRS_View.cpp index 2adbd8d3858..450567ce2c6 100644 --- a/libraries/AP_AHRS/AP_AHRS_View.cpp +++ b/libraries/AP_AHRS/AP_AHRS_View.cpp @@ -100,3 +100,9 @@ Vector2f AP_AHRS_View::body_to_earth2D(const Vector2f &bf) const return Vector2f(bf.x * trig.cos_yaw - bf.y * trig.sin_yaw, bf.x * trig.sin_yaw + bf.y * trig.cos_yaw); } + +// Rotate vector from AHRS reference frame to AHRS view reference frame +void AP_AHRS_View::rotate(Vector3f &vec) const +{ + vec = rot_view * vec; +} diff --git a/libraries/AP_AHRS/AP_AHRS_View.h b/libraries/AP_AHRS/AP_AHRS_View.h index 36fcb85a8e8..80abb2c628a 100644 --- a/libraries/AP_AHRS/AP_AHRS_View.h +++ b/libraries/AP_AHRS/AP_AHRS_View.h @@ -141,8 +141,8 @@ class AP_AHRS_View return ahrs.groundspeed(); } - const Vector3f &get_accel_ef_blended(void) const { - return ahrs.get_accel_ef_blended(); + const Vector3f &get_accel_ef(void) const { + return ahrs.get_accel_ef(); } uint32_t getLastPosNorthEastReset(Vector2f &pos) WARN_IF_UNUSED { @@ -187,10 +187,17 @@ class AP_AHRS_View // get current rotation + // note that this may not be the rotation were actually using, see _pitch_trim_deg enum Rotation get_rotation(void) const { return rotation; } + // get pitch trim (deg) + float get_pitch_trim() const { return _pitch_trim_deg; } + + // Rotate vector from AHRS reference frame to AHRS view refences frame + void rotate(Vector3f &vec) const; + private: const enum Rotation rotation; AP_AHRS &ahrs; diff --git a/libraries/AP_AHRS/LogStructure.h b/libraries/AP_AHRS/LogStructure.h index c8eb04f2a4a..9434ebfe7bf 100644 --- a/libraries/AP_AHRS/LogStructure.h +++ b/libraries/AP_AHRS/LogStructure.h @@ -8,7 +8,8 @@ LOG_ATTITUDE_MSG, \ LOG_ORGN_MSG, \ LOG_POS_MSG, \ - LOG_RATE_MSG + LOG_RATE_MSG, \ + LOG_ATSC_MSG // @LoggerMessage: AHR2 // @Description: Backup AHRS data @@ -168,6 +169,20 @@ struct PACKED log_Video_Stabilisation { float Q4; }; +// @LoggerMessage: ATSC +// @Description: Scale factors for attitude controller +// @Field: TimeUS: Time since system startup +// @Field: AngPScX: Angle P scale X +// @Field: AngPScY: Angle P scale Y +// @Field: AngPScZ: Angle P scale Z +struct PACKED log_ATSC { + LOG_PACKET_HEADER; + uint64_t time_us; + float scaleP_x; + float scaleP_y; + float scaleP_z; +}; + #define LOG_STRUCTURE_FROM_AHRS \ { LOG_AHR2_MSG, sizeof(log_AHRS), \ @@ -182,6 +197,8 @@ struct PACKED log_Video_Stabilisation { "POS","QLLfff","TimeUS,Lat,Lng,Alt,RelHomeAlt,RelOriginAlt", "sDUmmm", "FGG000" , true }, \ { LOG_RATE_MSG, sizeof(log_Rate), \ "RATE", "Qffffffffffff", "TimeUS,RDes,R,ROut,PDes,P,POut,YDes,Y,YOut,ADes,A,AOut", "skk-kk-kk-oo-", "F?????????BB-" , true }, \ + { LOG_ATSC_MSG, sizeof(log_ATSC), \ + "ATSC", "Qfff", "TimeUS,AngPScX,AngPScY,AngPScZ", "s---", "F000" , true }, \ { LOG_VIDEO_STABILISATION_MSG, sizeof(log_Video_Stabilisation), \ "VSTB", "Qffffffffff", "TimeUS,GyrX,GyrY,GyrZ,AccX,AccY,AccZ,Q1,Q2,Q3,Q4", "sEEEooo????", "F000000????" }, diff --git a/libraries/AP_AIS/AP_AIS.cpp b/libraries/AP_AIS/AP_AIS.cpp index 84e6367c10f..628ea79a5f9 100644 --- a/libraries/AP_AIS/AP_AIS.cpp +++ b/libraries/AP_AIS/AP_AIS.cpp @@ -19,7 +19,13 @@ #include "AP_AIS.h" -#if HAL_AIS_ENABLED +#if AP_AIS_ENABLED + +#include + +#define AP_AIS_DUMMY_METHODS_ENABLED ((AP_AIS_ENABLED == 2) && !APM_BUILD_TYPE(APM_BUILD_Rover)) + +#if !AP_AIS_DUMMY_METHODS_ENABLED #include #include @@ -63,9 +69,20 @@ const AP_Param::GroupInfo AP_AIS::var_info[] = { // constructor AP_AIS::AP_AIS() { + if (_singleton != nullptr) { + AP_HAL::panic("AIS must be singleton"); + } + _singleton = this; + AP_Param::setup_object_defaults(this, var_info); } +// return true if AIS is enabled +bool AP_AIS::enabled() const +{ + return AISType(_type.get()) != AISType::NONE; +} + // Initialize the AIS object and prepare it for use void AP_AIS::init() { @@ -804,4 +821,30 @@ bool AP_AIS::decode_latest_term() return false; } -#endif // HAL_AIS_ENABLED +// get singleton instance +AP_AIS *AP_AIS::get_singleton() { + return _singleton; +} + +#else +// Dummy methods are required to allow functionality to be enabled for Rover. +// It is not posible to compile in or out the full code based on vehicle type due to limitations +// of the handling of `APM_BUILD_TYPE` define. +// These dummy methods minimise flash cost in that case. + +const AP_Param::GroupInfo AP_AIS::var_info[] = { AP_GROUPEND }; +AP_AIS::AP_AIS() {}; + +bool AP_AIS::enabled() const { return false; } + +void AP_AIS::init() {}; +void AP_AIS::update() {}; +void AP_AIS::send(mavlink_channel_t chan) {}; + +AP_AIS *AP_AIS::get_singleton() { return nullptr; } + +#endif // AP_AIS_DUMMY_METHODS_ENABLED + +AP_AIS *AP_AIS::_singleton; + +#endif // AP_AIS_ENABLED diff --git a/libraries/AP_AIS/AP_AIS.h b/libraries/AP_AIS/AP_AIS.h index e7507f35bf7..1f4c82e6409 100644 --- a/libraries/AP_AIS/AP_AIS.h +++ b/libraries/AP_AIS/AP_AIS.h @@ -14,15 +14,17 @@ */ #pragma once +#include "AP_AIS_config.h" + +#if AP_AIS_ENABLED +// 0 fully disabled and compiled out +// 1 compiled in and enabled +// 2 compiled in with dummy methods, none functional, except rover which never uses dummy methods functionality + #include #include #include - -#ifndef HAL_AIS_ENABLED -#define HAL_AIS_ENABLED !HAL_MINIMIZE_FEATURES -#endif - -#if HAL_AIS_ENABLED +#include #define AIVDM_BUFFER_SIZE 10 #define AIVDM_PAYLOAD_SIZE 65 @@ -32,12 +34,13 @@ class AP_AIS public: AP_AIS(); - /* Do not allow copies */ - AP_AIS(const AP_AIS &other) = delete; - AP_AIS &operator=(const AP_AIS&) = delete; + CLASS_NO_COPY(AP_AIS); + + // get singleton instance + static AP_AIS *get_singleton(); // return true if AIS is enabled - bool enabled() const { return AISType(_type.get()) != AISType::NONE; } + bool enabled() const; // Initialize the AIS object and prepare it for use void init(); @@ -131,6 +134,8 @@ class AP_AIS bool _term_is_checksum; // current term is the checksum bool _sentence_valid; // is current sentence valid so far bool _sentence_done; // true if this sentence has already been decoded + + static AP_AIS *_singleton; }; -#endif // HAL_AIS_ENABLED +#endif // AP_AIS_ENABLED diff --git a/libraries/AP_AIS/AP_AIS_config.h b/libraries/AP_AIS/AP_AIS_config.h new file mode 100644 index 00000000000..d80b65934df --- /dev/null +++ b/libraries/AP_AIS/AP_AIS_config.h @@ -0,0 +1,11 @@ +#pragma once + +#include + +#ifndef AP_AIS_ENABLED +#if BOARD_FLASH_SIZE <= 1024 + #define AP_AIS_ENABLED 0 +#else + #define AP_AIS_ENABLED 2 +#endif +#endif diff --git a/libraries/AP_AIS/LogStructure.h b/libraries/AP_AIS/LogStructure.h index 563a29e9c62..2eeb701f91c 100644 --- a/libraries/AP_AIS/LogStructure.h +++ b/libraries/AP_AIS/LogStructure.h @@ -1,6 +1,7 @@ #pragma once #include +#include "AP_AIS_config.h" #define LOG_IDS_FROM_AIS \ LOG_AIS_RAW_MSG,\ @@ -140,6 +141,9 @@ struct PACKED log_AIS_msg5 { // @Field: dst: Destination // @Field: dte: DTE +#if !AP_AIS_ENABLED +#define LOG_STRUCTURE_FROM_AIS +#else #define LOG_STRUCTURE_FROM_AIS \ { LOG_AIS_RAW_MSG, sizeof(log_AIS_raw), \ "AISR", "QBBBZ", "TimeUS,num,total,ID,payload", "s----", "F0000" }, \ @@ -148,4 +152,5 @@ struct PACKED log_AIS_msg5 { { LOG_AIS_MSG4, sizeof(log_AIS_msg4), \ "AIS4", "QBIHBBBBBBLLBBI", "US,rep,mmsi,year,mth,day,h,m,s,fix,lon,lat,epfd,raim,rad", "s--------------", "F00000000000000" }, \ { LOG_AIS_MSG5, sizeof(log_AIS_msg5), \ - "AIS5", "QBIBINZBHHBBBBZB", "US,rep,mmsi,ver,imo,cal,nam,typ,bow,stn,prt,str,fix,dght,dst,dte", "s-------mmmm-m--", "F------------A--" } + "AIS5", "QBIBINZBHHBBBBZB", "US,rep,mmsi,ver,imo,cal,nam,typ,bow,stn,prt,str,fix,dght,dst,dte", "s-------mmmm-m--", "F------------A--" }, +#endif diff --git a/libraries/AP_AccelCal/AP_AccelCal.cpp b/libraries/AP_AccelCal/AP_AccelCal.cpp index dd0c0d9b1f3..0867cfbf923 100644 --- a/libraries/AP_AccelCal/AP_AccelCal.cpp +++ b/libraries/AP_AccelCal/AP_AccelCal.cpp @@ -362,15 +362,33 @@ bool AP_AccelCal::client_active(uint8_t client_num) } #if HAL_GCS_ENABLED -void AP_AccelCal::handleMessage(const mavlink_message_t &msg) +void AP_AccelCal::handle_command_ack(const mavlink_command_ack_t &packet) { if (!_waiting_for_mavlink_ack) { return; } - _waiting_for_mavlink_ack = false; - if (msg.msgid == MAVLINK_MSG_ID_COMMAND_ACK) { - _start_collect_sample = true; + // this is support for the old, non-accelcal-specific calibration. + // The GCS is expected to send back a COMMAND_ACK when the vehicle + // is posed, but we placed no constraints on the result code or + // the command field in the ack packet. That meant that any ACK + // would move the cal process forward - and since we don't even + // check the source system/component here the process could easily + // fail due to other ACKs floating around the mavlink network. + // GCSs should be moved to using the non-gcs-snoop method. As a + // round-up: + // MAVProxy: command=1-6 depending on pose, result=1 + // QGC: command=0, result=1 + // MissionPlanner: uses new ACCELCAL_VEHICLE_POS + if (packet.command > 6) { + // not an acknowledgement for a vehicle position + return; } + if (packet.result != MAV_RESULT_TEMPORARILY_REJECTED) { + // not an acknowledgement for a vehicle position + return; + } + _waiting_for_mavlink_ack = false; + _start_collect_sample = true; } bool AP_AccelCal::gcs_vehicle_position(float position) diff --git a/libraries/AP_AccelCal/AP_AccelCal.h b/libraries/AP_AccelCal/AP_AccelCal.h index f8c4badda29..5b0e26d0821 100644 --- a/libraries/AP_AccelCal/AP_AccelCal.h +++ b/libraries/AP_AccelCal/AP_AccelCal.h @@ -43,7 +43,7 @@ class AP_AccelCal { static void register_client(AP_AccelCal_Client* client); #if HAL_GCS_ENABLED - void handleMessage(const mavlink_message_t &msg); + void handle_command_ack(const mavlink_command_ack_t &packet); #endif // true if we are in a calibration process diff --git a/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp b/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp index 5004afa0ae6..71f0a7ead0d 100644 --- a/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp +++ b/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp @@ -42,13 +42,13 @@ const AP_Param::GroupInfo AP_AdvancedFailsafe::var_info[] = { // @Param: MAN_PIN // @DisplayName: Manual Pin - // @Description: This sets a digital output pin to set high when in manual mode + // @Description: This sets a digital output pin to set high when in manual mode. See the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot. // @User: Advanced AP_GROUPINFO("MAN_PIN", 0, AP_AdvancedFailsafe, _manual_pin, -1), // @Param: HB_PIN // @DisplayName: Heartbeat Pin - // @Description: This sets a digital output pin which is cycled at 10Hz when termination is not activated. Note that if a FS_TERM_PIN is set then the heartbeat pin will continue to cycle at 10Hz when termination is activated, to allow the termination board to distinguish between autopilot crash and termination. + // @Description: This sets a digital output pin which is cycled at 10Hz when termination is not activated. Note that if a FS_TERM_PIN is set then the heartbeat pin will continue to cycle at 10Hz when termination is activated, to allow the termination board to distinguish between autopilot crash and termination. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot. // @User: Advanced // @Values: -1:Disabled,49:BB Blue GP0 pin 4,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6,57:BB Blue GP0 pin 3,113:BB Blue GP0 pin 6,116:BB Blue GP0 pin 5 AP_GROUPINFO("HB_PIN", 1, AP_AdvancedFailsafe, _heartbeat_pin, -1), @@ -79,7 +79,7 @@ const AP_Param::GroupInfo AP_AdvancedFailsafe::var_info[] = { // @Param: TERM_PIN // @DisplayName: Terminate Pin - // @Description: This sets a digital output pin to set high on flight termination + // @Description: This sets a digital output pin to set high on flight termination. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot. // @User: Advanced // @Values: -1:Disabled,49:BB Blue GP0 pin 4,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6,57:BB Blue GP0 pin 3,113:BB Blue GP0 pin 6,116:BB Blue GP0 pin 5 AP_GROUPINFO("TERM_PIN", 7, AP_AdvancedFailsafe, _terminate_pin, -1), diff --git a/libraries/AP_Airspeed/AP_Airspeed.cpp b/libraries/AP_Airspeed/AP_Airspeed.cpp index 11a5c1528a1..7fab6c0e053 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed.cpp @@ -45,15 +45,10 @@ #include "AP_Airspeed_analog.h" #include "AP_Airspeed_ASP5033.h" #include "AP_Airspeed_Backend.h" -#if HAL_ENABLE_LIBUAVCAN_DRIVERS #include "AP_Airspeed_UAVCAN.h" -#endif -#if APM_BUILD_TYPE(APM_BUILD_Rover) || APM_BUILD_TYPE(APM_BUILD_ArduSub) #include "AP_Airspeed_NMEA.h" -#endif -#if HAL_MSP_AIRSPEED_ENABLED #include "AP_Airspeed_MSP.h" -#endif +#include "AP_Airspeed_SITL.h" extern const AP_HAL::HAL &hal; #ifdef HAL_AIRSPEED_TYPE_DEFAULT @@ -92,7 +87,7 @@ extern const AP_HAL::HAL &hal; #define PSI_RANGE_DEFAULT 1.0f #endif -#define OPTIONS_DEFAULT AP_Airspeed::OptionsMask::ON_FAILURE_AHRS_WIND_MAX_DO_DISABLE | AP_Airspeed::OptionsMask::ON_FAILURE_AHRS_WIND_MAX_RECOVERY_DO_REENABLE +#define OPTIONS_DEFAULT AP_Airspeed::OptionsMask::ON_FAILURE_AHRS_WIND_MAX_DO_DISABLE | AP_Airspeed::OptionsMask::ON_FAILURE_AHRS_WIND_MAX_RECOVERY_DO_REENABLE | AP_Airspeed::OptionsMask::USE_EKF_CONSISTENCY // table of user settable parameters const AP_Param::GroupInfo AP_Airspeed::var_info[] = { @@ -100,7 +95,7 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = { // @Param: _TYPE // @DisplayName: Airspeed type // @Description: Type of airspeed sensor - // @Values: 0:None,1:I2C-MS4525D0,2:Analog,3:I2C-MS5525,4:I2C-MS5525 (0x76),5:I2C-MS5525 (0x77),6:I2C-SDP3X,7:I2C-DLVR-5in,8:DroneCAN,9:I2C-DLVR-10in,10:I2C-DLVR-20in,11:I2C-DLVR-30in,12:I2C-DLVR-60in,13:NMEA water speed,14:MSP,15:ASP5033 + // @Values: 0:None,1:I2C-MS4525D0,2:Analog,3:I2C-MS5525,4:I2C-MS5525 (0x76),5:I2C-MS5525 (0x77),6:I2C-SDP3X,7:I2C-DLVR-5in,8:DroneCAN,9:I2C-DLVR-10in,10:I2C-DLVR-20in,11:I2C-DLVR-30in,12:I2C-DLVR-60in,13:NMEA water speed,14:MSP,15:ASP5033,100:SITL // @User: Standard AP_GROUPINFO_FLAGS("_TYPE", 0, AP_Airspeed, param[0].type, ARSPD_DEFAULT_TYPE, AP_PARAM_FLAG_ENABLE), // NOTE: Index 0 is actually used as index 63 here @@ -115,6 +110,7 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = { // @Param: _USE // @DisplayName: Airspeed use // @Description: Enables airspeed use for automatic throttle modes and replaces control from THR_TRIM. Continues to display and log airspeed if set to 0. Uses airspeed for control if set to 1. Only uses airspeed when throttle = 0 if set to 2 (useful for gliders with airspeed sensors behind propellers). + // @Description{Copter, Blimp, Rover, Sub}: This parameter is not used by this vehicle. Always set to 0. // @Values: 0:DoNotUse,1:Use,2:UseWhenZeroThrottle // @User: Standard AP_GROUPINFO("_USE", 1, AP_Airspeed, param[0].use, 0), @@ -143,6 +139,7 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = { #if AP_AIRSPEED_AUTOCAL_ENABLE // @Param: _AUTOCAL // @DisplayName: Automatic airspeed ratio calibration + // @DisplayName{Copter, Blimp, Rover, Sub}: This parameter and function is not used by this vehicle. Always set to 0. // @Description: Enables automatic adjustment of ARSPD_RATIO during a calibration flight based on estimation of ground speed and true airspeed. New ratio saved every 2 minutes if change is > 5%. Should not be left enabled. // @User: Advanced AP_GROUPINFO("_AUTOCAL", 5, AP_Airspeed, param[0].autocal, 0), @@ -150,13 +147,14 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = { // @Param: _TUBE_ORDER // @DisplayName: Control pitot tube order - // @Description: Changes the pitot tube order to specify the dynamic pressure side of the sensor. Accepts either if set to 2. Accepts only one side if set to 0 or 1 and can help detect excessive pressure on the static port without indicating positive airspeed. + // @Description: This parameter allows you to control whether the order in which the tubes are attached to your pitot tube matters. If you set this to 0 then the first (often the top) connector on the sensor needs to be the stagnation pressure (the pressure at the tip of the pitot tube). If set to 1 then the second (often the bottom) connector needs to be the stagnation pressure. If set to 2 (the default) then the airspeed driver will accept either order. The reason you may wish to specify the order is it will allow your airspeed sensor to detect if the aircraft is receiving excessive pressure on the static port compared to the stagnation port such as during a stall, which would otherwise be seen as a positive airspeed. // @User: Advanced + // @Values: 0:Normal,1:Swapped,2:Auto Detect AP_GROUPINFO("_TUBE_ORDER", 6, AP_Airspeed, param[0].tube_order, 2), #ifndef HAL_BUILD_AP_PERIPH // @Param: _SKIP_CAL - // @DisplayName: Skip airspeed calibration on startup + // @DisplayName: Skip airspeed offset calibration on startup // @Description: This parameter allows you to skip airspeed offset calibration on startup, instead using the offset from the last calibration. This may be desirable if the offset variance between flights for your sensor is low and you want to avoid having to cover the pitot tube on each boot. // @Values: 0:Disable,1:Enable // @User: Advanced @@ -165,7 +163,7 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = { // @Param: _PSI_RANGE // @DisplayName: The PSI range of the device - // @Description: This parameter allows you to to set the PSI (pounds per square inch) range for your sensor. You should not change this unless you examine the datasheet for your device + // @Description: This parameter allows you to set the PSI (pounds per square inch) range for your sensor. You should not change this unless you examine the datasheet for your device // @User: Advanced AP_GROUPINFO("_PSI_RANGE", 8, AP_Airspeed, param[0].psi_range, PSI_RANGE_DEFAULT), @@ -173,7 +171,7 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = { // @Param: _BUS // @DisplayName: Airspeed I2C bus // @Description: Bus number of the I2C bus where the airspeed sensor is connected - // @Values: 0:Bus0(internal),1:Bus1(external),2:Bus2(auxillary) + // @Values: 0:Bus0(internal),1:Bus1(external),2:Bus2(auxiliary) // @User: Advanced AP_GROUPINFO("_BUS", 9, AP_Airspeed, param[0].bus, HAL_AIRSPEED_BUS_DEFAULT), #endif // HAL_BUILD_AP_PERIPH @@ -190,14 +188,16 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = { #ifndef HAL_BUILD_AP_PERIPH // @Param: _OPTIONS // @DisplayName: Airspeed options bitmask - // @Description: Bitmask of options to use with airspeed. 0:Disable use based on airspeed/groundspeed mismatch (see ARSPD_WIND_MAX), 1:Automatically reenable use based on airspeed/groundspeed mismatch recovery (see ARSPD_WIND_MAX) 2:Disable voltage correction - // @Bitmask: 0:SpeedMismatchDisable, 1:AllowSpeedMismatchRecovery, 2:DisableVoltageCorrection + // @Description: Bitmask of options to use with airspeed. 0:Disable use based on airspeed/groundspeed mismatch (see ARSPD_WIND_MAX), 1:Automatically reenable use based on airspeed/groundspeed mismatch recovery (see ARSPD_WIND_MAX) 2:Disable voltage correction, 3:Check that the airspeed is statistically consistent with the navigation EKF vehicle and wind velocity estimates using EKF3 (requires AHRS_EKF_TYPE = 3) + // @Description{Copter, Blimp, Rover, Sub}: This parameter and function is not used by this vehicle. Always set to 0. + // @Bitmask: 0:SpeedMismatchDisable, 1:AllowSpeedMismatchRecovery, 2:DisableVoltageCorrection, 3:UseEkf3Consistency // @User: Advanced AP_GROUPINFO("_OPTIONS", 21, AP_Airspeed, _options, OPTIONS_DEFAULT), // @Param: _WIND_MAX // @DisplayName: Maximum airspeed and ground speed difference // @Description: If the difference between airspeed and ground speed is greater than this value the sensor will be marked unhealthy. Using ARSPD_OPTION this health value can be used to disable the sensor. + // @Description{Copter, Blimp, Rover, Sub}: This parameter and function is not used by this vehicle. Always set to 0. // @Units: m/s // @User: Advanced AP_GROUPINFO("_WIND_MAX", 22, AP_Airspeed, _wind_max, 0), @@ -205,9 +205,19 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = { // @Param: _WIND_WARN // @DisplayName: Airspeed and ground speed difference that gives a warning // @Description: If the difference between airspeed and ground speed is greater than this value the sensor will issue a warning. If 0 ARSPD_WIND_MAX is used. + // @Description{Copter, Blimp, Rover, Sub}: This parameter and function is not used by this vehicle. Always set to 0. // @Units: m/s // @User: Advanced AP_GROUPINFO("_WIND_WARN", 23, AP_Airspeed, _wind_warn, 0), + + // @Param: _WIND_GATE + // @DisplayName: Re-enable Consistency Check Gate Size + // @Description: Number of standard deviations applied to the re-enable EKF consistency check that is used when ARSPD_OPTIONS bit position 3 is set. Larger values will make the re-enabling of the airspeed sensor faster, but increase the likelihood of re-enabling a degraded sensor. The value can be tuned by using the ARSP.TR log message by setting ARSP_WIND_GATE to a value that is higher than the value for ARSP.TR observed with a healthy airspeed sensor. Occasional transients in ARSP.TR above the value set by ARSP_WIND_GATE can be tolerated provided they are less than 5 seconds in duration and less than 10% duty cycle. + // @Description{Copter, Blimp, Rover, Sub}: This parameter and function is not used by this vehicle. + // @Range: 0.0 10.0 + // @User: Advanced + AP_GROUPINFO("_WIND_GATE", 26, AP_Airspeed, _wind_gate, 5.0f), + #endif #if AIRSPEED_MAX_SENSORS > 1 @@ -221,6 +231,7 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = { // @Param: 2_USE // @DisplayName: Enable use of 2nd airspeed sensor // @Description: use airspeed for flight control. When set to 0 airspeed sensor can be logged and displayed on a GCS but won't be used for flight. When set to 1 it will be logged and used. When set to 2 it will be only used when the throttle is zero, which can be useful in gliders with airspeed sensors behind a propeller + // @Description{Copter, Blimp, Rover, Sub}: This parameter and function is not used by this vehicle. Always set to 0. // @Values: 0:Don't Use,1:use,2:UseWhenZeroThrottle // @User: Standard AP_GROUPINFO("2_USE", 12, AP_Airspeed, param[1].use, 0), @@ -248,17 +259,19 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = { // @Param: 2_AUTOCAL // @DisplayName: Automatic airspeed ratio calibration for 2nd airspeed sensor // @Description: If this is enabled then the autopilot will automatically adjust the ARSPD_RATIO during flight, based upon an estimation filter using ground speed and true airspeed. The automatic calibration will save the new ratio to EEPROM every 2 minutes if it changes by more than 5%. This option should be enabled for a calibration flight then disabled again when calibration is complete. Leaving it enabled all the time is not recommended. + // @Description{Copter, Blimp, Rover, Sub}: This parameter and function is not used by this vehicle. Always set to 0. // @User: Advanced AP_GROUPINFO("2_AUTOCAL", 16, AP_Airspeed, param[1].autocal, 0), // @Param: 2_TUBE_ORDR // @DisplayName: Control pitot tube order of 2nd airspeed sensor - // @Description: This parameter allows you to control whether the order in which the tubes are attached to your pitot tube matters. If you set this to 0 then the top connector on the sensor needs to be the dynamic pressure. If set to 1 then the bottom connector needs to be the dynamic pressure. If set to 2 (the default) then the airspeed driver will accept either order. The reason you may wish to specify the order is it will allow your airspeed sensor to detect if the aircraft it receiving excessive pressure on the static port, which would otherwise be seen as a positive airspeed. + // @Description: This parameter allows you to control whether the order in which the tubes are attached to your pitot tube matters. If you set this to 0 then the first (often the top) connector on the sensor needs to be the stagnation pressure (the pressure at the tip of the pitot tube). If set to 1 then the second (often the bottom) connector needs to be the stagnation pressure. If set to 2 (the default) then the airspeed driver will accept either order. The reason you may wish to specify the order is it will allow your airspeed sensor to detect if the aircraft is receiving excessive pressure on the static port compared to the stagnation port such as during a stall, which would otherwise be seen as a positive airspeed. // @User: Advanced + // @Values: 0:Normal,1:Swapped,2:Auto Detect AP_GROUPINFO("2_TUBE_ORDR", 17, AP_Airspeed, param[1].tube_order, 2), // @Param: 2_SKIP_CAL - // @DisplayName: Skip airspeed calibration on startup for 2nd sensor + // @DisplayName: Skip airspeed offset calibration on startup for 2nd sensor // @Description: This parameter allows you to skip airspeed offset calibration on startup, instead using the offset from the last calibration. This may be desirable if the offset variance between flights for your sensor is low and you want to avoid having to cover the pitot tube on each boot. // @Values: 0:Disable,1:Enable // @User: Advanced @@ -266,14 +279,14 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = { // @Param: 2_PSI_RANGE // @DisplayName: The PSI range of the device for 2nd sensor - // @Description: This parameter allows you to to set the PSI (pounds per square inch) range for your sensor. You should not change this unless you examine the datasheet for your device + // @Description: This parameter allows you to set the PSI (pounds per square inch) range for your sensor. You should not change this unless you examine the datasheet for your device // @User: Advanced AP_GROUPINFO("2_PSI_RANGE", 19, AP_Airspeed, param[1].psi_range, PSI_RANGE_DEFAULT), // @Param: 2_BUS // @DisplayName: Airspeed I2C bus for 2nd sensor // @Description: The bus number of the I2C bus to look for the sensor on - // @Values: 0:Bus0(internal),1:Bus1(external),2:Bus2(auxillary) + // @Values: 0:Bus0(internal),1:Bus1(external),2:Bus2(auxiliary) // @User: Advanced AP_GROUPINFO("2_BUS", 20, AP_Airspeed, param[1].bus, 1), @@ -288,7 +301,7 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = { #endif // AIRSPEED_MAX_SENSORS - // Note that 21, 22 and 23 are used above by the _OPTIONS, _WIND_MAX and _WIND_WARN parameters. Do not use them!! + // Note that 21, 22, 23, 24, 25 and 26 are used above by the _OPTIONS, _DEVID, __WIND_MAX, _WIND_WARN and _WIND_GATE parameters. Do not use them!! // NOTE: Index 63 is used by AIRSPEED_TYPE, Do not use it!: AP_Param converts an index of 0 to 63 so that the index may be bit shifted AP_GROUPEND @@ -385,65 +398,84 @@ void AP_Airspeed::init() // nothing to do break; case TYPE_I2C_MS4525: +#if AP_AIRSPEED_MS4525_ENABLED sensor[i] = new AP_Airspeed_MS4525(*this, i); +#endif + break; + case TYPE_SITL: +#if AP_AIRSPEED_SITL_ENABLED + sensor[i] = new AP_Airspeed_SITL(*this, i); +#endif break; case TYPE_ANALOG: +#if AP_AIRSPEED_ANALOG_ENABLED sensor[i] = new AP_Airspeed_Analog(*this, i); +#endif break; case TYPE_I2C_MS5525: +#if AP_AIRSPEED_MS5525_ENABLED sensor[i] = new AP_Airspeed_MS5525(*this, i, AP_Airspeed_MS5525::MS5525_ADDR_AUTO); +#endif break; case TYPE_I2C_MS5525_ADDRESS_1: +#if AP_AIRSPEED_MS5525_ENABLED sensor[i] = new AP_Airspeed_MS5525(*this, i, AP_Airspeed_MS5525::MS5525_ADDR_1); +#endif break; case TYPE_I2C_MS5525_ADDRESS_2: +#if AP_AIRSPEED_MS5525_ENABLED sensor[i] = new AP_Airspeed_MS5525(*this, i, AP_Airspeed_MS5525::MS5525_ADDR_2); +#endif break; case TYPE_I2C_SDP3X: +#if AP_AIRSPEED_SDP3X_ENABLED sensor[i] = new AP_Airspeed_SDP3X(*this, i); +#endif break; case TYPE_I2C_DLVR_5IN: -#if !HAL_MINIMIZE_FEATURES +#if AP_AIRSPEED_DLVR_ENABLED sensor[i] = new AP_Airspeed_DLVR(*this, i, 5); -#endif // !HAL_MINIMIZE_FEATURES +#endif break; case TYPE_I2C_DLVR_10IN: -#if !HAL_MINIMIZE_FEATURES +#if AP_AIRSPEED_DLVR_ENABLED sensor[i] = new AP_Airspeed_DLVR(*this, i, 10); -#endif // !HAL_MINIMIZE_FEATURES +#endif break; case TYPE_I2C_DLVR_20IN: -#if !HAL_MINIMIZE_FEATURES +#if AP_AIRSPEED_DLVR_ENABLED sensor[i] = new AP_Airspeed_DLVR(*this, i, 20); -#endif // !HAL_MINIMIZE_FEATURES +#endif break; case TYPE_I2C_DLVR_30IN: -#if !HAL_MINIMIZE_FEATURES +#if AP_AIRSPEED_DLVR_ENABLED sensor[i] = new AP_Airspeed_DLVR(*this, i, 30); -#endif // !HAL_MINIMIZE_FEATURES +#endif break; case TYPE_I2C_DLVR_60IN: -#if !HAL_MINIMIZE_FEATURES +#if AP_AIRSPEED_DLVR_ENABLED sensor[i] = new AP_Airspeed_DLVR(*this, i, 60); -#endif // !HAL_MINIMIZE_FEATURES +#endif // AP_AIRSPEED_DLVR_ENABLED break; case TYPE_I2C_ASP5033: -#if !HAL_MINIMIZE_FEATURES +#if AP_AIRSPEED_ASP5033_ENABLED sensor[i] = new AP_Airspeed_ASP5033(*this, i); -#endif // !HAL_MINIMIZE_FEATURES +#endif break; case TYPE_UAVCAN: -#if HAL_ENABLE_LIBUAVCAN_DRIVERS - sensor[i] = AP_Airspeed_UAVCAN::probe(*this, i); +#if AP_AIRSPEED_UAVCAN_ENABLED + sensor[i] = AP_Airspeed_UAVCAN::probe(*this, i, uint32_t(param[i].bus_id.get())); #endif break; case TYPE_NMEA_WATER: +#if AP_AIRSPEED_NMEA_ENABLED #if APM_BUILD_TYPE(APM_BUILD_Rover) || APM_BUILD_TYPE(APM_BUILD_ArduSub) sensor[i] = new AP_Airspeed_NMEA(*this, i); +#endif #endif break; case TYPE_MSP: -#if HAL_MSP_AIRSPEED_ENABLED +#if AP_AIRSPEED_MSP_ENABLED sensor[i] = new AP_Airspeed_MSP(*this, i, 0); #endif break; @@ -457,7 +489,30 @@ void AP_Airspeed::init() num_sensors = i+1; } } + +#if AP_AIRSPEED_UAVCAN_ENABLED + // we need a 2nd pass for DroneCAN sensors so we can match order by DEVID + // the 2nd pass accepts any devid + for (uint8_t i=0; iget_hygrometer(hygrometer.sample_ms, hygrometer.temperature, hygrometer.humidity) && + hygrometer.sample_ms != state[i].last_hygrometer_log_ms) { + AP::logger().WriteStreaming("HYGR", + "TimeUS,Id,Humidity,Temp", + "s#%O", + "F---", + "QBff", + AP_HAL::micros64(), + i, + hygrometer.humidity, + hygrometer.temperature); + state[i].last_hygrometer_log_ms = hygrometer.sample_ms; + } +#endif } } @@ -728,6 +812,68 @@ bool AP_Airspeed::all_healthy(void) const return true; } +// return true if airspeed is enabled +bool AP_Airspeed::enabled(uint8_t i) const { + if (i < AIRSPEED_MAX_SENSORS) { + return param[i].type.get() != TYPE_NONE; + } + return false; +} + +// return health status of sensor +bool AP_Airspeed::healthy(uint8_t i) const { + bool ok = state[i].healthy && enabled(i) && sensor[i] != nullptr; +#ifndef HAL_BUILD_AP_PERIPH + // sanity check the offset parameter. Zero is permitted if we are skipping calibration. + ok &= (fabsf(param[i].offset) > 0 || state[i].use_zero_offset || param[i].skip_cal); +#endif + return ok; +} + +// return the current airspeed in m/s +float AP_Airspeed::get_airspeed(uint8_t i) const { + if (!enabled(i)) { + // we can't have negative airspeed so sending an obviously invalid value + return -1.0; + } + return state[i].airspeed; +} + +// return the unfiltered airspeed in m/s +float AP_Airspeed::get_raw_airspeed(uint8_t i) const { + if (!enabled(i)) { + // we can't have negative airspeed so sending an obviously invalid value + return -1.0; + } + return state[i].raw_airspeed; +} + +// return the differential pressure in Pascal for the last airspeed reading +float AP_Airspeed::get_differential_pressure(uint8_t i) const { + if (!enabled(i)) { + return 0.0; + } + return state[i].last_pressure; +} + +// return the current corrected pressure +float AP_Airspeed::get_corrected_pressure(uint8_t i) const { + if (!enabled(i)) { + return 0.0; + } + return state[i].corrected_pressure; +} + +#if AP_AIRSPEED_HYGROMETER_ENABLE +bool AP_Airspeed::get_hygrometer(uint8_t i, uint32_t &last_sample_ms, float &temperature, float &humidity) const +{ + if (!enabled(i) || sensor[i] == nullptr) { + return false; + } + return sensor[i]->get_hygrometer(last_sample_ms, temperature, humidity); +} +#endif // AP_AIRSPEED_HYGROMETER_ENABLE + #else // build type is not appropriate; provide a dummy implementation: const AP_Param::GroupInfo AP_Airspeed::var_info[] = { AP_GROUPEND }; @@ -735,8 +881,12 @@ void AP_Airspeed::update() {}; bool AP_Airspeed::get_temperature(uint8_t i, float &temperature) { return false; } void AP_Airspeed::calibrate(bool in_startup) {} bool AP_Airspeed::use(uint8_t i) const { return false; } +bool AP_Airspeed::enabled(uint8_t i) const { return false; } +bool AP_Airspeed::healthy(uint8_t i) const { return false; } +float AP_Airspeed::get_airspeed(uint8_t i) const { return 0.0; } +float AP_Airspeed::get_differential_pressure(uint8_t i) const { return 0.0; } -#if HAL_MSP_AIRSPEED_ENABLED +#if AP_AIRSPEED_MSP_ENABLED void AP_Airspeed::handle_msp(const MSP::msp_airspeed_data_message_t &pkt) {} #endif diff --git a/libraries/AP_Airspeed/AP_Airspeed.h b/libraries/AP_Airspeed/AP_Airspeed.h index a4790d484b1..b860cfe137f 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.h +++ b/libraries/AP_Airspeed/AP_Airspeed.h @@ -1,30 +1,12 @@ #pragma once -#include -#include +#include "AP_Airspeed_config.h" + #include -#include #include -#include - -#ifndef AP_AIRSPEED_ENABLED -#define AP_AIRSPEED_ENABLED 1 -#endif - class AP_Airspeed_Backend; -#ifndef AIRSPEED_MAX_SENSORS -#define AIRSPEED_MAX_SENSORS 2 -#endif - -#ifndef AP_AIRSPEED_AUTOCAL_ENABLE -#define AP_AIRSPEED_AUTOCAL_ENABLE !defined(HAL_BUILD_AP_PERIPH) -#endif - -#ifndef HAL_MSP_AIRSPEED_ENABLED -#define HAL_MSP_AIRSPEED_ENABLED HAL_MSP_SENSORS_ENABLED -#endif class Airspeed_Calibration { public: friend class AP_Airspeed; @@ -73,15 +55,11 @@ class AP_Airspeed void calibrate(bool in_startup); // return the current airspeed in m/s - float get_airspeed(uint8_t i) const { - return state[i].airspeed; - } + float get_airspeed(uint8_t i) const; float get_airspeed(void) const { return get_airspeed(primary); } // return the unfiltered airspeed in m/s - float get_raw_airspeed(uint8_t i) const { - return state[i].raw_airspeed; - } + float get_raw_airspeed(uint8_t i) const; float get_raw_airspeed(void) const { return get_raw_airspeed(primary); } // return the current airspeed ratio (dimensionless) @@ -110,32 +88,18 @@ class AP_Airspeed } // return true if airspeed is enabled - bool enabled(uint8_t i) const { - if (i < AIRSPEED_MAX_SENSORS) { - return param[i].type.get() != TYPE_NONE; - } - return false; - } + bool enabled(uint8_t i) const; bool enabled(void) const { return enabled(primary); } // return the differential pressure in Pascal for the last airspeed reading - float get_differential_pressure(uint8_t i) const { - return state[i].last_pressure; - } + float get_differential_pressure(uint8_t i) const; float get_differential_pressure(void) const { return get_differential_pressure(primary); } // update airspeed ratio calibration void update_calibration(const Vector3f &vground, int16_t max_airspeed_allowed_during_cal); // return health status of sensor - bool healthy(uint8_t i) const { - bool ok = state[i].healthy && enabled(i); -#ifndef HAL_BUILD_AP_PERIPH - // sanity check the offset parameter. Zero is permitted if we are skipping calibration. - ok &= (fabsf(param[i].offset) > 0 || state[i].use_zero_offset || param[i].skip_cal); -#endif - return ok; - } + bool healthy(uint8_t i) const; bool healthy(void) const { return healthy(primary); } // return true if all enabled sensors are healthy @@ -145,6 +109,10 @@ class AP_Airspeed uint32_t last_update_ms(uint8_t i) const { return state[i].last_update_ms; } uint32_t last_update_ms(void) const { return last_update_ms(primary); } +#if AP_AIRSPEED_HYGROMETER_ENABLE + bool get_hygrometer(uint8_t i, uint32_t &last_sample_ms, float &temperature, float &humidity) const; +#endif + static const struct AP_Param::GroupInfo var_info[]; enum pitot_tube_order { PITOT_TUBE_ORDER_POSITIVE = 0, @@ -155,6 +123,7 @@ class AP_Airspeed ON_FAILURE_AHRS_WIND_MAX_DO_DISABLE = (1<<0), // If set then use airspeed failure check ON_FAILURE_AHRS_WIND_MAX_RECOVERY_DO_REENABLE = (1<<1), // If set then automatically enable the airspeed sensor use when healthy again. DISABLE_VOLTAGE_CORRECTION = (1<<2), + USE_EKF_CONSISTENCY = (1<<3), }; enum airspeed_type { @@ -174,6 +143,7 @@ class AP_Airspeed TYPE_NMEA_WATER=13, TYPE_MSP=14, TYPE_I2C_ASP5033=15, + TYPE_SITL=100, }; // get current primary sensor @@ -185,14 +155,12 @@ class AP_Airspeed static AP_Airspeed *get_singleton() { return _singleton; } // return the current corrected pressure, public for AP_Periph - float get_corrected_pressure(uint8_t i) const { - return state[i].corrected_pressure; - } + float get_corrected_pressure(uint8_t i) const; float get_corrected_pressure(void) const { return get_corrected_pressure(primary); } -#if HAL_MSP_AIRSPEED_ENABLED +#if AP_AIRSPEED_MSP_ENABLED void handle_msp(const MSP::msp_airspeed_data_message_t &pkt); #endif @@ -203,6 +171,7 @@ class AP_Airspeed AP_Int32 _options; // bitmask options for airspeed AP_Float _wind_max; AP_Float _wind_warn; + AP_Float _wind_gate; struct { AP_Float offset; @@ -245,9 +214,14 @@ class AP_Airspeed struct { uint32_t last_check_ms; float health_probability; + float test_ratio; int8_t param_use_backup; uint32_t last_warn_ms; } failures; + +#if AP_AIRSPEED_HYGROMETER_ENABLE + uint32_t last_hygrometer_log_ms; +#endif } state[AIRSPEED_MAX_SENSORS]; bool calibration_enabled; @@ -266,12 +240,20 @@ class AP_Airspeed // returns 0 if the sensor is not enabled float get_pressure(uint8_t i); - // get the failure health probability - float get_health_failure_probability(uint8_t i) const { + // get the health probability + float get_health_probability(uint8_t i) const { return state[i].failures.health_probability; } - float get_health_failure_probability(void) const { - return get_health_failure_probability(primary); + float get_health_probability(void) const { + return get_health_probability(primary); + } + + // get the consistency test ratio + float get_test_ratio(uint8_t i) const { + return state[i].failures.test_ratio; + } + float get_test_ratio(void) const { + return get_test_ratio(primary); } void update_calibration(uint8_t i, float raw_pressure); diff --git a/libraries/AP_Airspeed/AP_Airspeed_ASP5033.cpp b/libraries/AP_Airspeed/AP_Airspeed_ASP5033.cpp index f687f72cc16..e727d5924c7 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_ASP5033.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_ASP5033.cpp @@ -19,6 +19,9 @@ */ #include "AP_Airspeed_ASP5033.h" + +#if AP_AIRSPEED_ASP5033_ENABLED + #include extern const AP_HAL::HAL &hal; @@ -174,3 +177,5 @@ bool AP_Airspeed_ASP5033::get_temperature(float &temperature) return true; } + +#endif diff --git a/libraries/AP_Airspeed/AP_Airspeed_ASP5033.h b/libraries/AP_Airspeed/AP_Airspeed_ASP5033.h index 00aaf6f4c57..99c340ec5b8 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_ASP5033.h +++ b/libraries/AP_Airspeed/AP_Airspeed_ASP5033.h @@ -14,6 +14,14 @@ */ #pragma once +#include + +#ifndef AP_AIRSPEED_ASP5033_ENABLED +#define AP_AIRSPEED_ASP5033_ENABLED AP_AIRSPEED_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_AIRSPEED_ASP5033_ENABLED + /* backend driver for airspeed from I2C */ @@ -44,3 +52,5 @@ class AP_Airspeed_ASP5033 : public AP_Airspeed_Backend AP_HAL::OwnPtr dev; }; + +#endif // AP_AIRSPEED_ASP5033_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_Backend.cpp b/libraries/AP_Airspeed/AP_Airspeed_Backend.cpp index 441747bb4ef..58b68ee7a21 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_Backend.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_Backend.cpp @@ -54,3 +54,8 @@ bool AP_Airspeed_Backend::bus_is_confgured(void) const { return frontend.param[instance].bus.configured(); } + +void AP_Airspeed_Backend::set_bus_id(uint32_t id) +{ + frontend.param[instance].bus_id.set_and_save(int32_t(id)); +} diff --git a/libraries/AP_Airspeed/AP_Airspeed_Backend.h b/libraries/AP_Airspeed/AP_Airspeed_Backend.h index 614631cacf9..4bacf9adbd1 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_Backend.h +++ b/libraries/AP_Airspeed/AP_Airspeed_Backend.h @@ -19,7 +19,8 @@ */ #include -#include +#include +#include #include "AP_Airspeed.h" class AP_Airspeed_Backend { @@ -42,9 +43,12 @@ class AP_Airspeed_Backend { // return airspeed in m/s if available virtual bool get_airspeed(float& airspeed) {return false;} -#if HAL_MSP_AIRSPEED_ENABLED virtual void handle_msp(const MSP::msp_airspeed_data_message_t &pkt) {} -#endif + +#if AP_AIRSPEED_HYGROMETER_ENABLE + // optional hygrometer support + virtual bool get_hygrometer(uint32_t &last_sample_ms, float &temperature, float &humidity) { return false; } +#endif protected: int8_t get_pin(void) const; @@ -92,9 +96,7 @@ class AP_Airspeed_Backend { } // set bus ID of this instance, for ARSPD_DEVID parameters - void set_bus_id(uint32_t id) { - frontend.param[instance].bus_id.set(int32_t(id)); - } + void set_bus_id(uint32_t id); enum class DevType { SITL = 0x01, diff --git a/libraries/AP_Airspeed/AP_Airspeed_DLVR.cpp b/libraries/AP_Airspeed/AP_Airspeed_DLVR.cpp index dcbfed53da0..211c36e3283 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_DLVR.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_DLVR.cpp @@ -18,6 +18,9 @@ */ #include "AP_Airspeed_DLVR.h" + +#if AP_AIRSPEED_DLVR_ENABLED + #include extern const AP_HAL::HAL &hal; @@ -176,3 +179,5 @@ bool AP_Airspeed_DLVR::get_temperature(float &_temperature) _temperature = temperature; return true; } + +#endif diff --git a/libraries/AP_Airspeed/AP_Airspeed_DLVR.h b/libraries/AP_Airspeed/AP_Airspeed_DLVR.h index 806e2bfeae1..2e8bd1a6b9c 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_DLVR.h +++ b/libraries/AP_Airspeed/AP_Airspeed_DLVR.h @@ -17,6 +17,14 @@ // backend driver for AllSensors DLVR differential airspeed sensor // currently assumes a 5" of water, noise reduced, sensor +#include + +#ifndef AP_AIRSPEED_DLVR_ENABLED +#define AP_AIRSPEED_DLVR_ENABLED AP_AIRSPEED_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_AIRSPEED_DLVR_ENABLED + #include #include #include @@ -60,3 +68,5 @@ class AP_Airspeed_DLVR : public AP_Airspeed_Backend AP_HAL::OwnPtr dev; }; + +#endif // AP_AIRSPEED_DLVR_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_Health.cpp b/libraries/AP_Airspeed/AP_Airspeed_Health.cpp index 4ee9a90e287..f228f550404 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_Health.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_Health.cpp @@ -4,6 +4,8 @@ #include #include #include +#include +#include void AP_Airspeed::check_sensor_failures() { @@ -23,13 +25,12 @@ void AP_Airspeed::check_sensor_ahrs_wind_max_failures(uint8_t i) } state[i].failures.last_check_ms = now_ms; - if (!is_positive(_wind_max)) { + if (!is_positive(_wind_max) && !is_positive(_wind_gate)) { // nothing to do return; } - const float aspeed = get_airspeed(); - if (aspeed <= 0) { + if (state[i].airspeed <= 0) { // invalid estimate return; } @@ -44,15 +45,34 @@ void AP_Airspeed::check_sensor_ahrs_wind_max_failures(uint8_t i) } return; } - const float speed_diff = fabsf(aspeed-gps.ground_speed()); + // check for airspeed consistent with wind and vehicle velocity using the EKF + uint32_t age_ms; + float innovation, innovationVariance; + if (AP::ahrs().airspeed_health_data(innovation, innovationVariance, age_ms) && age_ms < 1000 && is_positive(innovationVariance)) { + state[i].failures.test_ratio = fabsf(innovation) / safe_sqrt(innovationVariance); + } else { + state[i].failures.test_ratio = 0.0f; + } + bool data_is_inconsistent = false; + if (is_positive(_wind_gate) && (AP_Airspeed::OptionsMask::USE_EKF_CONSISTENCY & _options) != 0) { + float gate_size = MAX(_wind_gate, 0.0f); + if (param[i].use == 0) { + // require a smaller inconsistency for a disabled sensor to be declared consistent + gate_size *= 0.7f; + } + data_is_inconsistent = state[i].failures.test_ratio > gate_size; + } + + const float speed_diff = fabsf(state[i].airspeed-gps.ground_speed()); + const bool data_is_implausible = is_positive(_wind_max) && speed_diff > _wind_max; // update health_probability with LowPassFilter - if (speed_diff > _wind_max) { + if (data_is_implausible || data_is_inconsistent) { // bad, decay fast const float probability_coeff = 0.90f; state[i].failures.health_probability = probability_coeff*state[i].failures.health_probability; - } else { + } else if (!data_is_implausible && !data_is_inconsistent) { // good, grow slow const float probability_coeff = 0.98f; state[i].failures.health_probability = probability_coeff*state[i].failures.health_probability + (1.0f-probability_coeff)*1.0f; @@ -78,11 +98,11 @@ void AP_Airspeed::check_sensor_ahrs_wind_max_failures(uint8_t i) // set warn to max if not set or larger than max float wind_warn = _wind_warn; - if (!is_positive(wind_warn) || (wind_warn > _wind_max)) { + if ((!is_positive(wind_warn) || (wind_warn > _wind_max)) && is_positive(_wind_max)) { wind_warn = _wind_max; } - if ((speed_diff > wind_warn) && ((now_ms - state[i].failures.last_warn_ms) > 15000)) { + if (is_positive(wind_warn) && (speed_diff > wind_warn) && ((now_ms - state[i].failures.last_warn_ms) > 15000)) { state[i].failures.last_warn_ms = now_ms; GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Airspeed %d warning %0.1fm/s air to gnd speed diff", i+1, speed_diff); } diff --git a/libraries/AP_Airspeed/AP_Airspeed_MS4525.cpp b/libraries/AP_Airspeed/AP_Airspeed_MS4525.cpp index 75241031104..d6e4c456a32 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_MS4525.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_MS4525.cpp @@ -18,6 +18,8 @@ */ #include "AP_Airspeed_MS4525.h" +#if AP_AIRSPEED_MS4525_ENABLED + #include #include #include @@ -282,3 +284,5 @@ bool AP_Airspeed_MS4525::get_temperature(float &temperature) temperature = _temperature; return true; } + +#endif // AP_AIRSPEED_MS4525_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_MS4525.h b/libraries/AP_Airspeed/AP_Airspeed_MS4525.h index be11ebf25d8..64ea04fb769 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_MS4525.h +++ b/libraries/AP_Airspeed/AP_Airspeed_MS4525.h @@ -14,6 +14,14 @@ */ #pragma once +#include + +#ifndef AP_AIRSPEED_MS4525_ENABLED +#define AP_AIRSPEED_MS4525_ENABLED AP_AIRSPEED_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_AIRSPEED_MS4525_ENABLED + /* backend driver for airspeed from I2C */ @@ -61,3 +69,5 @@ class AP_Airspeed_MS4525 : public AP_Airspeed_Backend bool probe(uint8_t bus, uint8_t address); }; + +#endif // AP_AIRSPEED_MS4525_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_MS5525.cpp b/libraries/AP_Airspeed/AP_Airspeed_MS5525.cpp index a23c2a8cddf..811fbbd149d 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_MS5525.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_MS5525.cpp @@ -18,6 +18,8 @@ */ #include "AP_Airspeed_MS5525.h" +#if AP_AIRSPEED_MS5525_ENABLED + #include #include @@ -298,3 +300,5 @@ bool AP_Airspeed_MS5525::get_temperature(float &_temperature) _temperature = temperature; return true; } + +#endif // AP_AIRSPEED_MS5525_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_MS5525.h b/libraries/AP_Airspeed/AP_Airspeed_MS5525.h index 08a2eb0379c..afa7d448c42 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_MS5525.h +++ b/libraries/AP_Airspeed/AP_Airspeed_MS5525.h @@ -18,6 +18,14 @@ backend driver for airspeed from I2C */ +#include + +#ifndef AP_AIRSPEED_MS5525_ENABLED +#define AP_AIRSPEED_MS5525_ENABLED AP_AIRSPEED_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_AIRSPEED_MS5525_ENABLED + #include #include #include @@ -76,3 +84,5 @@ class AP_Airspeed_MS5525 : public AP_Airspeed_Backend AP_HAL::OwnPtr dev; }; + +#endif // AP_AIRSPEED_MS5525_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_MSP.cpp b/libraries/AP_Airspeed/AP_Airspeed_MSP.cpp index 65a4d6ee4c1..cce45fb5641 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_MSP.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_MSP.cpp @@ -1,6 +1,6 @@ #include "AP_Airspeed_MSP.h" -#if HAL_MSP_AIRSPEED_ENABLED +#if AP_AIRSPEED_MSP_ENABLED AP_Airspeed_MSP::AP_Airspeed_MSP(AP_Airspeed &_frontend, uint8_t _instance, uint8_t _msp_instance) : AP_Airspeed_Backend(_frontend, _instance), @@ -66,4 +66,4 @@ void AP_Airspeed_MSP::handle_msp(const MSP::msp_airspeed_data_message_t &pkt) } -#endif // HAL_MSP_AIRSPEED_ENABLED +#endif // AP_AIRSPEED_MSP_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_MSP.h b/libraries/AP_Airspeed/AP_Airspeed_MSP.h index f0bf4d590f3..ac26878ee56 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_MSP.h +++ b/libraries/AP_Airspeed/AP_Airspeed_MSP.h @@ -3,9 +3,17 @@ */ #pragma once -#include "AP_Airspeed_Backend.h" +#include +#include +#include + +#ifndef AP_AIRSPEED_MSP_ENABLED +#define AP_AIRSPEED_MSP_ENABLED HAL_MSP_SENSORS_ENABLED +#endif -#if HAL_MSP_AIRSPEED_ENABLED +#if AP_AIRSPEED_MSP_ENABLED + +#include "AP_Airspeed_Backend.h" class AP_Airspeed_MSP : public AP_Airspeed_Backend { @@ -32,4 +40,4 @@ class AP_Airspeed_MSP : public AP_Airspeed_Backend uint8_t temp_count; }; -#endif // HAL_MSP_AIRSPEED_ENABLED +#endif // AP_AIRSPEED_MSP_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_NMEA.cpp b/libraries/AP_Airspeed/AP_Airspeed_NMEA.cpp index 18698b63a68..cac1c54727a 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_NMEA.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_NMEA.cpp @@ -18,10 +18,13 @@ * https://gpsd.gitlab.io/gpsd/NMEA.html#_mtw_mean_temperature_of_water */ +#include "AP_Airspeed_NMEA.h" + +#if AP_AIRSPEED_NMEA_ENABLED + #include #if APM_BUILD_TYPE(APM_BUILD_Rover) || APM_BUILD_TYPE(APM_BUILD_ArduSub) -#include "AP_Airspeed_NMEA.h" #include "AP_Airspeed.h" #define TIMEOUT_MS 2000 @@ -218,3 +221,5 @@ bool AP_Airspeed_NMEA::decode_latest_term() } #endif // APM_BUILD_TYPE(APM_BUILD_Rover) || APM_BUILD_TYPE(APM_BUILD_ArduSub) + +#endif // AP_AIRSPEED_NMEA_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_NMEA.h b/libraries/AP_Airspeed/AP_Airspeed_NMEA.h index f54f2b2481a..47d5ed7b6fe 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_NMEA.h +++ b/libraries/AP_Airspeed/AP_Airspeed_NMEA.h @@ -1,5 +1,14 @@ #pragma once +#include + +// note additional vehicle restrictions are made in the .cpp file! +#ifndef AP_AIRSPEED_NMEA_ENABLED +#define AP_AIRSPEED_NMEA_ENABLED AP_AIRSPEED_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_AIRSPEED_NMEA_ENABLED + #include "AP_Airspeed_Backend.h" #include #include @@ -65,3 +74,5 @@ class AP_Airspeed_NMEA : public AP_Airspeed_Backend // time last message was received uint32_t _last_update_ms; }; + +#endif // AP_AIRSPEED_NMEA_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp b/libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp index 8a1438dfc2a..616e634c8aa 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp @@ -19,6 +19,9 @@ with thanks to https://github.com/PX4/Firmware/blob/master/src/drivers/sdp3x_airspeed */ #include "AP_Airspeed_SDP3X.h" + +#if AP_AIRSPEED_SDP3X_ENABLED + #include #include @@ -347,3 +350,5 @@ bool AP_Airspeed_SDP3X::_crc(const uint8_t data[], uint8_t size, uint8_t checksu // verify checksum return (crc_value == checksum); } + +#endif // AP_AIRSPEED_SDP3X_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_SDP3X.h b/libraries/AP_Airspeed/AP_Airspeed_SDP3X.h index be761335c75..6669cd1751c 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_SDP3X.h +++ b/libraries/AP_Airspeed/AP_Airspeed_SDP3X.h @@ -14,6 +14,14 @@ */ #pragma once +#include + +#ifndef AP_AIRSPEED_SDP3X_ENABLED +#define AP_AIRSPEED_SDP3X_ENABLED AP_AIRSPEED_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_AIRSPEED_SDP3X_ENABLED + /* backend driver for airspeed from I2C */ @@ -63,3 +71,6 @@ class AP_Airspeed_SDP3X : public AP_Airspeed_Backend AP_HAL::OwnPtr _dev; }; + + +#endif // AP_AIRSPEED_SDP3X_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_SITL.cpp b/libraries/AP_Airspeed/AP_Airspeed_SITL.cpp new file mode 100644 index 00000000000..92ab4357ccf --- /dev/null +++ b/libraries/AP_Airspeed/AP_Airspeed_SITL.cpp @@ -0,0 +1,45 @@ +#include "AP_Airspeed_SITL.h" + +#if AP_AIRSPEED_SITL_ENABLED + +#include +#include + +// return the current differential_pressure in Pascal +bool AP_Airspeed_SITL::get_differential_pressure(float &pressure) +{ + const uint8_t _instance = get_instance(); + + if (_instance >= AIRSPEED_MAX_SENSORS) { + return false; + } + + pressure = AP::sitl()->state.airspeed_raw_pressure[_instance]; + + return true; +} + +// get last temperature +bool AP_Airspeed_SITL::get_temperature(float &temperature) +{ + const uint8_t _instance = get_instance(); + + if (_instance >= AIRSPEED_MAX_SENSORS) { + return false; + } + + const auto *sitl = AP::sitl(); + + // this was mostly swiped from SIM_Airspeed_DLVR: + const float sim_alt = sitl->state.altitude; + + float sigma, delta, theta; + AP_Baro::SimpleAtmosphere(sim_alt * 0.001f, sigma, delta, theta); + + // To Do: Add a sensor board temperature offset parameter + temperature = (KELVIN_TO_C(SSL_AIR_TEMPERATURE * theta)) + 25.0; + + return true; +} + +#endif // AP_AIRSPEED_SITL_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_SITL.h b/libraries/AP_Airspeed/AP_Airspeed_SITL.h new file mode 100644 index 00000000000..64f6da29997 --- /dev/null +++ b/libraries/AP_Airspeed/AP_Airspeed_SITL.h @@ -0,0 +1,36 @@ +/* + SITL airspeed backend - a perfect airspeed sensor + */ +#pragma once + +#include +#include + +#ifndef AP_AIRSPEED_SITL_ENABLED +#define AP_AIRSPEED_SITL_ENABLED AP_SIM_ENABLED +#endif + +#if AP_AIRSPEED_SITL_ENABLED + +#include "AP_Airspeed_Backend.h" + +class AP_Airspeed_SITL : public AP_Airspeed_Backend +{ +public: + + using AP_Airspeed_Backend::AP_Airspeed_Backend; + + bool init(void) override { + return true; + } + + // return the current differential_pressure in Pascal + bool get_differential_pressure(float &pressure) override; + + // temperature not available via analog backend + bool get_temperature(float &temperature) override; + +private: +}; + +#endif // AP_AIRSPEED_SITL_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.cpp b/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.cpp index 9f0300c0358..deea83c2aa5 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.cpp @@ -1,22 +1,26 @@ -#include - -#if HAL_ENABLE_LIBUAVCAN_DRIVERS - #include "AP_Airspeed_UAVCAN.h" +#if AP_AIRSPEED_UAVCAN_ENABLED + #include #include #include - +#if AP_AIRSPEED_HYGROMETER_ENABLE +#include +#endif extern const AP_HAL::HAL& hal; #define LOG_TAG "AirSpeed" -// UAVCAN Frontend Registry Binder +// Frontend Registry Binders UC_REGISTRY_BINDER(AirspeedCb, uavcan::equipment::air_data::RawAirData); -AP_Airspeed_UAVCAN::DetectedModules AP_Airspeed_UAVCAN::_detected_modules[] = {0}; +#if AP_AIRSPEED_HYGROMETER_ENABLE +UC_REGISTRY_BINDER(HygrometerCb, dronecan::sensors::hygrometer::Hygrometer); +#endif + +AP_Airspeed_UAVCAN::DetectedModules AP_Airspeed_UAVCAN::_detected_modules[]; HAL_Semaphore AP_Airspeed_UAVCAN::_sem_registry; // constructor @@ -37,11 +41,20 @@ void AP_Airspeed_UAVCAN::subscribe_msgs(AP_UAVCAN* ap_uavcan) const int airspeed_listener_res = airspeed_listener->start(AirspeedCb(ap_uavcan, &handle_airspeed)); if (airspeed_listener_res < 0) { - AP_HAL::panic("UAVCAN Airspeed subscriber start problem\n"); + AP_HAL::panic("DroneCAN Airspeed subscriber error \n"); + } + +#if AP_AIRSPEED_HYGROMETER_ENABLE + uavcan::Subscriber *hygrometer_listener; + hygrometer_listener = new uavcan::Subscriber(*node); + const int hygrometer_listener_res = hygrometer_listener->start(HygrometerCb(ap_uavcan, &handle_hygrometer)); + if (hygrometer_listener_res < 0) { + AP_HAL::panic("DroneCAN Hygrometer subscriber error\n"); } +#endif } -AP_Airspeed_Backend* AP_Airspeed_UAVCAN::probe(AP_Airspeed &_frontend, uint8_t _instance) +AP_Airspeed_Backend* AP_Airspeed_UAVCAN::probe(AP_Airspeed &_frontend, uint8_t _instance, uint32_t previous_devid) { WITH_SEMAPHORE(_sem_registry); @@ -49,23 +62,28 @@ AP_Airspeed_Backend* AP_Airspeed_UAVCAN::probe(AP_Airspeed &_frontend, uint8_t _ for (uint8_t i = 0; i < AIRSPEED_MAX_SENSORS; i++) { if (_detected_modules[i].driver == nullptr && _detected_modules[i].ap_uavcan != nullptr) { + const auto bus_id = AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_UAVCAN, + _detected_modules[i].ap_uavcan->get_driver_index(), + _detected_modules[i].node_id, 0); + if (previous_devid != 0 && previous_devid != bus_id) { + // match with previous ID only + continue; + } backend = new AP_Airspeed_UAVCAN(_frontend, _instance); if (backend == nullptr) { - AP::can().log_text(AP_CANManager::LOG_INFO, - LOG_TAG, - "Failed register UAVCAN Airspeed Node %d on Bus %d\n", - _detected_modules[i].node_id, - _detected_modules[i].ap_uavcan->get_driver_index()); + AP::can().log_text(AP_CANManager::LOG_INFO, + LOG_TAG, + "Failed register UAVCAN Airspeed Node %d on Bus %d\n", + _detected_modules[i].node_id, + _detected_modules[i].ap_uavcan->get_driver_index()); } else { _detected_modules[i].driver = backend; - AP::can().log_text(AP_CANManager::LOG_INFO, - LOG_TAG, - "Registered UAVCAN Airspeed Node %d on Bus %d\n", - _detected_modules[i].node_id, - _detected_modules[i].ap_uavcan->get_driver_index()); - backend->set_bus_id(AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_UAVCAN, - _detected_modules[i].ap_uavcan->get_driver_index(), - _detected_modules[i].node_id, 0)); + AP::can().log_text(AP_CANManager::LOG_INFO, + LOG_TAG, + "Registered UAVCAN Airspeed Node %d on Bus %d\n", + _detected_modules[i].node_id, + _detected_modules[i].ap_uavcan->get_driver_index()); + backend->set_bus_id(bus_id); } break; } @@ -128,6 +146,22 @@ void AP_Airspeed_UAVCAN::handle_airspeed(AP_UAVCAN* ap_uavcan, uint8_t node_id, } } +#if AP_AIRSPEED_HYGROMETER_ENABLE +void AP_Airspeed_UAVCAN::handle_hygrometer(AP_UAVCAN* ap_uavcan, uint8_t node_id, const HygrometerCb &cb) +{ + WITH_SEMAPHORE(_sem_registry); + + AP_Airspeed_UAVCAN* driver = get_uavcan_backend(ap_uavcan, node_id); + + if (driver != nullptr) { + WITH_SEMAPHORE(driver->_sem_airspeed); + driver->_hygrometer.temperature = KELVIN_TO_C(cb.msg->temperature); + driver->_hygrometer.humidity = cb.msg->humidity; + driver->_hygrometer.last_sample_ms = AP_HAL::millis(); + } +} +#endif // AP_AIRSPEED_HYGROMETER_ENABLE + bool AP_Airspeed_UAVCAN::init() { // always returns true @@ -163,4 +197,21 @@ bool AP_Airspeed_UAVCAN::get_temperature(float &temperature) return true; } -#endif // HAL_ENABLE_LIBUAVCAN_DRIVERS +#if AP_AIRSPEED_HYGROMETER_ENABLE +/* + return hygrometer data if available + */ +bool AP_Airspeed_UAVCAN::get_hygrometer(uint32_t &last_sample_ms, float &temperature, float &humidity) +{ + if (_hygrometer.last_sample_ms == 0) { + return false; + } + WITH_SEMAPHORE(_sem_airspeed); + last_sample_ms = _hygrometer.last_sample_ms; + temperature = _hygrometer.temperature; + humidity = _hygrometer.humidity; + return true; +} +#endif // AP_AIRSPEED_HYGROMETER_ENABLE + +#endif // AP_AIRSPEED_UAVCAN_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.h b/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.h index 828a3b2fc87..ae67d77c61c 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.h +++ b/libraries/AP_Airspeed/AP_Airspeed_UAVCAN.h @@ -1,10 +1,19 @@ #pragma once +#include + +#ifndef AP_AIRSPEED_UAVCAN_ENABLED +#define AP_AIRSPEED_UAVCAN_ENABLED HAL_ENABLE_LIBUAVCAN_DRIVERS +#endif + +#if AP_AIRSPEED_UAVCAN_ENABLED + #include "AP_Airspeed_Backend.h" #include class AirspeedCb; +class HygrometerCb; class AP_Airspeed_UAVCAN : public AP_Airspeed_Backend { public: @@ -18,13 +27,19 @@ class AP_Airspeed_UAVCAN : public AP_Airspeed_Backend { // temperature not available via analog backend bool get_temperature(float &temperature) override; +#if AP_AIRSPEED_HYGROMETER_ENABLE + // get hygrometer data + bool get_hygrometer(uint32_t &last_sample_ms, float &temperature, float &humidity) override; +#endif + static void subscribe_msgs(AP_UAVCAN* ap_uavcan); - static AP_Airspeed_Backend* probe(AP_Airspeed &_fronted, uint8_t _instance); + static AP_Airspeed_Backend* probe(AP_Airspeed &_fronted, uint8_t _instance, uint32_t previous_devid); private: static void handle_airspeed(AP_UAVCAN* ap_uavcan, uint8_t node_id, const AirspeedCb &cb); + static void handle_hygrometer(AP_UAVCAN* ap_uavcan, uint8_t node_id, const HygrometerCb &cb); static AP_Airspeed_UAVCAN* get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t node_id); @@ -32,6 +47,13 @@ class AP_Airspeed_UAVCAN : public AP_Airspeed_Backend { float _temperature; // Celcius uint32_t _last_sample_time_ms; + // hygrometer data + struct { + float temperature; + float humidity; + uint32_t last_sample_ms; + } _hygrometer; + HAL_Semaphore _sem_airspeed; // Module Detection Registry @@ -44,3 +66,6 @@ class AP_Airspeed_UAVCAN : public AP_Airspeed_Backend { static HAL_Semaphore _sem_registry; bool _have_temperature; }; + + +#endif // AP_AIRSPEED_UAVCAN_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_analog.cpp b/libraries/AP_Airspeed/AP_Airspeed_analog.cpp index cb77817eb81..ffd29087d67 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_analog.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_analog.cpp @@ -16,11 +16,14 @@ * analog airspeed driver */ +#include "AP_Airspeed_analog.h" + +#if AP_AIRSPEED_ANALOG_ENABLED + #include #include #include "AP_Airspeed.h" -#include "AP_Airspeed_analog.h" extern const AP_HAL::HAL &hal; @@ -48,3 +51,5 @@ bool AP_Airspeed_Analog::get_differential_pressure(float &pressure) pressure = _source->voltage_average_ratiometric() * VOLTS_TO_PASCAL / get_psi_range(); return true; } + +#endif // AP_AIRSPEED_ANALOG_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_analog.h b/libraries/AP_Airspeed/AP_Airspeed_analog.h index 1131a12ec04..3ee890db481 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_analog.h +++ b/libraries/AP_Airspeed/AP_Airspeed_analog.h @@ -1,5 +1,13 @@ #pragma once +#include + +#ifndef AP_AIRSPEED_ANALOG_ENABLED +#define AP_AIRSPEED_ANALOG_ENABLED AP_AIRSPEED_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_AIRSPEED_ANALOG_ENABLED + #include #include @@ -22,3 +30,5 @@ class AP_Airspeed_Analog : public AP_Airspeed_Backend private: AP_HAL::AnalogSource *_source; }; + +#endif // AP_AIRSPEED_ANALOG_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_config.h b/libraries/AP_Airspeed/AP_Airspeed_config.h new file mode 100644 index 00000000000..3df9e793289 --- /dev/null +++ b/libraries/AP_Airspeed/AP_Airspeed_config.h @@ -0,0 +1,25 @@ +#pragma once + +#include +#include +#include + +#ifndef AP_AIRSPEED_ENABLED +#define AP_AIRSPEED_ENABLED 1 +#endif + +#ifndef AP_AIRSPEED_MSP_ENABLED +#define AP_AIRSPEED_MSP_ENABLED (AP_AIRSPEED_ENABLED && HAL_MSP_SENSORS_ENABLED) +#endif + +#ifndef AIRSPEED_MAX_SENSORS +#define AIRSPEED_MAX_SENSORS 2 +#endif + +#ifndef AP_AIRSPEED_AUTOCAL_ENABLE +#define AP_AIRSPEED_AUTOCAL_ENABLE AP_AIRSPEED_ENABLED +#endif + +#ifndef AP_AIRSPEED_HYGROMETER_ENABLE +#define AP_AIRSPEED_HYGROMETER_ENABLE (AP_AIRSPEED_ENABLED && BOARD_FLASH_SIZE > 1024) +#endif diff --git a/libraries/AP_Airspeed/Airspeed_Calibration.cpp b/libraries/AP_Airspeed/Airspeed_Calibration.cpp index c2221e94e0d..b6571ea0c22 100644 --- a/libraries/AP_Airspeed/Airspeed_Calibration.cpp +++ b/libraries/AP_Airspeed/Airspeed_Calibration.cpp @@ -84,7 +84,7 @@ float Airspeed_Calibration::update(float airspeed, const Vector3f &vg, int16_t m state += KG*(TAS_mea - TAS_pred); // [3 x 1] + [3 x 1] * [1 x 1] // Update the covariance matrix - Vector3f HP2 = H_TAS * P; + Vector3f HP2 = H_TAS.row_times_mat(P); P -= KG.mul_rowcol(HP2); // force symmetry on the covariance matrix - necessary due to rounding @@ -128,7 +128,7 @@ void AP_Airspeed::update_calibration(uint8_t i, const Vector3f &vground, int16_t state[i].calibration.state.z = 1.0f / sqrtf(ratio); // calculate true airspeed, assuming a airspeed ratio of 1.0 - float dpress = MAX(get_differential_pressure(), 0); + float dpress = MAX(get_differential_pressure(i), 0); float true_airspeed = sqrtf(dpress) * AP::baro().get_EAS2TAS(); float zratio = state[i].calibration.update(true_airspeed, vground, max_airspeed_allowed_during_cal); diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index 1646180b53c..1788d01c321 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -17,6 +17,7 @@ #include #include #include +#include #include #include #include @@ -25,6 +26,7 @@ #include #include #include +#include #include #include #include @@ -41,8 +43,13 @@ #include #include #include +#include #include #include +#include +#include +#include +#include #if HAL_MAX_CAN_PROTOCOL_DRIVERS #include @@ -73,6 +80,10 @@ #define ARMING_RUDDER_DEFAULT (uint8_t)RudderArming::ARMDISARM #endif +#ifndef PREARM_DISPLAY_PERIOD +# define PREARM_DISPLAY_PERIOD 30 +#endif + extern const AP_HAL::HAL& hal; const AP_Param::GroupInfo AP_Arming::var_info[] = { @@ -82,7 +93,7 @@ const AP_Param::GroupInfo AP_Arming::var_info[] = { // @Description: Arming disabled until some requirements are met. If 0, there are no requirements (arm immediately). If 1, require rudder stick or GCS arming before arming motors and sends the minimum throttle PWM value to the throttle channel when disarmed. If 2, require rudder stick or GCS arming and send 0 PWM to throttle channel when disarmed. See the ARMING_CHECK_* parameters to see what checks are done before arming. Note, if setting this parameter to 0 a reboot is required to arm the plane. Also note, even with this parameter at 0, if ARMING_CHECK parameter is not also zero the plane may fail to arm throttle at boot due to a pre-arm check failure. // @Values: 0:Disabled,1:THR_MIN PWM when disarmed,2:0 PWM when disarmed // @User: Advanced - AP_GROUPINFO_FLAGS_FRAME("REQUIRE", 0, AP_Arming, require, 1, + AP_GROUPINFO_FLAGS_FRAME("REQUIRE", 0, AP_Arming, require, float(Required::YES_MIN_PWM), AP_PARAM_FLAG_NO_SHIFT, AP_PARAM_FRAME_PLANE | AP_PARAM_FRAME_ROVER), @@ -126,6 +137,13 @@ const AP_Param::GroupInfo AP_Arming::var_info[] = { // @User: Standard AP_GROUPINFO("CHECK", 8, AP_Arming, checks_to_perform, ARMING_CHECK_ALL), + // @Param: OPTIONS + // @DisplayName: Arming options + // @Description: Options that can be applied to change arming behaviour + // @Values: 0:None,1:Disable prearm display + // @User: Advanced + AP_GROUPINFO("OPTIONS", 9, AP_Arming, _arming_options, 0), + AP_GROUPEND }; @@ -144,6 +162,24 @@ AP_Arming::AP_Arming() AP_Param::setup_object_defaults(this, var_info); } +// performs pre-arm checks. expects to be called at 1hz. +void AP_Arming::update(void) +{ + const uint32_t now_ms = AP_HAL::millis(); + // perform pre-arm checks & display failures every 30 seconds + bool display_fail = false; + if (now_ms - last_prearm_display_ms > PREARM_DISPLAY_PERIOD*1000) { + display_fail = true; + last_prearm_display_ms = now_ms; + } + // OTOH, the user may never want to display them: + if (option_enabled(Option::DISABLE_PREARM_DISPLAY)) { + display_fail = false; + } + + pre_arm_checks(display_fail); +} + uint16_t AP_Arming::compass_magfield_expected() const { return AP_ARMING_COMPASS_MAGFIELD_EXPECTED; @@ -151,7 +187,7 @@ uint16_t AP_Arming::compass_magfield_expected() const bool AP_Arming::is_armed() { - return (Required)require.get() == Required::NO || armed; + return armed || arming_required() == Required::NO; } uint32_t AP_Arming::get_enabled_checks() const @@ -167,22 +203,27 @@ bool AP_Arming::check_enabled(const enum AP_Arming::ArmingChecks check) const return (checks_to_perform & check); } -MAV_SEVERITY AP_Arming::check_severity(const enum AP_Arming::ArmingChecks check) const -{ - if (check_enabled(check)) { - return MAV_SEVERITY_CRITICAL; - } - return MAV_SEVERITY_DEBUG; // technically should be NOTICE, but will annoy users at that level -} - void AP_Arming::check_failed(const enum AP_Arming::ArmingChecks check, bool report, const char *fmt, ...) const { if (!report) { return; } char taggedfmt[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1]; - hal.util->snprintf(taggedfmt, sizeof(taggedfmt), "PreArm: %s", fmt); - MAV_SEVERITY severity = check_severity(check); + + // metafmt is wrapped around the passed-in format string to + // prepend "PreArm" or "Arm", depending on what sorts of checks + // we're currently doing. + const char *metafmt = "PreArm: %s"; // it's formats all the way down + if (running_arming_checks) { + metafmt = "Arm: %s"; + } + hal.util->snprintf(taggedfmt, sizeof(taggedfmt), metafmt, fmt); + + MAV_SEVERITY severity = MAV_SEVERITY_CRITICAL; + if (!check_enabled(check)) { + // technically should be NOTICE, but will annoy users at that level: + severity = MAV_SEVERITY_DEBUG; + } va_list arg_list; va_start(arg_list, fmt); gcs().send_textv(severity, taggedfmt, arg_list); @@ -195,7 +236,16 @@ void AP_Arming::check_failed(bool report, const char *fmt, ...) const return; } char taggedfmt[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1]; - hal.util->snprintf(taggedfmt, sizeof(taggedfmt), "PreArm: %s", fmt); + + // metafmt is wrapped around the passed-in format string to + // prepend "PreArm" or "Arm", depending on what sorts of checks + // we're currently doing. + const char *metafmt = "PreArm: %s"; // it's formats all the way down + if (running_arming_checks) { + metafmt = "Arm: %s"; + } + hal.util->snprintf(taggedfmt, sizeof(taggedfmt), metafmt, fmt); + va_list arg_list; va_start(arg_list, fmt); gcs().send_textv(MAV_SEVERITY_CRITICAL, taggedfmt, arg_list); @@ -215,8 +265,9 @@ bool AP_Arming::barometer_checks(bool report) #endif if ((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_BARO)) { - if (!AP::baro().all_healthy()) { - check_failed(ARMING_CHECK_BARO, report, "Barometer not healthy"); + char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {}; + if (!AP::baro().arming_checks(sizeof(buffer), buffer)) { + check_failed(ARMING_CHECK_BARO, report, "Baro: %s", buffer); return false; } } @@ -300,14 +351,22 @@ bool AP_Arming::ins_accels_consistent(const AP_InertialSensor &ins) // EKF is less sensitive to Z-axis error vec_diff.z *= 0.5f; - if (vec_diff.length() <= threshold) { - last_accel_pass_ms[i] = now; - } - if (now - last_accel_pass_ms[i] > 10000) { + if (vec_diff.length() > threshold) { + // this sensor disagrees with the primary sensor, so + // accels are inconsistent: return false; } } + // we didn't return false in the loop above, so sensors are + // consistent right now: + last_accel_pass_ms = now; + + // must pass for at least 10 seconds before we're considered consistent: + if (now - last_accel_pass_ms > 10000) { + return false; + } + return true; } @@ -327,16 +386,23 @@ bool AP_Arming::ins_gyros_consistent(const AP_InertialSensor &ins) // get next gyro vector const Vector3f &gyro_vec = ins.get_gyro(i); const Vector3f vec_diff = gyro_vec - prime_gyro_vec; - // allow for up to 5 degrees/s difference. Pass if it has - // been OK in last 10 seconds - if (vec_diff.length() <= radians(5)) { - last_gyro_pass_ms[i] = now; - } - if (now - last_gyro_pass_ms[i] > 10000) { + // allow for up to 5 degrees/s difference + if (vec_diff.length() > radians(5)) { + // this sensor disagrees with the primary sensor, so + // gyros are inconsistent: return false; } } + // we didn't return false in the loop above, so sensors are + // consistent right now: + last_gyro_pass_ms = now; + + // must pass for at least 10 seconds before we're considered consistent: + if (now - last_gyro_pass_ms > 10000) { + return false; + } + return true; } @@ -385,13 +451,6 @@ bool AP_Arming::ins_checks(bool report) check_failed(ARMING_CHECK_INS, report, "temperature cal running"); return false; } - - // check AHRS attitudes are consistent - char failure_msg[50] = {}; - if (!AP::ahrs().attitudes_consistent(failure_msg, ARRAY_SIZE(failure_msg))) { - check_failed(ARMING_CHECK_INS, report, "%s", failure_msg); - return false; - } } #if HAL_GYROFFT_ENABLED @@ -486,12 +545,12 @@ bool AP_Arming::gps_checks(bool report) if ((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_GPS)) { // Any failure messages from GPS backends - char failure_msg[50] = {}; - if (!AP::gps().backends_healthy(failure_msg, ARRAY_SIZE(failure_msg))) { - if (failure_msg[0] != '\0') { - check_failed(ARMING_CHECK_GPS, report, "%s", failure_msg); - } - return false; + char failure_msg[50] = {}; + if (!AP::gps().backends_healthy(failure_msg, ARRAY_SIZE(failure_msg))) { + if (failure_msg[0] != '\0') { + check_failed(ARMING_CHECK_GPS, report, "%s", failure_msg); + } + return false; } for (uint8_t i = 0; i < gps.num_sensors(); i++) { @@ -522,7 +581,7 @@ bool AP_Arming::gps_checks(bool report) } if (!AP::ahrs().home_is_set()) { - check_failed(ARMING_CHECK_GPS, report, "GPS: waiting for home"); + check_failed(ARMING_CHECK_GPS, report, "AHRS: waiting for home"); return false; } @@ -539,13 +598,15 @@ bool AP_Arming::gps_checks(bool report) } // check AHRS and GPS are within 10m of each other - const Location gps_loc = gps.location(); - Location ahrs_loc; - if (AP::ahrs().get_location(ahrs_loc)) { - const float distance = gps_loc.get_distance(ahrs_loc); - if (distance > AP_ARMING_AHRS_GPS_ERROR_MAX) { - check_failed(ARMING_CHECK_GPS, report, "GPS and AHRS differ by %4.1fm", (double)distance); - return false; + if (gps.num_sensors() > 0) { + const Location gps_loc = gps.location(); + Location ahrs_loc; + if (AP::ahrs().get_location(ahrs_loc)) { + const float distance = gps_loc.get_distance(ahrs_loc); + if (distance > AP_ARMING_AHRS_GPS_ERROR_MAX) { + check_failed(ARMING_CHECK_GPS, report, "GPS and AHRS differ by %4.1fm", (double)distance); + return false; + } } } } @@ -796,7 +857,7 @@ bool AP_Arming::servo_checks(bool report) const bool check_passed = true; for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) { const SRV_Channel *c = SRV_Channels::srv_channel(i); - if (c == nullptr || c->get_function() == SRV_Channel::k_none) { + if (c == nullptr || c->get_function() <= SRV_Channel::k_none) { continue; } @@ -809,10 +870,27 @@ bool AP_Arming::servo_checks(bool report) const check_failed(report, "SERVO%d_MAX is less than SERVO%d_TRIM", i + 1, i + 1); check_passed = false; } + + // check functions using PWM are enabled + if (SRV_Channels::get_disabled_channel_mask() & 1U<get_function(); + + // motors, e-stoppable functions, neopixels and ProfiLEDs may be digital outputs and thus can be disabled + const bool disabled_ok = SRV_Channel::is_motor(ch_function) || + SRV_Channel::should_e_stop(ch_function) || + (ch_function >= SRV_Channel::k_LED_neopixel1 && ch_function <= SRV_Channel::k_LED_neopixel4) || + (ch_function >= SRV_Channel::k_ProfiLED_1 && ch_function <= SRV_Channel::k_ProfiLED_Clock); + + // for all other functions raise a pre-arm failure + if (!disabled_ok) { + check_failed(report, "SERVO%u_FUNCTION=%u on disabled channel", i + 1, (unsigned)ch_function); + check_passed = false; + } + } } #if HAL_WITH_IO_MCU - if (!iomcu.healthy()) { + if (!iomcu.healthy() && AP_BoardConfig::io_enabled()) { check_failed(report, "IOMCU is unhealthy"); check_passed = false; } @@ -877,6 +955,8 @@ bool AP_Arming::heater_min_temperature_checks(bool report) */ bool AP_Arming::system_checks(bool report) { + char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {}; + if (check_enabled(ARMING_CHECK_SYSTEM)) { if (!hal.storage->healthy()) { check_failed(ARMING_CHECK_SYSTEM, report, "Param storage failed"); @@ -891,8 +971,8 @@ bool AP_Arming::system_checks(bool report) #endif #if AP_SCRIPTING_ENABLED const AP_Scripting *scripting = AP_Scripting::get_singleton(); - if ((scripting != nullptr) && scripting->enabled() && scripting->init_failed()) { - check_failed(ARMING_CHECK_SYSTEM, report, "Scripting out of memory"); + if ((scripting != nullptr) && !scripting->arming_checks(sizeof(buffer), buffer)) { + check_failed(ARMING_CHECK_SYSTEM, report, "%s", buffer); return false; } #endif @@ -905,15 +985,13 @@ bool AP_Arming::system_checks(bool report) #endif } if (AP::internalerror().errors() != 0) { - uint8_t buffer[32]; - AP::internalerror().errors_as_string(buffer, ARRAY_SIZE(buffer)); + AP::internalerror().errors_as_string((uint8_t*)buffer, ARRAY_SIZE(buffer)); check_failed(report, "Internal errors 0x%x l:%u %s", (unsigned int)AP::internalerror().errors(), AP::internalerror().last_error_line(), buffer); return false; } if (check_enabled(ARMING_CHECK_PARAMETERS)) { auto *rpm = AP::rpm(); - char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {}; if (rpm && !rpm->arming_checks(sizeof(buffer), buffer)) { check_failed(ARMING_CHECK_PARAMETERS, report, "%s", buffer); return false; @@ -942,6 +1020,58 @@ bool AP_Arming::system_checks(bool report) return true; } +bool AP_Arming::terrain_database_required() const +{ + AP_Mission *mission = AP::mission(); + if (mission == nullptr) { + // no mission support? + return false; + } + if (mission->contains_terrain_alt_items()) { + return true; + } + return false; +} + +// check terrain database is fit-for-purpose +bool AP_Arming::terrain_checks(bool report) const +{ + if (!check_enabled(ARMING_CHECK_PARAMETERS)) { + return true; + } + + if (!terrain_database_required()) { + return true; + } + +#if AP_TERRAIN_AVAILABLE + + const AP_Terrain *terrain = AP_Terrain::get_singleton(); + if (terrain == nullptr) { + // this is also a system error, and it is already complaining + // about it. + return false; + } + + if (!terrain->enabled()) { + check_failed(ARMING_CHECK_PARAMETERS, report, "terrain disabled"); + return false; + } + + char fail_msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1]; + if (!terrain->pre_arm_checks(fail_msg, sizeof(fail_msg))) { + check_failed(ARMING_CHECK_PARAMETERS, report, "%s", fail_msg); + return false; + } + + return true; + +#else + check_failed(ARMING_CHECK_PARAMETERS, report, "terrain required but disabled"); + return false; +#endif +} + // check nothing is too close to vehicle bool AP_Arming::proximity_checks(bool report) const @@ -952,15 +1082,12 @@ bool AP_Arming::proximity_checks(bool report) const if (proximity == nullptr) { return true; } - if (proximity->get_status() == AP_Proximity::Status::NotConnected) { - return true; - } - - // return false if proximity sensor unhealthy - if (proximity->get_status() < AP_Proximity::Status::Good) { - check_failed(report, "check proximity sensor"); + char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1]; + if (!proximity->prearm_healthy(buffer, ARRAY_SIZE(buffer))) { + check_failed(report, "%s", buffer); return false; } + return true; #endif return true; @@ -1005,20 +1132,14 @@ bool AP_Arming::can_checks(bool report) case AP_CANManager::Driver_Type_UAVCAN: { #if HAL_ENABLE_LIBUAVCAN_DRIVERS - if (!AP::uavcan_dna_server().prearm_check(fail_msg, ARRAY_SIZE(fail_msg))) { + AP_UAVCAN *ap_uavcan = AP_UAVCAN::get_uavcan(i); + if (ap_uavcan != nullptr && !ap_uavcan->prearm_check(fail_msg, ARRAY_SIZE(fail_msg))) { check_failed(ARMING_CHECK_SYSTEM, report, "UAVCAN: %s", fail_msg); return false; } #endif break; } - case AP_CANManager::Driver_Type_ToshibaCAN: - { - // toshibacan doesn't currently have any prearm - // checks. Theres scope for adding a "not - // initialised" prearm check. - break; - } case AP_CANManager::Driver_Type_CANTester: { check_failed(ARMING_CHECK_SYSTEM, report, "TestCAN: No Arming with TestCAN enabled"); @@ -1028,6 +1149,7 @@ bool AP_Arming::can_checks(bool report) case AP_CANManager::Driver_Type_USD1: case AP_CANManager::Driver_Type_None: case AP_CANManager::Driver_Type_Scripting: + case AP_CANManager::Driver_Type_Scripting2: case AP_CANManager::Driver_Type_Benewake: break; } @@ -1040,6 +1162,7 @@ bool AP_Arming::can_checks(bool report) bool AP_Arming::fence_checks(bool display_failure) { +#if AP_FENCE_ENABLED const AC_Fence *fence = AP::fence(); if (fence == nullptr) { return true; @@ -1058,6 +1181,9 @@ bool AP_Arming::fence_checks(bool display_failure) } return false; +#else + return true; +#endif } bool AP_Arming::camera_checks(bool display_failure) @@ -1100,6 +1226,24 @@ bool AP_Arming::osd_checks(bool display_failure) const return true; } +bool AP_Arming::mount_checks(bool display_failure) const +{ +#if HAL_MOUNT_ENABLED + if ((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_CAMERA)) { + AP_Mount *mount = AP::mount(); + if (mount == nullptr) { + return true; + } + char fail_msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] = {}; + if (!mount->pre_arm_checks(fail_msg, sizeof(fail_msg))) { + check_failed(ARMING_CHECK_CAMERA, display_failure, "Mount: %s", fail_msg); + return false; + } + } +#endif + return true; +} + bool AP_Arming::fettec_checks(bool display_failure) const { #if AP_FETTEC_ONEWIRE_ENABLED @@ -1251,10 +1395,35 @@ bool AP_Arming::generator_checks(bool display_failure) const return true; } +// OpenDroneID Checks +bool AP_Arming::opendroneid_checks(bool display_failure) +{ +#if AP_OPENDRONEID_ENABLED + auto &opendroneid = AP::opendroneid(); + + char failure_msg[50] {}; + if (!opendroneid.pre_arm_check(failure_msg, sizeof(failure_msg))) { + check_failed(display_failure, "OpenDroneID: %s", failure_msg); + return false; + } +#endif + return true; +} + +//Check for multiple RC in serial protocols +bool AP_Arming::serial_protocol_checks(bool display_failure) +{ + if (AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_RCIN, 1)) { + check_failed(display_failure, "Multiple SERIAL ports configured for RC input"); + return false; + } + return true; +} + bool AP_Arming::pre_arm_checks(bool report) { #if !APM_BUILD_COPTER_OR_HELI - if (armed || require == (uint8_t)Required::NO) { + if (armed || arming_required() == Required::NO) { // if we are already armed or don't need any arming checks // then skip the checks return true; @@ -1277,16 +1446,20 @@ bool AP_Arming::pre_arm_checks(bool report) & servo_checks(report) & board_voltage_checks(report) & system_checks(report) + & terrain_checks(report) & can_checks(report) & generator_checks(report) & proximity_checks(report) & camera_checks(report) & osd_checks(report) + & mount_checks(report) & fettec_checks(report) & visodom_checks(report) & aux_auth_checks(report) & disarm_switch_checks(report) - & fence_checks(report); + & fence_checks(report) + & opendroneid_checks(report) + & serial_protocol_checks(report); } bool AP_Arming::arm_checks(AP_Arming::Method method) @@ -1298,13 +1471,6 @@ bool AP_Arming::arm_checks(AP_Arming::Method method) } } -#if HAL_GYROFFT_ENABLED - // make sure the FFT subsystem is enabled if arming checks have been disabled - AP_GyroFFT *fft = AP::fft(); - if (fft != nullptr) { - fft->prepare_for_arming(); - } -#endif // ensure the GPS drivers are ready on any final changes if ((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_GPS_CONFIG)) { @@ -1313,14 +1479,6 @@ bool AP_Arming::arm_checks(AP_Arming::Method method) } } - AC_Fence *fence = AP::fence(); - if (fence != nullptr) { - // If a fence is set to auto-enable, turn on the fence - if(fence->auto_enabled() == AC_Fence::AutoEnable::ONLY_WHEN_ARMED) { - fence->enable(true); - } - } - // note that this will prepare AP_Logger to start logging // so should be the last check to be done before arming @@ -1344,7 +1502,13 @@ bool AP_Arming::arm_checks(AP_Arming::Method method) bool AP_Arming::mandatory_checks(bool report) { - return rc_in_calibration_check(report); + bool ret = true; +#if AP_OPENDRONEID_ENABLED + ret &= opendroneid_checks(report); +#endif + ret &= rc_in_calibration_check(report); + ret &= serial_protocol_checks(report); + return ret; } //returns true if arming occurred successfully @@ -1354,6 +1518,8 @@ bool AP_Arming::arm(AP_Arming::Method method, const bool do_arming_checks) return false; } + running_arming_checks = true; // so we show Arm: rather than Disarm: in messages + if ((!do_arming_checks && mandatory_checks(true)) || (pre_arm_checks(true) && arm_checks(method))) { armed = true; @@ -1364,6 +1530,44 @@ bool AP_Arming::arm(AP_Arming::Method method, const bool do_arming_checks) armed = false; } + running_arming_checks = false; + + if (armed && do_arming_checks && checks_to_perform == 0) { + gcs().send_text(MAV_SEVERITY_WARNING, "Warning: Arming Checks Disabled"); + } + +#if HAL_GYROFFT_ENABLED + // make sure the FFT subsystem is enabled if arming checks have been disabled + AP_GyroFFT *fft = AP::fft(); + if (fft != nullptr) { + fft->prepare_for_arming(); + } +#endif + +#if AP_TERRAIN_AVAILABLE + if (armed) { + // tell terrain we have just armed, so it can setup + // a reference location for terrain adjustment + auto *terrain = AP::terrain(); + if (terrain != nullptr) { + terrain->set_reference_location(); + } + } +#endif + +#if AP_FENCE_ENABLED + if (armed) { + auto *fence = AP::fence(); + if (fence != nullptr) { + // If a fence is set to auto-enable, turn on the fence + if (fence->auto_enabled() == AC_Fence::AutoEnable::ONLY_WHEN_ARMED) { + fence->enable(true); + gcs().send_text(MAV_SEVERITY_INFO, "Fence: auto-enabled"); + } + } + } +#endif + return armed; } @@ -1395,19 +1599,29 @@ bool AP_Arming::disarm(const AP_Arming::Method method, bool do_disarm_checks) } #endif +#if AP_FENCE_ENABLED AC_Fence *fence = AP::fence(); if (fence != nullptr) { if(fence->auto_enabled() == AC_Fence::AutoEnable::ONLY_WHEN_ARMED) { fence->enable(false); } } +#endif return true; } AP_Arming::Required AP_Arming::arming_required() { - return (AP_Arming::Required)require.get(); +#if AP_OPENDRONEID_ENABLED + // cannot be disabled if OpenDroneID is present + if (AP::opendroneid().enabled()) { + if (require != Required::YES_MIN_PWM && require != Required::YES_ZERO_PWM) { + return Required::YES_MIN_PWM; + } + } +#endif + return require; } // Copter and sub share the same RC input limits @@ -1482,8 +1696,7 @@ bool AP_Arming::disarm_switch_checks(bool display_failure) const { const RC_Channel *chan = rc().find_channel_for_option(RC_Channel::AUX_FUNC::DISARM); if (chan != nullptr && - chan->get_aux_switch_pos() == RC_Channel::AuxSwitchPos::HIGH && - (checks_to_perform & ARMING_CHECK_ALL)) { + chan->get_aux_switch_pos() == RC_Channel::AuxSwitchPos::HIGH) { check_failed(display_failure, "Disarm Switch on"); return false; } @@ -1542,7 +1755,8 @@ void AP_Arming::check_forced_logging(const AP_Arming::Method method) case Method::GCS_FAILSAFE_SURFACEFAILED: case Method::GCS_FAILSAFE_HOLDFAILED: case Method::PILOT_INPUT_FAILSAFE: - // keep logging for longger if disarmed for a bad reason + case Method::DEADRECKON_FAILSAFE: + // keep logging for longer if disarmed for a bad reason AP::logger().set_long_log_persist(true); return; diff --git a/libraries/AP_Arming/AP_Arming.h b/libraries/AP_Arming/AP_Arming.h index 17ec0aed866..19af52eef38 100644 --- a/libraries/AP_Arming/AP_Arming.h +++ b/libraries/AP_Arming/AP_Arming.h @@ -1,21 +1,21 @@ #pragma once -#include +#include +#include #include -#include -#include +#include class AP_Arming { public: AP_Arming(); - /* Do not allow copies */ - AP_Arming(const AP_Arming &other) = delete; - AP_Arming &operator=(const AP_Arming&) = delete; + CLASS_NO_COPY(AP_Arming); /* Do not allow copies */ static AP_Arming *get_singleton(); + void update(); + enum ArmingChecks { ARMING_CHECK_ALL = (1U << 0), ARMING_CHECK_BARO = (1U << 1), @@ -73,6 +73,7 @@ class AP_Arming { TOYMODELANDTHROTTLE = 30, // only disarm uses this... TOYMODELANDFORCE = 31, // only disarm uses this... LANDING = 32, // only disarm uses this... + DEADRECKON_FAILSAFE = 33, // only disarm uses this... UNKNOWN = 100, }; @@ -122,21 +123,30 @@ class AP_Arming { // method that was last used for disarm; invalid unless the // vehicle has been disarmed at least once. - Method last_disarm_method() const { return _last_disarm_method; } + Method last_disarm_method() const { return _last_disarm_method; } + + // enum for ARMING_OPTIONS parameter + enum class Option : int32_t { + DISABLE_PREARM_DISPLAY = (1U << 0), + }; + bool option_enabled(Option option) const { + return (_arming_options & uint32_t(option)) != 0; + } protected: // Parameters - AP_Int8 require; + AP_Enum require; AP_Int32 checks_to_perform; // bitmask for which checks are required AP_Float accel_error_threshold; AP_Int8 _rudder_arming; - AP_Int32 _required_mission_items; + AP_Int32 _required_mission_items; + AP_Int32 _arming_options; // internal members bool armed; - uint32_t last_accel_pass_ms[INS_MAX_INSTANCES]; - uint32_t last_gyro_pass_ms[INS_MAX_INSTANCES]; + uint32_t last_accel_pass_ms; + uint32_t last_gyro_pass_ms; virtual bool barometer_checks(bool report); @@ -164,7 +174,13 @@ class AP_Arming { bool manual_transmitter_checks(bool report); - bool mission_checks(bool report); + virtual bool mission_checks(bool report); + + bool terrain_checks(bool report) const; + + // expected to return true if the terrain database is required to have + // all data loaded + virtual bool terrain_database_required() const; bool rangefinder_checks(bool report); @@ -178,10 +194,16 @@ class AP_Arming { bool osd_checks(bool display_failure) const; + bool mount_checks(bool display_failure) const; + bool aux_auth_checks(bool display_failure); bool generator_checks(bool report) const; + bool opendroneid_checks(bool display_failure); + + bool serial_protocol_checks(bool display_failure); + virtual bool system_checks(bool report); bool can_checks(bool report); @@ -191,7 +213,7 @@ class AP_Arming { virtual bool proximity_checks(bool report) const; bool servo_checks(bool report) const; - bool rc_checks_copter_sub(bool display_failure, const RC_Channel *channels[4]) const; + bool rc_checks_copter_sub(bool display_failure, const class RC_Channel *channels[4]) const; bool visodom_checks(bool report) const; bool disarm_switch_checks(bool report) const; @@ -201,8 +223,6 @@ class AP_Arming { // returns true if a particular check is enabled bool check_enabled(const enum AP_Arming::ArmingChecks check) const; - // returns a mavlink severity which should be used if a specific check fails - MAV_SEVERITY check_severity(const enum AP_Arming::ArmingChecks check) const; // handle the case where a check fails void check_failed(const enum AP_Arming::ArmingChecks check, bool report, const char *fmt, ...) const FMT_PRINTF(4, 5); void check_failed(bool report, const char *fmt, ...) const FMT_PRINTF(3, 4); @@ -214,8 +234,8 @@ class AP_Arming { static AP_Arming *_singleton; - bool ins_accels_consistent(const AP_InertialSensor &ins); - bool ins_gyros_consistent(const AP_InertialSensor &ins); + bool ins_accels_consistent(const class AP_InertialSensor &ins); + bool ins_gyros_consistent(const class AP_InertialSensor &ins); // check if we should keep logging after disarming void check_forced_logging(const AP_Arming::Method method); @@ -247,6 +267,9 @@ class AP_Arming { // method that was last used for disarm; invalid unless the // vehicle has been disarmed at least once. Method _last_disarm_method = Method::UNKNOWN; + + uint32_t last_prearm_display_ms; // last time we send statustexts for prearm failures + bool running_arming_checks; // true if the arming checks currently being performed are being done because the vehicle is trying to arm the vehicle }; namespace AP { diff --git a/libraries/AP_Avoidance/AP_Avoidance.cpp b/libraries/AP_Avoidance/AP_Avoidance.cpp index 4f4921da246..7b7829b5a5d 100644 --- a/libraries/AP_Avoidance/AP_Avoidance.cpp +++ b/libraries/AP_Avoidance/AP_Avoidance.cpp @@ -147,7 +147,7 @@ void AP_Avoidance::init(void) if (_obstacles == nullptr) { // dynamic RAM allocation of _obstacles[] failed, disable gracefully - hal.console->printf("Unable to initialize Avoidance obstacle list\n"); + DEV_PRINTF("Unable to initialize Avoidance obstacle list\n"); // disable ourselves to avoid repeated allocation attempts _enabled.set(0); return; diff --git a/libraries/AP_Avoidance/AP_Avoidance.h b/libraries/AP_Avoidance/AP_Avoidance.h index b6a35cb19fa..a802ded22a0 100644 --- a/libraries/AP_Avoidance/AP_Avoidance.h +++ b/libraries/AP_Avoidance/AP_Avoidance.h @@ -95,8 +95,8 @@ class AP_Avoidance { void update(); // enable or disable avoidance - void enable() { _enabled = true; }; - void disable() { _enabled = false; }; + void enable() { _enabled.set(true); }; + void disable() { _enabled.set(false); }; // current overall threat level MAV_COLLISION_THREAT_LEVEL current_threat_level() const; diff --git a/libraries/AP_BLHeli/AP_BLHeli.cpp b/libraries/AP_BLHeli/AP_BLHeli.cpp index dfe2ba9653b..f86fd034a03 100644 --- a/libraries/AP_BLHeli/AP_BLHeli.cpp +++ b/libraries/AP_BLHeli/AP_BLHeli.cpp @@ -39,9 +39,9 @@ #include #include #include -#include #include #include +#include extern const AP_HAL::HAL& hal; @@ -58,8 +58,9 @@ const AP_Param::GroupInfo AP_BLHeli::var_info[] = { // @Param: MASK // @DisplayName: BLHeli Channel Bitmask // @Description: Enable of BLHeli pass-thru servo protocol support to specific channels. This mask is in addition to motors enabled using SERVO_BLH_AUTO (if any) - // @Bitmask: 0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16 + // @Bitmask: 0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16, 16:Channel 17, 17: Channel 18, 18: Channel 19, 19: Channel 20, 20: Channel 21, 21: Channel 22, 22: Channel 23, 23: Channel 24, 24: Channel 25, 25: Channel 26, 26: Channel 27, 27: Channel 28, 28: Channel 29, 29: Channel 30, 30: Channel 31, 31: Channel 32 // @User: Advanced + // @RebootRequired: True AP_GROUPINFO("MASK", 1, AP_BLHeli, channel_mask, 0), #if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_Rover) @@ -68,6 +69,7 @@ const AP_Param::GroupInfo AP_BLHeli::var_info[] = { // @Description: If set to 1 this auto-enables BLHeli pass-thru support for all multicopter motors // @Values: 0:Disabled,1:Enabled // @User: Standard + // @RebootRequired: True AP_GROUPINFO("AUTO", 2, AP_BLHeli, channel_auto, 0), #endif @@ -106,6 +108,7 @@ const AP_Param::GroupInfo AP_BLHeli::var_info[] = { // @Description: When set to a non-zero value this overrides the output type for the output channels given by SERVO_BLH_MASK. This can be used to enable DShot on outputs that are not part of the multicopter motors group. // @Values: 0:None,1:OneShot,2:OneShot125,3:Brushed,4:DShot150,5:DShot300,6:DShot600,7:DShot1200 // @User: Advanced + // @RebootRequired: True AP_GROUPINFO("OTYPE", 7, AP_BLHeli, output_type, 0), // @Param: PORT @@ -120,28 +123,32 @@ const AP_Param::GroupInfo AP_BLHeli::var_info[] = { // @Description: This allows calculation of true RPM from ESC's eRPM. The default is 14. // @Range: 1 127 // @User: Advanced + // @RebootRequired: True AP_GROUPINFO("POLES", 9, AP_BLHeli, motor_poles, 14), // @Param: 3DMASK // @DisplayName: BLHeli bitmask of 3D channels // @Description: Mask of channels which are dynamically reversible. This is used to configure ESCs in '3D' mode, allowing for the motor to spin in either direction - // @Bitmask: 0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16 + // @Bitmask: 0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16, 16:Channel 17, 17: Channel 18, 18: Channel 19, 19: Channel 20, 20: Channel 21, 21: Channel 22, 22: Channel 23, 23: Channel 24, 24: Channel 25, 25: Channel 26, 26: Channel 27, 27: Channel 28, 28: Channel 29, 29: Channel 30, 30: Channel 31, 31: Channel 32 // @User: Advanced + // @RebootRequired: True AP_GROUPINFO("3DMASK", 10, AP_BLHeli, channel_reversible_mask, 0), #ifdef HAL_WITH_BIDIR_DSHOT // @Param: BDMASK // @DisplayName: BLHeli bitmask of bi-directional dshot channels // @Description: Mask of channels which support bi-directional dshot. This is used for ESCs which have firmware that supports bi-directional dshot allowing fast rpm telemetry values to be returned for the harmonic notch. - // @Bitmask: 0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16 + // @Bitmask: 0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16, 16:Channel 17, 17: Channel 18, 18: Channel 19, 19: Channel 20, 20: Channel 21, 21: Channel 22, 22: Channel 23, 23: Channel 24, 24: Channel 25, 25: Channel 26, 26: Channel 27, 27: Channel 28, 28: Channel 29, 29: Channel 30, 30: Channel 31, 31: Channel 32 // @User: Advanced + // @RebootRequired: True AP_GROUPINFO("BDMASK", 11, AP_BLHeli, channel_bidir_dshot_mask, 0), #endif // @Param: RVMASK // @DisplayName: BLHeli bitmask of reversed channels // @Description: Mask of channels which are reversed. This is used to configure ESCs in reversed mode - // @Bitmask: 0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16 + // @Bitmask: 0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16, 16:Channel 17, 17: Channel 18, 18: Channel 19, 19: Channel 20, 20: Channel 21, 21: Channel 22, 22: Channel 23, 23: Channel 24, 24: Channel 25, 25: Channel 26, 26: Channel 27, 27: Channel 28, 28: Channel 29, 29: Channel 30, 30: Channel 31, 31: Channel 32 // @User: Advanced + // @RebootRequired: True AP_GROUPINFO("RVMASK", 12, AP_BLHeli, channel_reversed_mask, 0), AP_GROUPEND @@ -478,6 +485,7 @@ void AP_BLHeli::msp_process_command(void) // set the output to each motor uint8_t nmotors = msp.dataSize / 2; debug("MSP_SET_MOTOR %u", nmotors); + motors_disabled_mask = SRV_Channels::get_disabled_channel_mask(); SRV_Channels::set_disabled_channel_mask(0xFFFF); motors_disabled = true; EXPECT_DELAY_MS(1000); @@ -939,7 +947,7 @@ void AP_BLHeli::blheli_process_command(void) serial_start_ms = 0; if (motors_disabled) { motors_disabled = false; - SRV_Channels::set_disabled_channel_mask(0); + SRV_Channels::set_disabled_channel_mask(motors_disabled_mask); } if (uart_locked) { debug("Unlocked UART"); @@ -1237,7 +1245,7 @@ void AP_BLHeli::run_connection_test(uint8_t chan) } } hal.rcout->serial_end(); - SRV_Channels::set_disabled_channel_mask(0); + SRV_Channels::set_disabled_channel_mask(motors_disabled_mask); motors_disabled = false; serial_start_ms = 0; blheli.chan = saved_chan; @@ -1270,7 +1278,7 @@ void AP_BLHeli::update(void) } if (motors_disabled) { motors_disabled = false; - SRV_Channels::set_disabled_channel_mask(0); + SRV_Channels::set_disabled_channel_mask(motors_disabled_mask); } if (uart != nullptr) { debug("Unlocked UART"); @@ -1325,7 +1333,7 @@ void AP_BLHeli::init(void) } #endif - uint16_t mask = uint16_t(channel_mask.get()); + uint32_t mask = uint32_t(channel_mask.get()); /* allow mode override - this makes it possible to use DShot for @@ -1351,7 +1359,7 @@ void AP_BLHeli::init(void) break; } - uint16_t digital_mask = 0; + uint32_t digital_mask = 0; // setting the digital mask changes the min/max PWM values // it's important that this is NOT done for non-digital channels as otherwise // PWM min can result in motors turning. set for individual overrides first @@ -1369,7 +1377,7 @@ void AP_BLHeli::init(void) AP_Motors *motors = AP::motors(); #endif if (motors) { - uint16_t motormask = motors->get_motor_mask(); + uint32_t motormask = motors->get_motor_mask(); // set the rest of the digital channels if (motors->is_digital_pwm_type()) { digital_mask |= motormask; @@ -1378,15 +1386,15 @@ void AP_BLHeli::init(void) } #endif // tell SRV_Channels about ESC capabilities - SRV_Channels::set_digital_outputs(digital_mask, uint16_t(channel_reversible_mask.get()) & digital_mask); + SRV_Channels::set_digital_outputs(digital_mask, uint32_t(channel_reversible_mask.get()) & digital_mask); // the dshot ESC type is required in order to send the reversed/reversible dshot command correctly hal.rcout->set_dshot_esc_type(SRV_Channels::get_dshot_esc_type()); - hal.rcout->set_reversible_mask(uint16_t(channel_reversible_mask.get()) & digital_mask); - hal.rcout->set_reversed_mask(uint16_t(channel_reversed_mask.get()) & digital_mask); + hal.rcout->set_reversible_mask(uint32_t(channel_reversible_mask.get()) & digital_mask); + hal.rcout->set_reversed_mask(uint32_t(channel_reversed_mask.get()) & digital_mask); #ifdef HAL_WITH_BIDIR_DSHOT // possibly enable bi-directional dshot hal.rcout->set_motor_poles(motor_poles); - hal.rcout->set_bidir_dshot_mask(uint16_t(channel_bidir_dshot_mask.get()) & digital_mask); + hal.rcout->set_bidir_dshot_mask(uint32_t(channel_bidir_dshot_mask.get()) & digital_mask); #endif // add motors from channel mask for (uint8_t i=0; i<16 && num_motors < max_motors; i++) { @@ -1396,7 +1404,7 @@ void AP_BLHeli::init(void) } } motor_mask = mask; - debug("ESC: %u motors mask=0x%04x", num_motors, mask); + debug("ESC: %u motors mask=0x%08lx", num_motors, mask); // check if we have a combination of reversable and normal mixed_type = (mask != (mask & channel_reversible_mask.get())) && (channel_reversible_mask.get() != 0); @@ -1460,7 +1468,7 @@ void AP_BLHeli::read_telemetry_packet(void) trpm = trpm * 200 / motor_poles; } } - hal.console->printf("ESC[%u] T=%u V=%f C=%f con=%f RPM=%u e=%.1f t=%u\n", + DEV_PRINTF("ESC[%u] T=%u V=%f C=%f con=%f RPM=%u e=%.1f t=%u\n", last_telem_esc, t.temperature_cdeg, t.voltage, @@ -1482,13 +1490,14 @@ void AP_BLHeli::log_bidir_telemetry(void) if (has_bidir_dshot(last_telem_esc)) { const uint8_t motor_idx = motor_map[last_telem_esc]; uint16_t trpm = hal.rcout->get_erpm(motor_idx); - const float terr = hal.rcout->get_erpm_error_rate(motor_idx); if (trpm != 0xFFFF) { // don't log invalid values as they are never used trpm = trpm * 200 / motor_poles; } - last_log_ms[last_telem_esc] = now; - hal.console->printf("ESC[%u] RPM=%u e=%.1f t=%u\n", last_telem_esc, trpm, terr, (unsigned)AP_HAL::millis()); + if (trpm > 0) { + last_log_ms[last_telem_esc] = now; + DEV_PRINTF("ESC[%u] RPM=%u e=%.1f t=%u\n", last_telem_esc, trpm, hal.rcout->get_erpm_error_rate(motor_idx), (unsigned)AP_HAL::millis()); + } } } @@ -1573,7 +1582,7 @@ void AP_BLHeli::update_telemetry(void) break; } } - uint16_t mask = 1U << motor_map[idx]; + uint32_t mask = 1U << motor_map[idx]; if (SRV_Channels::have_digital_outputs(mask)) { hal.rcout->set_telem_request_mask(mask); last_telem_esc = idx; diff --git a/libraries/AP_BLHeli/AP_BLHeli.h b/libraries/AP_BLHeli/AP_BLHeli.h index 24b6d94e5b6..2614cd39ae4 100644 --- a/libraries/AP_BLHeli/AP_BLHeli.h +++ b/libraries/AP_BLHeli/AP_BLHeli.h @@ -53,7 +53,7 @@ class AP_BLHeli : public AP_ESC_Telem_Backend { return channel_bidir_dshot_mask.get() & (1U << motor_map[esc_index]); } - uint16_t get_bidir_dshot_mask() const { return channel_bidir_dshot_mask.get(); } + uint32_t get_bidir_dshot_mask() const { return channel_bidir_dshot_mask.get(); } static AP_BLHeli *get_singleton(void) { return _singleton; @@ -231,6 +231,8 @@ class AP_BLHeli : public AP_ESC_Telem_Backend { // have we disabled motor outputs? bool motors_disabled; + // mask of channels that should normally be disabled + uint32_t motors_disabled_mask; // have we locked the UART? bool uart_locked; @@ -240,7 +242,7 @@ class AP_BLHeli : public AP_ESC_Telem_Backend { // mapping from BLHeli motor numbers to RC output channels uint8_t motor_map[max_motors]; - uint16_t motor_mask; + uint32_t motor_mask; // convert between servo number and FMU channel number for ESC telemetry uint8_t chan_offset; diff --git a/libraries/AP_Baro/AP_Baro.cpp b/libraries/AP_Baro/AP_Baro.cpp index e2ce13be4d4..5e059da7e3b 100644 --- a/libraries/AP_Baro/AP_Baro.cpp +++ b/libraries/AP_Baro/AP_Baro.cpp @@ -29,6 +29,7 @@ #include #include #include +#include #include "AP_Baro_SITL.h" #include "AP_Baro_BMP085.h" @@ -42,15 +43,18 @@ #include "AP_Baro_DPS280.h" #include "AP_Baro_BMP388.h" #include "AP_Baro_Dummy.h" -#if HAL_ENABLE_LIBUAVCAN_DRIVERS #include "AP_Baro_UAVCAN.h" -#endif #include "AP_Baro_MSP.h" #include "AP_Baro_ExternalAHRS.h" +#include "AP_Baro_ICP101XX.h" +#include "AP_Baro_ICP201XX.h" #include #include +#include #include +#include +#include #define INTERNAL_TEMPERATURE_CLAMP 35.0f @@ -127,7 +131,7 @@ const AP_Param::GroupInfo AP_Baro::var_info[] = { // @User: Advanced AP_GROUPINFO("_EXT_BUS", 7, AP_Baro, _ext_bus, HAL_BARO_EXTERNAL_BUS_DEFAULT), - // @Param: _SPEC_GRAV + // @Param{Sub}: _SPEC_GRAV // @DisplayName: Specific Gravity (For water depth measurement) // @Description: This sets the specific gravity of the fluid when flying an underwater ROV. // @Values: 1.0:Freshwater,1.024:Saltwater @@ -169,7 +173,7 @@ const AP_Param::GroupInfo AP_Baro::var_info[] = { // @Increment: 1 AP_GROUPINFO("_FLTR_RNG", 13, AP_Baro, _filter_range, HAL_BARO_FILTER_DEFAULT), -#if defined(HAL_PROBE_EXTERNAL_I2C_BAROS) || defined(HAL_MSP_BARO_ENABLED) +#if defined(HAL_PROBE_EXTERNAL_I2C_BAROS) || defined(AP_BARO_MSP_ENABLED) // @Param: _PROBE_EXT // @DisplayName: External barometers to probe // @Description: This sets which types of external i2c barometer to look for. It is a bitmask of barometer types. The I2C buses to probe is based on GND_EXT_BUS. If BARO_EXT_BUS is -1 then it will probe all external buses, otherwise it will probe just the bus number given in GND_EXT_BUS. @@ -219,8 +223,36 @@ const AP_Param::GroupInfo AP_Baro::var_info[] = { // @Path: AP_Baro_Wind.cpp AP_SUBGROUPINFO(sensors[2].wind_coeff, "3_WCF_", 20, AP_Baro, WindCoeff), #endif +#ifndef HAL_BUILD_AP_PERIPH + // @Param: _FIELD_ELV + // @DisplayName: field elevation + // @Description: User provided field elevation in meters. This is used to improve the calculation of the altitude the vehicle is at. This parameter is not persistent and will be reset to 0 every time the vehicle is rebooted. A value of 0 means no correction for takeoff height above sea level is performed. + // @Units: m + // @Increment: 0.1 + // @Volatile: True + // @User: Advanced + AP_GROUPINFO("_FIELD_ELV", 22, AP_Baro, _field_elevation, 0), +#endif #endif +#if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane) + // @Param: _ALTERR_MAX + // @DisplayName: Altitude error maximum + // @Description: This is the maximum acceptable altitude discrepancy between GPS altitude and barometric presssure altitude calculated against a standard atmosphere for arming checks to pass. If you are getting an arming error due to this parameter then you may have a faulty or substituted barometer. A common issue is vendors replacing a MS5611 in a "Pixhawk" with a MS5607. If you have that issue then please see BARO_OPTIONS parameter to force the MS5611 to be treated as a MS5607. This check is disabled if the value is zero. + // @Units: m + // @Increment: 1 + // @Range: 0 5000 + // @User: Advanced + AP_GROUPINFO("_ALTERR_MAX", 23, AP_Baro, _alt_error_max, 2000), + + // @Param: _OPTIONS + // @DisplayName: Barometer options + // @Description: Barometer options + // @Bitmask: 0:Treat MS5611 as MS5607 + // @User: Advanced + AP_GROUPINFO("_OPTIONS", 24, AP_Baro, _options, 0), +#endif + AP_GROUPEND }; @@ -241,6 +273,7 @@ AP_Baro::AP_Baro() _singleton = this; AP_Param::setup_object_defaults(this, var_info); + _field_elevation_active = _field_elevation; } // calibrate the barometer. This must be called at least once before @@ -318,7 +351,8 @@ void AP_Baro::calibrate(bool save) sensors[i].calibrated = false; } else { if (save) { - sensors[i].ground_pressure.set_and_save(sum_pressure[i] / count[i]); + float p0_sealevel = get_sealevel_pressure(sum_pressure[i] / count[i]); + sensors[i].ground_pressure.set_and_save(p0_sealevel); } } } @@ -353,7 +387,7 @@ void AP_Baro::update_calibration() } for (uint8_t i=0; i<_num_sensors; i++) { if (healthy(i)) { - float corrected_pressure = get_pressure(i) + sensors[i].p_correction; + float corrected_pressure = get_sealevel_pressure(get_pressure(i) + sensors[i].p_correction); sensors[i].ground_pressure.set(corrected_pressure); } @@ -380,11 +414,25 @@ float AP_Baro::get_altitude_difference(float base_pressure, float pressure) cons // This is an exact calculation that is within +-2.5m of the standard // atmosphere tables in the troposphere (up to 11,000 m amsl). - ret = 153.8462f * temp * (1.0f - expf(0.190259f * logf(scaling))); + ret = 153.8462f * temp * (1.0f - expf(0.190259f * logf(scaling)))-_field_elevation_active; return ret; } +// return sea level pressure where in which the current measured pressure +// at field elevation returns the same altitude under the +// 1976 standard atmospheric model +float AP_Baro::get_sealevel_pressure(float pressure) const +{ + float temp = C_TO_KELVIN(get_ground_temperature()); + float p0_sealevel; + // This is an exact calculation that is within +-2.5m of the standard + // atmosphere tables in the troposphere (up to 11,000 m amsl). + p0_sealevel = 8.651154799255761e30f*pressure*powF((769231.0f-(5000.0f*_field_elevation_active)/temp),-5.255993146184937f); + + return p0_sealevel; +} + // return current scale factor that converts from equivalent to true airspeed // valid for altitudes up to 10km AMSL @@ -505,6 +553,21 @@ bool AP_Baro::_add_backend(AP_Baro_Backend *backend) return true; } +/* + wrapper around hal.i2c_mgr->get_device() that prevents duplicate devices being opened + */ +bool AP_Baro::_have_i2c_driver(uint8_t bus, uint8_t address) const +{ + for (int i=0; i<_num_drivers; ++i) { + if (AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_I2C, bus, address, 0) == + AP_HAL::Device::change_bus_id(uint32_t(sensors[i].bus_id.get()), 0)) { + // device already has been defined. + return true; + } + } + return false; +} + /* macro to add a backend with check for too many sensors We don't try to start more than the maximum allowed @@ -524,10 +587,12 @@ void AP_Baro::init(void) { init_done = true; - // ensure that there isn't a previous ground temperature saved - if (!is_zero(_user_ground_temperature)) { - _user_ground_temperature.set_and_save(0.0f); - _user_ground_temperature.notify(); + // always set field elvation to zero on reboot in the case user + // fails to update. TBD automate sanity checking error bounds on + // on previously saved value at new location etc. + if (!is_zero(_field_elevation)) { + _field_elevation.set_and_save(0.0f); + _field_elevation.notify(); } // zero bus IDs before probing @@ -535,14 +600,24 @@ void AP_Baro::init(void) sensors[i].bus_id.set(0); } -#if HAL_ENABLE_LIBUAVCAN_DRIVERS +#if AP_SIM_BARO_ENABLED + SITL::SIM *sitl = AP::sitl(); + if (sitl == nullptr) { + AP_HAL::panic("No SITL pointer"); + } + for(uint8_t i = 0; i < sitl->baro_count; i++) { + ADD_BACKEND(new AP_Baro_SITL(*this)); + } +#endif + +#if AP_BARO_UAVCAN_ENABLED // Detect UAVCAN Modules, try as many times as there are driver slots for (uint8_t i = 0; i < BARO_MAX_DRIVERS; i++) { ADD_BACKEND(AP_Baro_UAVCAN::probe(*this)); } #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_BARO_EXTERNALAHRS_ENABLED const int8_t serial_port = AP::externalAHRS().get_port(); if (serial_port >= 0) { ADD_BACKEND(new AP_Baro_ExternalAHRS(*this, serial_port)); @@ -550,7 +625,16 @@ void AP_Baro::init(void) #endif // macro for use by HAL_INS_PROBE_LIST -#define GET_I2C_DEVICE(bus, address) hal.i2c_mgr->get_device(bus, address) +#define GET_I2C_DEVICE(bus, address) _have_i2c_driver(bus, address)?nullptr:hal.i2c_mgr->get_device(bus, address) + +#if AP_SIM_BARO_ENABLED +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && AP_BARO_MS56XX_ENABLED + ADD_BACKEND(AP_Baro_MS56XX::probe(*this, + std::move(GET_I2C_DEVICE(_ext_bus, HAL_BARO_MS5611_I2C_ADDR)))); +#endif + // do not probe for other drivers when using simulation: + return; +#endif #if defined(HAL_BARO_PROBE_LIST) // probe list from BARO lines in hwdef.dat @@ -558,7 +642,7 @@ void AP_Baro::init(void) #elif AP_FEATURE_BOARD_DETECT switch (AP_BoardConfig::get_board_type()) { case AP_BoardConfig::PX4_BOARD_PX4V1: -#ifdef HAL_BARO_MS5611_I2C_BUS +#if AP_BARO_MS56XX_ENABLED && defined(HAL_BARO_MS5611_I2C_BUS) ADD_BACKEND(AP_Baro_MS56XX::probe(*this, std::move(GET_I2C_DEVICE(HAL_BARO_MS5611_I2C_BUS, HAL_BARO_MS5611_I2C_ADDR)))); #endif @@ -569,32 +653,41 @@ void AP_Baro::init(void) case AP_BoardConfig::PX4_BOARD_AUAV21: case AP_BoardConfig::PX4_BOARD_PH2SLIM: case AP_BoardConfig::PX4_BOARD_PIXHAWK_PRO: +#if AP_BARO_MS56XX_ENABLED ADD_BACKEND(AP_Baro_MS56XX::probe(*this, std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME)))); +#endif break; case AP_BoardConfig::PX4_BOARD_PIXHAWK2: case AP_BoardConfig::PX4_BOARD_SP01: +#if AP_BARO_MS56XX_ENABLED ADD_BACKEND(AP_Baro_MS56XX::probe(*this, std::move(hal.spi->get_device(HAL_BARO_MS5611_SPI_EXT_NAME)))); ADD_BACKEND(AP_Baro_MS56XX::probe(*this, std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME)))); +#endif break; case AP_BoardConfig::PX4_BOARD_MINDPXV2: +#if AP_BARO_MS56XX_ENABLED ADD_BACKEND(AP_Baro_MS56XX::probe(*this, std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME)))); +#endif break; case AP_BoardConfig::PX4_BOARD_AEROFC: +#if AP_BARO_MS56XX_ENABLED #ifdef HAL_BARO_MS5607_I2C_BUS ADD_BACKEND(AP_Baro_MS56XX::probe(*this, std::move(GET_I2C_DEVICE(HAL_BARO_MS5607_I2C_BUS, HAL_BARO_MS5607_I2C_ADDR)), AP_Baro_MS56XX::BARO_MS5607)); #endif +#endif // AP_BARO_MS56XX_ENABLED break; case AP_BoardConfig::VRX_BOARD_BRAIN54: +#if AP_BARO_MS56XX_ENABLED ADD_BACKEND(AP_Baro_MS56XX::probe(*this, std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME)))); ADD_BACKEND(AP_Baro_MS56XX::probe(*this, @@ -603,6 +696,7 @@ void AP_Baro::init(void) ADD_BACKEND(AP_Baro_MS56XX::probe(*this, std::move(hal.spi->get_device(HAL_BARO_MS5611_SPI_IMU_NAME)))); #endif +#endif // AP_BARO_MS56XX_ENABLED break; case AP_BoardConfig::VRX_BOARD_BRAIN51: @@ -611,33 +705,31 @@ void AP_Baro::init(void) case AP_BoardConfig::VRX_BOARD_CORE10: case AP_BoardConfig::VRX_BOARD_UBRAIN51: case AP_BoardConfig::VRX_BOARD_UBRAIN52: +#if AP_BARO_MS56XX_ENABLED ADD_BACKEND(AP_Baro_MS56XX::probe(*this, std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME)))); +#endif // AP_BARO_MS56XX_ENABLED break; case AP_BoardConfig::PX4_BOARD_PCNC1: +#if AP_BARO_ICM20789_ENABLED ADD_BACKEND(AP_Baro_ICM20789::probe(*this, std::move(GET_I2C_DEVICE(1, 0x63)), std::move(hal.spi->get_device(HAL_INS_MPU60x0_NAME)))); +#endif break; case AP_BoardConfig::PX4_BOARD_FMUV5: case AP_BoardConfig::PX4_BOARD_FMUV6: +#if AP_BARO_MS56XX_ENABLED ADD_BACKEND(AP_Baro_MS56XX::probe(*this, std::move(hal.spi->get_device(HAL_BARO_MS5611_NAME)))); +#endif break; default: break; } -#elif AP_SIM_BARO_ENABLED - SITL::SIM *sitl = AP::sitl(); - if (sitl == nullptr) { - AP_HAL::panic("No SITL pointer"); - } - for(uint8_t i = 0; i < sitl->baro_count; i++) { - ADD_BACKEND(new AP_Baro_SITL(*this)); - } #elif HAL_BARO_DEFAULT == HAL_BARO_LPS25H_IMU_I2C ADD_BACKEND(AP_Baro_LPS2XH::probe_InvensenseIMU(*this, std::move(GET_I2C_DEVICE(HAL_BARO_LPS25H_I2C_BUS, HAL_BARO_LPS25H_I2C_ADDR)), @@ -655,14 +747,19 @@ void AP_Baro::init(void) // can optionally have baro on I2C too if (_ext_bus >= 0) { #if APM_BUILD_TYPE(APM_BUILD_ArduSub) +#if AP_BARO_MS56XX_ENABLED ADD_BACKEND(AP_Baro_MS56XX::probe(*this, std::move(GET_I2C_DEVICE(_ext_bus, HAL_BARO_MS5837_I2C_ADDR)), AP_Baro_MS56XX::BARO_MS5837)); - +#endif +#if AP_BARO_KELLERLD_ENABLED ADD_BACKEND(AP_Baro_KellerLD::probe(*this, std::move(GET_I2C_DEVICE(_ext_bus, HAL_BARO_KELLERLD_I2C_ADDR)))); +#endif #else +#if AP_BARO_MS56XX_ENABLED ADD_BACKEND(AP_Baro_MS56XX::probe(*this, std::move(GET_I2C_DEVICE(_ext_bus, HAL_BARO_MS5611_I2C_ADDR)))); +#endif #endif } @@ -670,7 +767,7 @@ void AP_Baro::init(void) _probe_i2c_barometers(); #endif -#if HAL_MSP_BARO_ENABLED +#if AP_BARO_MSP_ENABLED if ((_baro_probe_ext.get() & PROBE_MSP) && msp_instance_mask == 0) { // allow for late addition of MSP sensor msp_instance_mask |= 1; @@ -709,6 +806,7 @@ void AP_Baro::init(void) void AP_Baro::_probe_i2c_barometers(void) { uint32_t probe = _baro_probe_ext.get(); + (void)probe; // may be unused if most baros compiled out uint32_t mask = hal.i2c_mgr->get_bus_mask_external(); if (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_PIXHAWK2) { // for the purpose of baro probing, treat CubeBlack internal i2c as external. It has @@ -720,94 +818,64 @@ void AP_Baro::_probe_i2c_barometers(void) if (ext_bus >= 0) { mask = 1U << (uint8_t)ext_bus; } - if (probe & PROBE_BMP085) { - FOREACH_I2C_MASK(i,mask) { - ADD_BACKEND(AP_Baro_BMP085::probe(*this, - std::move(GET_I2C_DEVICE(i, HAL_BARO_BMP085_I2C_ADDR)))); - } - } - if (probe & PROBE_BMP280) { - FOREACH_I2C_MASK(i,mask) { - ADD_BACKEND(AP_Baro_BMP280::probe(*this, - std::move(GET_I2C_DEVICE(i, HAL_BARO_BMP280_I2C_ADDR)))); - ADD_BACKEND(AP_Baro_BMP280::probe(*this, - std::move(GET_I2C_DEVICE(i, HAL_BARO_BMP280_I2C_ADDR2)))); - } - } - if (probe & PROBE_SPL06) { - FOREACH_I2C_MASK(i,mask) { - ADD_BACKEND(AP_Baro_SPL06::probe(*this, - std::move(GET_I2C_DEVICE(i, HAL_BARO_SPL06_I2C_ADDR)))); - ADD_BACKEND(AP_Baro_SPL06::probe(*this, - std::move(GET_I2C_DEVICE(i, HAL_BARO_SPL06_I2C_ADDR2)))); - } - } - if (probe & PROBE_BMP388) { - FOREACH_I2C_MASK(i,mask) { - ADD_BACKEND(AP_Baro_BMP388::probe(*this, - std::move(GET_I2C_DEVICE(i, HAL_BARO_BMP388_I2C_ADDR)))); - ADD_BACKEND(AP_Baro_BMP388::probe(*this, - std::move(GET_I2C_DEVICE(i, HAL_BARO_BMP388_I2C_ADDR2)))); - } - } - if (probe & PROBE_MS5611) { - FOREACH_I2C_MASK(i,mask) { - ADD_BACKEND(AP_Baro_MS56XX::probe(*this, - std::move(GET_I2C_DEVICE(i, HAL_BARO_MS5611_I2C_ADDR)))); - ADD_BACKEND(AP_Baro_MS56XX::probe(*this, - std::move(GET_I2C_DEVICE(i, HAL_BARO_MS5611_I2C_ADDR2)))); - } - } - if (probe & PROBE_MS5607) { - FOREACH_I2C_MASK(i,mask) { - ADD_BACKEND(AP_Baro_MS56XX::probe(*this, - std::move(GET_I2C_DEVICE(i, HAL_BARO_MS5607_I2C_ADDR)), - AP_Baro_MS56XX::BARO_MS5607)); - } - } - if (probe & PROBE_MS5637) { - FOREACH_I2C_MASK(i,mask) { - ADD_BACKEND(AP_Baro_MS56XX::probe(*this, - std::move(GET_I2C_DEVICE(i, HAL_BARO_MS5637_I2C_ADDR)), - AP_Baro_MS56XX::BARO_MS5637)); - } - } - if (probe & PROBE_FBM320) { - FOREACH_I2C_MASK(i,mask) { - ADD_BACKEND(AP_Baro_FBM320::probe(*this, - std::move(GET_I2C_DEVICE(i, HAL_BARO_FBM320_I2C_ADDR)))); - ADD_BACKEND(AP_Baro_FBM320::probe(*this, - std::move(GET_I2C_DEVICE(i, HAL_BARO_FBM320_I2C_ADDR2)))); - } - } - if (probe & PROBE_DPS280) { - FOREACH_I2C_MASK(i,mask) { - ADD_BACKEND(AP_Baro_DPS280::probe(*this, - std::move(GET_I2C_DEVICE(i, HAL_BARO_DPS280_I2C_ADDR)))); - ADD_BACKEND(AP_Baro_DPS280::probe(*this, - std::move(GET_I2C_DEVICE(i, HAL_BARO_DPS280_I2C_ADDR2)))); - } - } - if (probe & PROBE_LPS25H) { - FOREACH_I2C_MASK(i,mask) { - ADD_BACKEND(AP_Baro_LPS2XH::probe(*this, - std::move(GET_I2C_DEVICE(i, HAL_BARO_LPS25H_I2C_ADDR)))); - } - } + + static const struct BaroProbeSpec { + uint32_t bit; + AP_Baro_Backend* (*probefn)(AP_Baro&, AP_HAL::OwnPtr); + uint8_t addr; + } baroprobespec[] { +#if AP_BARO_BMP085_ENABLED + { PROBE_BMP085, AP_Baro_BMP085::probe, HAL_BARO_BMP085_I2C_ADDR }, +#endif +#if AP_BARO_BMP280_ENABLED + { PROBE_BMP280, AP_Baro_BMP280::probe, HAL_BARO_BMP280_I2C_ADDR }, + { PROBE_BMP280, AP_Baro_BMP280::probe, HAL_BARO_BMP280_I2C_ADDR2 }, +#endif +#if AP_BARO_SPL06_ENABLED + { PROBE_SPL06, AP_Baro_SPL06::probe, HAL_BARO_SPL06_I2C_ADDR }, + { PROBE_SPL06, AP_Baro_SPL06::probe, HAL_BARO_SPL06_I2C_ADDR2 }, +#endif +#if AP_BARO_BMP388_ENABLED + { PROBE_BMP388, AP_Baro_BMP388::probe, HAL_BARO_BMP388_I2C_ADDR }, + { PROBE_BMP388, AP_Baro_BMP388::probe, HAL_BARO_BMP388_I2C_ADDR2 }, +#endif +#if AP_BARO_MS56XX_ENABLED + { PROBE_MS5611, AP_Baro_MS56XX::probe_5611, HAL_BARO_MS5611_I2C_ADDR }, + { PROBE_MS5611, AP_Baro_MS56XX::probe_5611, HAL_BARO_MS5611_I2C_ADDR2 }, + { PROBE_MS5607, AP_Baro_MS56XX::probe_5607, HAL_BARO_MS5607_I2C_ADDR }, + { PROBE_MS5637, AP_Baro_MS56XX::probe_5637, HAL_BARO_MS5637_I2C_ADDR }, +#endif +#if AP_BARO_FBM320_ENABLED + { PROBE_FBM320, AP_Baro_FBM320::probe, HAL_BARO_FBM320_I2C_ADDR }, + { PROBE_FBM320, AP_Baro_FBM320::probe, HAL_BARO_FBM320_I2C_ADDR2 }, +#endif +#if AP_BARO_DPS280_ENABLED + { PROBE_DPS280, AP_Baro_DPS280::probe_280, HAL_BARO_DPS280_I2C_ADDR }, + { PROBE_DPS280, AP_Baro_DPS280::probe_280, HAL_BARO_DPS280_I2C_ADDR2 }, +#endif +#if AP_BARO_LPS2XH_ENABLED + { PROBE_LPS25H, AP_Baro_LPS2XH::probe, HAL_BARO_LPS25H_I2C_ADDR }, +#endif + #if APM_BUILD_TYPE(APM_BUILD_ArduSub) - if (probe & PROBE_KELLER) { - FOREACH_I2C_MASK(i,mask) { - ADD_BACKEND(AP_Baro_KellerLD::probe(*this, - std::move(GET_I2C_DEVICE(i, HAL_BARO_KELLERLD_I2C_ADDR)))); +#if AP_BARO_KELLERLD_ENABLED + { PROBE_KELLER, AP_Baro_KellerLD::probe, HAL_BARO_KELLERLD_I2C_ADDR }, +#endif +#if AP_BARO_MS56XX_ENABLED + { PROBE_MS5837, AP_Baro_MS56XX::probe_5837, HAL_BARO_MS5837_I2C_ADDR }, +#endif +#endif // APM_BUILD_TYPE(APM_BUILD_ArduSub) + }; + + for (const auto &spec : baroprobespec) { + if (!(probe & spec.bit)) { + // not in mask to be probed for + continue; } - } - if (probe & PROBE_MS5837) { - FOREACH_I2C_MASK(i,mask) { - ADD_BACKEND(AP_Baro_MS56XX::probe(*this, - std::move(GET_I2C_DEVICE(i, HAL_BARO_MS5837_I2C_ADDR)), AP_Baro_MS56XX::BARO_MS5837)); + FOREACH_I2C_MASK(i, mask) { + ADD_BACKEND(spec.probefn(*this, std::move(GET_I2C_DEVICE(i, spec.addr)))); } } -#endif } bool AP_Baro::should_log() const @@ -840,6 +908,10 @@ void AP_Baro::update(void) _alt_offset_active = _alt_offset; } +#if HAL_LOGGING_ENABLED + bool old_primary_healthy = sensors[_primary].healthy; +#endif + for (uint8_t i=0; i<_num_drivers; i++) { drivers[i]->backend_update(i); } @@ -849,7 +921,7 @@ void AP_Baro::update(void) // update altitude calculation float ground_pressure = sensors[i].ground_pressure; if (!is_positive(ground_pressure) || isnan(ground_pressure) || isinf(ground_pressure)) { - sensors[i].ground_pressure = sensors[i].pressure; + sensors[i].ground_pressure.set(sensors[i].pressure); } float altitude = sensors[i].altitude; float corrected_pressure = sensors[i].pressure + sensors[i].p_correction; @@ -888,12 +960,39 @@ void AP_Baro::update(void) } } } +#ifndef HAL_BUILD_AP_PERIPH + const uint32_t now_ms = AP_HAL::millis(); + if (now_ms - _field_elevation_last_ms >= 1000 && fabsf(_field_elevation_active-_field_elevation) > 1.0) { + if (!AP::arming().is_armed()) { + _field_elevation_last_ms = now_ms; + _field_elevation_active = _field_elevation; + AP::ahrs().resetHeightDatum(); + update_calibration(); + BARO_SEND_TEXT(MAV_SEVERITY_INFO, "Barometer Field Elevation Set: %.0fm",_field_elevation_active); + } + else { + _field_elevation.set(_field_elevation_active); + _field_elevation.notify(); + BARO_SEND_TEXT(MAV_SEVERITY_ALERT, "Failed to Set Field Elevation: Armed"); + } + } +#endif // logging #if HAL_LOGGING_ENABLED if (should_log()) { Write_Baro(); } + +#define MASK_LOG_ANY 0xFFFF + + // log sensor healthy state change: + if (sensors[_primary].healthy != old_primary_healthy) { + if (AP::logger().should_log(MASK_LOG_ANY)) { + const LogErrorCode code = sensors[_primary].healthy ? LogErrorCode::ERROR_RESOLVED : LogErrorCode::UNHEALTHY; + AP::logger().Write_Error(LogErrorSubsystem::BARO, code); + } + } #endif } @@ -941,7 +1040,7 @@ void AP_Baro::set_pressure_correction(uint8_t instance, float p_correction) } } -#if HAL_MSP_BARO_ENABLED +#if AP_BARO_MSP_ENABLED /* handle MSP barometer data */ @@ -958,9 +1057,9 @@ void AP_Baro::handle_msp(const MSP::msp_baro_data_message_t &pkt) } } } -#endif +#endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_BARO_EXTERNALAHRS_ENABLED /* handle ExternalAHRS barometer data */ @@ -970,7 +1069,36 @@ void AP_Baro::handle_external(const AP_ExternalAHRS::baro_data_message_t &pkt) drivers[i]->handle_external(pkt); } } -#endif +#endif // AP_BARO_EXTERNALAHRS_ENABLED + +// returns false if we fail arming checks, in which case the buffer will be populated with a failure message +bool AP_Baro::arming_checks(size_t buflen, char *buffer) const +{ + if (!all_healthy()) { + hal.util->snprintf(buffer, buflen, "not healthy"); + return false; + } + +#if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane) + /* + check for a pressure altitude discrepancy between GPS alt and + baro alt this catches bad barometers, such as when a MS5607 has + been substituted for a MS5611 + */ + const auto &gps = AP::gps(); + if (_alt_error_max > 0 && gps.status() >= AP_GPS::GPS_Status::GPS_OK_FIX_3D) { + const float alt_amsl = gps.location().alt*0.01; + // note the addition of _field_elevation_active as this is subtracted in get_altitude_difference() + const float alt_pressure = get_altitude_difference(SSL_AIR_PRESSURE, get_pressure()) + _field_elevation_active; + const float error = fabsf(alt_amsl - alt_pressure); + if (error > _alt_error_max) { + hal.util->snprintf(buffer, buflen, "GPS alt error %.0fm (see BARO_ALTERR_MAX)", error); + return false; + } + } +#endif + return true; +} namespace AP { diff --git a/libraries/AP_Baro/AP_Baro.h b/libraries/AP_Baro/AP_Baro.h index 27e61467170..b1c7b5bf792 100644 --- a/libraries/AP_Baro/AP_Baro.h +++ b/libraries/AP_Baro/AP_Baro.h @@ -2,17 +2,20 @@ #include #include -#include #include #include #include #ifndef AP_SIM_BARO_ENABLED -#define AP_SIM_BARO_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL) +#define AP_SIM_BARO_ENABLED AP_SIM_ENABLED #endif -#ifndef HAL_MSP_BARO_ENABLED -#define HAL_MSP_BARO_ENABLED HAL_MSP_SENSORS_ENABLED +#ifndef AP_BARO_EXTERNALAHRS_ENABLED +#define AP_BARO_EXTERNALAHRS_ENABLED HAL_EXTERNAL_AHRS_ENABLED +#endif + +#ifndef AP_BARO_MSP_ENABLED +#define AP_BARO_MSP_ENABLED HAL_MSP_SENSORS_ENABLED #endif // maximum number of sensor instances @@ -76,6 +79,9 @@ class AP_Baro // check if all baros are healthy - used for SYS_STATUS report bool all_healthy(void) const; + // returns false if we fail arming checks, in which case the buffer will be populated with a failure message + bool arming_checks(size_t buflen, char *buffer) const; + // get primary sensor uint8_t get_primary(void) const { return _primary; } @@ -115,6 +121,10 @@ class AP_Baro // pressure in Pascal float get_altitude_difference(float base_pressure, float pressure) const; + // get sea level pressure relative to 1976 standard atmosphere model + // pressure in Pascal + float get_sealevel_pressure(float pressure) const; + // get scale factor required to convert equivalent to true airspeed float get_EAS2TAS(void); @@ -166,7 +176,7 @@ class AP_Baro uint8_t num_instances(void) const { return _num_sensors; } // set baro drift amount - void set_baro_drift_altitude(float alt) { _alt_offset = alt; } + void set_baro_drift_altitude(float alt) { _alt_offset.set(alt); } // get baro drift amount float get_baro_drift_offset(void) const { return _alt_offset_active; } @@ -191,14 +201,23 @@ class AP_Baro return _rsem; } -#if HAL_MSP_BARO_ENABLED +#if AP_BARO_MSP_ENABLED void handle_msp(const MSP::msp_baro_data_message_t &pkt); #endif - -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_BARO_EXTERNALAHRS_ENABLED void handle_external(const AP_ExternalAHRS::baro_data_message_t &pkt); #endif - + + enum Options : uint16_t { + TreatMS5611AsMS5607 = (1U << 0U), + }; + + // check if an option is set + bool option_enabled(const Options option) const + { + return (uint16_t(_options.get()) & uint16_t(option)) != 0; + } + private: // singleton static AP_Baro *_singleton; @@ -217,9 +236,7 @@ class AP_Baro bool init_done; -#if HAL_MSP_BARO_ENABLED uint8_t msp_instance_mask; -#endif // bitmask values for GND_PROBE_EXT enum { @@ -271,6 +288,9 @@ class AP_Baro AP_Float _alt_offset; float _alt_offset_active; + AP_Float _field_elevation; // field elevation in meters + float _field_elevation_active; + uint32_t _field_elevation_last_ms; AP_Int8 _primary_baro; // primary chosen by user AP_Int8 _ext_bus; // bus number for external barometer float _last_altitude_EAS2TAS; @@ -285,11 +305,19 @@ class AP_Baro // when did we last notify the GCS of new pressure reference? uint32_t _last_notify_ms; + // see if we already have probed a i2c driver by bus number and address + bool _have_i2c_driver(uint8_t bus_num, uint8_t address) const; bool _add_backend(AP_Baro_Backend *backend); void _probe_i2c_barometers(void); AP_Int8 _filter_range; // valid value range from mean value AP_Int32 _baro_probe_ext; +#ifndef HAL_BUILD_AP_PERIPH + AP_Float _alt_error_max; +#endif + + AP_Int16 _options; + // semaphore for API access from threads HAL_Semaphore _rsem; diff --git a/libraries/AP_Baro/AP_Baro_BMP085.cpp b/libraries/AP_Baro/AP_Baro_BMP085.cpp index b45c04cdf2d..9601db80d2c 100644 --- a/libraries/AP_Baro/AP_Baro_BMP085.cpp +++ b/libraries/AP_Baro/AP_Baro_BMP085.cpp @@ -14,6 +14,8 @@ */ #include "AP_Baro_BMP085.h" +#if AP_BARO_BMP085_ENABLED + #include #include @@ -57,6 +59,9 @@ AP_Baro_Backend * AP_Baro_BMP085::probe(AP_Baro &baro, AP_HAL::OwnPtr conversion_time_msec; } + +#endif // AP_BARO_BMP085_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_BMP085.h b/libraries/AP_Baro/AP_Baro_BMP085.h index 9be1ba11d8e..92b7178e837 100644 --- a/libraries/AP_Baro/AP_Baro_BMP085.h +++ b/libraries/AP_Baro/AP_Baro_BMP085.h @@ -1,12 +1,18 @@ #pragma once +#include "AP_Baro_Backend.h" + +#ifndef AP_BARO_BMP085_ENABLED +#define AP_BARO_BMP085_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_BARO_BMP085_ENABLED + #include #include #include #include -#include "AP_Baro_Backend.h" - #ifndef HAL_BARO_BMP085_I2C_ADDR #define HAL_BARO_BMP085_I2C_ADDR (0x77) #endif @@ -62,3 +68,5 @@ class AP_Baro_BMP085 : public AP_Baro_Backend { uint8_t _vers; uint8_t _type; }; + +#endif // AP_BARO_BMP085_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_BMP280.cpp b/libraries/AP_Baro/AP_Baro_BMP280.cpp index d6823ee2fb4..1eb2c1ab51a 100644 --- a/libraries/AP_Baro/AP_Baro_BMP280.cpp +++ b/libraries/AP_Baro/AP_Baro_BMP280.cpp @@ -14,6 +14,8 @@ */ #include "AP_Baro_BMP280.h" +#if AP_BARO_BMP280_ENABLED + #include extern const AP_HAL::HAL &hal; @@ -162,7 +164,7 @@ void AP_Baro_BMP280::_update_temperature(int32_t temp_raw) _t_fine = var1 + var2; t = (_t_fine * 5 + 128) >> 8; - const float temp = ((float)t) / 100.0f; + const float temp = ((float)t) * 0.01f; WITH_SEMAPHORE(_sem); @@ -203,3 +205,5 @@ void AP_Baro_BMP280::_update_pressure(int32_t press_raw) _pressure_sum += press; _pressure_count++; } + +#endif // AP_BARO_BMP280_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_BMP280.h b/libraries/AP_Baro/AP_Baro_BMP280.h index 98e81a32eba..48c62aebf8d 100644 --- a/libraries/AP_Baro/AP_Baro_BMP280.h +++ b/libraries/AP_Baro/AP_Baro_BMP280.h @@ -1,11 +1,17 @@ #pragma once +#include "AP_Baro_Backend.h" + +#ifndef AP_BARO_BMP280_ENABLED +#define AP_BARO_BMP280_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_BARO_BMP280_ENABLED + #include #include #include -#include "AP_Baro_Backend.h" - #ifndef HAL_BARO_BMP280_I2C_ADDR #define HAL_BARO_BMP280_I2C_ADDR (0x76) #endif @@ -42,3 +48,5 @@ class AP_Baro_BMP280 : public AP_Baro_Backend int16_t _t2, _t3, _p2, _p3, _p4, _p5, _p6, _p7, _p8, _p9; uint16_t _t1, _p1; }; + +#endif // AP_BARO_BMP280_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_BMP388.cpp b/libraries/AP_Baro/AP_Baro_BMP388.cpp index 7eb4e310053..e069a293d49 100644 --- a/libraries/AP_Baro/AP_Baro_BMP388.cpp +++ b/libraries/AP_Baro/AP_Baro_BMP388.cpp @@ -14,6 +14,8 @@ */ #include "AP_Baro_BMP388.h" +#if AP_BARO_BMP388_ENABLED + #include extern const AP_HAL::HAL &hal; @@ -24,8 +26,10 @@ extern const AP_HAL::HAL &hal; #define BMP388_MODE BMP388_MODE_NORMAL #define BMP388_ID 0x50 +#define BMP390_ID 0x60 #define BMP388_REG_ID 0x00 +#define BMP388_REV_ID_ADDR 0x01 #define BMP388_REG_ERR 0x02 #define BMP388_REG_STATUS 0x03 #define BMP388_REG_PRESS 0x04 // 24 bit @@ -87,9 +91,18 @@ bool AP_Baro_BMP388::init() dev->write_register(BMP388_REG_PWR_CTRL, 0x33, true); uint8_t whoami; - if (!read_registers(BMP388_REG_ID, &whoami, 1) || - whoami != BMP388_ID) { - // not a BMP388 + if (!read_registers(BMP388_REG_ID, &whoami, 1)) { + return false; + } + + switch (whoami) { + case BMP388_ID: + dev->set_device_type(DEVTYPE_BARO_BMP388); + break; + case BMP390_ID: + dev->set_device_type(DEVTYPE_BARO_BMP390); + break; + default: return false; } @@ -106,7 +119,6 @@ bool AP_Baro_BMP388::init() instance = _frontend.register_sensor(); - dev->set_device_type(DEVTYPE_BARO_BMP388); set_bus_id(instance, dev->get_bus_id()); // request 50Hz update @@ -238,3 +250,5 @@ bool AP_Baro_BMP388::read_registers(uint8_t reg, uint8_t *data, uint8_t len) memcpy(data, &b[2], len); return true; } + +#endif // AP_BARO_BMP388_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_BMP388.h b/libraries/AP_Baro/AP_Baro_BMP388.h index b854da246f0..a6126a4c6bd 100644 --- a/libraries/AP_Baro/AP_Baro_BMP388.h +++ b/libraries/AP_Baro/AP_Baro_BMP388.h @@ -1,11 +1,17 @@ #pragma once +#include "AP_Baro_Backend.h" + +#ifndef AP_BARO_BMP388_ENABLED +#define AP_BARO_BMP388_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_BARO_BMP388_ENABLED + #include #include #include -#include "AP_Baro_Backend.h" - #ifndef HAL_BARO_BMP388_I2C_ADDR #define HAL_BARO_BMP388_I2C_ADDR (0x76) #endif @@ -80,3 +86,5 @@ class AP_Baro_BMP388 : public AP_Baro_Backend void scale_calibration_data(void); bool read_registers(uint8_t reg, uint8_t *data, uint8_t len); }; + +#endif // AP_BARO_BMP388_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_Backend.cpp b/libraries/AP_Baro/AP_Baro_Backend.cpp index 95da66d3202..06ae436693c 100644 --- a/libraries/AP_Baro/AP_Baro_Backend.cpp +++ b/libraries/AP_Baro/AP_Baro_Backend.cpp @@ -1,4 +1,5 @@ #include "AP_Baro_Backend.h" + #include extern const AP_HAL::HAL& hal; diff --git a/libraries/AP_Baro/AP_Baro_Backend.h b/libraries/AP_Baro/AP_Baro_Backend.h index 8f8d1acb430..045fffcca35 100644 --- a/libraries/AP_Baro/AP_Baro_Backend.h +++ b/libraries/AP_Baro/AP_Baro_Backend.h @@ -2,6 +2,10 @@ #include "AP_Baro.h" +#ifndef AP_BARO_BACKEND_DEFAULT_ENABLED +#define AP_BARO_BACKEND_DEFAULT_ENABLED 1 +#endif + class AP_Baro_Backend { public: @@ -24,14 +28,14 @@ class AP_Baro_Backend bool pressure_ok(float press); uint32_t get_error_count() const { return _error_count; } -#if HAL_MSP_BARO_ENABLED +#if AP_BARO_MSP_ENABLED virtual void handle_msp(const MSP::msp_baro_data_message_t &pkt) {} -#endif +#endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_BARO_EXTERNALAHRS_ENABLED virtual void handle_external(const AP_ExternalAHRS::baro_data_message_t &pkt) {} -#endif - +#endif + /* device driver IDs. These are used to fill in the devtype field of the device ID, which shows up as BARO_DEVID* parameters to @@ -52,6 +56,12 @@ class AP_Baro_Backend DEVTYPE_BARO_SPL06 = 0x0C, DEVTYPE_BARO_UAVCAN = 0x0D, DEVTYPE_BARO_MSP = 0x0E, + DEVTYPE_BARO_ICP101XX = 0x0F, + DEVTYPE_BARO_ICP201XX = 0x10, + DEVTYPE_BARO_MS5607 = 0x11, + DEVTYPE_BARO_MS5837 = 0x12, + DEVTYPE_BARO_MS5637 = 0x13, + DEVTYPE_BARO_BMP390 = 0x14, }; protected: diff --git a/libraries/AP_Baro/AP_Baro_DPS280.cpp b/libraries/AP_Baro/AP_Baro_DPS280.cpp index 5d864a7cd91..3dd6ad5527f 100644 --- a/libraries/AP_Baro/AP_Baro_DPS280.cpp +++ b/libraries/AP_Baro/AP_Baro_DPS280.cpp @@ -18,6 +18,8 @@ #include "AP_Baro_DPS280.h" +#if AP_BARO_DPS280_ENABLED + #include #include @@ -305,3 +307,5 @@ void AP_Baro_DPS280::update(void) temperature_sum = 0; count=0; } + +#endif // AP_BARO_DPS280_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_DPS280.h b/libraries/AP_Baro/AP_Baro_DPS280.h index 6427d8e4810..783a7441025 100644 --- a/libraries/AP_Baro/AP_Baro_DPS280.h +++ b/libraries/AP_Baro/AP_Baro_DPS280.h @@ -1,11 +1,17 @@ #pragma once +#include "AP_Baro_Backend.h" + +#ifndef AP_BARO_DPS280_ENABLED +#define AP_BARO_DPS280_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_BARO_DPS280_ENABLED + #include #include #include -#include "AP_Baro_Backend.h" - #ifndef HAL_BARO_DPS280_I2C_ADDR #define HAL_BARO_DPS280_I2C_ADDR 0x76 #endif @@ -20,6 +26,10 @@ class AP_Baro_DPS280 : public AP_Baro_Backend { /* AP_Baro public interface: */ void update() override; + static AP_Baro_Backend *probe_280(AP_Baro &baro, AP_HAL::OwnPtr dev) { + return probe(baro, std::move(dev), false); + } + static AP_Baro_Backend *probe(AP_Baro &baro, AP_HAL::OwnPtr dev, bool _is_dps310=false); protected: @@ -67,3 +77,4 @@ class AP_Baro_DPS310 : public AP_Baro_DPS280 { }; +#endif // AP_BARO_DPS280_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_Dummy.cpp b/libraries/AP_Baro/AP_Baro_Dummy.cpp index 1ba8540bf19..477a9a747e7 100644 --- a/libraries/AP_Baro/AP_Baro_Dummy.cpp +++ b/libraries/AP_Baro/AP_Baro_Dummy.cpp @@ -1,5 +1,7 @@ #include "AP_Baro_Dummy.h" +#if AP_BARO_DUMMY_ENABLED + AP_Baro_Dummy::AP_Baro_Dummy(AP_Baro &baro) : AP_Baro_Backend(baro) { @@ -11,3 +13,5 @@ void AP_Baro_Dummy::update(void) { _copy_to_frontend(0, 91300, 21); } + +#endif // AP_BARO_DUMMY_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_Dummy.h b/libraries/AP_Baro/AP_Baro_Dummy.h index 6f36a246318..d43f512b3e6 100644 --- a/libraries/AP_Baro/AP_Baro_Dummy.h +++ b/libraries/AP_Baro/AP_Baro_Dummy.h @@ -6,6 +6,12 @@ #include "AP_Baro_Backend.h" +#ifndef AP_BARO_DUMMY_ENABLED +#define AP_BARO_DUMMY_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_BARO_DUMMY_ENABLED + class AP_Baro_Dummy : public AP_Baro_Backend { public: @@ -18,3 +24,5 @@ class AP_Baro_Dummy : public AP_Baro_Backend private: uint8_t _instance; }; + +#endif // AP_BARO_DUMMY_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_ExternalAHRS.cpp b/libraries/AP_Baro/AP_Baro_ExternalAHRS.cpp index 79ca28b8107..79a3c8bd3be 100644 --- a/libraries/AP_Baro/AP_Baro_ExternalAHRS.cpp +++ b/libraries/AP_Baro/AP_Baro_ExternalAHRS.cpp @@ -1,6 +1,6 @@ #include "AP_Baro_ExternalAHRS.h" -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_BARO_EXTERNALAHRS_ENABLED AP_Baro_ExternalAHRS::AP_Baro_ExternalAHRS(AP_Baro &baro, uint8_t port) : AP_Baro_Backend(baro) @@ -32,4 +32,4 @@ void AP_Baro_ExternalAHRS::handle_external(const AP_ExternalAHRS::baro_data_mess count++; } -#endif // HAL_EXTERNAL_AHRS_ENABLED +#endif // AP_BARO_EXTERNALAHRS_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_ExternalAHRS.h b/libraries/AP_Baro/AP_Baro_ExternalAHRS.h index 3594b71c82a..1b5dbdf823c 100644 --- a/libraries/AP_Baro/AP_Baro_ExternalAHRS.h +++ b/libraries/AP_Baro/AP_Baro_ExternalAHRS.h @@ -5,7 +5,9 @@ #include "AP_Baro_Backend.h" -#if HAL_EXTERNAL_AHRS_ENABLED +// AP_BARO_EXTERNALAHRS_ENABLED is defined in AP_Baro.h + +#if AP_BARO_EXTERNALAHRS_ENABLED class AP_Baro_ExternalAHRS : public AP_Baro_Backend { @@ -21,5 +23,4 @@ class AP_Baro_ExternalAHRS : public AP_Baro_Backend uint16_t count; }; -#endif // HAL_EXTERNAL_AHRS_ENABLED - +#endif // AP_BARO_EXTERNALAHRS_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_FBM320.cpp b/libraries/AP_Baro/AP_Baro_FBM320.cpp index 33fee17a14e..60676e52a6c 100644 --- a/libraries/AP_Baro/AP_Baro_FBM320.cpp +++ b/libraries/AP_Baro/AP_Baro_FBM320.cpp @@ -18,6 +18,8 @@ #include "AP_Baro_FBM320.h" +#if AP_BARO_FBM320_ENABLED + #include #include @@ -221,3 +223,5 @@ void AP_Baro_FBM320::update(void) temperature_sum = 0; count=0; } + +#endif // AP_BARO_FBM320_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_FBM320.h b/libraries/AP_Baro/AP_Baro_FBM320.h index 55d36858a19..9cb0507094f 100644 --- a/libraries/AP_Baro/AP_Baro_FBM320.h +++ b/libraries/AP_Baro/AP_Baro_FBM320.h @@ -1,11 +1,17 @@ #pragma once +#include "AP_Baro_Backend.h" + +#ifndef AP_BARO_FBM320_ENABLED +#define AP_BARO_FBM320_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_BARO_FBM320_ENABLED + #include #include #include -#include "AP_Baro_Backend.h" - #ifndef HAL_BARO_FBM320_I2C_ADDR #define HAL_BARO_FBM320_I2C_ADDR 0x6C #endif @@ -46,3 +52,5 @@ class AP_Baro_FBM320 : public AP_Baro_Backend { uint32_t C4, C5, C7; } calibration; }; + +#endif // AP_BARO_FBM320_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_ICM20789.cpp b/libraries/AP_Baro/AP_Baro_ICM20789.cpp index e66fece690c..cb978356b14 100644 --- a/libraries/AP_Baro/AP_Baro_ICM20789.cpp +++ b/libraries/AP_Baro/AP_Baro_ICM20789.cpp @@ -13,13 +13,16 @@ along with this program. If not, see . */ +#include "AP_Baro_ICM20789.h" + +#if AP_BARO_ICM20789_ENABLED + #include #include #include #include #include -#include "AP_Baro_ICM20789.h" #include @@ -360,3 +363,4 @@ void AP_Baro_ICM20789::update() } } +#endif // AP_BARO_ICM20789_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_ICM20789.h b/libraries/AP_Baro/AP_Baro_ICM20789.h index f4dea7a0a1a..a7a23906239 100644 --- a/libraries/AP_Baro/AP_Baro_ICM20789.h +++ b/libraries/AP_Baro/AP_Baro_ICM20789.h @@ -2,6 +2,12 @@ #include "AP_Baro_Backend.h" +#ifndef AP_BARO_ICM20789_ENABLED +#define AP_BARO_ICM20789_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_BARO_ICM20789_ENABLED + #include #include #include @@ -64,3 +70,5 @@ class AP_Baro_ICM20789 : public AP_Baro_Backend const float quadr_factor = 1 / 16777216.0; const float offst_factor = 2048.0; }; + +#endif // AP_BARO_ICM20789_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_ICP101XX.cpp b/libraries/AP_Baro/AP_Baro_ICP101XX.cpp new file mode 100755 index 00000000000..f06df354d05 --- /dev/null +++ b/libraries/AP_Baro/AP_Baro_ICP101XX.cpp @@ -0,0 +1,315 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +#include "AP_Baro_ICP101XX.h" + +#if AP_BARO_ICP101XX_ENABLED + +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +#include +#include + +#include + +extern const AP_HAL::HAL &hal; + +#define ICP101XX_ID 0x08 +#define CMD_READ_ID 0xefc8 +#define CMD_SET_ADDR 0xc595 +#define CMD_READ_OTP 0xc7f7 +#define CMD_MEAS_LP 0x609c +#define CMD_MEAS_N 0x6825 +#define CMD_MEAS_LN 0x70df +#define CMD_MEAS_ULN 0x7866 +#define CMD_SOFT_RESET 0x805d + +/* + constructor + */ +AP_Baro_ICP101XX::AP_Baro_ICP101XX(AP_Baro &baro, AP_HAL::OwnPtr _dev) + : AP_Baro_Backend(baro) + , dev(std::move(_dev)) +{ +} + +AP_Baro_Backend *AP_Baro_ICP101XX::probe(AP_Baro &baro, + AP_HAL::OwnPtr dev) +{ + if (!dev) { + return nullptr; + } + AP_Baro_ICP101XX *sensor = new AP_Baro_ICP101XX(baro, std::move(dev)); + if (!sensor || !sensor->init()) { + delete sensor; + return nullptr; + } + return sensor; +} + +bool AP_Baro_ICP101XX::init() +{ + if (!dev) { + return false; + } + + dev->get_semaphore()->take_blocking(); + + uint16_t id = 0; + read_response(CMD_READ_ID, (uint8_t *)&id, 2); + uint8_t whoami = (id >> 8) & 0x3f; // Product ID Bits 5:0 + if (whoami != ICP101XX_ID) { + goto failed; + } + + if (!send_command(CMD_SOFT_RESET)) { + goto failed; + } + + // wait for sensor to settle + hal.scheduler->delay(10); + + if (!read_calibration_data()) { + goto failed; + } + + // start a reading + if (!start_measure(CMD_MEAS_ULN)) { + goto failed; + } + + dev->set_retries(0); + + instance = _frontend.register_sensor(); + + dev->set_device_type(DEVTYPE_BARO_ICP101XX); + set_bus_id(instance, dev->get_bus_id()); + + dev->get_semaphore()->give(); + + dev->register_periodic_callback(measure_interval/2, FUNCTOR_BIND_MEMBER(&AP_Baro_ICP101XX::timer, void)); + + return true; + + failed: + dev->get_semaphore()->give(); + return false; +} + +bool AP_Baro_ICP101XX::read_measure_results(uint8_t *buf, uint8_t len) +{ + return dev->transfer(nullptr, 0, buf, len); +} + +bool AP_Baro_ICP101XX::read_response(uint16_t cmd, uint8_t *buf, uint8_t len) +{ + uint8_t buff[2]; + buff[0] = (cmd >> 8) & 0xff; + buff[1] = cmd & 0xff; + return dev->transfer(&buff[0], 2, buf, len); +} + +bool AP_Baro_ICP101XX::send_command(uint16_t cmd) +{ + uint8_t buf[2]; + buf[0] = (cmd >> 8) & 0xff; + buf[1] = cmd & 0xff; + return dev->transfer(buf, sizeof(buf), nullptr, 0); +} + +bool AP_Baro_ICP101XX::send_command(uint16_t cmd, uint8_t *data, uint8_t len) +{ + uint8_t buf[5]; + buf[0] = (cmd >> 8) & 0xff; + buf[1] = cmd & 0xff; + memcpy(&buf[2], data, len); + return dev->transfer(&buf[0], len + 2, nullptr, 0); +} + +int8_t AP_Baro_ICP101XX::cal_crc(uint8_t seed, uint8_t data) +{ + int8_t poly = 0x31; + int8_t var2; + uint8_t i; + + for (i = 0; i < 8; i++) { + if ((seed & 0x80) ^ (data & 0x80)) { + var2 = 1; + + } else { + var2 = 0; + } + + seed = (seed & 0x7F) << 1; + data = (data & 0x7F) << 1; + seed = seed ^ (uint8_t)(poly * var2); + } + + return (int8_t)seed; +} + +bool AP_Baro_ICP101XX::read_calibration_data(void) +{ + // setup for OTP read + uint8_t cmd[3] = { 0x00, 0x66, 0x9c }; + if (!send_command(CMD_SET_ADDR, cmd, 3)) { + return false; + } + for (uint8_t i = 0; i < 4; i++) { + uint8_t d[3]; + uint8_t crc = 0xff; + read_response(CMD_READ_OTP, d, 3); + for (int j = 0; j < 2; j++) { + crc = (uint8_t)cal_crc(crc, d[j]); + } + if (crc != d[2]) { + return false; + } + sensor_constants[i] = (d[0] << 8) | d[1]; + } + return true; +} + +bool AP_Baro_ICP101XX::start_measure(uint16_t mode) +{ + /* + From ds-000186-icp-101xx-v1.0.pdf, page 6, table 1 + + Sensor Measurement Max Time + Mode Time (Forced) + Low Power (LP) 1.6 ms 1.8 ms + Normal (N) 5.6 ms 6.3 ms + Low Noise (LN) 20.8 ms 23.8 ms + Ultra Low Noise(ULN) 83.2 ms 94.5 ms + */ + + switch (mode) { + case CMD_MEAS_LP: + measure_interval = 2000; + break; + + case CMD_MEAS_LN: + measure_interval = 24000; + break; + + case CMD_MEAS_ULN: + measure_interval = 95000; + break; + + case CMD_MEAS_N: + default: + measure_interval = 7000; + break; + } + + if (!send_command(mode)) { + return false; + } + + return true; +} + +void AP_Baro_ICP101XX::calculate_conversion_constants(const float p_Pa[3], const float p_LUT[3], + float &A, float &B, float &C) +{ + C = (p_LUT[0] * p_LUT[1] * (p_Pa[0] - p_Pa[1]) + + p_LUT[1] * p_LUT[2] * (p_Pa[1] - p_Pa[2]) + + p_LUT[2] * p_LUT[0] * (p_Pa[2] - p_Pa[0])) / + (p_LUT[2] * (p_Pa[0] - p_Pa[1]) + + p_LUT[0] * (p_Pa[1] - p_Pa[2]) + + p_LUT[1] * (p_Pa[2] - p_Pa[0])); + A = (p_Pa[0] * p_LUT[0] - p_Pa[1] * p_LUT[1] - (p_Pa[1] - p_Pa[0]) * C) / (p_LUT[0] - p_LUT[1]); + B = (p_Pa[0] - A) * (p_LUT[0] + C); +} + +/* + Convert an output from a calibrated sensor to a pressure in Pa. + Arguments: + p_LSB -- Raw pressure data from sensor + T_LSB -- Raw temperature data from sensor +*/ +float AP_Baro_ICP101XX::get_pressure(uint32_t p_LSB, uint32_t T_LSB) +{ + float t = T_LSB - 32768.0; + float s[3]; + s[0] = LUT_lower + float(sensor_constants[0] * t * t) * quadr_factor; + s[1] = offst_factor * sensor_constants[3] + float(sensor_constants[1] * t * t) * quadr_factor; + s[2] = LUT_upper + float(sensor_constants[2] * t * t) * quadr_factor; + float A, B, C; + calculate_conversion_constants(p_Pa_calib, s, A, B, C); + return A + B / (C + p_LSB); +} + +void AP_Baro_ICP101XX::convert_data(uint32_t Praw, uint32_t Traw) +{ + // temperature is easy + float T = -45 + (175.0f / (1U<<16)) * Traw; + + // pressure involves a few more calculations + float P = get_pressure(Praw, Traw); + + if (!pressure_ok(P)) { + return; + } + + WITH_SEMAPHORE(_sem); + + accum.psum += P; + accum.tsum += T; + accum.count++; +} + +void AP_Baro_ICP101XX::timer(void) +{ + uint8_t d[9] {}; + if (read_measure_results(d, 9)) { + // ignore CRC bytes for now + uint32_t Traw = (uint32_t(d[0]) << 8) | d[1]; + uint32_t Praw = (uint32_t(d[3]) << 16) | (uint32_t(d[4]) << 8) | d[6]; + + convert_data(Praw, Traw); + start_measure(CMD_MEAS_ULN); + last_measure_us = AP_HAL::micros(); + } else { + if (AP_HAL::micros() - last_measure_us > measure_interval*3) { + // lost a sample + start_measure(CMD_MEAS_ULN); + last_measure_us = AP_HAL::micros(); + } + } +} + +void AP_Baro_ICP101XX::update() +{ + WITH_SEMAPHORE(_sem); + + if (accum.count > 0) { + _copy_to_frontend(instance, accum.psum/accum.count, accum.tsum/accum.count); + accum.psum = accum.tsum = 0; + accum.count = 0; + } +} + +#endif // AP_BARO_ICP101XX_ENABLED \ No newline at end of file diff --git a/libraries/AP_Baro/AP_Baro_ICP101XX.h b/libraries/AP_Baro/AP_Baro_ICP101XX.h new file mode 100755 index 00000000000..ee94db8af7d --- /dev/null +++ b/libraries/AP_Baro/AP_Baro_ICP101XX.h @@ -0,0 +1,67 @@ +#pragma once + +#include "AP_Baro_Backend.h" + +#ifndef AP_BARO_ICP101XX_ENABLED +#define AP_BARO_ICP101XX_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_BARO_ICP101XX_ENABLED + +#include +#include +#include + +class AP_Baro_ICP101XX : public AP_Baro_Backend +{ +public: + void update() override; + + static AP_Baro_Backend *probe(AP_Baro &baro, AP_HAL::OwnPtr dev); + +private: + AP_Baro_ICP101XX(AP_Baro &baro, AP_HAL::OwnPtr dev); + + bool init(); + bool send_cmd16(uint16_t cmd); + bool read_measure_results(uint8_t *buf, uint8_t len); + bool read_response(uint16_t cmd, uint8_t *buf, uint8_t len); + bool send_command(uint16_t cmd); + bool send_command(uint16_t cmd, uint8_t *data, uint8_t len); + int8_t cal_crc(uint8_t seed, uint8_t data); + bool start_measure(uint16_t mode); + bool read_calibration_data(void); + void convert_data(uint32_t Praw, uint32_t Traw); + void calculate_conversion_constants(const float p_Pa[3], const float p_LUT[3], + float &A, float &B, float &C); + float get_pressure(uint32_t p_LSB, uint32_t T_LSB); + void timer(void); + + // calibration data + int16_t sensor_constants[4]; + + uint8_t instance; + + AP_HAL::OwnPtr dev; + + // time last read command was sent + uint32_t last_measure_us; + + // accumulation structure, protected by _sem + struct { + float tsum; + float psum; + uint32_t count; + } accum; + + // conversion constants. Thanks to invensense for including python + // sample code in the datasheet! + const float p_Pa_calib[3] = {45000.0, 80000.0, 105000.0}; + const float LUT_lower = 3.5 * (1U<<20); + const float LUT_upper = 11.5 * (1U<<20); + const float quadr_factor = 1 / 16777216.0; + const float offst_factor = 2048.0; + uint32_t measure_interval = 0; +}; + +#endif // AP_BARO_ICP101XX_ENABLED \ No newline at end of file diff --git a/libraries/AP_Baro/AP_Baro_ICP201XX.cpp b/libraries/AP_Baro/AP_Baro_ICP201XX.cpp new file mode 100755 index 00000000000..b7b5c6ec899 --- /dev/null +++ b/libraries/AP_Baro/AP_Baro_ICP201XX.cpp @@ -0,0 +1,496 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +#include "AP_Baro_ICP201XX.h" + +#if AP_BARO_ICP201XX_ENABLED + +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +#include +#include + +#include + +extern const AP_HAL::HAL &hal; + +#define ICP201XX_ID 0x63 + +#define CONVERSION_INTERVAL 25000 + +#define REG_EMPTY 0x00 +#define REG_TRIM1_MSB 0x05 +#define REG_TRIM2_LSB 0x06 +#define REG_TRIM2_MSB 0x07 +#define REG_DEVICE_ID 0x0C +#define REG_OTP_MTP_OTP_CFG1 0xAC +#define REG_OTP_MTP_MR_LSB 0xAD +#define REG_OTP_MTP_MR_MSB 0xAE +#define REG_OTP_MTP_MRA_LSB 0xAF +#define REG_OTP_MTP_MRA_MSB 0xB0 +#define REG_OTP_MTP_MRB_LSB 0xB1 +#define REG_OTP_MTP_MRB_MSB 0xB2 +#define REG_OTP_MTP_OTP_ADDR 0xB5 +#define REG_OTP_MTP_OTP_CMD 0xB6 +#define REG_OTP_MTP_RD_DATA 0xB8 +#define REG_OTP_MTP_OTP_STATUS 0xB9 +#define REG_OTP_DEBUG2 0xBC +#define REG_MASTER_LOCK 0xBE +#define REG_OTP_MTP_OTP_STATUS2 0xBF +#define REG_MODE_SELECT 0xC0 +#define REG_INTERRUPT_STATUS 0xC1 +#define REG_INTERRUPT_MASK 0xC2 +#define REG_FIFO_CONFIG 0xC3 +#define REG_FIFO_FILL 0xC4 +#define REG_SPI_MODE 0xC5 +#define REG_PRESS_ABS_LSB 0xC7 +#define REG_PRESS_ABS_MSB 0xC8 +#define REG_PRESS_DELTA_LSB 0xC9 +#define REG_PRESS_DELTA_MSB 0xCA +#define REG_DEVICE_STATUS 0xCD +#define REG_I3C_INFO 0xCE +#define REG_VERSION 0xD3 +#define REG_FIFO_BASE 0xFA + +/* + constructor + */ +AP_Baro_ICP201XX::AP_Baro_ICP201XX(AP_Baro &baro, AP_HAL::OwnPtr _dev) + : AP_Baro_Backend(baro) + , dev(std::move(_dev)) +{ +} + +AP_Baro_Backend *AP_Baro_ICP201XX::probe(AP_Baro &baro, + AP_HAL::OwnPtr dev) +{ + if (!dev) { + return nullptr; + } + AP_Baro_ICP201XX *sensor = new AP_Baro_ICP201XX(baro, std::move(dev)); + if (!sensor || !sensor->init()) { + delete sensor; + return nullptr; + } + return sensor; +} + +bool AP_Baro_ICP201XX::init() +{ + if (!dev) { + return false; + } + + dev->get_semaphore()->take_blocking(); + + uint8_t id = 0xFF; + uint8_t ver = 0xFF; + read_reg(REG_DEVICE_ID, &id); + read_reg(REG_VERSION, &ver); + + if (id != ICP201XX_ID) { + goto failed; + } + + if (ver != 0x00 && ver != 0xB2) { + goto failed; + } + + hal.scheduler->delay(10); + + soft_reset(); + + if (!boot_sequence()) { + goto failed; + } + + if (!configure()) { + goto failed; + } + + wait_read(); + + dev->set_retries(0); + + instance = _frontend.register_sensor(); + + dev->set_device_type(DEVTYPE_BARO_ICP201XX); + set_bus_id(instance, dev->get_bus_id()); + + dev->get_semaphore()->give(); + + dev->register_periodic_callback(CONVERSION_INTERVAL/2, FUNCTOR_BIND_MEMBER(&AP_Baro_ICP201XX::timer, void)); + return true; + + failed: + dev->get_semaphore()->give(); + return false; +} + + +void AP_Baro_ICP201XX::dummy_reg() +{ + do { + uint8_t reg = REG_EMPTY; + uint8_t val = 0; + dev->transfer(®, 1, &val, 1); + } while (0); +} + +bool AP_Baro_ICP201XX::read_reg(uint8_t reg, uint8_t *buf, uint8_t len) +{ + bool ret; + ret = dev->transfer(®, 1, buf, len); + dummy_reg(); + return ret; +} + +bool AP_Baro_ICP201XX::read_reg(uint8_t reg, uint8_t *val) +{ + return read_reg(reg, val, 1); +} + +bool AP_Baro_ICP201XX::write_reg(uint8_t reg, uint8_t val) +{ + bool ret; + uint8_t data[2] = { reg, val }; + ret = dev->transfer(data, sizeof(data), nullptr, 0); + dummy_reg(); + return ret; +} + +void AP_Baro_ICP201XX::soft_reset() +{ + /* Stop the measurement */ + mode_select(0x00); + + hal.scheduler->delay(2); + + /* Flush FIFO */ + flush_fifo(); + + /* Mask all interrupts */ + write_reg(REG_FIFO_CONFIG, 0x00); + write_reg(REG_INTERRUPT_MASK, 0xFF); +} + +bool AP_Baro_ICP201XX::mode_select(uint8_t mode) +{ + uint8_t mode_sync_status = 0; + + do { + read_reg(REG_DEVICE_STATUS, &mode_sync_status, 1); + + if (mode_sync_status & 0x01) { + break; + } + + hal.scheduler->delay(1); + } while (1); + + return write_reg(REG_MODE_SELECT, mode); +} + +bool AP_Baro_ICP201XX::read_otp_data(uint8_t addr, uint8_t cmd, uint8_t *val) +{ + uint8_t otp_status = 0xFF; + + /* Write the address content and read command */ + if (!write_reg(REG_OTP_MTP_OTP_ADDR, addr)) { + return false; + } + + if (!write_reg(REG_OTP_MTP_OTP_CMD, cmd)) { + return false; + } + + /* Wait for the OTP read to finish Monitor otp_status */ + do { + read_reg(REG_OTP_MTP_OTP_STATUS, &otp_status); + + if (otp_status == 0) { + break; + } + + hal.scheduler->delay_microseconds(1); + } while (1); + + /* Read the data from register */ + if (!read_reg(REG_OTP_MTP_RD_DATA, val)) { + return false; + } + + return true; +} + +bool AP_Baro_ICP201XX::get_sensor_data(float *pressure, float *temperature) +{ + uint8_t fifo_data[96] {0}; + uint8_t fifo_packets = 0; + int32_t data_temp = 0; + int32_t data_press = 0; + *pressure = 0; + *temperature = 0; + + if (read_reg(REG_FIFO_FILL, &fifo_packets)) { + fifo_packets = (uint8_t)(fifo_packets & 0x1F); + if (fifo_packets > 16) { + flush_fifo(); + return false; + } + if (fifo_packets > 0 && fifo_packets <= 16 && read_reg(REG_FIFO_BASE, fifo_data, fifo_packets * 2 * 3)) { + uint8_t offset = 0; + + for (uint8_t i = 0; i < fifo_packets; i++) { + data_press = (int32_t)(((fifo_data[offset + 2] & 0x0f) << 16) | (fifo_data[offset + 1] << 8) | fifo_data[offset]); + if (data_press & 0x080000) { + data_press |= 0xFFF00000; + } + /* P = (POUT/2^17)*40kPa + 70kPa */ + *pressure += ((float)(data_press) * 40 / 131072) + 70; + offset += 3; + + data_temp = (int32_t)(((fifo_data[offset + 2] & 0x0f) << 16) | (fifo_data[offset + 1] << 8) | fifo_data[offset]); + if (data_temp & 0x080000) { + data_temp |= 0xFFF00000; + } + /* T = (TOUT/2^18)*65C + 25C */ + *temperature += ((float)(data_temp) * 65 / 262144) + 25; + offset += 3; + } + + *pressure = *pressure * 1000 / fifo_packets; + *temperature = *temperature / fifo_packets; + return true; + } + } + + return false; +} + +bool AP_Baro_ICP201XX::boot_sequence() +{ + uint8_t reg_value = 0; + uint8_t offset = 0, gain = 0, Hfosc = 0; + uint8_t version = 0; + uint8_t bootup_status = 0; + int ret = 1; + + /* read version register */ + if (!read_reg(REG_VERSION, &version)) { + return false; + } + + if (version == 0xB2) { + /* B2 version Asic is detected. Boot up sequence is not required for B2 Asic, so returning */ + return true; + } + + /* Read boot up status and avoid re running boot up sequence if it is already done */ + if (!read_reg(REG_OTP_MTP_OTP_STATUS2, &bootup_status)) { + return false; + } + + if (bootup_status & 0x01) { + /* Boot up sequence is already done, not required to repeat boot up sequence */ + return true; + } + + /* Bring the ASIC in power mode to activate the OTP power domain and get access to the main registers */ + mode_select(0x04); + hal.scheduler->delay(4); + + /* Unlock the main registers */ + write_reg(REG_MASTER_LOCK, 0x1F); + + /* Enable the OTP and the write switch */ + read_reg(REG_OTP_MTP_OTP_CFG1, ®_value); + reg_value |= 0x03; + write_reg(REG_OTP_MTP_OTP_CFG1, reg_value); + hal.scheduler->delay_microseconds(10); + + /* Toggle the OTP reset pin */ + read_reg(REG_OTP_DEBUG2, ®_value); + reg_value |= 1 << 7; + write_reg(REG_OTP_DEBUG2, reg_value); + hal.scheduler->delay_microseconds(10); + + read_reg(REG_OTP_DEBUG2, ®_value); + reg_value &= ~(1 << 7); + write_reg(REG_OTP_DEBUG2, reg_value); + hal.scheduler->delay_microseconds(10); + + /* Program redundant read */ + write_reg(REG_OTP_MTP_MRA_LSB, 0x04); + write_reg(REG_OTP_MTP_MRA_MSB, 0x04); + write_reg(REG_OTP_MTP_MRB_LSB, 0x21); + write_reg(REG_OTP_MTP_MRB_MSB, 0x20); + write_reg(REG_OTP_MTP_MR_LSB, 0x10); + write_reg(REG_OTP_MTP_MR_MSB, 0x80); + + /* Read the data from register */ + ret &= read_otp_data(0xF8, 0x10, &offset); + ret &= read_otp_data(0xF9, 0x10, &gain); + ret &= read_otp_data(0xFA, 0x10, &Hfosc); + hal.scheduler->delay_microseconds(10); + + /* Write OTP values to main registers */ + ret &= read_reg(REG_TRIM1_MSB, ®_value); + if (ret) { + reg_value = (reg_value & (~0x3F)) | (offset & 0x3F); + ret &= write_reg(REG_TRIM1_MSB, reg_value); + } + + ret &= read_reg(REG_TRIM2_MSB, ®_value); + if (ret) { + reg_value = (reg_value & (~0x70)) | ((gain & 0x07) << 4); + ret &= write_reg(REG_TRIM2_MSB, reg_value); + } + + ret &= read_reg(REG_TRIM2_LSB, ®_value); + if (ret) { + reg_value = (reg_value & (~0x7F)) | (Hfosc & 0x7F); + ret &= write_reg(REG_TRIM2_LSB, reg_value); + } + + hal.scheduler->delay_microseconds(10); + + /* Update boot up status to 1 */ + if (ret) { + ret &= read_reg(REG_OTP_MTP_OTP_STATUS2, ®_value); + if (!ret) { + reg_value |= 0x01; + ret &= write_reg(REG_OTP_MTP_OTP_STATUS2, reg_value); + } + } + + /* Disable OTP and write switch */ + read_reg(REG_OTP_MTP_OTP_CFG1, ®_value); + reg_value &= ~0x03; + write_reg(REG_OTP_MTP_OTP_CFG1, reg_value); + + /* Lock the main register */ + write_reg(REG_MASTER_LOCK, 0x00); + + /* Move to standby */ + mode_select(0x00); + + return ret; +} + +bool AP_Baro_ICP201XX::configure() +{ + uint8_t reg_value = 0; + + /* Initiate Triggered Operation: Stay in Standby mode */ + reg_value |= (reg_value & (~0x10)) | ((uint8_t)_forced_meas_trigger << 4); + + /* Power Mode Selection: Normal Mode */ + reg_value |= (reg_value & (~0x04)) | ((uint8_t)_power_mode << 2); + + /* FIFO Readout Mode Selection: Pressure first. */ + reg_value |= (reg_value & (~0x03)) | ((uint8_t)(_fifo_readout_mode)); + + /* Measurement Configuration: Mode2*/ + reg_value |= (reg_value & (~0xE0)) | (((uint8_t)_op_mode) << 5); + + /* Measurement Mode Selection: Continuous Measurements (duty cycled) */ + reg_value |= (reg_value & (~0x08)) | ((uint8_t)_meas_mode << 3); + + return mode_select(reg_value); +} + +void AP_Baro_ICP201XX::wait_read() +{ + /* + * If FIR filter is enabled, it will cause a settling effect on the first 14 pressure values. + * Therefore the first 14 pressure output values are discarded. + **/ + uint8_t fifo_packets = 0; + uint8_t fifo_packets_to_skip = 14; + + do { + hal.scheduler->delay(10); + read_reg(REG_FIFO_FILL, &fifo_packets); + fifo_packets = (uint8_t)(fifo_packets & 0x1F); + } while (fifo_packets >= fifo_packets_to_skip); + + flush_fifo(); + fifo_packets = 0; + + do { + hal.scheduler->delay(10); + read_reg(REG_FIFO_FILL, &fifo_packets); + fifo_packets = (uint8_t)(fifo_packets & 0x1F); + } while (fifo_packets == 0); +} + +bool AP_Baro_ICP201XX::flush_fifo() +{ + uint8_t reg_value; + + if (!read_reg(REG_FIFO_FILL, ®_value)) { + return false; + } + + reg_value |= 0x80; + + if (!write_reg(REG_FIFO_FILL, reg_value)) { + return false; + } + + return true; +} + +void AP_Baro_ICP201XX::timer() +{ + float p = 0; + float t = 0; + + if (get_sensor_data(&p, &t)) { + WITH_SEMAPHORE(_sem); + + accum.psum += p; + accum.tsum += t; + accum.count++; + last_measure_us = AP_HAL::micros(); + } else { + if (AP_HAL::micros() - last_measure_us > CONVERSION_INTERVAL*3) { + flush_fifo(); + last_measure_us = AP_HAL::micros(); + } + } +} + +void AP_Baro_ICP201XX::update() +{ + WITH_SEMAPHORE(_sem); + + if (accum.count > 0) { + _copy_to_frontend(instance, accum.psum/accum.count, accum.tsum/accum.count); + accum.psum = accum.tsum = 0; + accum.count = 0; + } +} + +#endif // AP_BARO_ICP201XX_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_ICP201XX.h b/libraries/AP_Baro/AP_Baro_ICP201XX.h new file mode 100755 index 00000000000..54018162343 --- /dev/null +++ b/libraries/AP_Baro/AP_Baro_ICP201XX.h @@ -0,0 +1,85 @@ +#pragma once + +#include "AP_Baro_Backend.h" + +#ifndef AP_BARO_ICP201XX_ENABLED +#define AP_BARO_ICP201XX_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_BARO_ICP201XX_ENABLED + +#include +#include +#include + +class AP_Baro_ICP201XX : public AP_Baro_Backend +{ +public: + void update() override; + + static AP_Baro_Backend *probe(AP_Baro &baro, AP_HAL::OwnPtr dev); + +private: + AP_Baro_ICP201XX(AP_Baro &baro, AP_HAL::OwnPtr dev); + + bool init(); + void dummy_reg(); + bool read_reg(uint8_t reg, uint8_t *buf, uint8_t len); + bool read_reg(uint8_t reg, uint8_t *val); + bool write_reg(uint8_t reg, uint8_t val); + bool mode_select(uint8_t mode); + bool read_otp_data(uint8_t addr, uint8_t cmd, uint8_t *val); + bool get_sensor_data(float *pressure, float *temperature); + void soft_reset(); + bool boot_sequence(); + bool configure(); + void wait_read(); + bool flush_fifo(); + void timer(); + + uint8_t instance; + + AP_HAL::OwnPtr dev; + + // accumulation structure, protected by _sem + struct { + float tsum; + float psum; + uint32_t count; + } accum; + + // time last read command was sent + uint32_t last_measure_us; + + enum class OP_MODE : uint8_t { + OP_MODE0 = 0, /* Mode 0: Bw:6.25 Hz ODR: 25Hz */ + OP_MODE1, /* Mode 1: Bw:30 Hz ODR: 120Hz */ + OP_MODE2, /* Mode 2: Bw:10 Hz ODR: 40Hz */ + OP_MODE3, /* Mode 3: Bw:0.5 Hz ODR: 2Hz */ + OP_MODE4, /* Mode 4: User configurable Mode */ + } _op_mode{OP_MODE::OP_MODE2}; + + enum class FIFO_READOUT_MODE : uint8_t { + FIFO_READOUT_MODE_PRES_TEMP = 0, /* Pressure and temperature as pair and address wraps to the start address of the Pressure value ( pressure first ) */ + FIFO_READOUT_MODE_TEMP_ONLY = 1, /* Temperature only reporting */ + FIFO_READOUT_MODE_TEMP_PRES = 2, /* Pressure and temperature as pair and address wraps to the start address of the Temperature value ( Temperature first ) */ + FIFO_READOUT_MODE_PRES_ONLY = 3 /* Pressure only reporting */ + } _fifo_readout_mode{FIFO_READOUT_MODE::FIFO_READOUT_MODE_PRES_TEMP}; + + enum class POWER_MODE : uint8_t { + POWER_MODE_NORMAL = 0, /* Normal Mode: Device is in standby and goes to active mode during the execution of a measurement */ + POWER_MODE_ACTIVE = 1 /* Active Mode: Power on DVDD and enable the high frequency clock */ + } _power_mode{POWER_MODE::POWER_MODE_NORMAL}; + + enum MEAS_MODE : uint8_t { + MEAS_MODE_FORCED_TRIGGER = 0, /* Force trigger mode based on icp201xx_forced_meas_trigger_t **/ + MEAS_MODE_CONTINUOUS = 1 /* Continuous measurements based on selected mode ODR settings*/ + } _meas_mode{MEAS_MODE::MEAS_MODE_CONTINUOUS}; + + enum FORCED_MEAS_TRIGGER : uint8_t { + FORCE_MEAS_STANDBY = 0, /* Stay in Stand by */ + FORCE_MEAS_TRIGGER_FORCE_MEAS = 1 /* Trigger for forced measurements */ + } _forced_meas_trigger{FORCED_MEAS_TRIGGER::FORCE_MEAS_STANDBY}; +}; + +#endif // AP_BARO_ICP201XX_ENABLED \ No newline at end of file diff --git a/libraries/AP_Baro/AP_Baro_KellerLD.cpp b/libraries/AP_Baro/AP_Baro_KellerLD.cpp index 55a0e27bec5..3532b484d0c 100644 --- a/libraries/AP_Baro/AP_Baro_KellerLD.cpp +++ b/libraries/AP_Baro/AP_Baro_KellerLD.cpp @@ -15,6 +15,8 @@ #include "AP_Baro_KellerLD.h" +#if AP_BARO_KELLERLD_ENABLED + #include #include @@ -319,3 +321,5 @@ void AP_Baro_KellerLD::update() _copy_to_frontend(_instance, pressure, temperature); } + +#endif // AP_BARO_KELLERLD_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_KellerLD.h b/libraries/AP_Baro/AP_Baro_KellerLD.h index bc9086928d6..235acff0a08 100644 --- a/libraries/AP_Baro/AP_Baro_KellerLD.h +++ b/libraries/AP_Baro/AP_Baro_KellerLD.h @@ -27,6 +27,12 @@ #include "AP_Baro_Backend.h" +#ifndef AP_BARO_KELLERLD_ENABLED +#define AP_BARO_KELLERLD_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_BARO_KELLERLD_ENABLED + #include #include #include @@ -87,3 +93,6 @@ class AP_Baro_KellerLD : public AP_Baro_Backend bool read_cal(); bool read_mode_type(); }; + + +#endif // AP_BARO_KELLERLD_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_LPS2XH.cpp b/libraries/AP_Baro/AP_Baro_LPS2XH.cpp index aed59ef9dd1..448ff64ed1a 100644 --- a/libraries/AP_Baro/AP_Baro_LPS2XH.cpp +++ b/libraries/AP_Baro/AP_Baro_LPS2XH.cpp @@ -12,11 +12,13 @@ You should have received a copy of the GNU General Public License along with this program. If not, see . */ +#include "AP_Baro_LPS2XH.h" + +#if AP_BARO_LPS2XH_ENABLED + #include #include -#include "AP_Baro_LPS2XH.h" - #include extern const AP_HAL::HAL &hal; @@ -117,7 +119,7 @@ bool AP_Baro_LPS2XH::_imu_i2c_init(uint8_t imu_address) uint8_t whoami=0; _dev->read_registers(MPUREG_WHOAMI, &whoami, 1); - hal.console->printf("IMU: whoami 0x%02x old_address=%02x\n", whoami, old_address); + DEV_PRINTF("IMU: whoami 0x%02x old_address=%02x\n", whoami, old_address); _dev->write_register(MPUREG_FIFO_EN, 0x00); _dev->write_register(MPUREG_PWR_MGMT_1, BIT_PWR_MGMT_1_CLK_XGYRO); @@ -194,7 +196,7 @@ bool AP_Baro_LPS2XH::_check_whoami(void) if (!_dev->read_registers(REG_ID, &whoami, 1)) { return false; } - hal.console->printf("LPS2XH whoami 0x%02x\n", whoami); + DEV_PRINTF("LPS2XH whoami 0x%02x\n", whoami); switch(whoami){ case LPS22HB_WHOAMI: @@ -274,3 +276,5 @@ void AP_Baro_LPS2XH::_update_pressure(void) _pressure_sum += Pressure_mb; _pressure_count++; } + +#endif // AP_BARO_LPS2XH_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_LPS2XH.h b/libraries/AP_Baro/AP_Baro_LPS2XH.h index f086d77fff9..7ca571f1456 100644 --- a/libraries/AP_Baro/AP_Baro_LPS2XH.h +++ b/libraries/AP_Baro/AP_Baro_LPS2XH.h @@ -1,11 +1,17 @@ #pragma once +#include "AP_Baro_Backend.h" + +#ifndef AP_BARO_LPS2XH_ENABLED +#define AP_BARO_LPS2XH_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_BARO_LPS2XH_ENABLED + #include #include #include -#include "AP_Baro_Backend.h" - #define HAL_BARO_LPS25H_I2C_BUS 0 #ifndef HAL_BARO_LPS25H_I2C_ADDR @@ -51,3 +57,5 @@ class AP_Baro_LPS2XH : public AP_Baro_Backend enum LPS2XH_TYPE _lps2xh_type; }; + +#endif // AP_BARO_LPS2XH_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_Logging.cpp b/libraries/AP_Baro/AP_Baro_Logging.cpp index 6e84d033e0d..454be20bff2 100644 --- a/libraries/AP_Baro/AP_Baro_Logging.cpp +++ b/libraries/AP_Baro/AP_Baro_Logging.cpp @@ -1,4 +1,5 @@ #include "AP_Baro.h" + #include void AP_Baro::Write_Baro_instance(uint64_t time_us, uint8_t baro_instance) diff --git a/libraries/AP_Baro/AP_Baro_MS5611.cpp b/libraries/AP_Baro/AP_Baro_MS5611.cpp index 7ad0492be28..295cd2e9e4c 100644 --- a/libraries/AP_Baro/AP_Baro_MS5611.cpp +++ b/libraries/AP_Baro/AP_Baro_MS5611.cpp @@ -14,11 +14,14 @@ */ #include "AP_Baro_MS5611.h" +#if AP_BARO_MS56XX_ENABLED + #include #include #include #include +#include extern const AP_HAL::HAL &hal; @@ -92,6 +95,13 @@ bool AP_Baro_MS56XX::_init() _dev->transfer(&CMD_MS56XX_RESET, 1, nullptr, 0); hal.scheduler->delay(4); + + /* + cope with vendors substituting a MS5607 for a MS5611 on Pixhawk1 'clone' boards + */ + if (_ms56xx_type == BARO_MS5611 && _frontend.option_enabled(AP_Baro::Options::TreatMS5611AsMS5607)) { + _ms56xx_type = BARO_MS5607; + } const char *name = "MS5611"; switch (_ms56xx_type) { @@ -134,7 +144,23 @@ bool AP_Baro_MS56XX::_init() _instance = _frontend.register_sensor(); - _dev->set_device_type(DEVTYPE_BARO_MS5611); + enum DevTypes devtype = DEVTYPE_BARO_MS5611; + switch (_ms56xx_type) { + case BARO_MS5607: + devtype = DEVTYPE_BARO_MS5607; + break; + case BARO_MS5611: + devtype = DEVTYPE_BARO_MS5611; + break; + case BARO_MS5837: + devtype = DEVTYPE_BARO_MS5837; + break; + case BARO_MS5637: + devtype = DEVTYPE_BARO_MS5637; + break; + } + + _dev->set_device_type(devtype); set_bus_id(_instance, _dev->get_bus_id()); if (_ms56xx_type == BARO_MS5837) { @@ -490,3 +516,5 @@ void AP_Baro_MS56XX::_calculate_5837() _copy_to_frontend(_instance, (float)pressure, temperature); } + +#endif // AP_BARO_MS56XX_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_MS5611.h b/libraries/AP_Baro/AP_Baro_MS5611.h index 146ceff37fd..4115a3f8a33 100644 --- a/libraries/AP_Baro/AP_Baro_MS5611.h +++ b/libraries/AP_Baro/AP_Baro_MS5611.h @@ -2,6 +2,12 @@ #include "AP_Baro_Backend.h" +#ifndef AP_BARO_MS56XX_ENABLED +#define AP_BARO_MS56XX_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_BARO_MS56XX_ENABLED + #include #include #include @@ -38,9 +44,23 @@ class AP_Baro_MS56XX : public AP_Baro_Backend BARO_MS5837 = 3 }; - static AP_Baro_Backend *probe(AP_Baro &baro, AP_HAL::OwnPtr dev, enum MS56XX_TYPE ms56xx_type = BARO_MS5611); + static AP_Baro_Backend *probe_5611(AP_Baro &baro, AP_HAL::OwnPtr dev) { + return probe(baro, std::move(dev), BARO_MS5611); + } + static AP_Baro_Backend *probe_5607(AP_Baro &baro, AP_HAL::OwnPtr dev) { + return probe(baro, std::move(dev), BARO_MS5607); + } + static AP_Baro_Backend *probe_5637(AP_Baro &baro, AP_HAL::OwnPtr dev) { + return probe(baro, std::move(dev), BARO_MS5637); + } + static AP_Baro_Backend *probe_5837(AP_Baro &baro, AP_HAL::OwnPtr dev) { + return probe(baro, std::move(dev), BARO_MS5837); + } + + static AP_Baro_Backend *probe(AP_Baro &baro, AP_HAL::OwnPtr dev, enum MS56XX_TYPE ms56xx_type=BARO_MS5611); private: + /* * Update @accum and @count with the new sample in @val, taking into * account a maximum number of samples given by @max_count; in case @@ -90,3 +110,5 @@ class AP_Baro_MS56XX : public AP_Baro_Backend enum MS56XX_TYPE _ms56xx_type; }; + +#endif // AP_BARO_MS56XX_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_MSP.cpp b/libraries/AP_Baro/AP_Baro_MSP.cpp index 128995148ae..6112e9a4a6e 100644 --- a/libraries/AP_Baro/AP_Baro_MSP.cpp +++ b/libraries/AP_Baro/AP_Baro_MSP.cpp @@ -1,6 +1,6 @@ #include "AP_Baro_MSP.h" -#if HAL_MSP_BARO_ENABLED +#if AP_BARO_MSP_ENABLED AP_Baro_MSP::AP_Baro_MSP(AP_Baro &baro, uint8_t _msp_instance) : AP_Baro_Backend(baro) @@ -33,4 +33,4 @@ void AP_Baro_MSP::handle_msp(const MSP::msp_baro_data_message_t &pkt) count++; } -#endif // HAL_MSP_BARO_ENABLED +#endif // AP_BARO_MSP_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_MSP.h b/libraries/AP_Baro/AP_Baro_MSP.h index 1ddba3ece43..19e65c99099 100644 --- a/libraries/AP_Baro/AP_Baro_MSP.h +++ b/libraries/AP_Baro/AP_Baro_MSP.h @@ -5,9 +5,11 @@ #include "AP_Baro_Backend.h" -#define MOVING_AVERAGE_WEIGHT 0.20f // a 5 samples moving average +// AP_BARO_MSP_ENABLED is defined in AP_Baro.h + +#if AP_BARO_MSP_ENABLED -#if HAL_MSP_BARO_ENABLED +#define MOVING_AVERAGE_WEIGHT 0.20f // a 5 samples moving average class AP_Baro_MSP : public AP_Baro_Backend { @@ -24,4 +26,4 @@ class AP_Baro_MSP : public AP_Baro_Backend uint16_t count; }; -#endif // HAL_MSP_BARO_ENABLED +#endif // AP_BARO_MSP_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_SITL.cpp b/libraries/AP_Baro/AP_Baro_SITL.cpp index f160cf8affe..ec05c90aa99 100644 --- a/libraries/AP_Baro/AP_Baro_SITL.cpp +++ b/libraries/AP_Baro/AP_Baro_SITL.cpp @@ -66,7 +66,7 @@ void AP_Baro_SITL::_timer() return; } - sim_alt += _sitl->baro[_instance].drift * now / 1000.0f; + sim_alt += _sitl->baro[_instance].drift * now * 0.001f; sim_alt += _sitl->baro[_instance].noise * rand_float(); // add baro glitch diff --git a/libraries/AP_Baro/AP_Baro_SPL06.cpp b/libraries/AP_Baro/AP_Baro_SPL06.cpp index fe29dfc2a38..92fc19cf50c 100644 --- a/libraries/AP_Baro/AP_Baro_SPL06.cpp +++ b/libraries/AP_Baro/AP_Baro_SPL06.cpp @@ -14,6 +14,8 @@ */ #include "AP_Baro_SPL06.h" +#if AP_BARO_SPL06_ENABLED + #include extern const AP_HAL::HAL &hal; @@ -246,3 +248,5 @@ void AP_Baro_SPL06::_update_pressure(int32_t press_raw) _pressure_sum += press_comp; _pressure_count++; } + +#endif // AP_BARO_SPL06_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_SPL06.h b/libraries/AP_Baro/AP_Baro_SPL06.h index c57cb7e829e..6c7f1480977 100644 --- a/libraries/AP_Baro/AP_Baro_SPL06.h +++ b/libraries/AP_Baro/AP_Baro_SPL06.h @@ -1,11 +1,17 @@ #pragma once +#include "AP_Baro_Backend.h" + +#ifndef AP_BARO_SPL06_ENABLED +#define AP_BARO_SPL06_ENABLED AP_BARO_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_BARO_SPL06_ENABLED + #include #include #include -#include "AP_Baro_Backend.h" - #ifndef HAL_BARO_SPL06_I2C_ADDR #define HAL_BARO_SPL06_I2C_ADDR (0x76) #endif @@ -45,3 +51,5 @@ class AP_Baro_SPL06 : public AP_Baro_Backend int32_t _c00, _c10; int16_t _c0, _c1, _c01, _c11, _c20, _c21, _c30; }; + +#endif // AP_BARO_SPL06_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_UAVCAN.cpp b/libraries/AP_Baro/AP_Baro_UAVCAN.cpp index 617b5d88739..0c7c46e5cc8 100644 --- a/libraries/AP_Baro/AP_Baro_UAVCAN.cpp +++ b/libraries/AP_Baro/AP_Baro_UAVCAN.cpp @@ -1,9 +1,7 @@ -#include - -#if HAL_ENABLE_LIBUAVCAN_DRIVERS - #include "AP_Baro_UAVCAN.h" +#if AP_BARO_UAVCAN_ENABLED + #include #include @@ -18,7 +16,7 @@ extern const AP_HAL::HAL& hal; UC_REGISTRY_BINDER(PressureCb, uavcan::equipment::air_data::StaticPressure); UC_REGISTRY_BINDER(TemperatureCb, uavcan::equipment::air_data::StaticTemperature); -AP_Baro_UAVCAN::DetectedModules AP_Baro_UAVCAN::_detected_modules[] = {0}; +AP_Baro_UAVCAN::DetectedModules AP_Baro_UAVCAN::_detected_modules[]; HAL_Semaphore AP_Baro_UAVCAN::_sem_registry; /* @@ -192,5 +190,4 @@ void AP_Baro_UAVCAN::update(void) } } -#endif // HAL_ENABLE_LIBUAVCAN_DRIVERS - +#endif // AP_BARO_UAVCAN_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_UAVCAN.h b/libraries/AP_Baro/AP_Baro_UAVCAN.h index 5b368f4585b..9ac8af6dfc3 100644 --- a/libraries/AP_Baro/AP_Baro_UAVCAN.h +++ b/libraries/AP_Baro/AP_Baro_UAVCAN.h @@ -2,6 +2,12 @@ #include "AP_Baro_Backend.h" +#ifndef AP_BARO_UAVCAN_ENABLED +#define AP_BARO_UAVCAN_ENABLED (AP_BARO_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_LIBUAVCAN_DRIVERS) +#endif + +#if AP_BARO_UAVCAN_ENABLED + #include class PressureCb; @@ -44,3 +50,5 @@ class AP_Baro_UAVCAN : public AP_Baro_Backend { static HAL_Semaphore _sem_registry; }; + +#endif // AP_BARO_UAVCAN_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_Wind.cpp b/libraries/AP_Baro/AP_Baro_Wind.cpp index f8694c7050c..5050810d1ff 100644 --- a/libraries/AP_Baro/AP_Baro_Wind.cpp +++ b/libraries/AP_Baro/AP_Baro_Wind.cpp @@ -15,7 +15,7 @@ const AP_Param::GroupInfo AP_Baro::WindCoeff::var_info[] = { // @Param: FWD // @DisplayName: Pressure error coefficient in positive X direction (forward) - // @Description: This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the X body axis. If the baro height estimate rises during forwards flight, then this will be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_BCOEF_X and EK3_BCOEF_Y parameters have been tuned. + // @Description: This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the X body axis. If the baro height estimate rises during forwards flight, then this will be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned. // @Range: -1.0 1.0 // @Increment: 0.05 // @User: Advanced @@ -23,7 +23,7 @@ const AP_Param::GroupInfo AP_Baro::WindCoeff::var_info[] = { // @Param: BCK // @DisplayName: Pressure error coefficient in negative X direction (backwards) - // @Description: This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the X body axis. If the baro height estimate rises during backwards flight, then this will be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_BCOEF_X and EK3_BCOEF_Y parameters have been tuned. + // @Description: This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the X body axis. If the baro height estimate rises during backwards flight, then this will be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned. // @Range: -1.0 1.0 // @Increment: 0.05 // @User: Advanced @@ -31,7 +31,7 @@ const AP_Param::GroupInfo AP_Baro::WindCoeff::var_info[] = { // @Param: RGT // @DisplayName: Pressure error coefficient in positive Y direction (right) - // @Description: This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the Y body axis. If the baro height estimate rises during sideways flight to the right, then this should be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_BCOEF_X and EK3_BCOEF_Y parameters have been tuned. + // @Description: This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the Y body axis. If the baro height estimate rises during sideways flight to the right, then this should be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned. // @Range: -1.0 1.0 // @Increment: 0.05 // @User: Advanced @@ -39,7 +39,7 @@ const AP_Param::GroupInfo AP_Baro::WindCoeff::var_info[] = { // @Param: LFT // @DisplayName: Pressure error coefficient in negative Y direction (left) - // @Description: This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the Y body axis. If the baro height estimate rises during sideways flight to the left, then this should be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_BCOEF_X and EK3_BCOEF_Y parameters have been tuned. + // @Description: This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the Y body axis. If the baro height estimate rises during sideways flight to the left, then this should be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned. // @Range: -1.0 1.0 // @Increment: 0.05 // @User: Advanced diff --git a/libraries/AP_BattMonitor/AP_BattMonitor.cpp b/libraries/AP_BattMonitor/AP_BattMonitor.cpp index 3ca95b9cb57..e125bbd0cca 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor.cpp @@ -16,6 +16,7 @@ #include "AP_BattMonitor_INA2xx.h" #include "AP_BattMonitor_LTC2946.h" #include "AP_BattMonitor_Torqeedo.h" +#include "AP_BattMonitor_FuelLevel_Analog.h" #include @@ -49,6 +50,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Sum.cpp // @Group: _ // @Path: AP_BattMonitor_UAVCAN.cpp + // @Group: _ + // @Path: AP_BattMonitor_FuelLevel_Analog.cpp AP_SUBGROUPVARPTR(drivers[0], "_", 41, AP_BattMonitor, backend_var_info[0]), #if AP_BATT_MONITOR_MAX_INSTANCES > 1 @@ -64,6 +67,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Sum.cpp // @Group: 2_ // @Path: AP_BattMonitor_UAVCAN.cpp + // @Group: 2_ + // @Path: AP_BattMonitor_FuelLevel_Analog.cpp AP_SUBGROUPVARPTR(drivers[1], "2_", 42, AP_BattMonitor, backend_var_info[1]), #endif @@ -80,6 +85,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Sum.cpp // @Group: 3_ // @Path: AP_BattMonitor_UAVCAN.cpp + // @Group: 3_ + // @Path: AP_BattMonitor_FuelLevel_Analog.cpp AP_SUBGROUPVARPTR(drivers[2], "3_", 43, AP_BattMonitor, backend_var_info[2]), #endif @@ -96,6 +103,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Sum.cpp // @Group: 4_ // @Path: AP_BattMonitor_UAVCAN.cpp + // @Group: 4_ + // @Path: AP_BattMonitor_FuelLevel_Analog.cpp AP_SUBGROUPVARPTR(drivers[3], "4_", 44, AP_BattMonitor, backend_var_info[3]), #endif @@ -112,6 +121,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Sum.cpp // @Group: 5_ // @Path: AP_BattMonitor_UAVCAN.cpp + // @Group: 5_ + // @Path: AP_BattMonitor_FuelLevel_Analog.cpp AP_SUBGROUPVARPTR(drivers[4], "5_", 45, AP_BattMonitor, backend_var_info[4]), #endif @@ -128,6 +139,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Sum.cpp // @Group: 6_ // @Path: AP_BattMonitor_UAVCAN.cpp + // @Group: 6_ + // @Path: AP_BattMonitor_FuelLevel_Analog.cpp AP_SUBGROUPVARPTR(drivers[5], "6_", 46, AP_BattMonitor, backend_var_info[5]), #endif @@ -144,6 +157,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Sum.cpp // @Group: 7_ // @Path: AP_BattMonitor_UAVCAN.cpp + // @Group: 7_ + // @Path: AP_BattMonitor_FuelLevel_Analog.cpp AP_SUBGROUPVARPTR(drivers[6], "7_", 47, AP_BattMonitor, backend_var_info[6]), #endif @@ -160,6 +175,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Sum.cpp // @Group: 8_ // @Path: AP_BattMonitor_UAVCAN.cpp + // @Group: 8_ + // @Path: AP_BattMonitor_FuelLevel_Analog.cpp AP_SUBGROUPVARPTR(drivers[7], "8_", 48, AP_BattMonitor, backend_var_info[7]), #endif @@ -176,6 +193,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Sum.cpp // @Group: 9_ // @Path: AP_BattMonitor_UAVCAN.cpp + // @Group: 9_ + // @Path: AP_BattMonitor_FuelLevel_Analog.cpp AP_SUBGROUPVARPTR(drivers[8], "9_", 49, AP_BattMonitor, backend_var_info[8]), #endif @@ -267,14 +286,21 @@ AP_BattMonitor::init() case Type::Sum: drivers[instance] = new AP_BattMonitor_Sum(*this, state[instance], _params[instance], instance); break; -#if AP_BATTMON_FUEL_ENABLE +#if AP_BATTMON_FUELFLOW_ENABLE case Type::FuelFlow: drivers[instance] = new AP_BattMonitor_FuelFlow(*this, state[instance], _params[instance]); break; +#endif // AP_BATTMON_FUELFLOW_ENABLE +#if AP_BATTMON_FUELLEVEL_PWM_ENABLE case Type::FuelLevel_PWM: drivers[instance] = new AP_BattMonitor_FuelLevel_PWM(*this, state[instance], _params[instance]); break; -#endif // AP_BATTMON_FUEL_ENABLE +#endif // AP_BATTMON_FUELLEVEL_PWM_ENABLE +#if AP_BATTMON_FUELLEVEL_ANALOG_ENABLE + case Type::FuelLevel_Analog: + drivers[instance] = new AP_BattMonitor_FuelLevel_Analog(*this, state[instance], _params[instance]); + break; +#endif // AP_BATTMON_FUELLEVEL_ANALOG_ENABLE #if HAL_GENERATOR_ENABLED case Type::GENERATOR_ELEC: drivers[instance] = new AP_BattMonitor_Generator_Elec(*this, state[instance], _params[instance]); @@ -365,6 +391,7 @@ void AP_BattMonitor::convert_dynamic_param_groups(uint8_t instance) ap_var_type type; const char* new_name; } conversion_table[] = { + // PARAMETER_CONVERSION - Added: Aug-2021 { 2, AP_PARAM_INT8, "VOLT_PIN" }, { 3, AP_PARAM_INT8, "CURR_PIN" }, { 4, AP_PARAM_FLOAT, "VOLT_MULT" }, @@ -438,6 +465,19 @@ float AP_BattMonitor::voltage_resting_estimate(uint8_t instance) const } } +/// voltage - returns battery voltage in volts for GCS, may be resting voltage if option enabled +float AP_BattMonitor::gcs_voltage(uint8_t instance) const +{ + if ((_params[instance]._options.get() & uint32_t(AP_BattMonitor_Params::Options::GCS_Resting_Voltage)) != 0) { + return voltage_resting_estimate(instance); + } + if (instance < _num_instances) { + return state[instance].voltage; + } else { + return 0.0f; + } +} + /// current_amps - returns the instantaneous current draw in amperes bool AP_BattMonitor::current_amps(float ¤t, uint8_t instance) const { if ((instance < _num_instances) && (drivers[instance] != nullptr) && drivers[instance]->has_current()) { @@ -726,6 +766,19 @@ uint32_t AP_BattMonitor::get_mavlink_fault_bitmask(const uint8_t instance) const return drivers[instance]->get_mavlink_fault_bitmask(); } +/* + check that all configured battery monitors are healthy + */ +bool AP_BattMonitor::healthy() const +{ + for (uint8_t i=0; i< _num_instances; i++) { + if (get_type(i) != Type::NONE && !healthy(i)) { + return false; + } + } + return true; +} + namespace AP { AP_BattMonitor &battery() diff --git a/libraries/AP_BattMonitor/AP_BattMonitor.h b/libraries/AP_BattMonitor/AP_BattMonitor.h index 4df2770d1fc..f4eaa685184 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor.h @@ -31,8 +31,16 @@ #define AP_BATTMON_SMBUS_ENABLE 1 #endif -#ifndef AP_BATTMON_FUEL_ENABLE -#define AP_BATTMON_FUEL_ENABLE 1 +#ifndef AP_BATTMON_FUELFLOW_ENABLE +#define AP_BATTMON_FUELFLOW_ENABLE (BOARD_FLASH_SIZE > 1024) +#endif + +#ifndef AP_BATTMON_FUELLEVEL_PWM_ENABLE +#define AP_BATTMON_FUELLEVEL_PWM_ENABLE (BOARD_FLASH_SIZE > 1024) +#endif + +#ifndef AP_BATTMON_FUELLEVEL_ANALOG_ENABLE +#define AP_BATTMON_FUELLEVEL_ANALOG_ENABLE (BOARD_FLASH_SIZE > 1024) #endif // declare backend class @@ -48,6 +56,7 @@ class AP_BattMonitor_Generator; class AP_BattMonitor_INA2XX; class AP_BattMonitor_LTC2946; class AP_BattMonitor_Torqeedo; +class AP_BattMonitor_FuelLevel_Analog; class AP_BattMonitor { @@ -67,6 +76,7 @@ class AP_BattMonitor friend class AP_BattMonitor_LTC2946; friend class AP_BattMonitor_Torqeedo; + friend class AP_BattMonitor_FuelLevel_Analog; public: @@ -101,6 +111,7 @@ class AP_BattMonitor INA2XX = 21, LTC2946 = 22, Torqeedo = 23, + FuelLevel_Analog = 24, }; FUNCTOR_TYPEDEF(battery_failsafe_handler_fn_t, void, const char *, const int8_t); @@ -156,12 +167,18 @@ class AP_BattMonitor // healthy - returns true if monitor is functioning bool healthy(uint8_t instance) const; - bool healthy() const { return healthy(AP_BATT_PRIMARY_INSTANCE); } + + // return true if all configured battery monitors are healthy + bool healthy() const; /// voltage - returns battery voltage in volts float voltage(uint8_t instance) const; float voltage() const { return voltage(AP_BATT_PRIMARY_INSTANCE); } + // voltage for a GCS, may be resistance compensated + float gcs_voltage(uint8_t instance) const; + float gcs_voltage(void) const { return gcs_voltage(AP_BATT_PRIMARY_INSTANCE); } + /// get voltage with sag removed (based on battery current draw and resistance) /// this will always be greater than or equal to the raw voltage float voltage_resting_estimate(uint8_t instance) const; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Analog.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Analog.cpp index a37257587bc..e43e400887e 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Analog.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Analog.cpp @@ -82,8 +82,8 @@ AP_BattMonitor_Analog::read() // read current if (has_current()) { // calculate time since last current read - uint32_t tnow = AP_HAL::micros(); - float dt = tnow - _state.last_time_micros; + const uint32_t tnow = AP_HAL::micros(); + const uint32_t dt_us = tnow - _state.last_time_micros; // this copes with changing the pin at runtime _state.healthy &= _curr_pin_analog_source->set_pin(_curr_pin); @@ -91,12 +91,7 @@ AP_BattMonitor_Analog::read() // read current _state.current_amps = (_curr_pin_analog_source->voltage_average() - _curr_amp_offset) * _curr_amp_per_volt; - // update total current drawn since startup - if (_state.last_time_micros != 0 && dt < 2000000.0f) { - float mah = calculate_mah(_state.current_amps, dt); - _state.consumed_mah += mah; - _state.consumed_wh += 0.001f * mah * _state.voltage; - } + update_consumed(_state, dt_us); // record time _state.last_time_micros = tnow; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp index edce254eb16..50b8313d421 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp @@ -75,7 +75,7 @@ void AP_BattMonitor_Backend::update_resistance_estimate() // calculate time since last update uint32_t now = AP_HAL::millis(); - float loop_interval = (now - _resistance_timer_ms) / 1000.0f; + float loop_interval = (now - _resistance_timer_ms) * 0.001f; _resistance_timer_ms = now; // estimate short-term resistance @@ -176,7 +176,8 @@ bool AP_BattMonitor_Backend::arming_checks(char * buffer, size_t buflen) const is_positive(_params._low_voltage) && (_params._low_voltage < _params._critical_voltage); - bool result = update_check(buflen, buffer, below_arming_voltage, "below minimum arming voltage"); + bool result = update_check(buflen, buffer, !_state.healthy, "unhealthy"); + result = result && update_check(buflen, buffer, below_arming_voltage, "below minimum arming voltage"); result = result && update_check(buflen, buffer, below_arming_capacity, "below minimum arming capacity"); result = result && update_check(buflen, buffer, low_voltage, "low voltage failsafe"); result = result && update_check(buflen, buffer, low_capacity, "low capacity failsafe"); @@ -253,3 +254,16 @@ bool AP_BattMonitor_Backend::reset_remaining(float percentage) return true; } + +/* + update consumed mAh and Wh + */ +void AP_BattMonitor_Backend::update_consumed(AP_BattMonitor::BattMonitor_State &state, uint32_t dt_us) +{ + // update total current drawn since startup + if (state.last_time_micros != 0 && dt_us < 2000000) { + const float mah = calculate_mah(state.current_amps, dt_us); + state.consumed_mah += mah; + state.consumed_wh += 0.001 * mah * state.voltage; + } +} diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Backend.h b/libraries/AP_BattMonitor/AP_BattMonitor_Backend.h index 5d8d81f5aa7..0c1a0d9eaba 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Backend.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Backend.h @@ -15,7 +15,6 @@ #pragma once #include -#include #include "AP_BattMonitor.h" class AP_BattMonitor_Backend @@ -90,6 +89,7 @@ class AP_BattMonitor_Backend // checks what failsafes could be triggered void check_failsafe_types(bool &low_voltage, bool &low_capacity, bool &critical_voltage, bool &critical_capacity) const; + void update_consumed(AP_BattMonitor::BattMonitor_State &state, uint32_t dt_us); private: // resistance estimate diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Bebop.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Bebop.cpp index c43e41671ec..eb12e427126 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Bebop.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Bebop.cpp @@ -177,7 +177,7 @@ void AP_BattMonitor_Bebop::read(void) } /* get battery voltage observed by cypress */ - vbat_raw = (float)data.batt_mv / 1000.0f; + vbat_raw = (float)data.batt_mv * 0.001f; /* do not compute battery status on ramping or braking transition */ if (data.status == BEBOP_BLDC_STATUS_RAMPING || @@ -214,7 +214,7 @@ void AP_BattMonitor_Bebop::read(void) _state.voltage = vbat; _state.last_time_micros = tnow; _state.healthy = true; - _state.consumed_mah = capacity - (remaining * capacity) / 100.0f; + _state.consumed_mah = capacity - (remaining * capacity) * 0.01f; } #endif diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_Analog.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_Analog.cpp new file mode 100644 index 00000000000..db0724ed2ef --- /dev/null +++ b/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_Analog.cpp @@ -0,0 +1,118 @@ +/* + * This file is free software: you can redistribute it and/or modify it + * under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program. If not, see . + * + * Code by Charlie Johnson + */ + +#include +#include +#include "AP_BattMonitor_FuelLevel_Analog.h" + +extern const AP_HAL::HAL& hal; + +const AP_Param::GroupInfo AP_BattMonitor_FuelLevel_Analog::var_info[] = { + + // @Param: FL_VLT_MIN + // @DisplayName: Empty fuel level voltage + // @Description: The voltage seen on the analog pin when the fuel tank is empty. Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS. + // @Range: 0.01 10 + // @Units: V + // @User: Advanced + AP_GROUPINFO("FL_VLT_MIN", 40, AP_BattMonitor_FuelLevel_Analog, _fuel_level_empty_voltage, 0.5), + + // @Param: FL_V_MULT + // @DisplayName: Fuel level voltage multiplier + // @Description: Voltage multiplier to determine what the full tank voltage reading is. This is calculated as 1 / (Voltage_Full - Voltage_Empty) Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS. + // @Range: 0.01 10 + // @User: Advanced + AP_GROUPINFO("FL_V_MULT", 41, AP_BattMonitor_FuelLevel_Analog, _fuel_level_voltage_mult, 0.5), + + // @Param: FL_FLTR + // @DisplayName: Fuel level filter frequency + // @Description: Filter frequency in Hertz where a low pass filter is used. This is used to filter out tank slosh from the fuel level reading. A value of -1 disables the filter and unfiltered voltage is used to determine the fuel level. The suggested values at in the range of 0.2 Hz to 0.5 Hz. + // @Range: -1 1 + // @User: Advanced + // @Units: Hz + // @RebootRequired: True + AP_GROUPINFO("FL_FLTR", 42, AP_BattMonitor_FuelLevel_Analog, _fuel_level_filter_frequency, 0.3), + + // @Param: FL_PIN + // @DisplayName: Fuel level analog pin number + // @Description: Analog input pin that fuel level sensor is connected to. Airspeed ports can be used for Analog input. When using analog pin 103, the maximum value of the input in 3.3V. + // @Values: -1:Not Used,11:Pixracer,13:Pixhawk ADC4,14:Pixhawk ADC3,15:Pixhawk ADC6/Pixhawk2 ADC,103:Pixhawk SBUS + AP_GROUPINFO("FL_PIN", 43, AP_BattMonitor_FuelLevel_Analog, _pin, -1), + + // Param indexes must be between 40 and 49 to avoid conflict with other battery monitor param tables loaded by pointer + + AP_GROUPEND +}; + +// Constructor +AP_BattMonitor_FuelLevel_Analog::AP_BattMonitor_FuelLevel_Analog(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, AP_BattMonitor_Params ¶ms) : + AP_BattMonitor_Backend(mon, mon_state, params) +{ + AP_Param::setup_object_defaults(this, var_info); + _state.var_info = var_info; + + _analog_source = hal.analogin->channel(_pin); + + // create a low pass filter + // use a pole at 0.3 Hz if the filter is not being used + _voltage_filter.set_cutoff_frequency((_fuel_level_filter_frequency >= 0) ? _fuel_level_filter_frequency : 0.3f); +} + +/* + read - read the "voltage" and "current" +*/ +void AP_BattMonitor_FuelLevel_Analog::read() +{ + if (_analog_source == nullptr) { + return; + } + + if (!_analog_source->set_pin(_pin)) { + _state.healthy = false; + return; + } + _state.healthy = true; + + // get a dt and a timestamp + const uint32_t tnow = AP_HAL::micros(); + const uint32_t dt_us = tnow - _state.last_time_micros; + + // get voltage from an ADC pin and filter it + const float voltage = _analog_source->voltage_average(); + const float filtered_voltage = _voltage_filter.apply(voltage, float(dt_us) * 1.0e-6f); + const float &voltage_used = (_fuel_level_filter_frequency >= 0) ? filtered_voltage : voltage; + + // output the ADC voltage to the voltage field for easier calibration of sensors + // also output filtered voltage as a measure of tank slosh filtering + // this could be useful for tuning the LPF + _state.voltage = voltage; + _state.current_amps = filtered_voltage; + + // this driver assumes that CAPACITY is set to tank volume in millilitres. + // _fuel_level_voltage_mult is calculated by the user as 1 / (full_voltage - empty_voltage) + const float fuel_level_ratio = (voltage_used - _fuel_level_empty_voltage) * _fuel_level_voltage_mult; + const float fuel_level_used_ratio = 1.0 - fuel_level_ratio; + + // map consumed_mah to consumed millilitres + _state.consumed_mah = fuel_level_used_ratio * _params._pack_capacity; + + // map consumed_wh using fixed voltage of 1 + _state.consumed_wh = _state.consumed_mah; + + // record time + _state.last_time_micros = tnow; +} diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_Analog.h b/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_Analog.h new file mode 100644 index 00000000000..fb4fc6290b7 --- /dev/null +++ b/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_Analog.h @@ -0,0 +1,54 @@ +/* + * This file is free software: you can redistribute it and/or modify it + * under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program. If not, see . + * + * Code by Charlie Johnson + */ + +#pragma once + +#include +#include "AP_BattMonitor.h" +#include "AP_BattMonitor_Backend.h" + +class AP_BattMonitor_FuelLevel_Analog : public AP_BattMonitor_Backend +{ +public: + + // Constructor + AP_BattMonitor_FuelLevel_Analog(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, AP_BattMonitor_Params ¶ms); + + static const struct AP_Param::GroupInfo var_info[]; + + // Read the battery voltage and current. Should be called at 10hz + void read() override; + + // returns true if battery monitor provides consumed energy info + bool has_consumed_energy() const override { return true; } + + // returns true if battery monitor provides current info + bool has_current() const override { return true; } + + void init(void) override {} + +private: + + AP_Float _fuel_level_empty_voltage; + AP_Float _fuel_level_voltage_mult; + AP_Float _fuel_level_filter_frequency; + AP_Int8 _pin; + + AP_HAL::AnalogSource *_analog_source; + + LowPassFilterFloat _voltage_filter; +}; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_INA2xx.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_INA2xx.cpp index 84f780ee2a5..55654e73eb0 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_INA2xx.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_INA2xx.cpp @@ -61,14 +61,19 @@ void AP_BattMonitor_INA2XX::init(void) if (!dev) { return; } + // register now and configure in the timer callbacks + dev->register_periodic_callback(25000, FUNCTOR_BIND_MEMBER(&AP_BattMonitor_INA2XX::timer, void)); +} - int16_t config = 0; +void AP_BattMonitor_INA2XX::configure(void) +{ WITH_SEMAPHORE(dev->get_semaphore()); + + int16_t config = 0; if (!write_word(REG_CONFIG, REG_CONFIG_RESET) || !write_word(REG_CONFIG, REG_CONFIG_DEFAULT) || !read_word(REG_CONFIG, config) || config != REG_CONFIG_DEFAULT) { - GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "INA2XX: Failed to find device 0x%04x", unsigned(config)); return; } @@ -81,16 +86,10 @@ void AP_BattMonitor_INA2XX::init(void) if (!write_word(REG_CONFIG, REG_CONFIG_RESET) || // reset !write_word(REG_CONFIG, conf) || !write_word(REG_CALIBRATION, cal)) { - GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "INA2XX: Failed to configure device"); return; } - - GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "INA2XX: found monitor on I2C:%u:%02x", unsigned(i2c_bus), unsigned(i2c_address)); - - if (dev) { - dev->register_periodic_callback(25000, FUNCTOR_BIND_MEMBER(&AP_BattMonitor_INA2XX::timer, void)); - } + configured = true; } /// read the battery_voltage and current, should be called at 10hz @@ -109,15 +108,11 @@ void AP_BattMonitor_INA2XX::read(void) accumulate.count = 0; const uint32_t tnow = AP_HAL::micros(); - const float dt = tnow - _state.last_time_micros; + const uint32_t dt_us = tnow - _state.last_time_micros; // update total current drawn since startup - if (_state.last_time_micros != 0 && dt < 2000000.0) { - // .0002778 is 1/3600 (conversion to hours) - const float mah = _state.current_amps * dt * 0.0000002778; - _state.consumed_mah += mah; - _state.consumed_wh += 0.001 * mah * _state.voltage; - } + update_consumed(_state, dt_us); + _state.last_time_micros = tnow; } @@ -150,11 +145,33 @@ bool AP_BattMonitor_INA2XX::write_word(const uint8_t reg, const uint16_t data) c void AP_BattMonitor_INA2XX::timer(void) { + // allow for power-on after boot + if (!configured) { + uint32_t now = AP_HAL::millis(); + if (now - last_configure_ms > 200) { + // try contacting the device at 5Hz + last_configure_ms = now; + configure(); + } + if (!configured) { + // waiting for the device to respond + return; + } + } + int16_t bus_voltage, current; + if (!read_word(REG_BUS_VOLTAGE, bus_voltage) || !read_word(REG_CURRENT, current)) { + failed_reads++; + if (failed_reads > 10) { + // device has disconnected, we need to reconfigure it + configured = false; + } return; } + failed_reads = 0; + WITH_SEMAPHORE(accumulate.sem); accumulate.volt_sum += bus_voltage * voltage_LSB; accumulate.current_sum += current * current_LSB; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_INA2xx.h b/libraries/AP_BattMonitor/AP_BattMonitor_INA2xx.h index 8c4b77a2275..d70f963187e 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_INA2xx.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_INA2xx.h @@ -23,23 +23,27 @@ class AP_BattMonitor_INA2XX : public AP_BattMonitor_Backend bool has_cell_voltages() const override { return false; } bool has_temperature() const override { return false; } bool has_current() const override { return true; } - bool reset_remaining(float percentage) override { return false; } bool get_cycle_count(uint16_t &cycles) const override { return false; } - virtual void init(void) override; - virtual void read() override; + void init(void) override; + void read() override; static const struct AP_Param::GroupInfo var_info[]; private: AP_HAL::OwnPtr dev; + void configure(void); bool read_word(const uint8_t reg, int16_t& data) const; bool write_word(const uint8_t reg, const uint16_t data) const; void timer(void); AP_Int8 i2c_bus; AP_Int8 i2c_address; + bool configured; + bool callback_registered; + uint32_t failed_reads; + uint32_t last_configure_ms; struct { uint16_t count; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_LTC2946.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_LTC2946.cpp index 418698436fe..3274a82da65 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_LTC2946.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_LTC2946.cpp @@ -67,15 +67,11 @@ void AP_BattMonitor_LTC2946::read(void) accumulate.count = 0; const uint32_t tnow = AP_HAL::micros(); - const float dt = tnow - _state.last_time_micros; + const uint32_t dt_us = tnow - _state.last_time_micros; // update total current drawn since startup - if (_state.last_time_micros != 0 && dt < 2000000.0) { - // .0002778 is 1/3600 (conversion to hours) - const float mah = _state.current_amps * dt * 0.0000002778; - _state.consumed_mah += mah; - _state.consumed_wh += 0.001 * mah * _state.voltage; - } + update_consumed(_state, dt_us); + _state.last_time_micros = tnow; } diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_LTC2946.h b/libraries/AP_BattMonitor/AP_BattMonitor_LTC2946.h index c3497e9df89..aa13b75d7ec 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_LTC2946.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_LTC2946.h @@ -18,7 +18,6 @@ class AP_BattMonitor_LTC2946 : public AP_BattMonitor_Backend bool has_cell_voltages() const override { return false; } bool has_temperature() const override { return false; } bool has_current() const override { return true; } - bool reset_remaining(float percentage) override { return false; } bool get_cycle_count(uint16_t &cycles) const override { return false; } virtual void init(void) override; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp index 2ea402bc68a..87b9a2a541f 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp @@ -13,7 +13,7 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = { // @Param: MONITOR // @DisplayName: Battery monitoring // @Description: Controls enabling monitoring of the battery's voltage and current - // @Values: 0:Disabled,3:Analog Voltage Only,4:Analog Voltage and Current,5:Solo,6:Bebop,7:SMBus-Generic,8:DroneCAN-BatteryInfo,9:ESC,10:Sum Of Selected Monitors,11:FuelFlow,12:FuelLevelPWM,13:SMBUS-SUI3,14:SMBUS-SUI6,15:NeoDesign,16:SMBus-Maxell,17:Generator-Elec,18:Generator-Fuel,19:Rotoye,20:MPPT,21:INA2XX,22:LTC2946,23:Torqeedo + // @Values: 0:Disabled,3:Analog Voltage Only,4:Analog Voltage and Current,5:Solo,6:Bebop,7:SMBus-Generic,8:DroneCAN-BatteryInfo,9:ESC,10:Sum Of Selected Monitors,11:FuelFlow,12:FuelLevelPWM,13:SMBUS-SUI3,14:SMBUS-SUI6,15:NeoDesign,16:SMBus-Maxell,17:Generator-Elec,18:Generator-Fuel,19:Rotoye,20:MPPT,21:INA2XX,22:LTC2946,23:Torqeedo,24:FuelLevelAnalog // @User: Standard // @RebootRequired: True AP_GROUPINFO_FLAGS("MONITOR", 1, AP_BattMonitor_Params, _type, int8_t(AP_BattMonitor::Type::NONE), AP_PARAM_FLAG_ENABLE), @@ -143,7 +143,7 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = { // @Param: OPTIONS // @DisplayName: Battery monitor options // @Description: This sets options to change the behaviour of the battery monitor - // @Bitmask: 0:Ignore DroneCAN SoC, 1:MPPT reports input voltage and current, 2:MPPT Powered off when disarmed, 3:MPPT Powered on when armed, 4:MPPT Powered off at boot, 5:MPPT Powered on at boot + // @Bitmask: 0:Ignore DroneCAN SoC, 1:MPPT reports input voltage and current, 2:MPPT Powered off when disarmed, 3:MPPT Powered on when armed, 4:MPPT Powered off at boot, 5:MPPT Powered on at boot, 6:Send resistance compensated voltage to GCS // @User: Advanced AP_GROUPINFO("OPTIONS", 21, AP_BattMonitor_Params, _options, 0), diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Params.h b/libraries/AP_BattMonitor/AP_BattMonitor_Params.h index 1bd3c364bfe..32ae4102238 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Params.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Params.h @@ -24,6 +24,7 @@ class AP_BattMonitor_Params { MPPT_Power_On_At_Arm = (1U<<3), // MPPT Enabled when vehicle is armed, if HW supports it MPPT_Power_Off_At_Boot = (1U<<4), // MPPT Disabled at startup (aka boot), if HW supports it MPPT_Power_On_At_Boot = (1U<<5), // MPPT Enabled at startup (aka boot), if HW supports it. If Power_Off_at_Boot is also set, the behavior is Power_Off_at_Boot + GCS_Resting_Voltage = (1U<<6), // send resistance resting voltage to GCS }; BattMonitor_LowVoltage_Source failsafe_voltage_source(void) const { return (enum BattMonitor_LowVoltage_Source)_failsafe_voltage_source.get(); } diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus.cpp index 12317ed2cd6..1eb3919cf6f 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus.cpp @@ -39,8 +39,8 @@ AP_BattMonitor_SMBus::AP_BattMonitor_SMBus(AP_BattMonitor &mon, _state.var_info = var_info; _bus.set_default(i2c_bus); - _params._serial_number = AP_BATT_SERIAL_NUMBER_DEFAULT; - _params._pack_capacity = 0; + _params._serial_number.set(AP_BATT_SERIAL_NUMBER_DEFAULT); + _params._pack_capacity.set(0); } void AP_BattMonitor_SMBus::init(void) @@ -173,6 +173,45 @@ bool AP_BattMonitor_SMBus::read_word(uint8_t reg, uint16_t& data) const return true; } +// read_block - returns number of characters read if successful, zero if unsuccessful +uint8_t AP_BattMonitor_SMBus::read_block(uint8_t reg, uint8_t* data, uint8_t len) const +{ + // get length + uint8_t bufflen; + // read byte (first byte indicates the number of bytes in the block) + if (!_dev->read_registers(reg, &bufflen, 1)) { + return 0; + } + + // sanity check length returned by smbus + if (bufflen == 0 || bufflen > len) { + return 0; + } + + // buffer to hold results (2 extra byte returned holding length and PEC) + const uint8_t read_size = bufflen + 1 + (_pec_supported ? 1 : 0); + uint8_t buff[read_size]; + + // read bytes + if (!_dev->read_registers(reg, buff, read_size)) { + return 0; + } + + // check PEC + if (_pec_supported) { + const uint8_t pec = get_PEC(_address, reg, true, buff, bufflen+1); + if (pec != buff[bufflen+1]) { + return 0; + } + } + + // copy data (excluding length & PEC) + memcpy(data, &buff[1], bufflen); + + // return success + return bufflen; +} + /// get_PEC - calculate packet error correction code of buffer uint8_t AP_BattMonitor_SMBus::get_PEC(const uint8_t i2c_addr, uint8_t cmd, bool reading, const uint8_t buff[], uint8_t len) const { diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus.h b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus.h index 3c26aba47ed..7b5330f91a9 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus.h @@ -10,7 +10,8 @@ #define AP_BATTMONITOR_SMBUS_BUS_INTERNAL 0 #define AP_BATTMONITOR_SMBUS_BUS_EXTERNAL 1 #define AP_BATTMONITOR_SMBUS_I2C_ADDR 0x0B -#define AP_BATTMONITOR_SMBUS_TIMEOUT_MICROS 5000000 // sensor becomes unhealthy if no successful readings for 5 seconds +#define AP_BATTMONITOR_SMBUS_TIMEOUT_MICROS 5000000 // sensor becomes unhealthy if no successful readings for 5 seconds +#define AP_BATTMONITOR_SMBUS_READ_BLOCK_MAXIMUM_TRANSFER 0x20 // A Block Read or Write is allowed to transfer a maximum of 32 data bytes. class AP_BattMonitor_SMBus : public AP_BattMonitor_Backend { @@ -84,6 +85,9 @@ class AP_BattMonitor_SMBus : public AP_BattMonitor_Backend // returns true if read was successful, false if failed bool read_word(uint8_t reg, uint16_t& data) const; + // read_block - returns number of characters read if successful, zero if unsuccessful + uint8_t read_block(uint8_t reg, uint8_t* data, uint8_t len) const; + // get_PEC - calculate PEC for a read or write from the battery // buff is the data that was read or will be written uint8_t get_PEC(const uint8_t i2c_addr, uint8_t cmd, bool reading, const uint8_t buff[], uint8_t len) const; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Generic.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Generic.cpp index 0e59af57d0e..9d02f308881 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Generic.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Generic.cpp @@ -3,7 +3,6 @@ #include #include "AP_BattMonitor.h" #include "AP_BattMonitor_SMBus_Generic.h" -#include uint8_t smbus_cell_ids[] = { 0x3f, // cell 1 0x3e, // cell 2 @@ -23,7 +22,6 @@ uint8_t smbus_cell_ids[] = { 0x3f, // cell 1 #endif }; -#define SMBUS_READ_BLOCK_MAXIMUM_TRANSFER 0x20 // A Block Read or Write is allowed to transfer a maximum of 32 data bytes. #define SMBUS_CELL_COUNT_CHECK_TIMEOUT 15 // check cell count for up to 15 seconds /* @@ -60,7 +58,7 @@ void AP_BattMonitor_SMBus_Generic::timer() // read voltage (V) if (read_word(BATTMONITOR_SMBUS_VOLTAGE, data)) { - _state.voltage = (float)data / 1000.0f; + _state.voltage = (float)data * 0.001f; _state.last_time_micros = tnow; _state.healthy = true; } @@ -113,7 +111,7 @@ void AP_BattMonitor_SMBus_Generic::timer() // read current (A) if (read_word(BATTMONITOR_SMBUS_CURRENT, data)) { - _state.current_amps = -(float)((int16_t)data) / 1000.0f; + _state.current_amps = -(float)((int16_t)data) * 0.001f; _state.last_time_micros = tnow; } @@ -129,50 +127,6 @@ void AP_BattMonitor_SMBus_Generic::timer() read_cycle_count(); } -// read_block - returns number of characters read if successful, zero if unsuccessful -uint8_t AP_BattMonitor_SMBus_Generic::read_block(uint8_t reg, uint8_t* data, bool append_zero) const -{ - // get length - uint8_t bufflen; - // read byte (first byte indicates the number of bytes in the block) - if (!_dev->read_registers(reg, &bufflen, 1)) { - return 0; - } - - // sanity check length returned by smbus - if (bufflen == 0 || bufflen > SMBUS_READ_BLOCK_MAXIMUM_TRANSFER) { - return 0; - } - - // buffer to hold results (2 extra byte returned holding length and PEC) - const uint8_t read_size = bufflen + 1 + (_pec_supported ? 1 : 0); - uint8_t buff[read_size]; - - // read bytes - if (!_dev->read_registers(reg, buff, read_size)) { - return 0; - } - - // check PEC - if (_pec_supported) { - uint8_t pec = get_PEC(AP_BATTMONITOR_SMBUS_I2C_ADDR, reg, true, buff, bufflen+1); - if (pec != buff[bufflen+1]) { - return 0; - } - } - - // copy data (excluding PEC) - memcpy(data, &buff[1], bufflen); - - // optionally add zero to end - if (append_zero) { - data[bufflen] = '\0'; - } - - // return success - return bufflen; -} - // check if PEC supported with the version value in SpecificationInfo() function // returns true once PEC is confirmed as working or not working bool AP_BattMonitor_SMBus_Generic::check_pec_support() @@ -199,8 +153,8 @@ bool AP_BattMonitor_SMBus_Generic::check_pec_support() } // check manufacturer name - uint8_t buff[SMBUS_READ_BLOCK_MAXIMUM_TRANSFER + 1]; - if (read_block(BATTMONITOR_SMBUS_MANUFACTURE_NAME, buff, true)) { + uint8_t buff[AP_BATTMONITOR_SMBUS_READ_BLOCK_MAXIMUM_TRANSFER + 1] {}; + if (read_block(BATTMONITOR_SMBUS_MANUFACTURE_NAME, buff, sizeof(buff))) { // Hitachi maxell batteries do not support PEC if (strcmp((char*)buff, "Hitachi maxell") == 0) { _pec_supported = false; @@ -214,4 +168,3 @@ bool AP_BattMonitor_SMBus_Generic::check_pec_support() _pec_confirmed = true; return true; } - diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Generic.h b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Generic.h index 34a5b139f60..7edc4a6264d 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Generic.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Generic.h @@ -25,9 +25,6 @@ class AP_BattMonitor_SMBus_Generic : public AP_BattMonitor_SMBus // returns true once PEC is confirmed as working or not working bool check_pec_support(); - // read_block - returns number of characters read if successful, zero if unsuccessful - uint8_t read_block(uint8_t reg, uint8_t* data, bool append_zero) const; - uint8_t _pec_confirmed; // count of the number of times PEC has been confirmed as working uint32_t _last_cell_update_us[BATTMONITOR_SMBUS_NUM_CELLS_MAX]; // system time of last successful read of cell voltage uint32_t _cell_count_check_start_us; // system time we started attempting to count the number of cells diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_SUI.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_SUI.cpp index b1382f7d9e0..7d8aacce338 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_SUI.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_SUI.cpp @@ -65,38 +65,6 @@ void AP_BattMonitor_SMBus_SUI::timer() update_health(); } -// read_block - returns true if successful -bool AP_BattMonitor_SMBus_SUI::read_block(uint8_t reg, uint8_t* data, uint8_t len) const -{ - // buffer to hold results (2 extra byte returned holding length and PEC) - uint8_t buff[len+2]; - - // read bytes - if (!_dev->read_registers(reg, buff, sizeof(buff))) { - return false; - } - - // get length - uint8_t bufflen = buff[0]; - - // sanity check length returned by smbus - if (bufflen == 0 || bufflen > len) { - return false; - } - - // check PEC - uint8_t pec = get_PEC(_address, reg, true, buff, bufflen+1); - if (pec != buff[bufflen+1]) { - return false; - } - - // copy data (excluding PEC) - memcpy(data, &buff[1], bufflen); - - // return success - return true; -} - // read_bare_block - returns true if successful bool AP_BattMonitor_SMBus_SUI::read_block_bare(uint8_t reg, uint8_t* data, uint8_t len) const { @@ -129,7 +97,7 @@ void AP_BattMonitor_SMBus_SUI::read_cell_voltages() // we can't read voltage of all cells. get overall pack voltage to work out // an average for remaining cells uint16_t total_mv; - if (read_block(BATTMONITOR_SMBUS_VOLTAGE, (uint8_t *)&total_mv, sizeof(total_mv))) { + if (read_word(BATTMONITOR_SMBUS_VOLTAGE, total_mv)) { // if total voltage is below pack_voltage_mv then we will // read zero volts for the extra cells. total_mv = MAX(total_mv, pack_voltage_mv); diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_SUI.h b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_SUI.h index 5ba8ad913e7..506f5bc541d 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_SUI.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_SUI.h @@ -21,8 +21,7 @@ class AP_BattMonitor_SMBus_SUI : public AP_BattMonitor_SMBus void read_cell_voltages(); void update_health(); - // read_block - returns number of characters read if successful, zero if unsuccessful - bool read_block(uint8_t reg, uint8_t* data, uint8_t len) const; + // read_block_bare - returns number of characters read if successful, zero if unsuccessful bool read_block_bare(uint8_t reg, uint8_t* data, uint8_t len) const; const uint8_t cell_count; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Solo.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Solo.cpp index 4520d1430e9..5d4be883425 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Solo.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Solo.cpp @@ -66,7 +66,7 @@ void AP_BattMonitor_SMBus_Solo::timer() // read current if (read_block(BATTMONITOR_SMBUS_SOLO_CURRENT, buff, 4) == 4) { - _state.current_amps = -(float)((int32_t)((uint32_t)buff[3]<<24 | (uint32_t)buff[2]<<16 | (uint32_t)buff[1]<<8 | (uint32_t)buff[0])) / 1000.0f; + _state.current_amps = -(float)((int32_t)((uint32_t)buff[3]<<24 | (uint32_t)buff[2]<<16 | (uint32_t)buff[1]<<8 | (uint32_t)buff[0])) * 0.001f; _state.last_time_micros = tnow; } @@ -95,34 +95,3 @@ void AP_BattMonitor_SMBus_Solo::timer() read_cycle_count(); } - -// read_block - returns number of characters read if successful, zero if unsuccessful -uint8_t AP_BattMonitor_SMBus_Solo::read_block(uint8_t reg, uint8_t* data, uint8_t max_len) const -{ - uint8_t buff[max_len+2]; // buffer to hold results (2 extra byte returned holding length and PEC) - - // read bytes - if (!_dev->read_registers(reg, buff, sizeof(buff))) { - return 0; - } - - // get length - uint8_t bufflen = buff[0]; - - // sanity check length returned by smbus - if (bufflen == 0 || bufflen > max_len) { - return 0; - } - - // check PEC - uint8_t pec = get_PEC(_address, reg, true, buff, bufflen+1); - if (pec != buff[bufflen+1]) { - return 0; - } - - // copy data (excluding PEC) - memcpy(data, &buff[1], bufflen); - - // return success - return bufflen; -} diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Solo.h b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Solo.h index d343f3f7bda..2200220b461 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Solo.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Solo.h @@ -15,8 +15,5 @@ class AP_BattMonitor_SMBus_Solo : public AP_BattMonitor_SMBus void timer(void) override; - // read_block - returns number of characters read if successful, zero if unsuccessful - uint8_t read_block(uint8_t reg, uint8_t* data, uint8_t max_len) const; - uint8_t _button_press_count; }; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Sum.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Sum.cpp index cf8d3f973c4..7ce61484f89 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Sum.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Sum.cpp @@ -73,13 +73,22 @@ AP_BattMonitor_Sum::read() current_count++; } } + const uint32_t tnow_us = AP_HAL::micros(); + const uint32_t dt_us = tnow_us - _state.last_time_micros; + if (voltage_count > 0) { _state.voltage = voltage_sum / voltage_count; - _state.last_time_micros = AP_HAL::micros(); } if (current_count > 0) { _state.current_amps = current_sum; } + + update_consumed(_state, dt_us); + _has_current = (current_count > 0); _state.healthy = (voltage_count > 0); + + if (_state.healthy) { + _state.last_time_micros = tnow_us; + } } diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_UAVCAN.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_UAVCAN.cpp index 81e41875149..3544c87c3f7 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_UAVCAN.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_UAVCAN.cpp @@ -154,14 +154,10 @@ void AP_BattMonitor_UAVCAN::update_interim_state(const float voltage, const floa const uint32_t tnow = AP_HAL::micros(); if (!_has_battery_info_aux || _mppt.is_detected) { - uint32_t dt = tnow - _interim_state.last_time_micros; + const uint32_t dt_us = tnow - _interim_state.last_time_micros; // update total current drawn since startup - if (_interim_state.last_time_micros != 0 && dt < 2000000) { - float mah = calculate_mah(_interim_state.current_amps, dt); - _interim_state.consumed_mah += mah; - _interim_state.consumed_wh += 0.001f * mah * _interim_state.voltage; - } + update_consumed(_interim_state, dt_us); } // record time diff --git a/libraries/AP_Beacon/AP_Beacon.cpp b/libraries/AP_Beacon/AP_Beacon.cpp index 68a3718cfa0..4491ff3556d 100644 --- a/libraries/AP_Beacon/AP_Beacon.cpp +++ b/libraries/AP_Beacon/AP_Beacon.cpp @@ -21,6 +21,7 @@ #include "AP_Beacon_SITL.h" #include +#include extern const AP_HAL::HAL &hal; @@ -73,8 +74,7 @@ const AP_Param::GroupInfo AP_Beacon::var_info[] = { AP_GROUPEND }; -AP_Beacon::AP_Beacon(AP_SerialManager &_serial_manager) : - serial_manager(_serial_manager) +AP_Beacon::AP_Beacon() { #if CONFIG_HAL_BOARD == HAL_BOARD_SITL if (_singleton != nullptr) { @@ -388,6 +388,32 @@ bool AP_Beacon::device_ready(void) const return ((_driver != nullptr) && (_type != AP_BeaconType_None)); } +// Write beacon sensor (position) data +void AP_Beacon::log() +{ + if (!enabled()) { + return; + } + // position + Vector3f pos; + float accuracy = 0.0f; + get_vehicle_position_ned(pos, accuracy); + + const struct log_Beacon pkt_beacon{ + LOG_PACKET_HEADER_INIT(LOG_BEACON_MSG), + time_us : AP_HAL::micros64(), + health : (uint8_t)healthy(), + count : (uint8_t)count(), + dist0 : beacon_distance(0), + dist1 : beacon_distance(1), + dist2 : beacon_distance(2), + dist3 : beacon_distance(3), + posx : pos.x, + posy : pos.y, + posz : pos.z + }; + AP::logger().WriteBlock(&pkt_beacon, sizeof(pkt_beacon)); +} // singleton instance AP_Beacon *AP_Beacon::_singleton; diff --git a/libraries/AP_Beacon/AP_Beacon.h b/libraries/AP_Beacon/AP_Beacon.h index 3bf766c7ee8..6cb02b91c8a 100644 --- a/libraries/AP_Beacon/AP_Beacon.h +++ b/libraries/AP_Beacon/AP_Beacon.h @@ -15,10 +15,8 @@ #pragma once #include -#include #include #include -#include #include class AP_Beacon_Backend; @@ -32,7 +30,7 @@ class AP_Beacon public: friend class AP_Beacon_Backend; - AP_Beacon(AP_SerialManager &_serial_manager); + AP_Beacon(); // get singleton instance static AP_Beacon *get_singleton() { return _singleton; } @@ -104,6 +102,9 @@ class AP_Beacon static const struct AP_Param::GroupInfo var_info[]; + // a method for vehicles to call to make onboard log messages: + void log(); + private: static AP_Beacon *_singleton; @@ -128,7 +129,6 @@ class AP_Beacon // external references AP_Beacon_Backend *_driver; - AP_SerialManager &serial_manager; // last known position Vector3f veh_pos_ned; diff --git a/libraries/AP_Beacon/AP_Beacon_Backend.cpp b/libraries/AP_Beacon/AP_Beacon_Backend.cpp index e970a78b5ea..66ec41c2308 100644 --- a/libraries/AP_Beacon/AP_Beacon_Backend.cpp +++ b/libraries/AP_Beacon/AP_Beacon_Backend.cpp @@ -16,6 +16,7 @@ #include "AP_Beacon_Backend.h" // debug #include +#include /* base class constructor. @@ -89,7 +90,7 @@ Vector3f AP_Beacon_Backend::correct_for_orient_yaw(const Vector3f &vector) // check for change in parameter value and update constants if (orient_yaw_deg != _frontend.orient_yaw) { - _frontend.orient_yaw = wrap_180(_frontend.orient_yaw.get()); + _frontend.orient_yaw.set(wrap_180(_frontend.orient_yaw.get())); // calculate rotation constants orient_yaw_deg = _frontend.orient_yaw; diff --git a/libraries/AP_Beacon/AP_Beacon_Pozyx.cpp b/libraries/AP_Beacon/AP_Beacon_Pozyx.cpp index 7b5e3b11028..9880d783555 100644 --- a/libraries/AP_Beacon/AP_Beacon_Pozyx.cpp +++ b/libraries/AP_Beacon/AP_Beacon_Pozyx.cpp @@ -113,7 +113,7 @@ void AP_Beacon_Pozyx::parse_buffer() int32_t beacon_x = (uint32_t)linebuf[5] << 24 | (uint32_t)linebuf[4] << 16 | (uint32_t)linebuf[3] << 8 | (uint32_t)linebuf[2]; int32_t beacon_y = (uint32_t)linebuf[9] << 24 | (uint32_t)linebuf[8] << 16 | (uint32_t)linebuf[7] << 8 | (uint32_t)linebuf[6]; int32_t beacon_z = (uint32_t)linebuf[13] << 24 | (uint32_t)linebuf[12] << 16 | (uint32_t)linebuf[11] << 8 | (uint32_t)linebuf[10]; - Vector3f beacon_pos(beacon_x / 1000.0f, beacon_y / 1000.0f, -beacon_z / 1000.0f); + Vector3f beacon_pos(beacon_x * 0.001f, beacon_y * 0.001f, -beacon_z * 0.001f); if (beacon_pos.length() <= AP_BEACON_DISTANCE_MAX) { set_beacon_position(beacon_id, beacon_pos); parsed = true; @@ -139,7 +139,7 @@ void AP_Beacon_Pozyx::parse_buffer() int32_t vehicle_y = (uint32_t)linebuf[7] << 24 | (uint32_t)linebuf[6] << 16 | (uint32_t)linebuf[5] << 8 | (uint32_t)linebuf[4]; int32_t vehicle_z = (uint32_t)linebuf[11] << 24 | (uint32_t)linebuf[10] << 16 | (uint32_t)linebuf[9] << 8 | (uint32_t)linebuf[8]; int16_t position_error = (uint32_t)linebuf[13] << 8 | (uint32_t)linebuf[12]; - Vector3f veh_pos(Vector3f(vehicle_x / 1000.0f, vehicle_y / 1000.0f, -vehicle_z / 1000.0f)); + Vector3f veh_pos(Vector3f(vehicle_x * 0.001f, vehicle_y * 0.001f, -vehicle_z * 0.001f)); if (veh_pos.length() <= AP_BEACON_DISTANCE_MAX) { set_vehicle_position(veh_pos, position_error); parsed = true; diff --git a/libraries/AP_Beacon/LogStructure.h b/libraries/AP_Beacon/LogStructure.h new file mode 100644 index 00000000000..f0faa8f355d --- /dev/null +++ b/libraries/AP_Beacon/LogStructure.h @@ -0,0 +1,37 @@ +#pragma once + +#include + +#define LOG_IDS_FROM_BEACON \ + LOG_BEACON_MSG + +// @LoggerMessage: BCN +// @Description: Beacon information +// @Field: TimeUS: Time since system startup +// @Field: Health: True if beacon sensor is healthy +// @Field: Cnt: Number of beacons being used +// @Field: D0: Distance to first beacon +// @Field: D1: Distance to second beacon +// @Field: D2: Distance to third beacon +// @Field: D3: Distance to fourth beacon +// @Field: PosX: Calculated beacon position, x-axis +// @Field: PosY: Calculated beacon position, y-axis +// @Field: PosZ: Calculated beacon position, z-axis + +struct PACKED log_Beacon { + LOG_PACKET_HEADER; + uint64_t time_us; + uint8_t health; + uint8_t count; + float dist0; + float dist1; + float dist2; + float dist3; + float posx; + float posy; + float posz; +}; + +#define LOG_STRUCTURE_FROM_BEACON \ + { LOG_BEACON_MSG, sizeof(log_Beacon), \ + "BCN", "QBBfffffff", "TimeUS,Health,Cnt,D0,D1,D2,D3,PosX,PosY,PosZ", "s--mmmmmmm", "F--0000000", true }, diff --git a/libraries/AP_Beacon/examples/AP_Marvelmind_test/AP_Marvelmind_test.cpp b/libraries/AP_Beacon/examples/AP_Marvelmind_test/AP_Marvelmind_test.cpp index 6e605843c80..a3dae7a7f16 100644 --- a/libraries/AP_Beacon/examples/AP_Marvelmind_test/AP_Marvelmind_test.cpp +++ b/libraries/AP_Beacon/examples/AP_Marvelmind_test/AP_Marvelmind_test.cpp @@ -5,6 +5,7 @@ #include #include #include +#include #include void setup(); @@ -15,7 +16,7 @@ void set_object_value_and_report(const void *object_pointer, const AP_HAL::HAL& hal = AP_HAL::get_HAL(); static AP_SerialManager serial_manager; -AP_Beacon beacon{serial_manager}; +AP_Beacon beacon; // try to set the object value but provide diagnostic if it failed void set_object_value_and_report(const void *object_pointer, diff --git a/libraries/AP_BoardConfig/AP_BoardConfig.cpp b/libraries/AP_BoardConfig/AP_BoardConfig.cpp index 084c1964fa2..563f0ee0911 100644 --- a/libraries/AP_BoardConfig/AP_BoardConfig.cpp +++ b/libraries/AP_BoardConfig/AP_BoardConfig.cpp @@ -32,9 +32,6 @@ #endif #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS -#ifndef BOARD_SAFETY_ENABLE_DEFAULT -# define BOARD_SAFETY_ENABLE_DEFAULT 1 -#endif #ifndef BOARD_SER1_RTSCTS_DEFAULT # define BOARD_SER1_RTSCTS_DEFAULT 2 #endif @@ -43,6 +40,18 @@ #endif #endif +#ifndef BOARD_SAFETY_ENABLE_DEFAULT +#if defined(HAL_GPIO_PIN_SAFETY_IN) + // have safety startup enabled if we have a safety pin + # define BOARD_SAFETY_ENABLE_DEFAULT 1 +#elif defined(HAL_WITH_IO_MCU) + // if we have an IOMCU then enable by default + # define BOARD_SAFETY_ENABLE_DEFAULT HAL_WITH_IO_MCU +#else + # define BOARD_SAFETY_ENABLE_DEFAULT 0 +#endif +#endif + #ifndef HAL_IMU_TEMP_DEFAULT #define HAL_IMU_TEMP_DEFAULT -1 // disabled #endif @@ -146,7 +155,6 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] = { #endif #endif -#if HAL_HAVE_SAFETY_SWITCH // @Param: SAFETYENABLE // @DisplayName: Enable use of safety arming switch // @Description: This controls the default state of the safety switch at startup. When set to 1 the safety switch will start in the safe state (flashing) at boot. When set to zero the safety switch will start in the unsafe state (solid) at startup. Note that if a safety switch is fitted the user can still control the safety state after startup using the switch. The safety state can also be controlled in software using a MAVLink message. @@ -154,7 +162,6 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] = { // @RebootRequired: True // @User: Standard AP_GROUPINFO("SAFETYENABLE", 3, AP_BoardConfig, state.safety_enable, BOARD_SAFETY_ENABLE_DEFAULT), -#endif #if AP_FEATURE_SBUS_OUT // @Param: SBUS_OUT @@ -169,11 +176,10 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] = { // @Param: SERIAL_NUM // @DisplayName: User-defined serial number // @Description: User-defined serial number of this vehicle, it can be any arbitrary number you want and has no effect on the autopilot - // @Range: -32768 32767 + // @Range: -8388608 8388607 // @User: Standard AP_GROUPINFO("SERIAL_NUM", 5, AP_BoardConfig, vehicleSerialNumber, 0), -#if HAL_HAVE_SAFETY_SWITCH // @Param: SAFETY_MASK // @DisplayName: Outputs which ignore the safety switch state // @Description: A bitmask which controls what outputs can move while the safety switch has not been pressed @@ -181,7 +187,6 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] = { // @RebootRequired: True // @User: Advanced AP_GROUPINFO("SAFETY_MASK", 7, AP_BoardConfig, state.ignore_safety_channels, 0), -#endif #if HAL_HAVE_IMU_HEATER // @Param: HEAT_TARG @@ -206,8 +211,8 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] = { #if HAL_WITH_IO_MCU // @Param: IO_ENABLE // @DisplayName: Enable IO co-processor - // @Description: This allows for the IO co-processor on FMUv1 and FMUv2 to be disabled - // @Values: 0:Disabled,1:Enabled + // @Description: This allows for the IO co-processor on boards with an IOMCU to be disabled. Setting to 2 will enable the IOMCU but not attempt to update firmware on startup + // @Values: 0:Disabled,1:Enabled,2:EnableNoFWUpdate // @RebootRequired: True // @User: Advanced AP_GROUPINFO("IO_ENABLE", 10, AP_BoardConfig, state.io_enable, 1), @@ -222,7 +227,7 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] = { // @Param: SAFETYOPTION // @DisplayName: Options for safety button behavior // @Description: This controls the activation of the safety button. It allows you to control if the safety button can be used for safety enable and/or disable, and whether the button is only active when disarmed - // @Bitmask: 0:ActiveForSafetyEnable,1:ActiveForSafetyDisable,2:ActiveWhenArmed,3:Force safety on when the aircraft disarms + // @Bitmask: 0:ActiveForSafetyDisable,1:ActiveForSafetyEnable,2:ActiveWhenArmed,3:Force safety on when the aircraft disarms // @User: Standard AP_GROUPINFO("SAFETYOPTION", 13, AP_BoardConfig, state.safety_option, BOARD_SAFETY_OPTION_DEFAULT), @@ -337,6 +342,9 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] = { void AP_BoardConfig::init() { + // PARAMETER_CONVERSION - Added: APR-2022 + vehicleSerialNumber.convert_parameter_width(AP_PARAM_INT16); + board_setup(); AP::rtc().set_utc_usec(hal.util->get_hw_rtc(), AP_RTC::SOURCE_HW); @@ -370,11 +378,9 @@ void AP_BoardConfig::init() } // set default value for BRD_SAFETY_MASK -void AP_BoardConfig::set_default_safety_ignore_mask(uint16_t mask) +void AP_BoardConfig::set_default_safety_ignore_mask(uint32_t mask) { -#if HAL_HAVE_SAFETY_SWITCH state.ignore_safety_channels.set_default(mask); -#endif } void AP_BoardConfig::init_safety() @@ -410,7 +416,7 @@ void AP_BoardConfig::throw_error(const char *err_type, const char *fmt, va_list vprintf(printfmt, arg_copy); va_end(arg_copy); } -#if !APM_BUILD_TYPE(APM_BUILD_UNKNOWN) && !defined(HAL_BUILD_AP_PERIPH) +#if HAL_GCS_ENABLED hal.util->snprintf(printfmt, sizeof(printfmt), "%s: %s", err_type, fmt); { va_list arg_copy; @@ -420,7 +426,7 @@ void AP_BoardConfig::throw_error(const char *err_type, const char *fmt, va_list } #endif } -#if !APM_BUILD_TYPE(APM_BUILD_UNKNOWN) && !defined(HAL_BUILD_AP_PERIPH) +#if HAL_GCS_ENABLED gcs().update_receive(); gcs().update_send(); #endif diff --git a/libraries/AP_BoardConfig/AP_BoardConfig.h b/libraries/AP_BoardConfig/AP_BoardConfig.h index 34297de10d8..af4c3f97b86 100644 --- a/libraries/AP_BoardConfig/AP_BoardConfig.h +++ b/libraries/AP_BoardConfig/AP_BoardConfig.h @@ -96,11 +96,13 @@ class AP_BoardConfig { VRX_BOARD_CORE10 = 36, VRX_BOARD_BRAIN54 = 38, PX4_BOARD_FMUV6 = 39, + FMUV6_BOARD_HOLYBRO_6X = 40, + FMUV6_BOARD_CUAV_6X = 41, PX4_BOARD_OLDDRIVERS = 100, }; // set default value for BRD_SAFETY_MASK - void set_default_safety_ignore_mask(uint16_t mask); + void set_default_safety_ignore_mask(uint32_t mask); static enum px4_board_type get_board_type(void) { #if AP_FEATURE_BOARD_DETECT @@ -140,11 +142,7 @@ class AP_BoardConfig { // return the value of BRD_SAFETY_MASK uint16_t get_safety_mask(void) const { -#if AP_FEATURE_BOARD_DETECT || defined(AP_FEATURE_BRD_PWM_COUNT_PARAM) - return uint16_t(state.ignore_safety_channels.get()); -#else - return 0; -#endif + return uint32_t(state.ignore_safety_channels.get()); } #if HAL_HAVE_BOARD_VOLTAGE @@ -227,7 +225,7 @@ class AP_BoardConfig { private: static AP_BoardConfig *_singleton; - AP_Int16 vehicleSerialNumber; + AP_Int32 vehicleSerialNumber; struct { AP_Int8 safety_enable; @@ -249,6 +247,7 @@ class AP_BoardConfig { bool spi_check_register_inv2(const char *devname, uint8_t regnum, uint8_t value, uint8_t read_flag = 0x80); void validate_board_type(void); void board_autodetect(void); + void detect_fmuv6_variant(void); bool check_ms5611(const char* devname); #endif // AP_FEATURE_BOARD_DETECT diff --git a/libraries/AP_BoardConfig/IMU_heater.cpp b/libraries/AP_BoardConfig/IMU_heater.cpp index 541e0062322..c165b1da008 100644 --- a/libraries/AP_BoardConfig/IMU_heater.cpp +++ b/libraries/AP_BoardConfig/IMU_heater.cpp @@ -81,6 +81,7 @@ void AP_BoardConfig::set_imu_temp(float current) heater.output = constrain_float(heater.output, 0, 100); } +#if HAL_LOGGING_ENABLED if (now - heater.last_log_ms >= 1000) { // @LoggerMessage: HEAT // @Description: IMU Heater data @@ -98,6 +99,8 @@ void AP_BoardConfig::set_imu_temp(float current) heater.output); heater.last_log_ms = now; } +#endif // HAL_LOGGING_ENABLED + #if 0 gcs().send_text(MAV_SEVERITY_INFO, "Heater: Out=%.1f Temp=%.1f", double(heater.output), diff --git a/libraries/AP_BoardConfig/board_drivers.cpp b/libraries/AP_BoardConfig/board_drivers.cpp index bd58df7b105..cc90d3456e9 100644 --- a/libraries/AP_BoardConfig/board_drivers.cpp +++ b/libraries/AP_BoardConfig/board_drivers.cpp @@ -33,10 +33,9 @@ extern const AP_HAL::HAL& hal; */ void AP_BoardConfig::board_init_safety() { -#if HAL_HAVE_SAFETY_SWITCH bool force_safety_off = (state.safety_enable.get() == 0); if (!force_safety_off && hal.util->was_watchdog_safety_off()) { - gcs().send_text(MAV_SEVERITY_INFO, "Forcing safety off for watchdog\n"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Forcing safety off for watchdog\n"); force_safety_off = true; } if (force_safety_off) { @@ -47,7 +46,6 @@ void AP_BoardConfig::board_init_safety() hal.scheduler->delay(20); } } -#endif } /* @@ -73,28 +71,11 @@ void AP_BoardConfig::board_init_debug() AP_BoardConfig::px4_board_type AP_BoardConfig::px4_configured_board; -#if defined(CONFIG_ARCH_BOARD_PX4FMU_V4) -extern "C" { - int fmu_main(int, char **); -}; -#endif - void AP_BoardConfig::board_setup_drivers(void) { -#if defined(CONFIG_ARCH_BOARD_PX4FMU_V4) - /* - this works around an issue with some FMUv4 hardware (eg. copies - of the Pixracer) which have incorrect components leading to - sensor brownout on boot - */ - if (px4_start_driver(fmu_main, "fmu", "sensor_reset 20")) { - printf("FMUv4 sensor reset complete\n"); - } -#endif - if (state.board_type == PX4_BOARD_OLDDRIVERS) { printf("Old drivers no longer supported\n"); - state.board_type = PX4_BOARD_AUTO; + state.board_type.set(PX4_BOARD_AUTO); } // run board auto-detection @@ -136,6 +117,8 @@ void AP_BoardConfig::board_setup_drivers(void) case PX4_BOARD_PIXHAWK_PRO: case PX4_BOARD_PCNC1: case PX4_BOARD_MINDPXV2: + case FMUV6_BOARD_HOLYBRO_6X: + case FMUV6_BOARD_CUAV_6X: break; default: config_error("Unknown board type"); @@ -285,6 +268,11 @@ bool AP_BoardConfig::check_ms5611(const char* devname) { #define INV2_WHOAMI_ICM20948 0xEA #define INV2_WHOAMI_ICM20649 0xE1 +#define INV3REG_WHOAMI 0x75 + +#define INV3_WHOAMI_ICM42688 0x47 +#define INV3_WHOAMI_ICM42670 0x67 + /* validation of the board type */ @@ -295,7 +283,7 @@ void AP_BoardConfig::validate_board_type(void) cook the IMUs if the user uses an old paramater file. We override the board type for that specific case */ -#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2) || defined(HAL_CHIBIOS_ARCH_FMUV3) +#if defined(HAL_CHIBIOS_ARCH_FMUV3) if (state.board_type == PX4_BOARD_PIXHAWK && (spi_check_register("mpu6000_ext", MPUREG_WHOAMI, MPU_WHOAMI_MPU60X0) || spi_check_register("mpu9250_ext", MPUREG_WHOAMI, MPU_WHOAMI_MPU9250) || @@ -307,18 +295,14 @@ void AP_BoardConfig::validate_board_type(void) // Pixhawk2 has LSM303D and MPUxxxx on external bus. If we // detect those, then force PIXHAWK2, even if the user has // configured for PIXHAWK1 -#if !defined(CONFIG_ARCH_BOARD_PX4FMU_V3) && !defined(HAL_CHIBIOS_ARCH_FMUV3) +#if !defined(HAL_CHIBIOS_ARCH_FMUV3) // force user to load the right firmware config_error("Pixhawk2 requires FMUv3 firmware"); #endif state.board_type.set(PX4_BOARD_PIXHAWK2); - hal.console->printf("Forced PIXHAWK2\n"); + DEV_PRINTF("Forced PIXHAWK2\n"); } #endif - -#if defined(CONFIG_ARCH_BOARD_PX4FMU_V4PRO) - // Nothing to do for the moment -#endif } /* @@ -342,12 +326,7 @@ void AP_BoardConfig::board_autodetect(void) return; } -#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1) - // only one choice - state.board_type.set(PX4_BOARD_PX4V1); - hal.console->printf("Detected PX4v1\n"); - -#elif defined(CONFIG_ARCH_BOARD_PX4FMU_V2) || defined(HAL_CHIBIOS_ARCH_FMUV3) +#if defined(HAL_CHIBIOS_ARCH_FMUV3) if ((spi_check_register("mpu6000_ext", MPUREG_WHOAMI, MPU_WHOAMI_MPU60X0) || spi_check_register("mpu6000_ext", MPUREG_WHOAMI, MPU_WHOAMI_MPU60X0) || spi_check_register("mpu9250_ext", MPUREG_WHOAMI, MPU_WHOAMI_MPU60X0) || @@ -359,13 +338,13 @@ void AP_BoardConfig::board_autodetect(void) spi_check_register_inv2("icm20948_ext", INV2REG_WHOAMI, INV2_WHOAMI_ICM20948))) { // Pixhawk2 has LSM303D and MPUxxxx on external bus state.board_type.set(PX4_BOARD_PIXHAWK2); - hal.console->printf("Detected PIXHAWK2\n"); + DEV_PRINTF("Detected PIXHAWK2\n"); } else if ((spi_check_register("icm20608-am", MPUREG_WHOAMI, MPU_WHOAMI_ICM20608) || spi_check_register("icm20608-am", MPUREG_WHOAMI, MPU_WHOAMI_ICM20602)) && spi_check_register("mpu9250", MPUREG_WHOAMI, MPU_WHOAMI_MPU9250)) { // PHMINI has an ICM20608 and MPU9250 on sensor bus state.board_type.set(PX4_BOARD_PHMINI); - hal.console->printf("Detected PixhawkMini\n"); + DEV_PRINTF("Detected PixhawkMini\n"); } else if (spi_check_register("lsm9ds0_am", LSMREG_WHOAMI, LSM_WHOAMI_LSM303D) && (spi_check_register("mpu6000", MPUREG_WHOAMI, MPU_WHOAMI_MPU60X0) || spi_check_register("icm20608", MPUREG_WHOAMI, MPU_WHOAMI_ICM20608) || @@ -374,52 +353,42 @@ void AP_BoardConfig::board_autodetect(void) // classic or upgraded Pixhawk1 state.board_type.set(PX4_BOARD_PIXHAWK); - hal.console->printf("Detected Pixhawk\n"); + DEV_PRINTF("Detected Pixhawk\n"); } else { config_error("Unable to detect board type"); } -#elif defined(CONFIG_ARCH_BOARD_PX4FMU_V4) || defined(HAL_CHIBIOS_ARCH_FMUV4) +#elif defined(HAL_CHIBIOS_ARCH_FMUV4) // only one choice state.board_type.set_and_notify(PX4_BOARD_PIXRACER); - hal.console->printf("Detected Pixracer\n"); + DEV_PRINTF("Detected Pixracer\n"); #elif defined(HAL_CHIBIOS_ARCH_MINDPXV2) // only one choice state.board_type.set_and_notify(PX4_BOARD_MINDPXV2); - hal.console->printf("Detected MindPX-V2\n"); -#elif defined(CONFIG_ARCH_BOARD_PX4FMU_V4PRO) || defined(HAL_CHIBIOS_ARCH_FMUV4PRO) + DEV_PRINTF("Detected MindPX-V2\n"); +#elif defined(HAL_CHIBIOS_ARCH_FMUV4PRO) // only one choice state.board_type.set_and_notify(PX4_BOARD_PIXHAWK_PRO); - hal.console->printf("Detected Pixhawk Pro\n"); -#elif defined(CONFIG_ARCH_BOARD_AEROFC_V1) - state.board_type.set_and_notify(PX4_BOARD_AEROFC); - hal.console->printf("Detected Aero FC\n"); + DEV_PRINTF("Detected Pixhawk Pro\n"); #elif defined(HAL_CHIBIOS_ARCH_FMUV5) state.board_type.set_and_notify(PX4_BOARD_FMUV5); - hal.console->printf("Detected FMUv5\n"); + DEV_PRINTF("Detected FMUv5\n"); #elif defined(HAL_CHIBIOS_ARCH_FMUV6) - state.board_type.set_and_notify(PX4_BOARD_FMUV5); - hal.console->printf("Detected FMUv6\n"); -#elif defined(CONFIG_ARCH_BOARD_VRBRAIN_V51) || defined(HAL_CHIBIOS_ARCH_BRAINV51) + detect_fmuv6_variant(); +#elif defined(HAL_CHIBIOS_ARCH_BRAINV51) state.board_type.set_and_notify(VRX_BOARD_BRAIN51); - hal.console->printf("Detected VR Brain 5.1\n"); -#elif defined(CONFIG_ARCH_BOARD_VRBRAIN_V52) || defined(HAL_CHIBIOS_ARCH_BRAINV52) + DEV_PRINTF("Detected VR Brain 5.1\n"); +#elif defined(HAL_CHIBIOS_ARCH_BRAINV52) state.board_type.set_and_notify(VRX_BOARD_BRAIN52); - hal.console->printf("Detected VR Brain 5.2\n"); -#elif defined(CONFIG_ARCH_BOARD_VRBRAIN_V52E) - state.board_type.set_and_notify(VRX_BOARD_BRAIN52E); - hal.console->printf("Detected VR Brain 5.2E\n"); -#elif defined(CONFIG_ARCH_BOARD_VRUBRAIN_V51) || defined(HAL_CHIBIOS_ARCH_UBRAINV51) + DEV_PRINTF("Detected VR Brain 5.2\n"); +#elif defined(HAL_CHIBIOS_ARCH_UBRAINV51) state.board_type.set_and_notify(VRX_BOARD_UBRAIN51); - hal.console->printf("Detected VR Micro Brain 5.1\n"); -#elif defined(CONFIG_ARCH_BOARD_VRUBRAIN_V52) - state.board_type.set_and_notify(VRX_BOARD_UBRAIN52); - hal.console->printf("Detected VR Micro Brain 5.2\n"); -#elif defined(CONFIG_ARCH_BOARD_VRCORE_V10) || defined(HAL_CHIBIOS_ARCH_COREV10) + DEV_PRINTF("Detected VR Micro Brain 5.1\n"); +#elif defined(HAL_CHIBIOS_ARCH_COREV10) state.board_type.set_and_notify(VRX_BOARD_CORE10); - hal.console->printf("Detected VR Core 1.0\n"); -#elif defined(CONFIG_ARCH_BOARD_VRBRAIN_V54) || defined(HAL_CHIBIOS_ARCH_BRAINV54) + DEV_PRINTF("Detected VR Core 1.0\n"); +#elif defined(HAL_CHIBIOS_ARCH_BRAINV54) state.board_type.set_and_notify(VRX_BOARD_BRAIN54); - hal.console->printf("Detected VR Brain 5.4\n"); + DEV_PRINTF("Detected VR Brain 5.4\n"); #endif } @@ -519,3 +488,30 @@ void AP_BoardConfig::board_setup() #endif } + +#ifdef HAL_CHIBIOS_ARCH_FMUV6 + +#define BMI088REG_CHIPID 0x00 +#define CHIPID_BMI088_G 0x0F + +/* + detect which FMUV6 variant we are running on + */ +void AP_BoardConfig::detect_fmuv6_variant() +{ + if (((spi_check_register_inv2("icm20649", INV2REG_WHOAMI, INV2_WHOAMI_ICM20649) || + spi_check_register("bmi088_g", BMI088REG_CHIPID, CHIPID_BMI088_G)) && // alternative config + spi_check_register("icm42688", INV3REG_WHOAMI, INV3_WHOAMI_ICM42688) && + spi_check_register("icm42670", INV3REG_WHOAMI, INV3_WHOAMI_ICM42670))) { + state.board_type.set_and_notify(FMUV6_BOARD_HOLYBRO_6X); + DEV_PRINTF("Detected Holybro 6X\n"); + } else if ((spi_check_register_inv2("icm20649_2", INV2REG_WHOAMI, INV2_WHOAMI_ICM20649) && + spi_check_register("icm42688", INV3REG_WHOAMI, INV3_WHOAMI_ICM42688) && + spi_check_register("bmi088_g", BMI088REG_CHIPID, CHIPID_BMI088_G))) { + state.board_type.set_and_notify(FMUV6_BOARD_CUAV_6X); + DEV_PRINTF("Detected CUAV 6X\n"); + AP_Param::load_defaults_file("@ROMFS/param/CUAV_V6X_defaults.parm", false); + } + +} +#endif diff --git a/libraries/AP_Button/AP_Button.cpp b/libraries/AP_Button/AP_Button.cpp index 1349341abb8..6fb4e58e98f 100644 --- a/libraries/AP_Button/AP_Button.cpp +++ b/libraries/AP_Button/AP_Button.cpp @@ -20,6 +20,7 @@ #include #include +#include // very crude debounce method #define DEBOUNCE_MS 50 @@ -39,28 +40,28 @@ const AP_Param::GroupInfo AP_Button::var_info[] = { // @Param: PIN1 // @DisplayName: First button Pin - // @Description: Digital pin number for first button input. + // @Description: Digital pin number for first button input. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot. // @User: Standard // @Values: -1:Disabled,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6 AP_GROUPINFO("PIN1", 1, AP_Button, pin[0], -1), // @Param: PIN2 // @DisplayName: Second button Pin - // @Description: Digital pin number for second button input. + // @Description: Digital pin number for second button input. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot. // @User: Standard // @Values: -1:Disabled,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6 AP_GROUPINFO("PIN2", 2, AP_Button, pin[1], -1), // @Param: PIN3 // @DisplayName: Third button Pin - // @Description: Digital pin number for third button input. + // @Description: Digital pin number for third button input. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot. // @User: Standard // @Values: -1:Disabled,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6 AP_GROUPINFO("PIN3", 3, AP_Button, pin[2], -1), // @Param: PIN4 // @DisplayName: Fourth button Pin - // @Description: Digital pin number for fourth button input. + // @Description: Digital pin number for fourth button input. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot. // @User: Standard // @Values: -1:Disabled,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6 AP_GROUPINFO("PIN4", 4, AP_Button, pin[3], -1), @@ -74,27 +75,27 @@ const AP_Param::GroupInfo AP_Button::var_info[] = { // @Param: OPTIONS1 // @DisplayName: Button Pin 1 Options - // @Description: Options for Pin 1. PWM input detects PWM above or below 1800/1200us instead of logic level. Invert changes HIGH state to be logic low voltage on pin, or below 1200us, if PWM input. + // @Description: Options for Pin 1. PWM input detects PWM above or below 1800/1200us instead of logic level. If PWM is not detected or is less than 800us or above 2200us the button will interpreted as low. Invert changes HIGH state to be logic low voltage on pin, or below 1200us, if PWM input. // @User: Standard // @Bitmask: 0:PWM Input,1:InvertInput AP_GROUPINFO("OPTIONS1", 6, AP_Button, options[0], 0), // @Param: OPTIONS2 // @DisplayName: Button Pin 2 Options - // @Description: Options for Pin 2. PWM input detects PWM above or below 1800/1200us instead of logic level. Invert changes HIGH state to be logic low voltage on pin, or below 1200us, if PWM input. + // @Description: Options for Pin 2. PWM input detects PWM above or below 1800/1200us instead of logic level. If PWM is not detected or is less than 800us or above 2200us the button will interpreted as low. Invert changes HIGH state to be logic low voltage on pin, or below 1200us, if PWM input. // @User: Standard // @Bitmask: 0:PWM Input,1:InvertInput AP_GROUPINFO("OPTIONS2", 7, AP_Button, options[1], 0), // @Param: OPTIONS3 // @DisplayName: Button Pin 3 Options - // @Description: Options for Pin 3. PWM input detects PWM above or below 1800/1200us instead of logic level. Invert changes HIGH state to be logic low voltage on pin, or below 1200us, if PWM input. + // @Description: Options for Pin 3. PWM input detects PWM above or below 1800/1200us instead of logic level. If PWM is not detected or is less than 800us or above 2200us the button will interpreted as low. Invert changes HIGH state to be logic low voltage on pin, or below 1200us, if PWM input. // @Bitmask: 0:PWM Input,1:InvertInput AP_GROUPINFO("OPTIONS3", 8, AP_Button, options[2], 0), // @Param: OPTIONS4 // @DisplayName: Button Pin 4 Options - // @Description: Options for Pin 4. PWM input detects PWM above or below 1800/1200us instead of logic level. Invert changes HIGH state to be logic low voltage on pin, or below 1200us, if PWM input. + // @Description: Options for Pin 4. PWM input detects PWM above or below 1800/1200us instead of logic level. If PWM is not detected or is less than 800us or above 2200us the button will interpreted as low. Invert changes HIGH state to be logic low voltage on pin, or below 1200us, if PWM input. // @User: Standard // @Bitmask: 0:PWM Input,1:InvertInput AP_GROUPINFO("OPTIONS4", 9, AP_Button, options[3], 0), @@ -183,6 +184,13 @@ void AP_Button::update(void) continue; } const uint16_t pwm_us = pwm_pin_source[i].get_pwm_us(); + if (pwm_us < RC_Channel::RC_MIN_LIMIT_PWM || pwm_us > RC_Channel::RC_MAX_LIMIT_PWM) { + // invalid pulse width, trigger low + if (pwm_state & mask) { + new_pwm_state &= ~mask; + } + continue; + } // these values are the same as used in RC_Channel: if (pwm_state & mask) { // currently asserted; check to see if we should de-assert @@ -380,7 +388,12 @@ bool AP_Button::arming_checks(size_t buflen, char *buffer) const } for (uint8_t i=0; ivalid_pin(pin[i])) { - hal.util->snprintf(buffer, buflen, "BTN_PIN%u %d invalid", unsigned(i + 1), int(pin[i].get())); + uint8_t servo_ch; + if (hal.gpio->pin_to_servo_channel(pin[i], servo_ch)) { + hal.util->snprintf(buffer, buflen, "BTN_PIN%u=%d, set SERVO%u_FUNCTION=-1", unsigned(i + 1), int(pin[i].get()), unsigned(servo_ch+1)); + } else { + hal.util->snprintf(buffer, buflen, "BTN_PIN%u=%d invalid", unsigned(i + 1), int(pin[i].get())); + } return false; } } diff --git a/libraries/AP_CANManager/AP_CANDriver.cpp b/libraries/AP_CANManager/AP_CANDriver.cpp index a458065145e..97bc7c82fca 100644 --- a/libraries/AP_CANManager/AP_CANDriver.cpp +++ b/libraries/AP_CANManager/AP_CANDriver.cpp @@ -20,7 +20,6 @@ #include #include -#include #include #include "AP_CANTester.h" #include @@ -32,7 +31,7 @@ const AP_Param::GroupInfo AP_CANManager::CANDriver_Params::var_info[] = { // @Param: PROTOCOL // @DisplayName: Enable use of specific protocol over virtual driver // @Description: Enabling this option starts selected protocol that will use this virtual driver - // @Values: 0:Disabled,1:DroneCAN,3:ToshibaCAN,4:PiccoloCAN,5:CANTester,6:EFI_NWPMU,7:USD1,8:KDECAN,10:Scripting,11:Benewake + // @Values: 0:Disabled,1:DroneCAN,4:PiccoloCAN,5:CANTester,6:EFI_NWPMU,7:USD1,8:KDECAN,10:Scripting,11:Benewake,12:Scripting2 // @User: Advanced // @RebootRequired: True AP_GROUPINFO("PROTOCOL", 1, AP_CANManager::CANDriver_Params, _driver_type, AP_CANManager::Driver_Type_UAVCAN), @@ -47,7 +46,7 @@ const AP_Param::GroupInfo AP_CANManager::CANDriver_Params::var_info[] = { AP_SUBGROUPPTR(_kdecan, "KDE_", 3, AP_CANManager::CANDriver_Params, AP_KDECAN), #endif -#if HAL_NUM_CAN_IFACES > 1 && !HAL_MINIMIZE_FEATURES +#if HAL_NUM_CAN_IFACES > 1 && !HAL_MINIMIZE_FEATURES && HAL_ENABLE_CANTESTER // @Group: TST_ // @Path: ../AP_CANManager/AP_CANTester.cpp AP_SUBGROUPPTR(_testcan, "TST_", 4, AP_CANManager::CANDriver_Params, CANTester), diff --git a/libraries/AP_CANManager/AP_CANIfaceParams.cpp b/libraries/AP_CANManager/AP_CANIfaceParams.cpp index 32276e24816..b088f392c74 100644 --- a/libraries/AP_CANManager/AP_CANIfaceParams.cpp +++ b/libraries/AP_CANManager/AP_CANIfaceParams.cpp @@ -35,6 +35,14 @@ const AP_Param::GroupInfo AP_CANManager::CANIface_Params::var_info[] = { // @User: Advanced AP_GROUPINFO("BITRATE", 2, AP_CANManager::CANIface_Params, _bitrate, 1000000), +#if HAL_CANFD_SUPPORTED + // @Param: FDBITRATE + // @DisplayName: Bitrate of CANFD interface + // @Description: Bit rate can be set up to from 1000000 to 8000000 + // @Values: 1:1M, 2:2M, 4:4M, 5:5M, 8:8M + // @User: Advanced + AP_GROUPINFO("FDBITRATE", 3, AP_CANManager::CANIface_Params, _fdbitrate, HAL_CANFD_SUPPORTED), +#endif // Index 3 occupied by Param: DEBUG AP_GROUPEND }; diff --git a/libraries/AP_CANManager/AP_CANManager.cpp b/libraries/AP_CANManager/AP_CANManager.cpp index 8bf0c027e24..2bb83fa7cfc 100644 --- a/libraries/AP_CANManager/AP_CANManager.cpp +++ b/libraries/AP_CANManager/AP_CANManager.cpp @@ -25,7 +25,6 @@ #include #include #include -#include #include #include #include @@ -167,10 +166,10 @@ void AP_CANManager::init() // instead of a driver if (_slcan_interface.init_passthrough(i)) { // we have slcan bridge setup pass that on as can iface - can_initialised = hal.can[i]->init(_interfaces[i]._bitrate, AP_HAL::CANIface::NormalMode); + can_initialised = hal.can[i]->init(_interfaces[i]._bitrate, _interfaces[i]._fdbitrate*1000000, AP_HAL::CANIface::NormalMode); iface = &_slcan_interface; } else { - can_initialised = hal.can[i]->init(_interfaces[i]._bitrate, AP_HAL::CANIface::NormalMode); + can_initialised = hal.can[i]->init(_interfaces[i]._bitrate, _interfaces[i]._fdbitrate*1000000, AP_HAL::CANIface::NormalMode); } if (!can_initialised) { @@ -215,13 +214,6 @@ void AP_CANManager::init() AP_Param::load_object_from_eeprom((AP_KDECAN*)_drivers[drv_num], AP_KDECAN::var_info); #endif - } else if (drv_type[drv_num] == Driver_Type_ToshibaCAN) { - _drivers[drv_num] = new AP_ToshibaCAN; - - if (_drivers[drv_num] == nullptr) { - AP_BoardConfig::allocation_error("ToshibaCAN %d", drv_num + 1); - continue; - } } else if (drv_type[drv_num] == Driver_Type_PiccoloCAN) { #if HAL_PICCOLO_CAN_ENABLE _drivers[drv_num] = _drv_param[drv_num]._piccolocan = new AP_PiccoloCAN; @@ -234,7 +226,7 @@ void AP_CANManager::init() AP_Param::load_object_from_eeprom((AP_PiccoloCAN*)_drivers[drv_num], AP_PiccoloCAN::var_info); #endif } else if (drv_type[drv_num] == Driver_Type_CANTester) { -#if HAL_NUM_CAN_IFACES > 1 && !HAL_MINIMIZE_FEATURES +#if HAL_NUM_CAN_IFACES > 1 && !HAL_MINIMIZE_FEATURES && HAL_ENABLE_CANTESTER _drivers[drv_num] = _drv_param[drv_num]._testcan = new CANTester; if (_drivers[drv_num] == nullptr) { @@ -424,16 +416,86 @@ bool AP_CANManager::handle_can_forward(mavlink_channel_t chan, const mavlink_com /* handle a CAN_FRAME packet */ -void AP_CANManager::handle_can_frame(const mavlink_message_t &msg) const +void AP_CANManager::handle_can_frame(const mavlink_message_t &msg) { - mavlink_can_frame_t p; - mavlink_msg_can_frame_decode(&msg, &p); - if (p.bus >= HAL_NUM_CAN_IFACES || hal.can[p.bus] == nullptr) { - return; + if (frame_buffer == nullptr) { + // allocate frame buffer + WITH_SEMAPHORE(_sem); + // 20 is good for firmware upload + uint8_t buffer_size = 20; + while (frame_buffer == nullptr && buffer_size > 0) { + // we'd like 20 frames, but will live with less + frame_buffer = new ObjectBuffer(buffer_size); + if (frame_buffer != nullptr) { + // register a callback for when frames can't be sent immediately + hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_CANManager::process_frame_buffer, void)); + break; + } + buffer_size /= 2; + } + if (frame_buffer == nullptr) { + // disard the frames + return; + } + } + + switch (msg.msgid) { + case MAVLINK_MSG_ID_CAN_FRAME: { + mavlink_can_frame_t p; + mavlink_msg_can_frame_decode(&msg, &p); + if (p.bus >= HAL_NUM_CAN_IFACES || hal.can[p.bus] == nullptr) { + return; + } + struct BufferFrame frame { + bus : p.bus, + frame : AP_HAL::CANFrame(p.id, p.data, p.len) + }; + WITH_SEMAPHORE(_sem); + frame_buffer->push(frame); + break; + } + case MAVLINK_MSG_ID_CANFD_FRAME: { + mavlink_canfd_frame_t p; + mavlink_msg_canfd_frame_decode(&msg, &p); + if (p.bus >= HAL_NUM_CAN_IFACES || hal.can[p.bus] == nullptr) { + return; + } + struct BufferFrame frame { + bus : p.bus, + frame : AP_HAL::CANFrame(p.id, p.data, p.len, true) + }; + WITH_SEMAPHORE(_sem); + frame_buffer->push(frame); + break; + } + } + process_frame_buffer(); +} + +/* + process the frame buffer + */ +void AP_CANManager::process_frame_buffer(void) +{ + while (frame_buffer) { + WITH_SEMAPHORE(_sem); + struct BufferFrame frame; + const uint16_t timeout_us = 2000; + if (!frame_buffer->peek(frame)) { + // no frames in the queue + break; + } + const int16_t retcode = hal.can[frame.bus]->send(frame.frame, + AP_HAL::native_micros64() + timeout_us, + frame.frame.isCanFDFrame()?AP_HAL::CANIface::IsMAVCAN:0); + if (retcode == 0) { + // no space in the CAN output slots, try again later + break; + } + // retcode == 1 means sent, -1 means a frame that can't be + // sent. Either way we should remove from the queue + frame_buffer->pop(); } - const uint16_t timeout_us = 2000; - AP_HAL::CANFrame frame{p.id, p.data, p.len}; - hal.can[p.bus]->send(frame, AP_HAL::native_micros64() + timeout_us, AP_HAL::CANIface::IsMAVCAN); } /* @@ -527,7 +589,7 @@ void AP_CANManager::handle_can_filter_modify(const mavlink_message_t &msg) /* handler for CAN frames from the registered callback, sending frames - out as CAN_FRAME messages + out as CAN_FRAME or CANFD_FRAME messages */ void AP_CANManager::can_frame_callback(uint8_t bus, const AP_HAL::CANFrame &frame) { @@ -543,26 +605,34 @@ void AP_CANManager::can_frame_callback(uint8_t bus, const AP_HAL::CANFrame &fram can_forward.frame_counter = 0; } WITH_SEMAPHORE(comm_chan_lock(can_forward.chan)); - if (HAVE_PAYLOAD_SPACE(can_forward.chan, CAN_FRAME)) { - if (can_forward.num_filter_ids != 0) { - // work out ID of this frame - uint16_t id = 0; - if ((frame.id&0xff) != 0) { - // not anonymous - if (frame.id & 0x80) { - // service message - id = uint8_t(frame.id>>16); - } else { - // message frame - id = uint16_t(frame.id>>8); - } - } - if (!bisect_search_uint16(can_forward.filter_ids, can_forward.num_filter_ids, id)) { - return; + if (can_forward.filter_ids != nullptr) { + // work out ID of this frame + uint16_t id = 0; + if ((frame.id&0xff) != 0) { + // not anonymous + if (frame.id & 0x80) { + // service message + id = uint8_t(frame.id>>16); + } else { + // message frame + id = uint16_t(frame.id>>8); } } - mavlink_msg_can_frame_send(can_forward.chan, can_forward.system_id, can_forward.component_id, - bus, frame.dlc, frame.id, const_cast(frame.data)); + if (!bisect_search_uint16(can_forward.filter_ids, can_forward.num_filter_ids, id)) { + return; + } + } + const uint8_t data_len = AP_HAL::CANFrame::dlcToDataLength(frame.dlc); + if (frame.isCanFDFrame()) { + if (HAVE_PAYLOAD_SPACE(can_forward.chan, CANFD_FRAME)) { + mavlink_msg_canfd_frame_send(can_forward.chan, can_forward.system_id, can_forward.component_id, + bus, data_len, frame.id, const_cast(frame.data)); + } + } else { + if (HAVE_PAYLOAD_SPACE(can_forward.chan, CAN_FRAME)) { + mavlink_msg_can_frame_send(can_forward.chan, can_forward.system_id, can_forward.component_id, + bus, data_len, frame.id, const_cast(frame.data)); + } } } #endif // HAL_GCS_ENABLED diff --git a/libraries/AP_CANManager/AP_CANManager.h b/libraries/AP_CANManager/AP_CANManager.h index 730bdeda1f6..44cab3fe390 100644 --- a/libraries/AP_CANManager/AP_CANManager.h +++ b/libraries/AP_CANManager/AP_CANManager.h @@ -25,6 +25,7 @@ #include "AP_SLCANIface.h" #include "AP_CANDriver.h" #include +#include class AP_CANManager { @@ -55,7 +56,7 @@ class AP_CANManager Driver_Type_None = 0, Driver_Type_UAVCAN = 1, // 2 was KDECAN -- do not re-use - Driver_Type_ToshibaCAN = 3, + // 3 was ToshibaCAN -- do not re-use Driver_Type_PiccoloCAN = 4, Driver_Type_CANTester = 5, Driver_Type_EFI_NWPMU = 6, @@ -64,6 +65,7 @@ class AP_CANManager // 9 was Driver_Type_MPPT_PacketDigital Driver_Type_Scripting = 10, Driver_Type_Benewake = 11, + Driver_Type_Scripting2 = 12, }; void init(void); @@ -110,7 +112,7 @@ class AP_CANManager #if HAL_GCS_ENABLED bool handle_can_forward(mavlink_channel_t chan, const mavlink_command_long_t &packet, const mavlink_message_t &msg); - void handle_can_frame(const mavlink_message_t &msg) const; + void handle_can_frame(const mavlink_message_t &msg); void handle_can_filter_modify(const mavlink_message_t &msg); #endif @@ -132,6 +134,7 @@ class AP_CANManager private: AP_Int8 _driver_number; AP_Int32 _bitrate; + AP_Int32 _fdbitrate; }; //Parameter Interface for CANDrivers @@ -186,6 +189,15 @@ class AP_CANManager uint16_t num_filter_ids; uint16_t *filter_ids; } can_forward; + + // buffer for MAVCAN frames + struct BufferFrame { + uint8_t bus; + AP_HAL::CANFrame frame; + }; + ObjectBuffer *frame_buffer; + + void process_frame_buffer(void); #endif // HAL_GCS_ENABLED }; diff --git a/libraries/AP_CANManager/AP_CANTester.cpp b/libraries/AP_CANManager/AP_CANTester.cpp index dc25bc45dfa..a643a737826 100644 --- a/libraries/AP_CANManager/AP_CANTester.cpp +++ b/libraries/AP_CANManager/AP_CANTester.cpp @@ -20,8 +20,8 @@ #include #include "AP_CANManager.h" -#if HAL_MAX_CAN_PROTOCOL_DRIVERS > 1 && !HAL_MINIMIZE_FEATURES && HAL_CANMANAGER_ENABLED #include "AP_CANTester.h" +#if HAL_MAX_CAN_PROTOCOL_DRIVERS > 1 && !HAL_MINIMIZE_FEATURES && HAL_CANMANAGER_ENABLED && HAL_ENABLE_CANTESTER #include #include #include @@ -29,7 +29,6 @@ #include #include #include -#include #include #include "AP_CANTester_KDECAN.h" extern const AP_HAL::HAL& hal; @@ -39,9 +38,10 @@ const AP_Param::GroupInfo CANTester::var_info[] = { // @DisplayName: CAN Test Index // @Description: Selects the Index of Test that needs to be run recursively, this value gets reset to 0 at boot. // @Range: 0 4 - // @Values: 0:TEST_NONE, 1:TEST_LOOPBACK,2:TEST_BUSOFF_RECOVERY,3:TEST_UAVCAN_DNA,4:TEST_TOSHIBA_CAN, 5:TEST_KDE_CAN, 6:TEST_UAVCAN_ESC + // @Values: 0:TEST_NONE, 1:TEST_LOOPBACK,2:TEST_BUSOFF_RECOVERY,3:TEST_UAVCAN_DNA,5:TEST_KDE_CAN, 6:TEST_UAVCAN_ESC, 7:TEST_UAVCAN_FD_ESC // @User: Advanced AP_GROUPINFO("ID", 1, CANTester, _test_id, 0), + // @Param: LPR8 // @DisplayName: CANTester LoopRate // @Description: Selects the Looprate of Test methods @@ -192,18 +192,6 @@ void CANTester::main_thread() gcs().send_text(MAV_SEVERITY_ALERT, "Only one iface needs to be set for UAVCAN_DNA_TEST"); } break; - case CANTester::TEST_TOSHIBA_CAN: - if (_can_ifaces[1] == nullptr) { - gcs().send_text(MAV_SEVERITY_ALERT, "********Running Toshiba CAN Test********"); - if (test_toshiba_can()) { - gcs().send_text(MAV_SEVERITY_ALERT, "********Toshiba CAN Test Pass********"); - } else { - gcs().send_text(MAV_SEVERITY_ALERT, "********Toshiba CAN Test Fail********"); - } - } else { - gcs().send_text(MAV_SEVERITY_ALERT, "Only one iface needs to be set for TEST_TOSHIBA_CAN"); - } - break; case CANTester::TEST_KDE_CAN: if (_can_ifaces[1] == nullptr) { gcs().send_text(MAV_SEVERITY_ALERT, "********Running KDE CAN Test********"); @@ -219,7 +207,7 @@ void CANTester::main_thread() case CANTester::TEST_UAVCAN_ESC: if (_can_ifaces[1] == nullptr) { gcs().send_text(MAV_SEVERITY_ALERT, "********Running UAVCAN ESC Test********"); - if (test_uavcan_esc()) { + if (test_uavcan_esc(false)) { gcs().send_text(MAV_SEVERITY_ALERT, "********UAVCAN ESC Test Pass********"); } else { gcs().send_text(MAV_SEVERITY_ALERT, "********UAVCAN ESC Test Fail********"); @@ -228,6 +216,18 @@ void CANTester::main_thread() gcs().send_text(MAV_SEVERITY_ALERT, "Only one iface needs to be set for UAVCAN_ESC_TEST"); } break; + case CANTester::TEST_UAVCAN_FD_ESC: + if (_can_ifaces[1] == nullptr) { + gcs().send_text(MAV_SEVERITY_ALERT, "********Running UAVCAN FD ESC Test********"); + if (test_uavcan_esc(true)) { + gcs().send_text(MAV_SEVERITY_ALERT, "********UAVCAN FD ESC Test Pass********"); + } else { + gcs().send_text(MAV_SEVERITY_ALERT, "********UAVCAN FD ESC Test Fail********"); + } + } else { + gcs().send_text(MAV_SEVERITY_ALERT, "Only one iface needs to be set for UAVCAN_FD_ESC_TEST"); + } + break; default: break; } @@ -315,10 +315,10 @@ bool CANTester::test_loopback(uint32_t loop_rate) } for (uint8_t i = 0; i < _num_ifaces; i++) { - hal.console->printf("Loopback Test Results %d->%d:\n", i, (i+1)%2); - hal.console->printf("num_tx: %lu, failed_tx: %lu\n", + DEV_PRINTF("Loopback Test Results %d->%d:\n", i, (i+1)%2); + DEV_PRINTF("num_tx: %lu, failed_tx: %lu\n", (long unsigned int)_loopback_stats[i].num_tx, (long unsigned int)_loopback_stats[i].failed_tx); - hal.console->printf("num_rx: %lu, flushed_rx: %lu, bad_rx_data: %lu, bad_rx_seq: %lu\n", + DEV_PRINTF("num_rx: %lu, flushed_rx: %lu, bad_rx_data: %lu, bad_rx_seq: %lu\n", (long unsigned int)_loopback_stats[i].num_rx, (long unsigned int)_loopback_stats[i].num_flushed_rx, (long unsigned int)_loopback_stats[i].bad_rx_data, (long unsigned int)_loopback_stats[i].bad_rx_seq); if (_loopback_stats[i].num_rx < 0.9f * _loopback_stats[i].num_tx || @@ -340,7 +340,8 @@ void CANTester::reset_frame(AP_HAL::CANFrame& frame) void CANTester::create_loopback_frame(CANTester::loopback_stats_s &stats, AP_HAL::CANFrame& frame) { frame.id = 13 | AP_HAL::CANFrame::FlagEFF; - frame.dlc = AP_HAL::CANFrame::MaxDataLen; + frame.dlc = 8; + frame.setCanFD(stats.tx_seq%2); //every other frame is canfd if supported memcpy(frame.data, &stats.tx_seq, sizeof(stats.tx_seq)); uint32_t loopback_magic = LOOPBACK_MAGIC; memcpy(&frame.data[4], &loopback_magic, sizeof(loopback_magic)); @@ -349,7 +350,7 @@ void CANTester::create_loopback_frame(CANTester::loopback_stats_s &stats, AP_HAL void CANTester::check_loopback_frame(CANTester::loopback_stats_s &stats, AP_HAL::CANFrame& frame) { - if (frame.dlc != AP_HAL::CANFrame::MaxDataLen) { + if (frame.dlc != 8) { stats.bad_rx_data++; } @@ -380,7 +381,7 @@ bool CANTester::test_busoff_recovery() AP_HAL::CANFrame bo_frame; bo_frame.id = (10 | AP_HAL::CANFrame::FlagEFF); memset(bo_frame.data, 0xA, sizeof(bo_frame.data)); - bo_frame.dlc = AP_HAL::CANFrame::MaxDataLen; + bo_frame.dlc =8;//AP_HAL::CANFrame::MaxDataLen; bool bus_off_detected = false; // Bus Fault can be introduced by shorting CANH and CANL gcs().send_text(MAV_SEVERITY_ERROR, "Introduce Bus Off Fault on the bus."); @@ -499,192 +500,6 @@ bool CANTester::test_uavcan_dna() return true; } -/***************************************** - * TOSHIBA CAN Test * - *****************************************/ -#define NUM_TOSHIBA_TEST_RUN 1000 -bool CANTester::test_toshiba_can() -{ - AP_HAL::CANFrame frame; - uint16_t num_runs = NUM_TOSHIBA_TEST_RUN; - uint32_t num_errors = 0; - uint32_t num_lock_cmds = 0; - uint32_t num_request_data_cmds = 0; - uint32_t num_motor_cmds = 0; - uint32_t start_time = AP_HAL::native_millis(); - AP_HAL::CANIface::CanIOFlags flags; - - while (num_runs--) { - if (!read_frame(0, frame, _loop_rate, flags)) { - continue; - } - if (flags & AP_HAL::CANIface::Loopback) { - continue; - } - switch (frame.id) { - case AP_ToshibaCAN::COMMAND_LOCK: { - AP_ToshibaCAN::motor_lock_cmd_t lock_frame; - if (sizeof(lock_frame) != frame.dlc) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "Bad lock command length"); - num_errors++; - } - memcpy(&lock_frame, frame.data, sizeof(lock_frame)); - if (lock_frame.motor1 != 1 && lock_frame.motor1 != 2 && - lock_frame.motor2 != 1 && lock_frame.motor2 != 2 && - lock_frame.motor3 != 1 && lock_frame.motor3 != 2 && - lock_frame.motor4 != 1 && lock_frame.motor4 != 2 && - lock_frame.motor5 != 1 && lock_frame.motor5 != 2 && - lock_frame.motor6 != 1 && lock_frame.motor6 != 2 && - lock_frame.motor7 != 1 && lock_frame.motor7 != 2 && - lock_frame.motor8 != 1 && lock_frame.motor8 != 2 && - lock_frame.motor9 != 1 && lock_frame.motor9 != 2 && - lock_frame.motor10 != 1 && lock_frame.motor10 != 2 && - lock_frame.motor11 != 1 && lock_frame.motor11 != 2 && - lock_frame.motor12 != 1 && lock_frame.motor12 != 2) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "Bad lock frame received!"); - num_errors++; - } - num_lock_cmds++; - break; - } - case AP_ToshibaCAN::COMMAND_REQUEST_DATA: { - AP_ToshibaCAN::motor_request_data_cmd_t request_data_cmd; - if (sizeof(request_data_cmd) != frame.dlc) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "Bad request data command length"); - num_errors++; - } - memcpy(&request_data_cmd, frame.data, sizeof(request_data_cmd)); - if (!((request_data_cmd.motor1 == request_data_cmd.motor2 && - request_data_cmd.motor2 == request_data_cmd.motor3 && - request_data_cmd.motor3 == request_data_cmd.motor4 && - request_data_cmd.motor4 == request_data_cmd.motor5 && - request_data_cmd.motor5 == request_data_cmd.motor6 && - request_data_cmd.motor6 == request_data_cmd.motor7 && - request_data_cmd.motor7 == request_data_cmd.motor8 && - request_data_cmd.motor8 == request_data_cmd.motor9 && - request_data_cmd.motor9 == request_data_cmd.motor10 && - request_data_cmd.motor10 == request_data_cmd.motor11 && - request_data_cmd.motor11 == request_data_cmd.motor12) && - (request_data_cmd.motor1 == 0 || - request_data_cmd.motor1 == 1 || - request_data_cmd.motor1 == 2 || - request_data_cmd.motor1 == 3 || - request_data_cmd.motor1 == 4 || - request_data_cmd.motor1 == 5))) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "Bad request frame received!"); - num_errors++; - } - num_request_data_cmds++; - send_toshiba_can_reply(request_data_cmd.motor1); - break; - } - case AP_ToshibaCAN::COMMAND_MOTOR1: - case AP_ToshibaCAN::COMMAND_MOTOR2: - case AP_ToshibaCAN::COMMAND_MOTOR3: { - AP_ToshibaCAN::motor_rotation_cmd_t rotation_cmd; - if (frame.dlc != sizeof(rotation_cmd)) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "Bad motor command length"); - num_errors++; - } - memcpy(&rotation_cmd, frame.data, sizeof(rotation_cmd)); - if ((rotation_cmd.motor1 > AP_ToshibaCAN::TOSHIBACAN_OUTPUT_MAX) || - (rotation_cmd.motor2 > AP_ToshibaCAN::TOSHIBACAN_OUTPUT_MAX) || - (rotation_cmd.motor3 > AP_ToshibaCAN::TOSHIBACAN_OUTPUT_MAX) || - (rotation_cmd.motor4 > AP_ToshibaCAN::TOSHIBACAN_OUTPUT_MAX)) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "Bad motor command data"); - num_errors++; - } - num_motor_cmds++; - break; - } - default: { - gcs().send_text(MAV_SEVERITY_CRITICAL, "Unsupported Command"); - num_errors++; - break; - } - } - } - uint32_t num_secs = (AP_HAL::native_millis() - start_time)/1000; - gcs().send_text(MAV_SEVERITY_ALERT, "Num Errors: %lu Cmds Lock: %lu Request: %lu Motor: %lu", - (long unsigned int)num_errors, - (long unsigned int)num_lock_cmds, - (long unsigned int)num_request_data_cmds, - (long unsigned int)num_motor_cmds); - - gcs().send_text(MAV_SEVERITY_ALERT, "Rates Lock: %lu Request: %lu Motor: %lu", - (long unsigned int)num_lock_cmds/num_secs, - (long unsigned int)num_request_data_cmds/num_secs, - (long unsigned int)num_motor_cmds/num_secs); - if (num_errors) { - return false; - } else { - return true; - } -} - -bool CANTester::send_toshiba_can_reply(uint32_t cmd) -{ - AP_HAL::CANFrame send_frame; - for (uint8_t sub_id = 0; sub_id < TOSHIBACAN_MAX_NUM_ESCS; sub_id++) { - // decode rpm and voltage data - switch (cmd) { - case 1: { - // copy contents to our structure - AP_ToshibaCAN::motor_reply_data1_t reply_data; - reply_data.rpm = htobe16(100); - reply_data.current_ma = htobe16(1000); - reply_data.voltage_mv = htobe16(12000); - memcpy(send_frame.data, &reply_data, sizeof(reply_data.data)); - send_frame.id = AP_ToshibaCAN::MOTOR_DATA1 + sub_id; - memcpy(send_frame.data, &reply_data, sizeof(reply_data)); - send_frame.dlc = 8; - write_frame(0, send_frame, 1000); - continue; - } - - // decode temperature data - case 2: { - // motor data2 data format is 8 bytes (64 bits) - // 10 bits: U temperature - // 10 bits: V temperature - // 10 bits: W temperature - // 10 bits: motor temperature - // remaining 24 bits: reserved - const uint16_t temp = (300 * 5) + 20; - send_frame.data[0] = (temp >> 2) & 0xFF; - send_frame.data[1] = ((temp << 6) | ((temp >> 4) & 0x3F)) & 0xFF; - send_frame.data[2] = (((temp << 4) & 0xF0) | ((temp >> 6) & 0x0F)) & 0xFF; - send_frame.data[3] = (((temp << 2) & 0xFC) | ((temp >> 8) & 0x03)) & 0xFF; - send_frame.data[4] = temp & 0xFF; - send_frame.id = AP_ToshibaCAN::MOTOR_DATA2 + sub_id; - send_frame.dlc = 8; - write_frame(0, send_frame, 1000); - continue; - } - - // encode cumulative usage data - case 3: { - // motor data3 data format is 8 bytes (64 bits) - // 3 bytes: usage in seconds - // 2 bytes: number of times rotors started and stopped - // 3 bytes: reserved - uint32_t secs = AP_HAL::native_millis()/1000; - send_frame.data[0] = (secs >> 16) & 0xFF; - send_frame.data[0] = (secs >> 8) & 0xFF; - send_frame.data[0] = (secs & 0xFF); - send_frame.id = AP_ToshibaCAN::MOTOR_DATA3 + sub_id; - send_frame.dlc = 8; - write_frame(0, send_frame, 1000); - continue; - } - default: - return false; - } - } - return true; -} - - /***************************************** * KDE CAN Test * *****************************************/ @@ -746,12 +561,12 @@ void handle_raw_command(const uavcan::ReceivedDataStructuresetTxTimeout(uavcan::MonotonicDuration::fromMSec(2)); esc_status_publisher->setPriority(uavcan::TransferPriority::OneLowerThanHighest); + + if (enable_canfd) { + node->enableCanFd(); + } else { + node->disableCanFd(); + } node->setNodeID(client.getAllocatedNodeID()); node->setModeOperational(); } diff --git a/libraries/AP_CANManager/AP_CANTester.h b/libraries/AP_CANManager/AP_CANTester.h index 8fad7557683..640f7b4e485 100644 --- a/libraries/AP_CANManager/AP_CANTester.h +++ b/libraries/AP_CANManager/AP_CANTester.h @@ -18,7 +18,11 @@ #include "AP_CANDriver.h" #include #include -#if HAL_MAX_CAN_PROTOCOL_DRIVERS > 1 && !HAL_MINIMIZE_FEATURES && HAL_CANMANAGER_ENABLED +#ifndef HAL_ENABLE_CANTESTER +#define HAL_ENABLE_CANTESTER 0 +#endif + +#if HAL_MAX_CAN_PROTOCOL_DRIVERS > 1 && !HAL_MINIMIZE_FEATURES && HAL_CANMANAGER_ENABLED && HAL_ENABLE_CANTESTER class CANTester : public AP_CANDriver { @@ -48,9 +52,9 @@ class CANTester : public AP_CANDriver TEST_LOOPBACK, TEST_BUSOFF_RECOVERY, TEST_UAVCAN_DNA, - TEST_TOSHIBA_CAN, TEST_KDE_CAN, TEST_UAVCAN_ESC, + TEST_UAVCAN_FD_ESC, TEST_END, }; @@ -74,12 +78,10 @@ class CANTester : public AP_CANDriver bool test_busoff_recovery(); bool test_uavcan_dna(); - bool test_toshiba_can(); - bool send_toshiba_can_reply(uint32_t cmd); bool test_kdecan(); - bool test_uavcan_esc(); + bool test_uavcan_esc(bool enable_canfd); // write frame on CAN bus, returns true on success bool write_frame(uint8_t iface, AP_HAL::CANFrame &out_frame, uint64_t timeout); diff --git a/libraries/AP_CANManager/AP_CANTester_KDECAN.cpp b/libraries/AP_CANManager/AP_CANTester_KDECAN.cpp index 8527992b870..31737eb68ec 100644 --- a/libraries/AP_CANManager/AP_CANTester_KDECAN.cpp +++ b/libraries/AP_CANManager/AP_CANTester_KDECAN.cpp @@ -201,12 +201,12 @@ void AP_CANTester_KDECAN::loop(void) void AP_CANTester_KDECAN::print_stats(void) { - hal.console->printf("KDECANTester: TimeStamp: %u\n", (unsigned)AP_HAL::micros()); + DEV_PRINTF("KDECANTester: TimeStamp: %u\n", (unsigned)AP_HAL::micros()); for (uint16_t i=0; i<100; i++) { if (counters[i].frame_id == 0) { break; } - hal.console->printf("0x%08x: %u\n", (unsigned)counters[i].frame_id, (unsigned)counters[i].count); + DEV_PRINTF("0x%08x: %u\n", (unsigned)counters[i].frame_id, (unsigned)counters[i].count); counters[i].count = 0; } } diff --git a/libraries/AP_CANManager/AP_SLCANIface.cpp b/libraries/AP_CANManager/AP_SLCANIface.cpp index f4ad8986e43..8688ae65079 100644 --- a/libraries/AP_CANManager/AP_SLCANIface.cpp +++ b/libraries/AP_CANManager/AP_SLCANIface.cpp @@ -120,10 +120,11 @@ bool SLCAN::CANIface::push_Frame(AP_HAL::CANFrame &frame) * * The emitting functions below are highly optimized for speed. */ -bool SLCAN::CANIface::handle_FrameDataExt(const char* cmd) +bool SLCAN::CANIface::handle_FrameDataExt(const char* cmd, bool canfd) { - AP_HAL::CANFrame f; + AP_HAL::CANFrame f {}; hex2nibble_error = false; + f.canfd = canfd; f.id = f.FlagEFF | (hex2nibble(cmd[1]) << 28) | (hex2nibble(cmd[2]) << 24) | @@ -133,16 +134,53 @@ bool SLCAN::CANIface::handle_FrameDataExt(const char* cmd) (hex2nibble(cmd[6]) << 8) | (hex2nibble(cmd[7]) << 4) | (hex2nibble(cmd[8]) << 0); - if (cmd[9] < '0' || cmd[9] > ('0' + AP_HAL::CANFrame::MaxDataLen)) { + f.dlc = hex2nibble(cmd[9]); + if (hex2nibble_error || f.dlc > (canfd?15:8)) { return false; } - f.dlc = cmd[9] - '0'; - if (f.dlc > AP_HAL::CANFrame::MaxDataLen) { + { + const char* p = &cmd[10]; + const uint8_t dlen = AP_HAL::CANFrame::dlcToDataLength(f.dlc); + for (unsigned i = 0; i < dlen; i++) { + f.data[i] = (hex2nibble(*p) << 4) | hex2nibble(*(p + 1)); + p += 2; + } + } + if (hex2nibble_error) { + return false; + } + return push_Frame(f); +} + +/** + * General frame format: + * + * The emitting functions below are highly optimized for speed. + */ +bool SLCAN::CANIface::handle_FDFrameDataExt(const char* cmd) +{ +#if HAL_CANFD_SUPPORTED + return false; +#else + AP_HAL::CANFrame f {}; + hex2nibble_error = false; + f.canfd = true; + f.id = f.FlagEFF | + (hex2nibble(cmd[1]) << 28) | + (hex2nibble(cmd[2]) << 24) | + (hex2nibble(cmd[3]) << 20) | + (hex2nibble(cmd[4]) << 16) | + (hex2nibble(cmd[5]) << 12) | + (hex2nibble(cmd[6]) << 8) | + (hex2nibble(cmd[7]) << 4) | + (hex2nibble(cmd[8]) << 0); + f.dlc = hex2nibble(cmd[9]); + if (f.dlc > AP_HAL::CANFrame::dataLengthToDlc(AP_HAL::CANFrame::MaxDataLen)) { return false; } { const char* p = &cmd[10]; - for (unsigned i = 0; i < f.dlc; i++) { + for (unsigned i = 0; i < AP_HAL::CANFrame::dlcToDataLength(f.dlc); i++) { f.data[i] = (hex2nibble(*p) << 4) | hex2nibble(*(p + 1)); p += 2; } @@ -151,20 +189,21 @@ bool SLCAN::CANIface::handle_FrameDataExt(const char* cmd) return false; } return push_Frame(f); +#endif //#if HAL_CANFD_SUPPORTED } bool SLCAN::CANIface::handle_FrameDataStd(const char* cmd) { - AP_HAL::CANFrame f; + AP_HAL::CANFrame f {}; hex2nibble_error = false; f.id = (hex2nibble(cmd[1]) << 8) | (hex2nibble(cmd[2]) << 4) | (hex2nibble(cmd[3]) << 0); - if (cmd[4] < '0' || cmd[4] > ('0' + AP_HAL::CANFrame::MaxDataLen)) { + if (cmd[4] < '0' || cmd[4] > ('0' + AP_HAL::CANFrame::NonFDCANMaxDataLen)) { return false; } f.dlc = cmd[4] - '0'; - if (f.dlc > AP_HAL::CANFrame::MaxDataLen) { + if (f.dlc > AP_HAL::CANFrame::NonFDCANMaxDataLen) { return false; } { @@ -182,7 +221,7 @@ bool SLCAN::CANIface::handle_FrameDataStd(const char* cmd) bool SLCAN::CANIface::handle_FrameRTRExt(const char* cmd) { - AP_HAL::CANFrame f; + AP_HAL::CANFrame f {}; hex2nibble_error = false; f.id = f.FlagEFF | f.FlagRTR | (hex2nibble(cmd[1]) << 28) | @@ -193,12 +232,12 @@ bool SLCAN::CANIface::handle_FrameRTRExt(const char* cmd) (hex2nibble(cmd[6]) << 8) | (hex2nibble(cmd[7]) << 4) | (hex2nibble(cmd[8]) << 0); - if (cmd[9] < '0' || cmd[9] > ('0' + AP_HAL::CANFrame::MaxDataLen)) { + if (cmd[9] < '0' || cmd[9] > ('0' + AP_HAL::CANFrame::NonFDCANMaxDataLen)) { return false; } f.dlc = cmd[9] - '0'; - if (f.dlc > AP_HAL::CANFrame::MaxDataLen) { + if (f.dlc > AP_HAL::CANFrame::NonFDCANMaxDataLen) { return false; } if (hex2nibble_error) { @@ -209,17 +248,17 @@ bool SLCAN::CANIface::handle_FrameRTRExt(const char* cmd) bool SLCAN::CANIface::handle_FrameRTRStd(const char* cmd) { - AP_HAL::CANFrame f; + AP_HAL::CANFrame f {}; hex2nibble_error = false; f.id = f.FlagRTR | (hex2nibble(cmd[1]) << 8) | (hex2nibble(cmd[2]) << 4) | (hex2nibble(cmd[3]) << 0); - if (cmd[4] < '0' || cmd[4] > ('0' + AP_HAL::CANFrame::MaxDataLen)) { + if (cmd[4] < '0' || cmd[4] > ('0' + AP_HAL::CANFrame::NonFDCANMaxDataLen)) { return false; } f.dlc = cmd[4] - '0'; - if (f.dlc <= AP_HAL::CANFrame::MaxDataLen) { + if (f.dlc <= AP_HAL::CANFrame::NonFDCANMaxDataLen) { return false; } if (hex2nibble_error) { @@ -267,7 +306,11 @@ int16_t SLCAN::CANIface::reportFrame(const AP_HAL::CANFrame& frame, uint64_t tim if (_port == nullptr) { return -1; } +#if HAL_CANFD_SUPPORTED + constexpr unsigned SLCANMaxFrameSize = 200; +#else constexpr unsigned SLCANMaxFrameSize = 40; +#endif uint8_t buffer[SLCANMaxFrameSize] = {'\0'}; uint8_t* p = &buffer[0]; /* @@ -277,7 +320,13 @@ int16_t SLCAN::CANIface::reportFrame(const AP_HAL::CANFrame& frame, uint64_t tim *p++ = frame.isExtended() ? 'R' : 'r'; } else if (frame.isErrorFrame()) { return -1; // Not supported - } else { + } +#if HAL_CANFD_SUPPORTED + else if (frame.canfd) { + *p++ = frame.isExtended() ? 'D' : 'd'; + } +#endif + else { *p++ = frame.isExtended() ? 'T' : 't'; } @@ -301,12 +350,12 @@ int16_t SLCAN::CANIface::reportFrame(const AP_HAL::CANFrame& frame, uint64_t tim /* * DLC */ - *p++ = char('0' + frame.dlc); + *p++ = nibble2hex(frame.dlc); /* * Data */ - for (unsigned i = 0; i < frame.dlc; i++) { + for (unsigned i = 0; i < AP_HAL::CANFrame::dlcToDataLength(frame.dlc); i++) { const uint8_t byte = frame.data[i]; *p++ = nibble2hex(byte >> 4); *p++ = nibble2hex(byte); @@ -351,8 +400,8 @@ const char* SLCAN::CANIface::processCommand(char* cmd) /* * High-traffic SLCAN commands go first */ - if (cmd[0] == 'T') { - return handle_FrameDataExt(cmd) ? "Z\r" : "\a"; + if (cmd[0] == 'T' || cmd[0] == 'D') { + return handle_FrameDataExt(cmd, cmd[0]=='D') ? "Z\r" : "\a"; } else if (cmd[0] == 't') { return handle_FrameDataStd(cmd) ? "z\r" : "\a"; } else if (cmd[0] == 'R') { @@ -361,6 +410,12 @@ const char* SLCAN::CANIface::processCommand(char* cmd) // See long commands below return handle_FrameRTRStd(cmd) ? "z\r" : "\a"; } +#if HAL_CANFD_SUPPORTED + else if (cmd[0] == 'D') { + return handle_FDFrameDataExt(cmd) ? "Z\r" : "\a"; + } +#endif + uint8_t resp_bytes[40]; uint16_t resp_len; /* @@ -456,12 +511,17 @@ inline void SLCAN::CANIface::addByte(const uint8_t byte) void SLCAN::CANIface::update_slcan_port() { + const bool armed = hal.util->get_soft_armed(); if (_set_by_sermgr) { - // Once we pick SerialManager path we hold on - // to that until reboot + if (armed && _port != nullptr) { + // auto-disable when armed + _port->lock_port(0, 0); + _port = nullptr; + _set_by_sermgr = false; + } return; } - if (_port == nullptr) { + if (_port == nullptr && !armed) { _port = AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_SLCAN, 0); if (_port != nullptr) { _port->lock_port(_serial_lock_key, _serial_lock_key); @@ -622,7 +682,11 @@ int16_t SLCAN::CANIface::send(const AP_HAL::CANFrame& frame, uint64_t tx_deadlin return ret; } - if (frame.isErrorFrame() || frame.dlc > 8) { + if (frame.isErrorFrame() +#if !HAL_CANFD_SUPPORTED + || frame.dlc > 8 +#endif + ) { return ret; } reportFrame(frame, AP_HAL::native_micros64()); diff --git a/libraries/AP_CANManager/AP_SLCANIface.h b/libraries/AP_CANManager/AP_SLCANIface.h index 9991c37b485..00e96eb44bb 100644 --- a/libraries/AP_CANManager/AP_SLCANIface.h +++ b/libraries/AP_CANManager/AP_SLCANIface.h @@ -50,7 +50,9 @@ class CANIface: public AP_HAL::CANIface bool handle_FrameRTRStd(const char* cmd); bool handle_FrameRTRExt(const char* cmd); bool handle_FrameDataStd(const char* cmd); - bool handle_FrameDataExt(const char* cmd); + bool handle_FrameDataExt(const char* cmd, bool canfd); + + bool handle_FDFrameDataExt(const char* cmd); // Parsing bytes received on the serial port inline void addByte(const uint8_t byte); diff --git a/libraries/AP_Camera/AP_Camera.cpp b/libraries/AP_Camera/AP_Camera.cpp index c195823e552..f7dcfc43933 100644 --- a/libraries/AP_Camera/AP_Camera.cpp +++ b/libraries/AP_Camera/AP_Camera.cpp @@ -10,6 +10,7 @@ #include #include #include +#include #include "AP_Camera_SoloGimbal.h" // ------------------------------ @@ -19,7 +20,7 @@ const AP_Param::GroupInfo AP_Camera::var_info[] = { // @Param: TRIGG_TYPE // @DisplayName: Camera shutter (trigger) type // @Description: how to trigger the camera to take a picture - // @Values: 0:Servo,1:Relay, 2:GoPro in Solo Gimbal + // @Values: 0:Servo,1:Relay, 2:GoPro in Solo Gimbal, 3:Mount (Siyi) // @User: Standard AP_GROUPINFO("TRIGG_TYPE", 0, AP_Camera, _trigger_type, 0), @@ -80,7 +81,7 @@ const AP_Param::GroupInfo AP_Camera::var_info[] = { // @Param: FEEDBACK_PIN // @DisplayName: Camera feedback pin - // @Description: pin number to use for save accurate camera feedback messages. If set to -1 then don't use a pin flag for this, otherwise this is a pin number which if held high after a picture trigger order, will save camera messages when camera really takes a picture. A universal camera hot shoe is needed. The pin should be held high for at least 2 milliseconds for reliable trigger detection. See also the CAM_FEEDBACK_POL option. + // @Description: pin number to use for save accurate camera feedback messages. If set to -1 then don't use a pin flag for this, otherwise this is a pin number which if held high after a picture trigger order, will save camera messages when camera really takes a picture. A universal camera hot shoe is needed. The pin should be held high for at least 2 milliseconds for reliable trigger detection. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot. See also the CAM_FEEDBACK_POL option. // @Values: -1:Disabled,50:AUX1,51:AUX2,52:AUX3,53:AUX4,54:AUX5,55:AUX6 // @User: Standard // @RebootRequired: True @@ -157,6 +158,15 @@ void AP_Camera::trigger_pic() case CamTrigType::gopro: // gopro in Solo Gimbal AP_Camera_SoloGimbal::gopro_shutter_toggle(); break; +#endif +#if HAL_MOUNT_ENABLED + case CamTrigType::mount: { + AP_Mount* mount = AP::mount(); + if (mount != nullptr) { + mount->take_picture(0); + } + break; + } #endif default: break; @@ -190,6 +200,7 @@ AP_Camera::trigger_pic_cleanup() break; } case CamTrigType::gopro: + case CamTrigType::mount: // nothing to do break; } @@ -368,9 +379,9 @@ void AP_Camera::update() const AP_AHRS &ahrs = AP::ahrs(); Location current_loc; - if (!ahrs.get_location(current_loc)) { - // completely ignore this failure! AHRS will provide its best guess. - } + + // ignore failure - AHRS will provide its best guess + IGNORE_RETURN(ahrs.get_location(current_loc)); if (_last_location.lat == 0 && _last_location.lng == 0) { _last_location = current_loc; @@ -394,15 +405,7 @@ void AP_Camera::update() return; } - uint32_t tnow = AP_HAL::millis(); - if (tnow - _last_photo_time < (unsigned) _min_interval) { - return; - } - take_picture(); - - _last_location = current_loc; - _last_photo_time = tnow; } /* @@ -487,6 +490,17 @@ void AP_Camera::log_picture() // take_picture - take a picture void AP_Camera::take_picture() { + uint32_t tnow = AP_HAL::millis(); + if (tnow - _last_photo_time < (unsigned) _min_interval) { + _trigger_pending = true; + return; + } + _trigger_pending = false; + + IGNORE_RETURN(AP::ahrs().get_location(_last_location)); + + _last_photo_time = tnow; + // take a local picture: trigger_pic(); @@ -499,6 +513,69 @@ void AP_Camera::take_picture() GCS_MAVLINK::send_to_components(MAVLINK_MSG_ID_COMMAND_LONG, (char*)&cmd_msg, sizeof(cmd_msg)); } +// start/stop recording video. returns true on success +// start_recording should be true to start recording, false to stop recording +bool AP_Camera::record_video(bool start_recording) +{ +#if HAL_MOUNT_ENABLED + // only mount implements recording video + if (get_trigger_type() == CamTrigType::mount) { + AP_Mount* mount = AP::mount(); + if (mount != nullptr) { + return mount->record_video(0, start_recording); + } + } +#endif + return false; +} + +// zoom in, out or hold. returns true on success +// zoom out = -1, hold = 0, zoom in = 1 +bool AP_Camera::set_zoom_step(int8_t zoom_step) +{ +#if HAL_MOUNT_ENABLED + // only mount implements set_zoom_step + if (get_trigger_type() == CamTrigType::mount) { + AP_Mount* mount = AP::mount(); + if (mount != nullptr) { + return mount->set_zoom_step(0, zoom_step); + } + } +#endif + return false; +} + +// focus in, out or hold. returns true on success +// focus in = -1, focus hold = 0, focus out = 1 +bool AP_Camera::set_manual_focus_step(int8_t focus_step) +{ +#if HAL_MOUNT_ENABLED + // only mount implements set_manual_focus_step + if (get_trigger_type() == CamTrigType::mount) { + AP_Mount* mount = AP::mount(); + if (mount != nullptr) { + return mount->set_manual_focus_step(0, focus_step); + } + } +#endif + return false; +} + +// auto focus. returns true on success +bool AP_Camera::set_auto_focus() +{ +#if HAL_MOUNT_ENABLED + // only mount implements set_auto_focus + if (get_trigger_type() == CamTrigType::mount) { + AP_Mount* mount = AP::mount(); + if (mount != nullptr) { + return mount->set_auto_focus(0); + } + } +#endif + return false; +} + void AP_Camera::prep_mavlink_msg_camera_feedback(uint64_t timestamp_us) { const AP_AHRS &ahrs = AP::ahrs(); @@ -519,6 +596,9 @@ void AP_Camera::prep_mavlink_msg_camera_feedback(uint64_t timestamp_us) */ void AP_Camera::update_trigger() { + if (_trigger_pending) { + take_picture(); + } trigger_pic_cleanup(); if (_camera_trigger_logged != _camera_trigger_count) { @@ -547,10 +627,11 @@ AP_Camera::CamTrigType AP_Camera::get_trigger_type(void) case CamTrigType::servo: case CamTrigType::relay: case CamTrigType::gopro: + case CamTrigType::mount: return (CamTrigType)type; default: return CamTrigType::servo; - } + } } // singleton instance diff --git a/libraries/AP_Camera/AP_Camera.h b/libraries/AP_Camera/AP_Camera.h index 64f070477ae..efbfd3cb991 100644 --- a/libraries/AP_Camera/AP_Camera.h +++ b/libraries/AP_Camera/AP_Camera.h @@ -2,9 +2,10 @@ /// @brief Photo or video camera manager, with EEPROM-backed storage of constants. #pragma once +#include +#include #include -#include -#include +#include #define AP_CAMERA_TRIGGER_DEFAULT_DURATION 10 // default duration servo or relay is held open in 10ths of a second (i.e. 10 = 1 second) @@ -56,6 +57,21 @@ class AP_Camera { void take_picture(); + // start/stop recording video + // start_recording should be true to start recording, false to stop recording + bool record_video(bool start_recording); + + // zoom in, out or hold + // zoom out = -1, hold = 0, zoom in = 1 + bool set_zoom_step(int8_t zoom_step); + + // focus in, out or hold + // focus in = -1, focus hold = 0, focus out = 1 + bool set_manual_focus_step(int8_t focus_step); + + // auto focus + bool set_auto_focus(); + // Update - to be called periodically @at least 50Hz void update(); @@ -76,6 +92,7 @@ class AP_Camera { servo = 0, relay = 1, gopro = 2, + mount = 3, }; AP_Camera::CamTrigType get_trigger_type(void); @@ -107,6 +124,7 @@ class AP_Camera { AP_Int16 _min_interval; // Minimum time between shots required by camera AP_Int16 _max_roll; // Maximum acceptable roll angle when trigging camera uint32_t _last_photo_time; // last time a photo was taken + bool _trigger_pending; // true when we have delayed take_picture struct Location _last_location; uint16_t _image_index; // number of pictures taken since boot diff --git a/libraries/AP_Camera/AP_RunCam.cpp b/libraries/AP_Camera/AP_RunCam.cpp index 90de281d9d4..4cf05fe9560 100644 --- a/libraries/AP_Camera/AP_RunCam.cpp +++ b/libraries/AP_Camera/AP_RunCam.cpp @@ -34,7 +34,7 @@ const AP_Param::GroupInfo AP_RunCam::var_info[] = { // @Param: TYPE // @DisplayName: RunCam device type // @Description: RunCam deviee type used to determine OSD menu structure and shutter options. - // @Values: 0:Disabled, 1:RunCam Split Micro/RunCam with UART, 2:RunCam Split, 3:RunCam Split4 4k, 4:RunCam Hybrid + // @Values: 0:Disabled, 1:RunCam Split Micro/RunCam with UART, 2:RunCam Split, 3:RunCam Split4 4k, 4:RunCam Hybrid/RunCam Thumb Pro AP_GROUPINFO_FLAGS("TYPE", 1, AP_RunCam, _cam_type, int(DeviceType::Disabled), AP_PARAM_FLAG_ENABLE), // @Param: FEATURES @@ -123,7 +123,7 @@ AP_RunCam::AP_RunCam() AP_HAL::panic("AP_RunCam must be singleton"); } _singleton = this; - _cam_type = constrain_int16(_cam_type, 0, RUNCAM_MAX_DEVICE_TYPES); + _cam_type.set(constrain_int16(_cam_type, 0, RUNCAM_MAX_DEVICE_TYPES)); _video_recording = VideoOption(_cam_control_option & uint8_t(ControlOption::VIDEO_RECORDING_AT_BOOT)); } @@ -142,6 +142,7 @@ void AP_RunCam::init() without a runcam */ _cam_type.set_default(int8_t(DeviceType::SplitMicro)); + AP_Param::invalidate_count(); } if (_cam_type.get() == int8_t(DeviceType::Disabled)) { uart = nullptr; @@ -498,15 +499,17 @@ AP_RunCam::Event AP_RunCam::map_rc_input_to_event() const } else if (_osd_option == OSDOption::ENTER && _cam_control_option & uint8_t(ControlOption::TWO_POS_SWITCH)) { result = Event::ENTER_MENU; - } else if (_osd_option == OSDOption::OPTION + } else if ((_osd_option == OSDOption::OPTION || _osd_option == OSDOption::ENTER) && _cam_control_option & uint8_t(ControlOption::THREE_POS_SWITCH)) { result = Event::ENTER_MENU; } else if (_osd_option == OSDOption::EXIT && _cam_control_option & uint8_t(ControlOption::TWO_POS_SWITCH)) { result = Event::EXIT_MENU; - } else if (_osd_option == OSDOption::NO_OPTION + } else if ((_osd_option == OSDOption::NO_OPTION || _osd_option == OSDOption::EXIT) && _cam_control_option & uint8_t(ControlOption::THREE_POS_SWITCH)) { result = Event::EXIT_MENU; + } else { + debug("map_rc_input_to_event(): nothing selected\n"); } return result; } @@ -950,7 +953,7 @@ void AP_RunCam::parse_device_info(const Request& request) uint8_t featureLowBits = request._recv_buf[2]; uint8_t featureHighBits = request._recv_buf[3]; if (!has_feature(Feature::FEATURES_OVERRIDE)) { - _features = (featureHighBits << 8) | featureLowBits; + _features.set((featureHighBits << 8) | featureLowBits); } if (_features > 0) { _state = State::INITIALIZED; diff --git a/libraries/AP_CheckFirmware/AP_CheckFirmware.cpp b/libraries/AP_CheckFirmware/AP_CheckFirmware.cpp new file mode 100644 index 00000000000..940048e8b56 --- /dev/null +++ b/libraries/AP_CheckFirmware/AP_CheckFirmware.cpp @@ -0,0 +1,228 @@ +/* + support checking board ID and firmware CRC in the bootloader + */ +#include "AP_CheckFirmware.h" +#include +#include + +#if AP_CHECK_FIRMWARE_ENABLED + +#if defined(HAL_BOOTLOADER_BUILD) + +#if AP_SIGNED_FIRMWARE +#include "../../Tools/AP_Bootloader/support.h" +#include +#include "monocypher.h" + +const struct ap_secure_data public_keys __attribute__((section(".apsec_data"))); + +/* + return true if all public keys are zero. We allow boot of an + unsigned firmware in that case + */ +static bool all_zero_public_keys(void) +{ + /* + look over all public keys, if one matches then we are OK + */ + const uint8_t zero_key[AP_PUBLIC_KEY_LEN] {}; + for (const auto &public_key : public_keys.public_key) { + if (memcmp(public_key.key, zero_key, AP_PUBLIC_KEY_LEN) != 0) { + return false; + } + } + return true; +} + +/* + check a signature against bootloader keys + */ +static check_fw_result_t check_firmware_signature(const app_descriptor_signed *ad, + const uint8_t *flash1, uint32_t len1, + const uint8_t *flash2, uint32_t len2) +{ + if (all_zero_public_keys()) { + return check_fw_result_t::CHECK_FW_OK; + } + + // 8 byte signature version + static const uint64_t sig_version = 30437LLU; + if (ad->signature_length != 72) { + return check_fw_result_t::FAIL_REASON_BAD_FIRMWARE_SIGNATURE; + } + if (memcmp((const uint8_t*)&sig_version, ad->signature, sizeof(sig_version)) != 0) { + return check_fw_result_t::FAIL_REASON_BAD_FIRMWARE_SIGNATURE; + } + + /* + look over all public keys, if one matches then we are OK + */ + for (const auto &public_key : public_keys.public_key) { + crypto_check_ctx ctx {}; + crypto_check_ctx_abstract *actx = (crypto_check_ctx_abstract*)&ctx; + crypto_check_init(actx, &ad->signature[sizeof(sig_version)], public_key.key); + + crypto_check_update(actx, flash1, len1); + crypto_check_update(actx, flash2, len2); + if (crypto_check_final(actx) == 0) { + // good signature + return check_fw_result_t::CHECK_FW_OK; + } + } + + // none of the public keys matched + return check_fw_result_t::FAIL_REASON_VERIFICATION; +} +#endif // AP_SIGNED_FIRMWARE + +/* + check firmware CRC and board ID to see if it matches + */ +static check_fw_result_t check_good_firmware_signed(void) +{ + const uint8_t sig[8] = AP_APP_DESCRIPTOR_SIGNATURE_SIGNED; + const uint8_t *flash1 = (const uint8_t *)(FLASH_LOAD_ADDRESS + (FLASH_BOOTLOADER_LOAD_KB + APP_START_OFFSET_KB)*1024); + const uint32_t flash_size = (BOARD_FLASH_SIZE - (FLASH_BOOTLOADER_LOAD_KB + APP_START_OFFSET_KB))*1024; + const app_descriptor_signed *ad = (const app_descriptor_signed *)memmem(flash1, flash_size-sizeof(app_descriptor_signed), sig, sizeof(sig)); + if (ad == nullptr) { + // no application signature + return check_fw_result_t::FAIL_REASON_NO_APP_SIG; + } + // check length + if (ad->image_size > flash_size) { + return check_fw_result_t::FAIL_REASON_BAD_LENGTH_APP; + } + + bool id_ok = (ad->board_id == APJ_BOARD_ID); +#ifdef ALT_BOARD_ID + id_ok |= (ad->board_id == ALT_BOARD_ID); +#endif + + if (!id_ok) { + return check_fw_result_t::FAIL_REASON_BAD_BOARD_ID; + } + + const uint8_t *flash2 = (const uint8_t *)&ad->version_major; + const uint8_t desc_len = offsetof(app_descriptor_signed, version_major) - offsetof(app_descriptor_signed, image_crc1); + const uint32_t len1 = ((const uint8_t *)&ad->image_crc1) - flash1; + + if ((len1 + desc_len) > ad->image_size) { + return check_fw_result_t::FAIL_REASON_BAD_LENGTH_DESCRIPTOR; + } + + const uint32_t len2 = ad->image_size - (len1 + desc_len); + uint32_t crc1 = crc32_small(0, flash1, len1); + uint32_t crc2 = crc32_small(0, flash2, len2); + if (crc1 != ad->image_crc1 || crc2 != ad->image_crc2) { + return check_fw_result_t::FAIL_REASON_BAD_CRC; + } + + check_fw_result_t ret = check_fw_result_t::CHECK_FW_OK; + +#if AP_SIGNED_FIRMWARE + ret = check_firmware_signature(ad, flash1, len1, flash2, len2); +#endif + + return ret; +} + +/* + check firmware CRC and board ID to see if it matches, using unsigned + signature + */ +static check_fw_result_t check_good_firmware_unsigned(void) +{ + const uint8_t sig[8] = AP_APP_DESCRIPTOR_SIGNATURE_UNSIGNED; + const uint8_t *flash1 = (const uint8_t *)(FLASH_LOAD_ADDRESS + (FLASH_BOOTLOADER_LOAD_KB + APP_START_OFFSET_KB)*1024); + const uint32_t flash_size = (BOARD_FLASH_SIZE - (FLASH_BOOTLOADER_LOAD_KB + APP_START_OFFSET_KB))*1024; + const app_descriptor_unsigned *ad = (const app_descriptor_unsigned *)memmem(flash1, flash_size-sizeof(app_descriptor_unsigned), sig, sizeof(sig)); + if (ad == nullptr) { + // no application signature + return check_fw_result_t::FAIL_REASON_NO_APP_SIG; + } + // check length + if (ad->image_size > flash_size) { + return check_fw_result_t::FAIL_REASON_BAD_LENGTH_APP; + } + + bool id_ok = (ad->board_id == APJ_BOARD_ID); +#ifdef ALT_BOARD_ID + id_ok |= (ad->board_id == ALT_BOARD_ID); +#endif + + if (!id_ok) { + return check_fw_result_t::FAIL_REASON_BAD_BOARD_ID; + } + + const uint8_t *flash2 = (const uint8_t *)&ad->version_major; + const uint8_t desc_len = offsetof(app_descriptor_unsigned, version_major) - offsetof(app_descriptor_unsigned, image_crc1); + const uint32_t len1 = ((const uint8_t *)&ad->image_crc1) - flash1; + + if ((len1 + desc_len) > ad->image_size) { + return check_fw_result_t::FAIL_REASON_BAD_LENGTH_DESCRIPTOR; + } + + const uint32_t len2 = ad->image_size - (len1 + desc_len); + uint32_t crc1 = crc32_small(0, flash1, len1); + uint32_t crc2 = crc32_small(0, flash2, len2); + if (crc1 != ad->image_crc1 || crc2 != ad->image_crc2) { + return check_fw_result_t::FAIL_REASON_BAD_CRC; + } + + return check_fw_result_t::CHECK_FW_OK; +} + +check_fw_result_t check_good_firmware(void) +{ +#if AP_SIGNED_FIRMWARE + // allow unsigned format if we have no public keys. This allows + // for use of SECURE_COMMAND to remove all public keys and then + // load of unsigned firmware + const auto ret = check_good_firmware_signed(); + if (ret != check_fw_result_t::CHECK_FW_OK && + all_zero_public_keys() && + check_good_firmware_unsigned() == check_fw_result_t::CHECK_FW_OK) { + return check_fw_result_t::CHECK_FW_OK; + } + return ret; +#else + const auto ret = check_good_firmware_unsigned(); + if (ret != check_fw_result_t::CHECK_FW_OK) { + // allow for signed format, not checking public keys. This + // allows for booting of a signed firmware with an unsigned + // bootloader, which allows for bootstrapping a system up from + // unsigned to signed + return check_good_firmware_signed(); + } + return ret; +#endif +} + +#endif // HAL_BOOTLOADER_BUILD + +#if !defined(HAL_BOOTLOADER_BUILD) +extern const AP_HAL::HAL &hal; + +/* + declare constant app_descriptor in flash + */ +extern const app_descriptor_t app_descriptor; +#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS +const app_descriptor_t app_descriptor __attribute__((section(".app_descriptor"))); +#else +const app_descriptor_t app_descriptor; +#endif + +/* + this is needed to ensure we don't elide the app_descriptor + */ +void check_firmware_print(void) +{ + hal.console->printf("Booting %u/%u\n", + app_descriptor.version_major, + app_descriptor.version_minor); +} +#endif + + +#endif // AP_CHECK_FIRMWARE_ENABLED diff --git a/libraries/AP_CheckFirmware/AP_CheckFirmware.h b/libraries/AP_CheckFirmware/AP_CheckFirmware.h new file mode 100644 index 00000000000..cf0837d20ca --- /dev/null +++ b/libraries/AP_CheckFirmware/AP_CheckFirmware.h @@ -0,0 +1,173 @@ +/* + support checking board ID and firmware CRC in the bootloader + */ +#pragma once + +#include +#include +#include +#ifndef HAL_BOOTLOADER_BUILD +#include +#endif + +#ifndef AP_CHECK_FIRMWARE_ENABLED +#define AP_CHECK_FIRMWARE_ENABLED AP_OPENDRONEID_ENABLED +#endif + +#if AP_CHECK_FIRMWARE_ENABLED + +enum class check_fw_result_t : uint8_t { + CHECK_FW_OK = 0, + FAIL_REASON_NO_APP_SIG = 10, + FAIL_REASON_BAD_LENGTH_APP = 11, + FAIL_REASON_BAD_BOARD_ID = 12, + FAIL_REASON_BAD_CRC = 13, + FAIL_REASON_IN_UPDATE = 14, + FAIL_REASON_WATCHDOG = 15, + FAIL_REASON_BAD_LENGTH_DESCRIPTOR = 16, + FAIL_REASON_BAD_FIRMWARE_SIGNATURE = 17, + FAIL_REASON_VERIFICATION = 18, +}; + +#ifndef FW_MAJOR +#define APP_FW_MAJOR 0 +#define APP_FW_MINOR 0 +#else +#define APP_FW_MAJOR FW_MAJOR +#define APP_FW_MINOR FW_MINOR +#endif + +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && !defined(APJ_BOARD_ID) +// this allows for sitl_periph_gps to build +#define APJ_BOARD_ID 0 +#endif + +/* + the app_descriptor stored in flash in the main firmware and is used + by the bootloader to confirm that the firmware is not corrupt and is + suitable for this board. The build dependent values in this structure + are filled in by set_app_descriptor() in the waf build + + Note that we need to define both structures to make it possible to + boot a signed firmware using a bootloader setup for unsigned + */ + +#define AP_APP_DESCRIPTOR_SIGNATURE_SIGNED { 0x41, 0xa3, 0xe5, 0xf2, 0x65, 0x69, 0x92, 0x07 } +#define AP_APP_DESCRIPTOR_SIGNATURE_UNSIGNED { 0x40, 0xa2, 0xe4, 0xf1, 0x64, 0x68, 0x91, 0x06 } + +struct app_descriptor_unsigned { + uint8_t sig[8] = AP_APP_DESCRIPTOR_SIGNATURE_UNSIGNED; + // crc1 is the crc32 from firmware start to start of image_crc1 + uint32_t image_crc1 = 0; + // crc2 is the crc32 from the start of version_major to the end of the firmware + uint32_t image_crc2 = 0; + // total size of firmware image in bytes + uint32_t image_size = 0; + uint32_t git_hash = 0; + + // software version number + uint8_t version_major = APP_FW_MAJOR; + uint8_t version_minor = APP_FW_MINOR; + // APJ_BOARD_ID (hardware version). This is also used in CAN NodeInfo + // with high byte in HardwareVersion.major and low byte in HardwareVersion.minor + uint16_t board_id = APJ_BOARD_ID; + uint8_t reserved[8] = { 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff }; +}; + +struct app_descriptor_signed { + uint8_t sig[8] = AP_APP_DESCRIPTOR_SIGNATURE_SIGNED; + // crc1 is the crc32 from firmware start to start of image_crc1 + uint32_t image_crc1 = 0; + // crc2 is the crc32 from the start of version_major to the end of the firmware + uint32_t image_crc2 = 0; + // total size of firmware image in bytes + uint32_t image_size = 0; + uint32_t git_hash = 0; + + // firmware signature + uint32_t signature_length = 0; + uint8_t signature[72] = {}; + + // software version number + uint8_t version_major = APP_FW_MAJOR; + uint8_t version_minor = APP_FW_MINOR; + // APJ_BOARD_ID (hardware version). This is also used in CAN NodeInfo + // with high byte in HardwareVersion.major and low byte in HardwareVersion.minor + uint16_t board_id = APJ_BOARD_ID; + uint8_t reserved[8] = { 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff }; +}; + +#if AP_SIGNED_FIRMWARE +typedef struct app_descriptor_signed app_descriptor_t; +#else +typedef struct app_descriptor_unsigned app_descriptor_t; +#endif + +#define APP_DESCRIPTOR_UNSIGNED_TOTAL_LENGTH 36 +#define APP_DESCRIPTOR_SIGNED_TOTAL_LENGTH (APP_DESCRIPTOR_UNSIGNED_TOTAL_LENGTH+72+4) + +static_assert(sizeof(app_descriptor_unsigned) == APP_DESCRIPTOR_UNSIGNED_TOTAL_LENGTH, "app_descriptor_unsigned incorrect length"); +static_assert(sizeof(app_descriptor_signed) == APP_DESCRIPTOR_SIGNED_TOTAL_LENGTH, "app_descriptor_signed incorrect length"); + +#if AP_SIGNED_FIRMWARE + +#define AP_PUBLIC_KEY_LEN 32 +#define AP_PUBLIC_KEY_MAX_KEYS 10 +#define AP_PUBLIC_KEY_SIGNATURE {0x4e, 0xcf, 0x4e, 0xa5, 0xa6, 0xb6, 0xf7, 0x29} + +struct PACKED ap_secure_data { + uint8_t sig[8] = AP_PUBLIC_KEY_SIGNATURE; + struct PACKED { + uint8_t key[AP_PUBLIC_KEY_LEN] = {}; + } public_key[AP_PUBLIC_KEY_MAX_KEYS]; +}; +#endif + +#ifdef HAL_BOOTLOADER_BUILD +check_fw_result_t check_good_firmware(void); +#else +void check_firmware_print(void); + +class AP_CheckFirmware { +public: +#if HAL_GCS_ENABLED + // handle a message from the GCS. This is static as we don't have an AP_CheckFirmware object + static void handle_msg(mavlink_channel_t chan, const mavlink_message_t &msg); + static void handle_secure_command(mavlink_channel_t chan, const mavlink_secure_command_t &pkt); + static bool check_signature(const mavlink_secure_command_t &pkt); +#endif + static const struct ap_secure_data *find_public_keys(void); + + /* + in memory structure representing the current bootloader. It has two + data regions to cope with persistent data at the end of the + bootloader sector + */ + struct bl_data { + uint32_t length1; + uint8_t *data1; + uint32_t offset2; + uint32_t length2; + uint8_t *data2; + + // destructor + ~bl_data(void) { + delete[] data1; + delete[] data2; + } + }; + static struct bl_data *read_bootloader(void); + static bool write_bootloader(const struct bl_data *bld); + static bool set_public_keys(uint8_t key_idx, uint8_t num_keys, const uint8_t *key_data); + static bool all_zero_keys(const struct ap_secure_data *sec_data); + static bool check_signed_bootloader(const uint8_t *fw, uint32_t fw_size); + +private: +#if HAL_GCS_ENABLED + static uint8_t session_key[8]; +#endif +}; + +#endif // HAL_BOOTLOADER_BUILD + +#endif // AP_CHECK_FIRMWARE_ENABLED diff --git a/libraries/AP_CheckFirmware/AP_CheckFirmware_secure_command.cpp b/libraries/AP_CheckFirmware/AP_CheckFirmware_secure_command.cpp new file mode 100644 index 00000000000..d6578d8c5a9 --- /dev/null +++ b/libraries/AP_CheckFirmware/AP_CheckFirmware_secure_command.cpp @@ -0,0 +1,424 @@ +/* + support checking board ID and firmware CRC in the bootloader + */ +#include "AP_CheckFirmware.h" +#include + +#if AP_CHECK_FIRMWARE_ENABLED && AP_SIGNED_FIRMWARE && !defined(HAL_BOOTLOADER_BUILD) + +#include "monocypher.h" +#include + +extern const AP_HAL::HAL &hal; + +/* + find public keys in bootloader, or return NULL if signature not found + + this assumes the public keys are in the first sector + */ +const struct ap_secure_data *AP_CheckFirmware::find_public_keys(void) +{ +#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS + const uint32_t page_size = hal.flash->getpagesize(0); + const uint32_t flash_addr = hal.flash->getpageaddr(0); + const uint8_t *flash = (const uint8_t *)flash_addr; + const uint8_t key[] = AP_PUBLIC_KEY_SIGNATURE; + return (const struct ap_secure_data *)memmem(flash, page_size, key, sizeof(key)); +#else + return nullptr; +#endif +} + +/* + return true if all keys are zeros + */ +bool AP_CheckFirmware::all_zero_keys(const struct ap_secure_data *sec_data) +{ + const uint8_t zero_key[AP_PUBLIC_KEY_LEN] {}; + /* + look over all public keys, if one matches then we are OK + */ + for (const auto &public_key : sec_data->public_key) { + if (memcmp(public_key.key, zero_key, AP_PUBLIC_KEY_LEN) != 0) { + return false; + } + } + return true; +} + + +#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS +/* + return true if 1k of data is all 0xff (empty flash) + */ +static bool empty_1k(const uint8_t *data) +{ + for (uint32_t i=0; i<1024; i++) { + if (data[i] != 0xFFU) { + return false; + } + } + return true; +} +#endif + +/* + read bootloader into memory. This is complicated by the potential presence + of persistent data from temperature calibration at the end of the sector + + Also note this assumes the public keys are in the first sector if + the bootloader covers more than one sector. This is a reasonable + assumption given the linker file + */ +AP_CheckFirmware::bl_data *AP_CheckFirmware::read_bootloader(void) +{ +#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS + struct bl_data *bld = new bl_data; + if (bld == nullptr) { + return nullptr; + } + const uint32_t page_size = hal.flash->getpagesize(0); + const uint32_t flash_addr = hal.flash->getpageaddr(0); + const uint8_t *flash = (uint8_t *)flash_addr; + const uint16_t block_size = 1024; + uint16_t num_blocks = page_size / block_size; + /* + find first empty block + */ + for (uint16_t i=0; ilength1 += block_size; + } + bld->data1 = new uint8_t[bld->length1]; + if (bld->data1 == nullptr) { + delete bld; + return nullptr; + } + memcpy(bld->data1, flash, bld->length1); + flash += bld->length1; + num_blocks -= bld->length1 / block_size; + + /* + find first non-empty block, which should be the persistent data if-any + */ + bld->offset2 = bld->length1; + while (num_blocks > 0) { + if (!empty_1k(&flash[bld->offset2])) { + break; + } + num_blocks--; + bld->offset2 += block_size; + } + if (num_blocks > 0) { + // we have persistent data to save + bld->length2 = num_blocks * block_size; + bld->data2 = new uint8_t[bld->length2]; + if (bld->data2 == nullptr) { + delete bld; + return nullptr; + } + memcpy(bld->data2, &flash[bld->offset2], bld->length2); + } + return bld; +#else + return nullptr; +#endif +} + +#if HAL_GCS_ENABLED +uint8_t AP_CheckFirmware::session_key[8]; + +/* + make a session key + */ +static void make_session_key(uint8_t key[8]) +{ + struct { + uint32_t time_us; + uint8_t unique_id[12]; + uint16_t rand1; + uint16_t rand2; + } data {}; + static_assert(sizeof(data) % 4 == 0, "data must be multiple of 4 bytes"); + + // get data which will not apply on a different board, and includes some randomness + uint8_t uid_len = 12; + hal.util->get_system_id_unformatted(data.unique_id, uid_len); + data.time_us = AP_HAL::micros(); + data.rand1 = get_random16(); + data.rand2 = get_random16(); + const uint64_t c64 = crc_crc64((const uint32_t *)&data, sizeof(data)/sizeof(uint32_t)); + memcpy(key, (uint8_t *)&c64, 8); +} + + +/* + write bootloader from memory + */ +bool AP_CheckFirmware::write_bootloader(const struct bl_data *bld) +{ +#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS + const uint32_t flash_addr = hal.flash->getpageaddr(0); + EXPECT_DELAY_MS(3000); + if (!hal.flash->erasepage(0)) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Bootloader erase failed"); + return false; + } + EXPECT_DELAY_MS(3000); + if (!hal.flash->write(flash_addr, bld->data1, bld->length1)) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Bootloader write1 failed"); + return false; + } + EXPECT_DELAY_MS(3000); + if (bld->length2 != 0 && + !hal.flash->write(flash_addr+bld->offset2, bld->data2, bld->length2)) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Bootloader write1 failed"); + return false; + } + return true; +#else + return false; +#endif +} + +/* + check signature in a command against bootloader public keys + */ +bool AP_CheckFirmware::check_signature(const mavlink_secure_command_t &pkt) +{ + const struct ap_secure_data *sec_data = find_public_keys(); + if (sec_data == nullptr) { + return false; + } + if (all_zero_keys(sec_data)) { + // allow through if no keys are setup + return true; + } + if (pkt.sig_length != 64) { + // monocypher signatures are 64 bytes + return false; + } + /* + look over all public keys, if one matches then we are OK + */ + for (const auto &public_key : sec_data->public_key) { + crypto_check_ctx ctx {}; + crypto_check_ctx_abstract *actx = (crypto_check_ctx_abstract*)&ctx; + crypto_check_init(actx, &pkt.data[pkt.data_length], public_key.key); + + crypto_check_update(actx, (const uint8_t*)&pkt.sequence, sizeof(pkt.sequence)); + crypto_check_update(actx, (const uint8_t*)&pkt.operation, sizeof(pkt.operation)); + crypto_check_update(actx, pkt.data, pkt.data_length); + if (pkt.operation != SECURE_COMMAND_GET_SESSION_KEY) { + crypto_check_update(actx, session_key, sizeof(session_key)); + } + if (crypto_check_final(actx) == 0) { + // good signature + return true; + } + } + return false; +} + +/* + set public keys in bootloader + */ +bool AP_CheckFirmware::set_public_keys(uint8_t key_idx, uint8_t num_keys, const uint8_t *key_data) +{ + auto *bld = read_bootloader(); + if (bld == nullptr) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Failed to load bootloader into memory"); + return false; + } + const uint8_t key[] = AP_PUBLIC_KEY_SIGNATURE; + struct ap_secure_data *sec_data = (struct ap_secure_data *)memmem(bld->data1, bld->length1, key, sizeof(key)); + if (sec_data == nullptr) { + delete bld; + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Failed to find key signature"); + return false; + } + memcpy(sec_data->public_key[key_idx].key, key_data, num_keys*AP_PUBLIC_KEY_LEN); + + /* + pack so non-zero keys are at the start + */ + const uint8_t zero_key[AP_PUBLIC_KEY_LEN] {}; + uint8_t max_keys = AP_PUBLIC_KEY_MAX_KEYS; + for (uint8_t i=0; max_keys>1 && ipublic_key[i].key, AP_PUBLIC_KEY_LEN) == 0) { + memmove(sec_data->public_key[i].key, sec_data->public_key[i+1].key, AP_PUBLIC_KEY_LEN*(max_keys-(i+1))); + max_keys--; + i--; + } + } + memset(sec_data->public_key[max_keys-1].key, 0, AP_PUBLIC_KEY_LEN*(AP_PUBLIC_KEY_MAX_KEYS-max_keys)); + + bool ret = write_bootloader(bld); + delete bld; + return ret; +} + +/* + handle a SECURE_COMMAND + */ +void AP_CheckFirmware::handle_secure_command(mavlink_channel_t chan, const mavlink_secure_command_t &pkt) +{ + mavlink_secure_command_reply_t reply {}; + reply.result = MAV_RESULT_UNSUPPORTED; + reply.sequence = pkt.sequence; + reply.operation = pkt.operation; + + if (uint16_t(pkt.data_length) + uint16_t(pkt.sig_length) > sizeof(pkt.data)) { + reply.result = MAV_RESULT_DENIED; + goto send_reply; + } + if (!check_signature(pkt)) { + reply.result = MAV_RESULT_DENIED; + goto send_reply; + } + + switch (pkt.operation) { + + case SECURE_COMMAND_GET_SESSION_KEY: { + make_session_key(session_key); + reply.data_length = sizeof(session_key); + memcpy(reply.data, session_key, reply.data_length); + reply.result = MAV_RESULT_ACCEPTED; + break; + } + + case SECURE_COMMAND_GET_PUBLIC_KEYS: { + const struct ap_secure_data *sec_data = find_public_keys(); + if (pkt.data_length != 2) { + reply.result = MAV_RESULT_UNSUPPORTED; + goto send_reply; + } + const uint8_t key_idx = pkt.data[0]; + uint8_t num_keys = pkt.data[1]; + const uint8_t max_fetch = (sizeof(reply.data)-1) / AP_PUBLIC_KEY_LEN; + if (key_idx >= AP_PUBLIC_KEY_MAX_KEYS || + num_keys > max_fetch || + key_idx+num_keys > AP_PUBLIC_KEY_MAX_KEYS || + sec_data == nullptr) { + reply.result = MAV_RESULT_FAILED; + goto send_reply; + } + + // remove zero keys + const uint8_t zero_key[AP_PUBLIC_KEY_LEN] {}; + while (num_keys > 0 && + memcmp(zero_key, &sec_data->public_key[key_idx+num_keys-1], AP_PUBLIC_KEY_LEN) == 0) { + num_keys--; + } + + reply.data_length = 1+num_keys*AP_PUBLIC_KEY_LEN; + reply.data[0] = key_idx; + memcpy(&reply.data[1], &sec_data->public_key[key_idx], reply.data_length-1); + reply.result = MAV_RESULT_ACCEPTED; + break; + } + + case SECURE_COMMAND_SET_PUBLIC_KEYS: { + if (pkt.data_length < AP_PUBLIC_KEY_LEN+1) { + reply.result = MAV_RESULT_FAILED; + goto send_reply; + } + const uint8_t key_idx = pkt.data[0]; + const uint8_t num_keys = (pkt.data_length-1) / AP_PUBLIC_KEY_LEN; + if (num_keys == 0) { + reply.result = MAV_RESULT_FAILED; + goto send_reply; + } + if (key_idx >= AP_PUBLIC_KEY_MAX_KEYS || + key_idx+num_keys > AP_PUBLIC_KEY_MAX_KEYS) { + reply.result = MAV_RESULT_FAILED; + goto send_reply; + } + if (set_public_keys(key_idx, num_keys, &pkt.data[1])) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Bootloader update OK"); + reply.result = MAV_RESULT_ACCEPTED; + } else { + reply.result = MAV_RESULT_FAILED; + } + break; + } + + case SECURE_COMMAND_REMOVE_PUBLIC_KEYS: { + if (pkt.data_length != 2) { + reply.result = MAV_RESULT_FAILED; + goto send_reply; + } + const uint8_t key_idx = pkt.data[0]; + const uint8_t num_keys = pkt.data[1]; + if (num_keys == 0) { + reply.result = MAV_RESULT_FAILED; + goto send_reply; + } + if (key_idx >= AP_PUBLIC_KEY_MAX_KEYS || + key_idx+num_keys > AP_PUBLIC_KEY_MAX_KEYS) { + reply.result = MAV_RESULT_FAILED; + goto send_reply; + } + uint8_t *data = new uint8_t[num_keys*AP_PUBLIC_KEY_LEN]; + if (data == nullptr) { + reply.result = MAV_RESULT_FAILED; + goto send_reply; + } + if (set_public_keys(key_idx, num_keys, data)) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Bootloader update OK"); + reply.result = MAV_RESULT_ACCEPTED; + } else { + reply.result = MAV_RESULT_FAILED; + } + delete[] data; + break; + } + } + +send_reply: + // send reply + mavlink_msg_secure_command_reply_send_struct(chan, &reply); +} + +/* + implement secure command operations for updating public keys + */ +void AP_CheckFirmware::handle_msg(mavlink_channel_t chan, const mavlink_message_t &msg) +{ + switch (msg.msgid) { + case MAVLINK_MSG_ID_SECURE_COMMAND: { + mavlink_secure_command_t pkt; + mavlink_msg_secure_command_decode(&msg, &pkt); + handle_secure_command(chan, pkt); + break; + } + } +} + +#endif // HAL_GCS_ENABLED + +/* + check that a bootloader is OK to flash. We don't want to allow + flashing of a bootloader unless we either have no public keys setup + or the bootloader has public keys embedded. This prevents an easy + mistake of including an insecure bootloader in ROMFS with a secure build + */ +bool AP_CheckFirmware::check_signed_bootloader(const uint8_t *fw, uint32_t fw_size) +{ + const struct ap_secure_data *sec_data = find_public_keys(); + if (sec_data == nullptr || all_zero_keys(sec_data)) { + // current bootloader doesn't have public keys, so OK to load any bootloader + return true; + } + const uint8_t key[] = AP_PUBLIC_KEY_SIGNATURE; + sec_data = (const struct ap_secure_data *)memmem(fw, fw_size, key, sizeof(key)); + if (sec_data == nullptr || all_zero_keys(sec_data)) { + // new bootloader doesn't have any public keys, not allowed + return false; + } + return true; +} + +#endif // AP_CHECK_FIRMWARE_ENABLED diff --git a/libraries/AP_CheckFirmware/monocypher.cpp b/libraries/AP_CheckFirmware/monocypher.cpp new file mode 100644 index 00000000000..32cda54dae5 --- /dev/null +++ b/libraries/AP_CheckFirmware/monocypher.cpp @@ -0,0 +1,3044 @@ +// Monocypher version 3.1.2 +// +// This file is dual-licensed. Choose whichever licence you want from +// the two licences listed below. +// +// The first licence is a regular 2-clause BSD licence. The second licence +// is the CC-0 from Creative Commons. It is intended to release Monocypher +// to the public domain. The BSD licence serves as a fallback option. +// +// SPDX-License-Identifier: BSD-2-Clause OR CC0-1.0 +// +// ------------------------------------------------------------------------ +// +// Copyright (c) 2017-2020, Loup Vaillant +// All rights reserved. +// +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// 1. Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// +// 2. Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the +// distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR +// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT +// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, +// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY +// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ------------------------------------------------------------------------ +// +// Written in 2017-2020 by Loup Vaillant +// +// To the extent possible under law, the author(s) have dedicated all copyright +// and related neighboring rights to this software to the public domain +// worldwide. This software is distributed without any warranty. +// +// You should have received a copy of the CC0 Public Domain Dedication along +// with this software. If not, see +// + +#include "monocypher.h" + +// we don't need Argon2 +#define MONOCYPHER_ARGON2_ENABLE 0 + +// we want the bootloader to be as small as possible +#define BLAKE2_NO_UNROLLING 1 + +///////////////// +/// Utilities /// +///////////////// +#define FOR_T(type, i0, start, end) for (type i0 = (start); i0 < (end); i0++) +#define FOR(i1, start, end) FOR_T(size_t, i1, start, end) +#define COPY(dst, src, size) FOR(i2, 0, size) (dst)[i2] = (src)[i2] +#define ZERO(buf, size) FOR(i3, 0, size) (buf)[i3] = 0 +#define WIPE_CTX(ctx) crypto_wipe(ctx , sizeof(*(ctx))) +#define WIPE_BUFFER(buffer) crypto_wipe(buffer, sizeof(buffer)) +#define MIN(a, b) ((a) <= (b) ? (a) : (b)) +#define MAX(a, b) ((a) >= (b) ? (a) : (b)) + +typedef int8_t i8; +typedef uint8_t u8; +typedef int16_t i16; +typedef uint32_t u32; +typedef int32_t i32; +typedef int64_t i64; +typedef uint64_t u64; + +static const u8 zero[128] = {0}; + +// returns the smallest positive integer y such that +// (x + y) % pow_2 == 0 +// Basically, it's how many bytes we need to add to "align" x. +// Only works when pow_2 is a power of 2. +// Note: we use ~x+1 instead of -x to avoid compiler warnings +static size_t align(size_t x, size_t pow_2) +{ + return (~x + 1) & (pow_2 - 1); +} + +static u32 load24_le(const u8 s[3]) +{ + return (u32)s[0] + | ((u32)s[1] << 8) + | ((u32)s[2] << 16); +} + +static u32 load32_le(const u8 s[4]) +{ + return (u32)s[0] + | ((u32)s[1] << 8) + | ((u32)s[2] << 16) + | ((u32)s[3] << 24); +} + +static u64 load64_le(const u8 s[8]) +{ + return load32_le(s) | ((u64)load32_le(s+4) << 32); +} + +static void store32_le(u8 out[4], u32 in) +{ + out[0] = in & 0xff; + out[1] = (in >> 8) & 0xff; + out[2] = (in >> 16) & 0xff; + out[3] = (in >> 24) & 0xff; +} + +static void store64_le(u8 out[8], u64 in) +{ + store32_le(out , (u32)in ); + store32_le(out + 4, in >> 32); +} + +static void load32_le_buf (u32 *dst, const u8 *src, size_t size) { + FOR(i, 0, size) { dst[i] = load32_le(src + i*4); } +} +static void load64_le_buf (u64 *dst, const u8 *src, size_t size) { + FOR(i, 0, size) { dst[i] = load64_le(src + i*8); } +} +static void store32_le_buf(u8 *dst, const u32 *src, size_t size) { + FOR(i, 0, size) { store32_le(dst + i*4, src[i]); } +} +static void store64_le_buf(u8 *dst, const u64 *src, size_t size) { + FOR(i, 0, size) { store64_le(dst + i*8, src[i]); } +} + +static u64 rotr64(u64 x, u64 n) { return (x >> n) ^ (x << (64 - n)); } +static u32 rotl32(u32 x, u32 n) { return (x << n) ^ (x >> (32 - n)); } + +static int neq0(u64 diff) +{ // constant time comparison to zero + // return diff != 0 ? -1 : 0 + u64 half = (diff >> 32) | ((u32)diff); + return (1 & ((half - 1) >> 32)) - 1; +} + +static u64 x16(const u8 a[16], const u8 b[16]) +{ + return (load64_le(a + 0) ^ load64_le(b + 0)) + | (load64_le(a + 8) ^ load64_le(b + 8)); +} +static u64 x32(const u8 a[32],const u8 b[32]){return x16(a,b)| x16(a+16, b+16);} +static u64 x64(const u8 a[64],const u8 b[64]){return x32(a,b)| x32(a+32, b+32);} +int crypto_verify16(const u8 a[16], const u8 b[16]){ return neq0(x16(a, b)); } +int crypto_verify32(const u8 a[32], const u8 b[32]){ return neq0(x32(a, b)); } +int crypto_verify64(const u8 a[64], const u8 b[64]){ return neq0(x64(a, b)); } + +void crypto_wipe(void *secret, size_t size) +{ + volatile u8 *v_secret = (u8*)secret; + ZERO(v_secret, size); +} + +///////////////// +/// Chacha 20 /// +///////////////// +#define QUARTERROUND(a, b, c, d) \ + a += b; d = rotl32(d ^ a, 16); \ + c += d; b = rotl32(b ^ c, 12); \ + a += b; d = rotl32(d ^ a, 8); \ + c += d; b = rotl32(b ^ c, 7) + +static void chacha20_rounds(u32 out[16], const u32 in[16]) +{ + // The temporary variables make Chacha20 10% faster. + u32 t0 = in[ 0]; u32 t1 = in[ 1]; u32 t2 = in[ 2]; u32 t3 = in[ 3]; + u32 t4 = in[ 4]; u32 t5 = in[ 5]; u32 t6 = in[ 6]; u32 t7 = in[ 7]; + u32 t8 = in[ 8]; u32 t9 = in[ 9]; u32 t10 = in[10]; u32 t11 = in[11]; + u32 t12 = in[12]; u32 t13 = in[13]; u32 t14 = in[14]; u32 t15 = in[15]; + + FOR (i, 0, 10) { // 20 rounds, 2 rounds per loop. + QUARTERROUND(t0, t4, t8 , t12); // column 0 + QUARTERROUND(t1, t5, t9 , t13); // column 1 + QUARTERROUND(t2, t6, t10, t14); // column 2 + QUARTERROUND(t3, t7, t11, t15); // column 3 + QUARTERROUND(t0, t5, t10, t15); // diagonal 0 + QUARTERROUND(t1, t6, t11, t12); // diagonal 1 + QUARTERROUND(t2, t7, t8 , t13); // diagonal 2 + QUARTERROUND(t3, t4, t9 , t14); // diagonal 3 + } + out[ 0] = t0; out[ 1] = t1; out[ 2] = t2; out[ 3] = t3; + out[ 4] = t4; out[ 5] = t5; out[ 6] = t6; out[ 7] = t7; + out[ 8] = t8; out[ 9] = t9; out[10] = t10; out[11] = t11; + out[12] = t12; out[13] = t13; out[14] = t14; out[15] = t15; +} + +static void chacha20_init_key(u32 block[16], const u8 key[32]) +{ + load32_le_buf(block , (const u8*)"expand 32-byte k", 4); // constant + load32_le_buf(block+4, key , 8); // key +} + +void crypto_hchacha20(u8 out[32], const u8 key[32], const u8 in [16]) +{ + u32 block[16]; + chacha20_init_key(block, key); + // input + load32_le_buf(block + 12, in, 4); + chacha20_rounds(block, block); + // prevent reversal of the rounds by revealing only half of the buffer. + store32_le_buf(out , block , 4); // constant + store32_le_buf(out+16, block+12, 4); // counter and nonce + WIPE_BUFFER(block); +} + +u64 crypto_chacha20_ctr(u8 *cipher_text, const u8 *plain_text, + size_t text_size, const u8 key[32], const u8 nonce[8], + u64 ctr) +{ + u32 input[16]; + chacha20_init_key(input, key); + input[12] = (u32) ctr; + input[13] = (u32)(ctr >> 32); + load32_le_buf(input+14, nonce, 2); + + // Whole blocks + u32 pool[16]; + size_t nb_blocks = text_size >> 6; + FOR (i, 0, nb_blocks) { + chacha20_rounds(pool, input); + if (plain_text != 0) { + FOR (j, 0, 16) { + u32 p = pool[j] + input[j]; + store32_le(cipher_text, p ^ load32_le(plain_text)); + cipher_text += 4; + plain_text += 4; + } + } else { + FOR (j, 0, 16) { + u32 p = pool[j] + input[j]; + store32_le(cipher_text, p); + cipher_text += 4; + } + } + input[12]++; + if (input[12] == 0) { + input[13]++; + } + } + text_size &= 63; + + // Last (incomplete) block + if (text_size > 0) { + if (plain_text == 0) { + plain_text = zero; + } + chacha20_rounds(pool, input); + u8 tmp[64]; + FOR (i, 0, 16) { + store32_le(tmp + i*4, pool[i] + input[i]); + } + FOR (i, 0, text_size) { + cipher_text[i] = tmp[i] ^ plain_text[i]; + } + WIPE_BUFFER(tmp); + } + ctr = input[12] + ((u64)input[13] << 32) + (text_size > 0); + + WIPE_BUFFER(pool); + WIPE_BUFFER(input); + return ctr; +} + +u32 crypto_ietf_chacha20_ctr(u8 *cipher_text, const u8 *plain_text, + size_t text_size, + const u8 key[32], const u8 nonce[12], u32 ctr) +{ + u64 big_ctr = ctr + ((u64)load32_le(nonce) << 32); + return (u32)crypto_chacha20_ctr(cipher_text, plain_text, text_size, + key, nonce + 4, big_ctr); +} + +u64 crypto_xchacha20_ctr(u8 *cipher_text, const u8 *plain_text, + size_t text_size, + const u8 key[32], const u8 nonce[24], u64 ctr) +{ + u8 sub_key[32]; + crypto_hchacha20(sub_key, key, nonce); + ctr = crypto_chacha20_ctr(cipher_text, plain_text, text_size, + sub_key, nonce+16, ctr); + WIPE_BUFFER(sub_key); + return ctr; +} + +void crypto_chacha20(u8 *cipher_text, const u8 *plain_text, size_t text_size, + const u8 key[32], const u8 nonce[8]) +{ + crypto_chacha20_ctr(cipher_text, plain_text, text_size, key, nonce, 0); + +} +void crypto_ietf_chacha20(u8 *cipher_text, const u8 *plain_text, + size_t text_size, + const u8 key[32], const u8 nonce[12]) +{ + crypto_ietf_chacha20_ctr(cipher_text, plain_text, text_size, key, nonce, 0); +} + +void crypto_xchacha20(u8 *cipher_text, const u8 *plain_text, size_t text_size, + const u8 key[32], const u8 nonce[24]) +{ + crypto_xchacha20_ctr(cipher_text, plain_text, text_size, key, nonce, 0); +} + +///////////////// +/// Poly 1305 /// +///////////////// + +// h = (h + c) * r +// preconditions: +// ctx->h <= 4_ffffffff_ffffffff_ffffffff_ffffffff +// ctx->c <= 1_ffffffff_ffffffff_ffffffff_ffffffff +// ctx->r <= 0ffffffc_0ffffffc_0ffffffc_0fffffff +// Postcondition: +// ctx->h <= 4_ffffffff_ffffffff_ffffffff_ffffffff +static void poly_block(crypto_poly1305_ctx *ctx) +{ + // s = h + c, without carry propagation + const u64 s0 = ctx->h[0] + (u64)ctx->c[0]; // s0 <= 1_fffffffe + const u64 s1 = ctx->h[1] + (u64)ctx->c[1]; // s1 <= 1_fffffffe + const u64 s2 = ctx->h[2] + (u64)ctx->c[2]; // s2 <= 1_fffffffe + const u64 s3 = ctx->h[3] + (u64)ctx->c[3]; // s3 <= 1_fffffffe + const u32 s4 = ctx->h[4] + ctx->c[4]; // s4 <= 5 + + // Local all the things! + const u32 r0 = ctx->r[0]; // r0 <= 0fffffff + const u32 r1 = ctx->r[1]; // r1 <= 0ffffffc + const u32 r2 = ctx->r[2]; // r2 <= 0ffffffc + const u32 r3 = ctx->r[3]; // r3 <= 0ffffffc + const u32 rr0 = (r0 >> 2) * 5; // rr0 <= 13fffffb // lose 2 bits... + const u32 rr1 = (r1 >> 2) + r1; // rr1 <= 13fffffb // rr1 == (r1 >> 2) * 5 + const u32 rr2 = (r2 >> 2) + r2; // rr2 <= 13fffffb // rr1 == (r2 >> 2) * 5 + const u32 rr3 = (r3 >> 2) + r3; // rr3 <= 13fffffb // rr1 == (r3 >> 2) * 5 + + // (h + c) * r, without carry propagation + const u64 x0 = s0*r0+ s1*rr3+ s2*rr2+ s3*rr1+ s4*rr0; // <= 97ffffe007fffff8 + const u64 x1 = s0*r1+ s1*r0 + s2*rr3+ s3*rr2+ s4*rr1; // <= 8fffffe20ffffff6 + const u64 x2 = s0*r2+ s1*r1 + s2*r0 + s3*rr3+ s4*rr2; // <= 87ffffe417fffff4 + const u64 x3 = s0*r3+ s1*r2 + s2*r1 + s3*r0 + s4*rr3; // <= 7fffffe61ffffff2 + const u32 x4 = s4 * (r0 & 3); // ...recover 2 bits // <= f + + // partial reduction modulo 2^130 - 5 + const u32 u5 = x4 + (x3 >> 32); // u5 <= 7ffffff5 + const u64 u0 = (u5 >> 2) * 5 + (x0 & 0xffffffff); + const u64 u1 = (u0 >> 32) + (x1 & 0xffffffff) + (x0 >> 32); + const u64 u2 = (u1 >> 32) + (x2 & 0xffffffff) + (x1 >> 32); + const u64 u3 = (u2 >> 32) + (x3 & 0xffffffff) + (x2 >> 32); + const u64 u4 = (u3 >> 32) + (u5 & 3); + + // Update the hash + ctx->h[0] = (u32)u0; // u0 <= 1_9ffffff0 + ctx->h[1] = (u32)u1; // u1 <= 1_97ffffe0 + ctx->h[2] = (u32)u2; // u2 <= 1_8fffffe2 + ctx->h[3] = (u32)u3; // u3 <= 1_87ffffe4 + ctx->h[4] = (u32)u4; // u4 <= 4 +} + +// (re-)initialises the input counter and input buffer +static void poly_clear_c(crypto_poly1305_ctx *ctx) +{ + ZERO(ctx->c, 4); + ctx->c_idx = 0; +} + +static void poly_take_input(crypto_poly1305_ctx *ctx, u8 input) +{ + size_t word = ctx->c_idx >> 2; + size_t byte = ctx->c_idx & 3; + ctx->c[word] |= (u32)input << (byte * 8); + ctx->c_idx++; +} + +static void poly_update(crypto_poly1305_ctx *ctx, + const u8 *message, size_t message_size) +{ + FOR (i, 0, message_size) { + poly_take_input(ctx, message[i]); + if (ctx->c_idx == 16) { + poly_block(ctx); + poly_clear_c(ctx); + } + } +} + +void crypto_poly1305_init(crypto_poly1305_ctx *ctx, const u8 key[32]) +{ + // Initial hash is zero + ZERO(ctx->h, 5); + // add 2^130 to every input block + ctx->c[4] = 1; + poly_clear_c(ctx); + // load r and pad (r has some of its bits cleared) + load32_le_buf(ctx->r , key , 4); + load32_le_buf(ctx->pad, key+16, 4); + FOR (i, 0, 1) { ctx->r[i] &= 0x0fffffff; } + FOR (i, 1, 4) { ctx->r[i] &= 0x0ffffffc; } +} + +void crypto_poly1305_update(crypto_poly1305_ctx *ctx, + const u8 *message, size_t message_size) +{ + if (message_size == 0) { + return; + } + // Align ourselves with block boundaries + size_t aligned = MIN(align(ctx->c_idx, 16), message_size); + poly_update(ctx, message, aligned); + message += aligned; + message_size -= aligned; + + // Process the message block by block + size_t nb_blocks = message_size >> 4; + FOR (i, 0, nb_blocks) { + load32_le_buf(ctx->c, message, 4); + poly_block(ctx); + message += 16; + } + if (nb_blocks > 0) { + poly_clear_c(ctx); + } + message_size &= 15; + + // remaining bytes + poly_update(ctx, message, message_size); +} + +void crypto_poly1305_final(crypto_poly1305_ctx *ctx, u8 mac[16]) +{ + // Process the last block (if any) + if (ctx->c_idx != 0) { + // move the final 1 according to remaining input length + // (We may add less than 2^130 to the last input block) + ctx->c[4] = 0; + poly_take_input(ctx, 1); + // one last hash update + poly_block(ctx); + } + + // check if we should subtract 2^130-5 by performing the + // corresponding carry propagation. + u64 c = 5; + FOR (i, 0, 4) { + c += ctx->h[i]; + c >>= 32; + } + c += ctx->h[4]; + c = (c >> 2) * 5; // shift the carry back to the beginning + // c now indicates how many times we should subtract 2^130-5 (0 or 1) + FOR (i, 0, 4) { + c += (u64)ctx->h[i] + ctx->pad[i]; + store32_le(mac + i*4, (u32)c); + c = c >> 32; + } + WIPE_CTX(ctx); +} + +void crypto_poly1305(u8 mac[16], const u8 *message, + size_t message_size, const u8 key[32]) +{ + crypto_poly1305_ctx ctx; + crypto_poly1305_init (&ctx, key); + crypto_poly1305_update(&ctx, message, message_size); + crypto_poly1305_final (&ctx, mac); +} + +//////////////// +/// Blake2 b /// +//////////////// +static const u64 iv[8] = { + 0x6a09e667f3bcc908, 0xbb67ae8584caa73b, + 0x3c6ef372fe94f82b, 0xa54ff53a5f1d36f1, + 0x510e527fade682d1, 0x9b05688c2b3e6c1f, + 0x1f83d9abfb41bd6b, 0x5be0cd19137e2179, +}; + +// increment the input offset +static void blake2b_incr(crypto_blake2b_ctx *ctx) +{ + u64 *x = ctx->input_offset; + size_t y = ctx->input_idx; + x[0] += y; + if (x[0] < y) { + x[1]++; + } +} + +static void blake2b_compress(crypto_blake2b_ctx *ctx, int is_last_block) +{ + static const u8 sigma[12][16] = { + { 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15 }, + { 14, 10, 4, 8, 9, 15, 13, 6, 1, 12, 0, 2, 11, 7, 5, 3 }, + { 11, 8, 12, 0, 5, 2, 15, 13, 10, 14, 3, 6, 7, 1, 9, 4 }, + { 7, 9, 3, 1, 13, 12, 11, 14, 2, 6, 5, 10, 4, 0, 15, 8 }, + { 9, 0, 5, 7, 2, 4, 10, 15, 14, 1, 11, 12, 6, 8, 3, 13 }, + { 2, 12, 6, 10, 0, 11, 8, 3, 4, 13, 7, 5, 15, 14, 1, 9 }, + { 12, 5, 1, 15, 14, 13, 4, 10, 0, 7, 6, 3, 9, 2, 8, 11 }, + { 13, 11, 7, 14, 12, 1, 3, 9, 5, 0, 15, 4, 8, 6, 2, 10 }, + { 6, 15, 14, 9, 11, 3, 0, 8, 12, 2, 13, 7, 1, 4, 10, 5 }, + { 10, 2, 8, 4, 7, 6, 1, 5, 15, 11, 9, 14, 3, 12, 13, 0 }, + { 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15 }, + { 14, 10, 4, 8, 9, 15, 13, 6, 1, 12, 0, 2, 11, 7, 5, 3 }, + }; + + // init work vector + u64 v0 = ctx->hash[0]; u64 v8 = iv[0]; + u64 v1 = ctx->hash[1]; u64 v9 = iv[1]; + u64 v2 = ctx->hash[2]; u64 v10 = iv[2]; + u64 v3 = ctx->hash[3]; u64 v11 = iv[3]; + u64 v4 = ctx->hash[4]; u64 v12 = iv[4] ^ ctx->input_offset[0]; + u64 v5 = ctx->hash[5]; u64 v13 = iv[5] ^ ctx->input_offset[1]; + u64 v6 = ctx->hash[6]; u64 v14 = iv[6] ^ (u64)~(is_last_block - 1); + u64 v7 = ctx->hash[7]; u64 v15 = iv[7]; + + // mangle work vector + u64 *input = ctx->input; +#define BLAKE2_G(a, b, c, d, x, y) \ + a += b + x; d = rotr64(d ^ a, 32); \ + c += d; b = rotr64(b ^ c, 24); \ + a += b + y; d = rotr64(d ^ a, 16); \ + c += d; b = rotr64(b ^ c, 63) +#define BLAKE2_ROUND(i) \ + BLAKE2_G(v0, v4, v8 , v12, input[sigma[i][ 0]], input[sigma[i][ 1]]); \ + BLAKE2_G(v1, v5, v9 , v13, input[sigma[i][ 2]], input[sigma[i][ 3]]); \ + BLAKE2_G(v2, v6, v10, v14, input[sigma[i][ 4]], input[sigma[i][ 5]]); \ + BLAKE2_G(v3, v7, v11, v15, input[sigma[i][ 6]], input[sigma[i][ 7]]); \ + BLAKE2_G(v0, v5, v10, v15, input[sigma[i][ 8]], input[sigma[i][ 9]]); \ + BLAKE2_G(v1, v6, v11, v12, input[sigma[i][10]], input[sigma[i][11]]); \ + BLAKE2_G(v2, v7, v8 , v13, input[sigma[i][12]], input[sigma[i][13]]); \ + BLAKE2_G(v3, v4, v9 , v14, input[sigma[i][14]], input[sigma[i][15]]) + +#ifdef BLAKE2_NO_UNROLLING + FOR (i, 0, 12) { + BLAKE2_ROUND(i); + } +#else + BLAKE2_ROUND(0); BLAKE2_ROUND(1); BLAKE2_ROUND(2); BLAKE2_ROUND(3); + BLAKE2_ROUND(4); BLAKE2_ROUND(5); BLAKE2_ROUND(6); BLAKE2_ROUND(7); + BLAKE2_ROUND(8); BLAKE2_ROUND(9); BLAKE2_ROUND(10); BLAKE2_ROUND(11); +#endif + + // update hash + ctx->hash[0] ^= v0 ^ v8; ctx->hash[1] ^= v1 ^ v9; + ctx->hash[2] ^= v2 ^ v10; ctx->hash[3] ^= v3 ^ v11; + ctx->hash[4] ^= v4 ^ v12; ctx->hash[5] ^= v5 ^ v13; + ctx->hash[6] ^= v6 ^ v14; ctx->hash[7] ^= v7 ^ v15; +} + +static void blake2b_set_input(crypto_blake2b_ctx *ctx, u8 input, size_t index) +{ + if (index == 0) { + ZERO(ctx->input, 16); + } + size_t word = index >> 3; + size_t byte = index & 7; + ctx->input[word] |= (u64)input << (byte << 3); + +} + +static void blake2b_end_block(crypto_blake2b_ctx *ctx) +{ + if (ctx->input_idx == 128) { // If buffer is full, + blake2b_incr(ctx); // update the input offset + blake2b_compress(ctx, 0); // and compress the (not last) block + ctx->input_idx = 0; + } +} + +static void blake2b_update(crypto_blake2b_ctx *ctx, + const u8 *message, size_t message_size) +{ + FOR (i, 0, message_size) { + blake2b_end_block(ctx); + blake2b_set_input(ctx, message[i], ctx->input_idx); + ctx->input_idx++; + } +} + +void crypto_blake2b_general_init(crypto_blake2b_ctx *ctx, size_t hash_size, + const u8 *key, size_t key_size) +{ + // initial hash + COPY(ctx->hash, iv, 8); + ctx->hash[0] ^= 0x01010000 ^ (key_size << 8) ^ hash_size; + + ctx->input_offset[0] = 0; // beginning of the input, no offset + ctx->input_offset[1] = 0; // beginning of the input, no offset + ctx->hash_size = hash_size; // remember the hash size we want + ctx->input_idx = 0; + + // if there is a key, the first block is that key (padded with zeroes) + if (key_size > 0) { + u8 key_block[128] = {0}; + COPY(key_block, key, key_size); + // same as calling crypto_blake2b_update(ctx, key_block , 128) + load64_le_buf(ctx->input, key_block, 16); + ctx->input_idx = 128; + } +} + +void crypto_blake2b_init(crypto_blake2b_ctx *ctx) +{ + crypto_blake2b_general_init(ctx, 64, 0, 0); +} + +void crypto_blake2b_update(crypto_blake2b_ctx *ctx, + const u8 *message, size_t message_size) +{ + if (message_size == 0) { + return; + } + // Align ourselves with block boundaries + size_t aligned = MIN(align(ctx->input_idx, 128), message_size); + blake2b_update(ctx, message, aligned); + message += aligned; + message_size -= aligned; + + // Process the message block by block + FOR (i, 0, message_size >> 7) { // number of blocks + blake2b_end_block(ctx); + load64_le_buf(ctx->input, message, 16); + message += 128; + ctx->input_idx = 128; + } + message_size &= 127; + + // remaining bytes + blake2b_update(ctx, message, message_size); +} + +void crypto_blake2b_final(crypto_blake2b_ctx *ctx, u8 *hash) +{ + // Pad the end of the block with zeroes + FOR (i, ctx->input_idx, 128) { + blake2b_set_input(ctx, 0, i); + } + blake2b_incr(ctx); // update the input offset + blake2b_compress(ctx, 1); // compress the last block + size_t nb_words = ctx->hash_size >> 3; + store64_le_buf(hash, ctx->hash, nb_words); + FOR (i, nb_words << 3, ctx->hash_size) { + hash[i] = (ctx->hash[i >> 3] >> (8 * (i & 7))) & 0xff; + } + WIPE_CTX(ctx); +} + +void crypto_blake2b_general(u8 *hash , size_t hash_size, + const u8 *key , size_t key_size, + const u8 *message, size_t message_size) +{ + crypto_blake2b_ctx ctx; + crypto_blake2b_general_init(&ctx, hash_size, key, key_size); + crypto_blake2b_update(&ctx, message, message_size); + crypto_blake2b_final(&ctx, hash); +} + +void crypto_blake2b(u8 hash[64], const u8 *message, size_t message_size) +{ + crypto_blake2b_general(hash, 64, 0, 0, message, message_size); +} + +static void blake2b_vtable_init(void *ctx) { + crypto_blake2b_init(&((crypto_sign_ctx*)ctx)->hash); +} +static void blake2b_vtable_update(void *ctx, const u8 *m, size_t s) { + crypto_blake2b_update(&((crypto_sign_ctx*)ctx)->hash, m, s); +} +static void blake2b_vtable_final(void *ctx, u8 *h) { + crypto_blake2b_final(&((crypto_sign_ctx*)ctx)->hash, h); +} +const crypto_sign_vtable crypto_blake2b_vtable = { + crypto_blake2b, + blake2b_vtable_init, + blake2b_vtable_update, + blake2b_vtable_final, + sizeof(crypto_sign_ctx), +}; + +#if MONOCYPHER_ARGON2_ENABLE +//////////////// +/// Argon2 i /// +//////////////// +// references to R, Z, Q etc. come from the spec + +// Argon2 operates on 1024 byte blocks. +typedef struct { u64 a[128]; } block; + +static void wipe_block(block *b) +{ + volatile u64* a = b->a; + ZERO(a, 128); +} + +// updates a Blake2 hash with a 32 bit word, little endian. +static void blake_update_32(crypto_blake2b_ctx *ctx, u32 input) +{ + u8 buf[4]; + store32_le(buf, input); + crypto_blake2b_update(ctx, buf, 4); + WIPE_BUFFER(buf); +} + +static void load_block(block *b, const u8 bytes[1024]) +{ + load64_le_buf(b->a, bytes, 128); +} + +static void store_block(u8 bytes[1024], const block *b) +{ + store64_le_buf(bytes, b->a, 128); +} + +static void copy_block(block *o,const block*in){FOR(i,0,128)o->a[i] = in->a[i];} +static void xor_block(block *o,const block*in){FOR(i,0,128)o->a[i]^= in->a[i];} + +// Hash with a virtually unlimited digest size. +// Doesn't extract more entropy than the base hash function. +// Mainly used for filling a whole kilobyte block with pseudo-random bytes. +// (One could use a stream cipher with a seed hash as the key, but +// this would introduce another dependency —and point of failure.) +static void extended_hash(u8 *digest, u32 digest_size, + const u8 *input , u32 input_size) +{ + crypto_blake2b_ctx ctx; + crypto_blake2b_general_init(&ctx, MIN(digest_size, 64), 0, 0); + blake_update_32 (&ctx, digest_size); + crypto_blake2b_update (&ctx, input, input_size); + crypto_blake2b_final (&ctx, digest); + + if (digest_size > 64) { + // the conversion to u64 avoids integer overflow on + // ludicrously big hash sizes. + u32 r = (u32)(((u64)digest_size + 31) >> 5) - 2; + u32 i = 1; + u32 in = 0; + u32 out = 32; + while (i < r) { + // Input and output overlap. This is intentional + crypto_blake2b(digest + out, digest + in, 64); + i += 1; + in += 32; + out += 32; + } + crypto_blake2b_general(digest + out, digest_size - (32 * r), + 0, 0, // no key + digest + in , 64); + } +} + +#define LSB(x) ((x) & 0xffffffff) +#define G(a, b, c, d) \ + a += b + 2 * LSB(a) * LSB(b); d ^= a; d = rotr64(d, 32); \ + c += d + 2 * LSB(c) * LSB(d); b ^= c; b = rotr64(b, 24); \ + a += b + 2 * LSB(a) * LSB(b); d ^= a; d = rotr64(d, 16); \ + c += d + 2 * LSB(c) * LSB(d); b ^= c; b = rotr64(b, 63) +#define ROUND(v0, v1, v2, v3, v4, v5, v6, v7, \ + v8, v9, v10, v11, v12, v13, v14, v15) \ + G(v0, v4, v8, v12); G(v1, v5, v9, v13); \ + G(v2, v6, v10, v14); G(v3, v7, v11, v15); \ + G(v0, v5, v10, v15); G(v1, v6, v11, v12); \ + G(v2, v7, v8, v13); G(v3, v4, v9, v14) + +// Core of the compression function G. Computes Z from R in place. +static void g_rounds(block *work_block) +{ + // column rounds (work_block = Q) + for (int i = 0; i < 128; i += 16) { + ROUND(work_block->a[i ], work_block->a[i + 1], + work_block->a[i + 2], work_block->a[i + 3], + work_block->a[i + 4], work_block->a[i + 5], + work_block->a[i + 6], work_block->a[i + 7], + work_block->a[i + 8], work_block->a[i + 9], + work_block->a[i + 10], work_block->a[i + 11], + work_block->a[i + 12], work_block->a[i + 13], + work_block->a[i + 14], work_block->a[i + 15]); + } + // row rounds (work_block = Z) + for (int i = 0; i < 16; i += 2) { + ROUND(work_block->a[i ], work_block->a[i + 1], + work_block->a[i + 16], work_block->a[i + 17], + work_block->a[i + 32], work_block->a[i + 33], + work_block->a[i + 48], work_block->a[i + 49], + work_block->a[i + 64], work_block->a[i + 65], + work_block->a[i + 80], work_block->a[i + 81], + work_block->a[i + 96], work_block->a[i + 97], + work_block->a[i + 112], work_block->a[i + 113]); + } +} + +// The compression function G (copy version for the first pass) +static void g_copy(block *result, const block *x, const block *y, block* tmp) +{ + copy_block(tmp , x ); // tmp = X + xor_block (tmp , y ); // tmp = X ^ Y = R + copy_block(result, tmp); // result = R (only difference with g_xor) + g_rounds (tmp); // tmp = Z + xor_block (result, tmp); // result = R ^ Z +} + +// The compression function G (xor version for subsequent passes) +static void g_xor(block *result, const block *x, const block *y, block *tmp) +{ + copy_block(tmp , x ); // tmp = X + xor_block (tmp , y ); // tmp = X ^ Y = R + xor_block (result, tmp); // result = R ^ old (only difference with g_copy) + g_rounds (tmp); // tmp = Z + xor_block (result, tmp); // result = R ^ old ^ Z +} + +// Unary version of the compression function. +// The missing argument is implied zero. +// Does the transformation in place. +static void unary_g(block *work_block, block *tmp) +{ + // work_block == R + copy_block(tmp, work_block); // tmp = R + g_rounds (work_block); // work_block = Z + xor_block (work_block, tmp); // work_block = Z ^ R +} + +// Argon2i uses a kind of stream cipher to determine which reference +// block it will take to synthesise the next block. This context hold +// that stream's state. (It's very similar to Chacha20. The block b +// is analogous to Chacha's own pool) +typedef struct { + block b; + u32 pass_number; + u32 slice_number; + u32 nb_blocks; + u32 nb_iterations; + u32 ctr; + u32 offset; +} gidx_ctx; + +// The block in the context will determine array indices. To avoid +// timing attacks, it only depends on public information. No looking +// at a previous block to seed the next. This makes offline attacks +// easier, but timing attacks are the bigger threat in many settings. +static void gidx_refresh(gidx_ctx *ctx) +{ + // seed the beginning of the block... + ctx->b.a[0] = ctx->pass_number; + ctx->b.a[1] = 0; // lane number (we have only one) + ctx->b.a[2] = ctx->slice_number; + ctx->b.a[3] = ctx->nb_blocks; + ctx->b.a[4] = ctx->nb_iterations; + ctx->b.a[5] = 1; // type: Argon2i + ctx->b.a[6] = ctx->ctr; + ZERO(ctx->b.a + 7, 121); // ...then zero the rest out + + // Shuffle the block thus: ctx->b = G((G(ctx->b, zero)), zero) + // (G "square" function), to get cheap pseudo-random numbers. + block tmp; + unary_g(&ctx->b, &tmp); + unary_g(&ctx->b, &tmp); + wipe_block(&tmp); +} + +static void gidx_init(gidx_ctx *ctx, + u32 pass_number, u32 slice_number, + u32 nb_blocks, u32 nb_iterations) +{ + ctx->pass_number = pass_number; + ctx->slice_number = slice_number; + ctx->nb_blocks = nb_blocks; + ctx->nb_iterations = nb_iterations; + ctx->ctr = 0; + + // Offset from the beginning of the segment. For the first slice + // of the first pass, we start at the *third* block, so the offset + // starts at 2, not 0. + if (pass_number != 0 || slice_number != 0) { + ctx->offset = 0; + } else { + ctx->offset = 2; + ctx->ctr++; // Compensates for missed lazy creation + gidx_refresh(ctx); // at the start of gidx_next() + } +} + +static u32 gidx_next(gidx_ctx *ctx) +{ + // lazily creates the offset block we need + if ((ctx->offset & 127) == 0) { + ctx->ctr++; + gidx_refresh(ctx); + } + u32 index = ctx->offset & 127; // save index for current call + u32 offset = ctx->offset; // save offset for current call + ctx->offset++; // update offset for next call + + // Computes the area size. + // Pass 0 : all already finished segments plus already constructed + // blocks in this segment + // Pass 1+: 3 last segments plus already constructed + // blocks in this segment. THE SPEC SUGGESTS OTHERWISE. + // I CONFORM TO THE REFERENCE IMPLEMENTATION. + int first_pass = ctx->pass_number == 0; + u32 slice_size = ctx->nb_blocks >> 2; + u32 nb_segments = first_pass ? ctx->slice_number : 3; + u32 area_size = nb_segments * slice_size + offset - 1; + + // Computes the starting position of the reference area. + // CONTRARY TO WHAT THE SPEC SUGGESTS, IT STARTS AT THE + // NEXT SEGMENT, NOT THE NEXT BLOCK. + u32 next_slice = ((ctx->slice_number + 1) & 3) * slice_size; + u32 start_pos = first_pass ? 0 : next_slice; + + // Generate offset from J1 (no need for J2, there's only one lane) + u64 j1 = ctx->b.a[index] & 0xffffffff; // pseudo-random number + u64 x = (j1 * j1) >> 32; + u64 y = (area_size * x) >> 32; + u64 z = (area_size - 1) - y; + u64 ref = start_pos + z; // ref < 2 * nb_blocks + return (u32)(ref < ctx->nb_blocks ? ref : ref - ctx->nb_blocks); +} + +// Main algorithm +void crypto_argon2i_general(u8 *hash, u32 hash_size, + void *work_area, u32 nb_blocks, + u32 nb_iterations, + const u8 *password, u32 password_size, + const u8 *salt, u32 salt_size, + const u8 *key, u32 key_size, + const u8 *ad, u32 ad_size) +{ + // work area seen as blocks (must be suitably aligned) + block *blocks = (block*)work_area; + { + crypto_blake2b_ctx ctx; + crypto_blake2b_init(&ctx); + + blake_update_32 (&ctx, 1 ); // p: number of threads + blake_update_32 (&ctx, hash_size ); + blake_update_32 (&ctx, nb_blocks ); + blake_update_32 (&ctx, nb_iterations); + blake_update_32 (&ctx, 0x13 ); // v: version number + blake_update_32 (&ctx, 1 ); // y: Argon2i + blake_update_32 (&ctx, password_size); + crypto_blake2b_update(&ctx, password, password_size); + blake_update_32 (&ctx, salt_size); + crypto_blake2b_update(&ctx, salt, salt_size); + blake_update_32 (&ctx, key_size); + crypto_blake2b_update(&ctx, key, key_size); + blake_update_32 (&ctx, ad_size); + crypto_blake2b_update(&ctx, ad, ad_size); + + u8 initial_hash[72]; // 64 bytes plus 2 words for future hashes + crypto_blake2b_final(&ctx, initial_hash); + + // fill first 2 blocks + block tmp_block; + u8 hash_area[1024]; + store32_le(initial_hash + 64, 0); // first additional word + store32_le(initial_hash + 68, 0); // second additional word + extended_hash(hash_area, 1024, initial_hash, 72); + load_block(&tmp_block, hash_area); + copy_block(blocks, &tmp_block); + + store32_le(initial_hash + 64, 1); // slight modification + extended_hash(hash_area, 1024, initial_hash, 72); + load_block(&tmp_block, hash_area); + copy_block(blocks + 1, &tmp_block); + + WIPE_BUFFER(initial_hash); + WIPE_BUFFER(hash_area); + wipe_block(&tmp_block); + } + + // Actual number of blocks + nb_blocks -= nb_blocks & 3; // round down to 4 p (p == 1 thread) + const u32 segment_size = nb_blocks >> 2; + + // fill (then re-fill) the rest of the blocks + block tmp; + gidx_ctx ctx; // public information, no need to wipe + FOR_T (u32, pass_number, 0, nb_iterations) { + int first_pass = pass_number == 0; + + FOR_T (u32, segment, 0, 4) { + gidx_init(&ctx, pass_number, segment, nb_blocks, nb_iterations); + + // On the first segment of the first pass, + // blocks 0 and 1 are already filled. + // We use the offset to skip them. + u32 start_offset = first_pass && segment == 0 ? 2 : 0; + u32 segment_start = segment * segment_size + start_offset; + u32 segment_end = (segment + 1) * segment_size; + FOR_T (u32, current_block, segment_start, segment_end) { + u32 reference_block = gidx_next(&ctx); + u32 previous_block = current_block == 0 + ? nb_blocks - 1 + : current_block - 1; + block *c = blocks + current_block; + block *p = blocks + previous_block; + block *r = blocks + reference_block; + if (first_pass) { g_copy(c, p, r, &tmp); } + else { g_xor (c, p, r, &tmp); } + } + } + } + wipe_block(&tmp); + u8 final_block[1024]; + store_block(final_block, blocks + (nb_blocks - 1)); + + // wipe work area + volatile u64 *p = (u64*)work_area; + ZERO(p, 128 * nb_blocks); + + // hash the very last block with H' into the output hash + extended_hash(hash, hash_size, final_block, 1024); + WIPE_BUFFER(final_block); +} + +void crypto_argon2i(u8 *hash, u32 hash_size, + void *work_area, u32 nb_blocks, u32 nb_iterations, + const u8 *password, u32 password_size, + const u8 *salt, u32 salt_size) +{ + crypto_argon2i_general(hash, hash_size, work_area, nb_blocks, nb_iterations, + password, password_size, salt , salt_size, 0,0,0,0); +} + +#endif // MONOCYPHER_ARGON2_ENABLE + +//////////////////////////////////// +/// Arithmetic modulo 2^255 - 19 /// +//////////////////////////////////// +// Originally taken from SUPERCOP's ref10 implementation. +// A bit bigger than TweetNaCl, over 4 times faster. + +// field element +typedef i32 fe[10]; + +// field constants +// +// fe_one : 1 +// sqrtm1 : sqrt(-1) +// d : -121665 / 121666 +// D2 : 2 * -121665 / 121666 +// lop_x, lop_y: low order point in Edwards coordinates +// ufactor : -sqrt(-1) * 2 +// A2 : 486662^2 (A squared) +static const fe fe_one = {1}; +static const fe sqrtm1 = {-32595792, -7943725, 9377950, 3500415, 12389472, + -272473, -25146209, -2005654, 326686, 11406482,}; +static const fe d = {-10913610, 13857413, -15372611, 6949391, 114729, + -8787816, -6275908, -3247719, -18696448, -12055116,}; +static const fe D2 = {-21827239, -5839606, -30745221, 13898782, 229458, + 15978800, -12551817, -6495438, 29715968, 9444199,}; +static const fe lop_x = {21352778, 5345713, 4660180, -8347857, 24143090, + 14568123, 30185756, -12247770, -33528939, 8345319,}; +static const fe lop_y = {-6952922, -1265500, 6862341, -7057498, -4037696, + -5447722, 31680899, -15325402, -19365852, 1569102,}; +static const fe ufactor = {-1917299, 15887451, -18755900, -7000830, -24778944, + 544946, -16816446, 4011309, -653372, 10741468,}; +static const fe A2 = {12721188, 3529, 0, 0, 0, 0, 0, 0, 0, 0,}; + +static void fe_0(fe h) { ZERO(h , 10); } +static void fe_1(fe h) { h[0] = 1; ZERO(h+1, 9); } + +static void fe_copy(fe h,const fe f ){FOR(i,0,10) h[i] = f[i]; } +static void fe_neg (fe h,const fe f ){FOR(i,0,10) h[i] = -f[i]; } +static void fe_add (fe h,const fe f,const fe g){FOR(i,0,10) h[i] = f[i] + g[i];} +static void fe_sub (fe h,const fe f,const fe g){FOR(i,0,10) h[i] = f[i] - g[i];} + +static void fe_cswap(fe f, fe g, int b) +{ + i32 mask = -b; // -1 = 0xffffffff + FOR (i, 0, 10) { + i32 x = (f[i] ^ g[i]) & mask; + f[i] = f[i] ^ x; + g[i] = g[i] ^ x; + } +} + +static void fe_ccopy(fe f, const fe g, int b) +{ + i32 mask = -b; // -1 = 0xffffffff + FOR (i, 0, 10) { + i32 x = (f[i] ^ g[i]) & mask; + f[i] = f[i] ^ x; + } +} + + +// Signed carry propagation +// ------------------------ +// +// Let t be a number. It can be uniquely decomposed thus: +// +// t = h*2^26 + l +// such that -2^25 <= l < 2^25 +// +// Let c = (t + 2^25) / 2^26 (rounded down) +// c = (h*2^26 + l + 2^25) / 2^26 (rounded down) +// c = h + (l + 2^25) / 2^26 (rounded down) +// c = h (exactly) +// Because 0 <= l + 2^25 < 2^26 +// +// Let u = t - c*2^26 +// u = h*2^26 + l - h*2^26 +// u = l +// Therefore, -2^25 <= u < 2^25 +// +// Additionally, if |t| < x, then |h| < x/2^26 (rounded down) +// +// Notations: +// - In C, 1<<25 means 2^25. +// - In C, x>>25 means floor(x / (2^25)). +// - All of the above applies with 25 & 24 as well as 26 & 25. +// +// +// Note on negative right shifts +// ----------------------------- +// +// In C, x >> n, where x is a negative integer, is implementation +// defined. In practice, all platforms do arithmetic shift, which is +// equivalent to division by 2^26, rounded down. Some compilers, like +// GCC, even guarantee it. +// +// If we ever stumble upon a platform that does not propagate the sign +// bit (we won't), visible failures will show at the slightest test, and +// the signed shifts can be replaced by the following: +// +// typedef struct { i64 x:39; } s25; +// typedef struct { i64 x:38; } s26; +// i64 shift25(i64 x) { s25 s; s.x = ((u64)x)>>25; return s.x; } +// i64 shift26(i64 x) { s26 s; s.x = ((u64)x)>>26; return s.x; } +// +// Current compilers cannot optimise this, causing a 30% drop in +// performance. Fairly expensive for something that never happens. +// +// +// Precondition +// ------------ +// +// |t0| < 2^63 +// |t1|..|t9| < 2^62 +// +// Algorithm +// --------- +// c = t0 + 2^25 / 2^26 -- |c| <= 2^36 +// t0 -= c * 2^26 -- |t0| <= 2^25 +// t1 += c -- |t1| <= 2^63 +// +// c = t4 + 2^25 / 2^26 -- |c| <= 2^36 +// t4 -= c * 2^26 -- |t4| <= 2^25 +// t5 += c -- |t5| <= 2^63 +// +// c = t1 + 2^24 / 2^25 -- |c| <= 2^38 +// t1 -= c * 2^25 -- |t1| <= 2^24 +// t2 += c -- |t2| <= 2^63 +// +// c = t5 + 2^24 / 2^25 -- |c| <= 2^38 +// t5 -= c * 2^25 -- |t5| <= 2^24 +// t6 += c -- |t6| <= 2^63 +// +// c = t2 + 2^25 / 2^26 -- |c| <= 2^37 +// t2 -= c * 2^26 -- |t2| <= 2^25 < 1.1 * 2^25 (final t2) +// t3 += c -- |t3| <= 2^63 +// +// c = t6 + 2^25 / 2^26 -- |c| <= 2^37 +// t6 -= c * 2^26 -- |t6| <= 2^25 < 1.1 * 2^25 (final t6) +// t7 += c -- |t7| <= 2^63 +// +// c = t3 + 2^24 / 2^25 -- |c| <= 2^38 +// t3 -= c * 2^25 -- |t3| <= 2^24 < 1.1 * 2^24 (final t3) +// t4 += c -- |t4| <= 2^25 + 2^38 < 2^39 +// +// c = t7 + 2^24 / 2^25 -- |c| <= 2^38 +// t7 -= c * 2^25 -- |t7| <= 2^24 < 1.1 * 2^24 (final t7) +// t8 += c -- |t8| <= 2^63 +// +// c = t4 + 2^25 / 2^26 -- |c| <= 2^13 +// t4 -= c * 2^26 -- |t4| <= 2^25 < 1.1 * 2^25 (final t4) +// t5 += c -- |t5| <= 2^24 + 2^13 < 1.1 * 2^24 (final t5) +// +// c = t8 + 2^25 / 2^26 -- |c| <= 2^37 +// t8 -= c * 2^26 -- |t8| <= 2^25 < 1.1 * 2^25 (final t8) +// t9 += c -- |t9| <= 2^63 +// +// c = t9 + 2^24 / 2^25 -- |c| <= 2^38 +// t9 -= c * 2^25 -- |t9| <= 2^24 < 1.1 * 2^24 (final t9) +// t0 += c * 19 -- |t0| <= 2^25 + 2^38*19 < 2^44 +// +// c = t0 + 2^25 / 2^26 -- |c| <= 2^18 +// t0 -= c * 2^26 -- |t0| <= 2^25 < 1.1 * 2^25 (final t0) +// t1 += c -- |t1| <= 2^24 + 2^18 < 1.1 * 2^24 (final t1) +// +// Postcondition +// ------------- +// |t0|, |t2|, |t4|, |t6|, |t8| < 1.1 * 2^25 +// |t1|, |t3|, |t5|, |t7|, |t9| < 1.1 * 2^24 +#define FE_CARRY \ + i64 c; \ + c = (t0 + ((i64)1<<25)) >> 26; t0 -= c * ((i64)1 << 26); t1 += c; \ + c = (t4 + ((i64)1<<25)) >> 26; t4 -= c * ((i64)1 << 26); t5 += c; \ + c = (t1 + ((i64)1<<24)) >> 25; t1 -= c * ((i64)1 << 25); t2 += c; \ + c = (t5 + ((i64)1<<24)) >> 25; t5 -= c * ((i64)1 << 25); t6 += c; \ + c = (t2 + ((i64)1<<25)) >> 26; t2 -= c * ((i64)1 << 26); t3 += c; \ + c = (t6 + ((i64)1<<25)) >> 26; t6 -= c * ((i64)1 << 26); t7 += c; \ + c = (t3 + ((i64)1<<24)) >> 25; t3 -= c * ((i64)1 << 25); t4 += c; \ + c = (t7 + ((i64)1<<24)) >> 25; t7 -= c * ((i64)1 << 25); t8 += c; \ + c = (t4 + ((i64)1<<25)) >> 26; t4 -= c * ((i64)1 << 26); t5 += c; \ + c = (t8 + ((i64)1<<25)) >> 26; t8 -= c * ((i64)1 << 26); t9 += c; \ + c = (t9 + ((i64)1<<24)) >> 25; t9 -= c * ((i64)1 << 25); t0 += c * 19; \ + c = (t0 + ((i64)1<<25)) >> 26; t0 -= c * ((i64)1 << 26); t1 += c; \ + h[0]=(i32)t0; h[1]=(i32)t1; h[2]=(i32)t2; h[3]=(i32)t3; h[4]=(i32)t4; \ + h[5]=(i32)t5; h[6]=(i32)t6; h[7]=(i32)t7; h[8]=(i32)t8; h[9]=(i32)t9 + +static void fe_frombytes(fe h, const u8 s[32]) +{ + i64 t0 = load32_le(s); // t0 < 2^32 + i64 t1 = load24_le(s + 4) << 6; // t1 < 2^30 + i64 t2 = load24_le(s + 7) << 5; // t2 < 2^29 + i64 t3 = load24_le(s + 10) << 3; // t3 < 2^27 + i64 t4 = load24_le(s + 13) << 2; // t4 < 2^26 + i64 t5 = load32_le(s + 16); // t5 < 2^32 + i64 t6 = load24_le(s + 20) << 7; // t6 < 2^31 + i64 t7 = load24_le(s + 23) << 5; // t7 < 2^29 + i64 t8 = load24_le(s + 26) << 4; // t8 < 2^28 + i64 t9 = (load24_le(s + 29) & 0x7fffff) << 2; // t9 < 2^25 + FE_CARRY; // Carry recondition OK +} + +// Precondition +// |h[0]|, |h[2]|, |h[4]|, |h[6]|, |h[8]| < 1.1 * 2^25 +// |h[1]|, |h[3]|, |h[5]|, |h[7]|, |h[9]| < 1.1 * 2^24 +// +// Therefore, |h| < 2^255-19 +// There are two possibilities: +// +// - If h is positive, all we need to do is reduce its individual +// limbs down to their tight positive range. +// - If h is negative, we also need to add 2^255-19 to it. +// Or just remove 19 and chop off any excess bit. +static void fe_tobytes(u8 s[32], const fe h) +{ + i32 t[10]; + COPY(t, h, 10); + i32 q = (19 * t[9] + (((i32) 1) << 24)) >> 25; + // |t9| < 1.1 * 2^24 + // -1.1 * 2^24 < t9 < 1.1 * 2^24 + // -21 * 2^24 < 19 * t9 < 21 * 2^24 + // -2^29 < 19 * t9 + 2^24 < 2^29 + // -2^29 / 2^25 < (19 * t9 + 2^24) / 2^25 < 2^29 / 2^25 + // -16 < (19 * t9 + 2^24) / 2^25 < 16 + FOR (i, 0, 5) { + q += t[2*i ]; q >>= 26; // q = 0 or -1 + q += t[2*i+1]; q >>= 25; // q = 0 or -1 + } + // q = 0 iff h >= 0 + // q = -1 iff h < 0 + // Adding q * 19 to h reduces h to its proper range. + q *= 19; // Shift carry back to the beginning + FOR (i, 0, 5) { + t[i*2 ] += q; q = t[i*2 ] >> 26; t[i*2 ] -= q * ((i32)1 << 26); + t[i*2+1] += q; q = t[i*2+1] >> 25; t[i*2+1] -= q * ((i32)1 << 25); + } + // h is now fully reduced, and q represents the excess bit. + + store32_le(s + 0, ((u32)t[0] >> 0) | ((u32)t[1] << 26)); + store32_le(s + 4, ((u32)t[1] >> 6) | ((u32)t[2] << 19)); + store32_le(s + 8, ((u32)t[2] >> 13) | ((u32)t[3] << 13)); + store32_le(s + 12, ((u32)t[3] >> 19) | ((u32)t[4] << 6)); + store32_le(s + 16, ((u32)t[5] >> 0) | ((u32)t[6] << 25)); + store32_le(s + 20, ((u32)t[6] >> 7) | ((u32)t[7] << 19)); + store32_le(s + 24, ((u32)t[7] >> 13) | ((u32)t[8] << 12)); + store32_le(s + 28, ((u32)t[8] >> 20) | ((u32)t[9] << 6)); + + WIPE_BUFFER(t); +} + +// Precondition +// ------------- +// |f0|, |f2|, |f4|, |f6|, |f8| < 1.65 * 2^26 +// |f1|, |f3|, |f5|, |f7|, |f9| < 1.65 * 2^25 +// +// |g0|, |g2|, |g4|, |g6|, |g8| < 1.65 * 2^26 +// |g1|, |g3|, |g5|, |g7|, |g9| < 1.65 * 2^25 +static void fe_mul_small(fe h, const fe f, i32 g) +{ + i64 t0 = f[0] * (i64) g; i64 t1 = f[1] * (i64) g; + i64 t2 = f[2] * (i64) g; i64 t3 = f[3] * (i64) g; + i64 t4 = f[4] * (i64) g; i64 t5 = f[5] * (i64) g; + i64 t6 = f[6] * (i64) g; i64 t7 = f[7] * (i64) g; + i64 t8 = f[8] * (i64) g; i64 t9 = f[9] * (i64) g; + // |t0|, |t2|, |t4|, |t6|, |t8| < 1.65 * 2^26 * 2^31 < 2^58 + // |t1|, |t3|, |t5|, |t7|, |t9| < 1.65 * 2^25 * 2^31 < 2^57 + + FE_CARRY; // Carry precondition OK +} + +// Precondition +// ------------- +// |f0|, |f2|, |f4|, |f6|, |f8| < 1.65 * 2^26 +// |f1|, |f3|, |f5|, |f7|, |f9| < 1.65 * 2^25 +// +// |g0|, |g2|, |g4|, |g6|, |g8| < 1.65 * 2^26 +// |g1|, |g3|, |g5|, |g7|, |g9| < 1.65 * 2^25 +static void fe_mul(fe h, const fe f, const fe g) +{ + // Everything is unrolled and put in temporary variables. + // We could roll the loop, but that would make curve25519 twice as slow. + i32 f0 = f[0]; i32 f1 = f[1]; i32 f2 = f[2]; i32 f3 = f[3]; i32 f4 = f[4]; + i32 f5 = f[5]; i32 f6 = f[6]; i32 f7 = f[7]; i32 f8 = f[8]; i32 f9 = f[9]; + i32 g0 = g[0]; i32 g1 = g[1]; i32 g2 = g[2]; i32 g3 = g[3]; i32 g4 = g[4]; + i32 g5 = g[5]; i32 g6 = g[6]; i32 g7 = g[7]; i32 g8 = g[8]; i32 g9 = g[9]; + i32 F1 = f1*2; i32 F3 = f3*2; i32 F5 = f5*2; i32 F7 = f7*2; i32 F9 = f9*2; + i32 G1 = g1*19; i32 G2 = g2*19; i32 G3 = g3*19; + i32 G4 = g4*19; i32 G5 = g5*19; i32 G6 = g6*19; + i32 G7 = g7*19; i32 G8 = g8*19; i32 G9 = g9*19; + // |F1|, |F3|, |F5|, |F7|, |F9| < 1.65 * 2^26 + // |G0|, |G2|, |G4|, |G6|, |G8| < 2^31 + // |G1|, |G3|, |G5|, |G7|, |G9| < 2^30 + + i64 t0 = f0*(i64)g0 + F1*(i64)G9 + f2*(i64)G8 + F3*(i64)G7 + f4*(i64)G6 + + F5*(i64)G5 + f6*(i64)G4 + F7*(i64)G3 + f8*(i64)G2 + F9*(i64)G1; + i64 t1 = f0*(i64)g1 + f1*(i64)g0 + f2*(i64)G9 + f3*(i64)G8 + f4*(i64)G7 + + f5*(i64)G6 + f6*(i64)G5 + f7*(i64)G4 + f8*(i64)G3 + f9*(i64)G2; + i64 t2 = f0*(i64)g2 + F1*(i64)g1 + f2*(i64)g0 + F3*(i64)G9 + f4*(i64)G8 + + F5*(i64)G7 + f6*(i64)G6 + F7*(i64)G5 + f8*(i64)G4 + F9*(i64)G3; + i64 t3 = f0*(i64)g3 + f1*(i64)g2 + f2*(i64)g1 + f3*(i64)g0 + f4*(i64)G9 + + f5*(i64)G8 + f6*(i64)G7 + f7*(i64)G6 + f8*(i64)G5 + f9*(i64)G4; + i64 t4 = f0*(i64)g4 + F1*(i64)g3 + f2*(i64)g2 + F3*(i64)g1 + f4*(i64)g0 + + F5*(i64)G9 + f6*(i64)G8 + F7*(i64)G7 + f8*(i64)G6 + F9*(i64)G5; + i64 t5 = f0*(i64)g5 + f1*(i64)g4 + f2*(i64)g3 + f3*(i64)g2 + f4*(i64)g1 + + f5*(i64)g0 + f6*(i64)G9 + f7*(i64)G8 + f8*(i64)G7 + f9*(i64)G6; + i64 t6 = f0*(i64)g6 + F1*(i64)g5 + f2*(i64)g4 + F3*(i64)g3 + f4*(i64)g2 + + F5*(i64)g1 + f6*(i64)g0 + F7*(i64)G9 + f8*(i64)G8 + F9*(i64)G7; + i64 t7 = f0*(i64)g7 + f1*(i64)g6 + f2*(i64)g5 + f3*(i64)g4 + f4*(i64)g3 + + f5*(i64)g2 + f6*(i64)g1 + f7*(i64)g0 + f8*(i64)G9 + f9*(i64)G8; + i64 t8 = f0*(i64)g8 + F1*(i64)g7 + f2*(i64)g6 + F3*(i64)g5 + f4*(i64)g4 + + F5*(i64)g3 + f6*(i64)g2 + F7*(i64)g1 + f8*(i64)g0 + F9*(i64)G9; + i64 t9 = f0*(i64)g9 + f1*(i64)g8 + f2*(i64)g7 + f3*(i64)g6 + f4*(i64)g5 + + f5*(i64)g4 + f6*(i64)g3 + f7*(i64)g2 + f8*(i64)g1 + f9*(i64)g0; + // t0 < 0.67 * 2^61 + // t1 < 0.41 * 2^61 + // t2 < 0.52 * 2^61 + // t3 < 0.32 * 2^61 + // t4 < 0.38 * 2^61 + // t5 < 0.22 * 2^61 + // t6 < 0.23 * 2^61 + // t7 < 0.13 * 2^61 + // t8 < 0.09 * 2^61 + // t9 < 0.03 * 2^61 + + FE_CARRY; // Everything below 2^62, Carry precondition OK +} + +// Precondition +// ------------- +// |f0|, |f2|, |f4|, |f6|, |f8| < 1.65 * 2^26 +// |f1|, |f3|, |f5|, |f7|, |f9| < 1.65 * 2^25 +// +// Note: we could use fe_mul() for this, but this is significantly faster +static void fe_sq(fe h, const fe f) +{ + i32 f0 = f[0]; i32 f1 = f[1]; i32 f2 = f[2]; i32 f3 = f[3]; i32 f4 = f[4]; + i32 f5 = f[5]; i32 f6 = f[6]; i32 f7 = f[7]; i32 f8 = f[8]; i32 f9 = f[9]; + i32 f0_2 = f0*2; i32 f1_2 = f1*2; i32 f2_2 = f2*2; i32 f3_2 = f3*2; + i32 f4_2 = f4*2; i32 f5_2 = f5*2; i32 f6_2 = f6*2; i32 f7_2 = f7*2; + i32 f5_38 = f5*38; i32 f6_19 = f6*19; i32 f7_38 = f7*38; + i32 f8_19 = f8*19; i32 f9_38 = f9*38; + // |f0_2| , |f2_2| , |f4_2| , |f6_2| , |f8_2| < 1.65 * 2^27 + // |f1_2| , |f3_2| , |f5_2| , |f7_2| , |f9_2| < 1.65 * 2^26 + // |f5_38|, |f6_19|, |f7_38|, |f8_19|, |f9_38| < 2^31 + + i64 t0 = f0 *(i64)f0 + f1_2*(i64)f9_38 + f2_2*(i64)f8_19 + + f3_2*(i64)f7_38 + f4_2*(i64)f6_19 + f5 *(i64)f5_38; + i64 t1 = f0_2*(i64)f1 + f2 *(i64)f9_38 + f3_2*(i64)f8_19 + + f4 *(i64)f7_38 + f5_2*(i64)f6_19; + i64 t2 = f0_2*(i64)f2 + f1_2*(i64)f1 + f3_2*(i64)f9_38 + + f4_2*(i64)f8_19 + f5_2*(i64)f7_38 + f6 *(i64)f6_19; + i64 t3 = f0_2*(i64)f3 + f1_2*(i64)f2 + f4 *(i64)f9_38 + + f5_2*(i64)f8_19 + f6 *(i64)f7_38; + i64 t4 = f0_2*(i64)f4 + f1_2*(i64)f3_2 + f2 *(i64)f2 + + f5_2*(i64)f9_38 + f6_2*(i64)f8_19 + f7 *(i64)f7_38; + i64 t5 = f0_2*(i64)f5 + f1_2*(i64)f4 + f2_2*(i64)f3 + + f6 *(i64)f9_38 + f7_2*(i64)f8_19; + i64 t6 = f0_2*(i64)f6 + f1_2*(i64)f5_2 + f2_2*(i64)f4 + + f3_2*(i64)f3 + f7_2*(i64)f9_38 + f8 *(i64)f8_19; + i64 t7 = f0_2*(i64)f7 + f1_2*(i64)f6 + f2_2*(i64)f5 + + f3_2*(i64)f4 + f8 *(i64)f9_38; + i64 t8 = f0_2*(i64)f8 + f1_2*(i64)f7_2 + f2_2*(i64)f6 + + f3_2*(i64)f5_2 + f4 *(i64)f4 + f9 *(i64)f9_38; + i64 t9 = f0_2*(i64)f9 + f1_2*(i64)f8 + f2_2*(i64)f7 + + f3_2*(i64)f6 + f4 *(i64)f5_2; + // t0 < 0.67 * 2^61 + // t1 < 0.41 * 2^61 + // t2 < 0.52 * 2^61 + // t3 < 0.32 * 2^61 + // t4 < 0.38 * 2^61 + // t5 < 0.22 * 2^61 + // t6 < 0.23 * 2^61 + // t7 < 0.13 * 2^61 + // t8 < 0.09 * 2^61 + // t9 < 0.03 * 2^61 + + FE_CARRY; +} + +// h = 2 * (f^2) +// +// Precondition +// ------------- +// |f0|, |f2|, |f4|, |f6|, |f8| < 1.65 * 2^26 +// |f1|, |f3|, |f5|, |f7|, |f9| < 1.65 * 2^25 +// +// Note: we could implement fe_sq2() by copying fe_sq(), multiplying +// each limb by 2, *then* perform the carry. This saves one carry. +// However, doing so with the stated preconditions does not work (t2 +// would overflow). There are 3 ways to solve this: +// +// 1. Show that t2 actually never overflows (it really does not). +// 2. Accept an additional carry, at a small lost of performance. +// 3. Make sure the input of fe_sq2() is freshly carried. +// +// SUPERCOP ref10 relies on (1). +// Monocypher chose (2) and (3), mostly to save code. +static void fe_sq2(fe h, const fe f) +{ + fe_sq(h, f); + fe_mul_small(h, h, 2); +} + +// This could be simplified, but it would be slower +static void fe_pow22523(fe out, const fe z) +{ + fe t0, t1, t2; + fe_sq(t0, z); + fe_sq(t1,t0); fe_sq(t1, t1); fe_mul(t1, z, t1); + fe_mul(t0, t0, t1); + fe_sq(t0, t0); fe_mul(t0, t1, t0); + fe_sq(t1, t0); FOR (i, 1, 5) fe_sq(t1, t1); fe_mul(t0, t1, t0); + fe_sq(t1, t0); FOR (i, 1, 10) fe_sq(t1, t1); fe_mul(t1, t1, t0); + fe_sq(t2, t1); FOR (i, 1, 20) fe_sq(t2, t2); fe_mul(t1, t2, t1); + fe_sq(t1, t1); FOR (i, 1, 10) fe_sq(t1, t1); fe_mul(t0, t1, t0); + fe_sq(t1, t0); FOR (i, 1, 50) fe_sq(t1, t1); fe_mul(t1, t1, t0); + fe_sq(t2, t1); FOR (i, 1, 100) fe_sq(t2, t2); fe_mul(t1, t2, t1); + fe_sq(t1, t1); FOR (i, 1, 50) fe_sq(t1, t1); fe_mul(t0, t1, t0); + fe_sq(t0, t0); FOR (i, 1, 2) fe_sq(t0, t0); fe_mul(out, t0, z); + WIPE_BUFFER(t0); + WIPE_BUFFER(t1); + WIPE_BUFFER(t2); +} + +// Inverting means multiplying by 2^255 - 21 +// 2^255 - 21 = (2^252 - 3) * 8 + 3 +// So we reuse the multiplication chain of fe_pow22523 +static void fe_invert(fe out, const fe z) +{ + fe tmp; + fe_pow22523(tmp, z); + // tmp2^8 * z^3 + fe_sq(tmp, tmp); // 0 + fe_sq(tmp, tmp); fe_mul(tmp, tmp, z); // 1 + fe_sq(tmp, tmp); fe_mul(out, tmp, z); // 1 + WIPE_BUFFER(tmp); +} + +// Parity check. Returns 0 if even, 1 if odd +static int fe_isodd(const fe f) +{ + u8 s[32]; + fe_tobytes(s, f); + u8 isodd = s[0] & 1; + WIPE_BUFFER(s); + return isodd; +} + +// Returns 1 if equal, 0 if not equal +static int fe_isequal(const fe f, const fe g) +{ + u8 fs[32]; + u8 gs[32]; + fe_tobytes(fs, f); + fe_tobytes(gs, g); + int isdifferent = crypto_verify32(fs, gs); + WIPE_BUFFER(fs); + WIPE_BUFFER(gs); + return 1 + isdifferent; +} + +// Inverse square root. +// Returns true if x is a non zero square, false otherwise. +// After the call: +// isr = sqrt(1/x) if x is non-zero square. +// isr = sqrt(sqrt(-1)/x) if x is not a square. +// isr = 0 if x is zero. +// We do not guarantee the sign of the square root. +// +// Notes: +// Let quartic = x^((p-1)/4) +// +// x^((p-1)/2) = chi(x) +// quartic^2 = chi(x) +// quartic = sqrt(chi(x)) +// quartic = 1 or -1 or sqrt(-1) or -sqrt(-1) +// +// Note that x is a square if quartic is 1 or -1 +// There are 4 cases to consider: +// +// if quartic = 1 (x is a square) +// then x^((p-1)/4) = 1 +// x^((p-5)/4) * x = 1 +// x^((p-5)/4) = 1/x +// x^((p-5)/8) = sqrt(1/x) or -sqrt(1/x) +// +// if quartic = -1 (x is a square) +// then x^((p-1)/4) = -1 +// x^((p-5)/4) * x = -1 +// x^((p-5)/4) = -1/x +// x^((p-5)/8) = sqrt(-1) / sqrt(x) +// x^((p-5)/8) * sqrt(-1) = sqrt(-1)^2 / sqrt(x) +// x^((p-5)/8) * sqrt(-1) = -1/sqrt(x) +// x^((p-5)/8) * sqrt(-1) = -sqrt(1/x) or sqrt(1/x) +// +// if quartic = sqrt(-1) (x is not a square) +// then x^((p-1)/4) = sqrt(-1) +// x^((p-5)/4) * x = sqrt(-1) +// x^((p-5)/4) = sqrt(-1)/x +// x^((p-5)/8) = sqrt(sqrt(-1)/x) or -sqrt(sqrt(-1)/x) +// +// Note that the product of two non-squares is always a square: +// For any non-squares a and b, chi(a) = -1 and chi(b) = -1. +// Since chi(x) = x^((p-1)/2), chi(a)*chi(b) = chi(a*b) = 1. +// Therefore a*b is a square. +// +// Since sqrt(-1) and x are both non-squares, their product is a +// square, and we can compute their square root. +// +// if quartic = -sqrt(-1) (x is not a square) +// then x^((p-1)/4) = -sqrt(-1) +// x^((p-5)/4) * x = -sqrt(-1) +// x^((p-5)/4) = -sqrt(-1)/x +// x^((p-5)/8) = sqrt(-sqrt(-1)/x) +// x^((p-5)/8) = sqrt( sqrt(-1)/x) * sqrt(-1) +// x^((p-5)/8) * sqrt(-1) = sqrt( sqrt(-1)/x) * sqrt(-1)^2 +// x^((p-5)/8) * sqrt(-1) = sqrt( sqrt(-1)/x) * -1 +// x^((p-5)/8) * sqrt(-1) = -sqrt(sqrt(-1)/x) or sqrt(sqrt(-1)/x) +static int invsqrt(fe isr, const fe x) +{ + fe check, quartic; + fe_copy(check, x); + fe_pow22523(isr, check); + fe_sq (quartic, isr); + fe_mul(quartic, quartic, check); + fe_1 (check); int p1 = fe_isequal(quartic, check); + fe_neg(check, check ); int m1 = fe_isequal(quartic, check); + fe_neg(check, sqrtm1); int ms = fe_isequal(quartic, check); + fe_mul(check, isr, sqrtm1); + fe_ccopy(isr, check, m1 | ms); + WIPE_BUFFER(quartic); + WIPE_BUFFER(check); + return p1 | m1; +} + +// trim a scalar for scalar multiplication +static void trim_scalar(u8 scalar[32]) +{ + scalar[ 0] &= 248; + scalar[31] &= 127; + scalar[31] |= 64; +} + +// get bit from scalar at position i +static int scalar_bit(const u8 s[32], int i) +{ + if (i < 0) { return 0; } // handle -1 for sliding windows + return (s[i>>3] >> (i&7)) & 1; +} + +/////////////// +/// X-25519 /// Taken from SUPERCOP's ref10 implementation. +/////////////// +static void scalarmult(u8 q[32], const u8 scalar[32], const u8 p[32], + int nb_bits) +{ + // computes the scalar product + fe x1; + fe_frombytes(x1, p); + + // computes the actual scalar product (the result is in x2 and z2) + fe x2, z2, x3, z3, t0, t1; + // Montgomery ladder + // In projective coordinates, to avoid divisions: x = X / Z + // We don't care about the y coordinate, it's only 1 bit of information + fe_1(x2); fe_0(z2); // "zero" point + fe_copy(x3, x1); fe_1(z3); // "one" point + int swap = 0; + for (int pos = nb_bits-1; pos >= 0; --pos) { + // constant time conditional swap before ladder step + int b = scalar_bit(scalar, pos); + swap ^= b; // xor trick avoids swapping at the end of the loop + fe_cswap(x2, x3, swap); + fe_cswap(z2, z3, swap); + swap = b; // anticipates one last swap after the loop + + // Montgomery ladder step: replaces (P2, P3) by (P2*2, P2+P3) + // with differential addition + fe_sub(t0, x3, z3); + fe_sub(t1, x2, z2); + fe_add(x2, x2, z2); + fe_add(z2, x3, z3); + fe_mul(z3, t0, x2); + fe_mul(z2, z2, t1); + fe_sq (t0, t1 ); + fe_sq (t1, x2 ); + fe_add(x3, z3, z2); + fe_sub(z2, z3, z2); + fe_mul(x2, t1, t0); + fe_sub(t1, t1, t0); + fe_sq (z2, z2 ); + fe_mul_small(z3, t1, 121666); + fe_sq (x3, x3 ); + fe_add(t0, t0, z3); + fe_mul(z3, x1, z2); + fe_mul(z2, t1, t0); + } + // last swap is necessary to compensate for the xor trick + // Note: after this swap, P3 == P2 + P1. + fe_cswap(x2, x3, swap); + fe_cswap(z2, z3, swap); + + // normalises the coordinates: x == X / Z + fe_invert(z2, z2); + fe_mul(x2, x2, z2); + fe_tobytes(q, x2); + + WIPE_BUFFER(x1); + WIPE_BUFFER(x2); WIPE_BUFFER(z2); WIPE_BUFFER(t0); + WIPE_BUFFER(x3); WIPE_BUFFER(z3); WIPE_BUFFER(t1); +} + +void crypto_x25519(u8 raw_shared_secret[32], + const u8 your_secret_key [32], + const u8 their_public_key [32]) +{ + // restrict the possible scalar values + u8 e[32]; + COPY(e, your_secret_key, 32); + trim_scalar(e); + scalarmult(raw_shared_secret, e, their_public_key, 255); + WIPE_BUFFER(e); +} + +void crypto_x25519_public_key(u8 public_key[32], + const u8 secret_key[32]) +{ + static const u8 base_point[32] = {9}; + crypto_x25519(public_key, secret_key, base_point); +} + +/////////////////////////// +/// Arithmetic modulo L /// +/////////////////////////// +static const u32 L[8] = {0x5cf5d3ed, 0x5812631a, 0xa2f79cd6, 0x14def9de, + 0x00000000, 0x00000000, 0x00000000, 0x10000000,}; + +// p = a*b + p +static void multiply(u32 p[16], const u32 a[8], const u32 b[8]) +{ + FOR (i, 0, 8) { + u64 carry = 0; + FOR (j, 0, 8) { + carry += p[i+j] + (u64)a[i] * b[j]; + p[i+j] = (u32)carry; + carry >>= 32; + } + p[i+8] = (u32)carry; + } +} + +static int is_above_l(const u32 x[8]) +{ + // We work with L directly, in a 2's complement encoding + // (-L == ~L + 1) + u64 carry = 1; + FOR (i, 0, 8) { + carry += (u64)x[i] + ~L[i]; + carry >>= 32; + } + return carry; +} + +// Final reduction modulo L, by conditionally removing L. +// if x < l , then r = x +// if l <= x 2*l, then r = x-l +// otherwise the result will be wrong +static void remove_l(u32 r[8], const u32 x[8]) +{ + u64 carry = is_above_l(x); + u32 mask = ~(u32)carry + 1; // carry == 0 or 1 + FOR (i, 0, 8) { + carry += (u64)x[i] + (~L[i] & mask); + r[i] = (u32)carry; + carry >>= 32; + } +} + +// Full reduction modulo L (Barrett reduction) +static void mod_l(u8 reduced[32], const u32 x[16]) +{ + static const u32 r[9] = {0x0a2c131b,0xed9ce5a3,0x086329a7,0x2106215d, + 0xffffffeb,0xffffffff,0xffffffff,0xffffffff,0xf,}; + // xr = x * r + u32 xr[25] = {0}; + FOR (i, 0, 9) { + u64 carry = 0; + FOR (j, 0, 16) { + carry += xr[i+j] + (u64)r[i] * x[j]; + xr[i+j] = (u32)carry; + carry >>= 32; + } + xr[i+16] = (u32)carry; + } + // xr = floor(xr / 2^512) * L + // Since the result is guaranteed to be below 2*L, + // it is enough to only compute the first 256 bits. + // The division is performed by saying xr[i+16]. (16 * 32 = 512) + ZERO(xr, 8); + FOR (i, 0, 8) { + u64 carry = 0; + FOR (j, 0, 8-i) { + carry += xr[i+j] + (u64)xr[i+16] * L[j]; + xr[i+j] = (u32)carry; + carry >>= 32; + } + } + // xr = x - xr + u64 carry = 1; + FOR (i, 0, 8) { + carry += (u64)x[i] + ~xr[i]; + xr[i] = (u32)carry; + carry >>= 32; + } + // Final reduction modulo L (conditional subtraction) + remove_l(xr, xr); + store32_le_buf(reduced, xr, 8); + + WIPE_BUFFER(xr); +} + +static void reduce(u8 r[64]) +{ + u32 x[16]; + load32_le_buf(x, r, 16); + mod_l(r, x); + WIPE_BUFFER(x); +} + +// r = (a * b) + c +static void mul_add(u8 r[32], const u8 a[32], const u8 b[32], const u8 c[32]) +{ + u32 A[8]; load32_le_buf(A, a, 8); + u32 B[8]; load32_le_buf(B, b, 8); + u32 p[16]; + load32_le_buf(p, c, 8); + ZERO(p + 8, 8); + multiply(p, A, B); + mod_l(r, p); + WIPE_BUFFER(p); + WIPE_BUFFER(A); + WIPE_BUFFER(B); +} + +/////////////// +/// Ed25519 /// +/////////////// + +// Point (group element, ge) in a twisted Edwards curve, +// in extended projective coordinates. +// ge : x = X/Z, y = Y/Z, T = XY/Z +// ge_cached : Yp = X+Y, Ym = X-Y, T2 = T*D2 +// ge_precomp: Z = 1 +typedef struct { fe X; fe Y; fe Z; fe T; } ge; +typedef struct { fe Yp; fe Ym; fe Z; fe T2; } ge_cached; +typedef struct { fe Yp; fe Ym; fe T2; } ge_precomp; + +static void ge_zero(ge *p) +{ + fe_0(p->X); + fe_1(p->Y); + fe_1(p->Z); + fe_0(p->T); +} + +static void ge_tobytes(u8 s[32], const ge *h) +{ + fe recip, x, y; + fe_invert(recip, h->Z); + fe_mul(x, h->X, recip); + fe_mul(y, h->Y, recip); + fe_tobytes(s, y); + s[31] ^= fe_isodd(x) << 7; + + WIPE_BUFFER(recip); + WIPE_BUFFER(x); + WIPE_BUFFER(y); +} + +// h = s, where s is a point encoded in 32 bytes +// +// Variable time! Inputs must not be secret! +// => Use only to *check* signatures. +// +// From the specifications: +// The encoding of s contains y and the sign of x +// x = sqrt((y^2 - 1) / (d*y^2 + 1)) +// In extended coordinates: +// X = x, Y = y, Z = 1, T = x*y +// +// Note that num * den is a square iff num / den is a square +// If num * den is not a square, the point was not on the curve. +// From the above: +// Let num = y^2 - 1 +// Let den = d*y^2 + 1 +// x = sqrt((y^2 - 1) / (d*y^2 + 1)) +// x = sqrt(num / den) +// x = sqrt(num^2 / (num * den)) +// x = num * sqrt(1 / (num * den)) +// +// Therefore, we can just compute: +// num = y^2 - 1 +// den = d*y^2 + 1 +// isr = invsqrt(num * den) // abort if not square +// x = num * isr +// Finally, negate x if its sign is not as specified. +static int ge_frombytes_vartime(ge *h, const u8 s[32]) +{ + fe_frombytes(h->Y, s); + fe_1(h->Z); + fe_sq (h->T, h->Y); // t = y^2 + fe_mul(h->X, h->T, d ); // x = d*y^2 + fe_sub(h->T, h->T, h->Z); // t = y^2 - 1 + fe_add(h->X, h->X, h->Z); // x = d*y^2 + 1 + fe_mul(h->X, h->T, h->X); // x = (y^2 - 1) * (d*y^2 + 1) + int is_square = invsqrt(h->X, h->X); + if (!is_square) { + return -1; // Not on the curve, abort + } + fe_mul(h->X, h->T, h->X); // x = sqrt((y^2 - 1) / (d*y^2 + 1)) + if (fe_isodd(h->X) != (s[31] >> 7)) { + fe_neg(h->X, h->X); + } + fe_mul(h->T, h->X, h->Y); + return 0; +} + +static void ge_cache(ge_cached *c, const ge *p) +{ + fe_add (c->Yp, p->Y, p->X); + fe_sub (c->Ym, p->Y, p->X); + fe_copy(c->Z , p->Z ); + fe_mul (c->T2, p->T, D2 ); +} + +// Internal buffers are not wiped! Inputs must not be secret! +// => Use only to *check* signatures. +static void ge_add(ge *s, const ge *p, const ge_cached *q) +{ + fe a, b; + fe_add(a , p->Y, p->X ); + fe_sub(b , p->Y, p->X ); + fe_mul(a , a , q->Yp); + fe_mul(b , b , q->Ym); + fe_add(s->Y, a , b ); + fe_sub(s->X, a , b ); + + fe_add(s->Z, p->Z, p->Z ); + fe_mul(s->Z, s->Z, q->Z ); + fe_mul(s->T, p->T, q->T2); + fe_add(a , s->Z, s->T ); + fe_sub(b , s->Z, s->T ); + + fe_mul(s->T, s->X, s->Y); + fe_mul(s->X, s->X, b ); + fe_mul(s->Y, s->Y, a ); + fe_mul(s->Z, a , b ); +} + +// Internal buffers are not wiped! Inputs must not be secret! +// => Use only to *check* signatures. +static void ge_sub(ge *s, const ge *p, const ge_cached *q) +{ + ge_cached neg; + fe_copy(neg.Ym, q->Yp); + fe_copy(neg.Yp, q->Ym); + fe_copy(neg.Z , q->Z ); + fe_neg (neg.T2, q->T2); + ge_add(s, p, &neg); +} + +static void ge_madd(ge *s, const ge *p, const ge_precomp *q, fe a, fe b) +{ + fe_add(a , p->Y, p->X ); + fe_sub(b , p->Y, p->X ); + fe_mul(a , a , q->Yp); + fe_mul(b , b , q->Ym); + fe_add(s->Y, a , b ); + fe_sub(s->X, a , b ); + + fe_add(s->Z, p->Z, p->Z ); + fe_mul(s->T, p->T, q->T2); + fe_add(a , s->Z, s->T ); + fe_sub(b , s->Z, s->T ); + + fe_mul(s->T, s->X, s->Y); + fe_mul(s->X, s->X, b ); + fe_mul(s->Y, s->Y, a ); + fe_mul(s->Z, a , b ); +} + +static void ge_msub(ge *s, const ge *p, const ge_precomp *q, fe a, fe b) +{ + fe_add(a , p->Y, p->X ); + fe_sub(b , p->Y, p->X ); + fe_mul(a , a , q->Ym); + fe_mul(b , b , q->Yp); + fe_add(s->Y, a , b ); + fe_sub(s->X, a , b ); + + fe_add(s->Z, p->Z, p->Z ); + fe_mul(s->T, p->T, q->T2); + fe_sub(a , s->Z, s->T ); + fe_add(b , s->Z, s->T ); + + fe_mul(s->T, s->X, s->Y); + fe_mul(s->X, s->X, b ); + fe_mul(s->Y, s->Y, a ); + fe_mul(s->Z, a , b ); +} + +static void ge_double(ge *s, const ge *p, ge *q) +{ + fe_sq (q->X, p->X); + fe_sq (q->Y, p->Y); + fe_sq2(q->Z, p->Z); + fe_add(q->T, p->X, p->Y); + fe_sq (s->T, q->T); + fe_add(q->T, q->Y, q->X); + fe_sub(q->Y, q->Y, q->X); + fe_sub(q->X, s->T, q->T); + fe_sub(q->Z, q->Z, q->Y); + + fe_mul(s->X, q->X , q->Z); + fe_mul(s->Y, q->T , q->Y); + fe_mul(s->Z, q->Y , q->Z); + fe_mul(s->T, q->X , q->T); +} + +// 5-bit signed window in cached format (Niels coordinates, Z=1) +static const ge_precomp b_window[8] = { + {{25967493,-14356035,29566456,3660896,-12694345, + 4014787,27544626,-11754271,-6079156,2047605,}, + {-12545711,934262,-2722910,3049990,-727428, + 9406986,12720692,5043384,19500929,-15469378,}, + {-8738181,4489570,9688441,-14785194,10184609, + -12363380,29287919,11864899,-24514362,-4438546,},}, + {{15636291,-9688557,24204773,-7912398,616977, + -16685262,27787600,-14772189,28944400,-1550024,}, + {16568933,4717097,-11556148,-1102322,15682896, + -11807043,16354577,-11775962,7689662,11199574,}, + {30464156,-5976125,-11779434,-15670865,23220365, + 15915852,7512774,10017326,-17749093,-9920357,},}, + {{10861363,11473154,27284546,1981175,-30064349, + 12577861,32867885,14515107,-15438304,10819380,}, + {4708026,6336745,20377586,9066809,-11272109, + 6594696,-25653668,12483688,-12668491,5581306,}, + {19563160,16186464,-29386857,4097519,10237984, + -4348115,28542350,13850243,-23678021,-15815942,},}, + {{5153746,9909285,1723747,-2777874,30523605, + 5516873,19480852,5230134,-23952439,-15175766,}, + {-30269007,-3463509,7665486,10083793,28475525, + 1649722,20654025,16520125,30598449,7715701,}, + {28881845,14381568,9657904,3680757,-20181635, + 7843316,-31400660,1370708,29794553,-1409300,},}, + {{-22518993,-6692182,14201702,-8745502,-23510406, + 8844726,18474211,-1361450,-13062696,13821877,}, + {-6455177,-7839871,3374702,-4740862,-27098617, + -10571707,31655028,-7212327,18853322,-14220951,}, + {4566830,-12963868,-28974889,-12240689,-7602672, + -2830569,-8514358,-10431137,2207753,-3209784,},}, + {{-25154831,-4185821,29681144,7868801,-6854661, + -9423865,-12437364,-663000,-31111463,-16132436,}, + {25576264,-2703214,7349804,-11814844,16472782, + 9300885,3844789,15725684,171356,6466918,}, + {23103977,13316479,9739013,-16149481,817875, + -15038942,8965339,-14088058,-30714912,16193877,},}, + {{-33521811,3180713,-2394130,14003687,-16903474, + -16270840,17238398,4729455,-18074513,9256800,}, + {-25182317,-4174131,32336398,5036987,-21236817, + 11360617,22616405,9761698,-19827198,630305,}, + {-13720693,2639453,-24237460,-7406481,9494427, + -5774029,-6554551,-15960994,-2449256,-14291300,},}, + {{-3151181,-5046075,9282714,6866145,-31907062, + -863023,-18940575,15033784,25105118,-7894876,}, + {-24326370,15950226,-31801215,-14592823,-11662737, + -5090925,1573892,-2625887,2198790,-15804619,}, + {-3099351,10324967,-2241613,7453183,-5446979, + -2735503,-13812022,-16236442,-32461234,-12290683,},}, +}; + +// Incremental sliding windows (left to right) +// Based on Roberto Maria Avanzi[2005] +typedef struct { + i16 next_index; // position of the next signed digit + i8 next_digit; // next signed digit (odd number below 2^window_width) + u8 next_check; // point at which we must check for a new window +} slide_ctx; + +static void slide_init(slide_ctx *ctx, const u8 scalar[32]) +{ + // scalar is guaranteed to be below L, either because we checked (s), + // or because we reduced it modulo L (h_ram). L is under 2^253, so + // so bits 253 to 255 are guaranteed to be zero. No need to test them. + // + // Note however that L is very close to 2^252, so bit 252 is almost + // always zero. If we were to start at bit 251, the tests wouldn't + // catch the off-by-one error (constructing one that does would be + // prohibitively expensive). + // + // We should still check bit 252, though. + int i = 252; + while (i > 0 && scalar_bit(scalar, i) == 0) { + i--; + } + ctx->next_check = (u8)(i + 1); + ctx->next_index = -1; + ctx->next_digit = -1; +} + +static int slide_step(slide_ctx *ctx, int width, int i, const u8 scalar[32]) +{ + if (i == ctx->next_check) { + if (scalar_bit(scalar, i) == scalar_bit(scalar, i - 1)) { + ctx->next_check--; + } else { + // compute digit of next window + int w = MIN(width, i + 1); + int v = -(scalar_bit(scalar, i) << (w-1)); + FOR_T (int, j, 0, w-1) { + v += scalar_bit(scalar, i-(w-1)+j) << j; + } + v += scalar_bit(scalar, i-w); + int lsb = v & (~v + 1); // smallest bit of v + int s = ( ((lsb & 0xAA) != 0) // log2(lsb) + | (((lsb & 0xCC) != 0) << 1) + | (((lsb & 0xF0) != 0) << 2)); + ctx->next_index = (i16)(i-(w-1)+s); + ctx->next_digit = (i8) (v >> s ); + ctx->next_check -= (u8) w; + } + } + return i == ctx->next_index ? ctx->next_digit: 0; +} + +#define P_W_WIDTH 3 // Affects the size of the stack +#define B_W_WIDTH 5 // Affects the size of the binary +#define P_W_SIZE (1<<(P_W_WIDTH-2)) + +// P = [b]B + [p]P, where B is the base point +// +// Variable time! Internal buffers are not wiped! Inputs must not be secret! +// => Use only to *check* signatures. +static void ge_double_scalarmult_vartime(ge *P, const u8 p[32], const u8 b[32]) +{ + // cache P window for addition + ge_cached cP[P_W_SIZE]; + { + ge P2, tmp; + ge_double(&P2, P, &tmp); + ge_cache(&cP[0], P); + FOR (i, 1, P_W_SIZE) { + ge_add(&tmp, &P2, &cP[i-1]); + ge_cache(&cP[i], &tmp); + } + } + + // Merged double and add ladder, fused with sliding + slide_ctx p_slide; slide_init(&p_slide, p); + slide_ctx b_slide; slide_init(&b_slide, b); + int i = MAX(p_slide.next_check, b_slide.next_check); + ge *sum = P; + ge_zero(sum); + while (i >= 0) { + ge tmp; + ge_double(sum, sum, &tmp); + int p_digit = slide_step(&p_slide, P_W_WIDTH, i, p); + int b_digit = slide_step(&b_slide, B_W_WIDTH, i, b); + if (p_digit > 0) { ge_add(sum, sum, &cP[ p_digit / 2]); } + if (p_digit < 0) { ge_sub(sum, sum, &cP[-p_digit / 2]); } + fe t1, t2; + if (b_digit > 0) { ge_madd(sum, sum, b_window + b_digit/2, t1, t2); } + if (b_digit < 0) { ge_msub(sum, sum, b_window + -b_digit/2, t1, t2); } + i--; + } +} + +// R_check = s[B] - h_ram[pk], where B is the base point +// +// Variable time! Internal buffers are not wiped! Inputs must not be secret! +// => Use only to *check* signatures. +static int ge_r_check(u8 R_check[32], u8 s[32], u8 h_ram[32], u8 pk[32]) +{ + ge A; // not secret, not wiped + u32 s32[8]; // not secret, not wiped + load32_le_buf(s32, s, 8); + if (ge_frombytes_vartime(&A, pk) || // A = pk + is_above_l(s32)) { // prevent s malleability + return -1; + } + fe_neg(A.X, A.X); + fe_neg(A.T, A.T); // A = -pk + ge_double_scalarmult_vartime(&A, h_ram, s); // A = [s]B - [h_ram]pk + ge_tobytes(R_check, &A); // R_check = A + return 0; +} + +// 5-bit signed comb in cached format (Niels coordinates, Z=1) +static const ge_precomp b_comb_low[8] = { + {{-6816601,-2324159,-22559413,124364,18015490, + 8373481,19993724,1979872,-18549925,9085059,}, + {10306321,403248,14839893,9633706,8463310, + -8354981,-14305673,14668847,26301366,2818560,}, + {-22701500,-3210264,-13831292,-2927732,-16326337, + -14016360,12940910,177905,12165515,-2397893,},}, + {{-12282262,-7022066,9920413,-3064358,-32147467, + 2927790,22392436,-14852487,2719975,16402117,}, + {-7236961,-4729776,2685954,-6525055,-24242706, + -15940211,-6238521,14082855,10047669,12228189,}, + {-30495588,-12893761,-11161261,3539405,-11502464, + 16491580,-27286798,-15030530,-7272871,-15934455,},}, + {{17650926,582297,-860412,-187745,-12072900, + -10683391,-20352381,15557840,-31072141,-5019061,}, + {-6283632,-2259834,-4674247,-4598977,-4089240, + 12435688,-31278303,1060251,6256175,10480726,}, + {-13871026,2026300,-21928428,-2741605,-2406664, + -8034988,7355518,15733500,-23379862,7489131,},}, + {{6883359,695140,23196907,9644202,-33430614, + 11354760,-20134606,6388313,-8263585,-8491918,}, + {-7716174,-13605463,-13646110,14757414,-19430591, + -14967316,10359532,-11059670,-21935259,12082603,}, + {-11253345,-15943946,10046784,5414629,24840771, + 8086951,-6694742,9868723,15842692,-16224787,},}, + {{9639399,11810955,-24007778,-9320054,3912937, + -9856959,996125,-8727907,-8919186,-14097242,}, + {7248867,14468564,25228636,-8795035,14346339, + 8224790,6388427,-7181107,6468218,-8720783,}, + {15513115,15439095,7342322,-10157390,18005294, + -7265713,2186239,4884640,10826567,7135781,},}, + {{-14204238,5297536,-5862318,-6004934,28095835, + 4236101,-14203318,1958636,-16816875,3837147,}, + {-5511166,-13176782,-29588215,12339465,15325758, + -15945770,-8813185,11075932,-19608050,-3776283,}, + {11728032,9603156,-4637821,-5304487,-7827751, + 2724948,31236191,-16760175,-7268616,14799772,},}, + {{-28842672,4840636,-12047946,-9101456,-1445464, + 381905,-30977094,-16523389,1290540,12798615,}, + {27246947,-10320914,14792098,-14518944,5302070, + -8746152,-3403974,-4149637,-27061213,10749585,}, + {25572375,-6270368,-15353037,16037944,1146292, + 32198,23487090,9585613,24714571,-1418265,},}, + {{19844825,282124,-17583147,11004019,-32004269, + -2716035,6105106,-1711007,-21010044,14338445,}, + {8027505,8191102,-18504907,-12335737,25173494, + -5923905,15446145,7483684,-30440441,10009108,}, + {-14134701,-4174411,10246585,-14677495,33553567, + -14012935,23366126,15080531,-7969992,7663473,},}, +}; + +static const ge_precomp b_comb_high[8] = { + {{33055887,-4431773,-521787,6654165,951411, + -6266464,-5158124,6995613,-5397442,-6985227,}, + {4014062,6967095,-11977872,3960002,8001989, + 5130302,-2154812,-1899602,-31954493,-16173976,}, + {16271757,-9212948,23792794,731486,-25808309, + -3546396,6964344,-4767590,10976593,10050757,},}, + {{2533007,-4288439,-24467768,-12387405,-13450051, + 14542280,12876301,13893535,15067764,8594792,}, + {20073501,-11623621,3165391,-13119866,13188608, + -11540496,-10751437,-13482671,29588810,2197295,}, + {-1084082,11831693,6031797,14062724,14748428, + -8159962,-20721760,11742548,31368706,13161200,},}, + {{2050412,-6457589,15321215,5273360,25484180, + 124590,-18187548,-7097255,-6691621,-14604792,}, + {9938196,2162889,-6158074,-1711248,4278932, + -2598531,-22865792,-7168500,-24323168,11746309,}, + {-22691768,-14268164,5965485,9383325,20443693, + 5854192,28250679,-1381811,-10837134,13717818,},}, + {{-8495530,16382250,9548884,-4971523,-4491811, + -3902147,6182256,-12832479,26628081,10395408,}, + {27329048,-15853735,7715764,8717446,-9215518, + -14633480,28982250,-5668414,4227628,242148,}, + {-13279943,-7986904,-7100016,8764468,-27276630, + 3096719,29678419,-9141299,3906709,11265498,},}, + {{11918285,15686328,-17757323,-11217300,-27548967, + 4853165,-27168827,6807359,6871949,-1075745,}, + {-29002610,13984323,-27111812,-2713442,28107359, + -13266203,6155126,15104658,3538727,-7513788,}, + {14103158,11233913,-33165269,9279850,31014152, + 4335090,-1827936,4590951,13960841,12787712,},}, + {{1469134,-16738009,33411928,13942824,8092558, + -8778224,-11165065,1437842,22521552,-2792954,}, + {31352705,-4807352,-25327300,3962447,12541566, + -9399651,-27425693,7964818,-23829869,5541287,}, + {-25732021,-6864887,23848984,3039395,-9147354, + 6022816,-27421653,10590137,25309915,-1584678,},}, + {{-22951376,5048948,31139401,-190316,-19542447, + -626310,-17486305,-16511925,-18851313,-12985140,}, + {-9684890,14681754,30487568,7717771,-10829709, + 9630497,30290549,-10531496,-27798994,-13812825,}, + {5827835,16097107,-24501327,12094619,7413972, + 11447087,28057551,-1793987,-14056981,4359312,},}, + {{26323183,2342588,-21887793,-1623758,-6062284, + 2107090,-28724907,9036464,-19618351,-13055189,}, + {-29697200,14829398,-4596333,14220089,-30022969, + 2955645,12094100,-13693652,-5941445,7047569,}, + {-3201977,14413268,-12058324,-16417589,-9035655, + -7224648,9258160,1399236,30397584,-5684634,},}, +}; + +static void lookup_add(ge *p, ge_precomp *tmp_c, fe tmp_a, fe tmp_b, + const ge_precomp comb[8], const u8 scalar[32], int i) +{ + u8 teeth = (u8)((scalar_bit(scalar, i) ) + + (scalar_bit(scalar, i + 32) << 1) + + (scalar_bit(scalar, i + 64) << 2) + + (scalar_bit(scalar, i + 96) << 3)); + u8 high = teeth >> 3; + u8 index = (teeth ^ (high - 1)) & 7; + FOR (j, 0, 8) { + i32 select = 1 & (((j ^ index) - 1) >> 8); + fe_ccopy(tmp_c->Yp, comb[j].Yp, select); + fe_ccopy(tmp_c->Ym, comb[j].Ym, select); + fe_ccopy(tmp_c->T2, comb[j].T2, select); + } + fe_neg(tmp_a, tmp_c->T2); + fe_cswap(tmp_c->T2, tmp_a , high ^ 1); + fe_cswap(tmp_c->Yp, tmp_c->Ym, high ^ 1); + ge_madd(p, p, tmp_c, tmp_a, tmp_b); +} + +// p = [scalar]B, where B is the base point +static void ge_scalarmult_base(ge *p, const u8 scalar[32]) +{ + // twin 4-bits signed combs, from Mike Hamburg's + // Fast and compact elliptic-curve cryptography (2012) + // 1 / 2 modulo L + static const u8 half_mod_L[32] = { + 247,233,122,46,141,49,9,44,107,206,123,81,239,124,111,10, + 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,8, }; + // (2^256 - 1) / 2 modulo L + static const u8 half_ones[32] = { + 142,74,204,70,186,24,118,107,184,231,190,57,250,173,119,99, + 255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,7, }; + + // All bits set form: 1 means 1, 0 means -1 + u8 s_scalar[32]; + mul_add(s_scalar, scalar, half_mod_L, half_ones); + + // Double and add ladder + fe tmp_a, tmp_b; // temporaries for addition + ge_precomp tmp_c; // temporary for comb lookup + ge tmp_d; // temporary for doubling + fe_1(tmp_c.Yp); + fe_1(tmp_c.Ym); + fe_0(tmp_c.T2); + + // Save a double on the first iteration + ge_zero(p); + lookup_add(p, &tmp_c, tmp_a, tmp_b, b_comb_low , s_scalar, 31); + lookup_add(p, &tmp_c, tmp_a, tmp_b, b_comb_high, s_scalar, 31+128); + // Regular double & add for the rest + for (int i = 30; i >= 0; i--) { + ge_double(p, p, &tmp_d); + lookup_add(p, &tmp_c, tmp_a, tmp_b, b_comb_low , s_scalar, i); + lookup_add(p, &tmp_c, tmp_a, tmp_b, b_comb_high, s_scalar, i+128); + } + // Note: we could save one addition at the end if we assumed the + // scalar fit in 252 bit. Which it does in practice if it is + // selected at random. However, non-random, non-hashed scalars + // *can* overflow 252 bits in practice. Better account for that + // than leaving that kind of subtle corner case. + + WIPE_BUFFER(tmp_a); WIPE_CTX(&tmp_d); + WIPE_BUFFER(tmp_b); WIPE_CTX(&tmp_c); + WIPE_BUFFER(s_scalar); +} + +void crypto_sign_public_key_custom_hash(u8 public_key[32], + const u8 secret_key[32], + const crypto_sign_vtable *hash) +{ + u8 a[64]; + hash->hash(a, secret_key, 32); + trim_scalar(a); + ge A; + ge_scalarmult_base(&A, a); + ge_tobytes(public_key, &A); + WIPE_BUFFER(a); + WIPE_CTX(&A); +} + +void crypto_sign_public_key(u8 public_key[32], const u8 secret_key[32]) +{ + crypto_sign_public_key_custom_hash(public_key, secret_key, + &crypto_blake2b_vtable); +} + +void crypto_sign_init_first_pass_custom_hash(crypto_sign_ctx_abstract *ctx, + const u8 secret_key[32], + const u8 public_key[32], + const crypto_sign_vtable *hash) +{ + ctx->hash = hash; // set vtable + u8 *a = ctx->buf; + u8 *prefix = ctx->buf + 32; + ctx->hash->hash(a, secret_key, 32); + trim_scalar(a); + + if (public_key == 0) { + crypto_sign_public_key_custom_hash(ctx->pk, secret_key, ctx->hash); + } else { + COPY(ctx->pk, public_key, 32); + } + + // Deterministic part of EdDSA: Construct a nonce by hashing the message + // instead of generating a random number. + // An actual random number would work just fine, and would save us + // the trouble of hashing the message twice. If we did that + // however, the user could fuck it up and reuse the nonce. + ctx->hash->init (ctx); + ctx->hash->update(ctx, prefix , 32); +} + +void crypto_sign_init_first_pass(crypto_sign_ctx_abstract *ctx, + const u8 secret_key[32], + const u8 public_key[32]) +{ + crypto_sign_init_first_pass_custom_hash(ctx, secret_key, public_key, + &crypto_blake2b_vtable); +} + +void crypto_sign_update(crypto_sign_ctx_abstract *ctx, + const u8 *msg, size_t msg_size) +{ + ctx->hash->update(ctx, msg, msg_size); +} + +void crypto_sign_init_second_pass(crypto_sign_ctx_abstract *ctx) +{ + u8 *r = ctx->buf + 32; + u8 *half_sig = ctx->buf + 64; + ctx->hash->final(ctx, r); + reduce(r); + + // first half of the signature = "random" nonce times the base point + ge R; + ge_scalarmult_base(&R, r); + ge_tobytes(half_sig, &R); + WIPE_CTX(&R); + + // Hash R, the public key, and the message together. + // It cannot be done in parallel with the first hash. + ctx->hash->init (ctx); + ctx->hash->update(ctx, half_sig, 32); + ctx->hash->update(ctx, ctx->pk , 32); +} + +void crypto_sign_final(crypto_sign_ctx_abstract *ctx, u8 signature[64]) +{ + u8 *a = ctx->buf; + u8 *r = ctx->buf + 32; + u8 *half_sig = ctx->buf + 64; + u8 h_ram[64]; + ctx->hash->final(ctx, h_ram); + reduce(h_ram); + COPY(signature, half_sig, 32); + mul_add(signature + 32, h_ram, a, r); // s = h_ram * a + r + WIPE_BUFFER(h_ram); + crypto_wipe(ctx, ctx->hash->ctx_size); +} + +void crypto_sign(u8 signature[64], + const u8 secret_key[32], + const u8 public_key[32], + const u8 *message, size_t message_size) +{ + crypto_sign_ctx ctx; + crypto_sign_ctx_abstract *actx = (crypto_sign_ctx_abstract*)&ctx; + crypto_sign_init_first_pass (actx, secret_key, public_key); + crypto_sign_update (actx, message, message_size); + crypto_sign_init_second_pass(actx); + crypto_sign_update (actx, message, message_size); + crypto_sign_final (actx, signature); +} + +void crypto_check_init_custom_hash(crypto_check_ctx_abstract *ctx, + const u8 signature[64], + const u8 public_key[32], + const crypto_sign_vtable *hash) +{ + ctx->hash = hash; // set vtable + COPY(ctx->buf, signature , 64); + COPY(ctx->pk , public_key, 32); + ctx->hash->init (ctx); + ctx->hash->update(ctx, signature , 32); + ctx->hash->update(ctx, public_key, 32); +} + +void crypto_check_init(crypto_check_ctx_abstract *ctx, const u8 signature[64], + const u8 public_key[32]) +{ + crypto_check_init_custom_hash(ctx, signature, public_key, + &crypto_blake2b_vtable); +} + +void crypto_check_update(crypto_check_ctx_abstract *ctx, + const u8 *msg, size_t msg_size) +{ + ctx->hash->update(ctx, msg, msg_size); +} + +int crypto_check_final(crypto_check_ctx_abstract *ctx) +{ + u8 h_ram[64]; + ctx->hash->final(ctx, h_ram); + reduce(h_ram); + u8 *R = ctx->buf; // R + u8 *s = ctx->buf + 32; // s + u8 *R_check = ctx->pk; // overwrite ctx->pk to save stack space + if (ge_r_check(R_check, s, h_ram, ctx->pk)) { + return -1; + } + return crypto_verify32(R, R_check); // R == R_check ? OK : fail +} + +int crypto_check(const u8 signature[64], const u8 public_key[32], + const u8 *message, size_t message_size) +{ + crypto_check_ctx ctx; + crypto_check_ctx_abstract *actx = (crypto_check_ctx_abstract*)&ctx; + crypto_check_init (actx, signature, public_key); + crypto_check_update(actx, message, message_size); + return crypto_check_final(actx); +} + +/////////////////////// +/// EdDSA to X25519 /// +/////////////////////// +void crypto_from_eddsa_private(u8 x25519[32], const u8 eddsa[32]) +{ + u8 a[64]; + crypto_blake2b(a, eddsa, 32); + COPY(x25519, a, 32); + WIPE_BUFFER(a); +} + +void crypto_from_eddsa_public(u8 x25519[32], const u8 eddsa[32]) +{ + fe t1, t2; + fe_frombytes(t2, eddsa); + fe_add(t1, fe_one, t2); + fe_sub(t2, fe_one, t2); + fe_invert(t2, t2); + fe_mul(t1, t1, t2); + fe_tobytes(x25519, t1); + WIPE_BUFFER(t1); + WIPE_BUFFER(t2); +} + +///////////////////////////////////////////// +/// Dirty ephemeral public key generation /// +///////////////////////////////////////////// + +// Those functions generates a public key, *without* clearing the +// cofactor. Sending that key over the network leaks 3 bits of the +// private key. Use only to generate ephemeral keys that will be hidden +// with crypto_curve_to_hidden(). +// +// The public key is otherwise compatible with crypto_x25519() and +// crypto_key_exchange() (those properly clear the cofactor). +// +// Note that the distribution of the resulting public keys is almost +// uniform. Flipping the sign of the v coordinate (not provided by this +// function), covers the entire key space almost perfectly, where +// "almost" means a 2^-128 bias (undetectable). This uniformity is +// needed to ensure the proper randomness of the resulting +// representatives (once we apply crypto_curve_to_hidden()). +// +// Recall that Curve25519 has order C = 2^255 + e, with e < 2^128 (not +// to be confused with the prime order of the main subgroup, L, which is +// 8 times less than that). +// +// Generating all points would require us to multiply a point of order C +// (the base point plus any point of order 8) by all scalars from 0 to +// C-1. Clamping limits us to scalars between 2^254 and 2^255 - 1. But +// by negating the resulting point at random, we also cover scalars from +// -2^255 + 1 to -2^254 (which modulo C is congruent to e+1 to 2^254 + e). +// +// In practice: +// - Scalars from 0 to e + 1 are never generated +// - Scalars from 2^255 to 2^255 + e are never generated +// - Scalars from 2^254 + 1 to 2^254 + e are generated twice +// +// Since e < 2^128, detecting this bias requires observing over 2^100 +// representatives from a given source (this will never happen), *and* +// recovering enough of the private key to determine that they do, or do +// not, belong to the biased set (this practically requires solving +// discrete logarithm, which is conjecturally intractable). +// +// In practice, this means the bias is impossible to detect. + +// s + (x*L) % 8*L +// Guaranteed to fit in 256 bits iff s fits in 255 bits. +// L < 2^253 +// x%8 < 2^3 +// L * (x%8) < 2^255 +// s < 2^255 +// s + L * (x%8) < 2^256 +static void add_xl(u8 s[32], u8 x) +{ + u64 mod8 = x & 7; + u64 carry = 0; + FOR (i , 0, 8) { + carry = carry + load32_le(s + 4*i) + L[i] * mod8; + store32_le(s + 4*i, (u32)carry); + carry >>= 32; + } +} + +// "Small" dirty ephemeral key. +// Use if you need to shrink the size of the binary, and can afford to +// slow down by a factor of two (compared to the fast version) +// +// This version works by decoupling the cofactor from the main factor. +// +// - The trimmed scalar determines the main factor +// - The clamped bits of the scalar determine the cofactor. +// +// Cofactor and main factor are combined into a single scalar, which is +// then multiplied by a point of order 8*L (unlike the base point, which +// has prime order). That "dirty" base point is the addition of the +// regular base point (9), and a point of order 8. +void crypto_x25519_dirty_small(u8 public_key[32], const u8 secret_key[32]) +{ + // Base point of order 8*L + // Raw scalar multiplication with it does not clear the cofactor, + // and the resulting public key will reveal 3 bits of the scalar. + static const u8 dirty_base_point[32] = { + 0x34, 0xfc, 0x6c, 0xb7, 0xc8, 0xde, 0x58, 0x97, 0x77, 0x70, 0xd9, 0x52, + 0x16, 0xcc, 0xdc, 0x6c, 0x85, 0x90, 0xbe, 0xcd, 0x91, 0x9c, 0x07, 0x59, + 0x94, 0x14, 0x56, 0x3b, 0x4b, 0xa4, 0x47, 0x0f, }; + // separate the main factor & the cofactor of the scalar + u8 scalar[32]; + COPY(scalar, secret_key, 32); + trim_scalar(scalar); + + // Separate the main factor and the cofactor + // + // The scalar is trimmed, so its cofactor is cleared. The three + // least significant bits however still have a main factor. We must + // remove it for X25519 compatibility. + // + // We exploit the fact that 5*L = 1 (modulo 8) + // cofactor = lsb * 5 * L (modulo 8*L) + // combined = scalar + cofactor (modulo 8*L) + // combined = scalar + (lsb * 5 * L) (modulo 8*L) + add_xl(scalar, secret_key[0] * 5); + scalarmult(public_key, scalar, dirty_base_point, 256); + WIPE_BUFFER(scalar); +} + +// "Fast" dirty ephemeral key +// We use this one by default. +// +// This version works by performing a regular scalar multiplication, +// then add a low order point. The scalar multiplication is done in +// Edwards space for more speed (*2 compared to the "small" version). +// The cost is a bigger binary for programs that don't also sign messages. +void crypto_x25519_dirty_fast(u8 public_key[32], const u8 secret_key[32]) +{ + u8 scalar[32]; + ge pk; + COPY(scalar, secret_key, 32); + trim_scalar(scalar); + ge_scalarmult_base(&pk, scalar); + + // Select low order point + // We're computing the [cofactor]lop scalar multiplication, where: + // cofactor = tweak & 7. + // lop = (lop_x, lop_y) + // lop_x = sqrt((sqrt(d + 1) + 1) / d) + // lop_y = -lop_x * sqrtm1 + // Notes: + // - A (single) Montgomery ladder would be twice as slow. + // - An actual scalar multiplication would hurt performance. + // - A full table lookup would take more code. + u8 cofactor = secret_key[0] & 7; + int a = (cofactor >> 2) & 1; + int b = (cofactor >> 1) & 1; + int c = (cofactor >> 0) & 1; + fe t1, t2, t3; + fe_0(t1); + fe_ccopy(t1, sqrtm1, b); + fe_ccopy(t1, lop_x , c); + fe_neg (t3, t1); + fe_ccopy(t1, t3, a); + fe_1(t2); + fe_0(t3); + fe_ccopy(t2, t3 , b); + fe_ccopy(t2, lop_y, c); + fe_neg (t3, t2); + fe_ccopy(t2, t3, a^b); + ge_precomp low_order_point; + fe_add(low_order_point.Yp, t2, t1); + fe_sub(low_order_point.Ym, t2, t1); + fe_mul(low_order_point.T2, t2, t1); + fe_mul(low_order_point.T2, low_order_point.T2, D2); + + // Add low order point to the public key + ge_madd(&pk, &pk, &low_order_point, t1, t2); + + // Convert to Montgomery u coordinate (we ignore the sign) + fe_add(t1, pk.Z, pk.Y); + fe_sub(t2, pk.Z, pk.Y); + fe_invert(t2, t2); + fe_mul(t1, t1, t2); + + fe_tobytes(public_key, t1); + + WIPE_BUFFER(t1); WIPE_BUFFER(scalar); + WIPE_BUFFER(t2); WIPE_CTX(&pk); + WIPE_BUFFER(t3); WIPE_CTX(&low_order_point); +} + +/////////////////// +/// Elligator 2 /// +/////////////////// +static const fe A = {486662}; + +// Elligator direct map +// +// Computes the point corresponding to a representative, encoded in 32 +// bytes (little Endian). Since positive representatives fits in 254 +// bits, The two most significant bits are ignored. +// +// From the paper: +// w = -A / (fe(1) + non_square * r^2) +// e = chi(w^3 + A*w^2 + w) +// u = e*w - (fe(1)-e)*(A//2) +// v = -e * sqrt(u^3 + A*u^2 + u) +// +// We ignore v because we don't need it for X25519 (the Montgomery +// ladder only uses u). +// +// Note that e is either 0, 1 or -1 +// if e = 0 u = 0 and v = 0 +// if e = 1 u = w +// if e = -1 u = -w - A = w * non_square * r^2 +// +// Let r1 = non_square * r^2 +// Let r2 = 1 + r1 +// Note that r2 cannot be zero, -1/non_square is not a square. +// We can (tediously) verify that: +// w^3 + A*w^2 + w = (A^2*r1 - r2^2) * A / r2^3 +// Therefore: +// chi(w^3 + A*w^2 + w) = chi((A^2*r1 - r2^2) * (A / r2^3)) +// chi(w^3 + A*w^2 + w) = chi((A^2*r1 - r2^2) * (A / r2^3)) * 1 +// chi(w^3 + A*w^2 + w) = chi((A^2*r1 - r2^2) * (A / r2^3)) * chi(r2^6) +// chi(w^3 + A*w^2 + w) = chi((A^2*r1 - r2^2) * (A / r2^3) * r2^6) +// chi(w^3 + A*w^2 + w) = chi((A^2*r1 - r2^2) * A * r2^3) +// Corollary: +// e = 1 if (A^2*r1 - r2^2) * A * r2^3) is a non-zero square +// e = -1 if (A^2*r1 - r2^2) * A * r2^3) is not a square +// Note that w^3 + A*w^2 + w (and therefore e) can never be zero: +// w^3 + A*w^2 + w = w * (w^2 + A*w + 1) +// w^3 + A*w^2 + w = w * (w^2 + A*w + A^2/4 - A^2/4 + 1) +// w^3 + A*w^2 + w = w * (w + A/2)^2 - A^2/4 + 1) +// which is zero only if: +// w = 0 (impossible) +// (w + A/2)^2 = A^2/4 - 1 (impossible, because A^2/4-1 is not a square) +// +// Let isr = invsqrt((A^2*r1 - r2^2) * A * r2^3) +// isr = sqrt(1 / ((A^2*r1 - r2^2) * A * r2^3)) if e = 1 +// isr = sqrt(sqrt(-1) / ((A^2*r1 - r2^2) * A * r2^3)) if e = -1 +// +// if e = 1 +// let u1 = -A * (A^2*r1 - r2^2) * A * r2^2 * isr^2 +// u1 = w +// u1 = u +// +// if e = -1 +// let ufactor = -non_square * sqrt(-1) * r^2 +// let vfactor = sqrt(ufactor) +// let u2 = -A * (A^2*r1 - r2^2) * A * r2^2 * isr^2 * ufactor +// u2 = w * -1 * -non_square * r^2 +// u2 = w * non_square * r^2 +// u2 = u +void crypto_hidden_to_curve(uint8_t curve[32], const uint8_t hidden[32]) +{ + // Representatives are encoded in 254 bits. + // The two most significant ones are random padding that must be ignored. + u8 clamped[32]; + COPY(clamped, hidden, 32); + clamped[31] &= 0x3f; + + fe r, u, t1, t2, t3; + fe_frombytes(r, clamped); + fe_sq2(t1, r); + fe_add(u, t1, fe_one); + fe_sq (t2, u); + fe_mul(t3, A2, t1); + fe_sub(t3, t3, t2); + fe_mul(t3, t3, A); + fe_mul(t1, t2, u); + fe_mul(t1, t3, t1); + int is_square = invsqrt(t1, t1); + fe_sq(u, r); + fe_mul(u, u, ufactor); + fe_ccopy(u, fe_one, is_square); + fe_sq (t1, t1); + fe_mul(u, u, A); + fe_mul(u, u, t3); + fe_mul(u, u, t2); + fe_mul(u, u, t1); + fe_neg(u, u); + fe_tobytes(curve, u); + + WIPE_BUFFER(t1); WIPE_BUFFER(r); + WIPE_BUFFER(t2); WIPE_BUFFER(u); + WIPE_BUFFER(t3); WIPE_BUFFER(clamped); +} + +// Elligator inverse map +// +// Computes the representative of a point, if possible. If not, it does +// nothing and returns -1. Note that the success of the operation +// depends only on the point (more precisely its u coordinate). The +// tweak parameter is used only upon success +// +// The tweak should be a random byte. Beyond that, its contents are an +// implementation detail. Currently, the tweak comprises: +// - Bit 1 : sign of the v coordinate (0 if positive, 1 if negative) +// - Bit 2-5: not used +// - Bits 6-7: random padding +// +// From the paper: +// Let sq = -non_square * u * (u+A) +// if sq is not a square, or u = -A, there is no mapping +// Assuming there is a mapping: +// if v is positive: r = sqrt(-(u+A) / u) +// if v is negative: r = sqrt(-u / (u+A)) +// +// We compute isr = invsqrt(-non_square * u * (u+A)) +// if it wasn't a non-zero square, abort. +// else, isr = sqrt(-1 / (non_square * u * (u+A)) +// +// This causes us to abort if u is zero, even though we shouldn't. This +// never happens in practice, because (i) a random point in the curve has +// a negligible chance of being zero, and (ii) scalar multiplication with +// a trimmed scalar *never* yields zero. +// +// Since: +// isr * (u+A) = sqrt(-1 / (non_square * u * (u+A)) * (u+A) +// isr * (u+A) = sqrt(-(u+A) / (non_square * u * (u+A)) +// and: +// isr = u = sqrt(-1 / (non_square * u * (u+A)) * u +// isr = u = sqrt(-u / (non_square * u * (u+A)) +// Therefore: +// if v is positive: r = isr * (u+A) +// if v is negative: r = isr * u +int crypto_curve_to_hidden(u8 hidden[32], const u8 public_key[32], u8 tweak) +{ + fe t1, t2, t3; + fe_frombytes(t1, public_key); + + fe_add(t2, t1, A); + fe_mul(t3, t1, t2); + fe_mul_small(t3, t3, -2); + int is_square = invsqrt(t3, t3); + if (!is_square) { + // The only variable time bit. This ultimately reveals how many + // tries it took us to find a representable key. + // This does not affect security as long as we try keys at random. + WIPE_BUFFER(t1); + WIPE_BUFFER(t2); + WIPE_BUFFER(t3); + return -1; + } + fe_ccopy (t1, t2, tweak & 1); + fe_mul (t3, t1, t3); + fe_mul_small(t1, t3, 2); + fe_neg (t2, t3); + fe_ccopy (t3, t2, fe_isodd(t1)); + fe_tobytes(hidden, t3); + + // Pad with two random bits + hidden[31] |= tweak & 0xc0; + + WIPE_BUFFER(t1); + WIPE_BUFFER(t2); + WIPE_BUFFER(t3); + return 0; +} + +void crypto_hidden_key_pair(u8 hidden[32], u8 secret_key[32], u8 seed[32]) +{ + u8 pk [32]; // public key + u8 buf[64]; // seed + representative + COPY(buf + 32, seed, 32); + do { + crypto_chacha20(buf, 0, 64, buf+32, zero); + crypto_x25519_dirty_fast(pk, buf); // or the "small" version + } while(crypto_curve_to_hidden(buf+32, pk, buf[32])); + // Note that the return value of crypto_curve_to_hidden() is + // independent from its tweak parameter. + // Therefore, buf[32] is not actually reused. Either we loop one + // more time and buf[32] is used for the new seed, or we succeeded, + // and buf[32] becomes the tweak parameter. + + crypto_wipe(seed, 32); + COPY(hidden , buf + 32, 32); + COPY(secret_key, buf , 32); + WIPE_BUFFER(buf); + WIPE_BUFFER(pk); +} + +//////////////////// +/// Key exchange /// +//////////////////// +void crypto_key_exchange(u8 shared_key[32], + const u8 your_secret_key [32], + const u8 their_public_key[32]) +{ + crypto_x25519(shared_key, your_secret_key, their_public_key); + crypto_hchacha20(shared_key, shared_key, zero); +} + +/////////////////////// +/// Scalar division /// +/////////////////////// + +// Montgomery reduction. +// Divides x by (2^256), and reduces the result modulo L +// +// Precondition: +// x < L * 2^256 +// Constants: +// r = 2^256 (makes division by r trivial) +// k = (r * (1/r) - 1) // L (1/r is computed modulo L ) +// Algorithm: +// s = (x * k) % r +// t = x + s*L (t is always a multiple of r) +// u = (t/r) % L (u is always below 2*L, conditional subtraction is enough) +static void redc(u32 u[8], u32 x[16]) +{ + static const u32 k[8] = { 0x12547e1b, 0xd2b51da3, 0xfdba84ff, 0xb1a206f2, + 0xffa36bea, 0x14e75438, 0x6fe91836, 0x9db6c6f2,}; + static const u32 l[8] = { 0x5cf5d3ed, 0x5812631a, 0xa2f79cd6, 0x14def9de, + 0x00000000, 0x00000000, 0x00000000, 0x10000000,}; + // s = x * k (modulo 2^256) + // This is cheaper than the full multiplication. + u32 s[8] = {0}; + FOR (i, 0, 8) { + u64 carry = 0; + FOR (j, 0, 8-i) { + carry += s[i+j] + (u64)x[i] * k[j]; + s[i+j] = (u32)carry; + carry >>= 32; + } + } + u32 t[16] = {0}; + multiply(t, s, l); + + // t = t + x + u64 carry = 0; + FOR (i, 0, 16) { + carry += (u64)t[i] + x[i]; + t[i] = (u32)carry; + carry >>= 32; + } + + // u = (t / 2^256) % L + // Note that t / 2^256 is always below 2*L, + // So a constant time conditional subtraction is enough + // We work with L directly, in a 2's complement encoding + // (-L == ~L + 1) + remove_l(u, t+8); + + WIPE_BUFFER(s); + WIPE_BUFFER(t); +} + +void crypto_x25519_inverse(u8 blind_salt [32], const u8 private_key[32], + const u8 curve_point[32]) +{ + static const u8 Lm2[32] = { // L - 2 + 0xeb, 0xd3, 0xf5, 0x5c, 0x1a, 0x63, 0x12, 0x58, 0xd6, 0x9c, 0xf7, 0xa2, + 0xde, 0xf9, 0xde, 0x14, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x10, }; + // 1 in Montgomery form + u32 m_inv [8] = {0x8d98951d, 0xd6ec3174, 0x737dcf70, 0xc6ef5bf4, + 0xfffffffe, 0xffffffff, 0xffffffff, 0x0fffffff,}; + + u8 scalar[32]; + COPY(scalar, private_key, 32); + trim_scalar(scalar); + + // Convert the scalar in Montgomery form + // m_scl = scalar * 2^256 (modulo L) + u32 m_scl[8]; + { + u32 tmp[16]; + ZERO(tmp, 8); + load32_le_buf(tmp+8, scalar, 8); + mod_l(scalar, tmp); + load32_le_buf(m_scl, scalar, 8); + WIPE_BUFFER(tmp); // Wipe ASAP to save stack space + } + + u32 product[16]; + for (int i = 252; i >= 0; i--) { + ZERO(product, 16); + multiply(product, m_inv, m_inv); + redc(m_inv, product); + if (scalar_bit(Lm2, i)) { + ZERO(product, 16); + multiply(product, m_inv, m_scl); + redc(m_inv, product); + } + } + // Convert the inverse *out* of Montgomery form + // scalar = m_inv / 2^256 (modulo L) + COPY(product, m_inv, 8); + ZERO(product + 8, 8); + redc(m_inv, product); + store32_le_buf(scalar, m_inv, 8); // the *inverse* of the scalar + + // Clear the cofactor of scalar: + // cleared = scalar * (3*L + 1) (modulo 8*L) + // cleared = scalar + scalar * 3 * L (modulo 8*L) + // Note that (scalar * 3) is reduced modulo 8, so we only need the + // first byte. + add_xl(scalar, scalar[0] * 3); + + // Recall that 8*L < 2^256. However it is also very close to + // 2^255. If we spanned the ladder over 255 bits, random tests + // wouldn't catch the off-by-one error. + scalarmult(blind_salt, scalar, curve_point, 256); + + WIPE_BUFFER(scalar); WIPE_BUFFER(m_scl); + WIPE_BUFFER(product); WIPE_BUFFER(m_inv); +} + +//////////////////////////////// +/// Authenticated encryption /// +//////////////////////////////// +static void lock_auth(u8 mac[16], const u8 auth_key[32], + const u8 *ad , size_t ad_size, + const u8 *cipher_text, size_t text_size) +{ + u8 sizes[16]; // Not secret, not wiped + store64_le(sizes + 0, ad_size); + store64_le(sizes + 8, text_size); + crypto_poly1305_ctx poly_ctx; // auto wiped... + crypto_poly1305_init (&poly_ctx, auth_key); + crypto_poly1305_update(&poly_ctx, ad , ad_size); + crypto_poly1305_update(&poly_ctx, zero , align(ad_size, 16)); + crypto_poly1305_update(&poly_ctx, cipher_text, text_size); + crypto_poly1305_update(&poly_ctx, zero , align(text_size, 16)); + crypto_poly1305_update(&poly_ctx, sizes , 16); + crypto_poly1305_final (&poly_ctx, mac); // ...here +} + +void crypto_lock_aead(u8 mac[16], u8 *cipher_text, + const u8 key[32], const u8 nonce[24], + const u8 *ad , size_t ad_size, + const u8 *plain_text, size_t text_size) +{ + u8 sub_key[32]; + u8 auth_key[64]; // "Wasting" the whole Chacha block is faster + crypto_hchacha20(sub_key, key, nonce); + crypto_chacha20(auth_key, 0, 64, sub_key, nonce + 16); + crypto_chacha20_ctr(cipher_text, plain_text, text_size, + sub_key, nonce + 16, 1); + lock_auth(mac, auth_key, ad, ad_size, cipher_text, text_size); + WIPE_BUFFER(sub_key); + WIPE_BUFFER(auth_key); +} + +int crypto_unlock_aead(u8 *plain_text, const u8 key[32], const u8 nonce[24], + const u8 mac[16], + const u8 *ad , size_t ad_size, + const u8 *cipher_text, size_t text_size) +{ + u8 sub_key[32]; + u8 auth_key[64]; // "Wasting" the whole Chacha block is faster + crypto_hchacha20(sub_key, key, nonce); + crypto_chacha20(auth_key, 0, 64, sub_key, nonce + 16); + u8 real_mac[16]; + lock_auth(real_mac, auth_key, ad, ad_size, cipher_text, text_size); + WIPE_BUFFER(auth_key); + if (crypto_verify16(mac, real_mac)) { + WIPE_BUFFER(sub_key); + WIPE_BUFFER(real_mac); + return -1; + } + crypto_chacha20_ctr(plain_text, cipher_text, text_size, + sub_key, nonce + 16, 1); + WIPE_BUFFER(sub_key); + WIPE_BUFFER(real_mac); + return 0; +} + +void crypto_lock(u8 mac[16], u8 *cipher_text, + const u8 key[32], const u8 nonce[24], + const u8 *plain_text, size_t text_size) +{ + crypto_lock_aead(mac, cipher_text, key, nonce, 0, 0, plain_text, text_size); +} + +int crypto_unlock(u8 *plain_text, + const u8 key[32], const u8 nonce[24], const u8 mac[16], + const u8 *cipher_text, size_t text_size) +{ + return crypto_unlock_aead(plain_text, key, nonce, mac, 0, 0, + cipher_text, text_size); +} diff --git a/libraries/AP_CheckFirmware/monocypher.h b/libraries/AP_CheckFirmware/monocypher.h new file mode 100644 index 00000000000..304aabb176a --- /dev/null +++ b/libraries/AP_CheckFirmware/monocypher.h @@ -0,0 +1,374 @@ +// Monocypher version 3.1.2 +// +// This file is dual-licensed. Choose whichever licence you want from +// the two licences listed below. +// +// The first licence is a regular 2-clause BSD licence. The second licence +// is the CC-0 from Creative Commons. It is intended to release Monocypher +// to the public domain. The BSD licence serves as a fallback option. +// +// SPDX-License-Identifier: BSD-2-Clause OR CC0-1.0 +// +// ------------------------------------------------------------------------ +// +// Copyright (c) 2017-2019, Loup Vaillant +// All rights reserved. +// +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// 1. Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// +// 2. Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the +// distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR +// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT +// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, +// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY +// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ------------------------------------------------------------------------ +// +// Written in 2017-2019 by Loup Vaillant +// +// To the extent possible under law, the author(s) have dedicated all copyright +// and related neighboring rights to this software to the public domain +// worldwide. This software is distributed without any warranty. +// +// You should have received a copy of the CC0 Public Domain Dedication along +// with this software. If not, see +// + +#ifndef MONOCYPHER_H +#define MONOCYPHER_H + +#include +#include + +//////////////////////// +/// Type definitions /// +//////////////////////// + +// Vtable for EdDSA with a custom hash. +// Instantiate it to define a custom hash. +// Its size, contents, and layout, are part of the public API. +typedef struct { + void (*hash)(uint8_t hash[64], const uint8_t *message, size_t message_size); + void (*init )(void *ctx); + void (*update)(void *ctx, const uint8_t *message, size_t message_size); + void (*final )(void *ctx, uint8_t hash[64]); + size_t ctx_size; +} crypto_sign_vtable; + +// Do not rely on the size or contents of any of the types below, +// they may change without notice. + +// Poly1305 +typedef struct { + uint32_t r[4]; // constant multiplier (from the secret key) + uint32_t h[5]; // accumulated hash + uint32_t c[5]; // chunk of the message + uint32_t pad[4]; // random number added at the end (from the secret key) + size_t c_idx; // How many bytes are there in the chunk. +} crypto_poly1305_ctx; + +// Hash (Blake2b) +typedef struct { + uint64_t hash[8]; + uint64_t input_offset[2]; + uint64_t input[16]; + size_t input_idx; + size_t hash_size; +} crypto_blake2b_ctx; + +// Signatures (EdDSA) +typedef struct { + const crypto_sign_vtable *hash; + uint8_t buf[96]; + uint8_t pk [32]; +} crypto_sign_ctx_abstract; +typedef crypto_sign_ctx_abstract crypto_check_ctx_abstract; + +typedef struct { + crypto_sign_ctx_abstract ctx; + crypto_blake2b_ctx hash; +} crypto_sign_ctx; +typedef crypto_sign_ctx crypto_check_ctx; + +//////////////////////////// +/// High level interface /// +//////////////////////////// + +// Constant time comparisons +// ------------------------- + +// Return 0 if a and b are equal, -1 otherwise +int crypto_verify16(const uint8_t a[16], const uint8_t b[16]); +int crypto_verify32(const uint8_t a[32], const uint8_t b[32]); +int crypto_verify64(const uint8_t a[64], const uint8_t b[64]); + +// Erase sensitive data +// -------------------- + +// Please erase all copies +void crypto_wipe(void *secret, size_t size); + + +// Authenticated encryption +// ------------------------ +void crypto_lock(uint8_t mac[16], + uint8_t *cipher_text, + const uint8_t key[32], + const uint8_t nonce[24], + const uint8_t *plain_text, size_t text_size); +int crypto_unlock(uint8_t *plain_text, + const uint8_t key[32], + const uint8_t nonce[24], + const uint8_t mac[16], + const uint8_t *cipher_text, size_t text_size); + +// With additional data +void crypto_lock_aead(uint8_t mac[16], + uint8_t *cipher_text, + const uint8_t key[32], + const uint8_t nonce[24], + const uint8_t *ad , size_t ad_size, + const uint8_t *plain_text, size_t text_size); +int crypto_unlock_aead(uint8_t *plain_text, + const uint8_t key[32], + const uint8_t nonce[24], + const uint8_t mac[16], + const uint8_t *ad , size_t ad_size, + const uint8_t *cipher_text, size_t text_size); + + +// General purpose hash (Blake2b) +// ------------------------------ + +// Direct interface +void crypto_blake2b(uint8_t hash[64], + const uint8_t *message, size_t message_size); + +void crypto_blake2b_general(uint8_t *hash , size_t hash_size, + const uint8_t *key , size_t key_size, // optional + const uint8_t *message, size_t message_size); + +// Incremental interface +void crypto_blake2b_init (crypto_blake2b_ctx *ctx); +void crypto_blake2b_update(crypto_blake2b_ctx *ctx, + const uint8_t *message, size_t message_size); +void crypto_blake2b_final (crypto_blake2b_ctx *ctx, uint8_t *hash); + +void crypto_blake2b_general_init(crypto_blake2b_ctx *ctx, size_t hash_size, + const uint8_t *key, size_t key_size); + +// vtable for signatures +extern const crypto_sign_vtable crypto_blake2b_vtable; + + +// Password key derivation (Argon2 i) +// ---------------------------------- +void crypto_argon2i(uint8_t *hash, uint32_t hash_size, // >= 4 + void *work_area, uint32_t nb_blocks, // >= 8 + uint32_t nb_iterations, // >= 3 + const uint8_t *password, uint32_t password_size, + const uint8_t *salt, uint32_t salt_size); // >= 8 + +void crypto_argon2i_general(uint8_t *hash, uint32_t hash_size,// >= 4 + void *work_area, uint32_t nb_blocks,// >= 8 + uint32_t nb_iterations, // >= 3 + const uint8_t *password, uint32_t password_size, + const uint8_t *salt, uint32_t salt_size,// >= 8 + const uint8_t *key, uint32_t key_size, + const uint8_t *ad, uint32_t ad_size); + + +// Key exchange (x25519 + HChacha20) +// --------------------------------- +#define crypto_key_exchange_public_key crypto_x25519_public_key +void crypto_key_exchange(uint8_t shared_key [32], + const uint8_t your_secret_key [32], + const uint8_t their_public_key[32]); + + +// Signatures (EdDSA with curve25519 + Blake2b) +// -------------------------------------------- + +// Generate public key +void crypto_sign_public_key(uint8_t public_key[32], + const uint8_t secret_key[32]); + +// Direct interface +void crypto_sign(uint8_t signature [64], + const uint8_t secret_key[32], + const uint8_t public_key[32], // optional, may be 0 + const uint8_t *message, size_t message_size); +int crypto_check(const uint8_t signature [64], + const uint8_t public_key[32], + const uint8_t *message, size_t message_size); + +//////////////////////////// +/// Low level primitives /// +//////////////////////////// + +// For experts only. You have been warned. + +// Chacha20 +// -------- + +// Specialised hash. +// Used to hash X25519 shared secrets. +void crypto_hchacha20(uint8_t out[32], + const uint8_t key[32], + const uint8_t in [16]); + +// Unauthenticated stream cipher. +// Don't forget to add authentication. +void crypto_chacha20(uint8_t *cipher_text, + const uint8_t *plain_text, + size_t text_size, + const uint8_t key[32], + const uint8_t nonce[8]); +void crypto_xchacha20(uint8_t *cipher_text, + const uint8_t *plain_text, + size_t text_size, + const uint8_t key[32], + const uint8_t nonce[24]); +void crypto_ietf_chacha20(uint8_t *cipher_text, + const uint8_t *plain_text, + size_t text_size, + const uint8_t key[32], + const uint8_t nonce[12]); +uint64_t crypto_chacha20_ctr(uint8_t *cipher_text, + const uint8_t *plain_text, + size_t text_size, + const uint8_t key[32], + const uint8_t nonce[8], + uint64_t ctr); +uint64_t crypto_xchacha20_ctr(uint8_t *cipher_text, + const uint8_t *plain_text, + size_t text_size, + const uint8_t key[32], + const uint8_t nonce[24], + uint64_t ctr); +uint32_t crypto_ietf_chacha20_ctr(uint8_t *cipher_text, + const uint8_t *plain_text, + size_t text_size, + const uint8_t key[32], + const uint8_t nonce[12], + uint32_t ctr); + +// Poly 1305 +// --------- + +// This is a *one time* authenticator. +// Disclosing the mac reveals the key. +// See crypto_lock() on how to use it properly. + +// Direct interface +void crypto_poly1305(uint8_t mac[16], + const uint8_t *message, size_t message_size, + const uint8_t key[32]); + +// Incremental interface +void crypto_poly1305_init (crypto_poly1305_ctx *ctx, const uint8_t key[32]); +void crypto_poly1305_update(crypto_poly1305_ctx *ctx, + const uint8_t *message, size_t message_size); +void crypto_poly1305_final (crypto_poly1305_ctx *ctx, uint8_t mac[16]); + + +// X-25519 +// ------- + +// Shared secrets are not quite random. +// Hash them to derive an actual shared key. +void crypto_x25519_public_key(uint8_t public_key[32], + const uint8_t secret_key[32]); +void crypto_x25519(uint8_t raw_shared_secret[32], + const uint8_t your_secret_key [32], + const uint8_t their_public_key [32]); + +// "Dirty" versions of x25519_public_key() +// Only use to generate ephemeral keys you want to hide. +// Note that those functions leaks 3 bits of the private key. +void crypto_x25519_dirty_small(uint8_t pk[32], const uint8_t sk[32]); +void crypto_x25519_dirty_fast (uint8_t pk[32], const uint8_t sk[32]); + +// scalar "division" +// Used for OPRF. Be aware that exponential blinding is less secure +// than Diffie-Hellman key exchange. +void crypto_x25519_inverse(uint8_t blind_salt [32], + const uint8_t private_key[32], + const uint8_t curve_point[32]); + + +// EdDSA to X25519 +// --------------- +void crypto_from_eddsa_private(uint8_t x25519[32], const uint8_t eddsa[32]); +void crypto_from_eddsa_public (uint8_t x25519[32], const uint8_t eddsa[32]); + + +// EdDSA -- Incremental interface +// ------------------------------ + +// Signing (2 passes) +// Make sure the two passes hash the same message, +// else you might reveal the private key. +void crypto_sign_init_first_pass(crypto_sign_ctx_abstract *ctx, + const uint8_t secret_key[32], + const uint8_t public_key[32]); +void crypto_sign_update(crypto_sign_ctx_abstract *ctx, + const uint8_t *message, size_t message_size); +void crypto_sign_init_second_pass(crypto_sign_ctx_abstract *ctx); +// use crypto_sign_update() again. +void crypto_sign_final(crypto_sign_ctx_abstract *ctx, uint8_t signature[64]); + +// Verification (1 pass) +// Make sure you don't use (parts of) the message +// before you're done checking it. +void crypto_check_init (crypto_check_ctx_abstract *ctx, + const uint8_t signature[64], + const uint8_t public_key[32]); +void crypto_check_update(crypto_check_ctx_abstract *ctx, + const uint8_t *message, size_t message_size); +int crypto_check_final (crypto_check_ctx_abstract *ctx); + +// Custom hash interface +void crypto_sign_public_key_custom_hash(uint8_t public_key[32], + const uint8_t secret_key[32], + const crypto_sign_vtable *hash); +void crypto_sign_init_first_pass_custom_hash(crypto_sign_ctx_abstract *ctx, + const uint8_t secret_key[32], + const uint8_t public_key[32], + const crypto_sign_vtable *hash); +void crypto_check_init_custom_hash(crypto_check_ctx_abstract *ctx, + const uint8_t signature[64], + const uint8_t public_key[32], + const crypto_sign_vtable *hash); + +// Elligator 2 +// ----------- + +// Elligator mappings proper +void crypto_hidden_to_curve(uint8_t curve [32], const uint8_t hidden[32]); +int crypto_curve_to_hidden(uint8_t hidden[32], const uint8_t curve [32], + uint8_t tweak); + +// Easy to use key pair generation +void crypto_hidden_key_pair(uint8_t hidden[32], uint8_t secret_key[32], + uint8_t seed[32]); + + +#endif // MONOCYPHER_H diff --git a/libraries/AP_Common/AP_Common.h b/libraries/AP_Common/AP_Common.h index aad3adc3036..f9632eec01a 100644 --- a/libraries/AP_Common/AP_Common.h +++ b/libraries/AP_Common/AP_Common.h @@ -33,6 +33,13 @@ // used to mark a function that may be unused in some builds #define UNUSED_FUNCTION __attribute__((unused)) +// used to mark an attribute that may be unused in some builds +#ifdef __clang__ +#define UNUSED_PRIVATE_MEMBER __attribute__((unused)) +#else +#define UNUSED_PRIVATE_MEMBER +#endif + // this can be used to optimize individual functions #define OPTIMIZE(level) __attribute__((optimize(level))) @@ -81,6 +88,7 @@ bool. Bitnumber starts at 0 for the first bit */ #define BIT_IS_SET(value, bitnumber) (((value) & (1U<<(bitnumber))) != 0) +#define BIT_IS_SET_64(value, bitnumber) (((value) & (uint64_t(1U)<<(bitnumber))) != 0) // get high or low bytes from 2 byte integer #define LOWBYTE(i) ((uint8_t)(i)) diff --git a/libraries/AP_Common/AP_ExpandingArray.h b/libraries/AP_Common/AP_ExpandingArray.h index 0c3c9c97143..22fa837b928 100644 --- a/libraries/AP_Common/AP_ExpandingArray.h +++ b/libraries/AP_Common/AP_ExpandingArray.h @@ -83,12 +83,12 @@ class AP_ExpandingArray : public AP_ExpandingArrayGeneric { public: - AP_ExpandingArray(uint16_t elements_per_chunk) : + AP_ExpandingArray(uint16_t elements_per_chunk) : AP_ExpandingArrayGeneric(sizeof(T), elements_per_chunk) {} /* Do not allow copies */ - AP_ExpandingArray(const AP_ExpandingArray &other) = delete; + AP_ExpandingArray(const AP_ExpandingArray &other) = delete; AP_ExpandingArray &operator=(const AP_ExpandingArray&) = delete; // allow use as an array for assigning to elements. no bounds checking is performed diff --git a/libraries/AP_Common/AP_FWVersion.h b/libraries/AP_Common/AP_FWVersion.h index 5c1fabb8e9c..95a7eb50d11 100644 --- a/libraries/AP_Common/AP_FWVersion.h +++ b/libraries/AP_Common/AP_FWVersion.h @@ -1,7 +1,8 @@ #pragma once #include -#include +#include +#include class PACKED AP_FWVersion { diff --git a/libraries/AP_Common/Bitmask.h b/libraries/AP_Common/Bitmask.h index df40cc879d6..233d1b3e26f 100644 --- a/libraries/AP_Common/Bitmask.h +++ b/libraries/AP_Common/Bitmask.h @@ -37,6 +37,18 @@ class Bitmask { return *this; } + bool operator==(const Bitmask&other) { + if (other.numbits != numbits) { + return false; + } else { + return memcmp(bits, other.bits, sizeof(bits[0])*numwords) == 0; + } + } + + bool operator!=(const Bitmask&other) { + return !(*this == other); + } + Bitmask(const Bitmask &other) = delete; // set given bitnumber @@ -69,6 +81,15 @@ class Bitmask { bits[word] &= ~(1U << ofs); } + // set given bitnumber to on/off + void setonoff(uint16_t bit, bool onoff) { + if (onoff) { + set(bit); + } else { + clear(bit); + } + } + // clear all bits void clearall(void) { memset(bits, 0, numwords*sizeof(bits[0])); diff --git a/libraries/AP_Common/ExpandingString.cpp b/libraries/AP_Common/ExpandingString.cpp index 84101c3f0fc..31420d95fe0 100644 --- a/libraries/AP_Common/ExpandingString.cpp +++ b/libraries/AP_Common/ExpandingString.cpp @@ -18,6 +18,8 @@ #include "ExpandingString.h" +#include + extern const AP_HAL::HAL& hal; #define EXPAND_INCREMENT 512 diff --git a/libraries/AP_Common/ExpandingString.h b/libraries/AP_Common/ExpandingString.h index abc6de2ea78..2561332f3e8 100644 --- a/libraries/AP_Common/ExpandingString.h +++ b/libraries/AP_Common/ExpandingString.h @@ -18,7 +18,9 @@ #pragma once -#include +#include + +#include class ExpandingString { public: diff --git a/libraries/AP_Common/Location.cpp b/libraries/AP_Common/Location.cpp index 92a86ebc235..bc537dab994 100644 --- a/libraries/AP_Common/Location.cpp +++ b/libraries/AP_Common/Location.cpp @@ -140,7 +140,7 @@ bool Location::get_alt_cm(AltFrame desired_frame, int32_t &ret_alt_cm) const if (terrain == nullptr) { return false; } - if (!terrain->height_amsl(*this, alt_terr_cm, true)) { + if (!terrain->height_amsl(*this, alt_terr_cm)) { return false; } // convert terrain alt to cm @@ -236,7 +236,7 @@ bool Location::get_vector_from_origin_NEU(Vector3f &vec_neu) const return true; } -// return distance in meters between two locations +// return horizontal distance in meters between two locations ftype Location::get_distance(const struct Location &loc2) const { ftype dlat = (ftype)(loc2.lat - lat); @@ -355,9 +355,11 @@ bool Location::sanitize(const Location &defaultLoc) // convert relative alt=0 to mean current alt if (alt == 0 && relative_alt) { - relative_alt = false; - alt = defaultLoc.alt; - has_changed = true; + int32_t defaultLoc_alt; + if (defaultLoc.get_alt_cm(get_alt_frame(), defaultLoc_alt)) { + alt = defaultLoc_alt; + has_changed = true; + } } // limit lat/lng to appropriate ranges @@ -374,14 +376,14 @@ bool Location::sanitize(const Location &defaultLoc) assert_storage_size _assert_storage_size_Location; -// return bearing in centi-degrees from location to loc2 -int32_t Location::get_bearing_to(const struct Location &loc2) const +// return bearing in radians from location to loc2, return is 0 to 2*Pi +ftype Location::get_bearing(const struct Location &loc2) const { const int32_t off_x = diff_longitude(loc2.lng,lng); const int32_t off_y = (loc2.lat - lat) / loc2.longitude_scale((lat+loc2.lat)/2); - int32_t bearing = 9000 + atan2F(-off_y, off_x) * DEGX100; + ftype bearing = (M_PI*0.5) + atan2F(-off_y, off_x); if (bearing < 0) { - bearing += 36000; + bearing += 2*M_PI; } return bearing; } diff --git a/libraries/AP_Common/Location.h b/libraries/AP_Common/Location.h index d9b2565b98d..f3eb1b9a3cc 100644 --- a/libraries/AP_Common/Location.h +++ b/libraries/AP_Common/Location.h @@ -37,16 +37,20 @@ class Location void set_alt_cm(int32_t alt_cm, AltFrame frame); // get altitude (in cm) in the desired frame - // returns false on failure to get altitude in the desired frame which - // can only happen if the original frame or desired frame is above-terrain + // returns false on failure to get altitude in the desired frame which can only happen if the original frame or desired frame is: + // - above-terrain and the terrain database can't supply terrain height amsl + // - above-home and home is not set + // - above-origin and origin is not set bool get_alt_cm(AltFrame desired_frame, int32_t &ret_alt_cm) const WARN_IF_UNUSED; // get altitude frame AltFrame get_alt_frame() const; // converts altitude to new frame - // returns false on failure to convert which can only happen if - // the original frame or desired frame is above-terrain + // returns false on failure to convert which can only happen if the original frame or desired frame is: + // - above-terrain and the terrain database can't supply terrain height amsl + // - above-home and home is not set + // - above-origin and origin is not set bool change_alt_frame(AltFrame desired_frame); // get position as a vector (in cm) from origin (x,y only or x,y,z) @@ -56,7 +60,7 @@ class Location bool get_vector_xy_from_origin_NE(Vector2f &vec_ne) const WARN_IF_UNUSED; bool get_vector_from_origin_NEU(Vector3f &vec_neu) const WARN_IF_UNUSED; - // return distance in meters between two locations + // return horizontal distance in meters between two locations ftype get_distance(const struct Location &loc2) const; // return the altitude difference in meters taking into account alt frame. @@ -92,10 +96,13 @@ class Location void zero(void); - // return bearing in centi-degrees from location to loc2 - int32_t get_bearing_to(const struct Location &loc2) const; - // return the bearing in radians - ftype get_bearing(const struct Location &loc2) const { return radians(get_bearing_to(loc2) * 0.01); } ; + // return the bearing in radians, from 0 to 2*Pi + ftype get_bearing(const struct Location &loc2) const; + + // return bearing in centi-degrees from location to loc2, return is 0 to 35999 + int32_t get_bearing_to(const struct Location &loc2) const { + return int32_t(get_bearing(loc2) * DEGX100 + 0.5); + } // check if lat and lng match. Ignore altitude and options bool same_latlon_as(const Location &loc2) const; diff --git a/libraries/AP_Common/TSIndex.h b/libraries/AP_Common/TSIndex.h index 41821e6d787..6dd88a92164 100644 --- a/libraries/AP_Common/TSIndex.h +++ b/libraries/AP_Common/TSIndex.h @@ -98,7 +98,7 @@ template class typesafe_index base_type p; }; -/// This template associates the the base_type array with accessor_type(index). +/// This template associates the base_type array with accessor_type(index). /// So the elements can be accessed using [] only using accessor_type index /// _priv_instance is kept public for use in Parameter declaration. /// diff --git a/libraries/AP_Common/tests/test_cpp.cpp b/libraries/AP_Common/tests/test_cpp.cpp index d6946ae0aa4..9ffe282bbd4 100644 --- a/libraries/AP_Common/tests/test_cpp.cpp +++ b/libraries/AP_Common/tests/test_cpp.cpp @@ -10,17 +10,17 @@ class DummyDummy { TEST(AP_Common, TEST_CPP) { - DummyDummy * test_new = new DummyDummy[0]; + DummyDummy * test_new = new DummyDummy[1]; EXPECT_FALSE(test_new == nullptr); EXPECT_TRUE(sizeof(test_new) == 8); - EXPECT_EQ(test_new->count, 0); - EXPECT_FLOAT_EQ(test_new->d, 0); + EXPECT_FLOAT_EQ(test_new->count, 1); + EXPECT_FLOAT_EQ(test_new->d, 42.0); - DummyDummy * test_d = (DummyDummy*) ::operator new (0); + DummyDummy * test_d = (DummyDummy*) ::operator new (sizeof(DummyDummy)); EXPECT_FALSE(test_d == nullptr); EXPECT_TRUE(sizeof(test_d) == 8); - EXPECT_EQ(test_d->count, 0); - EXPECT_FLOAT_EQ(test_d->d, 0); + EXPECT_EQ(test_d->count, 0); // constructor isn't called + EXPECT_FLOAT_EQ(test_d->d, 0.0); DummyDummy * test_d2 = new DummyDummy; EXPECT_TRUE(sizeof(test_d2) == 8); @@ -32,4 +32,4 @@ TEST(AP_Common, TEST_CPP) delete test_d2; } -AP_GTEST_MAIN() \ No newline at end of file +AP_GTEST_MAIN() diff --git a/libraries/AP_Common/tests/test_expandingstring.cpp b/libraries/AP_Common/tests/test_expandingstring.cpp index be4c3ee41f0..99cd16e4e6c 100644 --- a/libraries/AP_Common/tests/test_expandingstring.cpp +++ b/libraries/AP_Common/tests/test_expandingstring.cpp @@ -1,5 +1,6 @@ #include #include +#include const AP_HAL::HAL& hal = AP_HAL::get_HAL(); diff --git a/libraries/AP_Common/tests/test_expandingstring_failure.cpp b/libraries/AP_Common/tests/test_expandingstring_failure.cpp index 930207aaab7..f95d3d9210f 100644 --- a/libraries/AP_Common/tests/test_expandingstring_failure.cpp +++ b/libraries/AP_Common/tests/test_expandingstring_failure.cpp @@ -1,6 +1,7 @@ #include #include #include +#include /** * This file test realloc failure on ExpandingString diff --git a/libraries/AP_Common/tests/test_location.cpp b/libraries/AP_Common/tests/test_location.cpp index fddbe3804e3..fa29927a567 100644 --- a/libraries/AP_Common/tests/test_location.cpp +++ b/libraries/AP_Common/tests/test_location.cpp @@ -311,30 +311,37 @@ TEST(Location, Distance) bearing = test_home.get_bearing_to(test_loc); EXPECT_EQ(31503, bearing); const float bearing_rad = test_home.get_bearing(test_loc); - EXPECT_FLOAT_EQ(radians(315.03), bearing_rad); + EXPECT_FLOAT_EQ(5.4982867, bearing_rad); } TEST(Location, Sanitize) { + // we will sanitize test_loc with test_default_loc + // test_home is just for reference const Location test_home{-35362938, 149165085, 100, Location::AltFrame::ABSOLUTE}; + EXPECT_TRUE(vehicle.ahrs.set_home(test_home)); + const Location test_default_loc{-35362938, 149165085, 200, Location::AltFrame::ABSOLUTE}; Location test_loc; test_loc.set_alt_cm(0, Location::AltFrame::ABOVE_HOME); - EXPECT_TRUE(test_loc.sanitize(test_home)); - EXPECT_TRUE(test_loc.same_latlon_as(test_home)); - EXPECT_EQ(test_home.alt, test_loc.alt); + EXPECT_TRUE(test_loc.sanitize(test_default_loc)); + EXPECT_TRUE(test_loc.same_latlon_as(test_default_loc)); + int32_t default_loc_alt; + // we should compare test_loc alt and test_default_loc alt in same frame , in this case, ABOVE HOME + EXPECT_TRUE(test_default_loc.get_alt_cm(Location::AltFrame::ABOVE_HOME, default_loc_alt)); + EXPECT_EQ(test_loc.alt, default_loc_alt); test_loc = Location(91*1e7, 0, 0, Location::AltFrame::ABSOLUTE); - EXPECT_TRUE(test_loc.sanitize(test_home)); - EXPECT_TRUE(test_loc.same_latlon_as(test_home)); - EXPECT_NE(test_home.alt, test_loc.alt); + EXPECT_TRUE(test_loc.sanitize(test_default_loc)); + EXPECT_TRUE(test_loc.same_latlon_as(test_default_loc)); + EXPECT_NE(test_default_loc.alt, test_loc.alt); test_loc = Location(0, 181*1e7, 0, Location::AltFrame::ABSOLUTE); - EXPECT_TRUE(test_loc.sanitize(test_home)); - EXPECT_TRUE(test_loc.same_latlon_as(test_home)); - EXPECT_NE(test_home.alt, test_loc.alt); + EXPECT_TRUE(test_loc.sanitize(test_default_loc)); + EXPECT_TRUE(test_loc.same_latlon_as(test_default_loc)); + EXPECT_NE(test_default_loc.alt, test_loc.alt); test_loc = Location(42*1e7, 42*1e7, 420, Location::AltFrame::ABSOLUTE); - EXPECT_FALSE(test_loc.sanitize(test_home)); - EXPECT_FALSE(test_loc.same_latlon_as(test_home)); - EXPECT_NE(test_home.alt, test_loc.alt); + EXPECT_FALSE(test_loc.sanitize(test_default_loc)); + EXPECT_FALSE(test_loc.same_latlon_as(test_default_loc)); + EXPECT_NE(test_default_loc.alt, test_loc.alt); } TEST(Location, Line) diff --git a/libraries/AP_Compass/AP_Compass.cpp b/libraries/AP_Compass/AP_Compass.cpp index f7461775080..e4067c70621 100644 --- a/libraries/AP_Compass/AP_Compass.cpp +++ b/libraries/AP_Compass/AP_Compass.cpp @@ -7,6 +7,7 @@ #include #include #include +#include #include "AP_Compass_SITL.h" #include "AP_Compass_AK8963.h" @@ -160,8 +161,8 @@ const AP_Param::GroupInfo Compass::var_info[] = { // @Param: ORIENT // @DisplayName: Compass orientation - // @Description: The orientation of the first external compass relative to the vehicle frame. This value will be ignored unless this compass is set as an external compass. When set correctly in the northern hemisphere, pointing the nose and right side down should increase the MagX and MagY values respectively. Rolling the vehicle upside down should decrease the MagZ value. For southern hemisphere, switch increase and decrease. NOTE: For internal compasses, AHRS_ORIENT is used. The label for each option is specified in the order of rotations for that orientation. - // @Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Yaw45Roll180,10:Yaw90Roll180,11:Yaw135Roll180,12:Pitch180,13:Yaw225Roll180,14:Yaw270Roll180,15:Yaw315Roll180,16:Roll90,17:Yaw45Roll90,18:Yaw90Roll90,19:Yaw135Roll90,20:Roll270,21:Yaw45Roll270,22:Yaw90Roll270,23:Yaw135Roll270,24:Pitch90,25:Pitch270,26:Yaw90Pitch180,27:Yaw270Pitch180,28:Pitch90Roll90,29:Pitch90Roll180,30:Pitch90Roll270,31:Pitch180Roll90,32:Pitch180Roll270,33:Pitch270Roll90,34:Pitch270Roll180,35:Pitch270Roll270,36:Yaw90Pitch180Roll90,37:Yaw270Roll90,38:Yaw293Pitch68Roll180,39:Pitch315,40:Pitch315Roll90,42:Roll45,43:Roll315,100:Custom + // @Description: The orientation of the first external compass relative to the vehicle frame. This value will be ignored unless this compass is set as an external compass. When set correctly in the northern hemisphere, pointing the nose and right side down should increase the MagX and MagY values respectively. Rolling the vehicle upside down should decrease the MagZ value. For southern hemisphere, switch increase and decrease. NOTE: For internal compasses, AHRS_ORIENT is used. The label for each option is specified in the order of rotations for that orientation. Firmware versions 4.2 and prior can use a CUSTOM (100) rotation to set the COMPASS_CUS_ROLL/PIT/YAW angles for Compass orientation. Later versions provide two general custom rotations which can be used, Custom 1 and Custom 2, with CUST_1_ROLL/PIT/YAW or CUST_2_ROLL/PIT/YAW angles. + // @Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Yaw45Roll180,10:Yaw90Roll180,11:Yaw135Roll180,12:Pitch180,13:Yaw225Roll180,14:Yaw270Roll180,15:Yaw315Roll180,16:Roll90,17:Yaw45Roll90,18:Yaw90Roll90,19:Yaw135Roll90,20:Roll270,21:Yaw45Roll270,22:Yaw90Roll270,23:Yaw135Roll270,24:Pitch90,25:Pitch270,26:Yaw90Pitch180,27:Yaw270Pitch180,28:Pitch90Roll90,29:Pitch90Roll180,30:Pitch90Roll270,31:Pitch180Roll90,32:Pitch180Roll270,33:Pitch270Roll90,34:Pitch270Roll180,35:Pitch270Roll270,36:Yaw90Pitch180Roll90,37:Yaw270Roll90,38:Yaw293Pitch68Roll180,39:Pitch315,40:Pitch315Roll90,42:Roll45,43:Roll315,100:Custom 4.1 and older,101:Custom 1,102:Custom 2 // @User: Advanced AP_GROUPINFO("ORIENT", 8, Compass, _state._priv_instance[0].orientation, ROTATION_NONE), @@ -320,8 +321,8 @@ const AP_Param::GroupInfo Compass::var_info[] = { // @Param: ORIENT2 // @DisplayName: Compass2 orientation - // @Description: The orientation of a second external compass relative to the vehicle frame. This value will be ignored unless this compass is set as an external compass. When set correctly in the northern hemisphere, pointing the nose and right side down should increase the MagX and MagY values respectively. Rolling the vehicle upside down should decrease the MagZ value. For southern hemisphere, switch increase and decrease. NOTE: For internal compasses, AHRS_ORIENT is used. - // @Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Roll180Yaw45,10:Roll180Yaw90,11:Roll180Yaw135,12:Pitch180,13:Roll180Yaw225,14:Roll180Yaw270,15:Roll180Yaw315,16:Roll90,17:Roll90Yaw45,18:Roll90Yaw90,19:Roll90Yaw135,20:Roll270,21:Roll270Yaw45,22:Roll270Yaw90,23:Roll270Yaw135,24:Pitch90,25:Pitch270,26:Pitch180Yaw90,27:Pitch180Yaw270,28:Roll90Pitch90,29:Roll180Pitch90,30:Roll270Pitch90,31:Roll90Pitch180,32:Roll270Pitch180,33:Roll90Pitch270,34:Roll180Pitch270,35:Roll270Pitch270,36:Roll90Pitch180Yaw90,37:Roll90Yaw270,38:Yaw293Pitch68Roll180,39:Pitch315,40:Roll90Pitch315,42:Roll45,43:Roll315,100:Custom + // @Description: The orientation of a second external compass relative to the vehicle frame. This value will be ignored unless this compass is set as an external compass. When set correctly in the northern hemisphere, pointing the nose and right side down should increase the MagX and MagY values respectively. Rolling the vehicle upside down should decrease the MagZ value. For southern hemisphere, switch increase and decrease. NOTE: For internal compasses, AHRS_ORIENT is used. The label for each option is specified in the order of rotations for that orientation. Firmware versions 4.2 and prior can use a CUSTOM (100) rotation to set the COMPASS_CUS_ROLL/PIT/YAW angles for Compass orientation. Later versions provide two general custom rotations which can be used, Custom 1 and Custom 2, with CUST_1_ROLL/PIT/YAW or CUST_2_ROLL/PIT/YAW angles. + // @Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Yaw45Roll180,10:Yaw90Roll180,11:Yaw135Roll180,12:Pitch180,13:Yaw225Roll180,14:Yaw270Roll180,15:Yaw315Roll180,16:Roll90,17:Yaw45Roll90,18:Yaw90Roll90,19:Yaw135Roll90,20:Roll270,21:Yaw45Roll270,22:Yaw90Roll270,23:Yaw135Roll270,24:Pitch90,25:Pitch270,26:Yaw90Pitch180,27:Yaw270Pitch180,28:Pitch90Roll90,29:Pitch90Roll180,30:Pitch90Roll270,31:Pitch180Roll90,32:Pitch180Roll270,33:Pitch270Roll90,34:Pitch270Roll180,35:Pitch270Roll270,36:Yaw90Pitch180Roll90,37:Yaw270Roll90,38:Yaw293Pitch68Roll180,39:Pitch315,40:Pitch315Roll90,42:Roll45,43:Roll315,100:Custom 4.1 and older,101:Custom 1,102:Custom 2 // @User: Advanced AP_GROUPINFO("ORIENT2", 19, Compass, _state._priv_instance[1].orientation, ROTATION_NONE), @@ -343,8 +344,8 @@ const AP_Param::GroupInfo Compass::var_info[] = { // @Param: ORIENT3 // @DisplayName: Compass3 orientation - // @Description: The orientation of a third external compass relative to the vehicle frame. This value will be ignored unless this compass is set as an external compass. When set correctly in the northern hemisphere, pointing the nose and right side down should increase the MagX and MagY values respectively. Rolling the vehicle upside down should decrease the MagZ value. For southern hemisphere, switch increase and decrease. NOTE: For internal compasses, AHRS_ORIENT is used. - // @Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Roll180Yaw45,10:Roll180Yaw90,11:Roll180Yaw135,12:Pitch180,13:Roll180Yaw225,14:Roll180Yaw270,15:Roll180Yaw315,16:Roll90,17:Roll90Yaw45,18:Roll90Yaw90,19:Roll90Yaw135,20:Roll270,21:Roll270Yaw45,22:Roll270Yaw90,23:Roll270Yaw135,24:Pitch90,25:Pitch270,26:Pitch180Yaw90,27:Pitch180Yaw270,28:Roll90Pitch90,29:Roll180Pitch90,30:Roll270Pitch90,31:Roll90Pitch180,32:Roll270Pitch180,33:Roll90Pitch270,34:Roll180Pitch270,35:Roll270Pitch270,36:Roll90Pitch180Yaw90,37:Roll90Yaw270,38:Yaw293Pitch68Roll180,39:Pitch315,40:Roll90Pitch315,42:Roll45,43:Roll315,100:Custom + // @Description: The orientation of a third external compass relative to the vehicle frame. This value will be ignored unless this compass is set as an external compass. When set correctly in the northern hemisphere, pointing the nose and right side down should increase the MagX and MagY values respectively. Rolling the vehicle upside down should decrease the MagZ value. For southern hemisphere, switch increase and decrease. NOTE: For internal compasses, AHRS_ORIENT is used. The label for each option is specified in the order of rotations for that orientation. Firmware versions 4.2 and prior can use a CUSTOM (100) rotation to set the COMPASS_CUS_ROLL/PIT/YAW angles for Compass orientation. Later versions provide two general custom rotations which can be used, Custom 1 and Custom 2, with CUST_1_ROLL/PIT/YAW or CUST_2_ROLL/PIT/YAW angles. + // @Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Yaw45Roll180,10:Yaw90Roll180,11:Yaw135Roll180,12:Pitch180,13:Yaw225Roll180,14:Yaw270Roll180,15:Yaw315Roll180,16:Roll90,17:Yaw45Roll90,18:Yaw90Roll90,19:Yaw135Roll90,20:Roll270,21:Yaw45Roll270,22:Yaw90Roll270,23:Yaw135Roll270,24:Pitch90,25:Pitch270,26:Yaw90Pitch180,27:Yaw270Pitch180,28:Pitch90Roll90,29:Pitch90Roll180,30:Pitch90Roll270,31:Pitch180Roll90,32:Pitch180Roll270,33:Pitch270Roll90,34:Pitch270Roll180,35:Pitch270Roll270,36:Yaw90Pitch180Roll90,37:Yaw270Roll90,38:Yaw293Pitch68Roll180,39:Pitch315,40:Pitch315Roll90,42:Roll45,43:Roll315,100:Custom 4.1 and older,101:Custom 1,102:Custom 2 // @User: Advanced AP_GROUPINFO("ORIENT3", 22, Compass, _state._priv_instance[2].orientation, ROTATION_NONE), @@ -373,7 +374,7 @@ const AP_Param::GroupInfo Compass::var_info[] = { // @DisplayName: Compass soft-iron diagonal Z component // @Description: DIA_Z in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]] // @User: Advanced - AP_GROUPINFO("DIA", 24, Compass, _state._priv_instance[0].diagonals, 0), + AP_GROUPINFO("DIA", 24, Compass, _state._priv_instance[0].diagonals, 1.0), // @Param: ODI_X // @DisplayName: Compass soft-iron off-diagonal X component @@ -411,7 +412,7 @@ const AP_Param::GroupInfo Compass::var_info[] = { // @DisplayName: Compass2 soft-iron diagonal Z component // @Description: DIA_Z in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]] // @User: Advanced - AP_GROUPINFO("DIA2", 26, Compass, _state._priv_instance[1].diagonals, 0), + AP_GROUPINFO("DIA2", 26, Compass, _state._priv_instance[1].diagonals, 1.0), // @Param: ODI2_X // @DisplayName: Compass2 soft-iron off-diagonal X component @@ -449,7 +450,7 @@ const AP_Param::GroupInfo Compass::var_info[] = { // @DisplayName: Compass3 soft-iron diagonal Z component // @Description: DIA_Z in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]] // @User: Advanced - AP_GROUPINFO("DIA3", 28, Compass, _state._priv_instance[2].diagonals, 0), + AP_GROUPINFO("DIA3", 28, Compass, _state._priv_instance[2].diagonals, 1.0), // @Param: ODI3_X // @DisplayName: Compass3 soft-iron off-diagonal X component @@ -632,7 +633,6 @@ const AP_Param::GroupInfo Compass::var_info[] = { AP_GROUPINFO("DEV_ID8", 48, Compass, extra_dev_id[4], 0), #endif // COMPASS_MAX_UNREG_DEV -#if !APM_BUILD_TYPE(APM_BUILD_AP_Periph) // @Param: CUS_ROLL // @DisplayName: Custom orientation roll offset // @Description: Compass mounting position roll offset. Positive values = roll right, negative values = roll left. This parameter is only used when COMPASS_ORIENT/2/3 is set to CUSTOM. @@ -641,7 +641,8 @@ const AP_Param::GroupInfo Compass::var_info[] = { // @Increment: 1 // @RebootRequired: True // @User: Advanced - AP_GROUPINFO("CUS_ROLL", 49, Compass, _custom_roll, 0), + + // index 49 // @Param: CUS_PIT // @DisplayName: Custom orientation pitch offset @@ -651,7 +652,8 @@ const AP_Param::GroupInfo Compass::var_info[] = { // @Increment: 1 // @RebootRequired: True // @User: Advanced - AP_GROUPINFO("CUS_PIT", 50, Compass, _custom_pitch, 0), + + // index 50 // @Param: CUS_YAW // @DisplayName: Custom orientation yaw offset @@ -661,8 +663,9 @@ const AP_Param::GroupInfo Compass::var_info[] = { // @Increment: 1 // @RebootRequired: True // @User: Advanced - AP_GROUPINFO("CUS_YAW", 51, Compass, _custom_yaw, 0), -#endif + + // index 51 + AP_GROUPEND }; @@ -690,9 +693,33 @@ void Compass::init() return; } + // convert to new custom rotation method + // PARAMETER_CONVERSION - Added: Nov-2021 +#if !APM_BUILD_TYPE(APM_BUILD_AP_Periph) + for (StateIndex i(0); i 1 // Look if there was a primary compass setup in previous version - // if so and the the primary compass is not set in current setup + // if so and the primary compass is not set in current setup // make the devid as primary. if (_priority_did_stored_list[Priority(0)] == 0) { uint16_t k_param_compass; @@ -1145,10 +1172,12 @@ void Compass::_probe_external_i2c_compasses(void) ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(i, ist8310_addr[a]), true, default_rotation)); } +#ifndef HAL_COMPASS_DISABLE_IST8310_INTERNAL_PROBE FOREACH_I2C_INTERNAL(i) { ADD_BACKEND(DRIVER_IST8310, AP_Compass_IST8310::probe(GET_I2C_DEVICE(i, ist8310_addr[a]), all_external, default_rotation)); } +#endif } } #endif @@ -1434,7 +1463,7 @@ void Compass::_detect_backends(void) if (_backend_count == 0 || _compass_count == 0) { - hal.console->printf("No Compass backends available\n"); + DEV_PRINTF("No Compass backends available\n"); } } @@ -1553,6 +1582,10 @@ Compass::read(void) return false; } +#if HAL_LOGGING_ENABLED + const bool old_healthy = healthy(); +#endif + #ifndef HAL_BUILD_AP_PERIPH if (!_initial_location_set) { try_set_initial_location(); @@ -1593,7 +1626,21 @@ Compass::read(void) break; } } - return healthy(); + const bool new_healthy = healthy(); + +#if HAL_LOGGING_ENABLED + + #define MASK_LOG_ANY 0xFFFF + + if (new_healthy != old_healthy) { + if (AP::logger().should_log(MASK_LOG_ANY)) { + const LogErrorCode code = new_healthy ? LogErrorCode::ERROR_RESOLVED : LogErrorCode::UNHEALTHY; + AP::logger().Write_Error(LogErrorSubsystem::COMPASS, code); + } + } +#endif + + return new_healthy; } uint8_t @@ -1858,7 +1905,7 @@ bool Compass::configured(uint8_t i) // if dev_id loaded from eeprom is different from detected dev id or dev_id loaded from eeprom is different from cached dev_id, compass is unconfigured if (_state[id].dev_id != _state[id].detected_dev_id || _state[id].dev_id != dev_id_cache_value) { // restore cached value - _state[id].dev_id = dev_id_cache_value; + _state[id].dev_id.set(dev_id_cache_value); // return failure return false; } @@ -1874,7 +1921,7 @@ bool Compass::configured(char *failure_msg, uint8_t failure_msg_len) for (Priority i(0); iread_registers(REG_COMPANY_ID, (uint8_t *)&whoami, 2)) { // a device is replying on the AK09916 I2C address, don't // load the ICM20948 - hal.console->printf("ICM20948: AK09916 bus conflict\n"); + DEV_PRINTF("ICM20948: AK09916 bus conflict\n"); goto fail; } @@ -230,7 +230,7 @@ bool AP_Compass_AK09916::init() _bus->get_semaphore()->take_blocking(); if (!_bus->configure()) { - hal.console->printf("AK09916: Could not configure the bus\n"); + DEV_PRINTF("AK09916: Could not configure the bus\n"); goto fail; } @@ -239,7 +239,6 @@ bool AP_Compass_AK09916::init() } if (!_check_id()) { - hal.console->printf("AK09916: Wrong id\n"); goto fail; } @@ -247,12 +246,12 @@ bool AP_Compass_AK09916::init() _bus->setup_checked_registers(1); if (!_setup_mode()) { - hal.console->printf("AK09916: Could not setup mode\n"); + DEV_PRINTF("AK09916: Could not setup mode\n"); goto fail; } if (!_bus->start_measurements()) { - hal.console->printf("AK09916: Could not start measurements\n"); + DEV_PRINTF("AK09916: Could not start measurements\n"); goto fail; } @@ -325,19 +324,6 @@ void AP_Compass_AK09916::_update() _make_adc_sensitivity_adjustment(raw_field); raw_field *= AK09916_MILLIGAUSS_SCALE; -#ifdef HAL_AK09916_HEATER_OFFSET - /* - the internal AK09916 can be impacted by the magnetic field from - a heater. We use the heater duty cycle to correct for the error - */ - if (AP_HAL::Device::devid_get_bus_type(_bus->get_bus_id()) == AP_HAL::Device::BUS_TYPE_SPI) { - auto *bc = AP::boardConfig(); - if (bc) { - raw_field += HAL_AK09916_HEATER_OFFSET * bc->get_heater_duty_cycle() * 0.01; - } - } -#endif - accumulate_sample(raw_field, _compass_instance, 10); check_registers: diff --git a/libraries/AP_Compass/AP_Compass_AK8963.cpp b/libraries/AP_Compass/AP_Compass_AK8963.cpp index d78f9220f57..96670902802 100644 --- a/libraries/AP_Compass/AP_Compass_AK8963.cpp +++ b/libraries/AP_Compass/AP_Compass_AK8963.cpp @@ -135,27 +135,27 @@ bool AP_Compass_AK8963::init() _bus->get_semaphore()->take_blocking(); if (!_bus->configure()) { - hal.console->printf("AK8963: Could not configure the bus\n"); + DEV_PRINTF("AK8963: Could not configure the bus\n"); goto fail; } if (!_check_id()) { - hal.console->printf("AK8963: Wrong id\n"); + DEV_PRINTF("AK8963: Wrong id\n"); goto fail; } if (!_calibrate()) { - hal.console->printf("AK8963: Could not read calibration data\n"); + DEV_PRINTF("AK8963: Could not read calibration data\n"); goto fail; } if (!_setup_mode()) { - hal.console->printf("AK8963: Could not setup mode\n"); + DEV_PRINTF("AK8963: Could not setup mode\n"); goto fail; } if (!_bus->start_measurements()) { - hal.console->printf("AK8963: Could not start measurements\n"); + DEV_PRINTF("AK8963: Could not start measurements\n"); goto fail; } diff --git a/libraries/AP_Compass/AP_Compass_BMM150.cpp b/libraries/AP_Compass/AP_Compass_BMM150.cpp index 4202e07b7d8..7d26f6ed291 100644 --- a/libraries/AP_Compass/AP_Compass_BMM150.cpp +++ b/libraries/AP_Compass/AP_Compass_BMM150.cpp @@ -118,7 +118,7 @@ bool AP_Compass_BMM150::_load_trim_values() } } if (-1 == tries) { - hal.console->printf("BMM150: Failed to load trim registers\n"); + DEV_PRINTF("BMM150: Failed to load trim registers\n"); return false; } @@ -175,7 +175,7 @@ bool AP_Compass_BMM150::init() break; } if (boot_tries == 0) { - hal.console->printf("BMM150: Wrong chip ID 0x%02x should be 0x%02x\n", val, CHIP_ID_VAL); + DEV_PRINTF("BMM150: Wrong chip ID 0x%02x should be 0x%02x\n", val, CHIP_ID_VAL); } } if (-1 == boot_tries) { diff --git a/libraries/AP_Compass/AP_Compass_Backend.cpp b/libraries/AP_Compass/AP_Compass_Backend.cpp index ae411082216..5ea08e92b84 100644 --- a/libraries/AP_Compass/AP_Compass_Backend.cpp +++ b/libraries/AP_Compass/AP_Compass_Backend.cpp @@ -5,6 +5,7 @@ #include #include +#include extern const AP_HAL::HAL& hal; @@ -21,25 +22,35 @@ void AP_Compass_Backend::rotate_field(Vector3f &mag, uint8_t instance) } mag.rotate(state.rotation); - if (!state.external) { - // and add in AHRS_ORIENTATION setting if not an external compass - if (_compass._board_orientation == ROTATION_CUSTOM && _compass._custom_rotation) { - mag = *_compass._custom_rotation * mag; - } else { - mag.rotate(_compass._board_orientation); +#ifdef HAL_HEATER_MAG_OFFSET + /* + apply compass compensations for boards that have a heater which + interferes with an internal compass. This needs to be applied + before the board orientation so it is independent of + AHRS_ORIENTATION + */ + if (!is_external(instance)) { + const uint32_t dev_id = uint32_t(_compass._state[Compass::StateIndex(instance)].dev_id); + static const struct offset { + uint32_t dev_id; + Vector3f ofs; + } offsets[] = HAL_HEATER_MAG_OFFSET; + const auto *bc = AP::boardConfig(); + if (bc) { + for (const auto &o : offsets) { + if (o.dev_id == dev_id) { + mag += o.ofs * bc->get_heater_duty_cycle() * 0.01; + } + } } + } +#endif + + if (!state.external) { + mag.rotate(_compass._board_orientation); } else { // add user selectable orientation -#if !APM_BUILD_TYPE(APM_BUILD_AP_Periph) - Rotation rotation = Rotation(state.orientation.get()); - if (rotation == ROTATION_CUSTOM && _compass._custom_external_rotation) { - mag = *_compass._custom_external_rotation * mag; - } else { - mag.rotate(rotation); - } -#else mag.rotate((enum Rotation)state.orientation.get()); -#endif } } @@ -62,10 +73,6 @@ void AP_Compass_Backend::correct_field(Vector3f &mag, uint8_t i) { Compass::mag_state &state = _compass._state[Compass::StateIndex(i)]; - if (state.diagonals.get().is_zero()) { - state.diagonals.set(Vector3f(1.0f,1.0f,1.0f)); - } - const Vector3f &offsets = state.offset.get(); const Vector3f &diagonals = state.diagonals.get(); const Vector3f &offdiagonals = state.offdiagonals.get(); @@ -80,13 +87,15 @@ void AP_Compass_Backend::correct_field(Vector3f &mag, uint8_t i) } // apply eliptical correction - Matrix3f mat( - diagonals.x, offdiagonals.x, offdiagonals.y, - offdiagonals.x, diagonals.y, offdiagonals.z, - offdiagonals.y, offdiagonals.z, diagonals.z - ); - - mag = mat * mag; + if (!diagonals.is_zero()) { + Matrix3f mat( + diagonals.x, offdiagonals.x, offdiagonals.y, + offdiagonals.x, diagonals.y, offdiagonals.z, + offdiagonals.y, offdiagonals.z, diagonals.z + ); + + mag = mat * mag; + } #if COMPASS_MOT_ENABLED const Vector3f &mot = state.motor_compensation.get(); @@ -233,15 +242,6 @@ bool AP_Compass_Backend::is_external(uint8_t instance) void AP_Compass_Backend::set_rotation(uint8_t instance, enum Rotation rotation) { _compass._state[Compass::StateIndex(instance)].rotation = rotation; -#if !APM_BUILD_TYPE(APM_BUILD_AP_Periph) - // lazily create the custom rotation matrix - if (!_compass._custom_external_rotation && Rotation(_compass._state[Compass::StateIndex(instance)].orientation.get()) == ROTATION_CUSTOM) { - _compass._custom_external_rotation = new Matrix3f(); - if (_compass._custom_external_rotation) { - _compass._custom_external_rotation->from_euler(radians(_compass._custom_roll), radians(_compass._custom_pitch), radians(_compass._custom_yaw)); - } - } -#endif } static constexpr float FILTER_KOEF = 0.1f; diff --git a/libraries/AP_Compass/AP_Compass_Backend.h b/libraries/AP_Compass/AP_Compass_Backend.h index 95b5976a18f..8636f982585 100644 --- a/libraries/AP_Compass/AP_Compass_Backend.h +++ b/libraries/AP_Compass/AP_Compass_Backend.h @@ -19,12 +19,13 @@ */ #pragma once -#include "AP_Compass.h" - +#include #ifndef HAL_MSP_COMPASS_ENABLED #define HAL_MSP_COMPASS_ENABLED HAL_MSP_SENSORS_ENABLED #endif +#include "AP_Compass.h" + class Compass; // forward declaration class AP_Compass_Backend { diff --git a/libraries/AP_Compass/AP_Compass_Calibration.cpp b/libraries/AP_Compass/AP_Compass_Calibration.cpp index eb7e2909ca3..a48edc30361 100644 --- a/libraries/AP_Compass/AP_Compass_Calibration.cpp +++ b/libraries/AP_Compass/AP_Compass_Calibration.cpp @@ -82,7 +82,7 @@ bool Compass::_start_calibration(uint8_t i, bool retry, float delay) if (_rotate_auto) { enum Rotation r = _get_state(prio).external?(enum Rotation)_get_state(prio).orientation.get():ROTATION_NONE; - if (r != ROTATION_CUSTOM) { + if (r < ROTATION_MAX) { _calibrator[prio]->set_orientation(r, _get_state(prio).external, _rotate_auto>=2, _rotate_auto>=3); } } @@ -333,8 +333,13 @@ bool Compass::is_calibrating() const case CompassCalibrator::Status::SUCCESS: case CompassCalibrator::Status::FAILED: case CompassCalibrator::Status::BAD_ORIENTATION: - break; - default: + case CompassCalibrator::Status::BAD_RADIUS: + // this backend isn't calibrating, + // but maybe the next one is: + continue; + case CompassCalibrator::Status::WAITING_TO_START: + case CompassCalibrator::Status::RUNNING_STEP_ONE: + case CompassCalibrator::Status::RUNNING_STEP_TWO: return true; } } @@ -445,22 +450,25 @@ bool Compass::get_uncorrected_field(uint8_t instance, Vector3f &field) const // form eliptical correction matrix and invert it. This is // needed to remove the effects of the eliptical correction // when calculating new offsets - const Vector3f &diagonals = get_diagonals(instance); - const Vector3f &offdiagonals = get_offdiagonals(instance); - Matrix3f mat { - diagonals.x, offdiagonals.x, offdiagonals.y, - offdiagonals.x, diagonals.y, offdiagonals.z, - offdiagonals.y, offdiagonals.z, diagonals.z - }; - if (!mat.invert()) { - return false; - } // get corrected field field = get_field(instance); - // remove impact of diagonals and off-diagonals - field = mat * field; + const Vector3f &diagonals = get_diagonals(instance); + if (!diagonals.is_zero()) { + const Vector3f &offdiagonals = get_offdiagonals(instance); + Matrix3f mat { + diagonals.x, offdiagonals.x, offdiagonals.y, + offdiagonals.x, diagonals.y, offdiagonals.z, + offdiagonals.y, offdiagonals.z, diagonals.z + }; + if (!mat.invert()) { + return false; + } + + // remove impact of diagonals and off-diagonals + field = mat * field; + } // remove impact of offsets field -= get_offsets(instance); diff --git a/libraries/AP_Compass/AP_Compass_HMC5843.cpp b/libraries/AP_Compass/AP_Compass_HMC5843.cpp index 4f237bd2040..4b09f8a7abf 100644 --- a/libraries/AP_Compass/AP_Compass_HMC5843.cpp +++ b/libraries/AP_Compass/AP_Compass_HMC5843.cpp @@ -152,7 +152,7 @@ bool AP_Compass_HMC5843::init() AP_HAL::Semaphore *bus_sem = _bus->get_semaphore(); if (!bus_sem) { - hal.console->printf("HMC5843: Unable to get bus semaphore\n"); + DEV_PRINTF("HMC5843: Unable to get bus semaphore\n"); return false; } bus_sem->take_blocking(); @@ -161,7 +161,7 @@ bool AP_Compass_HMC5843::init() _bus->set_retries(10); if (!_bus->configure()) { - hal.console->printf("HMC5843: Could not configure the bus\n"); + DEV_PRINTF("HMC5843: Could not configure the bus\n"); goto errout; } @@ -170,7 +170,7 @@ bool AP_Compass_HMC5843::init() } if (!_calibrate()) { - hal.console->printf("HMC5843: Could not calibrate sensor\n"); + DEV_PRINTF("HMC5843: Could not calibrate sensor\n"); goto errout; } @@ -179,7 +179,7 @@ bool AP_Compass_HMC5843::init() } if (!_bus->start_measurements()) { - hal.console->printf("HMC5843: Could not start measurements on bus\n"); + DEV_PRINTF("HMC5843: Could not start measurements on bus\n"); goto errout; } @@ -210,7 +210,7 @@ bool AP_Compass_HMC5843::init() _bus->register_periodic_callback(13333, FUNCTOR_BIND_MEMBER(&AP_Compass_HMC5843::_timer, void)); - hal.console->printf("HMC5843 found on bus 0x%x\n", (unsigned)_bus->get_bus_id()); + DEV_PRINTF("HMC5843 found on bus 0x%x\n", (unsigned)_bus->get_bus_id()); return true; diff --git a/libraries/AP_Compass/AP_Compass_IST8310.cpp b/libraries/AP_Compass/AP_Compass_IST8310.cpp index cd4fb05cb35..7a0769761d3 100644 --- a/libraries/AP_Compass/AP_Compass_IST8310.cpp +++ b/libraries/AP_Compass/AP_Compass_IST8310.cpp @@ -229,19 +229,6 @@ void AP_Compass_IST8310::timer() /* Resolution: 0.3 µT/LSB - already convert to milligauss */ Vector3f field = Vector3f{x * 3.0f, y * 3.0f, z * 3.0f}; -#ifdef HAL_IST8310_I2C_HEATER_OFFSET - /* - the internal IST8310 can be impacted by the magnetic field from - a heater. We use the heater duty cycle to correct for the error - */ - if (!is_external(_instance) && AP_HAL::Device::devid_get_bus_type(_dev->get_bus_id()) == AP_HAL::Device::BUS_TYPE_I2C) { - const auto *bc = AP::boardConfig(); - if (bc) { - field += HAL_IST8310_I2C_HEATER_OFFSET * bc->get_heater_duty_cycle() * 0.01; - } - } -#endif - accumulate_sample(field, _instance); } diff --git a/libraries/AP_Compass/AP_Compass_LSM303D.cpp b/libraries/AP_Compass/AP_Compass_LSM303D.cpp index 1e62f6e6cf9..ec5910e8b77 100644 --- a/libraries/AP_Compass/AP_Compass_LSM303D.cpp +++ b/libraries/AP_Compass/AP_Compass_LSM303D.cpp @@ -222,7 +222,7 @@ bool AP_Compass_LSM303D::_read_sample() } rx; if (_register_read(ADDR_CTRL_REG7) != _reg7_expected) { - hal.console->printf("LSM303D _read_data_transaction_accel: _reg7_expected unexpected\n"); + DEV_PRINTF("LSM303D _read_data_transaction_accel: _reg7_expected unexpected\n"); return false; } @@ -316,7 +316,7 @@ bool AP_Compass_LSM303D::_hardware_init() } } if (tries == 5) { - hal.console->printf("Failed to boot LSM303D 5 times\n"); + DEV_PRINTF("Failed to boot LSM303D 5 times\n"); goto fail_tries; } diff --git a/libraries/AP_Compass/AP_Compass_LSM9DS1.cpp b/libraries/AP_Compass/AP_Compass_LSM9DS1.cpp index f40ea2e05a4..3fb407e2d75 100644 --- a/libraries/AP_Compass/AP_Compass_LSM9DS1.cpp +++ b/libraries/AP_Compass/AP_Compass_LSM9DS1.cpp @@ -84,23 +84,23 @@ bool AP_Compass_LSM9DS1::init() AP_HAL::Semaphore *bus_sem = _dev->get_semaphore(); if (!bus_sem) { - hal.console->printf("LSM9DS1: Unable to get bus semaphore\n"); + DEV_PRINTF("LSM9DS1: Unable to get bus semaphore\n"); return false; } bus_sem->take_blocking(); if (!_check_id()) { - hal.console->printf("LSM9DS1: Could not check id\n"); + DEV_PRINTF("LSM9DS1: Could not check id\n"); goto errout; } if (!_configure()) { - hal.console->printf("LSM9DS1: Could not check id\n"); + DEV_PRINTF("LSM9DS1: Could not check id\n"); goto errout; } if (!_set_scale()) { - hal.console->printf("LSM9DS1: Could not set scale\n"); + DEV_PRINTF("LSM9DS1: Could not set scale\n"); goto errout; } @@ -127,15 +127,14 @@ bool AP_Compass_LSM9DS1::init() void AP_Compass_LSM9DS1::_dump_registers() { - hal.console->printf("LSMDS1 registers\n"); + DEV_PRINTF("LSMDS1 registers\n"); for (uint8_t reg = LSM9DS1M_OFFSET_X_REG_L_M; reg <= LSM9DS1M_INT_THS_H_M; reg++) { - uint8_t v = _register_read(reg); - hal.console->printf("%02x:%02x ", (unsigned)reg, (unsigned)v); + DEV_PRINTF("%02x:%02x ", (unsigned)reg, (unsigned)_register_read(reg)); if ((reg - (LSM9DS1M_OFFSET_X_REG_L_M-1)) % 16 == 0) { - hal.console->printf("\n"); + DEV_PRINTF("\n"); } } - hal.console->printf("\n"); + DEV_PRINTF("\n"); } void AP_Compass_LSM9DS1::_update(void) @@ -174,7 +173,7 @@ bool AP_Compass_LSM9DS1::_check_id(void) uint8_t value = _register_read(LSM9DS1M_WHO_AM_I); if (value != WHO_AM_I_MAG) { - hal.console->printf("LSM9DS1: unexpected WHOAMI 0x%x\n", (unsigned)value); + DEV_PRINTF("LSM9DS1: unexpected WHOAMI 0x%x\n", (unsigned)value); return false; } diff --git a/libraries/AP_Compass/AP_Compass_RM3100.cpp b/libraries/AP_Compass/AP_Compass_RM3100.cpp index f3423c13483..8df7c182df7 100644 --- a/libraries/AP_Compass/AP_Compass_RM3100.cpp +++ b/libraries/AP_Compass/AP_Compass_RM3100.cpp @@ -149,7 +149,7 @@ bool AP_Compass_RM3100::init() } set_dev_id(compass_instance, dev->get_bus_id()); - hal.console->printf("RM3100: Found at address 0x%x as compass %u\n", dev->get_bus_address(), compass_instance); + DEV_PRINTF("RM3100: Found at address 0x%x as compass %u\n", dev->get_bus_address(), compass_instance); set_rotation(compass_instance, rotation); diff --git a/libraries/AP_Compass/AP_Compass_SITL.cpp b/libraries/AP_Compass/AP_Compass_SITL.cpp index 27401637203..7f04ab534ee 100644 --- a/libraries/AP_Compass/AP_Compass_SITL.cpp +++ b/libraries/AP_Compass/AP_Compass_SITL.cpp @@ -128,12 +128,7 @@ void AP_Compass_SITL::_timer() Vector3f f = (_eliptical_corr * new_mag_data) - _sitl->mag_ofs[i].get(); // rotate compass f.rotate_inverse((enum Rotation)_sitl->mag_orient[i].get()); - // and add in AHRS_ORIENTATION setting if not an external compass - if (get_board_orientation() == ROTATION_CUSTOM) { - f = _sitl->ahrs_rotation * f; - } else { - f.rotate(get_board_orientation()); - } + f.rotate(get_board_orientation()); // scale the compass to simulate sensor scale factor errors f *= _sitl->mag_scaling[i]; diff --git a/libraries/AP_Compass/AP_Compass_UAVCAN.cpp b/libraries/AP_Compass/AP_Compass_UAVCAN.cpp index e80f48a75d9..892daea168e 100644 --- a/libraries/AP_Compass/AP_Compass_UAVCAN.cpp +++ b/libraries/AP_Compass/AP_Compass_UAVCAN.cpp @@ -32,7 +32,7 @@ extern const AP_HAL::HAL& hal; UC_REGISTRY_BINDER(MagCb, uavcan::equipment::ahrs::MagneticFieldStrength); UC_REGISTRY_BINDER(Mag2Cb, uavcan::equipment::ahrs::MagneticFieldStrength2); -AP_Compass_UAVCAN::DetectedModules AP_Compass_UAVCAN::_detected_modules[] = {0}; +AP_Compass_UAVCAN::DetectedModules AP_Compass_UAVCAN::_detected_modules[]; HAL_Semaphore AP_Compass_UAVCAN::_sem_registry; AP_Compass_UAVCAN::AP_Compass_UAVCAN(AP_UAVCAN* ap_uavcan, uint8_t node_id, uint8_t sensor_id, uint32_t devid) diff --git a/libraries/AP_Compass/Compass_learn.cpp b/libraries/AP_Compass/Compass_learn.cpp index a9b3e9683c2..4ccda4f3be3 100644 --- a/libraries/AP_Compass/Compass_learn.cpp +++ b/libraries/AP_Compass/Compass_learn.cpp @@ -51,8 +51,10 @@ void CompassLearn::update(void) AP_Notify::flags.compass_cal_running = true; ftype yaw_rad, yaw_variance; - if (!gsf->getYawData(yaw_rad, yaw_variance) || + uint8_t n_clips; + if (!gsf->getYawData(yaw_rad, yaw_variance, &n_clips) || !is_positive(yaw_variance) || + n_clips > 1 || yaw_variance >= sq(radians(YAW_ACCURACY_THRESHOLD_DEG))) { // not converged return; diff --git a/libraries/AP_CustomRotations/AP_CustomRotations.cpp b/libraries/AP_CustomRotations/AP_CustomRotations.cpp new file mode 100644 index 00000000000..0af266ea1fe --- /dev/null +++ b/libraries/AP_CustomRotations/AP_CustomRotations.cpp @@ -0,0 +1,159 @@ +#include "AP_CustomRotations.h" + +#include +#include +#include +#include + +#if !APM_BUILD_TYPE(APM_BUILD_AP_Periph) + +const AP_Param::GroupInfo AP_CustomRotations::var_info[] = { + + // @Param: _ENABLE + // @DisplayName: Enable Custom rotations + // @Values: 0:Disable, 1:Enable + // @Description: This enables custom rotations + // @User: Standard + // @RebootRequired: True + AP_GROUPINFO_FLAGS("_ENABLE", 1, AP_CustomRotations, enable, 0, AP_PARAM_FLAG_ENABLE), + + // @Group: 1_ + // @Path: AP_CustomRotations_params.cpp + AP_SUBGROUPINFO(params[0], "1_", 2, AP_CustomRotations, AP_CustomRotation_params), + + // @Group: 2_ + // @Path: AP_CustomRotations_params.cpp + AP_SUBGROUPINFO(params[1], "2_", 3, AP_CustomRotations, AP_CustomRotation_params), + + AP_GROUPEND +}; + +AP_CustomRotation::AP_CustomRotation(AP_CustomRotation_params &_params): + params(_params) +{ + init(); +} + +void AP_CustomRotation::init() +{ + m.from_euler(radians(params.roll),radians(params.pitch),radians(params.yaw)); + q.from_rotation_matrix(m); +} + +AP_CustomRotations::AP_CustomRotations() +{ + AP_Param::setup_object_defaults(this, var_info); + +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL + if (singleton != nullptr) { + AP_HAL::panic("AP_CustomRotations must be singleton"); + } +#endif + singleton = this; +} + +void AP_CustomRotations::init() +{ + if (enable == 0) { + return; + } + + // make sure all custom rotations are allocated + for (uint8_t i = 0; i < NUM_CUST_ROT; i++) { + AP_CustomRotation* rot = get_rotation(Rotation(i + ROTATION_CUSTOM_1)); + if (rot == nullptr) { + AP_BoardConfig::allocation_error("Custom Rotations"); + } + } +} + +void AP_CustomRotations::convert(Rotation r, float roll, float pitch, float yaw) +{ + AP_CustomRotation* rot = get_rotation(r); + if (rot == nullptr) { + return; + } + if (!rot->params.roll.configured() && !rot->params.pitch.configured() && !rot->params.yaw.configured()) { + rot->params.roll.set_and_save(roll); + rot->params.pitch.set_and_save(pitch); + rot->params.yaw.set_and_save(yaw); + rot->init(); + } +} + +void AP_CustomRotations::set(Rotation r, float roll, float pitch, float yaw) +{ + AP_CustomRotation* rot = get_rotation(r); + if (rot == nullptr) { + return; + } + rot->params.roll.set(roll); + rot->params.pitch.set(pitch); + rot->params.yaw.set(yaw); + rot->init(); +} + +void AP_CustomRotations::from_rotation(Rotation r, QuaternionD& q) +{ + AP_CustomRotation* rot = get_rotation(r); + if (rot == nullptr) { + return; + } + q = rot->q.todouble(); +} + +void AP_CustomRotations::from_rotation(Rotation r, Quaternion& q) +{ + AP_CustomRotation* rot = get_rotation(r); + if (rot == nullptr) { + return; + } + q = rot->q; +} + +void AP_CustomRotations::rotate(Rotation r, Vector3d& v) +{ + AP_CustomRotation* rot = get_rotation(r); + if (rot == nullptr) { + return; + } + v = (rot->m * v.tofloat()).todouble(); +} + +void AP_CustomRotations::rotate(Rotation r, Vector3f& v) +{ + AP_CustomRotation* rot = get_rotation(r); + if (rot == nullptr) { + return; + } + v = rot->m * v; +} + +AP_CustomRotation* AP_CustomRotations::get_rotation(Rotation r) +{ + if (r < ROTATION_CUSTOM_1 || r >= ROTATION_CUSTOM_END) { + INTERNAL_ERROR(AP_InternalError::error_t::bad_rotation); + return nullptr; + } + const uint8_t index = r - ROTATION_CUSTOM_1; + if (rotations[index] == nullptr) { + rotations[index] = new AP_CustomRotation(params[index]); + // make sure param is enabled if custom rotation is used + enable.set_and_save_ifchanged(1); + } + return rotations[index]; +} + +// singleton instance +AP_CustomRotations *AP_CustomRotations::singleton; + +namespace AP { + +AP_CustomRotations &custom_rotations() +{ + return *AP_CustomRotations::get_singleton(); +} + +} + +#endif // !APM_BUILD_TYPE(APM_BUILD_AP_Periph) diff --git a/libraries/AP_CustomRotations/AP_CustomRotations.h b/libraries/AP_CustomRotations/AP_CustomRotations.h new file mode 100644 index 00000000000..f26c43b7106 --- /dev/null +++ b/libraries/AP_CustomRotations/AP_CustomRotations.h @@ -0,0 +1,82 @@ +/* + * This file is free software: you can redistribute it and/or modify it + * under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program. If not, see . + */ +#pragma once + +#include +#include + +#define NUM_CUST_ROT ROTATION_CUSTOM_END - ROTATION_CUSTOM_1 + +struct AP_CustomRotation_params { +public: + AP_CustomRotation_params(); + + static const struct AP_Param::GroupInfo var_info[]; + + AP_Float roll; + AP_Float pitch; + AP_Float yaw; +}; + +class AP_CustomRotation { +public: + AP_CustomRotation(AP_CustomRotation_params &_params); + + void init(); + + Quaternion q; + Matrix3f m; + + AP_CustomRotation_params ¶ms; +}; + +class AP_CustomRotations { +public: + AP_CustomRotations(); + + CLASS_NO_COPY(AP_CustomRotations); + + static AP_CustomRotations *get_singleton(void) { return singleton; } + + void init(); + + void from_rotation(enum Rotation r, QuaternionD &q); + void from_rotation(enum Rotation r, Quaternion &q); + + void rotate(enum Rotation r, Vector3d& v); + void rotate(enum Rotation r, Vector3f& v); + + void convert(Rotation r, float roll, float pitch, float yaw); + void set(Rotation r, float roll, float pitch, float yaw); + + static const struct AP_Param::GroupInfo var_info[]; + +private: + + AP_Int8 enable; + + AP_CustomRotation* get_rotation(Rotation r); + + AP_CustomRotation* rotations[NUM_CUST_ROT]; + + AP_CustomRotation_params params[NUM_CUST_ROT]; + + static AP_CustomRotations *singleton; +}; + +namespace AP { + AP_CustomRotations &custom_rotations(); +}; + diff --git a/libraries/AP_CustomRotations/AP_CustomRotations_params.cpp b/libraries/AP_CustomRotations/AP_CustomRotations_params.cpp new file mode 100644 index 00000000000..07d260d2cbc --- /dev/null +++ b/libraries/AP_CustomRotations/AP_CustomRotations_params.cpp @@ -0,0 +1,36 @@ +#include "AP_CustomRotations.h" +#include + +#if !APM_BUILD_TYPE(APM_BUILD_AP_Periph) + +const AP_Param::GroupInfo AP_CustomRotation_params::var_info[] = { + + // @Param: ROLL + // @DisplayName: Custom roll + // @Description: Custom euler roll, euler 321 (yaw, pitch, roll) ordering + // @Units: deg + // @RebootRequired: True + AP_GROUPINFO("ROLL", 1, AP_CustomRotation_params, roll, 0), + + // @Param: PITCH + // @DisplayName: Custom pitch + // @Description: Custom euler pitch, euler 321 (yaw, pitch, roll) ordering + // @Units: deg + // @RebootRequired: True + AP_GROUPINFO("PITCH", 2, AP_CustomRotation_params, pitch, 0), + + // @Param: YAW + // @DisplayName: Custom yaw + // @Description: Custom euler yaw, euler 321 (yaw, pitch, roll) ordering + // @Units: deg + // @RebootRequired: True + AP_GROUPINFO("YAW", 3, AP_CustomRotation_params, yaw, 0), + + AP_GROUPEND +}; + +AP_CustomRotation_params::AP_CustomRotation_params() { + AP_Param::setup_object_defaults(this, var_info); +} + +#endif // !APM_BUILD_TYPE(APM_BUILD_AP_Periph) diff --git a/libraries/AP_DAL/AP_DAL.h b/libraries/AP_DAL/AP_DAL.h index c5929727313..4c0c945540a 100644 --- a/libraries/AP_DAL/AP_DAL.h +++ b/libraries/AP_DAL/AP_DAL.h @@ -47,6 +47,9 @@ class AP_DAL { unsetTerrainHgtStable = 10, requestYawReset = 11, checkLaneSwitch = 12, + setSourceSet0 = 13, + setSourceSet1 = 14, + setSourceSet2 = 15, }; // must remain the same as AP_AHRS_VehicleClass numbers-wise diff --git a/libraries/AP_DAL/AP_DAL_RangeFinder.cpp b/libraries/AP_DAL/AP_DAL_RangeFinder.cpp index 01e8872de94..d6bb1f506a6 100644 --- a/libraries/AP_DAL/AP_DAL_RangeFinder.cpp +++ b/libraries/AP_DAL/AP_DAL_RangeFinder.cpp @@ -53,7 +53,7 @@ int16_t AP_DAL_RangeFinder::max_distance_cm_orient(enum Rotation orientation) co const auto *rangefinder = AP::rangefinder(); // the EKF only asks for this from a specific orientation. Thankfully. INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); - return rangefinder->ground_clearance_cm_orient(orientation); + return rangefinder->max_distance_cm_orient(orientation); } #endif diff --git a/libraries/AP_Declination/AP_Declination.cpp b/libraries/AP_Declination/AP_Declination.cpp index e68c69a3846..5ff2fce6df0 100644 --- a/libraries/AP_Declination/AP_Declination.cpp +++ b/libraries/AP_Declination/AP_Declination.cpp @@ -36,9 +36,10 @@ bool AP_Declination::get_mag_field_ef(float latitude_deg, float longitude_deg, f { bool valid_input_data = true; - /* round down to nearest sampling resolution */ - int32_t min_lat = static_cast(static_cast(floorf(latitude_deg / SAMPLING_RES)) * SAMPLING_RES); - int32_t min_lon = static_cast(static_cast(floorf(longitude_deg / SAMPLING_RES)) * SAMPLING_RES); + /* round down to nearest sampling resolution. On some platforms (e.g. clang on macOS), + the behaviour of implicit casts from int32 to float can be undefined thus making it explicit here. */ + float min_lat = float(static_cast(static_cast(floorf(latitude_deg / SAMPLING_RES)) * SAMPLING_RES)); + float min_lon = float(static_cast(static_cast(floorf(longitude_deg / SAMPLING_RES)) * SAMPLING_RES)); /* for the rare case of hitting the bounds exactly * the rounding logic wouldn't fit, so enforce it. @@ -46,28 +47,28 @@ bool AP_Declination::get_mag_field_ef(float latitude_deg, float longitude_deg, f /* limit to table bounds - required for maxima even when table spans full globe range */ if (latitude_deg <= SAMPLING_MIN_LAT) { - min_lat = static_cast(SAMPLING_MIN_LAT); + min_lat = float(static_cast(SAMPLING_MIN_LAT)); valid_input_data = false; } if (latitude_deg >= SAMPLING_MAX_LAT) { - min_lat = static_cast(static_cast(latitude_deg / SAMPLING_RES) * SAMPLING_RES - SAMPLING_RES); + min_lat = float(static_cast(static_cast(latitude_deg / SAMPLING_RES) * SAMPLING_RES - SAMPLING_RES)); valid_input_data = false; } if (longitude_deg <= SAMPLING_MIN_LON) { - min_lon = static_cast(SAMPLING_MIN_LON); + min_lon = float(static_cast(SAMPLING_MIN_LON)); valid_input_data = false; } if (longitude_deg >= SAMPLING_MAX_LON) { - min_lon = static_cast(static_cast(longitude_deg / SAMPLING_RES) * SAMPLING_RES - SAMPLING_RES); + min_lon = float(static_cast(static_cast(longitude_deg / SAMPLING_RES) * SAMPLING_RES - SAMPLING_RES)); valid_input_data = false; } /* find index of nearest low sampling point */ - uint32_t min_lat_index = static_cast((-(SAMPLING_MIN_LAT) + min_lat) / SAMPLING_RES); - uint32_t min_lon_index = static_cast((-(SAMPLING_MIN_LON) + min_lon) / SAMPLING_RES); + uint32_t min_lat_index = constrain_int32(static_cast((-(SAMPLING_MIN_LAT) + min_lat) / SAMPLING_RES), 0, LAT_TABLE_SIZE - 2); + uint32_t min_lon_index = constrain_int32(static_cast((-(SAMPLING_MIN_LON) + min_lon) / SAMPLING_RES), 0, LON_TABLE_SIZE -2); /* calculate intensity */ diff --git a/libraries/AP_Declination/AP_Declination.h b/libraries/AP_Declination/AP_Declination.h index a9dec3fea06..2832428f05f 100644 --- a/libraries/AP_Declination/AP_Declination.h +++ b/libraries/AP_Declination/AP_Declination.h @@ -35,7 +35,10 @@ class AP_Declination static const float SAMPLING_MIN_LON; static const float SAMPLING_MAX_LON; - static const float declination_table[19][37]; - static const float inclination_table[19][37]; - static const float intensity_table[19][37]; + static const uint32_t LAT_TABLE_SIZE = 19; + static const uint32_t LON_TABLE_SIZE = 37; + + static const float declination_table[LAT_TABLE_SIZE][LON_TABLE_SIZE]; + static const float inclination_table[LAT_TABLE_SIZE][LON_TABLE_SIZE]; + static const float intensity_table[LAT_TABLE_SIZE][LON_TABLE_SIZE]; }; diff --git a/libraries/AP_Declination/tables.cpp b/libraries/AP_Declination/tables.cpp index 5879f039162..2b1542559fb 100644 --- a/libraries/AP_Declination/tables.cpp +++ b/libraries/AP_Declination/tables.cpp @@ -9,7 +9,7 @@ const float AP_Declination::SAMPLING_MAX_LAT = 90; const float AP_Declination::SAMPLING_MIN_LON = -180; const float AP_Declination::SAMPLING_MAX_LON = 180; -const float AP_Declination::declination_table[19][37] = { +const float AP_Declination::declination_table[LAT_TABLE_SIZE][LON_TABLE_SIZE] = { {149.10950f,139.10950f,129.10950f,119.10950f,109.10949f,99.10950f,89.10950f,79.10950f,69.10950f,59.10950f,49.10950f,39.10950f,29.10950f,19.10950f,9.10950f,-0.89050f,-10.89050f,-20.89050f,-30.89050f,-40.89050f,-50.89050f,-60.89050f,-70.89050f,-80.89050f,-90.89050f,-100.89050f,-110.89050f,-120.89050f,-130.89050f,-140.89050f,-150.89050f,-160.89050f,-170.89050f,179.10950f,169.10950f,159.10950f,149.10950f}, {129.37759f,117.14583f,106.01898f,95.84726f,86.44522f,77.63150f,69.24826f,61.16874f,53.29825f,45.57105f,37.94414f,30.38880f,22.88112f,15.39339f,7.88854f,0.31945f,-7.36677f,-15.22089f,-23.28322f,-31.57827f,-40.11442f,-48.88906f,-57.89765f,-67.14429f,-76.65158f,-86.46832f,-96.67422f,-107.38079f,-118.72599f,-130.85732f,-143.89431f,-157.86353f,-172.61739f,172.21319f,157.16190f,142.76170f,129.37759f}, {85.60184f,77.69003f,71.32207f,65.86993f,60.92414f,56.17033f,51.35320f,46.28164f,40.84704f,35.03587f,28.92623f,22.66416f,16.41848f,10.31921f,4.39763f,-1.44271f,-7.40082f,-13.70324f,-20.51470f,-27.87783f,-35.70713f,-43.83304f,-52.06997f,-60.27655f,-68.39086f,-76.44339f,-84.56374f,-93.00460f,-102.21930f,-113.07088f,-127.37057f,-149.05145f,176.63172f,138.21637f,112.07842f,96.22737f,85.60184f}, @@ -31,7 +31,7 @@ const float AP_Declination::declination_table[19][37] = { {-177.79784f,-167.79784f,-157.79784f,-147.79784f,-137.79784f,-127.79784f,-117.79784f,-107.79784f,-97.79784f,-87.79784f,-77.79784f,-67.79784f,-57.79784f,-47.79784f,-37.79784f,-27.79784f,-17.79784f,-7.79784f,2.20217f,12.20217f,22.20217f,32.20217f,42.20217f,52.20217f,62.20217f,72.20217f,82.20217f,92.20217f,102.20217f,112.20217f,122.20217f,132.20217f,142.20217f,152.20217f,162.20217f,172.20217f,-177.79784f} }; -const float AP_Declination::inclination_table[19][37] = { +const float AP_Declination::inclination_table[LAT_TABLE_SIZE][LON_TABLE_SIZE] = { {-72.08447f,-72.08447f,-72.08447f,-72.08447f,-72.08447f,-72.08447f,-72.08447f,-72.08447f,-72.08447f,-72.08447f,-72.08447f,-72.08447f,-72.08447f,-72.08447f,-72.08447f,-72.08447f,-72.08447f,-72.08447f,-72.08447f,-72.08447f,-72.08447f,-72.08447f,-72.08447f,-72.08447f,-72.08447f,-72.08447f,-72.08447f,-72.08447f,-72.08447f,-72.08447f,-72.08447f,-72.08447f,-72.08447f,-72.08447f,-72.08447f,-72.08447f,-72.08447f}, {-78.33243f,-77.56645f,-76.64486f,-75.60941f,-74.49599f,-73.33711f,-72.16456f,-71.01082f,-69.90877f,-68.88978f,-67.98065f,-67.20063f,-66.55969f,-66.05909f,-65.69426f,-65.45930f,-65.35147f,-65.37404f,-65.53651f,-65.85220f,-66.33408f,-66.99021f,-67.82010f,-68.81276f,-69.94649f,-71.18994f,-72.50361f,-73.84119f,-75.15044f,-76.37388f,-77.45008f,-78.31699f,-78.91913f,-79.21830f,-79.20379f,-78.89480f,-78.33243f}, {-80.91847f,-79.09801f,-77.26826f,-75.41050f,-73.49957f,-71.51974f,-69.48020f,-67.42760f,-65.44927f,-63.66181f,-62.18407f,-61.10090f,-60.43119f,-60.11709f,-60.04466f,-60.08935f,-60.16521f,-60.25535f,-60.41391f,-60.74312f,-61.35672f,-62.34264f,-63.73840f,-65.52698f,-67.65072f,-70.03207f,-72.58967f,-75.24472f,-77.91857f,-80.52353f,-82.93966f,-84.94483f,-86.05606f,-85.75384f,-84.42566f,-82.72116f,-80.91847f}, @@ -53,7 +53,7 @@ const float AP_Declination::inclination_table[19][37] = { {88.07502f,88.07502f,88.07502f,88.07502f,88.07502f,88.07502f,88.07502f,88.07502f,88.07502f,88.07502f,88.07502f,88.07502f,88.07502f,88.07502f,88.07502f,88.07502f,88.07502f,88.07502f,88.07502f,88.07502f,88.07502f,88.07502f,88.07502f,88.07502f,88.07502f,88.07502f,88.07502f,88.07502f,88.07502f,88.07502f,88.07502f,88.07502f,88.07502f,88.07502f,88.07502f,88.07502f,88.07502f} }; -const float AP_Declination::intensity_table[19][37] = { +const float AP_Declination::intensity_table[LAT_TABLE_SIZE][LON_TABLE_SIZE] = { {0.54677f,0.54677f,0.54677f,0.54677f,0.54677f,0.54677f,0.54677f,0.54677f,0.54677f,0.54677f,0.54677f,0.54677f,0.54677f,0.54677f,0.54677f,0.54677f,0.54677f,0.54677f,0.54677f,0.54677f,0.54677f,0.54677f,0.54677f,0.54677f,0.54677f,0.54677f,0.54677f,0.54677f,0.54677f,0.54677f,0.54677f,0.54677f,0.54677f,0.54677f,0.54677f,0.54677f,0.54677f}, {0.60733f,0.60103f,0.59321f,0.58408f,0.57385f,0.56274f,0.55099f,0.53886f,0.52664f,0.51464f,0.50318f,0.49258f,0.48311f,0.47506f,0.46864f,0.46409f,0.46158f,0.46131f,0.46341f,0.46797f,0.47499f,0.48434f,0.49579f,0.50895f,0.52332f,0.53833f,0.55334f,0.56771f,0.58086f,0.59227f,0.60156f,0.60848f,0.61292f,0.61488f,0.61448f,0.61189f,0.60733f}, {0.63154f,0.61845f,0.60363f,0.58729f,0.56950f,0.55031f,0.52986f,0.50843f,0.48660f,0.46508f,0.44473f,0.42628f,0.41025f,0.39690f,0.38632f,0.37857f,0.37385f,0.37260f,0.37540f,0.38291f,0.39557f,0.41347f,0.43621f,0.46292f,0.49236f,0.52306f,0.55344f,0.58192f,0.60704f,0.62760f,0.64283f,0.65244f,0.65659f,0.65582f,0.65087f,0.64254f,0.63154f}, diff --git a/libraries/AP_EFI/AP_EFI.cpp b/libraries/AP_EFI/AP_EFI.cpp index 5e84353aa70..3911cd01784 100644 --- a/libraries/AP_EFI/AP_EFI.cpp +++ b/libraries/AP_EFI/AP_EFI.cpp @@ -20,6 +20,10 @@ #include "AP_EFI_Serial_MS.h" #include "AP_EFI_Serial_Lutan.h" #include "AP_EFI_NWPMU.h" +#include "AP_EFI_DroneCAN.h" +#include "AP_EFI_Currawong_ECU.h" +#include "AP_EFI_Scripting.h" + #include #if HAL_MAX_CAN_PROTOCOL_DRIVERS @@ -33,25 +37,33 @@ const AP_Param::GroupInfo AP_EFI::var_info[] = { // @Param: _TYPE // @DisplayName: EFI communication type // @Description: What method of communication is used for EFI #1 - // @Values: 0:None,1:Serial-MS,2:NWPMU,3:Serial-Lutan + // @Values: 0:None,1:Serial-MS,2:NWPMU,3:Serial-Lutan,5:DroneCAN,6:Currawong-ECU,7:Scripting // @User: Advanced // @RebootRequired: True AP_GROUPINFO_FLAGS("_TYPE", 1, AP_EFI, type, 0, AP_PARAM_FLAG_ENABLE), // @Param: _COEF1 // @DisplayName: EFI Calibration Coefficient 1 - // @Description: Used to calibrate fuel flow for MS protocol (Slope) + // @Description: Used to calibrate fuel flow for MS protocol (Slope). This should be calculated from a log at constant fuel usage rate. Plot (ECYL[0].InjT*EFI.Rpm)/600.0 to get the duty_cycle. Measure actual fuel usage in cm^3/min, and set EFI_COEF1 = fuel_usage_cm3permin / duty_cycle // @Range: 0 1 // @User: Advanced AP_GROUPINFO("_COEF1", 2, AP_EFI, coef1, 0), // @Param: _COEF2 // @DisplayName: EFI Calibration Coefficient 2 - // @Description: Used to calibrate fuel flow for MS protocol (Offset) + // @Description: Used to calibrate fuel flow for MS protocol (Offset). This can be used to correct for a non-zero offset in the fuel consumption calculation of EFI_COEF1 // @Range: 0 10 // @User: Advanced AP_GROUPINFO("_COEF2", 3, AP_EFI, coef2, 0), + // @Param: _FUEL_DENS + // @DisplayName: ECU Fuel Density + // @Description: Used to calculate fuel consumption + // @Units: kg/m/m/m + // @Range: 0 10000 + // @User: Advanced + AP_GROUPINFO("_FUEL_DENS", 4, AP_EFI, ecu_fuel_density, 0), + AP_GROUPEND }; @@ -83,10 +95,25 @@ void AP_EFI::init(void) case Type::NWPMU: #if HAL_EFI_NWPWU_ENABLED backend = new AP_EFI_NWPMU(*this); +#endif + break; + case Type::DroneCAN: +#if HAL_EFI_DRONECAN_ENABLED + backend = new AP_EFI_DroneCAN(*this); +#endif + break; + case Type::CurrawongECU: +#if HAL_EFI_CURRAWONG_ECU_ENABLED + backend = new AP_EFI_Currawong_ECU(*this); +#endif + break; + case Type::SCRIPTING: +#if AP_EFI_SCRIPTING_ENABLED + backend = new AP_EFI_Scripting(*this); #endif break; default: - gcs().send_text(MAV_SEVERITY_INFO, "Unknown EFI type"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Unknown EFI type"); break; } } @@ -96,7 +123,9 @@ void AP_EFI::update() { if (backend) { backend->update(); +#if HAL_LOGGING_ENABLED log_status(); +#endif } } @@ -105,6 +134,7 @@ bool AP_EFI::is_healthy(void) const return (backend && (AP_HAL::millis() - state.last_updated_ms) < HEALTHY_LAST_RECEIVED_MS); } +#if HAL_LOGGING_ENABLED /* write status to log */ @@ -182,7 +212,6 @@ void AP_EFI::log_status(void) uint8_t(state.spark_plug_usage), uint8_t(state.ecu_index)); - for (uint8_t i = 0; i < ENGINE_MAX_CYLINDERS; i++) { // @LoggerMessage: ECYL // @Description: EFI per-cylinder information // @Field: TimeUS: Time since system startup @@ -193,21 +222,21 @@ void AP_EFI::log_status(void) // @Field: EGT: Exhaust gas temperature // @Field: Lambda: Estimated lambda coefficient (dimensionless ratio) // @Field: IDX: Index of the publishing ECU - AP::logger().WriteStreaming("ECYL", - "TimeUS,Inst,IgnT,InjT,CHT,EGT,Lambda,IDX", - "s#dsOO--", - "F-0C0000", - "QBfffffB", - AP_HAL::micros64(), - i, - state.cylinder_status[i].ignition_timing_deg, - state.cylinder_status[i].injection_time_ms, - state.cylinder_status[i].cylinder_head_temperature, - state.cylinder_status[i].exhaust_gas_temperature, - state.cylinder_status[i].lambda_coefficient, - state.ecu_index); - } + AP::logger().WriteStreaming("ECYL", + "TimeUS,Inst,IgnT,InjT,CHT,EGT,Lambda,IDX", + "s#dsOO--", + "F-0C0000", + "QBfffffB", + AP_HAL::micros64(), + 0, + state.cylinder_status.ignition_timing_deg, + state.cylinder_status.injection_time_ms, + state.cylinder_status.cylinder_head_temperature, + state.cylinder_status.exhaust_gas_temperature, + state.cylinder_status.lambda_coefficient, + state.ecu_index); } +#endif // LOGGING_ENABLED /* send EFI_STATUS @@ -230,10 +259,21 @@ void AP_EFI::send_mavlink_status(mavlink_channel_t chan) state.atmospheric_pressure_kpa, state.intake_manifold_pressure_kpa, KELVIN_TO_C(state.intake_manifold_temperature), - KELVIN_TO_C(state.cylinder_status[0].cylinder_head_temperature), - state.cylinder_status[0].ignition_timing_deg, - state.cylinder_status[0].injection_time_ms, - 0, 0, 0); + KELVIN_TO_C(state.cylinder_status.cylinder_head_temperature), + state.cylinder_status.ignition_timing_deg, + state.cylinder_status.injection_time_ms, + KELVIN_TO_C(state.cylinder_status.exhaust_gas_temperature), + state.throttle_out, + state.pt_compensation, + state.ignition_voltage + ); +} + +// get a copy of state structure +void AP_EFI::get_state(EFI_State &_state) +{ + WITH_SEMAPHORE(sem); + _state = state; } namespace AP { diff --git a/libraries/AP_EFI/AP_EFI.h b/libraries/AP_EFI/AP_EFI.h index d5ceadaeb52..1fefdd5972a 100644 --- a/libraries/AP_EFI/AP_EFI.h +++ b/libraries/AP_EFI/AP_EFI.h @@ -15,17 +15,14 @@ #pragma once +#include "AP_EFI_config.h" +#if HAL_EFI_ENABLED #include #include -#include - -#ifndef HAL_EFI_ENABLED -#define HAL_EFI_ENABLED !HAL_MINIMIZE_FEATURES && BOARD_FLASH_SIZE > 1024 -#endif +#include -#if HAL_EFI_ENABLED #include "AP_EFI_Backend.h" #include "AP_EFI_State.h" @@ -66,6 +63,14 @@ class AP_EFI { bool is_healthy() const; + // return timestamp of last update + uint32_t get_last_update_ms(void) const { + return state.last_updated_ms; + } + + // get a copy of state structure + void get_state(EFI_State &state); + // Parameter info static const struct AP_Param::GroupInfo var_info[]; @@ -73,9 +78,12 @@ class AP_EFI { enum class Type : uint8_t { NONE = 0, MegaSquirt = 1, - NWPMU = 2, - Lutan = 3, + NWPMU = 2, + Lutan = 3, // LOWEHEISER = 4, + DroneCAN = 5, + CurrawongECU = 6, + SCRIPTING = 7, }; static AP_EFI *get_singleton(void) { @@ -85,12 +93,18 @@ class AP_EFI { // send EFI_STATUS void send_mavlink_status(mavlink_channel_t chan); +#if AP_SCRIPTING_ENABLED + AP_EFI_Backend* get_backend(uint8_t idx) { return idx==0?backend:nullptr; } +#endif + protected: // Back end Parameters AP_Float coef1; AP_Float coef2; + AP_Float ecu_fuel_density; + EFI_State state; private: @@ -101,6 +115,9 @@ class AP_EFI { AP_EFI_Backend *backend; static AP_EFI *singleton; + // Semaphore for access to shared frontend data + HAL_Semaphore sem; + // write to log void log_status(); }; diff --git a/libraries/AP_EFI/AP_EFI_Backend.cpp b/libraries/AP_EFI/AP_EFI_Backend.cpp index 944ed76bc91..8eff55e857a 100644 --- a/libraries/AP_EFI/AP_EFI_Backend.cpp +++ b/libraries/AP_EFI/AP_EFI_Backend.cpp @@ -28,7 +28,7 @@ AP_EFI_Backend::AP_EFI_Backend(AP_EFI &_frontend) : void AP_EFI_Backend::copy_to_frontend() { - WITH_SEMAPHORE(sem); + WITH_SEMAPHORE(frontend.sem); frontend.state = internal_state; } @@ -41,4 +41,14 @@ float AP_EFI_Backend::get_coef2(void) const { return frontend.coef2; } + +HAL_Semaphore &AP_EFI_Backend::get_sem(void) +{ + return frontend.sem; +} + +float AP_EFI_Backend::get_ecu_fuel_density(void) const +{ + return frontend.ecu_fuel_density; +} #endif // HAL_EFI_ENABLED diff --git a/libraries/AP_EFI/AP_EFI_Backend.h b/libraries/AP_EFI/AP_EFI_Backend.h index 2f48a4694ea..9506c7ff091 100644 --- a/libraries/AP_EFI/AP_EFI_Backend.h +++ b/libraries/AP_EFI/AP_EFI_Backend.h @@ -16,7 +16,7 @@ #include "AP_EFI.h" #include "AP_EFI_State.h" -#include +#include class AP_EFI; //forward declaration @@ -31,19 +31,23 @@ class AP_EFI_Backend { // Update the state structure virtual void update() = 0; +#if AP_SCRIPTING_ENABLED + virtual bool handle_scripting(const EFI_State &efi_state) { return false; } +#endif + protected: // Copies internal state to the frontend state void copy_to_frontend(); - // Semaphore for access to shared frontend data - HAL_Semaphore sem; - // Internal state for this driver (before copying to frontend) EFI_State internal_state; int8_t get_uavcan_node_id(void) const; float get_coef1(void) const; float get_coef2(void) const; + float get_ecu_fuel_density(void) const; + + HAL_Semaphore &get_sem(void); private: AP_EFI &frontend; diff --git a/libraries/AP_EFI/AP_EFI_Currawong_ECU.cpp b/libraries/AP_EFI/AP_EFI_Currawong_ECU.cpp new file mode 100644 index 00000000000..091537807c5 --- /dev/null +++ b/libraries/AP_EFI/AP_EFI_Currawong_ECU.cpp @@ -0,0 +1,106 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +/* + * AP_EFI_Currawong_ECU.cpp + * + * Author: Reilly Callaway / Currawong Engineering Pty Ltd + */ + +#include "AP_EFI_Currawong_ECU.h" + +#if HAL_EFI_CURRAWONG_ECU_ENABLED + +#include +#include +#include + +AP_EFI_Currawong_ECU* AP_EFI_Currawong_ECU::_singleton; + +AP_EFI_Currawong_ECU::AP_EFI_Currawong_ECU(AP_EFI &_frontend) : + AP_EFI_Backend(_frontend) +{ + _singleton = this; + // Indicate that temperature and fuel pressure are supported + internal_state.fuel_pressure_status = Fuel_Pressure_Status::OK; + internal_state.temperature_status = Temperature_Status::OK; +} + +void AP_EFI_Currawong_ECU::update() +{ + // copy the data to the front end + copy_to_frontend(); +} + +bool AP_EFI_Currawong_ECU::handle_message(AP_HAL::CANFrame &frame) +{ + bool valid = true; + + // There are differences between Ardupilot EFI_State and types/scaling of Piccolo packets. + // First decode to Piccolo structs, and then store the data we need in internal_state with any scaling required. + + // Structs to decode Piccolo messages into + ECU_TelemetryFast_t telemetry_fast; + ECU_TelemetrySlow0_t telemetry_slow0; + ECU_TelemetrySlow1_t telemetry_slow1; + ECU_TelemetrySlow2_t telemetry_slow2; + + // Throw the message at the decoding functions + if (decodeECU_TelemetryFastPacketStructure(&frame, &telemetry_fast)) { + internal_state.throttle_position_percent = static_cast(telemetry_fast.throttle); + internal_state.engine_load_percent = static_cast(telemetry_fast.throttle); + internal_state.engine_speed_rpm = static_cast(telemetry_fast.rpm); + + if (internal_state.engine_speed_rpm > 0) { + internal_state.engine_state = Engine_State::RUNNING; + } else { + internal_state.engine_state = Engine_State::STOPPED; + } + + // Prevent div by zero + if (get_ecu_fuel_density() > 0.01) { + internal_state.estimated_consumed_fuel_volume_cm3 = static_cast(telemetry_fast.fuelUsed) / KG_PER_M3_TO_G_PER_CM3(get_ecu_fuel_density()); + } else { + // If no (reasonable) density is provided + internal_state.estimated_consumed_fuel_volume_cm3 = 0.; + } + + internal_state.general_error = telemetry_fast.ecuStatusBits.errorIndicator; + if (!telemetry_fast.ecuStatusBits.enabled) { + internal_state.engine_state = Engine_State::STOPPED; + } + } else if (decodeECU_TelemetrySlow0PacketStructure(&frame, &telemetry_slow0)) { + internal_state.intake_manifold_pressure_kpa = telemetry_slow0.map; + internal_state.atmospheric_pressure_kpa = telemetry_slow0.baro; + internal_state.cylinder_status.cylinder_head_temperature = C_TO_KELVIN(telemetry_slow0.cht); + } else if (decodeECU_TelemetrySlow1PacketStructure(&frame, &telemetry_slow1)) { + internal_state.intake_manifold_temperature = C_TO_KELVIN(telemetry_slow1.mat); + internal_state.fuel_pressure = telemetry_slow1.fuelPressure; + } else if (decodeECU_TelemetrySlow2PacketStructure(&frame, &telemetry_slow2)) { + internal_state.cylinder_status.ignition_timing_deg = telemetry_slow2.ignAngle1; + + internal_state.fuel_consumption_rate_cm3pm = telemetry_slow2.flowRate / KG_PER_M3_TO_G_PER_CM3(get_ecu_fuel_density()); + } else { + valid = false; + } + + if (valid) { + internal_state.last_updated_ms = AP_HAL::millis(); + } + + return valid; +} + +#endif // HAL_EFI_CURRAWONG_ECU_ENABLED diff --git a/libraries/AP_EFI/AP_EFI_Currawong_ECU.h b/libraries/AP_EFI/AP_EFI_Currawong_ECU.h new file mode 100644 index 00000000000..89387e9dd4e --- /dev/null +++ b/libraries/AP_EFI/AP_EFI_Currawong_ECU.h @@ -0,0 +1,53 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +/* + * AP_EFI_Currawong_ECU.h + * + * Author: Reilly Callaway / Currawong Engineering Pty Ltd + */ + +#pragma once + +#include "AP_EFI.h" +#include "AP_EFI_Backend.h" + +#ifndef HAL_EFI_CURRAWONG_ECU_ENABLED +#define HAL_EFI_CURRAWONG_ECU_ENABLED HAL_MAX_CAN_PROTOCOL_DRIVERS && (BOARD_FLASH_SIZE > 1024) +#endif + +#if HAL_EFI_CURRAWONG_ECU_ENABLED + +class AP_EFI_Currawong_ECU : public AP_EFI_Backend { +public: + AP_EFI_Currawong_ECU(AP_EFI &_frontend); + + void update() override; + + static AP_EFI_Currawong_ECU* get_instance(void) + { + return _singleton; + } + +private: + bool handle_message(AP_HAL::CANFrame &frame); + + static AP_EFI_Currawong_ECU* _singleton; + + friend class AP_PiccoloCAN; +}; + +#endif // HAL_EFI_CURRAWONG_ECU_ENABLED + diff --git a/libraries/AP_EFI/AP_EFI_DroneCAN.cpp b/libraries/AP_EFI/AP_EFI_DroneCAN.cpp new file mode 100644 index 00000000000..50388c15080 --- /dev/null +++ b/libraries/AP_EFI/AP_EFI_DroneCAN.cpp @@ -0,0 +1,169 @@ +#include + +#include "AP_EFI_DroneCAN.h" + +#if HAL_EFI_DRONECAN_ENABLED + +#include +#include + +#include + +extern const AP_HAL::HAL& hal; + +AP_EFI_DroneCAN *AP_EFI_DroneCAN::driver; + +// DroneCAN Frontend Registry Binder +UC_REGISTRY_BINDER(EFIStatusCb, uavcan::equipment::ice::reciprocating::Status); + +// constructor +AP_EFI_DroneCAN::AP_EFI_DroneCAN(AP_EFI &_frontend) : + AP_EFI_Backend(_frontend) +{ + driver = this; +} + +// links the DroneCAN message to this backend +void AP_EFI_DroneCAN::subscribe_msgs(AP_UAVCAN *ap_uavcan) +{ + if (ap_uavcan == nullptr) { + return; + } + auto* node = ap_uavcan->get_node(); + + uavcan::Subscriber *status_listener; + status_listener = new uavcan::Subscriber(*node); + + // Register method to handle incoming status + const int status_listener_res = status_listener->start(EFIStatusCb(ap_uavcan, &trampoline_status)); + if (status_listener_res < 0) { + AP_HAL::panic("DroneCAN EFI subscriber start problem\n\r"); + return; + } +} + +// Called from frontend to update with the readings received by handler +void AP_EFI_DroneCAN::update() +{ +} + +// EFI message handler +void AP_EFI_DroneCAN::trampoline_status(AP_UAVCAN *ap_uavcan, uint8_t node_id, const EFIStatusCb &cb) +{ + if (driver == nullptr) { + return; + } + const uavcan::equipment::ice::reciprocating::Status &pkt = *cb.msg; + driver->handle_status(pkt); +} + +/* + handle reciprocating ICE status message from DroneCAN + */ +void AP_EFI_DroneCAN::handle_status(const uavcan::equipment::ice::reciprocating::Status &pkt) +{ + auto &istate = internal_state; + + // state maps 1:1 from Engine_State + istate.engine_state = Engine_State(pkt.state); + + if (!(pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_CRANKSHAFT_SENSOR_ERROR_SUPPORTED)) { + istate.crankshaft_sensor_status = Crankshaft_Sensor_Status::NOT_SUPPORTED; + } else if (pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_CRANKSHAFT_SENSOR_ERROR) { + istate.crankshaft_sensor_status = Crankshaft_Sensor_Status::ERROR; + } else { + istate.crankshaft_sensor_status = Crankshaft_Sensor_Status::OK; + } + + if (!(pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_TEMPERATURE_SUPPORTED)) { + istate.temperature_status = Temperature_Status::NOT_SUPPORTED; + } else if (pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_TEMPERATURE_BELOW_NOMINAL) { + istate.temperature_status = Temperature_Status::BELOW_NOMINAL; + } else if (pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_TEMPERATURE_ABOVE_NOMINAL) { + istate.temperature_status = Temperature_Status::ABOVE_NOMINAL; + } else if (pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_TEMPERATURE_OVERHEATING) { + istate.temperature_status = Temperature_Status::OVERHEATING; + } else if (pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_TEMPERATURE_EGT_ABOVE_NOMINAL) { + istate.temperature_status = Temperature_Status::EGT_ABOVE_NOMINAL; + } else { + istate.temperature_status = Temperature_Status::OK; + } + + if (!(pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_FUEL_PRESSURE_SUPPORTED)) { + istate.fuel_pressure_status = Fuel_Pressure_Status::NOT_SUPPORTED; + } else if (pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_FUEL_PRESSURE_BELOW_NOMINAL) { + istate.fuel_pressure_status = Fuel_Pressure_Status::BELOW_NOMINAL; + } else if (pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_FUEL_PRESSURE_ABOVE_NOMINAL) { + istate.fuel_pressure_status = Fuel_Pressure_Status::ABOVE_NOMINAL; + } else { + istate.fuel_pressure_status = Fuel_Pressure_Status::OK; + } + + if (!(pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_OIL_PRESSURE_SUPPORTED)) { + istate.oil_pressure_status = Oil_Pressure_Status::NOT_SUPPORTED; + } else if (pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_OIL_PRESSURE_BELOW_NOMINAL) { + istate.oil_pressure_status = Oil_Pressure_Status::BELOW_NOMINAL; + } else if (pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_OIL_PRESSURE_ABOVE_NOMINAL) { + istate.oil_pressure_status = Oil_Pressure_Status::ABOVE_NOMINAL; + } else { + istate.oil_pressure_status = Oil_Pressure_Status::OK; + } + + if (!(pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_DETONATION_SUPPORTED)) { + istate.detonation_status = Detonation_Status::NOT_SUPPORTED; + } else if (pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_DETONATION_OBSERVED) { + istate.detonation_status = Detonation_Status::OBSERVED; + } else { + istate.detonation_status = Detonation_Status::NOT_OBSERVED; + } + + if (!(pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_MISFIRE_SUPPORTED)) { + istate.misfire_status = Misfire_Status::NOT_SUPPORTED; + } else if (pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_MISFIRE_OBSERVED) { + istate.misfire_status = Misfire_Status::OBSERVED; + } else { + istate.misfire_status = Misfire_Status::NOT_OBSERVED; + } + + if (!(pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_DEBRIS_SUPPORTED)) { + istate.debris_status = Debris_Status::NOT_SUPPORTED; + } else if (pkt.flags & uavcan::equipment::ice::reciprocating::Status::FLAG_DEBRIS_DETECTED) { + istate.debris_status = Debris_Status::DETECTED; + } else { + istate.debris_status = Debris_Status::NOT_DETECTED; + } + + istate.engine_load_percent = pkt.engine_load_percent; + istate.engine_speed_rpm = pkt.engine_speed_rpm; + istate.spark_dwell_time_ms = pkt.spark_dwell_time_ms; + istate.atmospheric_pressure_kpa = pkt.atmospheric_pressure_kpa; + istate.intake_manifold_pressure_kpa = pkt.intake_manifold_pressure_kpa; + istate.intake_manifold_temperature = pkt.intake_manifold_temperature; + istate.coolant_temperature = pkt.coolant_temperature; + istate.oil_pressure = pkt.oil_pressure; + istate.oil_temperature = pkt.oil_temperature; + istate.fuel_pressure = pkt.fuel_pressure; + istate.fuel_consumption_rate_cm3pm = pkt.fuel_consumption_rate_cm3pm; + istate.estimated_consumed_fuel_volume_cm3 = pkt.estimated_consumed_fuel_volume_cm3; + istate.throttle_position_percent = pkt.throttle_position_percent; + istate.ecu_index = pkt.ecu_index; + + // 1:1 for spark plug usage + istate.spark_plug_usage = Spark_Plug_Usage(pkt.spark_plug_usage); + + // assume max one cylinder status + if (pkt.cylinder_status.size() > 0) { + const auto &cs = pkt.cylinder_status[0]; + auto &c = istate.cylinder_status; + c.ignition_timing_deg = cs.ignition_timing_deg; + c.injection_time_ms = cs.injection_time_ms; + c.cylinder_head_temperature = cs.cylinder_head_temperature; + c.exhaust_gas_temperature = cs.exhaust_gas_temperature; + c.lambda_coefficient = cs.lambda_coefficient; + } + + copy_to_frontend(); +} + +#endif // HAL_EFI_DRONECAN_ENABLED + diff --git a/libraries/AP_EFI/AP_EFI_DroneCAN.h b/libraries/AP_EFI/AP_EFI_DroneCAN.h new file mode 100644 index 00000000000..35c02d5e376 --- /dev/null +++ b/libraries/AP_EFI/AP_EFI_DroneCAN.h @@ -0,0 +1,32 @@ +#pragma once + +#include "AP_EFI.h" +#include "AP_EFI_Backend.h" + +#ifndef HAL_EFI_DRONECAN_ENABLED +#define HAL_EFI_DRONECAN_ENABLED HAL_MAX_CAN_PROTOCOL_DRIVERS && BOARD_FLASH_SIZE > 1024 && HAL_CANMANAGER_ENABLED +#endif + +#if HAL_EFI_DRONECAN_ENABLED +#include +#include + +class EFIStatusCb; + +class AP_EFI_DroneCAN : public AP_EFI_Backend { +public: + AP_EFI_DroneCAN(AP_EFI &_frontend); + + void update() override; + + static void subscribe_msgs(AP_UAVCAN* ap_uavcan); + static void trampoline_status(AP_UAVCAN* ap_uavcan, uint8_t node_id, const EFIStatusCb &cb); + +private: + void handle_status(const uavcan::equipment::ice::reciprocating::Status &pkt); + + // singleton for trampoline + static AP_EFI_DroneCAN *driver; +}; +#endif // HAL_EFI_DRONECAN_ENABLED + diff --git a/libraries/AP_EFI/AP_EFI_NWPMU.cpp b/libraries/AP_EFI/AP_EFI_NWPMU.cpp index 00bc9d33d34..3c0316772c5 100644 --- a/libraries/AP_EFI/AP_EFI_NWPMU.cpp +++ b/libraries/AP_EFI/AP_EFI_NWPMU.cpp @@ -36,7 +36,7 @@ void AP_EFI_NWPMU::handle_frame(AP_HAL::CANFrame &frame) { const uint32_t id = frame.id & AP_HAL::CANFrame::MaskExtID; - WITH_SEMAPHORE(sem); + WITH_SEMAPHORE(get_sem()); switch ((NWPMU_ID)id) { case NWPMU_ID::ECU_1: { @@ -45,7 +45,7 @@ void AP_EFI_NWPMU::handle_frame(AP_HAL::CANFrame &frame) memcpy(&data, frame.data, sizeof(data)); internal_state.engine_speed_rpm = data.rpm; internal_state.throttle_position_percent = data.tps * 0.1f; - internal_state.cylinder_status[0].ignition_timing_deg = data.ignition_angle * 0.1f; + internal_state.cylinder_status.ignition_timing_deg = data.ignition_angle * 0.1f; break; } @@ -65,7 +65,7 @@ void AP_EFI_NWPMU::handle_frame(AP_HAL::CANFrame &frame) default: break; } - internal_state.cylinder_status[0].lambda_coefficient = data.lambda * 0.01f; + internal_state.cylinder_status.lambda_coefficient = data.lambda * 0.01f; break; } @@ -87,11 +87,11 @@ void AP_EFI_NWPMU::handle_frame(AP_HAL::CANFrame &frame) switch((NWPMU_TEMPERATURE_TYPE)data.temp_type) { case NWPMU_TEMPERATURE_TYPE::C: internal_state.coolant_temperature = C_TO_KELVIN(data.coolant_temp * 0.1f); - internal_state.cylinder_status[0].cylinder_head_temperature = C_TO_KELVIN(data.coolant_temp * 0.1f); + internal_state.cylinder_status.cylinder_head_temperature = C_TO_KELVIN(data.coolant_temp * 0.1f); break; case NWPMU_TEMPERATURE_TYPE::F: internal_state.coolant_temperature = F_TO_KELVIN(data.coolant_temp * 0.1f); - internal_state.cylinder_status[0].cylinder_head_temperature = F_TO_KELVIN(data.coolant_temp * 0.1f); + internal_state.cylinder_status.cylinder_head_temperature = F_TO_KELVIN(data.coolant_temp * 0.1f); break; default: break; @@ -104,7 +104,7 @@ void AP_EFI_NWPMU::handle_frame(AP_HAL::CANFrame &frame) struct ecu_6 data; memcpy(&data, frame.data, sizeof(data)); if (!_emitted_version && (AP_HAL::millis() > 10000)) { // don't emit a version early in the boot process - gcs().send_text(MAV_SEVERITY_INFO, "NWPMU Version: %d.%d.%d", + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "NWPMU Version: %d.%d.%d", data.firmware_major, data.firmware_minor, data.firmware_build); diff --git a/libraries/AP_EFI/AP_EFI_Scripting.cpp b/libraries/AP_EFI/AP_EFI_Scripting.cpp new file mode 100644 index 00000000000..8a4b2f73a0b --- /dev/null +++ b/libraries/AP_EFI/AP_EFI_Scripting.cpp @@ -0,0 +1,19 @@ +#include "AP_EFI_Scripting.h" + +#if AP_EFI_SCRIPTING_ENABLED + +// Called from frontend to update with the readings received by handler +void AP_EFI_Scripting::update() +{ + // Nothing to do here +} + +// handle EFI message from scripting +bool AP_EFI_Scripting::handle_scripting(const EFI_State &efi_state) +{ + internal_state = efi_state; + copy_to_frontend(); + return true; +} + +#endif // AP_EFI_SCRIPTING_ENABLED diff --git a/libraries/AP_EFI/AP_EFI_Scripting.h b/libraries/AP_EFI/AP_EFI_Scripting.h new file mode 100644 index 00000000000..4bd5ed1f908 --- /dev/null +++ b/libraries/AP_EFI/AP_EFI_Scripting.h @@ -0,0 +1,16 @@ +#pragma once + +#include "AP_EFI.h" +#include "AP_EFI_Backend.h" + +#if AP_EFI_SCRIPTING_ENABLED + +class AP_EFI_Scripting : public AP_EFI_Backend { +public: + using AP_EFI_Backend::AP_EFI_Backend; + + void update() override; + + bool handle_scripting(const EFI_State &efi_state) override; +}; +#endif // AP_EFI_SCRIPTING_ENABLED diff --git a/libraries/AP_EFI/AP_EFI_Serial_Lutan.cpp b/libraries/AP_EFI/AP_EFI_Serial_Lutan.cpp index 1d0141d6bef..3812c69abdd 100644 --- a/libraries/AP_EFI/AP_EFI_Serial_Lutan.cpp +++ b/libraries/AP_EFI/AP_EFI_Serial_Lutan.cpp @@ -16,11 +16,17 @@ #include #include "AP_EFI_Serial_Lutan.h" #include -#include #if HAL_EFI_ENABLED + +#include + +#include #include +// RPM Threshold for fuel consumption estimator +#define RPM_THRESHOLD 100 + extern const AP_HAL::HAL &hal; AP_EFI_Serial_Lutan::AP_EFI_Serial_Lutan(AP_EFI &_frontend): @@ -47,9 +53,9 @@ void AP_EFI_Serial_Lutan::update() if (n + pkt_nbytes > sizeof(pkt)) { pkt_nbytes = 0; } - const ssize_t nread = port->read(&pkt[pkt_nbytes], n); - if (nread <= 0) { - return; + ssize_t nread = port->read(&pkt[pkt_nbytes], n); + if (nread < 0) { + nread = 0; } pkt_nbytes += nread; if (pkt_nbytes > 2) { @@ -60,23 +66,32 @@ void AP_EFI_Serial_Lutan::update() const uint32_t crc2 = ~crc_crc32(~0U, &pkt[2], length); if (crc == crc2) { // valid data - internal_state.last_updated_ms = now; internal_state.spark_dwell_time_ms = int16_t(be16toh(data.dwell))*0.1; - internal_state.cylinder_status[0].injection_time_ms = be16toh(data.pulseWidth1)*0.00666; + internal_state.cylinder_status.injection_time_ms = be16toh(data.pulseWidth1)*0.00666; internal_state.engine_speed_rpm = be16toh(data.rpm); internal_state.atmospheric_pressure_kpa = int16_t(be16toh(data.barometer))*0.1; internal_state.intake_manifold_pressure_kpa = int16_t(be16toh(data.map))*0.1; internal_state.intake_manifold_temperature = degF_to_Kelvin(int16_t(be16toh(data.mat))*0.1); internal_state.coolant_temperature = degF_to_Kelvin(int16_t(be16toh(data.coolant))*0.1); // CHT is in coolant field - internal_state.cylinder_status[0].cylinder_head_temperature = internal_state.coolant_temperature; + internal_state.cylinder_status.cylinder_head_temperature = internal_state.coolant_temperature; internal_state.throttle_position_percent = int16_t(be16toh(data.tps))*0.1; + + // integrate fuel consumption + if (internal_state.engine_speed_rpm > RPM_THRESHOLD) { + const float duty_cycle = (internal_state.cylinder_status.injection_time_ms * internal_state.engine_speed_rpm)/600.0f; + internal_state.fuel_consumption_rate_cm3pm = duty_cycle*get_coef1() - get_coef2(); + internal_state.estimated_consumed_fuel_volume_cm3 += internal_state.fuel_consumption_rate_cm3pm * (now - internal_state.last_updated_ms)/60000.0f; + } else { + internal_state.fuel_consumption_rate_cm3pm = 0; + } + internal_state.last_updated_ms = now; copy_to_frontend(); } pkt_nbytes = 0; } } - if (n == 0 || now - last_request_ms > 200) { + if (now - last_request_ms > 200) { last_request_ms = now; port->discard_input(); send_request(); diff --git a/libraries/AP_EFI/AP_EFI_Serial_MS.cpp b/libraries/AP_EFI/AP_EFI_Serial_MS.cpp index f5820fa272e..d5e144e6546 100644 --- a/libraries/AP_EFI/AP_EFI_Serial_MS.cpp +++ b/libraries/AP_EFI/AP_EFI_Serial_MS.cpp @@ -17,6 +17,7 @@ #include "AP_EFI_Serial_MS.h" #if HAL_EFI_ENABLED +#include #include extern const AP_HAL::HAL &hal; @@ -80,12 +81,12 @@ bool AP_EFI_Serial_MS::read_incoming_realtime_data() } // Iterate over the payload bytes - for ( uint8_t offset=RT_FIRST_OFFSET; offset < (RT_FIRST_OFFSET + message_length - 1); offset++) { + for (uint16_t offset=RT_FIRST_OFFSET; offset < (RT_FIRST_OFFSET + message_length - 1); offset++) { uint8_t data = read_byte_CRC32(); float temp_float; switch (offset) { case PW1_MSB: - internal_state.cylinder_status[0].injection_time_ms = (float)((data << 8) + read_byte_CRC32())/1000.0f; + internal_state.cylinder_status.injection_time_ms = (float)((data << 8) + read_byte_CRC32())/1000.0f; offset++; // increment the counter because we read a byte in the previous line break; case RPM_MSB: @@ -94,7 +95,7 @@ bool AP_EFI_Serial_MS::read_incoming_realtime_data() offset++; break; case ADVANCE_MSB: - internal_state.cylinder_status[0].ignition_timing_deg = (float)((data << 8) + read_byte_CRC32())/10.0f; + internal_state.cylinder_status.ignition_timing_deg = (float)((data << 8) + read_byte_CRC32())/10.0f; offset++; break; case ENGINE_BM: @@ -115,7 +116,7 @@ bool AP_EFI_Serial_MS::read_incoming_realtime_data() case CHT_MSB: temp_float = (float)((data << 8) + read_byte_CRC32())/10.0f; offset++; - internal_state.cylinder_status[0].cylinder_head_temperature = degF_to_Kelvin(temp_float); + internal_state.cylinder_status.cylinder_head_temperature = degF_to_Kelvin(temp_float); break; case TPS_MSB: temp_float = (float)((data << 8) + read_byte_CRC32())/10.0f; @@ -125,7 +126,7 @@ bool AP_EFI_Serial_MS::read_incoming_realtime_data() case AFR1_MSB: temp_float = (float)((data << 8) + read_byte_CRC32())/10.0f; offset++; - internal_state.cylinder_status[0].lambda_coefficient = temp_float; + internal_state.cylinder_status.lambda_coefficient = temp_float; break; case DWELL_MSB: temp_float = (float)((data << 8) + read_byte_CRC32())/10.0f; @@ -159,7 +160,7 @@ bool AP_EFI_Serial_MS::read_incoming_realtime_data() // Calculate Fuel Consumption // Duty Cycle (Percent, because that's how HFE gives us the calibration coefficients) - float duty_cycle = (internal_state.cylinder_status[0].injection_time_ms * internal_state.engine_speed_rpm)/600.0f; + float duty_cycle = (internal_state.cylinder_status.injection_time_ms * internal_state.engine_speed_rpm)/600.0f; uint32_t current_time = AP_HAL::millis(); // Super Simplified integration method - Error Analysis TBD // This calculation gives erroneous results when the engine isn't running diff --git a/libraries/AP_EFI/AP_EFI_State.h b/libraries/AP_EFI/AP_EFI_State.h index ccaf491584b..6b0abc93d21 100644 --- a/libraries/AP_EFI/AP_EFI_State.h +++ b/libraries/AP_EFI/AP_EFI_State.h @@ -17,7 +17,6 @@ #define EFI_MAX_INSTANCES 2 #define EFI_MAX_BACKENDS 2 -#define ENGINE_MAX_CYLINDERS 1 #include #include @@ -61,10 +60,10 @@ enum class Fuel_Pressure_Status : uint8_t { }; enum class Oil_Pressure_Status : uint8_t { - OIL_PRESSURE_STATUS_NOT_SUPPORTED = 0, - OIL_PRESSURE_OK = 1, - OIL_PRESSURE_BELOW_NOMINAL = 2, - OIL_PRESSURE_ABOVE_NOMINAL = 3 + NOT_SUPPORTED = 0, + OK = 1, + BELOW_NOMINAL = 2, + ABOVE_NOMINAL = 3 }; enum class Detonation_Status : uint8_t { @@ -197,6 +196,14 @@ struct EFI_State { Spark_Plug_Usage spark_plug_usage; // Status for each cylinder in the engine - Cylinder_Status cylinder_status[ENGINE_MAX_CYLINDERS]; + Cylinder_Status cylinder_status; + + // ignition voltage in Volts + float ignition_voltage; + + // throttle output percentage + float throttle_out; + // PT compensation + float pt_compensation; }; diff --git a/libraries/AP_EFI/AP_EFI_config.h b/libraries/AP_EFI/AP_EFI_config.h new file mode 100644 index 00000000000..37669582f63 --- /dev/null +++ b/libraries/AP_EFI/AP_EFI_config.h @@ -0,0 +1,11 @@ +#pragma once + +#include + +#ifndef HAL_EFI_ENABLED +#define HAL_EFI_ENABLED !HAL_MINIMIZE_FEATURES && BOARD_FLASH_SIZE > 1024 +#endif + +#ifndef AP_EFI_SCRIPTING_ENABLED +#define AP_EFI_SCRIPTING_ENABLED (HAL_EFI_ENABLED && AP_SCRIPTING_ENABLED) +#endif diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp b/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp index 9d68b67e89c..b0ee54c5d98 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp @@ -24,14 +24,31 @@ //#define ESC_TELEM_DEBUG +#define ESC_RPM_CHECK_TIMEOUT_US 100000UL // timeout for motor running validity + extern const AP_HAL::HAL& hal; +// table of user settable parameters +const AP_Param::GroupInfo AP_ESC_Telem::var_info[] = { + + // @Param: _MAV_OFS + // @DisplayName: ESC Telemetry mavlink offset + // @Description: Offset to apply to ESC numbers when reporting as ESC_TELEMETRY packets over MAVLink. This allows high numbered motors to be displayed as low numbered ESCs for convenience on GCS displays. A value of 4 would send ESC on output 5 as ESC number 1 in ESC_TELEMETRY packets + // @Increment: 1 + // @Range: 0 31 + // @User: Standard + AP_GROUPINFO("_MAV_OFS", 1, AP_ESC_Telem, mavlink_offset, 0), + + AP_GROUPEND +}; + AP_ESC_Telem::AP_ESC_Telem() { if (_singleton) { AP_HAL::panic("Too many AP_ESC_Telem instances"); } _singleton = this; + AP_Param::setup_object_defaults(this, var_info); } // return the average motor RPM @@ -64,10 +81,14 @@ uint8_t AP_ESC_Telem::get_motor_frequencies_hz(uint8_t nfreqs, float* freqs) con uint8_t valid_escs = 0; // average the rpm of each motor as reported by BLHeli and convert to Hz - for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS && i < nfreqs; i++) { + for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS && valid_escs < nfreqs; i++) { float rpm; if (get_rpm(i, rpm)) { freqs[valid_escs++] = rpm * (1.0f / 60.0f); + } else if (_rpm_data[i].last_update_us > 0) { + // if we have ever received data on an ESC, mark it as valid but with no data + // this prevents large frequency shifts when ESCs disappear + freqs[valid_escs++] = 0.0f; } } @@ -76,8 +97,8 @@ uint8_t AP_ESC_Telem::get_motor_frequencies_hz(uint8_t nfreqs, float* freqs) con // get mask of ESCs that sent valid telemetry data in the last // ESC_TELEM_DATA_TIMEOUT_MS -uint16_t AP_ESC_Telem::get_active_esc_mask() const { - uint16_t ret = 0; +uint32_t AP_ESC_Telem::get_active_esc_mask() const { + uint32_t ret = 0; const uint32_t now = AP_HAL::millis(); for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) { if (now - _telem_data[i].last_update_ms >= ESC_TELEM_DATA_TIMEOUT_MS) { @@ -94,10 +115,44 @@ uint16_t AP_ESC_Telem::get_active_esc_mask() const { // return number of active ESCs present uint8_t AP_ESC_Telem::get_num_active_escs() const { - uint16_t active = get_active_esc_mask(); + uint32_t active = get_active_esc_mask(); return __builtin_popcount(active); } +// return the whether all the motors in servo_channel_mask are running +bool AP_ESC_Telem::are_motors_running(uint32_t servo_channel_mask, float min_rpm) const +{ + const uint32_t now = AP_HAL::micros(); + + for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) { + if (BIT_IS_SET(servo_channel_mask, i)) { + const volatile AP_ESC_Telem_Backend::RpmData& rpmdata = _rpm_data[i]; + // we choose a relatively strict measure of health so that failsafe actions can rely on the results + if (now < rpmdata.last_update_us || now - rpmdata.last_update_us > ESC_RPM_CHECK_TIMEOUT_US) { + return false; + } + if (rpmdata.rpm < min_rpm) { + return false; + } + } + } + return true; +} + +// is telemetry active for the provided channel mask +bool AP_ESC_Telem::is_telemetry_active(uint32_t servo_channel_mask) const +{ + for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) { + if (BIT_IS_SET(servo_channel_mask, i)) { + // no data received + if (get_last_telem_data_ms(i) == 0 && _rpm_data[i].last_update_us == 0) { + return false; + } + } + } + return true; +} + // get an individual ESC's slewed rpm if available, returns true on success bool AP_ESC_Telem::get_rpm(uint8_t esc_index, float& rpm) const { @@ -116,6 +171,13 @@ bool AP_ESC_Telem::get_rpm(uint8_t esc_index, float& rpm) const && (now - rpmdata.last_update_us < ESC_RPM_DATA_TIMEOUT_US)) { const float slew = MIN(1.0f, (now - rpmdata.last_update_us) * rpmdata.update_rate_hz * (1.0f / 1e6f)); rpm = (rpmdata.prev_rpm + (rpmdata.rpm - rpmdata.prev_rpm) * slew); + +#if AP_SCRIPTING_ENABLED + if ((1U< ESC_TELEM_DATA_TIMEOUT_MS \ - && now_us - _rpm_data[idx].last_update_us > ESC_RPM_DATA_TIMEOUT_US) - // skip this group of ESCs if no data to send - if (ESC_DATA_STALE(i * 4) && ESC_DATA_STALE(i * 4 + 1) && ESC_DATA_STALE(i * 4 + 2) && ESC_DATA_STALE(i * 4 + 3)) { + bool all_stale = true; + for (uint8_t j=0; j<4; j++) { + const uint8_t esc_id = (i * 4 + j) + esc_offset; + if (esc_id < ESC_TELEM_MAX_ESCS && + (now - _telem_data[esc_id].last_update_ms <= ESC_TELEM_DATA_TIMEOUT_MS || + now_us - _rpm_data[esc_id].last_update_us <= ESC_RPM_DATA_TIMEOUT_US)) { + all_stale = false; + break; + } + } + if (all_stale) { + // skip this group of ESCs if no data to send continue; } + // arrays to hold output - uint8_t temperature[4] {}; - uint16_t voltage[4] {}; - uint16_t current[4] {}; - uint16_t current_tot[4] {}; - uint16_t rpm[4] {}; - uint16_t count[4] {}; + mavlink_esc_telemetry_1_to_4_t s {}; // fill in output arrays for (uint8_t j = 0; j < 4; j++) { - const uint8_t esc_id = i * 4 + j; - temperature[j] = _telem_data[esc_id].temperature_cdeg / 100; - voltage[j] = constrain_float(_telem_data[esc_id].voltage * 100.0f, 0, UINT16_MAX); - current[j] = constrain_float(_telem_data[esc_id].current * 100.0f, 0, UINT16_MAX); - current_tot[j] = constrain_float(_telem_data[esc_id].consumption_mah, 0, UINT16_MAX); + const uint8_t esc_id = (i * 4 + j) + esc_offset; + if (esc_id >= ESC_TELEM_MAX_ESCS) { + continue; + } + + s.temperature[j] = _telem_data[esc_id].temperature_cdeg / 100; + s.voltage[j] = constrain_float(_telem_data[esc_id].voltage * 100.0f, 0, UINT16_MAX); + s.current[j] = constrain_float(_telem_data[esc_id].current * 100.0f, 0, UINT16_MAX); + s.totalcurrent[j] = constrain_float(_telem_data[esc_id].consumption_mah, 0, UINT16_MAX); float rpmf = 0.0f; if (get_rpm(esc_id, rpmf)) { - rpm[j] = constrain_float(rpmf, 0, UINT16_MAX); - } else { - rpm[j] = 0; + s.rpm[j] = constrain_float(rpmf, 0, UINT16_MAX); } - count[j] = _telem_data[esc_id].count; + s.count[j] = _telem_data[esc_id].count; } + // make sure a msg hasn't been extended + static_assert(MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN == MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN && + MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN == MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN && + MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN == MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_LEN && + MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN == MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_LEN && + MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN == MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_LEN && + MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN == MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_LEN && + MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN == MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_LEN && + MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN == MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_LEN, + "telem messages not compatible"); + + const mavlink_channel_t chan = (mavlink_channel_t)mav_chan; // send messages switch (i) { case 0: - mavlink_msg_esc_telemetry_1_to_4_send((mavlink_channel_t)mav_chan, temperature, voltage, current, current_tot, rpm, count); + mavlink_msg_esc_telemetry_1_to_4_send_struct(chan, &s); break; case 1: - mavlink_msg_esc_telemetry_5_to_8_send((mavlink_channel_t)mav_chan, temperature, voltage, current, current_tot, rpm, count); + mavlink_msg_esc_telemetry_5_to_8_send_struct(chan, (const mavlink_esc_telemetry_5_to_8_t *)&s); break; case 2: - mavlink_msg_esc_telemetry_9_to_12_send((mavlink_channel_t)mav_chan, temperature, voltage, current, current_tot, rpm, count); + mavlink_msg_esc_telemetry_9_to_12_send_struct(chan, (const mavlink_esc_telemetry_9_to_12_t *)&s); + break; + case 3: + mavlink_msg_esc_telemetry_13_to_16_send_struct(chan, (const mavlink_esc_telemetry_13_to_16_t *)&s); break; - default: +#if ESC_TELEM_MAX_ESCS > 16 + case 4: + mavlink_msg_esc_telemetry_17_to_20_send_struct(chan, (const mavlink_esc_telemetry_17_to_20_t *)&s); break; + case 5: + mavlink_msg_esc_telemetry_21_to_24_send_struct(chan, (const mavlink_esc_telemetry_21_to_24_t *)&s); + break; + case 6: + mavlink_msg_esc_telemetry_25_to_28_send_struct(chan, (const mavlink_esc_telemetry_25_to_28_t *)&s); + break; + case 7: + mavlink_msg_esc_telemetry_29_to_32_send_struct(chan, (const mavlink_esc_telemetry_29_to_32_t *)&s); + break; +#endif } } + // we checked for all sends without running out of buffer space, + // start at zero next time + next_idx = 0; + #endif // HAL_GCS_ENABLED } @@ -341,7 +443,7 @@ void AP_ESC_Telem::update_telem_data(const uint8_t esc_index, const AP_ESC_Telem // record an update to the RPM together with timestamp, this allows the notch values to be slewed // this should be called by backends when new telemetry values are available -void AP_ESC_Telem::update_rpm(const uint8_t esc_index, const uint16_t new_rpm, const float error_rate) +void AP_ESC_Telem::update_rpm(const uint8_t esc_index, const float new_rpm, const float error_rate) { if (esc_index >= ESC_TELEM_MAX_ESCS) { return; @@ -351,11 +453,12 @@ void AP_ESC_Telem::update_rpm(const uint8_t esc_index, const uint16_t new_rpm, c const uint32_t now = AP_HAL::micros(); volatile AP_ESC_Telem_Backend::RpmData& rpmdata = _rpm_data[esc_index]; + const auto last_update_us = rpmdata.last_update_us; rpmdata.prev_rpm = rpmdata.rpm; rpmdata.rpm = new_rpm; - if (now > rpmdata.last_update_us) { // cope with wrapping - rpmdata.update_rate_hz = 1.0e6f / (now - rpmdata.last_update_us); + if (now > last_update_us) { // cope with wrapping + rpmdata.update_rate_hz = 1.0e6f / (now - last_update_us); } rpmdata.last_update_us = now; rpmdata.error_rate = error_rate; @@ -365,7 +468,6 @@ void AP_ESC_Telem::update_rpm(const uint8_t esc_index, const uint16_t new_rpm, c #endif } -// log ESC telemetry at 10Hz void AP_ESC_Telem::update() { AP_Logger *logger = AP_Logger::get_singleton(); @@ -412,6 +514,19 @@ void AP_ESC_Telem::update() } } +#if AP_SCRIPTING_ENABLED +/* + set RPM scale factor from script +*/ +void AP_ESC_Telem::set_rpm_scale(const uint8_t esc_index, const float scale_factor) +{ + if (esc_index < ESC_TELEM_MAX_ESCS) { + rpm_scale_factor[esc_index] = scale_factor; + rpm_scale_mask |= (1U< +#include #include "AP_ESC_Telem_Backend.h" #if HAL_WITH_ESC_TELEM -#define ESC_TELEM_MAX_ESCS 12 +#ifdef NUM_SERVO_CHANNELS + #define ESC_TELEM_MAX_ESCS NUM_SERVO_CHANNELS +#elif !HAL_MINIMIZE_FEATURES && BOARD_FLASH_SIZE > 1024 + #define ESC_TELEM_MAX_ESCS 32 +#else + #define ESC_TELEM_MAX_ESCS 16 +#endif + #define ESC_TELEM_DATA_TIMEOUT_MS 5000UL #define ESC_RPM_DATA_TIMEOUT_US 1000000UL @@ -16,8 +24,9 @@ class AP_ESC_Telem { AP_ESC_Telem(); /* Do not allow copies */ - AP_ESC_Telem(const AP_ESC_Telem &other) = delete; - AP_ESC_Telem &operator=(const AP_ESC_Telem&) = delete; + CLASS_NO_COPY(AP_ESC_Telem); + + static const struct AP_Param::GroupInfo var_info[]; static AP_ESC_Telem *get_singleton(); @@ -33,6 +42,9 @@ class AP_ESC_Telem { // return the average motor RPM float get_average_motor_rpm() const { return get_average_motor_rpm(0xFFFFFFFF); } + // determine whether all the motors in servo_channel_mask are running + bool are_motors_running(uint32_t servo_channel_mask, float min_rpm) const; + // get an individual ESC's temperature in centi-degrees if available, returns true on success bool get_temperature(uint8_t esc_index, int16_t& temp) const; @@ -68,7 +80,7 @@ class AP_ESC_Telem { // get mask of ESCs that sent valid telemetry data in the last // ESC_TELEM_DATA_TIMEOUT_MS - uint16_t get_active_esc_mask() const; + uint32_t get_active_esc_mask() const; // return the last time telemetry data was received in ms for the given ESC or 0 if never uint32_t get_last_telem_data_ms(uint8_t esc_index) const { @@ -82,9 +94,22 @@ class AP_ESC_Telem { // udpate at 10Hz to log telemetry void update(); -private: + // is rpm telemetry configured for the provided channel mask + bool is_telemetry_active(uint32_t servo_channel_mask) const; + // callback to update the rpm in the frontend, should be called by the driver when new data is available - void update_rpm(const uint8_t esc_index, const uint16_t new_rpm, const float error_rate); + // can also be called from scripting + void update_rpm(const uint8_t esc_index, const float new_rpm, const float error_rate); + +#if AP_SCRIPTING_ENABLED + /* + set RPM scale factor from script + */ + void set_rpm_scale(const uint8_t esc_index, const float scale_factor); +#endif + +private: + // callback to update the data in the frontend, should be called by the driver when new data is available void update_telem_data(const uint8_t esc_index, const AP_ESC_Telem_Backend::TelemetryData& new_data, const uint16_t data_mask); @@ -95,9 +120,18 @@ class AP_ESC_Telem { uint32_t _last_telem_log_ms[ESC_TELEM_MAX_ESCS]; uint32_t _last_rpm_log_us[ESC_TELEM_MAX_ESCS]; + uint8_t next_idx; +#if AP_SCRIPTING_ENABLED + // allow for scaling of RPMs via lua scripts + float rpm_scale_factor[ESC_TELEM_MAX_ESCS]; + uint32_t rpm_scale_mask; +#endif + bool _have_data; + AP_Int8 mavlink_offset; + static AP_ESC_Telem *_singleton; }; @@ -105,4 +139,5 @@ namespace AP { AP_ESC_Telem &esc_telem(); }; -#endif +#endif // HAL_WITH_ESC_TELEM + diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.cpp b/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.cpp index 7733dc6a09e..b104c835628 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.cpp +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.cpp @@ -31,7 +31,7 @@ AP_ESC_Telem_Backend::AP_ESC_Telem_Backend() { } // callback to update the rpm in the frontend, should be called by the driver when new data is available -void AP_ESC_Telem_Backend::update_rpm(const uint8_t esc_index, const uint16_t new_rpm, const float error_rate) { +void AP_ESC_Telem_Backend::update_rpm(const uint8_t esc_index, const float new_rpm, const float error_rate) { _frontend->update_rpm(esc_index, new_rpm, error_rate); } diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.h b/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.h index 5e581ffd1c7..769807230f4 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.h +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.h @@ -2,8 +2,10 @@ #include -#ifndef HAL_WITH_ESC_TELEM -#define HAL_WITH_ESC_TELEM HAL_SUPPORT_RCOUT_SERIAL || HAL_MAX_CAN_PROTOCOL_DRIVERS +#if defined(NUM_SERVO_CHANNELS) && NUM_SERVO_CHANNELS == 0 +#define HAL_WITH_ESC_TELEM 0 +#elif !defined(HAL_WITH_ESC_TELEM) +#define HAL_WITH_ESC_TELEM (HAL_SUPPORT_RCOUT_SERIAL || HAL_MAX_CAN_PROTOCOL_DRIVERS) && !defined(HAL_BUILD_AP_PERIPH) #endif #if HAL_WITH_ESC_TELEM @@ -51,7 +53,7 @@ class AP_ESC_Telem_Backend { protected: // callback to update the rpm in the frontend, should be called by the driver when new data is available - void update_rpm(const uint8_t esc_index, const uint16_t new_rpm, const float error_rate = 0.0f); + void update_rpm(const uint8_t esc_index, const float new_rpm, const float error_rate = 0.0f); // callback to update the data in the frontend, should be called by the driver when new data is available void update_telem_data(const uint8_t esc_index, const TelemetryData& new_data, const uint16_t data_present_mask); diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem_SITL.cpp b/libraries/AP_ESC_Telem/AP_ESC_Telem_SITL.cpp index f29fbad525d..220c899823c 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem_SITL.cpp +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem_SITL.cpp @@ -36,16 +36,42 @@ void AP_ESC_Telem_SITL::update() return; } - if (is_zero(sitl->throttle)) { +#if HAL_WITH_ESC_TELEM + + if (AP_HAL::millis64() < 6000) { + // this prevents us sending blank data at startup, which triggers + // ESC telem messages for all channels return; } + uint32_t mask = sitl->state.motor_mask; + uint8_t bit; + while ((bit = __builtin_ffs(mask)) != 0) { + uint8_t motor = bit-1; + mask &= ~(1U<state.num_motors; i++) { - update_rpm(i, sitl->state.rpm[sitl->state.vtol_motor_start+i]); + if (is_zero(sitl->throttle)) { + if (!is_zero(sitl->esc_rpm_armed) && hal.util->get_soft_armed()) { + update_rpm(motor, sitl->esc_rpm_armed); + } + } else { + update_rpm(motor, sitl->state.rpm[motor]); + } + + // some fake values so that is_telemetry_active() returns true + TelemetryData t { + .temperature_cdeg = 32, + .voltage = 16.8f, + .current = 0.8f, + .consumption_mah = 1.0f, + }; + + update_telem_data(motor, t, + AP_ESC_Telem_Backend::TelemetryType::CURRENT + | AP_ESC_Telem_Backend::TelemetryType::VOLTAGE + | AP_ESC_Telem_Backend::TelemetryType::CONSUMPTION + | AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE); } #endif - } -#endif \ No newline at end of file +#endif diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp index b99efe4ffdf..a56114ba996 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp @@ -194,10 +194,10 @@ Vector3f AP_ExternalAHRS::get_accel(void) } // send an EKF_STATUS message to GCS -void AP_ExternalAHRS::send_status_report(mavlink_channel_t chan) const +void AP_ExternalAHRS::send_status_report(GCS_MAVLINK &link) const { if (backend) { - backend->send_status_report(chan); + backend->send_status_report(link); } } diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS.h b/libraries/AP_ExternalAHRS/AP_ExternalAHRS.h index 0d7aa94bcce..2f516c0433c 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS.h +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS.h @@ -29,8 +29,6 @@ #if HAL_EXTERNAL_AHRS_ENABLED -#include - class AP_ExternalAHRS_backend; class AP_ExternalAHRS { @@ -91,7 +89,7 @@ class AP_ExternalAHRS { void get_filter_status(nav_filter_status &status) const; Vector3f get_gyro(void); Vector3f get_accel(void); - void send_status_report(mavlink_channel_t chan) const; + void send_status_report(class GCS_MAVLINK &link) const; // update backend void update(); diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_LORD.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_LORD.cpp index 2d390ff44b5..f7512608a97 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_LORD.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_LORD.cpp @@ -269,6 +269,7 @@ void AP_ExternalAHRS_LORD::post_imu() const AP::compass().handle_external(mag); } +#if AP_BARO_EXTERNALAHRS_ENABLED { const AP_ExternalAHRS::baro_data_message_t baro { instance: 0, @@ -278,6 +279,7 @@ void AP_ExternalAHRS_LORD::post_imu() const }; AP::baro().handle_external(baro); } +#endif } // Collects data from a gnss packet into `gnss_data` @@ -290,7 +292,7 @@ void AP_ExternalAHRS_LORD::handle_gnss(const LORD_Packet &packet) switch ((GNSSPacketField) packet.payload[i+1]) { // GPS Time case GNSSPacketField::GPS_TIME: { - gnss_data.tow_ms = extract_double(packet.payload, i+2) * 1000; // Convert seconds to ms + gnss_data.tow_ms = double_to_uint32(extract_double(packet.payload, i+2) * 1000); // Convert seconds to ms gnss_data.week = be16toh_ptr(&packet.payload[i+10]); break; } @@ -489,7 +491,7 @@ void AP_ExternalAHRS_LORD::get_filter_status(nav_filter_status &status) const } } -void AP_ExternalAHRS_LORD::send_status_report(mavlink_channel_t chan) const +void AP_ExternalAHRS_LORD::send_status_report(GCS_MAVLINK &link) const { // prepare flags uint16_t flags = 0; @@ -534,7 +536,7 @@ void AP_ExternalAHRS_LORD::send_status_report(mavlink_channel_t chan) const const float pos_gate = 4; // represents hz value data is posted at const float hgt_gate = 4; // represents hz value data is posted at const float mag_var = 0; //we may need to change this to be like the other gates, set to 0 because mag is ignored by the ins filter in vectornav - mavlink_msg_ekf_status_report_send(chan, flags, + mavlink_msg_ekf_status_report_send(link.get_chan(), flags, gnss_data.speed_accuracy/vel_gate, gnss_data.horizontal_position_accuracy/pos_gate, gnss_data.vertical_position_accuracy/hgt_gate, mag_var, 0, 0); diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_LORD.h b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_LORD.h index f7faa04fa62..6695437d492 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_LORD.h +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_LORD.h @@ -40,7 +40,7 @@ class AP_ExternalAHRS_LORD: public AP_ExternalAHRS_backend bool initialised(void) const override; bool pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const override; void get_filter_status(nav_filter_status &status) const override; - void send_status_report(mavlink_channel_t chan) const override; + void send_status_report(class GCS_MAVLINK &link) const override; // check for new data void update() override { diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp index da14f5be54d..596f732a0a6 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp @@ -244,7 +244,8 @@ void AP_ExternalAHRS_VectorNav::process_packet1(const uint8_t *b) Location::AltFrame::ABSOLUTE}; state.have_location = true; } - + +#if AP_BARO_EXTERNALAHRS_ENABLED { AP_ExternalAHRS::baro_data_message_t baro; baro.instance = 0; @@ -253,6 +254,7 @@ void AP_ExternalAHRS_VectorNav::process_packet1(const uint8_t *b) AP::baro().handle_external(baro); } +#endif { AP_ExternalAHRS::mag_data_message_t mag; @@ -415,7 +417,7 @@ void AP_ExternalAHRS_VectorNav::get_filter_status(nav_filter_status &status) con } // send an EKF_STATUS message to GCS -void AP_ExternalAHRS_VectorNav::send_status_report(mavlink_channel_t chan) const +void AP_ExternalAHRS_VectorNav::send_status_report(GCS_MAVLINK &link) const { if (!last_pkt1) { return; @@ -464,7 +466,7 @@ void AP_ExternalAHRS_VectorNav::send_status_report(mavlink_channel_t chan) const const float pos_gate = 5; const float hgt_gate = 5; const float mag_var = 0; - mavlink_msg_ekf_status_report_send(chan, flags, + mavlink_msg_ekf_status_report_send(link.get_chan(), flags, pkt1.velU/vel_gate, pkt1.posU/pos_gate, pkt1.posU/hgt_gate, mag_var, 0, 0); } diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.h b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.h index 2ca99717716..e83df32401e 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.h +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.h @@ -22,8 +22,6 @@ #if HAL_EXTERNAL_AHRS_ENABLED -#include - class AP_ExternalAHRS_VectorNav : public AP_ExternalAHRS_backend { public: @@ -37,7 +35,7 @@ class AP_ExternalAHRS_VectorNav : public AP_ExternalAHRS_backend { bool initialised(void) const override; bool pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const override; void get_filter_status(nav_filter_status &status) const override; - void send_status_report(mavlink_channel_t chan) const override; + void send_status_report(class GCS_MAVLINK &link) const override; // check for new data void update() override { @@ -49,7 +47,6 @@ class AP_ExternalAHRS_VectorNav : public AP_ExternalAHRS_backend { int8_t port_num; bool port_opened; uint32_t baudrate; - uint16_t rate; void update_thread(); bool check_uart(); diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_backend.h b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_backend.h index fe0edbe1329..1d0204e0d1b 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_backend.h +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_backend.h @@ -34,7 +34,7 @@ class AP_ExternalAHRS_backend { virtual bool initialised(void) const = 0; virtual bool pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const = 0; virtual void get_filter_status(nav_filter_status &status) const {} - virtual void send_status_report(mavlink_channel_t chan) const {} + virtual void send_status_report(class GCS_MAVLINK &link) const {} // check for new data virtual void update() = 0; diff --git a/libraries/AP_FETtecOneWire/AP_FETtecOneWire.cpp b/libraries/AP_FETtecOneWire/AP_FETtecOneWire.cpp index da0e37e6c86..200651a446f 100644 --- a/libraries/AP_FETtecOneWire/AP_FETtecOneWire.cpp +++ b/libraries/AP_FETtecOneWire/AP_FETtecOneWire.cpp @@ -119,15 +119,16 @@ void AP_FETtecOneWire::init() return; // no serial port available, so nothing to do here } - _motor_mask = _motor_mask_parameter; // take a copy that will not change after we leave this function + _motor_mask = uint32_t(_motor_mask_parameter); // take a copy that will not change after we leave this function _esc_count = __builtin_popcount(_motor_mask); #if HAL_WITH_ESC_TELEM - // OneWire supports at most 15 ESCs, because of the 4 bit limitation + // OneWire supports telemetry in at most 15 ESCs, because of the 4 bit limitation // on the fast-throttle command. But we are still limited to the // number of ESCs the telem library will collect data for. - if (_esc_count == 0 || _motor_mask >= (1 << MIN(15, ESC_TELEM_MAX_ESCS))) { + if (_esc_count == 0 || _motor_mask >= (1U << MIN(15, ESC_TELEM_MAX_ESCS))) { #else - if (_esc_count == 0 || _motor_mask >= (1 << NUM_SERVO_CHANNELS)) { + // OneWire supports at most 24 ESCs without telemetry + if (_esc_count == 0 || _motor_mask >= (1U << MIN(24, NUM_SERVO_CHANNELS))) { #endif _invalid_mask = true; return; @@ -750,7 +751,7 @@ void AP_FETtecOneWire::configure_escs() case ESCState::WAITING_SET_FAST_COM_LENGTH_OK: return; case ESCState::RUNNING: - _running_mask |= (1 << esc.servo_ofs); + _running_mask |= (1U << esc.servo_ofs); break; } } @@ -782,7 +783,7 @@ void AP_FETtecOneWire::update() // telem OK continue; } - _running_mask &= ~(1 << esc.servo_ofs); + _running_mask &= ~(1U << esc.servo_ofs); GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "No telem from esc id=%u. Resetting it.", esc.id); //GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "unknown %u, invalid %u, too short %u, unexpected: %u, crc_err %u", _unknown_esc_message, _message_invalid_in_state_count, _period_too_short, esc.unexpected_telem, crc_rec_err_cnt); esc.set_state(ESCState::WANT_SEND_OK_TO_GET_RUNNING_SW_TYPE); diff --git a/libraries/AP_FETtecOneWire/AP_FETtecOneWire.h b/libraries/AP_FETtecOneWire/AP_FETtecOneWire.h index 56d30994225..5de08f13114 100644 --- a/libraries/AP_FETtecOneWire/AP_FETtecOneWire.h +++ b/libraries/AP_FETtecOneWire/AP_FETtecOneWire.h @@ -193,10 +193,9 @@ class AP_FETtecOneWire : public AP_ESC_Telem_Backend }; uint32_t _min_fast_throttle_period_us; ///< minimum allowed fast-throttle command transmit period - uint32_t _last_not_running_warning_ms; ///< last time we warned the user their ESCs are stuffed - int32_t _motor_mask; ///< an un-mutable copy of the _motor_mask_parameter taken before _init_done goes true - int32_t _reverse_mask; ///< a copy of the _reverse_mask_parameter taken while not armed - int32_t _running_mask; ///< a bitmask of the actively running ESCs + uint32_t _motor_mask; ///< an un-mutable copy of the _motor_mask_parameter taken before _init_done goes true + uint32_t _reverse_mask; ///< a copy of the _reverse_mask_parameter taken while not armed + uint32_t _running_mask; ///< a bitmask of the actively running ESCs uint32_t _last_transmit_us; ///< last time the transmit() function sent data ESC *_escs; uint8_t _esc_count; ///< number of allocated ESCs diff --git a/libraries/AP_FETtecOneWire/README.md b/libraries/AP_FETtecOneWire/README.md index 45fbb0ac7e6..482670b0fbf 100644 --- a/libraries/AP_FETtecOneWire/README.md +++ b/libraries/AP_FETtecOneWire/README.md @@ -41,7 +41,7 @@ For purchase, connection and configuration information please see the [ArduPilot ## ArduPilot to ESC protocol -The FETtec OneWire protocol supports up to 24 ESCs. As most copters only use at most 12 motors, ArduPilot's implementation supports only 12 (`ESC_TELEM_MAX_ESCS`)to save memory. +The FETtec OneWire protocol supports up to 24 ESCs without telemetry and up to 15 ESCs with telemetry. There are two types of messages sent to the ESCs configuration and fast-throttle messages: @@ -104,7 +104,7 @@ Four ESCs need 90us for the fast-throttle request and telemetry reception. With Each additional ESC adds 11 extra fast-throttle command bits, so the update rate is lowered by each additional ESC. If you use 8 ESCs, it needs 160us including telemetry response, so 5.8kHz update rate would be possible. The FETtec ArduPilot device driver limits the message transmit period to `_min_fast_throttle_period_us` according to the number of ESCs used. -The update() function has an extra invocation period limit so that even at very high loop rates the the ESCs will still operate correctly albeit doing some decimation. +The update() function has an extra invocation period limit so that even at very high loop rates the ESCs will still operate correctly albeit doing some decimation. The current update rate for Copter is 400Hz (~2500us) and for other vehicles is 50Hz (~20000us) so we are bellow device driver limit. **Note:** The FETtec ESCs firmware requires at least a 4Hz fast-throttle update rate (max. 250ms between messages) otherwise the FETtec ESC disarm (stop) the motors. @@ -165,7 +165,7 @@ pre_arm_check() The `SERVO_FTW_MASK` parameter selects which servo outputs, if any, will be routed to FETtec ESCs. You need to reboot after changing this parameter. -When `HAL_WITH_ESC_TELEM` is active (default) only the first 12 (`ESC_TELEM_MAX_ESCS`) can be used. +When `HAL_WITH_ESC_TELEM` is active (default) only the first 15 (`ESC_TELEM_MAX_ESCS`) can be used. The FETtec ESC IDs set inside the FETtec firmware by the FETtec configuration tool are one-indexed. These IDs must start at ID 1 and be in a single contiguous block. You do not need to change these FETtec IDs if you change the servo output assignments inside ArduPilot the using the `SERVO_FTW_MASK` parameter. diff --git a/libraries/AP_Filesystem/AP_Filesystem.cpp b/libraries/AP_Filesystem/AP_Filesystem.cpp index 1719a7b0c54..2227242de5e 100644 --- a/libraries/AP_Filesystem/AP_Filesystem.cpp +++ b/libraries/AP_Filesystem/AP_Filesystem.cpp @@ -49,7 +49,7 @@ static AP_Filesystem_Param fs_param; static AP_Filesystem_Sys fs_sys; #include -#if HAL_MISSION_ENABLED +#if AP_MISSION_ENABLED #include "AP_Filesystem_Mission.h" static AP_Filesystem_Mission fs_mission; #endif @@ -65,7 +65,7 @@ const AP_Filesystem::Backend AP_Filesystem::backends[] = { { "@PARAM/", fs_param }, { "@SYS/", fs_sys }, { "@SYS", fs_sys }, -#if HAL_MISSION_ENABLED +#if AP_MISSION_ENABLED { "@MISSION/", fs_mission }, #endif }; @@ -106,10 +106,10 @@ const AP_Filesystem::Backend &AP_Filesystem::backend_by_fd(int &fd) const return backends[idx]; } -int AP_Filesystem::open(const char *fname, int flags) +int AP_Filesystem::open(const char *fname, int flags, bool allow_absolute_paths) { const Backend &backend = backend_by_path(fname); - int fd = backend.fs.open(fname, flags); + int fd = backend.fs.open(fname, flags, allow_absolute_paths); if (fd < 0) { return -1; } diff --git a/libraries/AP_Filesystem/AP_Filesystem.h b/libraries/AP_Filesystem/AP_Filesystem.h index 972b8e93ddb..b7f1938b938 100644 --- a/libraries/AP_Filesystem/AP_Filesystem.h +++ b/libraries/AP_Filesystem/AP_Filesystem.h @@ -34,6 +34,7 @@ #endif #define DT_REG 0 #define DT_DIR 1 +#define DT_LNK 10 struct dirent { char d_name[MAX_NAME_LEN]; /* filename */ @@ -80,7 +81,7 @@ class AP_Filesystem { AP_Filesystem() {} // functions that closely match the equivalent posix calls - int open(const char *fname, int flags); + int open(const char *fname, int flags, bool allow_absolute_paths = false); int close(int fd); int32_t read(int fd, void *buf, uint32_t count); int32_t write(int fd, const void *buf, uint32_t count); diff --git a/libraries/AP_Filesystem/AP_Filesystem_ESP32.cpp b/libraries/AP_Filesystem/AP_Filesystem_ESP32.cpp index 3e34ba4a234..de285e358ef 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_ESP32.cpp +++ b/libraries/AP_Filesystem/AP_Filesystem_ESP32.cpp @@ -26,7 +26,7 @@ extern const AP_HAL::HAL& hal; -int AP_Filesystem_ESP32::open(const char *fname, int flags) +int AP_Filesystem_ESP32::open(const char *fname, int flags, bool allow_absolute_paths) { #if FSDEBUG printf("DO open %s \n", fname); diff --git a/libraries/AP_Filesystem/AP_Filesystem_ESP32.h b/libraries/AP_Filesystem/AP_Filesystem_ESP32.h index bdc03fbd33c..69877fb7f59 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_ESP32.h +++ b/libraries/AP_Filesystem/AP_Filesystem_ESP32.h @@ -21,7 +21,7 @@ class AP_Filesystem_ESP32 : public AP_Filesystem_Backend { public: // functions that closely match the equivalent posix calls - int open(const char *fname, int flags) override; + int open(const char *fname, int flags, bool allow_absolute_paths = false) override; int close(int fd) override; int32_t read(int fd, void *buf, uint32_t count) override; int32_t write(int fd, const void *buf, uint32_t count) override; diff --git a/libraries/AP_Filesystem/AP_Filesystem_FATFS.cpp b/libraries/AP_Filesystem/AP_Filesystem_FATFS.cpp index 887aabfd988..29a45d3aed0 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_FATFS.cpp +++ b/libraries/AP_Filesystem/AP_Filesystem_FATFS.cpp @@ -279,7 +279,7 @@ static bool remount_file_system(void) return true; } -int AP_Filesystem_FATFS::open(const char *pathname, int flags) +int AP_Filesystem_FATFS::open(const char *pathname, int flags, bool allow_absolute_path) { int fileno; int fatfs_modes; diff --git a/libraries/AP_Filesystem/AP_Filesystem_FATFS.h b/libraries/AP_Filesystem/AP_Filesystem_FATFS.h index 5193555947f..663dffc8193 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_FATFS.h +++ b/libraries/AP_Filesystem/AP_Filesystem_FATFS.h @@ -20,7 +20,7 @@ class AP_Filesystem_FATFS : public AP_Filesystem_Backend { public: // functions that closely match the equivalent posix calls - int open(const char *fname, int flags) override; + int open(const char *fname, int flags, bool allow_absolute_paths = false) override; int close(int fd) override; int32_t read(int fd, void *buf, uint32_t count) override; int32_t write(int fd, const void *buf, uint32_t count) override; diff --git a/libraries/AP_Filesystem/AP_Filesystem_Mission.cpp b/libraries/AP_Filesystem/AP_Filesystem_Mission.cpp index d4cb9f34de9..6bbc33aa2cb 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_Mission.cpp +++ b/libraries/AP_Filesystem/AP_Filesystem_Mission.cpp @@ -23,14 +23,14 @@ #include #include -#if HAL_MISSION_ENABLED +#if AP_MISSION_ENABLED extern const AP_HAL::HAL& hal; extern int errno; #define IDLE_TIMEOUT_MS 30000 -int AP_Filesystem_Mission::open(const char *fname, int flags) +int AP_Filesystem_Mission::open(const char *fname, int flags, bool allow_absolute_paths) { enum MAV_MISSION_TYPE mtype; @@ -236,8 +236,10 @@ bool AP_Filesystem_Mission::get_item(uint32_t idx, enum MAV_MISSION_TYPE mtype, } return mission->get_item(idx, item); } +#if AP_FENCE_ENABLED case MAV_MISSION_TYPE_FENCE: return MissionItemProtocol_Fence::get_item_as_mission_item(idx, item); +#endif case MAV_MISSION_TYPE_RALLY: return MissionItemProtocol_Rally::get_item_as_mission_item(idx, item); @@ -261,11 +263,15 @@ uint32_t AP_Filesystem_Mission::get_num_items(enum MAV_MISSION_TYPE mtype) const } case MAV_MISSION_TYPE_FENCE: { +#if AP_FENCE_ENABLED auto *fence = AP::fence(); if (fence == nullptr) { return 0; } return fence->polyfence().num_stored_items(); +#else + return 0; +#endif } case MAV_MISSION_TYPE_RALLY: { diff --git a/libraries/AP_Filesystem/AP_Filesystem_Mission.h b/libraries/AP_Filesystem/AP_Filesystem_Mission.h index b4ff4f53ca9..a4f0f869fd5 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_Mission.h +++ b/libraries/AP_Filesystem/AP_Filesystem_Mission.h @@ -23,7 +23,7 @@ class AP_Filesystem_Mission : public AP_Filesystem_Backend { public: // functions that closely match the equivalent posix calls - int open(const char *fname, int flags) override; + int open(const char *fname, int flags, bool allow_absolute_paths = false) override; int close(int fd) override; int32_t read(int fd, void *buf, uint32_t count) override; int32_t lseek(int fd, int32_t offset, int whence) override; diff --git a/libraries/AP_Filesystem/AP_Filesystem_Param.cpp b/libraries/AP_Filesystem/AP_Filesystem_Param.cpp index 5d3203227c1..afa838d0b5a 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_Param.cpp +++ b/libraries/AP_Filesystem/AP_Filesystem_Param.cpp @@ -26,7 +26,7 @@ extern const AP_HAL::HAL& hal; extern int errno; -int AP_Filesystem_Param::open(const char *fname, int flags) +int AP_Filesystem_Param::open(const char *fname, int flags, bool allow_absolute_path) { if (!check_file_name(fname)) { errno = ENOENT; @@ -53,6 +53,7 @@ int AP_Filesystem_Param::open(const char *fname, int flags) } r.file_ofs = 0; r.open = true; + r.with_defaults = false; r.start = 0; r.count = 0; r.read_size = 0; @@ -94,6 +95,18 @@ int AP_Filesystem_Param::open(const char *fname, int flags) c = strchr(c, '&'); continue; } +#if AP_PARAM_DEFAULTS_ENABLED + if (strncmp(c, "withdefaults=", 13) == 0) { + uint32_t v = strtoul(c+13, nullptr, 10); + if (v > 1) { + goto failed; + } + r.with_defaults = v == 1; + c += 13; + c = strchr(c, '&'); + continue; + } +#endif } return idx; @@ -128,18 +141,18 @@ int AP_Filesystem_Param::close(int fd) /* packed format: file header: - uint16_t magic = 0x671b + uint16_t magic = 0x671b or 0x671c for included default values uint16_t num_params uint16_t total_params per-parameter: uint8_t type:4; // AP_Param type NONE=0, INT8=1, INT16=2, INT32=3, FLOAT=4 - uint8_t flags:4; // for future use + uint8_t flags:4; // bit 0: includes default value for this param uint8_t common_len:4; // number of name bytes in common with previous entry, 0..15 uint8_t name_len:4; // non-common length of param name -1 (0..15) uint8_t name[name_len]; // name - uint8_t data[]; // value, length given by variable type + uint8_t data[]; // value, length given by variable type, data length doubled if default is included Any leading zero bytes after the header should be discarded as pad bytes. Pad bytes are used to ensure that a parameter data[] field @@ -155,18 +168,19 @@ uint8_t AP_Filesystem_Param::pack_param(const struct rfile &r, struct cursor &c, name[AP_MAX_NAME_SIZE] = 0; enum ap_var_type ptype; AP_Param *ap; + float default_val; if (c.token_ofs == 0) { c.idx = 0; - ap = AP_Param::first(&c.token, &ptype); + ap = AP_Param::first(&c.token, &ptype, &default_val); uint16_t idx = 0; while (idx < r.start && ap) { - ap = AP_Param::next_scalar(&c.token, &ptype); + ap = AP_Param::next_scalar(&c.token, &ptype, &default_val); idx++; } } else { c.idx++; - ap = AP_Param::next_scalar(&c.token, &ptype); + ap = AP_Param::next_scalar(&c.token, &ptype, &default_val); } if (ap == nullptr || (r.count && c.idx >= r.count)) { return 0; @@ -181,10 +195,20 @@ uint8_t AP_Filesystem_Param::pack_param(const struct rfile &r, struct cursor &c, pname++; last_name++; } - const uint8_t name_len = strlen(pname); + uint8_t name_len = strlen(pname); + if (name_len == 0) { + name_len = 1; + common_len--; + pname--; + } +#if AP_PARAM_DEFAULTS_ENABLED + const bool add_default = r.with_defaults && !is_equal(ap->cast_to_float(ptype), default_val); +#else + const bool add_default = false; +#endif const uint8_t type_len = AP_Param::type_size(ptype); - uint8_t packed_len = type_len + name_len + 2; - const uint8_t flags = 0; + uint8_t packed_len = type_len + name_len + 2 + (add_default ? type_len : 0); + const uint8_t flags = add_default; /* see if we need to add padding to ensure that a data field never @@ -206,6 +230,36 @@ uint8_t AP_Filesystem_Param::pack_param(const struct rfile &r, struct cursor &c, buf[1] = common_len | ((name_len-1)<<4); memcpy(&buf[2], pname, name_len); memcpy(&buf[2+name_len], ap, type_len); +#if AP_PARAM_DEFAULTS_ENABLED + if (add_default) { + switch (ptype) { + case AP_PARAM_NONE: + case AP_PARAM_GROUP: + // should never happen... + break; + case AP_PARAM_INT8: { + const int32_t int8_default = default_val; + memcpy(&buf[2+name_len+type_len], &int8_default, type_len); + break; + } + case AP_PARAM_INT16: { + const int16_t int16_default = default_val; + memcpy(&buf[2+name_len+type_len], &int16_default, type_len); + break; + } + case AP_PARAM_INT32: { + const int32_t int32_default = default_val; + memcpy(&buf[2+name_len+type_len], &int32_default, type_len); + break; + } + case AP_PARAM_FLOAT: + case AP_PARAM_VECTOR3F: { + memcpy(&buf[2+name_len+type_len], &default_val, type_len); + break; + } + } + } +#endif strcpy(c.last_name, name); @@ -301,6 +355,9 @@ int32_t AP_Filesystem_Param::read(int fd, void *buf, uint32_t count) hdr.num_params = r.count; } uint8_t n = MIN(sizeof(hdr) - r.file_ofs, count); + if (r.with_defaults) { + hdr.magic = pmagic_with_default; + } const uint8_t *b = (const uint8_t *)&hdr; memcpy(buf, &b[r.file_ofs], n); count -= n; diff --git a/libraries/AP_Filesystem/AP_Filesystem_Param.h b/libraries/AP_Filesystem/AP_Filesystem_Param.h index 98e8dc6af11..8b0af02b374 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_Param.h +++ b/libraries/AP_Filesystem/AP_Filesystem_Param.h @@ -24,7 +24,7 @@ class AP_Filesystem_Param : public AP_Filesystem_Backend { public: // functions that closely match the equivalent posix calls - int open(const char *fname, int flags) override; + int open(const char *fname, int flags, bool allow_absolute_paths = false) override; int close(int fd) override; int32_t read(int fd, void *buf, uint32_t count) override; int32_t lseek(int fd, int32_t offset, int whence) override; @@ -39,10 +39,12 @@ class AP_Filesystem_Param : public AP_Filesystem_Backend // only allow up to 4 files at a time static constexpr uint8_t max_open_file = 4; - // maximum size of one packed parameter - static constexpr uint8_t max_pack_len = AP_MAX_NAME_SIZE + 2 + 4 + 3; + // maximum size of one packed parameter and default value + static constexpr uint8_t max_pack_len = AP_MAX_NAME_SIZE + 2 + 4 + 4 + 3; + // Support both protocol versions static constexpr uint16_t pmagic = 0x671b; + static constexpr uint16_t pmagic_with_default = 0x671c; // header at front of the file struct header { @@ -62,6 +64,7 @@ class AP_Filesystem_Param : public AP_Filesystem_Backend struct rfile { bool open; + bool with_defaults; uint16_t read_size; uint16_t start; uint16_t count; diff --git a/libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp b/libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp index 5b23b4e898a..d4e3dadb3f2 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp +++ b/libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp @@ -23,7 +23,7 @@ #if defined(HAL_HAVE_AP_ROMFS_EMBEDDED_H) -int AP_Filesystem_ROMFS::open(const char *fname, int flags) +int AP_Filesystem_ROMFS::open(const char *fname, int flags, bool allow_absolute_paths) { if ((flags & O_ACCMODE) != O_RDONLY) { errno = EROFS; diff --git a/libraries/AP_Filesystem/AP_Filesystem_ROMFS.h b/libraries/AP_Filesystem/AP_Filesystem_ROMFS.h index fb69e23360d..897195915e8 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_ROMFS.h +++ b/libraries/AP_Filesystem/AP_Filesystem_ROMFS.h @@ -21,7 +21,7 @@ class AP_Filesystem_ROMFS : public AP_Filesystem_Backend { public: // functions that closely match the equivalent posix calls - int open(const char *fname, int flags) override; + int open(const char *fname, int flags, bool allow_absolute_paths = false) override; int close(int fd) override; int32_t read(int fd, void *buf, uint32_t count) override; int32_t write(int fd, const void *buf, uint32_t count) override; diff --git a/libraries/AP_Filesystem/AP_Filesystem_Sys.cpp b/libraries/AP_Filesystem/AP_Filesystem_Sys.cpp index da14a5bfc53..dacd553f359 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_Sys.cpp +++ b/libraries/AP_Filesystem/AP_Filesystem_Sys.cpp @@ -60,7 +60,7 @@ int8_t AP_Filesystem_Sys::file_in_sysfs(const char *fname) { return -1; } -int AP_Filesystem_Sys::open(const char *fname, int flags) +int AP_Filesystem_Sys::open(const char *fname, int flags, bool allow_absolute_paths) { if ((flags & O_ACCMODE) != O_RDONLY) { errno = EROFS; @@ -135,9 +135,11 @@ int AP_Filesystem_Sys::open(const char *fname, int flags) if (strcmp(fname, "persistent.parm") == 0) { hal.util->load_persistent_params(*r.str); } +#if AP_CRASHDUMP_ENABLED if (strcmp(fname, "crash_dump.bin") == 0) { r.str->set_buffer((char*)hal.util->last_crash_dump_ptr(), hal.util->last_crash_dump_size(), hal.util->last_crash_dump_size()); - } else + } +#endif if (strcmp(fname, "storage.bin") == 0) { // we don't want to store the contents of storage.bin // we read directly from the storage driver @@ -270,8 +272,10 @@ int AP_Filesystem_Sys::stat(const char *pathname, struct stat *stbuf) // read every file for a directory listing if (strcmp(pathname_noslash, "storage.bin") == 0) { stbuf->st_size = HAL_STORAGE_SIZE; +#if AP_CRASHDUMP_ENABLED } else if (strcmp(pathname_noslash, "crash_dump.bin") == 0) { stbuf->st_size = hal.util->last_crash_dump_size(); +#endif } else { stbuf->st_size = 100000; } diff --git a/libraries/AP_Filesystem/AP_Filesystem_Sys.h b/libraries/AP_Filesystem/AP_Filesystem_Sys.h index 1eef1fac359..e097b74d4a2 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_Sys.h +++ b/libraries/AP_Filesystem/AP_Filesystem_Sys.h @@ -23,7 +23,7 @@ class AP_Filesystem_Sys : public AP_Filesystem_Backend { public: // functions that closely match the equivalent posix calls - int open(const char *fname, int flags) override; + int open(const char *fname, int flags, bool allow_absolute_paths = false) override; int close(int fd) override; int32_t read(int fd, void *buf, uint32_t count) override; int32_t lseek(int fd, int32_t offset, int whence) override; diff --git a/libraries/AP_Filesystem/AP_Filesystem_backend.h b/libraries/AP_Filesystem/AP_Filesystem_backend.h index a60fad1d176..f359891cf9c 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_backend.h +++ b/libraries/AP_Filesystem/AP_Filesystem_backend.h @@ -43,7 +43,7 @@ class AP_Filesystem_Backend { public: // functions that closely match the equivalent posix calls - virtual int open(const char *fname, int flags) { + virtual int open(const char *fname, int flags, bool allow_absolute_paths = false) { return -1; } virtual int close(int fd) { return -1; } diff --git a/libraries/AP_Filesystem/AP_Filesystem_posix.cpp b/libraries/AP_Filesystem/AP_Filesystem_posix.cpp index 6454d86d603..f0982159b20 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_posix.cpp +++ b/libraries/AP_Filesystem/AP_Filesystem_posix.cpp @@ -49,10 +49,12 @@ static const char *map_filename(const char *fname) return fname; } -int AP_Filesystem_Posix::open(const char *fname, int flags) +int AP_Filesystem_Posix::open(const char *fname, int flags, bool allow_absolute_paths) { FS_CHECK_ALLOWED(-1); - fname = map_filename(fname); + if (! allow_absolute_paths) { + fname = map_filename(fname); + } // we automatically add O_CLOEXEC as we always want it for ArduPilot FS usage return ::open(fname, flags | O_CLOEXEC, 0644); } diff --git a/libraries/AP_Filesystem/AP_Filesystem_posix.h b/libraries/AP_Filesystem/AP_Filesystem_posix.h index 42fdad3ec6b..61d6bfdfd37 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_posix.h +++ b/libraries/AP_Filesystem/AP_Filesystem_posix.h @@ -29,7 +29,7 @@ class AP_Filesystem_Posix : public AP_Filesystem_Backend { public: // functions that closely match the equivalent posix calls - int open(const char *fname, int flags) override; + int open(const char *fname, int flags, bool allow_absolute_paths = false) override; int close(int fd) override; int32_t read(int fd, void *buf, uint32_t count) override; int32_t write(int fd, const void *buf, uint32_t count) override; diff --git a/libraries/AP_Filesystem/posix_compat.cpp b/libraries/AP_Filesystem/posix_compat.cpp index 2e80cbb9290..fad69d08a47 100644 --- a/libraries/AP_Filesystem/posix_compat.cpp +++ b/libraries/AP_Filesystem/posix_compat.cpp @@ -146,15 +146,14 @@ int apfs_fputs(const char *s, APFS_FILE *stream) return ret; } +#undef fgets char *apfs_fgets(char *s, int size, APFS_FILE *stream) { CHECK_STREAM(stream, NULL); - ssize_t ret = AP::FS().read(stream->fd, s, size-1); - if (ret < 0) { - stream->error = true; + auto &fs = AP::FS(); + if (!fs.fgets(s, size, stream->fd)) { return NULL; } - s[ret] = 0; return s; } diff --git a/libraries/AP_Filesystem/posix_compat.h b/libraries/AP_Filesystem/posix_compat.h index 8eff6eafd23..5fa0fba3caa 100644 --- a/libraries/AP_Filesystem/posix_compat.h +++ b/libraries/AP_Filesystem/posix_compat.h @@ -50,7 +50,7 @@ long apfs_ftell(APFS_FILE *stream); APFS_FILE *apfs_freopen(const char *pathname, const char *mode, APFS_FILE *stream); int apfs_remove(const char *pathname); int apfs_rename(const char *oldpath, const char *newpath); -char *tmpnam(char *s); +char *tmpnam(char s[L_tmpnam]); #undef stdin #undef stdout diff --git a/libraries/AP_FlashIface/AP_FlashIface_JEDEC.cpp b/libraries/AP_FlashIface/AP_FlashIface_JEDEC.cpp index 74471879287..2c3929f08db 100644 --- a/libraries/AP_FlashIface/AP_FlashIface_JEDEC.cpp +++ b/libraries/AP_FlashIface/AP_FlashIface_JEDEC.cpp @@ -668,7 +668,7 @@ bool AP_FlashIface_JEDEC::start_sector_erase(uint32_t sector, uint32_t &delay_ms bool AP_FlashIface_JEDEC::start_erase_offset(uint32_t offset, uint32_t size, uint32_t &erasing, uint32_t &delay_ms, uint32_t &timeout_ms) { - uint8_t ins; + uint8_t ins = 0; uint32_t erase_size = 0; erasing = 0; // Find the maximum size we can erase @@ -921,6 +921,9 @@ bool AP_FlashIface_JEDEC::start_xip_mode(void** addr) Debug("XIP mode unsupported on this chip"); return false; } + + bool success = false; + switch(_desc.entry_method) { case AP_FlashIface_JEDEC::XIP_ENTRY_METHOD_1: { @@ -937,7 +940,8 @@ bool AP_FlashIface_JEDEC::start_xip_mode(void** addr) cmd.addr = 0; cmd.dummy = _desc.fast_read_dummy_cycles; _dev->set_cmd_header(cmd); - return _dev->enter_xip_mode(addr); + success = _dev->enter_xip_mode(addr); + break; } case AP_FlashIface_JEDEC::XIP_ENTRY_METHOD_2: { @@ -965,7 +969,8 @@ bool AP_FlashIface_JEDEC::start_xip_mode(void** addr) // correct dummy bytes because of addition of alt bytes cmd.dummy = _desc.fast_read_dummy_cycles - 1; _dev->set_cmd_header(cmd); - return _dev->enter_xip_mode(addr); + success = _dev->enter_xip_mode(addr); + break; } default: { @@ -973,6 +978,9 @@ bool AP_FlashIface_JEDEC::start_xip_mode(void** addr) return false; } } + // make sure that the flash is ready once we enter XIP + DELAY_MICROS(100); + return success; } bool AP_FlashIface_JEDEC::stop_xip_mode() diff --git a/libraries/AP_FlashIface/examples/jedec_test/jedec_test.cpp b/libraries/AP_FlashIface/examples/jedec_test/jedec_test.cpp index bb7e6544c48..ae0723b399d 100644 --- a/libraries/AP_FlashIface/examples/jedec_test/jedec_test.cpp +++ b/libraries/AP_FlashIface/examples/jedec_test/jedec_test.cpp @@ -1,4 +1,20 @@ #include + +#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX + +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); +void setup() { } + +void loop() +{ + // the library simply panics if a JEDEC device can't be found. We + // can't really recover from that. + hal.console->printf("No JEDEC on linux\n"); + hal.scheduler->delay(1000); +} + +#else + #include #include #include @@ -184,4 +200,7 @@ void loop() hal.scheduler->delay(1000); } +#endif + AP_HAL_MAIN(); + diff --git a/libraries/AP_Follow/AP_Follow.cpp b/libraries/AP_Follow/AP_Follow.cpp index f1def162d25..371cdde7f75 100644 --- a/libraries/AP_Follow/AP_Follow.cpp +++ b/libraries/AP_Follow/AP_Follow.cpp @@ -33,6 +33,14 @@ extern const AP_HAL::HAL& hal; #define AP_FOLLOW_POS_P_DEFAULT 0.1f // position error gain default +#if APM_BUILD_TYPE(APM_BUILD_ArduPlane) +#define AP_FOLLOW_ALT_TYPE_DEFAULT 0 +#else +#define AP_FOLLOW_ALT_TYPE_DEFAULT AP_FOLLOW_ALTITUDE_TYPE_RELATIVE +#endif + +AP_Follow *AP_Follow::_singleton; + // table of user settable parameters const AP_Param::GroupInfo AP_Follow::var_info[] = { @@ -117,7 +125,7 @@ const AP_Param::GroupInfo AP_Follow::var_info[] = { // @Description: Follow altitude type // @Values: 0:absolute, 1:relative // @User: Standard - AP_GROUPINFO("_ALT_TYPE", 10, AP_Follow, _alt_type, AP_FOLLOW_ALTITUDE_TYPE_RELATIVE), + AP_GROUPINFO("_ALT_TYPE", 10, AP_Follow, _alt_type, AP_FOLLOW_ALT_TYPE_DEFAULT), #endif AP_GROUPEND @@ -131,6 +139,7 @@ const AP_Param::GroupInfo AP_Follow::var_info[] = { AP_Follow::AP_Follow() : _p_pos(AP_FOLLOW_POS_P_DEFAULT) { + _singleton = this; AP_Param::setup_object_defaults(this, var_info); } @@ -138,7 +147,7 @@ AP_Follow::AP_Follow() : void AP_Follow::clear_offsets_if_required() { if (_offsets_were_zero) { - _offset = Vector3f(); + _offset.set(Vector3f()); } _offsets_were_zero = false; } @@ -275,13 +284,10 @@ void AP_Follow::handle_msg(const mavlink_message_t &msg) } // decode global-position-int message - if (msg.msgid == MAVLINK_MSG_ID_GLOBAL_POSITION_INT) { - - // get estimated location and velocity (for logging) - Location loc_estimate{}; - Vector3f vel_estimate; - UNUSED_RESULT(get_target_location_and_velocity(loc_estimate, vel_estimate)); + bool updated = false; + switch (msg.msgid) { + case MAVLINK_MSG_ID_GLOBAL_POSITION_INT: { // decode message mavlink_global_position_int_t packet; mavlink_msg_global_position_int_decode(&msg, &packet); @@ -296,13 +302,11 @@ void AP_Follow::handle_msg(const mavlink_message_t &msg) // select altitude source based on FOLL_ALT_TYPE param if (_alt_type == AP_FOLLOW_ALTITUDE_TYPE_RELATIVE) { - // relative altitude - _target_location.alt = packet.relative_alt / 10; // convert millimeters to cm - _target_location.relative_alt = 1; // set relative_alt flag + // above home alt + _target_location.set_alt_cm(packet.relative_alt / 10, Location::AltFrame::ABOVE_HOME); } else { // absolute altitude - _target_location.alt = packet.alt / 10; // convert millimeters to cm - _target_location.relative_alt = 0; // reset relative_alt flag + _target_location.set_alt_cm(packet.alt / 10, Location::AltFrame::ABSOLUTE); } _target_velocity_ned.x = packet.vx * 0.01f; // velocity north @@ -320,6 +324,70 @@ void AP_Follow::handle_msg(const mavlink_message_t &msg) _sysid.set(msg.sysid); _automatic_sysid = true; } + updated = true; + break; + } + case MAVLINK_MSG_ID_FOLLOW_TARGET: { + // decode message + mavlink_follow_target_t packet; + mavlink_msg_follow_target_decode(&msg, &packet); + + // ignore message if lat and lon are (exactly) zero + if ((packet.lat == 0 && packet.lon == 0)) { + return; + } + // require at least position + if ((packet.est_capabilities & (1<<0)) == 0) { + return; + } + + Location new_loc = _target_location; + new_loc.lat = packet.lat; + new_loc.lng = packet.lon; + new_loc.set_alt_cm(packet.alt*100, Location::AltFrame::ABSOLUTE); + + // FOLLOW_TARGET is always AMSL, change the provided alt to + // above home if we are configured for relative alt + if (_alt_type == AP_FOLLOW_ALTITUDE_TYPE_RELATIVE && + !new_loc.change_alt_frame(Location::AltFrame::ABOVE_HOME)) { + return; + } + _target_location = new_loc; + + if (packet.est_capabilities & (1<<1)) { + _target_velocity_ned.x = packet.vel[0]; // velocity north + _target_velocity_ned.y = packet.vel[1]; // velocity east + _target_velocity_ned.z = packet.vel[2]; // velocity down + } else { + _target_velocity_ned.zero(); + } + + // get a local timestamp with correction for transport jitter + _last_location_update_ms = _jitter.correct_offboard_timestamp_msec(packet.timestamp, AP_HAL::millis()); + + if (packet.est_capabilities & (1<<3)) { + Quaternion q{packet.attitude_q[0], packet.attitude_q[1], packet.attitude_q[2], packet.attitude_q[3]}; + float r, p, y; + q.to_euler(r,p,y); + _target_heading = degrees(y); + _last_heading_update_ms = _last_location_update_ms; + } + + // initialise _sysid if zero to sender's id + if (_sysid == 0) { + _sysid.set(msg.sysid); + _automatic_sysid = true; + } + updated = true; + break; + } + } + + if (updated) { + // get estimated location and velocity + Location loc_estimate{}; + Vector3f vel_estimate; + UNUSED_RESULT(get_target_location_and_velocity(loc_estimate, vel_estimate)); // log lead's estimated vs reported position // @LoggerMessage: FOLL @@ -372,13 +440,13 @@ void AP_Follow::init_offsets_if_required(const Vector3f &dist_vec_ned) float target_heading_deg; if ((_offset_type == AP_FOLLOW_OFFSET_TYPE_RELATIVE) && get_target_heading_deg(target_heading_deg)) { // rotate offsets from north facing to vehicle's perspective - _offset = rotate_vector(-dist_vec_ned, -target_heading_deg); + _offset.set(rotate_vector(-dist_vec_ned, -target_heading_deg)); gcs().send_text(MAV_SEVERITY_INFO, "Relative follow offset loaded"); } else { // initialise offset in NED frame - _offset = -dist_vec_ned; + _offset.set(-dist_vec_ned); // ensure offset_type used matches frame of offsets saved - _offset_type = AP_FOLLOW_OFFSET_TYPE_NED; + _offset_type.set(AP_FOLLOW_OFFSET_TYPE_NED); gcs().send_text(MAV_SEVERITY_INFO, "N-E-D follow offset loaded"); } } @@ -420,3 +488,40 @@ void AP_Follow::clear_dist_and_bearing_to_target() _dist_to_target = 0.0f; _bearing_to_target = 0.0f; } + +// get target's estimated location and velocity (in NED), with offsets added +bool AP_Follow::get_target_location_and_velocity_ofs(Location &loc, Vector3f &vel_ned) const +{ + Vector3f ofs; + if (!get_offsets_ned(ofs) || + !get_target_location_and_velocity(loc, vel_ned)) { + return false; + } + // apply offsets + loc.offset(ofs.x, ofs.y); + loc.alt -= ofs.z*100; + return true; +} + +// return true if we have a target +bool AP_Follow::have_target(void) const +{ + if (!_enabled) { + return false; + } + + // check for timeout + if ((_last_location_update_ms == 0) || (AP_HAL::millis() - _last_location_update_ms > AP_FOLLOW_TIMEOUT_MS)) { + return false; + } + return true; +} + +namespace AP { + +AP_Follow &follow() +{ + return *AP_Follow::get_singleton(); +} + +} diff --git a/libraries/AP_Follow/AP_Follow.h b/libraries/AP_Follow/AP_Follow.h index fc5bc8eba6d..623bb748ca1 100644 --- a/libraries/AP_Follow/AP_Follow.h +++ b/libraries/AP_Follow/AP_Follow.h @@ -15,10 +15,11 @@ #pragma once #include +#include #include #include #include -#include +#include #include #include @@ -38,11 +39,16 @@ class AP_Follow // constructor AP_Follow(); + // enable as singleton + static AP_Follow *get_singleton(void) { + return _singleton; + } + // returns true if library is enabled bool enabled() const { return _enabled; } // set which target to follow - void set_target_sysid(uint8_t sysid) { _sysid = sysid; } + void set_target_sysid(uint8_t sysid) { _sysid.set(sysid); } // restore offsets to zero if necessary, should be called when vehicle exits follow mode void clear_offsets_if_required(); @@ -57,6 +63,9 @@ class AP_Follow // get target's estimated location and velocity (in NED) bool get_target_location_and_velocity(Location &loc, Vector3f &vel_ned) const; + // get target's estimated location and velocity (in NED), with offsets added + bool get_target_location_and_velocity_ofs(Location &loc, Vector3f &vel_ned) const; + // get distance vector to target (in meters), target plus offsets, and target's velocity all in NED frame bool get_target_dist_and_vel_ned(Vector3f &dist_ned, Vector3f &dist_with_ofs, Vector3f &vel_ned); @@ -86,10 +95,14 @@ class AP_Follow // get bearing to target (including offset) in degrees (for reporting purposes) float get_bearing_to_target() const { return _bearing_to_target; } + // get system time of last position update + uint32_t get_last_update_ms() const { return _last_location_update_ms; } + // parameter list static const struct AP_Param::GroupInfo var_info[]; private: + static AP_Follow *_singleton; // get velocity estimate in m/s in NED frame using dt since last update bool get_velocity_ned(Vector3f &vel_ned, float dt) const; @@ -132,3 +145,7 @@ class AP_Follow // setup jitter correction with max transport lag of 3s JitterCorrection _jitter{3000}; }; + +namespace AP { + AP_Follow &follow(); +}; diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_Backend.cpp b/libraries/AP_Frsky_Telem/AP_Frsky_Backend.cpp index 58315ede25d..d3a41f83747 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_Backend.cpp +++ b/libraries/AP_Frsky_Telem/AP_Frsky_Backend.cpp @@ -85,8 +85,8 @@ void AP_Frsky_Backend::calc_nav_alt(void) } } - _SPort_data.alt_nav_meters = (int16_t)current_height; - _SPort_data.alt_nav_cm = (current_height - _SPort_data.alt_nav_meters) * 100; + _SPort_data.alt_nav_meters = float_to_uint16(current_height); + _SPort_data.alt_nav_cm = float_to_uint16((current_height - _SPort_data.alt_nav_meters) * 100); } /* @@ -121,12 +121,12 @@ void AP_Frsky_Backend::calc_gps_position(void) _SPort_data.lon_ew = (loc.lng < 0) ? 'W' : 'E'; float alt = loc.alt * 0.01f; - _SPort_data.alt_gps_meters = (int16_t)alt; - _SPort_data.alt_gps_cm = (alt - _SPort_data.alt_gps_meters) * 100; + _SPort_data.alt_gps_meters = float_to_uint16(alt); + _SPort_data.alt_gps_cm = float_to_uint16((alt - _SPort_data.alt_gps_meters) * 100); const float speed = AP::ahrs().groundspeed(); - _SPort_data.speed_in_meter = speed; - _SPort_data.speed_in_centimeter = (speed - _SPort_data.speed_in_meter) * 100; + _SPort_data.speed_in_meter = float_to_int16(speed); + _SPort_data.speed_in_centimeter = float_to_uint16((speed - _SPort_data.speed_in_meter) * 100); } else { _SPort_data.latdddmm = 0; _SPort_data.latmmmm = 0; diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_MAVliteMsgHandler.cpp b/libraries/AP_Frsky_Telem/AP_Frsky_MAVliteMsgHandler.cpp index 4f9ecaf0e99..9952f6c6aed 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_MAVliteMsgHandler.cpp +++ b/libraries/AP_Frsky_Telem/AP_Frsky_MAVliteMsgHandler.cpp @@ -142,6 +142,7 @@ MAV_RESULT AP_Frsky_MAVliteMsgHandler::handle_command_preflight_calibration_baro MAV_RESULT AP_Frsky_MAVliteMsgHandler::handle_command_do_fence_enable(const mavlink_command_long_t &mav_command_long) { +#if AP_FENCE_ENABLED AC_Fence *fence = AP::fence(); if (fence == nullptr) { return MAV_RESULT_UNSUPPORTED; @@ -157,6 +158,9 @@ MAV_RESULT AP_Frsky_MAVliteMsgHandler::handle_command_do_fence_enable(const mavl default: return MAV_RESULT_FAILED; } +#else + return MAV_RESULT_UNSUPPORTED; +#endif // AP_FENCE_ENABLED } /* diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_SPort.cpp b/libraries/AP_Frsky_Telem/AP_Frsky_SPort.cpp index 8f69544c607..a16b5c08e54 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_SPort.cpp +++ b/libraries/AP_Frsky_Telem/AP_Frsky_SPort.cpp @@ -246,7 +246,7 @@ extern const AP_HAL::HAL& hal; bool AP_Frsky_SPortParser::should_process_packet(const uint8_t *packet, bool discard_duplicates) { // check for duplicate packets - if (discard_duplicates && _parse_state.last_packet != nullptr) { + if (discard_duplicates) { /* Note: the polling byte packet[0] should be ignored in the comparison because we might get the same packet with different polling bytes @@ -323,10 +323,10 @@ bool AP_Frsky_SPortParser::get_packet(AP_Frsky_SPort::sport_packet_t &sport_pack } const AP_Frsky_SPort::sport_packet_t sp { - _parse_state.rx_buffer[0], + { _parse_state.rx_buffer[0], _parse_state.rx_buffer[1], le16toh_ptr(&_parse_state.rx_buffer[2]), - le32toh_ptr(&_parse_state.rx_buffer[4]) + le32toh_ptr(&_parse_state.rx_buffer[4]) }, }; sport_packet = sp; diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.cpp b/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.cpp index cc82caa8709..59ba1406836 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.cpp +++ b/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.cpp @@ -582,12 +582,14 @@ uint32_t AP_Frsky_SPort_Passthrough::calc_ap_status(void) ap_status |= (uint8_t)(AP_Notify::flags.ekf_bad)<enabled() && fence->present()) << AP_FENCE_PRESENT_OFFSET; ap_status |= (uint8_t)(fence->get_breaches()>0) << AP_FENCE_BREACH_OFFSET; } +#endif // signed throttle [-100,100] scaled down to [-63,63] on 7 bits, MSB for sign + 6 bits for 0-63 ap_status |= prep_number(gcs().get_hud_throttle()*0.63, 2, 0)< #include #include +#include #include "AP_GPS_NOVA.h" #include "AP_GPS_ERB.h" @@ -36,6 +37,9 @@ #include "AP_GPS_MSP.h" #include "AP_GPS_ExternalAHRS.h" #include "GPS_Backend.h" +#if HAL_SIM_GPS_ENABLED +#include "AP_GPS_SITL.h" +#endif #if HAL_ENABLE_LIBUAVCAN_DRIVERS #include @@ -69,12 +73,15 @@ extern const AP_HAL::HAL &hal; const uint32_t AP_GPS::_baudrates[] = {9600U, 115200U, 4800U, 19200U, 38400U, 57600U, 230400U, 460800U}; // initialisation blobs to send to the GPS to try to get it into the -// right mode +// right mode. const char AP_GPS::_initialisation_blob[] = +#if AP_GPS_UBLOX_ENABLED UBLOX_SET_BINARY_230400 +#endif #if AP_GPS_SIRF_ENABLED SIRF_SET_BINARY #endif + "" // to compile we need *some_initialiser if all backends compiled out ; AP_GPS *AP_GPS::_singleton; @@ -301,14 +308,12 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = { AP_GROUPINFO("_BLEND_TC", 21, AP_GPS, _blend_tc, 10.0f), #endif -#if GPS_MOVING_BASELINE // @Param: _DRV_OPTIONS // @DisplayName: driver options // @Description: Additional backend specific options - // @Bitmask: 0:Use UART2 for moving baseline on ublox,1:Use base station for GPS yaw on SBF,2:Use baudrate 115200,3:Use dedicated CAN port b/w GPSes for moving baseline + // @Bitmask: 0:Use UART2 for moving baseline on ublox,1:Use base station for GPS yaw on SBF,2:Use baudrate 115200,3:Use dedicated CAN port b/w GPSes for moving baseline,4:Use ellipsoid height instead of AMSL for uBlox driver // @User: Advanced AP_GROUPINFO("_DRV_OPTIONS", 22, AP_GPS, _driver_options, 0), -#endif #if AP_GPS_SBF_ENABLED // @Param: _COM_PORT @@ -359,7 +364,7 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = { #if HAL_ENABLE_LIBUAVCAN_DRIVERS // @Param: _CAN_NODEID1 // @DisplayName: GPS Node ID 1 - // @Description: GPS Node id for discovered first. + // @Description: GPS Node id for first-discovered GPS. // @ReadOnly: True // @User: Advanced AP_GROUPINFO("_CAN_NODEID1", 28, AP_GPS, _node_id[0], 0), @@ -367,21 +372,21 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = { #if GPS_MAX_RECEIVERS > 1 // @Param: _CAN_NODEID2 // @DisplayName: GPS Node ID 2 - // @Description: GPS Node id for discovered second. + // @Description: GPS Node id for second-discovered GPS. // @ReadOnly: True // @User: Advanced AP_GROUPINFO("_CAN_NODEID2", 29, AP_GPS, _node_id[1], 0), #endif // GPS_MAX_RECEIVERS > 1 // @Param: 1_CAN_OVRIDE // @DisplayName: First DroneCAN GPS NODE ID - // @Description: GPS Node id for first GPS. If 0 the gps will be automatically selected on first come basis. + // @Description: GPS Node id for first GPS. If 0 the gps will be automatically selected on a first-come-first-GPS basis. // @User: Advanced AP_GROUPINFO("1_CAN_OVRIDE", 30, AP_GPS, _override_node_id[0], 0), #if GPS_MAX_RECEIVERS > 1 // @Param: 2_CAN_OVRIDE // @DisplayName: Second DroneCAN GPS NODE ID - // @Description: GPS Node id for second GPS. If 0 the gps will be automatically selected on first come basis. + // @Description: GPS Node id for second GPS. If 0 the gps will be automatically selected on a second-come-second-GPS basis. // @User: Advanced AP_GROUPINFO("2_CAN_OVRIDE", 31, AP_GPS, _override_node_id[1], 0), #endif // GPS_MAX_RECEIVERS > 1 @@ -453,7 +458,7 @@ void AP_GPS::init(const AP_SerialManager& serial_manager) // sanity check update rate for (uint8_t i=0; i GPS_MAX_RATE_MS) { - _rate_ms[i] = GPS_MAX_RATE_MS; + _rate_ms[i].set(GPS_MAX_RATE_MS); } } } @@ -549,6 +554,72 @@ void AP_GPS::send_blob_start(uint8_t instance, const char *_blob, uint16_t size) initblob_state[instance].remaining = size; } +/* + initialise state for sending binary blob initialisation strings. We + may choose different blobs not just based on type but also based on + parameters. + */ +void AP_GPS::send_blob_start(uint8_t instance) +{ +#if AP_GPS_UBLOX_ENABLED + if (_type[instance] == GPS_TYPE_UBLOX && option_set(DriverOptions::UBX_Use115200)) { + static const char blob[] = UBLOX_SET_BINARY_115200; + send_blob_start(instance, blob, sizeof(blob)); + return; + } +#endif // AP_GPS_UBLOX_ENABLED + +#if GPS_MOVING_BASELINE && AP_GPS_UBLOX_ENABLED + if ((_type[instance] == GPS_TYPE_UBLOX_RTK_BASE || + _type[instance] == GPS_TYPE_UBLOX_RTK_ROVER) && + !option_set(DriverOptions::UBX_MBUseUart2)) { + // we use 460800 when doing moving baseline as we need + // more bandwidth. We don't do this if using UART2, as + // in that case the RTCMv3 data doesn't go over the + // link to the flight controller + static const char blob[] = UBLOX_SET_BINARY_460800; + send_blob_start(instance, blob, sizeof(blob)); + return; + } +#endif + +#if AP_GPS_NMEA_ENABLED + if (_type[instance] == GPS_TYPE_HEMI) { + send_blob_start(instance, AP_GPS_NMEA_HEMISPHERE_INIT_STRING, strlen(AP_GPS_NMEA_HEMISPHERE_INIT_STRING)); + return; + } +#endif // AP_GPS_NMEA_ENABLED + + // the following devices don't have init blobs: + const char *blob = nullptr; + uint32_t blob_size = 0; + switch (_type[instance]) { +#if AP_GPS_SBF_ENABLED + case GPS_TYPE_SBF: +#endif //AP_GPS_SBF_ENABLED +#if AP_GPS_GSOF_ENABLED + case GPS_TYPE_GSOF: +#endif //AP_GPS_GSOF_ENABLED +#if AP_GPS_NOVA_ENABLED + case GPS_TYPE_NOVA: +#endif //AP_GPS_NOVA_ENABLED +#if HAL_SIM_GPS_ENABLED + case GPS_TYPE_SITL: +#endif // HAL_SIM_GPS_ENABLED + // none of these GPSs have initialisation blobs + break; + default: + // send combined initialisation blob, on the assumption that the + // GPS units will parse what they need and ignore the data they + // don't understand: + blob = _initialisation_blob; + blob_size = sizeof(_initialisation_blob); + break; + } + + send_blob_start(instance, blob, blob_size); +} + /* send some more initialisation string bytes if there is room in the UART transmit buffer @@ -579,26 +650,41 @@ void AP_GPS::send_blob_update(uint8_t instance) */ void AP_GPS::detect_instance(uint8_t instance) { - AP_GPS_Backend *new_gps = nullptr; - struct detect_state *dstate = &detect_state[instance]; const uint32_t now = AP_HAL::millis(); state[instance].status = NO_GPS; state[instance].hdop = GPS_UNKNOWN_DOP; state[instance].vdop = GPS_UNKNOWN_DOP; + AP_GPS_Backend *new_gps = _detect_instance(instance); + if (new_gps == nullptr) { + return; + } + + state[instance].status = NO_FIX; + drivers[instance] = new_gps; + timing[instance].last_message_time_ms = now; + timing[instance].delta_time_ms = GPS_TIMEOUT_MS; + + new_gps->broadcast_gps_type(); +} + +/* + run detection step for one GPS instance. If this finds a GPS then it + will return it - otherwise nullptr + */ +AP_GPS_Backend *AP_GPS::_detect_instance(uint8_t instance) +{ + struct detect_state *dstate = &detect_state[instance]; + switch (_type[instance]) { // user has to explicitly set the MAV type, do not use AUTO // do not try to detect the MAV type, assume it's there case GPS_TYPE_MAV: -#ifndef HAL_BUILD_AP_PERIPH #if AP_GPS_MAV_ENABLED dstate->auto_detected_baud = false; // specified, not detected - new_gps = new AP_GPS_MAV(*this, state[instance], nullptr); - goto found_gps; + return new AP_GPS_MAV(*this, state[instance], nullptr); #endif //AP_GPS_MAV_ENABLED -#endif - break; // user has to explicitly set the UAVCAN type, do not use AUTO case GPS_TYPE_UAVCAN: @@ -606,21 +692,18 @@ void AP_GPS::detect_instance(uint8_t instance) case GPS_TYPE_UAVCAN_RTK_ROVER: #if HAL_ENABLE_LIBUAVCAN_DRIVERS dstate->auto_detected_baud = false; // specified, not detected - new_gps = AP_GPS_UAVCAN::probe(*this, state[instance]); - goto found_gps; + return AP_GPS_UAVCAN::probe(*this, state[instance]); #endif - return; // We don't do anything here if UAVCAN is not supported + return nullptr; // We don't do anything here if UAVCAN is not supported #if HAL_MSP_GPS_ENABLED case GPS_TYPE_MSP: dstate->auto_detected_baud = false; // specified, not detected - new_gps = new AP_GPS_MSP(*this, state[instance], nullptr); - goto found_gps; + return new AP_GPS_MSP(*this, state[instance], nullptr); #endif #if HAL_EXTERNAL_AHRS_ENABLED case GPS_TYPE_EXTERNAL_AHRS: dstate->auto_detected_baud = false; // specified, not detected - new_gps = new AP_GPS_ExternalAHRS(*this, state[instance], nullptr); - goto found_gps; + return new AP_GPS_ExternalAHRS(*this, state[instance], nullptr); #endif default: break; @@ -628,36 +711,13 @@ void AP_GPS::detect_instance(uint8_t instance) if (_port[instance] == nullptr) { // UART not available - return; + return nullptr; } // all remaining drivers automatically cycle through baud rates to detect // the correct baud rate, and should have the selected baud broadcast dstate->auto_detected_baud = true; - - // don't build the less common GPS drivers on F1 AP_Periph -#if !defined(HAL_BUILD_AP_PERIPH) || !defined(STM32F1) - switch (_type[instance]) { -#if AP_GPS_SBF_ENABLED - // by default the sbf/trimble gps outputs no data on its port, until configured. - case GPS_TYPE_SBF: - new_gps = new AP_GPS_SBF(*this, state[instance], _port[instance]); - break; -#endif //AP_GPS_SBF_ENABLED -#if AP_GPS_GSOF_ENABLED - case GPS_TYPE_GSOF: - new_gps = new AP_GPS_GSOF(*this, state[instance], _port[instance]); - break; -#endif //AP_GPS_GSOF_ENABLED -#if AP_GPS_NOVA_ENABLED - case GPS_TYPE_NOVA: - new_gps = new AP_GPS_NOVA(*this, state[instance], _port[instance]); - break; -#endif //AP_GPS_NOVA_ENABLED - default: - break; - } -#endif // HAL_BUILD_AP_PERIPH + const uint32_t now = AP_HAL::millis(); if (now - dstate->last_baud_change_ms > GPS_BAUD_TIME_MS) { // try the next baud rate @@ -672,54 +732,61 @@ void AP_GPS::detect_instance(uint8_t instance) _port[instance]->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE); dstate->last_baud_change_ms = now; - if (_auto_config >= GPS_AUTO_CONFIG_ENABLE_SERIAL_ONLY && new_gps == nullptr) { - if (_type[instance] == GPS_TYPE_UBLOX && (_driver_options & AP_GPS_Backend::DriverOptions::UBX_Use115200)) { - static const char blob[] = UBLOX_SET_BINARY_115200; - send_blob_start(instance, blob, sizeof(blob)); - } else if ((_type[instance] == GPS_TYPE_UBLOX_RTK_BASE || - _type[instance] == GPS_TYPE_UBLOX_RTK_ROVER) && - ((_driver_options.get() & AP_GPS_Backend::DriverOptions::UBX_MBUseUart2) == 0)) { - // we use 460800 when doing moving baseline as we need - // more bandwidth. We don't do this if using UART2, as - // in that case the RTCMv3 data doesn't go over the - // link to the flight controller - static const char blob[] = UBLOX_SET_BINARY_460800; - send_blob_start(instance, blob, sizeof(blob)); -#if AP_GPS_NMEA_ENABLED - } else if (_type[instance] == GPS_TYPE_HEMI) { - send_blob_start(instance, AP_GPS_NMEA_HEMISPHERE_INIT_STRING, strlen(AP_GPS_NMEA_HEMISPHERE_INIT_STRING)); -#endif // AP_GPS_NMEA_ENABLED - } else { - send_blob_start(instance, _initialisation_blob, sizeof(_initialisation_blob)); - } + if (_auto_config >= GPS_AUTO_CONFIG_ENABLE_SERIAL_ONLY) { + send_blob_start(instance); } } - if (_auto_config >= GPS_AUTO_CONFIG_ENABLE_SERIAL_ONLY && new_gps == nullptr) { + if (_auto_config >= GPS_AUTO_CONFIG_ENABLE_SERIAL_ONLY) { send_blob_update(instance); } - while (initblob_state[instance].remaining == 0 && _port[instance]->available() > 0 - && new_gps == nullptr) { - uint8_t data = _port[instance]->read(); - /* - running a uBlox at less than 38400 will lead to packet - corruption, as we can't receive the packets in the 200ms - window for 5Hz fixes. The NMEA startup message should force - the uBlox into 230400 no matter what rate it is configured - for. - */ + switch (_type[instance]) { +#if AP_GPS_SBF_ENABLED + // by default the sbf/trimble gps outputs no data on its port, until configured. + case GPS_TYPE_SBF: + return new AP_GPS_SBF(*this, state[instance], _port[instance]); +#endif //AP_GPS_SBF_ENABLED +#if AP_GPS_GSOF_ENABLED + case GPS_TYPE_GSOF: + return new AP_GPS_GSOF(*this, state[instance], _port[instance]); +#endif //AP_GPS_GSOF_ENABLED +#if AP_GPS_NOVA_ENABLED + case GPS_TYPE_NOVA: + return new AP_GPS_NOVA(*this, state[instance], _port[instance]); +#endif //AP_GPS_NOVA_ENABLED + +#if HAL_SIM_GPS_ENABLED + case GPS_TYPE_SITL: + return new AP_GPS_SITL(*this, state[instance], _port[instance]); +#endif // HAL_SIM_GPS_ENABLED + + default: + break; + } + + if (initblob_state[instance].remaining != 0) { + // don't run detection engines if we haven't sent out the initblobs + return nullptr; + } + + uint16_t bytecount = MIN(8192U, _port[instance]->available()); + + while (bytecount-- > 0) { + const uint8_t data = _port[instance]->read(); + (void)data; // if all backends are compiled out then "data" is unused +#if AP_GPS_UBLOX_ENABLED if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_UBLOX) && ((!_auto_config && _baudrates[dstate->current_baud] >= 38400) || - (_baudrates[dstate->current_baud] >= 115200 && (_driver_options & AP_GPS_Backend::DriverOptions::UBX_Use115200)) || + (_baudrates[dstate->current_baud] >= 115200 && option_set(DriverOptions::UBX_Use115200)) || _baudrates[dstate->current_baud] == 230400) && AP_GPS_UBLOX::_detect(dstate->ublox_detect_state, data)) { - new_gps = new AP_GPS_UBLOX(*this, state[instance], _port[instance], GPS_ROLE_NORMAL); + return new AP_GPS_UBLOX(*this, state[instance], _port[instance], GPS_ROLE_NORMAL); } - const uint32_t ublox_mb_required_baud = (_driver_options.get() & AP_GPS_Backend::DriverOptions::UBX_MBUseUart2)?230400:460800; + const uint32_t ublox_mb_required_baud = option_set(DriverOptions::UBX_MBUseUart2)?230400:460800; if ((_type[instance] == GPS_TYPE_UBLOX_RTK_BASE || _type[instance] == GPS_TYPE_UBLOX_RTK_ROVER) && _baudrates[dstate->current_baud] == ublox_mb_required_baud && @@ -730,56 +797,44 @@ void AP_GPS::detect_instance(uint8_t instance) } else { role = GPS_ROLE_MB_ROVER; } - new_gps = new AP_GPS_UBLOX(*this, state[instance], _port[instance], role); + return new AP_GPS_UBLOX(*this, state[instance], _port[instance], role); } -#ifndef HAL_BUILD_AP_PERIPH +#endif // AP_GPS_UBLOX_ENABLED #if AP_GPS_SBP2_ENABLED - else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_SBP) && + if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_SBP) && AP_GPS_SBP2::_detect(dstate->sbp2_detect_state, data)) { - new_gps = new AP_GPS_SBP2(*this, state[instance], _port[instance]); + return new AP_GPS_SBP2(*this, state[instance], _port[instance]); } #endif //AP_GPS_SBP2_ENABLED #if AP_GPS_SBP_ENABLED - else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_SBP) && + if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_SBP) && AP_GPS_SBP::_detect(dstate->sbp_detect_state, data)) { - new_gps = new AP_GPS_SBP(*this, state[instance], _port[instance]); + return new AP_GPS_SBP(*this, state[instance], _port[instance]); } #endif //AP_GPS_SBP_ENABLED #if !HAL_MINIMIZE_FEATURES && AP_GPS_SIRF_ENABLED - else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_SIRF) && + if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_SIRF) && AP_GPS_SIRF::_detect(dstate->sirf_detect_state, data)) { - new_gps = new AP_GPS_SIRF(*this, state[instance], _port[instance]); + return new AP_GPS_SIRF(*this, state[instance], _port[instance]); } #endif #if AP_GPS_ERB_ENABLED - else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_ERB) && + if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_ERB) && AP_GPS_ERB::_detect(dstate->erb_detect_state, data)) { - new_gps = new AP_GPS_ERB(*this, state[instance], _port[instance]); + return new AP_GPS_ERB(*this, state[instance], _port[instance]); } #endif // AP_GPS_ERB_ENABLED #if AP_GPS_NMEA_ENABLED - else if ((_type[instance] == GPS_TYPE_NMEA || + if ((_type[instance] == GPS_TYPE_NMEA || _type[instance] == GPS_TYPE_HEMI || _type[instance] == GPS_TYPE_ALLYSTAR) && AP_GPS_NMEA::_detect(dstate->nmea_detect_state, data)) { - new_gps = new AP_GPS_NMEA(*this, state[instance], _port[instance]); + return new AP_GPS_NMEA(*this, state[instance], _port[instance]); } #endif //AP_GPS_NMEA_ENABLED - -#endif // HAL_BUILD_AP_PERIPH - if (new_gps) { - goto found_gps; - } } -found_gps: - if (new_gps != nullptr) { - state[instance].status = NO_FIX; - drivers[instance] = new_gps; - timing[instance].last_message_time_ms = now; - timing[instance].delta_time_ms = GPS_TIMEOUT_MS; - new_gps->broadcast_gps_type(); - } + return nullptr; } AP_GPS::GPS_Status AP_GPS::highest_supported_status(uint8_t instance) const @@ -1113,13 +1168,34 @@ void AP_GPS::update_primary(void) if (primary_instance == GPS_BLENDED_INSTANCE) { primary_instance = 0; for (uint8_t i=1; i state[primary_instance].status) || - ((state[i].status == state[primary_instance].status) && (state[i].num_sats > state[primary_instance].num_sats))) { + // choose GPS with highest state or higher number of + // satellites. Reject a GPS with an old update time, as it + // may be the old timestamp that triggered the loss of + // blending + const uint32_t delay_threshold = 400; + const bool higher_status = state[i].status > state[primary_instance].status; + const bool old_data_primary = (now - state[primary_instance].last_gps_time_ms) > delay_threshold; + const bool old_data = (now - state[i].last_gps_time_ms) > delay_threshold; + const bool equal_status = state[i].status == state[primary_instance].status; + const bool more_sats = state[i].num_sats > state[primary_instance].num_sats; + if (old_data && !old_data_primary) { + // don't switch to a GPS that has not updated in 400ms + continue; + } + if (state[i].status < GPS_OK_FIX_3D) { + // don't use a GPS without 3D fix + continue; + } + // select the new GPS if the primary has old data, or new + // GPS either has higher status, or has the same status + // and more satellites + if ((old_data_primary && !old_data) || + higher_status || + (equal_status && more_sats)) { primary_instance = i; - _last_instance_swap_ms = now; } } + _last_instance_swap_ms = now; return; } #endif // defined(GPS_BLENDED_INSTANCE) @@ -1298,6 +1374,11 @@ void AP_GPS::send_mavlink_gps_raw(mavlink_channel_t chan) float hacc = 0.0f; float vacc = 0.0f; float sacc = 0.0f; + float undulation = 0.0; + int32_t height_elipsoid_mm = 0; + if (get_undulation(0, undulation)) { + height_elipsoid_mm = loc.alt*10 - undulation*1000; + } horizontal_accuracy(0, hacc); vertical_accuracy(0, vacc); speed_accuracy(0, sacc); @@ -1313,7 +1394,7 @@ void AP_GPS::send_mavlink_gps_raw(mavlink_channel_t chan) ground_speed(0)*100, // cm/s ground_course(0)*100, // 1/100 degrees, num_sats(0), - 0, // TODO: Elipsoid height in mm + height_elipsoid_mm, // Elipsoid height in mm hacc * 1000, // one-sigma standard deviation in mm vacc * 1000, // one-sigma standard deviation in mm sacc * 1000, // one-sigma standard deviation in mm/s @@ -1333,6 +1414,11 @@ void AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan) float hacc = 0.0f; float vacc = 0.0f; float sacc = 0.0f; + float undulation = 0.0; + float height_elipsoid_mm = 0; + if (get_undulation(0, undulation)) { + height_elipsoid_mm = loc.alt*10 - undulation*1000; + } horizontal_accuracy(1, hacc); vertical_accuracy(1, vacc); speed_accuracy(1, sacc); @@ -1351,7 +1437,7 @@ void AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan) state[1].rtk_num_sats, state[1].rtk_age_ms, gps_yaw_cdeg(1), - 0, // TODO: Elipsoid height in mm + height_elipsoid_mm, // Elipsoid height in mm hacc * 1000, // one-sigma standard deviation in mm vacc * 1000, // one-sigma standard deviation in mm sacc * 1000, // one-sigma standard deviation in mm/s @@ -1436,11 +1522,24 @@ void AP_GPS::handle_gps_rtcm_fragment(uint8_t flags, const uint8_t *data, uint8_ const uint8_t fragment = (flags >> 1U) & 0x03; const uint8_t sequence = (flags >> 3U) & 0x1F; + uint8_t* start_of_fragment_in_buffer = &rtcm_buffer->buffer[MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN * (uint16_t)fragment]; + bool should_clear_previous_fragments = false; + + if (rtcm_buffer->fragments_received) { + const bool sequence_nr_changed = rtcm_buffer->sequence != sequence; + const bool seen_this_fragment_index = rtcm_buffer->fragments_received & (1U << fragment); + + // check whether this is a duplicate fragment. If it is, we can + // return early. + if (!sequence_nr_changed && seen_this_fragment_index && !memcmp(start_of_fragment_in_buffer, data, len)) { + return; + } - // see if this fragment is consistent with existing fragments - if (rtcm_buffer->fragments_received && - (rtcm_buffer->sequence != sequence || - (rtcm_buffer->fragments_received & (1U<fragment_count = 0; @@ -1452,7 +1551,7 @@ void AP_GPS::handle_gps_rtcm_fragment(uint8_t flags, const uint8_t *data, uint8_ rtcm_buffer->fragments_received |= (1U << fragment); // copy the data - memcpy(&rtcm_buffer->buffer[MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN*(uint16_t)fragment], data, len); + memcpy(start_of_fragment_in_buffer, data, len); // when we get a fragment of less than max size then we know the // number of fragments. Note that this means if you want to send a @@ -1630,7 +1729,7 @@ bool AP_GPS::calc_blend_weights(void) for (uint8_t i=0; i= GPS_OK_FIX_3D) { if (state[i].have_speed_accuracy && state[i].speed_accuracy > 0.0f) { - speed_accuracy_sum_sq += state[i].speed_accuracy * state[i].speed_accuracy; + speed_accuracy_sum_sq += sq(state[i].speed_accuracy); } else { // not all receivers support this metric so set it to zero and don't use it speed_accuracy_sum_sq = 0.0f; @@ -1646,7 +1745,7 @@ bool AP_GPS::calc_blend_weights(void) for (uint8_t i=0; i= GPS_OK_FIX_2D) { if (state[i].have_horizontal_accuracy && state[i].horizontal_accuracy > 0.0f) { - horizontal_accuracy_sum_sq += state[i].horizontal_accuracy * state[i].horizontal_accuracy; + horizontal_accuracy_sum_sq += sq(state[i].horizontal_accuracy); } else { // not all receivers support this metric so set it to zero and don't use it horizontal_accuracy_sum_sq = 0.0f; @@ -1662,7 +1761,7 @@ bool AP_GPS::calc_blend_weights(void) for (uint8_t i=0; i= GPS_OK_FIX_3D) { if (state[i].have_vertical_accuracy && state[i].vertical_accuracy > 0.0f) { - vertical_accuracy_sum_sq += state[i].vertical_accuracy * state[i].vertical_accuracy; + vertical_accuracy_sum_sq += sq(state[i].vertical_accuracy); } else { // not all receivers support this metric so set it to zero and don't use it vertical_accuracy_sum_sq = 0.0f; @@ -1683,12 +1782,12 @@ bool AP_GPS::calc_blend_weights(void) // calculate a weighting using the reported horizontal position float hpos_blend_weights[GPS_MAX_RECEIVERS] = {}; - if (horizontal_accuracy_sum_sq > 0.0f && (_blend_mask & BLEND_MASK_USE_HPOS_ACC)) { + if (horizontal_accuracy_sum_sq > 0.0f) { // calculate the weights using the inverse of the variances float sum_of_hpos_weights = 0.0f; for (uint8_t i=0; i= GPS_OK_FIX_2D && state[i].horizontal_accuracy >= 0.001f) { - hpos_blend_weights[i] = horizontal_accuracy_sum_sq / (state[i].horizontal_accuracy * state[i].horizontal_accuracy); + hpos_blend_weights[i] = horizontal_accuracy_sum_sq / sq(state[i].horizontal_accuracy); sum_of_hpos_weights += hpos_blend_weights[i]; } } @@ -1703,12 +1802,12 @@ bool AP_GPS::calc_blend_weights(void) // calculate a weighting using the reported vertical position accuracy float vpos_blend_weights[GPS_MAX_RECEIVERS] = {}; - if (vertical_accuracy_sum_sq > 0.0f && (_blend_mask & BLEND_MASK_USE_VPOS_ACC)) { + if (vertical_accuracy_sum_sq > 0.0f) { // calculate the weights using the inverse of the variances float sum_of_vpos_weights = 0.0f; for (uint8_t i=0; i= GPS_OK_FIX_3D && state[i].vertical_accuracy >= 0.001f) { - vpos_blend_weights[i] = vertical_accuracy_sum_sq / (state[i].vertical_accuracy * state[i].vertical_accuracy); + vpos_blend_weights[i] = vertical_accuracy_sum_sq / sq(state[i].vertical_accuracy); sum_of_vpos_weights += vpos_blend_weights[i]; } } @@ -1723,12 +1822,12 @@ bool AP_GPS::calc_blend_weights(void) // calculate a weighting using the reported speed accuracy float spd_blend_weights[GPS_MAX_RECEIVERS] = {}; - if (speed_accuracy_sum_sq > 0.0f && (_blend_mask & BLEND_MASK_USE_SPD_ACC)) { + if (speed_accuracy_sum_sq > 0.0f) { // calculate the weights using the inverse of the variances float sum_of_spd_weights = 0.0f; for (uint8_t i=0; i= GPS_OK_FIX_3D && state[i].speed_accuracy >= 0.001f) { - spd_blend_weights[i] = speed_accuracy_sum_sq / (state[i].speed_accuracy * state[i].speed_accuracy); + spd_blend_weights[i] = speed_accuracy_sum_sq / sq(state[i].speed_accuracy); sum_of_spd_weights += spd_blend_weights[i]; } } @@ -1787,6 +1886,16 @@ void AP_GPS::calc_blended_state(void) timing[GPS_BLENDED_INSTANCE].last_fix_time_ms = 0; timing[GPS_BLENDED_INSTANCE].last_message_time_ms = 0; + if (state[0].have_undulation) { + state[GPS_BLENDED_INSTANCE].have_undulation = true; + state[GPS_BLENDED_INSTANCE].undulation = state[0].undulation; + } else if (state[1].have_undulation) { + state[GPS_BLENDED_INSTANCE].have_undulation = true; + state[GPS_BLENDED_INSTANCE].undulation = state[1].undulation; + } else { + state[GPS_BLENDED_INSTANCE].have_undulation = false; + } + // combine the states into a blended solution for (uint8_t i=0; iis_healthy(); +#else /* allow two lost frames before declaring the GPS unhealthy, but require the average frame rate to be close to 5Hz. We allow for @@ -1966,6 +2082,7 @@ bool AP_GPS::is_healthy(uint8_t instance) const return delay_ok && drivers[instance] != nullptr && drivers[instance]->is_healthy(); +#endif // HAL_BUILD_AP_PERIPH } bool AP_GPS::prepare_for_arming(void) { @@ -2032,6 +2149,17 @@ bool AP_GPS::get_error_codes(uint8_t instance, uint32_t &error_codes) const return drivers[instance]->get_error_codes(error_codes); } +// get the difference between WGS84 and AMSL. A positive value means +// the AMSL height is higher than WGS84 ellipsoid height +bool AP_GPS::get_undulation(uint8_t instance, float &undulation) const +{ + if (!state[instance].have_undulation) { + return false; + } + undulation = state[instance].undulation; + return true; +} + // Logging support: // Write an GPS packet void AP_GPS::Write_GPS(uint8_t i) @@ -2065,9 +2193,11 @@ void AP_GPS::Write_GPS(uint8_t i) /* write auxiliary accuracy information as well */ float hacc = 0, vacc = 0, sacc = 0; + float undulation = 0; horizontal_accuracy(i, hacc); vertical_accuracy(i, vacc); speed_accuracy(i, sacc); + get_undulation(i, undulation); struct log_GPA pkt2{ LOG_PACKET_HEADER_INIT(LOG_GPA_MSG), time_us : time_us, @@ -2079,7 +2209,8 @@ void AP_GPS::Write_GPS(uint8_t i) yaw_accuracy : yaw_accuracy_deg, have_vv : (uint8_t)have_vertical_velocity(i), sample_ms : last_message_time_ms(i), - delta_ms : last_message_delta_time_ms(i) + delta_ms : last_message_delta_time_ms(i), + undulation : undulation, }; AP::logger().WriteBlock(&pkt2, sizeof(pkt2)); } diff --git a/libraries/AP_GPS/AP_GPS.h b/libraries/AP_GPS/AP_GPS.h index 3bca1e13c98..cc8a13e7e17 100644 --- a/libraries/AP_GPS/AP_GPS.h +++ b/libraries/AP_GPS/AP_GPS.h @@ -20,9 +20,10 @@ #include #include #include "GPS_detect_state.h" -#include #include #include +#include +#include /** maximum number of GPS instances available on this platform. If more @@ -128,6 +129,9 @@ class AP_GPS GPS_TYPE_EXTERNAL_AHRS = 21, GPS_TYPE_UAVCAN_RTK_BASE = 22, GPS_TYPE_UAVCAN_RTK_ROVER = 23, +#if HAL_SIM_GPS_ENABLED + GPS_TYPE_SITL = 100, +#endif }; /// GPS status codes @@ -193,6 +197,8 @@ class AP_GPS bool have_vertical_accuracy; ///< does GPS give vertical position accuracy? Set to true only once available. bool have_gps_yaw; ///< does GPS give yaw? Set to true only once available. bool have_gps_yaw_accuracy; ///< does the GPS give a heading accuracy estimate? Set to true only once available + float undulation; // + extern const AP_HAL::HAL& hal; #if ERB_DEBUGGING @@ -55,6 +57,9 @@ AP_GPS_ERB::read(void) // read the next byte data = port->read(); +#if AP_GPS_DEBUG_LOGGING_ENABLED + log_data(&data, 1); +#endif reset: switch(_step) { @@ -146,6 +151,8 @@ AP_GPS_ERB::_parse_gps(void) state.location.lng = (int32_t)(_buffer.pos.longitude * (double)1e7); state.location.lat = (int32_t)(_buffer.pos.latitude * (double)1e7); state.location.alt = (int32_t)(_buffer.pos.altitude_msl * 100); + state.have_undulation = true; + state.undulation = _buffer.pos.altitude_msl - _buffer.pos.altitude_ellipsoid; state.status = next_fix; _new_position = true; state.horizontal_accuracy = _buffer.pos.horizontal_accuracy * 1.0e-3f; diff --git a/libraries/AP_GPS/AP_GPS_ERB.h b/libraries/AP_GPS/AP_GPS_ERB.h index d07b6f078ea..8fb6f7ed0e3 100644 --- a/libraries/AP_GPS/AP_GPS_ERB.h +++ b/libraries/AP_GPS/AP_GPS_ERB.h @@ -19,15 +19,9 @@ #pragma once -#include - #include "AP_GPS.h" #include "GPS_Backend.h" -#ifndef AP_GPS_ERB_ENABLED - #define AP_GPS_ERB_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED -#endif - #if AP_GPS_ERB_ENABLED class AP_GPS_ERB : public AP_GPS_Backend { diff --git a/libraries/AP_GPS/AP_GPS_ExternalAHRS.h b/libraries/AP_GPS/AP_GPS_ExternalAHRS.h index 4acd4b42825..b046748034e 100644 --- a/libraries/AP_GPS/AP_GPS_ExternalAHRS.h +++ b/libraries/AP_GPS/AP_GPS_ExternalAHRS.h @@ -19,7 +19,7 @@ #pragma once #include -#include +#include #include "AP_GPS.h" #include "GPS_Backend.h" diff --git a/libraries/AP_GPS/AP_GPS_GSOF.cpp b/libraries/AP_GPS/AP_GPS_GSOF.cpp index bb420b1f597..453e932c2ce 100644 --- a/libraries/AP_GPS/AP_GPS_GSOF.cpp +++ b/libraries/AP_GPS/AP_GPS_GSOF.cpp @@ -76,6 +76,9 @@ AP_GPS_GSOF::read(void) bool ret = false; while (port->available() > 0) { uint8_t temp = port->read(); +#if AP_GPS_DEBUG_LOGGING_ENABLED + log_data(&temp, 1); +#endif ret |= parse(temp); } diff --git a/libraries/AP_GPS/AP_GPS_GSOF.h b/libraries/AP_GPS/AP_GPS_GSOF.h index 74c76aed181..4829ac9ec95 100644 --- a/libraries/AP_GPS/AP_GPS_GSOF.h +++ b/libraries/AP_GPS/AP_GPS_GSOF.h @@ -22,10 +22,6 @@ #include "AP_GPS.h" #include "GPS_Backend.h" -#ifndef AP_GPS_GSOF_ENABLED - #define AP_GPS_GSOF_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED -#endif - #if AP_GPS_GSOF_ENABLED class AP_GPS_GSOF : public AP_GPS_Backend { diff --git a/libraries/AP_GPS/AP_GPS_MAV.h b/libraries/AP_GPS/AP_GPS_MAV.h index bb59400a41d..f0c3872d79c 100644 --- a/libraries/AP_GPS/AP_GPS_MAV.h +++ b/libraries/AP_GPS/AP_GPS_MAV.h @@ -19,8 +19,7 @@ // #pragma once -#include -#include +#include #include "AP_GPS.h" #include "GPS_Backend.h" diff --git a/libraries/AP_GPS/AP_GPS_NMEA.cpp b/libraries/AP_GPS/AP_GPS_NMEA.cpp index 826613747ca..de4dd36b0c8 100644 --- a/libraries/AP_GPS/AP_GPS_NMEA.cpp +++ b/libraries/AP_GPS/AP_GPS_NMEA.cpp @@ -54,12 +54,12 @@ bool AP_GPS_NMEA::read(void) numc = port->available(); while (numc--) { char c = port->read(); - if (_decode(c)) { - parsed = true; - } #if AP_GPS_DEBUG_LOGGING_ENABLED log_data((const uint8_t *)&c, 1); #endif + if (_decode(c)) { + parsed = true; + } } return parsed; } @@ -389,7 +389,7 @@ bool AP_GPS_NMEA::_term_complete() state.ground_speed = state.velocity.xy().length(); _last_3D_velocity_ms = now; } - if (is_equal(3.0f, _ksxt.fields[10])) { + if (is_equal(3.0f, float(_ksxt.fields[10]))) { // have good yaw (from RTK fixed moving baseline solution) _last_yaw_ms = now; state.gps_yaw = _ksxt.fields[4]; diff --git a/libraries/AP_GPS/AP_GPS_NMEA.h b/libraries/AP_GPS/AP_GPS_NMEA.h index 6fbf127cc9b..70b1d5f1720 100644 --- a/libraries/AP_GPS/AP_GPS_NMEA.h +++ b/libraries/AP_GPS/AP_GPS_NMEA.h @@ -46,10 +46,6 @@ #include "AP_GPS.h" #include "GPS_Backend.h" -#ifndef AP_GPS_NMEA_ENABLED - #define AP_GPS_NMEA_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED -#endif - #if AP_GPS_NMEA_ENABLED /// NMEA parser /// @@ -192,7 +188,7 @@ class AP_GPS_NMEA : public AP_GPS_Backend example: $KSXT,20211016083433.00,116.31296102,39.95817066,49.4911,223.57,-11.32,330.19,0.024,,1,3,28,27,,,,-0.012,0.021,0.020,,*2D */ struct { - float fields[21]; + double fields[21]; } _ksxt; }; diff --git a/libraries/AP_GPS/AP_GPS_NOVA.cpp b/libraries/AP_GPS/AP_GPS_NOVA.cpp index 60b17df383c..dc6246c5774 100644 --- a/libraries/AP_GPS/AP_GPS_NOVA.cpp +++ b/libraries/AP_GPS/AP_GPS_NOVA.cpp @@ -90,6 +90,9 @@ AP_GPS_NOVA::read(void) bool ret = false; while (port->available() > 0) { uint8_t temp = port->read(); +#if AP_GPS_DEBUG_LOGGING_ENABLED + log_data(&temp, 1); +#endif ret |= parse(temp); } @@ -205,6 +208,8 @@ AP_GPS_NOVA::process_message(void) state.location.lat = (int32_t) (bestposu.lat * (double)1e7); state.location.lng = (int32_t) (bestposu.lng * (double)1e7); state.location.alt = (int32_t) (bestposu.hgt * 100); + state.have_undulation = true; + state.undulation = bestposu.undulation; state.num_sats = bestposu.svsused; diff --git a/libraries/AP_GPS/AP_GPS_NOVA.h b/libraries/AP_GPS/AP_GPS_NOVA.h index 5a6bdeac047..1136123b427 100644 --- a/libraries/AP_GPS/AP_GPS_NOVA.h +++ b/libraries/AP_GPS/AP_GPS_NOVA.h @@ -22,10 +22,6 @@ #include "AP_GPS.h" #include "GPS_Backend.h" -#ifndef AP_GPS_NOVA_ENABLED - #define AP_GPS_NOVA_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED -#endif - #if AP_GPS_NOVA_ENABLED class AP_GPS_NOVA : public AP_GPS_Backend { diff --git a/libraries/AP_GPS/AP_GPS_SBF.cpp b/libraries/AP_GPS/AP_GPS_SBF.cpp index bf4af75b9b2..334e847a69f 100644 --- a/libraries/AP_GPS/AP_GPS_SBF.cpp +++ b/libraries/AP_GPS/AP_GPS_SBF.cpp @@ -68,7 +68,7 @@ AP_GPS_SBF::AP_GPS_SBF(AP_GPS &_gps, AP_GPS::GPS_State &_state, // if we ever parse RTK observations it will always be of type NED, so set it once state.rtk_baseline_coords_type = RTK_BASELINE_COORDINATE_SYSTEM_NED; - if (driver_options() & DriverOptions::SBF_UseBaseForYaw) { + if (option_set(AP_GPS::DriverOptions::SBF_UseBaseForYaw)) { state.gps_yaw_configured = true; } } @@ -86,6 +86,9 @@ AP_GPS_SBF::read(void) uint32_t available_bytes = port->available(); for (uint32_t i = 0; i < available_bytes; i++) { uint8_t temp = port->read(); +#if AP_GPS_DEBUG_LOGGING_ENABLED + log_data(&temp, 1); +#endif ret |= parse(temp); } @@ -416,6 +419,8 @@ AP_GPS_SBF::process_message(void) state.location.lat = (int32_t)(temp.Latitude * RAD_TO_DEG_DOUBLE * (double)1e7); state.location.lng = (int32_t)(temp.Longitude * RAD_TO_DEG_DOUBLE * (double)1e7); state.location.alt = (int32_t)(((float)temp.Height - temp.Undulation) * 1e2f); + state.have_undulation = true; + state.undulation = temp.Undulation; } if (temp.NrSV != 255) { @@ -533,7 +538,7 @@ AP_GPS_SBF::process_message(void) #if GPS_MOVING_BASELINE // copy the baseline data as a yaw source - if (driver_options() & DriverOptions::SBF_UseBaseForYaw) { + if (option_set(AP_GPS::DriverOptions::SBF_UseBaseForYaw)) { calculate_moving_base_yaw(temp.info.Azimuth * 0.01f + 180.0f, Vector3f(temp.info.DeltaNorth, temp.info.DeltaEast, temp.info.DeltaUp).length(), -temp.info.DeltaUp); diff --git a/libraries/AP_GPS/AP_GPS_SBF.h b/libraries/AP_GPS/AP_GPS_SBF.h index 190c4f314b7..ac4944a9ccb 100644 --- a/libraries/AP_GPS/AP_GPS_SBF.h +++ b/libraries/AP_GPS/AP_GPS_SBF.h @@ -22,10 +22,6 @@ #include "AP_GPS.h" #include "GPS_Backend.h" -#ifndef AP_GPS_SBF_ENABLED - #define AP_GPS_SBF_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED -#endif - #if AP_GPS_SBF_ENABLED #define SBF_DISK_ACTIVITY (1 << 7) diff --git a/libraries/AP_GPS/AP_GPS_SBP.cpp b/libraries/AP_GPS/AP_GPS_SBP.cpp index ae08e4f3f48..94eea80116b 100644 --- a/libraries/AP_GPS/AP_GPS_SBP.cpp +++ b/libraries/AP_GPS/AP_GPS_SBP.cpp @@ -30,7 +30,7 @@ extern const AP_HAL::HAL& hal; #define SBP_DEBUGGING 1 -#define SBP_HW_LOGGING 1 +#define SBP_HW_LOGGING HAL_LOGGING_ENABLED #define SBP_TIMEOUT_HEATBEAT 4000 #define SBP_TIMEOUT_PVT 500 @@ -100,6 +100,9 @@ AP_GPS_SBP::_sbp_process() while (port->available() > 0) { uint8_t temp = port->read(); +#if AP_GPS_DEBUG_LOGGING_ENABLED + log_data(&temp, 1); +#endif uint16_t crc; @@ -228,7 +231,9 @@ AP_GPS_SBP::_sbp_process_message() { break; } +#if SBP_HW_LOGGING logging_log_raw_sbp(parser_state.msg_type, parser_state.sender_id, parser_state.msg_len, parser_state.msg_buff); +#endif } bool @@ -292,7 +297,9 @@ AP_GPS_SBP::_attempt_state_update() last_full_update_cpu_ms = now; state.rtk_iar_num_hypotheses = last_iar_num_hypotheses; +#if SBP_HW_LOGGING logging_log_full_update(); +#endif ret = true; } else if (now - last_full_update_cpu_ms > SBP_TIMEOUT_PVT) { diff --git a/libraries/AP_GPS/AP_GPS_SBP.h b/libraries/AP_GPS/AP_GPS_SBP.h index a26ebe220a8..6ebeb1892d6 100644 --- a/libraries/AP_GPS/AP_GPS_SBP.h +++ b/libraries/AP_GPS/AP_GPS_SBP.h @@ -24,10 +24,6 @@ #include "AP_GPS.h" #include "GPS_Backend.h" -#ifndef AP_GPS_SBP_ENABLED - #define AP_GPS_SBP_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED -#endif - #if AP_GPS_SBP_ENABLED class AP_GPS_SBP : public AP_GPS_Backend { diff --git a/libraries/AP_GPS/AP_GPS_SBP2.cpp b/libraries/AP_GPS/AP_GPS_SBP2.cpp index 14ed7695a71..8638e671ebc 100644 --- a/libraries/AP_GPS/AP_GPS_SBP2.cpp +++ b/libraries/AP_GPS/AP_GPS_SBP2.cpp @@ -103,6 +103,9 @@ AP_GPS_SBP2::_sbp_process() while (nleft > 0) { nleft--; uint8_t temp = port->read(); +#if AP_GPS_DEBUG_LOGGING_ENABLED + log_data(&temp, 1); +#endif uint16_t crc; //This switch reads one character at a time, @@ -208,17 +211,21 @@ AP_GPS_SBP2::_sbp_process_message() { case SBP_EXT_EVENT_MSGTYPE: memcpy(&last_event, parser_state.msg_buff, sizeof(struct sbp_ext_event_t)); check_new_itow(last_event.tow, parser_state.msg_len); +#if HAL_LOGGING_ENABLED logging_ext_event(); +#endif break; default: break; } +#if HAL_LOGGING_ENABLED // send all messages we receive to log, even if it's an unsupported message, // so we can do additional post-processing from logs. // The log mask will be used to adjust or suppress logging logging_log_raw_sbp(parser_state.msg_type, parser_state.sender_id, parser_state.msg_len, parser_state.msg_buff); +#endif } int32_t @@ -440,6 +447,7 @@ AP_GPS_SBP2::_detect(struct SBP2_detect_state &state, uint8_t data) return false; } +#if HAL_LOGGING_ENABLED void AP_GPS_SBP2::logging_log_full_update() { @@ -525,4 +533,5 @@ AP_GPS_SBP2::logging_ext_event() { }; AP::logger().WriteBlock(&pkt, sizeof(pkt)); }; +#endif // HAL_LOGGING_ENABLED #endif //AP_GPS_SBP2_ENABLED diff --git a/libraries/AP_GPS/AP_GPS_SBP2.h b/libraries/AP_GPS/AP_GPS_SBP2.h index a82a96c6711..85ae81e04a9 100644 --- a/libraries/AP_GPS/AP_GPS_SBP2.h +++ b/libraries/AP_GPS/AP_GPS_SBP2.h @@ -24,10 +24,6 @@ #include "AP_GPS.h" #include "GPS_Backend.h" -#ifndef AP_GPS_SBP2_ENABLED - #define AP_GPS_SBP2_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED -#endif - #if AP_GPS_SBP2_ENABLED class AP_GPS_SBP2 : public AP_GPS_Backend { diff --git a/libraries/AP_GPS/AP_GPS_SIRF.cpp b/libraries/AP_GPS/AP_GPS_SIRF.cpp index 18f42155c7e..d758003c3ff 100644 --- a/libraries/AP_GPS/AP_GPS_SIRF.cpp +++ b/libraries/AP_GPS/AP_GPS_SIRF.cpp @@ -180,6 +180,8 @@ AP_GPS_SIRF::_parse_gps(void) state.location.lat = swap_int32(_buffer.nav.latitude); state.location.lng = swap_int32(_buffer.nav.longitude); state.location.alt = swap_int32(_buffer.nav.altitude_msl); + state.have_undulation = true; + state.undulation = (state.location.alt - swap_int32(_buffer.nav.altitude_ellipsoid))*0.01; state.ground_speed = swap_int32(_buffer.nav.ground_speed)*0.01f; state.ground_course = wrap_360(swap_int16(_buffer.nav.ground_course)*0.01f); state.num_sats = _buffer.nav.satellites; diff --git a/libraries/AP_GPS/AP_GPS_SIRF.h b/libraries/AP_GPS/AP_GPS_SIRF.h index ca798ffd4c3..d3c1b8ee7a4 100644 --- a/libraries/AP_GPS/AP_GPS_SIRF.h +++ b/libraries/AP_GPS/AP_GPS_SIRF.h @@ -25,10 +25,6 @@ #include "AP_GPS.h" #include "GPS_Backend.h" -#ifndef AP_GPS_SIRF_ENABLED - #define AP_GPS_SIRF_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED -#endif - #if AP_GPS_SIRF_ENABLED #define SIRF_SET_BINARY "$PSRF100,0,38400,8,1,0*3C\r\n" diff --git a/libraries/AP_GPS/AP_GPS_SITL.cpp b/libraries/AP_GPS/AP_GPS_SITL.cpp new file mode 100644 index 00000000000..fda48fb69a7 --- /dev/null +++ b/libraries/AP_GPS/AP_GPS_SITL.cpp @@ -0,0 +1,120 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +#include "AP_GPS_SITL.h" + +#if HAL_SIM_GPS_ENABLED + +#include +#include +#include +#include + +extern const AP_HAL::HAL& hal; + +/* + return GPS time of week in milliseconds + */ +/* + get timeval using simulation time + */ +static void simulation_timeval(struct timeval *tv) +{ + uint64_t now = AP_HAL::micros64(); + static uint64_t first_usec; + static struct timeval first_tv; + if (first_usec == 0) { + first_usec = now; + first_tv.tv_sec = AP::sitl()->start_time_UTC; + } + *tv = first_tv; + tv->tv_sec += now / 1000000ULL; + uint64_t new_usec = tv->tv_usec + (now % 1000000ULL); + tv->tv_sec += new_usec / 1000000ULL; + tv->tv_usec = new_usec % 1000000ULL; +} +static void gps_time(uint16_t *time_week, uint32_t *time_week_ms) +{ + struct timeval tv; + simulation_timeval(&tv); + const uint32_t epoch = 86400*(10*365 + (1980-1969)/4 + 1 + 6 - 2) - (GPS_LEAPSECONDS_MILLIS / 1000ULL); + uint32_t epoch_seconds = tv.tv_sec - epoch; + *time_week = epoch_seconds / AP_SEC_PER_WEEK; + uint32_t t_ms = tv.tv_usec / 1000; + // round time to nearest 200ms + *time_week_ms = (epoch_seconds % AP_SEC_PER_WEEK) * AP_MSEC_PER_SEC + ((t_ms/200) * 200); +} + +bool AP_GPS_SITL::read(void) +{ + const uint32_t now = AP_HAL::millis(); + if (now - last_update_ms < 200) { + return false; + } + last_update_ms = now; + + auto *sitl = AP::sitl(); + + double latitude =sitl->state.latitude; + double longitude = sitl->state.longitude; + float altitude = sitl->state.altitude; + const double speedN = sitl->state.speedN; + const double speedE = sitl->state.speedE; + const double speedD = sitl->state.speedD; + // const double yaw = sitl->state.yawDeg; + + uint16_t time_week; + uint32_t time_week_ms; + + gps_time(&time_week, &time_week_ms); + + state.time_week = time_week; + state.time_week_ms = time_week_ms; + state.status = AP_GPS::GPS_OK_FIX_3D; + state.num_sats = 15; + + state.location = Location{ + int32_t(latitude*1e7), + int32_t(longitude*1e7), + int32_t(altitude*100), + Location::AltFrame::ABSOLUTE + }; + + state.hdop = 100; + state.vdop = 100; + + state.have_vertical_velocity = true; + state.velocity.x = speedN; + state.velocity.y = speedE; + state.velocity.z = speedD; + + state.ground_course = wrap_360(degrees(atan2f(state.velocity.y, state.velocity.x))); + state.ground_speed = state.velocity.xy().length(); + + state.have_speed_accuracy = true; + state.have_horizontal_accuracy = true; + state.have_vertical_accuracy = true; + state.have_vertical_velocity = true; + + // state.horizontal_accuracy = pkt.horizontal_pos_accuracy; + // state.vertical_accuracy = pkt.vertical_pos_accuracy; + // state.speed_accuracy = pkt.horizontal_vel_accuracy; + + state.last_gps_time_ms = now; + + return true; +} + +#endif // HAL_SIM_GPS_ENABLED diff --git a/libraries/AP_GPS/AP_GPS_SITL.h b/libraries/AP_GPS/AP_GPS_SITL.h new file mode 100644 index 00000000000..52079df1a08 --- /dev/null +++ b/libraries/AP_GPS/AP_GPS_SITL.h @@ -0,0 +1,40 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +#pragma once + +#include "GPS_Backend.h" + +#include + +#if HAL_SIM_GPS_ENABLED + +class AP_GPS_SITL : public AP_GPS_Backend +{ + +public: + + using AP_GPS_Backend::AP_GPS_Backend; + + bool read() override; + + const char *name() const override { return "SITL"; } + +private: + + uint32_t last_update_ms; +}; + +#endif // HAL_SIM_GPS_ENABLED diff --git a/libraries/AP_GPS/AP_GPS_UAVCAN.cpp b/libraries/AP_GPS/AP_GPS_UAVCAN.cpp index ddb6205bf6b..36877325d07 100644 --- a/libraries/AP_GPS/AP_GPS_UAVCAN.cpp +++ b/libraries/AP_GPS/AP_GPS_UAVCAN.cpp @@ -75,7 +75,7 @@ UC_REGISTRY_BINDER(RelPosHeadingCb, ardupilot::gnss::RelPosHeading); #else #define NATIVE_TIME_OFFSET 0 #endif -AP_GPS_UAVCAN::DetectedModules AP_GPS_UAVCAN::_detected_modules[] = {0}; +AP_GPS_UAVCAN::DetectedModules AP_GPS_UAVCAN::_detected_modules[]; HAL_Semaphore AP_GPS_UAVCAN::_sem_registry; // Member Methods @@ -367,12 +367,41 @@ AP_GPS_UAVCAN* AP_GPS_UAVCAN::get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t n tempslot = _detected_modules[j]; _detected_modules[j] = _detected_modules[j-1]; _detected_modules[j-1] = tempslot; + // also fix the _detected_module in the driver so that RTCM injection + // can determine if it has the bus to itself + if (_detected_modules[j].driver) { + _detected_modules[j].driver->_detected_module = j; + } + if (_detected_modules[j-1].driver) { + _detected_modules[j-1].driver->_detected_module = j-1; + } } } } return nullptr; } +/* + handle velocity element of message + */ +void AP_GPS_UAVCAN::handle_velocity(const float vx, const float vy, const float vz) +{ + if (!uavcan::isNaN(vx)) { + const Vector3f vel(vx, vy, vz); + interim_state.velocity = vel; + interim_state.ground_speed = vel.xy().length(); + interim_state.ground_course = wrap_360(degrees(atan2f(vel.y, vel.x))); + // assume we have vertical velocity if we ever get a non-zero Z velocity + if (!isnanf(vel.z) && !is_zero(vel.z)) { + interim_state.have_vertical_velocity = true; + } else { + interim_state.have_vertical_velocity = state.have_vertical_velocity; + } + } else { + interim_state.have_vertical_velocity = false; + } +} + void AP_GPS_UAVCAN::handle_fix_msg(const FixCb &cb) { if (seen_fix2) { @@ -412,17 +441,11 @@ void AP_GPS_UAVCAN::handle_fix_msg(const FixCb &cb) loc.lat = cb.msg->latitude_deg_1e8 / 10; loc.lng = cb.msg->longitude_deg_1e8 / 10; loc.alt = cb.msg->height_msl_mm / 10; + interim_state.have_undulation = true; + interim_state.undulation = (cb.msg->height_msl_mm - cb.msg->height_ellipsoid_mm) * 0.001; interim_state.location = loc; - if (!uavcan::isNaN(cb.msg->ned_velocity[0])) { - Vector3f vel(cb.msg->ned_velocity[0], cb.msg->ned_velocity[1], cb.msg->ned_velocity[2]); - interim_state.velocity = vel; - interim_state.ground_speed = vel.xy().length(); - interim_state.ground_course = wrap_360(degrees(atan2f(vel.y, vel.x))); - interim_state.have_vertical_velocity = true; - } else { - interim_state.have_vertical_velocity = false; - } + handle_velocity(cb.msg->ned_velocity[0], cb.msg->ned_velocity[1], cb.msg->ned_velocity[2]); float pos_cov[9]; cb.msg->position_covariance.unpackSquareMatrix(pos_cov); @@ -536,17 +559,11 @@ void AP_GPS_UAVCAN::handle_fix2_msg(const Fix2Cb &cb) loc.lat = cb.msg->latitude_deg_1e8 / 10; loc.lng = cb.msg->longitude_deg_1e8 / 10; loc.alt = cb.msg->height_msl_mm / 10; + interim_state.have_undulation = true; + interim_state.undulation = (cb.msg->height_msl_mm - cb.msg->height_ellipsoid_mm) * 0.001; interim_state.location = loc; - if (!uavcan::isNaN(cb.msg->ned_velocity[0])) { - Vector3f vel(cb.msg->ned_velocity[0], cb.msg->ned_velocity[1], cb.msg->ned_velocity[2]); - interim_state.velocity = vel; - interim_state.ground_speed = vel.xy().length(); - interim_state.ground_course = wrap_360(degrees(atan2f(vel.y, vel.x))); - interim_state.have_vertical_velocity = true; - } else { - interim_state.have_vertical_velocity = false; - } + handle_velocity(cb.msg->ned_velocity[0], cb.msg->ned_velocity[1], cb.msg->ned_velocity[2]); if (cb.msg->covariance.size() == 6) { if (!uavcan::isNaN(cb.msg->covariance[0])) { @@ -926,11 +943,16 @@ bool AP_GPS_UAVCAN::is_configured(void) const */ void AP_GPS_UAVCAN::inject_data(const uint8_t *data, uint16_t len) { - // we only handle this if we are the first UAVCAN GPS, as we send - // the data as broadcast on all UAVCAN devive ports and we don't - // want to send duplicates - if (_detected_module == 0) { - _detected_modules[0].ap_uavcan->send_RTCMStream(data, len); + // we only handle this if we are the first UAVCAN GPS or we are + // using a different uavcan instance than the first GPS, as we + // send the data as broadcast on all UAVCAN devive ports and we + // don't want to send duplicates + const uint32_t now_ms = AP_HAL::millis(); + if (_detected_module == 0 || + _detected_modules[_detected_module].ap_uavcan != _detected_modules[0].ap_uavcan || + now_ms - _detected_modules[0].last_inject_ms > 2000) { + _detected_modules[_detected_module].ap_uavcan->send_RTCMStream(data, len); + _detected_modules[_detected_module].last_inject_ms = now_ms; } } @@ -955,14 +977,14 @@ bool AP_GPS_UAVCAN::handle_param_get_set_response_int(AP_UAVCAN* ap_uavcan, uint } if (strcmp(name, "GPS_MB_ONLY_PORT") == 0 && cfg_step == STEP_SET_MB_CAN_TX) { - if ((gps._driver_options & UAVCAN_MBUseDedicatedBus) && !value) { + if (option_set(AP_GPS::UAVCAN_MBUseDedicatedBus) && !value) { // set up so that another CAN port is used for the Moving Baseline Data // setting this value will allow another CAN port to be used as dedicated // line for the Moving Baseline Data value = 1; requires_save_and_reboot = true; return true; - } else if (!(gps._driver_options & UAVCAN_MBUseDedicatedBus) && value) { + } else if (!option_set(AP_GPS::UAVCAN_MBUseDedicatedBus) && value) { // set up so that all CAN ports are used for the Moving Baseline Data value = 0; requires_save_and_reboot = true; diff --git a/libraries/AP_GPS/AP_GPS_UAVCAN.h b/libraries/AP_GPS/AP_GPS_UAVCAN.h index 71f9d8a9b0f..0ff1b8d0c68 100644 --- a/libraries/AP_GPS/AP_GPS_UAVCAN.h +++ b/libraries/AP_GPS/AP_GPS_UAVCAN.h @@ -92,6 +92,7 @@ class AP_GPS_UAVCAN : public AP_GPS_Backend { void handle_aux_msg(const AuxCb &cb); void handle_heading_msg(const HeadingCb &cb); void handle_status_msg(const StatusCb &cb); + void handle_velocity(const float vx, const float vy, const float vz); #if GPS_MOVING_BASELINE void handle_moving_baseline_msg(const MovingBaselineDataCb &cb, uint8_t node_id); @@ -123,6 +124,7 @@ class AP_GPS_UAVCAN : public AP_GPS_Backend { AP_UAVCAN* ap_uavcan; uint8_t node_id; uint8_t instance; + uint32_t last_inject_ms; AP_GPS_UAVCAN* driver; } _detected_modules[GPS_MAX_RECEIVERS]; diff --git a/libraries/AP_GPS/AP_GPS_UBLOX.cpp b/libraries/AP_GPS/AP_GPS_UBLOX.cpp index 7d7ccfe4446..3060f1fd69b 100644 --- a/libraries/AP_GPS/AP_GPS_UBLOX.cpp +++ b/libraries/AP_GPS/AP_GPS_UBLOX.cpp @@ -18,8 +18,11 @@ // Origin code by Michael Smith, Jordi Munoz and Jose Julio, DIYDrones.com // Substantially rewritten for new GPS driver structure by Andrew Tridgell // -#include "AP_GPS.h" #include "AP_GPS_UBLOX.h" + +#if AP_GPS_UBLOX_ENABLED + +#include "AP_GPS.h" #include #include #include @@ -221,6 +224,22 @@ const AP_GPS_UBLOX::config_list AP_GPS_UBLOX::config_MB_Rover_uart2[] { }; #endif // GPS_MOVING_BASELINE +/* + config changes for M10 + we need to use B1C not B1 signal for Beidou on M10 to allow solid 5Hz, + and also disable Glonass and enable QZSS + */ +const AP_GPS_UBLOX::config_list AP_GPS_UBLOX::config_M10[] { + { ConfigKey::CFG_SIGNAL_BDS_ENA, 1}, + { ConfigKey::CFG_SIGNAL_BDS_B1_ENA, 0}, + { ConfigKey::CFG_SIGNAL_BDS_B1C_ENA, 1}, + { ConfigKey::CFG_SIGNAL_GLO_ENA, 0}, + { ConfigKey::CFG_SIGNAL_QZSS_ENA, 1}, + { ConfigKey::CFG_SIGNAL_QZSS_L1CA_ENA, 1}, + { ConfigKey::CFG_SIGNAL_QZSS_L1S_ENA, 1}, + { ConfigKey::CFG_NAVSPG_DYNMODEL, 8}, // Air < 4g +}; + void AP_GPS_UBLOX::_request_next_config(void) @@ -394,6 +413,30 @@ AP_GPS_UBLOX::_request_next_config(void) } #endif break; + case STEP_TIM_TM2: +#if UBLOX_TIM_TM2_LOGGING + if(!_request_message_rate(CLASS_TIM, MSG_TIM_TM2)) { + _next_message--; + } +#else + _unconfigured_messages &= ~CONFIG_TIM_TM2; +#endif + break; + + + case STEP_M10: { + if (_hardware_generation == UBLOX_M10) { + // special handling of M10 config + const config_list *list = config_M10; + const uint8_t list_length = ARRAY_SIZE(config_M10); + Debug("Sending M10 settings"); + if (!_configure_config_set(list, list_length, CONFIG_M10, UBX_VALSET_LAYER_RAM | UBX_VALSET_LAYER_BBR)) { + _next_message--; + } + } + break; + } + default: // this case should never be reached, do a full reset if it is hit _next_message = STEP_PVT; @@ -470,6 +513,15 @@ AP_GPS_UBLOX::_verify_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate) { } break; #endif // UBLOX_RXM_RAW_LOGGING +#if UBLOX_TIM_TM2_LOGGING + case CLASS_TIM: + if (msg_id == MSG_TIM_TM2) { + desired_rate = RATE_TIM_TM2; + config_msg_id = CONFIG_TIM_TM2; + break; + } + return; +#endif // UBLOX_TIM_TM2_LOGGING default: return; } @@ -723,6 +775,50 @@ void AP_GPS_UBLOX::log_mon_hw2(void) #endif } +#if UBLOX_TIM_TM2_LOGGING +void AP_GPS_UBLOX::log_tim_tm2(void) +{ +#if HAL_LOGGING_ENABLED + if (!should_log()) { + return; + } + +// @LoggerMessage: UBXT +// @Description: uBlox specific UBX-TIM-TM2 logging, see uBlox interface description +// @Field: TimeUS: Time since system startup +// @Field: I: GPS instance number +// @Field: ch: Channel (i.e. EXTINT) upon which the pulse was measured +// @Field: flags: Bitmask +// @Field: count: Rising edge counter +// @Field: wnR: Week number of last rising edge +// @Field: MsR: Tow of rising edge +// @Field: SubMsR: Millisecond fraction of tow of rising edge in nanoseconds +// @Field: wnF: Week number of last falling edge +// @Field: MsF: Tow of falling edge +// @Field: SubMsF: Millisecond fraction of tow of falling edge in nanoseconds +// @Field: accEst: Accuracy estimate + + AP::logger().WriteStreaming("UBXT", + "TimeUS,I,ch,flags,count,wnR,MsR,SubMsR,wnF,MsF,SubMsF,accEst", + "s#----ss-sss", + "F-----CI-CII", + "QBBBHHIIHIII", + AP_HAL::micros64(), + state.instance, + _buffer.tim_tm2.ch, + _buffer.tim_tm2.flags, + _buffer.tim_tm2.count, + _buffer.tim_tm2.wnR, + _buffer.tim_tm2.towMsR, + _buffer.tim_tm2.towSubMsR, + _buffer.tim_tm2.wnF, + _buffer.tim_tm2.towMsF, + _buffer.tim_tm2.towSubMsF, + _buffer.tim_tm2.accEst); +#endif +} +#endif // UBLOX_TIM_TM2_LOGGING + #if UBLOX_RXM_RAW_LOGGING void AP_GPS_UBLOX::log_rxm_raw(const struct ubx_rxm_raw &raw) { @@ -1110,26 +1206,27 @@ AP_GPS_UBLOX::_parse_gps(void) default: break; } -#if GPS_MOVING_BASELINE // see if it is in active config list int8_t cfg_idx = find_active_config_index(id); if (cfg_idx >= 0) { const uint8_t key_size = config_key_size(id); if (cfg_len < key_size || memcmp(&active_config.list[cfg_idx].value, cfg_data, key_size) != 0) { - _configure_valset(id, &active_config.list[cfg_idx].value); + _configure_valset(id, &active_config.list[cfg_idx].value, active_config.layers); _unconfigured_messages |= active_config.unconfig_bit; active_config.done_mask &= ~(1U << cfg_idx); _cfg_needs_save = true; } else { active_config.done_mask |= (1U << cfg_idx); + Debug("done %u mask=0x%x", + unsigned(cfg_idx), + unsigned(active_config.done_mask)); if (active_config.done_mask == (1U< - #include "AP_GPS.h" #include "GPS_Backend.h" +#if AP_GPS_UBLOX_ENABLED + +#include + /* * try to put a UBlox into binary mode. This is in two parts. * @@ -36,6 +38,12 @@ * The reason we need the NAV_SOL rate message at all is some uBlox * modules are configured with all ubx binary messages off, which * would mean we would never detect it. + + * running a uBlox at less than 38400 will lead to packet + * corruption, as we can't receive the packets in the 200ms + * window for 5Hz fixes. The NMEA startup message should force + * the uBlox into 230400 no matter what rate it is configured + * for. */ #define UBLOX_SET_BINARY_115200 "\265\142\006\001\003\000\001\006\001\022\117$PUBX,41,1,0023,0001,115200,0*1C\r\n" @@ -49,6 +57,9 @@ #define UBLOX_MAX_RXM_RAW_SATS 22 #define UBLOX_MAX_RXM_RAWX_SATS 32 #define UBLOX_GNSS_SETTINGS 1 +#ifndef UBLOX_TIM_TM2_LOGGING + #define UBLOX_TIM_TM2_LOGGING (BOARD_FLASH_SIZE>1024) +#endif #define UBLOX_MAX_GNSS_CONFIG_BLOCKS 7 @@ -65,6 +76,7 @@ #define RATE_DOP 1 #define RATE_HW 5 #define RATE_HW2 5 +#define RATE_TIM_TM2 1 #define CONFIG_RATE_NAV (1<<0) #define CONFIG_RATE_POSLLH (1<<1) @@ -84,7 +96,9 @@ #define CONFIG_RATE_TIMEGPS (1<<15) #define CONFIG_TMODE_MODE (1<<16) #define CONFIG_RTK_MOVBASE (1<<17) -#define CONFIG_LAST (1<<18) // this must always be the last bit +#define CONFIG_TIM_TM2 (1<<18) +#define CONFIG_M10 (1<<19) +#define CONFIG_LAST (1<<20) // this must always be the last bit #define CONFIG_REQUIRED_INITIAL (CONFIG_RATE_NAV | CONFIG_RATE_POSLLH | CONFIG_RATE_STATUS | CONFIG_RATE_VELNED) @@ -129,6 +143,11 @@ class AP_GPS_UBLOX : public AP_GPS_Backend #endif // CONFIG_HAL_BOARD != HAL_BOARD_SITL } + bool get_error_codes(uint32_t &error_codes) const override { + error_codes = _unconfigured_messages; + return true; + }; + void broadcast_configuration_failure_reason(void) const override; void Write_AP_Logger_Log_Startup_messages() const override; @@ -268,7 +287,45 @@ class AP_GPS_UBLOX : public AP_GPS_Backend MSGOUT_RTCM_3X_TYPE1127_UART2 = 0x209102d8, MSGOUT_RTCM_3X_TYPE1230_UART2 = 0x20910305, MSGOUT_UBX_NAV_RELPOSNED_UART2 = 0x2091008f, - }; + + // enable specific signals and constellations + CFG_SIGNAL_GPS_ENA = 0x1031001f, + CFG_SIGNAL_GPS_L1CA_ENA = 0x10310001, + CFG_SIGNAL_GPS_L2C_ENA = 0x10310003, + CFG_SIGNAL_GPS_L5_ENA = 0x10310004, + CFG_SIGNAL_SBAS_ENA = 0x10310020, + CFG_SIGNAL_SBAS_L1CA_ENA = 0x10310005, + CFG_SIGNAL_GAL_ENA = 0x10310021, + CFG_SIGNAL_GAL_E1_ENA = 0x10310007, + CFG_SIGNAL_GAL_E5A_ENA = 0x10310009, + CFG_SIGNAL_GAL_E5B_ENA = 0x1031000a, + CFG_SIGNAL_BDS_ENA = 0x10310022, + CFG_SIGNAL_BDS_B1_ENA = 0x1031000d, + CFG_SIGNAL_BDS_B1C_ENA = 0x1031000f, + CFG_SIGNAL_BDS_B2_ENA = 0x1031000e, + CFG_SIGNAL_BDS_B2A_ENA = 0x10310028, + CFG_SIGNAL_QZSS_ENA = 0x10310024, + CFG_SIGNAL_QZSS_L1CA_ENA = 0x10310012, + CFG_SIGNAL_QZSS_L1S_ENA = 0x10310014, + CFG_SIGNAL_QZSS_L2C_ENA = 0x10310015, + CFG_SIGNAL_QZSS_L5_ENA = 0x10310017, + CFG_SIGNAL_GLO_ENA = 0x10310025, + CFG_SIGNAL_GLO_L1_ENA = 0x10310018, + CFG_SIGNAL_GLO_L2_ENA = 0x1031001a, + CFG_SIGNAL_NAVIC_ENA = 0x10310026, + CFG_SIGNAL_NAVIC_L5_ENA = 0x1031001d, + + // other keys + CFG_NAVSPG_DYNMODEL = 0x20110021, + + }; + + // layers for VALSET + #define UBX_VALSET_LAYER_RAM 0x1U + #define UBX_VALSET_LAYER_BBR 0x2U + #define UBX_VALSET_LAYER_FLASH 0x4U + #define UBX_VALSET_LAYER_ALL 0x7U + struct PACKED ubx_cfg_valset { uint8_t version; uint8_t layers; @@ -341,7 +398,7 @@ class AP_GPS_UBLOX : public AP_GPS_Backend uint8_t flags2; uint8_t num_sv; int32_t lon, lat; - int32_t height, h_msl; + int32_t h_ellipsoid, h_msl; uint32_t h_acc, v_acc; int32_t velN, velE, velD, gspeed; int32_t head_mot; @@ -516,6 +573,19 @@ class AP_GPS_UBLOX : public AP_GPS_Backend uint32_t loadMask; }; + struct PACKED ubx_tim_tm2 { + uint8_t ch; + uint8_t flags; + uint16_t count; + uint16_t wnR; + uint16_t wnF; + uint32_t towMsR; + uint32_t towSubMsR; + uint32_t towMsF; + uint32_t towSubMsF; + uint32_t accEst; + }; + // Receive buffer union PACKED { DEFINE_BYTE_ARRAY_METHODS @@ -548,6 +618,7 @@ class AP_GPS_UBLOX : public AP_GPS_Backend ubx_rxm_rawx rxm_rawx; #endif ubx_ack_ack ack; + ubx_tim_tm2 tim_tm2; } _buffer; enum class RELPOSNED { @@ -573,6 +644,7 @@ class AP_GPS_UBLOX : public AP_GPS_Backend CLASS_CFG = 0x06, CLASS_MON = 0x0A, CLASS_RXM = 0x02, + CLASS_TIM = 0x0d, MSG_ACK_NACK = 0x00, MSG_ACK_ACK = 0x01, MSG_POSLLH = 0x2, @@ -598,7 +670,8 @@ class AP_GPS_UBLOX : public AP_GPS_Backend MSG_MON_VER = 0x04, MSG_NAV_SVINFO = 0x30, MSG_RXM_RAW = 0x10, - MSG_RXM_RAWX = 0x15 + MSG_RXM_RAWX = 0x15, + MSG_TIM_TM2 = 0x03 }; enum ubx_gnss_identifier { GNSS_GPS = 0x00, @@ -629,6 +702,7 @@ class AP_GPS_UBLOX : public AP_GPS_Backend UBLOX_M8, UBLOX_F9 = 0x80, // comes from MON_VER hwVersion/swVersion strings UBLOX_M9 = 0x81, // comes from MON_VER hwVersion/swVersion strings + UBLOX_M10 = 0x82, UBLOX_UNKNOWN_HARDWARE_GENERATION = 0xff // not in the ublox spec used for // flagging state in the driver }; @@ -655,6 +729,8 @@ class AP_GPS_UBLOX : public AP_GPS_Backend STEP_RAWX, STEP_VERSION, STEP_RTK_MOVBASE, // setup moving baseline + STEP_TIM_TM2, + STEP_M10, STEP_LAST }; @@ -710,7 +786,7 @@ class AP_GPS_UBLOX : public AP_GPS_Backend bool havePvtMsg; bool _configure_message_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate); - bool _configure_valset(ConfigKey key, const void *value); + bool _configure_valset(ConfigKey key, const void *value, uint8_t layers=UBX_VALSET_LAYER_ALL); bool _configure_valget(ConfigKey key); void _configure_rate(void); void _configure_sbas(bool enable); @@ -728,13 +804,14 @@ class AP_GPS_UBLOX : public AP_GPS_Backend void unexpected_message(void); void log_mon_hw(void); void log_mon_hw2(void); + void log_tim_tm2(void); void log_rxm_raw(const struct ubx_rxm_raw &raw); void log_rxm_rawx(const struct ubx_rxm_rawx &raw); #if GPS_MOVING_BASELINE // see if we should use uart2 for moving baseline config bool mb_use_uart2(void) const { - return (driver_options() & DriverOptions::UBX_MBUseUart2)?true:false; + return option_set(AP_GPS::DriverOptions::UBX_MBUseUart2)?true:false; } #endif @@ -751,7 +828,7 @@ class AP_GPS_UBLOX : public AP_GPS_Backend // configure a set of config key/value pairs. The unconfig_bit corresponds to // a bit in _unconfigured_messages - bool _configure_config_set(const config_list *list, uint8_t count, uint32_t unconfig_bit); + bool _configure_config_set(const config_list *list, uint8_t count, uint32_t unconfig_bit, uint8_t layers=UBX_VALSET_LAYER_ALL); // find index in active_config list int8_t find_active_config_index(ConfigKey key) const; @@ -765,6 +842,15 @@ class AP_GPS_UBLOX : public AP_GPS_Backend void set_pps_desired_freq(uint8_t freq) override; #endif + // status of active configuration for a role + struct { + const config_list *list; + uint8_t count; + uint32_t done_mask; + uint32_t unconfig_bit; + uint8_t layers; + } active_config; + #if GPS_MOVING_BASELINE // config for moving baseline base static const config_list config_MB_Base_uart1[]; @@ -774,15 +860,11 @@ class AP_GPS_UBLOX : public AP_GPS_Backend static const config_list config_MB_Rover_uart1[]; static const config_list config_MB_Rover_uart2[]; - // status of active configuration for a role - struct { - const config_list *list; - uint8_t count; - uint32_t done_mask; - uint32_t unconfig_bit; - } active_config; - // RTCM3 parser for when in moving baseline base mode RTCM3_Parser *rtcm3_parser; #endif // GPS_MOVING_BASELINE + + static const config_list config_M10[]; }; + +#endif diff --git a/libraries/AP_GPS/AP_GPS_config.h b/libraries/AP_GPS/AP_GPS_config.h new file mode 100644 index 00000000000..168fede5bfb --- /dev/null +++ b/libraries/AP_GPS/AP_GPS_config.h @@ -0,0 +1,41 @@ +#pragma once + +#ifndef AP_GPS_BACKEND_DEFAULT_ENABLED +#define AP_GPS_BACKEND_DEFAULT_ENABLED 1 +#endif + +#ifndef AP_GPS_ERB_ENABLED + #define AP_GPS_ERB_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_GPS_GSOF_ENABLED + #define AP_GPS_GSOF_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_GPS_NMEA_ENABLED + #define AP_GPS_NMEA_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_GPS_NOVA_ENABLED + #define AP_GPS_NOVA_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_GPS_SBF_ENABLED + #define AP_GPS_SBF_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_GPS_SBP_ENABLED + #define AP_GPS_SBP_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_GPS_SBP2_ENABLED + #define AP_GPS_SBP2_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_GPS_SIRF_ENABLED + #define AP_GPS_SIRF_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_GPS_UBLOX_ENABLED + #define AP_GPS_UBLOX_ENABLED 1 +#endif diff --git a/libraries/AP_GPS/GPS_Backend.cpp b/libraries/AP_GPS/GPS_Backend.cpp index e47ff483f26..2e1761034b8 100644 --- a/libraries/AP_GPS/GPS_Backend.cpp +++ b/libraries/AP_GPS/GPS_Backend.cpp @@ -250,11 +250,12 @@ void AP_GPS_Backend::check_new_itow(uint32_t itow, uint32_t msg_length) // get the time the packet arrived on the UART uint64_t uart_us; - if (port && _last_pps_time_us == 0) { - uart_us = port->receive_time_constraint_us(msg_length); - } else if (_last_pps_time_us != 0) { + if (_last_pps_time_us != 0 && (state.status >= AP_GPS::GPS_OK_FIX_2D)) { + // pps is only reliable when we have some sort of GPS fix uart_us = _last_pps_time_us; _last_pps_time_us = 0; + } else if (port) { + uart_us = port->receive_time_constraint_us(msg_length); } else { uart_us = AP_HAL::micros64(); } @@ -297,9 +298,12 @@ void AP_GPS_Backend::check_new_itow(uint32_t itow, uint32_t msg_length) state.last_corrected_gps_time_us = local_us; state.corrected_timestamp_updated = true; +#ifndef HAL_BUILD_AP_PERIPH // look for lagged data from the GPS. This is meant to detect // the case that the GPS is trying to push more data into the // UART than can fit (eg. with GPS_RAW_DATA at 115200). + // This is disabled on AP_Periph as it is better to catch missed packet rate at the flight + // controller level float expected_lag; if (gps.get_lag(state.instance, expected_lag)) { float lag_s = (now - (state.last_corrected_gps_time_us/1000U)) * 0.001; @@ -310,6 +314,8 @@ void AP_GPS_Backend::check_new_itow(uint32_t itow, uint32_t msg_length) state.lagged_sample_count = 0; } } +#endif // HAL_BUILD_AP_PERIPH + if (state.status >= AP_GPS::GPS_OK_FIX_2D) { // we must have a decent fix to calculate difference between itow and pseudo-itow _pseudo_itow_delta_ms = itow - (_pseudo_itow/1000ULL); @@ -417,34 +423,73 @@ bool AP_GPS_Backend::calculate_moving_base_yaw(AP_GPS::GPS_State &interim_state, #if AP_GPS_DEBUG_LOGGING_ENABLED -// log some data for debugging +/* + log some data for debugging + + the logging format matches that used by SITL with SIM_GPS_TYPE=7, + allowing for development of GPS drivers based on logged data +*/ void AP_GPS_Backend::log_data(const uint8_t *data, uint16_t length) { - logging.buf.write(data, length); - if (!logging.io_registered) { - logging.io_registered = true; - hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_GPS_Backend::logging_update, void)); + if (state.instance < 2) { + logging[state.instance].buf.write(data, length); + } + if (!log_thread_created) { + log_thread_created = true; + hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_GPS_Backend::logging_start, void), "gps_log", 4096, AP_HAL::Scheduler::PRIORITY_IO, 0); } } -// IO thread update, writing to log file -void AP_GPS_Backend::logging_update(void) +AP_GPS_Backend::loginfo AP_GPS_Backend::logging[2]; +bool AP_GPS_Backend::log_thread_created; + +// logging loop, needs to be static to allow for re-alloc of GPS backends +void AP_GPS_Backend::logging_loop(void) { - if (logging.fd == -1) { - char fname[] = "gpsN.log"; - fname[3] = '1' + state.instance; - logging.fd = AP::FS().open(fname, O_WRONLY|O_CREAT|O_APPEND); - } - if (logging.fd != -1) { - uint32_t n = 0; - const uint8_t *p = logging.buf.readptr(n); - if (p != nullptr && n != 0) { - int32_t written = AP::FS().write(logging.fd, p, n); - if (written > 0) { - logging.buf.advance(written); - AP::FS().fsync(logging.fd); + while (true) { + hal.scheduler->delay(10); + static uint16_t lognum; + for (uint8_t instance=0; instance<2; instance++) { + if (logging[instance].fd == -1) { + char fname[] = "gpsN_XXX.log"; + fname[3] = '1' + instance; + if (lognum == 0) { + for (lognum=1; lognum<1000; lognum++) { + struct stat st; + hal.util->snprintf(&fname[5], 8, "%03u.log", lognum); + if (AP::FS().stat(fname, &st) != 0) { + break; + } + } + } + hal.util->snprintf(&fname[5], 8, "%03u.log", lognum); + logging[instance].fd = AP::FS().open(fname, O_WRONLY|O_CREAT|O_APPEND); + } + if (logging[instance].fd != -1) { + uint32_t n = 0; + const uint8_t *p; + while ((p = logging[instance].buf.readptr(n)) != nullptr && n != 0) { + struct { + uint32_t magic = 0x7fe53b04U; + uint32_t time_ms; + uint32_t n; + } header; + header.n = n; + header.time_ms = AP_HAL::millis(); + // short writes are unlikely and are ignored (only FS full errors) + AP::FS().write(logging[instance].fd, (const uint8_t *)&header, sizeof(header)); + AP::FS().write(logging[instance].fd, p, n); + logging[instance].buf.advance(n); + AP::FS().fsync(logging[instance].fd); + } } } } } + +// logging thread start, needs to be non-static for thread_create +void AP_GPS_Backend::logging_start(void) +{ + logging_loop(); +} #endif // AP_GPS_DEBUG_LOGGING_ENABLED diff --git a/libraries/AP_GPS/GPS_Backend.h b/libraries/AP_GPS/GPS_Backend.h index 937542f249a..f4bb25bd258 100644 --- a/libraries/AP_GPS/GPS_Backend.h +++ b/libraries/AP_GPS/GPS_Backend.h @@ -21,10 +21,7 @@ #include #include #include "AP_GPS.h" - -#ifndef AP_GPS_BACKEND_DEFAULT_ENABLED -#define AP_GPS_BACKEND_DEFAULT_ENABLED 1 -#endif +#include "AP_GPS_config.h" #ifndef AP_GPS_DEBUG_LOGGING_ENABLED // enable this to log all bytes from the GPS. Also needs a call to @@ -98,12 +95,10 @@ class AP_GPS_Backend return (_pseudo_itow_delta_ms == 0)?(_last_itow_ms):((_pseudo_itow/1000ULL) + _pseudo_itow_delta_ms); } - enum DriverOptions : int16_t { - UBX_MBUseUart2 = (1U << 0U), - SBF_UseBaseForYaw = (1U << 1U), - UBX_Use115200 = (1U << 2U), - UAVCAN_MBUseDedicatedBus = (1 << 3U), - }; + // check if an option is set + bool option_set(const AP_GPS::DriverOptions option) const { + return gps.option_set(option); + } protected: AP_HAL::UARTDriver *port; ///< UART we are attached to @@ -141,13 +136,6 @@ class AP_GPS_Backend void check_new_itow(uint32_t itow, uint32_t msg_length); - /* - access to driver option bits - */ - DriverOptions driver_options(void) const { - return DriverOptions(gps._driver_options.get()); - } - #if GPS_MOVING_BASELINE bool calculate_moving_base_yaw(const float reported_heading_deg, const float reported_distance, const float reported_D); bool calculate_moving_base_yaw(AP_GPS::GPS_State &interim_state, const float reported_heading_deg, const float reported_distance, const float reported_D); @@ -173,12 +161,16 @@ class AP_GPS_Backend uint32_t _rate_ms; uint32_t _last_rate_ms; uint16_t _rate_counter; + #if AP_GPS_DEBUG_LOGGING_ENABLED - struct { + // support raw GPS logging + static struct loginfo { int fd = -1; - ByteBuffer buf{32768}; - bool io_registered; - } logging; - void logging_update(void); + ByteBuffer buf{16000}; + } logging[2]; + static bool log_thread_created; + static void logging_loop(void); + void logging_start(void); #endif + }; diff --git a/libraries/AP_GPS/LogStructure.h b/libraries/AP_GPS/LogStructure.h index 9dedef16b41..e34bed923f7 100644 --- a/libraries/AP_GPS/LogStructure.h +++ b/libraries/AP_GPS/LogStructure.h @@ -62,6 +62,7 @@ struct PACKED log_GPS { // @Field: VV: true if vertical velocity is available // @Field: SMS: time since system startup this sample was taken // @Field: Delta: system time delta between the last two reported positions +// @Field: Und: Undulation struct PACKED log_GPA { LOG_PACKET_HEADER; uint64_t time_us; @@ -74,6 +75,7 @@ struct PACKED log_GPA { uint8_t have_vv; uint32_t sample_ms; uint16_t delta_ms; + float undulation; }; /* @@ -200,7 +202,7 @@ struct PACKED log_GPS_RAWS { { LOG_GPS_MSG, sizeof(log_GPS), \ "GPS", "QBBIHBcLLeffffB", "TimeUS,I,Status,GMS,GWk,NSats,HDop,Lat,Lng,Alt,Spd,GCrs,VZ,Yaw,U", "s#---SmDUmnhnh-", "F----0BGGB000--" , true }, \ { LOG_GPA_MSG, sizeof(log_GPA), \ - "GPA", "QBCCCCfBIH", "TimeUS,I,VDop,HAcc,VAcc,SAcc,YAcc,VV,SMS,Delta", "s#mmmnd-ss", "F-BBBB0-CC" , true }, \ + "GPA", "QBCCCCfBIHf", "TimeUS,I,VDop,HAcc,VAcc,SAcc,YAcc,VV,SMS,Delta,Und", "s#mmmnd-ssm", "F-BBBB0-CC0" , true }, \ { LOG_GPS_UBX1_MSG, sizeof(log_Ubx1), \ "UBX1", "QBHBBHI", "TimeUS,Instance,noisePerMS,jamInd,aPower,agcCnt,config", "s#-----", "F------" , true }, \ { LOG_GPS_UBX2_MSG, sizeof(log_Ubx2), \ @@ -211,4 +213,4 @@ struct PACKED log_GPS_RAWS { "GRXH", "QdHbBB", "TimeUS,rcvTime,week,leapS,numMeas,recStat", "s-----", "F-----" , true }, \ { LOG_GPS_RAWS_MSG, sizeof(log_GPS_RAWS), \ "GRXS", "QddfBBBHBBBBB", "TimeUS,prMes,cpMes,doMes,gnss,sv,freq,lock,cno,prD,cpD,doD,trk", "s------------", "F------------" , true }, \ - LOG_STRUCTURE_FROM_GPS_SBP, + LOG_STRUCTURE_FROM_GPS_SBP diff --git a/libraries/AP_GPS/LogStructure_SBP.h b/libraries/AP_GPS/LogStructure_SBP.h index 1de9cf3449e..c3a427c3ce7 100644 --- a/libraries/AP_GPS/LogStructure_SBP.h +++ b/libraries/AP_GPS/LogStructure_SBP.h @@ -1,6 +1,7 @@ #pragma once #include +#include "AP_GPS_config.h" #define LOG_IDS_FROM_GPS_SBP \ LOG_MSG_SBPHEALTH, \ @@ -68,6 +69,7 @@ struct PACKED log_SbpEvent { uint8_t quality; }; +#if AP_GPS_SBP_ENABLED #define LOG_STRUCTURE_FROM_GPS_SBP \ { LOG_MSG_SBPHEALTH, sizeof(log_SbpHealth), \ "SBPH", "QIII", "TimeUS,CrcError,LastInject,IARhyp", "s---", "F---" , true }, \ @@ -76,4 +78,7 @@ struct PACKED log_SbpEvent { { LOG_MSG_SBPRAWM, sizeof(log_SbpRAWM), \ "SBRM", "QQQQQQQQQQQQQQQ", "TimeUS,msg_flag,1,2,3,4,5,6,7,8,9,10,11,12,13", "s??????????????", "F??????????????" , true }, \ { LOG_MSG_SBPEVENT, sizeof(log_SbpEvent), \ - "SBRE", "QHIiBB", "TimeUS,GWk,GMS,ns_residual,level,quality", "s?????", "F?????" } + "SBRE", "QHIiBB", "TimeUS,GWk,GMS,ns_residual,level,quality", "s?????", "F?????" }, +#else +#define LOG_STRUCTURE_FROM_GPS_SBP +#endif diff --git a/libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.cpp b/libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.cpp index 14c32a82dee..06d8e48f8c7 100644 --- a/libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.cpp +++ b/libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.cpp @@ -16,7 +16,7 @@ Test for AP_GPS_AUTO */ -#include +#include //This is a common Hardware Abstraction Layer. #include #include #include @@ -24,10 +24,10 @@ #include #include -void setup(); -void loop(); +void setup(); //This function is defined in most of the libraries. This function is called only once at boot up time. This function is called by main() function in HAL. +void loop(); //This function is defined in most of the libraries. This function is called by main function in HAL. The main work of the sketch is typically in this function only. -const AP_HAL::HAL& hal = AP_HAL::get_HAL(); +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); //Declare "hal" reference variable. This variable is pointing to Ap_HAL::HAL class's object. Here, AP_HAL is library and HAL is a class in that library. This reference variable can be used to get access to hardware specific functions. static AP_BoardConfig board_config; @@ -35,7 +35,7 @@ static AP_BoardConfig board_config; AP_BoardLED board_led; // create fake gcs object -GCS_Dummy _gcs; +GCS_Dummy _gcs; //gcs stands for Ground Control Station const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { AP_GROUPEND @@ -69,7 +69,7 @@ void print_latlon(AP_HAL::BetterStream *s, int32_t lat_or_lon); void print_latlon(AP_HAL::BetterStream *s, int32_t lat_or_lon) { int32_t dec_portion, frac_portion; - int32_t abs_lat_or_lon = labs(lat_or_lon); + int32_t abs_lat_or_lon = labs(lat_or_lon); //The labs() function in C++ returns the absolute value of a long or long int data. // extract decimal portion (special handling of negative numbers to ensure we round towards zero) dec_portion = abs_lat_or_lon / 10000000UL; @@ -92,7 +92,7 @@ void loop() // Update GPS state based on possible bytes received from the module. gps.update(); - // If new GPS data is received, output it's contents to the console + // If new GPS data is received, output its contents to the console // Here we rely on the time of the message in GPS class and the time of last message // saved in static variable last_msg_ms. When new message is received, the time // in GPS class will be updated. diff --git a/libraries/AP_Generator/AP_Generator.cpp b/libraries/AP_Generator/AP_Generator.cpp index 78309a80e98..2e9fba8372a 100644 --- a/libraries/AP_Generator/AP_Generator.cpp +++ b/libraries/AP_Generator/AP_Generator.cpp @@ -21,6 +21,8 @@ #include "AP_Generator_IE_2400.h" #include "AP_Generator_RichenPower.h" +#include + const AP_Param::GroupInfo AP_Generator::var_info[] = { // @Param: TYPE @@ -31,6 +33,13 @@ const AP_Param::GroupInfo AP_Generator::var_info[] = { // @RebootRequired: True AP_GROUPINFO_FLAGS("TYPE", 1, AP_Generator, _type, 0, AP_PARAM_FLAG_ENABLE), + // @Param: OPTIONS + // @DisplayName: Generator Options + // @Description: Bitmask of options for generators + // @Bitmask: 0:Supress Maintenance-Required Warnings + // @User: Standard + AP_GROUPINFO("OPTIONS", 2, AP_Generator, _options, 0), + AP_GROUPEND }; @@ -65,7 +74,9 @@ void AP_Generator::init() break; case Type::RICHENPOWER: +#if AP_GENERATOR_RICHENPOWER_ENABLED _driver_ptr = new AP_Generator_RichenPower(*this); +#endif break; } diff --git a/libraries/AP_Generator/AP_Generator.h b/libraries/AP_Generator/AP_Generator.h index 9e5a269e59e..829f1290f3a 100644 --- a/libraries/AP_Generator/AP_Generator.h +++ b/libraries/AP_Generator/AP_Generator.h @@ -9,7 +9,6 @@ #if HAL_GENERATOR_ENABLED #include -#include #include class AP_Generator_Backend; @@ -62,11 +61,20 @@ class AP_Generator bool idle(void); bool run(void); - void send_generator_status(const GCS_MAVLINK &channel); + void send_generator_status(const class GCS_MAVLINK &channel); // Parameter block static const struct AP_Param::GroupInfo var_info[]; + // bits which can be set in _options to modify generator behaviour: + enum class Option { + INHIBIT_MAINTENANCE_WARNINGS = 0, + }; + + bool option_set(Option opt) const { + return (_options & 1U< #if HAL_GENERATOR_ENABLED +#include +#include + // Initialize the fuelcell object and prepare it for use void AP_Generator_IE_FuelCell::init() { diff --git a/libraries/AP_Generator/AP_Generator_IE_FuelCell.h b/libraries/AP_Generator/AP_Generator_IE_FuelCell.h index 7ba662ec214..a1666adbe29 100644 --- a/libraries/AP_Generator/AP_Generator_IE_FuelCell.h +++ b/libraries/AP_Generator/AP_Generator_IE_FuelCell.h @@ -4,9 +4,6 @@ #if HAL_GENERATOR_ENABLED -#include -#include - class AP_Generator_IE_FuelCell : public AP_Generator_Backend { diff --git a/libraries/AP_Generator/AP_Generator_RichenPower.cpp b/libraries/AP_Generator/AP_Generator_RichenPower.cpp index 66b1ec073d6..99c18f7c714 100644 --- a/libraries/AP_Generator/AP_Generator_RichenPower.cpp +++ b/libraries/AP_Generator/AP_Generator_RichenPower.cpp @@ -15,7 +15,7 @@ #include "AP_Generator_RichenPower.h" -#if HAL_GENERATOR_ENABLED +#if AP_GENERATOR_RICHENPOWER_ENABLED #include #include @@ -129,8 +129,8 @@ bool AP_Generator_RichenPower::get_reading() last_reading.seconds_until_maintenance = be16toh(u.packet.seconds_until_maintenance_high) * 65536 + be16toh(u.packet.seconds_until_maintenance_low); last_reading.errors = be16toh(u.packet.errors); last_reading.rpm = be16toh(u.packet.rpm); - last_reading.output_voltage = be16toh(u.packet.output_voltage) / 100.0f; - last_reading.output_current = be16toh(u.packet.output_current) / 100.0f; + last_reading.output_voltage = be16toh(u.packet.output_voltage) * 0.01f; + last_reading.output_current = be16toh(u.packet.output_current) * 0.01f; last_reading.mode = (Mode)u.packet.mode; last_reading_ms = AP_HAL::millis(); @@ -194,6 +194,25 @@ constexpr float AP_Generator_RichenPower::heat_required_for_run() } +void AP_Generator_RichenPower::check_maintenance_required() +{ + // don't bother the user while flying: + if (hal.util->get_soft_armed()) { + return; + } + + if (!AP::generator()->option_set(AP_Generator::Option::INHIBIT_MAINTENANCE_WARNINGS)) { + const uint32_t now = AP_HAL::millis(); + + if (last_reading.errors & (1U< 60000) { + gcs().send_text(MAV_SEVERITY_NOTICE, "Generator: requires maintenance"); + last_maintenance_warning_ms = now; + } + } + } +} + /* update the state of the sensor */ @@ -205,6 +224,7 @@ void AP_Generator_RichenPower::update(void) if (last_reading_ms != 0) { update_runstate(); + check_maintenance_required(); } (void)get_reading(); @@ -335,17 +355,22 @@ bool AP_Generator_RichenPower::pre_arm_check(char *failmsg, uint8_t failmsg_len) hal.util->snprintf(failmsg, failmsg_len, "no messages in %ums", unsigned(now - last_reading_ms)); return false; } - if (last_reading.seconds_until_maintenance == 0) { - hal.util->snprintf(failmsg, failmsg_len, "requires maintenance"); - } if (SRV_Channels::get_channel_for(SRV_Channel::k_generator_control) == nullptr) { hal.util->snprintf(failmsg, failmsg_len, "need a servo output channel"); return false; } - if (last_reading.errors) { + uint16_t errors = last_reading.errors; + + // requiring maintenance isn't something that should stop + // people flying - they have work to do. But we definitely + // complain about it - a lot. + errors &= ~(1U << uint16_t(Errors::MaintenanceRequired)); + + if (errors) { + for (uint16_t i=0; i<16; i++) { - if (last_reading.errors & (1U << (uint16_t)i)) { + if (errors & (1U << i)) { if (i < (uint16_t)Errors::LAST) { hal.util->snprintf(failmsg, failmsg_len, "error: %s", error_strings[i]); } else { @@ -487,4 +512,4 @@ bool AP_Generator_RichenPower::run() set_pilot_desired_runstate(RunState::RUN); return true; } -#endif +#endif // AP_GENERATOR_RICHENPOWER_ENABLED diff --git a/libraries/AP_Generator/AP_Generator_RichenPower.h b/libraries/AP_Generator/AP_Generator_RichenPower.h index 3acf33566ca..3297bba3a42 100644 --- a/libraries/AP_Generator/AP_Generator_RichenPower.h +++ b/libraries/AP_Generator/AP_Generator_RichenPower.h @@ -3,7 +3,11 @@ #include "AP_Generator_Backend.h" -#if HAL_GENERATOR_ENABLED +#ifndef AP_GENERATOR_RICHENPOWER_ENABLED +#define AP_GENERATOR_RICHENPOWER_ENABLED 0 +#endif + +#if AP_GENERATOR_RICHENPOWER_ENABLED #include #include @@ -151,7 +155,7 @@ class AP_Generator_RichenPower : public AP_Generator_Backend uint8_t footermagic1; uint8_t footermagic2; }; - assert_storage_size _assert_storage_size_RichenPacket; + assert_storage_size _assert_storage_size_RichenPacket UNUSED_PRIVATE_MEMBER; union RichenUnion { uint8_t parse_buffer[70]; @@ -204,5 +208,11 @@ class AP_Generator_RichenPower : public AP_Generator_Backend } return AP_HAL::millis() - idle_state_start_ms; } + + // check if the generator requires maintenance and send a message if it does: + void check_maintenance_required(); + // if we are emitting warnings about the generator requiring + // maintenamce, this is the last time we sent the warning: + uint32_t last_maintenance_warning_ms; }; #endif diff --git a/libraries/AP_Gripper/AP_Gripper.cpp b/libraries/AP_Gripper/AP_Gripper.cpp index 833a7626fb1..83e7f6a0dbd 100644 --- a/libraries/AP_Gripper/AP_Gripper.cpp +++ b/libraries/AP_Gripper/AP_Gripper.cpp @@ -9,7 +9,8 @@ extern const AP_HAL::HAL& hal; #define GRIPPER_RELEASE_PWM_DEFAULT 1100 // EPM PWM definitions #define GRIPPER_NEUTRAL_PWM_DEFAULT 1500 -#define GRIPPER_REGRAB_DEFAULT 0 // default re-grab interval (in seconds) to ensure cargo is securely held +#define GRIPPER_REGRAB_DEFAULT 0 // default EPM re-grab interval (in seconds) to ensure cargo is securely held +#define GRIPPER_AUTOCLOSE_DEFAULT 0.0 // default automatic close time (in seconds) const AP_Param::GroupInfo AP_Gripper::var_info[] = { // @Param: ENABLE @@ -51,8 +52,8 @@ const AP_Param::GroupInfo AP_Gripper::var_info[] = { AP_GROUPINFO("NEUTRAL", 4, AP_Gripper, config.neutral_pwm, GRIPPER_NEUTRAL_PWM_DEFAULT), // @Param: REGRAB - // @DisplayName: Gripper Regrab interval - // @Description: Time in seconds that gripper will regrab the cargo to ensure grip has not weakened; 0 to disable + // @DisplayName: EPM Gripper Regrab interval + // @Description: Time in seconds that EPM gripper will regrab the cargo to ensure grip has not weakened; 0 to disable // @User: Advanced // @Range: 0 255 // @Units: s @@ -65,6 +66,14 @@ const AP_Param::GroupInfo AP_Gripper::var_info[] = { // @Range: 0 255 AP_GROUPINFO("CAN_ID", 6, AP_Gripper, config.uavcan_hardpoint_id, 0), + // @Param: AUTOCLOSE + // @DisplayName: Gripper Autoclose time + // @Description: Time in seconds that gripper close the gripper after opening; 0 to disable + // @User: Advanced + // @Range: 0.25 255 + // @Units: s + AP_GROUPINFO("AUTOCLOSE", 7, AP_Gripper, config.autoclose_time, GRIPPER_AUTOCLOSE_DEFAULT), + AP_GROUPEND }; diff --git a/libraries/AP_Gripper/AP_Gripper.h b/libraries/AP_Gripper/AP_Gripper.h index 0a5b7dd54b3..3f6036557d5 100644 --- a/libraries/AP_Gripper/AP_Gripper.h +++ b/libraries/AP_Gripper/AP_Gripper.h @@ -70,7 +70,8 @@ class AP_Gripper { AP_Int16 grab_pwm; // PWM value sent to Gripper to initiate grabbing the cargo AP_Int16 release_pwm; // PWM value sent to Gripper to release the cargo AP_Int16 neutral_pwm; // PWM value sent to gripper when not grabbing or releasing - AP_Int8 regrab_interval; // Time in seconds that gripper will regrab the cargo to ensure grip has not weakend + AP_Int8 regrab_interval; // Time in seconds that EPM gripper will regrab the cargo to ensure grip has not weakend + AP_Float autoclose_time; // Automatic close time (in seconds) AP_Int16 uavcan_hardpoint_id; gripper_state state = STATE_RELEASED; diff --git a/libraries/AP_Gripper/AP_Gripper_Backend.cpp b/libraries/AP_Gripper/AP_Gripper_Backend.cpp index 5e82144491c..3c4680651a5 100644 --- a/libraries/AP_Gripper/AP_Gripper_Backend.cpp +++ b/libraries/AP_Gripper/AP_Gripper_Backend.cpp @@ -1,4 +1,5 @@ #include "AP_Gripper_Backend.h" +#include extern const AP_HAL::HAL& hal; @@ -11,4 +12,11 @@ void AP_Gripper_Backend::init() void AP_Gripper_Backend::update() { update_gripper(); + + // close the gripper again if autoclose_time > 0.0 + if (config.state == AP_Gripper::STATE_RELEASED && (_last_grab_or_release > 0) && + (is_positive(config.autoclose_time)) && + (AP_HAL::millis() - _last_grab_or_release > (config.autoclose_time * 1000.0))) { + grab(); + } } diff --git a/libraries/AP_Gripper/AP_Gripper_Backend.h b/libraries/AP_Gripper/AP_Gripper_Backend.h index 30fb9f8a1df..4557ee89888 100644 --- a/libraries/AP_Gripper/AP_Gripper_Backend.h +++ b/libraries/AP_Gripper/AP_Gripper_Backend.h @@ -51,5 +51,7 @@ class AP_Gripper_Backend { protected: + uint32_t _last_grab_or_release; // ms; time last grab or release happened + struct AP_Gripper::Backend_Config &config; }; diff --git a/libraries/AP_Gripper/AP_Gripper_EPM.h b/libraries/AP_Gripper/AP_Gripper_EPM.h index 6b3b9d18bac..587c0116200 100644 --- a/libraries/AP_Gripper/AP_Gripper_EPM.h +++ b/libraries/AP_Gripper/AP_Gripper_EPM.h @@ -56,7 +56,4 @@ class AP_Gripper_EPM : public AP_Gripper_Backend { // UAVCAN driver fd int _uavcan_fd = -1; - - // internal variables - uint32_t _last_grab_or_release; }; diff --git a/libraries/AP_Gripper/AP_Gripper_Servo.cpp b/libraries/AP_Gripper/AP_Gripper_Servo.cpp index 97472221107..6c6f43eb1c5 100644 --- a/libraries/AP_Gripper/AP_Gripper_Servo.cpp +++ b/libraries/AP_Gripper/AP_Gripper_Servo.cpp @@ -10,32 +10,56 @@ extern const AP_HAL::HAL& hal; void AP_Gripper_Servo::init_gripper() { - // move the servo to the release position - release(); + // move the servo to the neutral position + SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.neutral_pwm); } void AP_Gripper_Servo::grab() { + // check if we are already grabbing + if (config.state == AP_Gripper::STATE_GRABBING) { + // do nothing + return; + } + + // check if we are already grabbed + if (config.state == AP_Gripper::STATE_GRABBED) { + // inform user that we are already grabbed + gcs().send_text(MAV_SEVERITY_INFO, "Gripper load grabbed"); + return; + } + + // flag we are active and grabbing cargo + config.state = AP_Gripper::STATE_GRABBING; + // move the servo to the grab position SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.grab_pwm); - action_timestamp = AP_HAL::millis(); -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL - is_releasing = false; - is_released = true; -#endif + _last_grab_or_release = AP_HAL::millis(); gcs().send_text(MAV_SEVERITY_INFO, "Gripper load grabbing"); AP::logger().Write_Event(LogEvent::GRIPPER_GRAB); } void AP_Gripper_Servo::release() { + // check if we are already releasing + if (config.state == AP_Gripper::STATE_RELEASING) { + // do nothing + return; + } + + // check if we are already released + if (config.state == AP_Gripper::STATE_RELEASED) { + // inform user that we are already released + gcs().send_text(MAV_SEVERITY_INFO, "Gripper load released"); + return; + } + + // flag we are releasing cargo + config.state = AP_Gripper::STATE_RELEASING; + // move the servo to the release position SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.release_pwm); - action_timestamp = AP_HAL::millis(); -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL - is_releasing = true; - is_released = false; -#endif + _last_grab_or_release = AP_HAL::millis(); gcs().send_text(MAV_SEVERITY_INFO, "Gripper load releasing"); AP::logger().Write_Event(LogEvent::GRIPPER_RELEASE); } @@ -53,41 +77,33 @@ bool AP_Gripper_Servo::has_state_pwm(const uint16_t pwm) const // (e.g. last action was a grab not a release) return false; } - if (AP_HAL::millis() - action_timestamp < action_time) { + if (AP_HAL::millis() - _last_grab_or_release < SERVO_ACTUATION_TIME) { // servo still moving.... return false; } -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL - if (is_releasing) { - gcs().send_text(MAV_SEVERITY_INFO, "Gripper load released"); - } else { - gcs().send_text(MAV_SEVERITY_INFO, "Gripper load grabbed"); - } -#endif return true; } - bool AP_Gripper_Servo::released() const { - return has_state_pwm(config.release_pwm); + return (config.state == AP_Gripper::STATE_RELEASED); } bool AP_Gripper_Servo::grabbed() const { - return has_state_pwm(config.grab_pwm); + return (config.state == AP_Gripper::STATE_GRABBED); } // type-specific periodic updates: -void AP_Gripper_Servo::update_gripper() { -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL - if (is_releasing && !is_released) { - is_released = released(); - } else if (!is_releasing && is_released) { - is_released = !grabbed(); +void AP_Gripper_Servo::update_gripper() +{ + // Check for successful grabbed or released + if (config.state == AP_Gripper::STATE_GRABBING && has_state_pwm(config.grab_pwm)) { + config.state = AP_Gripper::STATE_GRABBED; + } else if (config.state == AP_Gripper::STATE_RELEASING && has_state_pwm(config.release_pwm)) { + config.state = AP_Gripper::STATE_RELEASED; } -#endif -}; +} bool AP_Gripper_Servo::valid() const { diff --git a/libraries/AP_Gripper/AP_Gripper_Servo.h b/libraries/AP_Gripper/AP_Gripper_Servo.h index 87636f02ede..a98b0ca03c5 100644 --- a/libraries/AP_Gripper/AP_Gripper_Servo.h +++ b/libraries/AP_Gripper/AP_Gripper_Servo.h @@ -18,6 +18,8 @@ #include #include +#define SERVO_ACTUATION_TIME 500 // Time for servo to move to target position during grab or release in milliseconds + class AP_Gripper_Servo : public AP_Gripper_Backend { public: @@ -49,12 +51,5 @@ class AP_Gripper_Servo : public AP_Gripper_Backend { private: - uint32_t action_timestamp; // ms; time grab or release happened - const uint16_t action_time = 3000; // ms; time to grab or release - bool has_state_pwm(const uint16_t pwm) const; -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL - bool is_releasing; - bool is_released; -#endif }; diff --git a/libraries/AP_GyroFFT/AP_GyroFFT.cpp b/libraries/AP_GyroFFT/AP_GyroFFT.cpp index 82ac4fd49c6..0ddebffb521 100644 --- a/libraries/AP_GyroFFT/AP_GyroFFT.cpp +++ b/libraries/AP_GyroFFT/AP_GyroFFT.cpp @@ -25,6 +25,9 @@ #include #include #include +#if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane) +#include +#endif #include extern const AP_HAL::HAL& hal; @@ -155,6 +158,14 @@ const AP_Param::GroupInfo AP_GyroFFT::var_info[] = { // @User: Advanced AP_GROUPINFO("HMNC_PEAK", 13, AP_GyroFFT, _harmonic_peak, 0), + // @Param: NUM_FRAMES + // @DisplayName: FFT output frames to retain and average + // @Description: Number of output frequency frames to retain and average in order to calculate final frequencies. Averaging output frames can drastically reduce noise and jitter at the cost of latency as long as the input is stable. The default is to perform no averaging. For rapidly changing frequencies (e.g. smaller aircraft) fewer frames should be averaged. + // @Range: 0 8 + // @User: Advanced + // @RebootRequired: True + AP_GROUPINFO("NUM_FRAMES", 14, AP_GyroFFT, _num_frames, 0), + AP_GROUPEND }; @@ -195,29 +206,32 @@ void AP_GyroFFT::init(uint16_t loop_rate_hz) } // check that we support the window size requested and it is a power of 2 - _window_size = 1 << lrintf(log2f(_window_size.get())); + _window_size.set(1 << lrintf(log2f(_window_size.get()))); #if defined(STM32H7) || CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_SITL - _window_size = constrain_int16(_window_size, 32, 512); + _window_size.set(constrain_int16(_window_size, 32, 512)); #else - _window_size = constrain_int16(_window_size, 32, 256); + _window_size.set(constrain_int16(_window_size, 32, 256)); #endif // number of samples needed before a new frame can be processed - _window_overlap = constrain_float(_window_overlap, 0.0f, 0.9f); + _window_overlap.set(constrain_float(_window_overlap, 0.0f, 0.9f)); _samples_per_frame = (1.0f - _window_overlap) * _window_size; // if we allow too small a number of samples per frame the output rate gets very high // this is particularly a problem on IMUs with higher sample rates (e.g. BMI088) // 16 gives a maximum output rate of 2Khz / 16 = 125Hz per axis or 375Hz in aggregate _samples_per_frame = MAX(FFT_MIN_SAMPLES_PER_FRAME, 1 << lrintf(log2f(_samples_per_frame))); + if (_num_frames > 0) { + _num_frames.set(constrain_int16(_num_frames, 2, AP_HAL::DSP::MAX_SLIDING_WINDOW_SIZE)); + } // check that we have enough memory for the window size requested // INS: XYZ_AXIS_COUNT * INS_MAX_INSTANCES * _window_size, DSP: 3 * _window_size, FFT: XYZ_AXIS_COUNT + 3 * _window_size - const uint32_t allocation_count = (XYZ_AXIS_COUNT * INS_MAX_INSTANCES + 3 + XYZ_AXIS_COUNT + 3) * sizeof(float); + const uint32_t allocation_count = (XYZ_AXIS_COUNT * INS_MAX_INSTANCES + 3 + XYZ_AXIS_COUNT + 3 + _num_frames) * sizeof(float); if (allocation_count * FFT_DEFAULT_WINDOW_SIZE > hal.util->available_memory() / 2) { gcs().send_text(MAV_SEVERITY_WARNING, "AP_GyroFFT: disabled, required %u bytes", (unsigned int)allocation_count * FFT_DEFAULT_WINDOW_SIZE); return; } else if (allocation_count * _window_size > hal.util->available_memory() / 2) { gcs().send_text(MAV_SEVERITY_WARNING, "AP_GyroFFT: req alloc %u bytes (free=%u)", (unsigned int)allocation_count * _window_size, (unsigned int)hal.util->available_memory()); - _window_size = FFT_DEFAULT_WINDOW_SIZE; + _window_size.set(FFT_DEFAULT_WINDOW_SIZE); } // save any changes that were made _window_size.save(); @@ -248,10 +262,23 @@ void AP_GyroFFT::init(uint16_t loop_rate_hz) return; } - const uint8_t harmonics = _ins->get_gyro_harmonic_notch_harmonics(); + // check for harmonics across all harmonic notch filters + // note that we only allow one harmonic notch filter linked to the FFT code + uint8_t harmonics = 0; + uint8_t num_notches = 0; + for (auto ¬ch : _ins->harmonic_notches) { + if (notch.params.enabled()) { + harmonics |= notch.params.harmonics(); + num_notches = MAX(num_notches, notch.num_dynamic_notches); + } + } + if (harmonics == 0) { + // this allows use of FFT to find peaks with all notch filters disabled + harmonics = 3; + } // count the number of active harmonics or dynamic notchs _tracked_peaks = constrain_int16(MAX(__builtin_popcount(harmonics), - _ins->get_num_gyro_dynamic_notches()), 1, FrequencyPeak::MAX_TRACKED_PEAKS); + num_notches), 1, FrequencyPeak::MAX_TRACKED_PEAKS); // calculate harmonic multiplier. this assumes the harmonics configured on the // harmonic notch reflect the multiples of the fundamental harmonic that should be tracked @@ -274,7 +301,7 @@ void AP_GyroFFT::init(uint16_t loop_rate_hz) } // initialise the HAL DSP subsystem - _state = hal.dsp->fft_init(_window_size, _fft_sampling_rate_hz); + _state = hal.dsp->fft_init(_window_size, _fft_sampling_rate_hz, _num_frames); if (_state == nullptr) { gcs().send_text(MAV_SEVERITY_WARNING, "Failed to initialize DSP engine"); return; @@ -312,7 +339,7 @@ void AP_GyroFFT::init(uint16_t loop_rate_hz) // finally we are done _initialized = true; - update_parameters(); + update_parameters(true); // start running FFTs if (start_update_thread()) { set_analysis_enabled(true); @@ -374,7 +401,13 @@ void AP_GyroFFT::update() if (!_rpy_health.x && !_rpy_health.y) { _health = 0; } else { - _health = MIN(_global_state._health, _ins->get_num_gyro_dynamic_notches()); + uint8_t num_notches = 1; + for (auto ¬ch : _ins->harmonic_notches) { + if (notch.params.enabled()) { + num_notches = MAX(num_notches, notch.num_dynamic_notches); + } + } + _health = MIN(_global_state._health, num_notches); } } @@ -456,17 +489,17 @@ bool AP_GyroFFT::start_analysis() { } // update calculated values of dynamic parameters - runs at 1Hz -void AP_GyroFFT::update_parameters() +void AP_GyroFFT::update_parameters(bool force) { // lock contention is very costly, so don't allow configuration updates while flying - if (!_initialized || AP::arming().is_armed()) { + if ((!_initialized || AP::arming().is_armed()) && !force) { return; } WITH_SEMAPHORE(_sem); // don't allow MAXHZ to go to Nyquist - _fft_max_hz = MIN(_fft_max_hz, _fft_sampling_rate_hz * 0.48); + _fft_max_hz.set(MIN(_fft_max_hz, _fft_sampling_rate_hz * 0.48)); _config._snr_threshold_db = _snr_threshold_db; _config._fft_min_hz = _fft_min_hz; _config._fft_max_hz = _fft_max_hz; @@ -475,7 +508,7 @@ void AP_GyroFFT::update_parameters() // determine the endt FFT bin for all frequency detection _config._fft_end_bin = MIN(ceilf(_fft_max_hz.get() / _state->_bin_resolution), _state->_bin_count); // actual attenuation from the db value - _config._attenuation_cutoff = powf(10.0f, -_attenuation_power_db / 10.0f); + _config._attenuation_cutoff = powf(10.0f, -_attenuation_power_db * 0.1f); } // thread for processing gyro data via FFT @@ -542,7 +575,7 @@ bool AP_GyroFFT::pre_arm_check(char *failure_msg, const uint8_t failure_msg_len) return false; } - // make sure the frequency maxium is below Nyquist + // make sure the frequency maximum is below Nyquist if (_fft_max_hz > _fft_sampling_rate_hz * 0.5f) { hal.util->snprintf(failure_msg, failure_msg_len, "FFT config MAXHZ %dHz > %dHz", _fft_max_hz.get(), _fft_sampling_rate_hz / 2); return false; @@ -574,7 +607,7 @@ bool AP_GyroFFT::pre_arm_check(char *failure_msg, const uint8_t failure_msg_len) if (_calibrated) { // provide the user with some useful information about what they have configured - gcs().send_text(MAV_SEVERITY_INFO, "FFT: calibrated %.1fKHz/%.1fHz/%.1fHz", _fft_sampling_rate_hz / 1000.0f, + gcs().send_text(MAV_SEVERITY_INFO, "FFT: calibrated %.1fKHz/%.1fHz/%.1fHz", _fft_sampling_rate_hz * 0.001f, _state->_bin_resolution * 0.5, 1000.0f * XYZ_AXIS_COUNT / _frame_time_ms); } @@ -595,10 +628,18 @@ void AP_GyroFFT::update_freq_hover(float dt, float throttle_out) if (!analysis_enabled()) { return; } + + // throttle averaging for average fft calculation + if (is_zero(_avg_throttle_out)) { + _avg_throttle_out = throttle_out; + } else { + _avg_throttle_out = constrain_float(_avg_throttle_out + (dt / (10.0f + dt)) * (throttle_out - _avg_throttle_out), 0.01f, 0.9f); + } + // we have chosen to constrain the hover frequency to be within the range reachable by the third order expo polynomial. - _freq_hover_hz = constrain_float(_freq_hover_hz + (dt / (10.0f + dt)) * (get_weighted_noise_center_freq_hz() - _freq_hover_hz), _fft_min_hz, _fft_max_hz); - _bandwidth_hover_hz = constrain_float(_bandwidth_hover_hz + (dt / (10.0f + dt)) * (get_weighted_noise_center_bandwidth_hz() - _bandwidth_hover_hz), 0, _fft_max_hz * 0.5f); - _throttle_ref = constrain_float(_throttle_ref + (dt / (10.0f + dt)) * (throttle_out * sq((float)_fft_min_hz.get() / _freq_hover_hz.get()) - _throttle_ref), 0.01f, 0.9f); + _freq_hover_hz.set(constrain_float(_freq_hover_hz + (dt / (10.0f + dt)) * (get_weighted_noise_center_freq_hz() - _freq_hover_hz), _fft_min_hz, _fft_max_hz)); + _bandwidth_hover_hz.set(constrain_float(_bandwidth_hover_hz + (dt / (10.0f + dt)) * (get_weighted_noise_center_bandwidth_hz() - _bandwidth_hover_hz), 0, _fft_max_hz * 0.5f)); + _throttle_ref.set(constrain_float(_throttle_ref + (dt / (10.0f + dt)) * (throttle_out * sq((float)_fft_min_hz.get() / _freq_hover_hz.get()) - _throttle_ref), 0.01f, 0.9f)); } // save parameters as part of disarming @@ -614,6 +655,69 @@ void AP_GyroFFT::save_params_on_disarm() _throttle_ref.save(); } + // notch tuning +void AP_GyroFFT::start_notch_tune() +{ + if (!analysis_enabled()) { + return; + } + + if (!hal.dsp->fft_start_average(_state)) { + gcs().send_text(MAV_SEVERITY_WARNING, "FFT: Unable to start FFT averaging"); + } + _avg_throttle_out = 0.0f; +} + +void AP_GyroFFT::stop_notch_tune() +{ + if (!analysis_enabled()) { + return; + } + + float freqs[FrequencyPeak::MAX_TRACKED_PEAKS] {}; + + uint16_t numpeaks = hal.dsp->fft_stop_average(_state, _config._fft_start_bin, _config._fft_end_bin, freqs); + + if (numpeaks == 0) { + return; + } + + float harmonic = freqs[0]; + float harmonic_fit = 100.0f; + + for (uint8_t i = 1; i < numpeaks; i++) { + if (freqs[i] < harmonic) { + const float fit = 100.0f * fabsf(harmonic - freqs[i] * _harmonic_multiplier) / harmonic; + if (isfinite(fit) && fit < _harmonic_fit && fit < harmonic_fit) { + harmonic = freqs[i]; + harmonic_fit = fit; + } + } + } + + gcs().send_text(MAV_SEVERITY_INFO, "FFT: Found peaks at %.1f/%.1f/%.1fHz", freqs[0], freqs[1], freqs[2]); + gcs().send_text(MAV_SEVERITY_NOTICE, "FFT: Selected %.1fHz with fit %.1f%%\n", harmonic, is_equal(harmonic_fit, 100.0f) ? 100.0f : 100.0f - harmonic_fit); + + // if we don't have a throttle value then all bets are off + if (is_zero(_avg_throttle_out) || is_zero(harmonic)) { + gcs().send_text(MAV_SEVERITY_WARNING, "FFT: Unable to calculate notch: need stable hover"); + return; + } + + // pick a ref which means the notch covers all the way down to FFT_MINHZ + const float thr_ref = _avg_throttle_out * sq((float)_fft_min_hz.get() / harmonic); + + if (!_ins->setup_throttle_gyro_harmonic_notch((float)_fft_min_hz.get(), thr_ref)) { + gcs().send_text(MAV_SEVERITY_WARNING, "FFT: Unable to set throttle notch with %.1fHz/%.2f", + (float)_fft_min_hz.get(), thr_ref); + // save results to FFT slots + _throttle_ref.set(thr_ref); + _freq_hover_hz.set(harmonic); + } else { + gcs().send_text(MAV_SEVERITY_NOTICE, "FFT: Notch frequency %.1fHz and ref %.2f selected", (float)_fft_min_hz.get(), thr_ref); + } +} + // return the noise peak that is being tracked // called from main thread AP_GyroFFT::FrequencyPeak AP_GyroFFT::get_tracked_noise_peak() const @@ -685,7 +789,7 @@ float AP_GyroFFT::get_weighted_noise_center_freq_hz() const if (!_health) { #if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane) AP_Motors* motors = AP::motors(); - if (motors != nullptr) { + if (motors != nullptr && !is_zero(_throttle_ref)) { // FFT is not healthy, fallback to throttle-based estimate return constrain_float(_fft_min_hz * MAX(1.0f, sqrtf(motors->get_throttle_out() / _throttle_ref)), _fft_min_hz, _fft_max_hz); } @@ -764,7 +868,7 @@ float AP_GyroFFT::calculate_weighted_freq_hz(const Vector3f& energy, const Vecto // @Description: FFT Filter Tuning // @Field: TimeUS: microseconds since system startup // @Field: PkAvg: peak noise frequency as an energy-weighted average of roll and pitch peak frequencies -// @Field: BwAvg: bandwidth of weighted peak freqency where edges are determined by FFT_ATT_REF +// @Field: BwAvg: bandwidth of weighted peak frequency where edges are determined by FFT_ATT_REF // @Field: SnX: signal-to-noise ratio on the roll axis // @Field: SnY: signal-to-noise ratio on the pitch axis // @Field: SnZ: signal-to-noise ratio on the yaw axis @@ -813,7 +917,7 @@ void AP_GyroFFT::write_log_messages() gcs().send_text(MAV_SEVERITY_WARNING, "FFT: f:%.1f, fr:%.1f, b:%u, fd:%.1f", _debug_state._center_freq_hz_filtered[FrequencyPeak::CENTER][_update_axis], _debug_state._center_freq_hz[_update_axis], _debug_max_bin, _debug_max_bin_freq); gcs().send_text(MAV_SEVERITY_WARNING, "FFT: bw:%.1f, e:%.1f, r:%.1f, snr:%.1f", - _debug_state._center_bandwidth_hz_filtered[FrequencyPeak::CENTER][_update_axis], _debug_max_freq_bin, _ref_energy[_update_axis][_debug_max_bin], _debug_snr); + _debug_state._center_bandwidth_hz_filtered[FrequencyPeak::CENTER][_update_axis], _debug_max_freq_bin, _ref_energy[_debug_max_bin][_update_axis], _debug_snr); _last_output_ms = now; } #endif @@ -826,9 +930,9 @@ void AP_GyroFFT::write_log_messages() // @Field: PkX: noise frequency of the peak on roll // @Field: PkY: noise frequency of the peak on pitch // @Field: PkZ: noise frequency of the peak on yaw -// @Field: BwX: bandwidth of the peak freqency on roll where edges are determined by FFT_ATT_REF -// @Field: BwY: bandwidth of the peak freqency on pitch where edges are determined by FFT_ATT_REF -// @Field: BwZ: bandwidth of the peak freqency on yaw where edges are determined by FFT_ATT_REF +// @Field: BwX: bandwidth of the peak frequency on roll where edges are determined by FFT_ATT_REF +// @Field: BwY: bandwidth of the peak frequency on pitch where edges are determined by FFT_ATT_REF +// @Field: BwZ: bandwidth of the peak frequency on yaw where edges are determined by FFT_ATT_REF // @Field: EnX: power spectral density bin energy of the peak on roll // @Field: EnY: power spectral density bin energy of the peak on roll // @Field: EnZ: power spectral density bin energy of the peak on roll @@ -919,7 +1023,7 @@ void AP_GyroFFT::calculate_noise(bool calibrating, const EngineConfig& config) #if DEBUG_FFT WITH_SEMAPHORE(_sem); _debug_state = _thread_state; - _debug_max_freq_bin = _state->_freq_bins[_state->_peak_data[FrequencyPeak::CENTER]._bin]; + _debug_max_freq_bin = _state->get_freq_bin(_state->_peak_data[FrequencyPeak::CENTER]._bin); _debug_max_bin_freq = _state->_peak_data[FrequencyPeak::CENTER]._freq_hz; _debug_snr = snr; _debug_max_bin = _state->_peak_data[FrequencyPeak::CENTER]._bin; @@ -1012,7 +1116,7 @@ bool AP_GyroFFT::calculate_filtered_noise(FrequencyPeak target_peak, FrequencyPe if (freqs.is_valid(FrequencyPeak(source_peak))) { // total peak energy requires an integration, as an approximation use amplitude * noise width * 5/6 - update_tl_center_freq_energy(target_peak, _update_axis, _state->_freq_bins[nb] * peak_data->_noise_width_hz * 0.8333f); + update_tl_center_freq_energy(target_peak, _update_axis, _state->get_freq_bin(nb) * peak_data->_noise_width_hz * 0.8333f); update_tl_noise_center_bandwidth_hz(target_peak, _update_axis, peak_data->_noise_width_hz); update_tl_noise_center_freq_hz(target_peak, _update_axis, freqs.get_weighted_frequency(FrequencyPeak(source_peak))); _missed_cycles[_update_axis][target_peak] = 0; @@ -1025,7 +1129,7 @@ bool AP_GyroFFT::calculate_filtered_noise(FrequencyPeak target_peak, FrequencyPe } // we failed to find a signal for more than FFT_MAX_MISSED_UPDATES cycles - update_tl_center_freq_energy(target_peak, _update_axis, _state->_freq_bins[nb] * peak_data->_noise_width_hz * 0.8333f); // use the actual energy detected rather than 0 + update_tl_center_freq_energy(target_peak, _update_axis, _state->get_freq_bin(nb) * peak_data->_noise_width_hz * 0.8333f); // use the actual energy detected rather than 0 update_tl_noise_center_bandwidth_hz(target_peak, _update_axis, _bandwidth_hover_hz); update_tl_noise_center_freq_hz(target_peak, _update_axis, config._fft_min_hz); @@ -1061,12 +1165,12 @@ bool AP_GyroFFT::get_weighted_frequency(FrequencyPeak peak, float& weighted_peak const uint16_t bin = peak_data->_bin; // calculate the SNR and center frequency energy - const float max_energy = MAX(1.0f, _state->_freq_bins[bin]); - const float ref_energy = MAX(1.0f, _ref_energy[_update_axis][bin]); + const float max_energy = MAX(1.0f, _state->get_freq_bin(bin)); + const float ref_energy = MAX(1.0f, _ref_energy[bin][_update_axis]); snr = 10.f * (log10f(max_energy) - log10f(ref_energy)); // if the bin energy is above the noise threshold then we have a signal - if (!_thread_state._noise_needs_calibration && isfinite(_state->_freq_bins[bin]) && snr > config._snr_threshold_db) { + if (!_thread_state._noise_needs_calibration && isfinite(_state->get_freq_bin(bin)) && snr > config._snr_threshold_db) { weighted_peak_freq_hz = constrain_float(peak_data->_freq_hz, (float)config._fft_min_hz, (float)config._fft_max_hz); return true; } @@ -1122,13 +1226,13 @@ void AP_GyroFFT::update_ref_energy(uint16_t max_bin) // determine a PS noise reference at each of the possible center frequencies if (_noise_cycles == 0 && _noise_calibration_cycles[_update_axis] > 0) { for (uint16_t i = 1; i < _state->_bin_count; i++) { - _ref_energy[_update_axis][i] += _state->_freq_bins[i]; + _ref_energy[i][_update_axis] += _state->get_freq_bin(i); } if (--_noise_calibration_cycles[_update_axis] == 0) { for (uint16_t i = 1; i < _state->_bin_count; i++) { const float cycles = (static_cast(_window_size) / static_cast(_samples_per_frame)) * 2; // overall random noise is reduced by sqrt(N) when averaging periodigrams so adjust for that - _ref_energy[_update_axis][i] = (_ref_energy[_update_axis][i] / cycles) * sqrtf(cycles); + _ref_energy[i][_update_axis] = (_ref_energy[i][_update_axis] / cycles) * sqrtf(cycles); } WITH_SEMAPHORE(_sem); @@ -1181,6 +1285,12 @@ float AP_GyroFFT::self_test(float frequency, FloatBuffer& test_window) _update_axis = 0; + // if using averaging we need to process _num_frames in order to not bias the result + for (uint8_t i = 1; i < _num_frames; i++) { + hal.dsp->fft_start(_state, test_window, 0); + hal.dsp->fft_analyse(_state, _config._fft_start_bin, _config._fft_end_bin, _config._attenuation_cutoff); + } + // final cycle is the one we want hal.dsp->fft_start(_state, test_window, 0); uint16_t max_bin = hal.dsp->fft_analyse(_state, _config._fft_start_bin, _config._fft_end_bin, _config._attenuation_cutoff); diff --git a/libraries/AP_GyroFFT/AP_GyroFFT.h b/libraries/AP_GyroFFT/AP_GyroFFT.h index c0d98322c64..3767c0cbcbc 100644 --- a/libraries/AP_GyroFFT/AP_GyroFFT.h +++ b/libraries/AP_GyroFFT/AP_GyroFFT.h @@ -56,11 +56,13 @@ class AP_GyroFFT // update the engine state - runs at 400Hz void update(); // update calculated values of dynamic parameters - runs at 1Hz - void update_parameters(); + void update_parameters() { update_parameters(false); } // thread for processing gyro data via FFT void update_thread(); // start the update thread bool start_update_thread(); + // is the subsystem enabled + bool enabled() const { return _enable; } // check at startup that standard frequencies can be detected bool pre_arm_check(char *failure_msg, const uint8_t failure_msg_len); @@ -72,6 +74,9 @@ class AP_GyroFFT void save_params_on_disarm(); // dynamically enable or disable the analysis through the aux switch void set_analysis_enabled(bool enabled) { _analysis_enabled = enabled; }; + // notch tuning + void start_notch_tune(); + void stop_notch_tune(); // detected peak frequency filtered at 1/3 the update rate const Vector3f& get_noise_center_freq_hz() const { return get_noise_center_freq_hz(FrequencyPeak::CENTER); } @@ -206,6 +211,7 @@ class AP_GyroFFT uint16_t get_available_samples(uint8_t axis) { return _sample_mode == 0 ?_ins->get_raw_gyro_window(axis).available() : _downsampled_gyro_data[axis].available(); } + void update_parameters(bool force); // semaphore for access to shared FFT data HAL_Semaphore _sem; @@ -282,6 +288,8 @@ class AP_GyroFFT uint8_t _health; // engine health on roll/pitch/yaw Vector3 _rpy_health; + // averaged throttle output over averaging period + float _avg_throttle_out; // smoothing filter on the output MedianLowPassFilter3dFloat _center_freq_filter[FrequencyPeak::MAX_TRACKED_PEAKS]; @@ -333,6 +341,8 @@ class AP_GyroFFT AP_Int8 _harmonic_fit; // harmonic peak target AP_Int8 _harmonic_peak; + // number of output frames to retain for averaging + AP_Int8 _num_frames; AP_InertialSensor* _ins; #if DEBUG_FFT uint32_t _last_output_ms; diff --git a/libraries/AP_HAL/AP_HAL_Boards.h b/libraries/AP_HAL/AP_HAL_Boards.h index a9560e014f5..3cb843faaaf 100644 --- a/libraries/AP_HAL/AP_HAL_Boards.h +++ b/libraries/AP_HAL/AP_HAL_Boards.h @@ -228,6 +228,10 @@ #define HAL_ENABLE_LIBUAVCAN_DRIVERS HAL_CANMANAGER_ENABLED #endif +#ifndef AP_AIRSPEED_BACKEND_DEFAULT_ENABLED +#define AP_AIRSPEED_BACKEND_DEFAULT_ENABLED 1 +#endif + #ifdef HAVE_LIBDL #define AP_MODULE_SUPPORTED 1 #else @@ -253,6 +257,10 @@ #define USE_LIBC_REALLOC 1 #endif +#ifndef AP_HAL_SHARED_DMA_ENABLED +#define AP_HAL_SHARED_DMA_ENABLED 1 +#endif + #ifndef HAL_ENABLE_THREAD_STATISTICS #define HAL_ENABLE_THREAD_STATISTICS 0 #endif @@ -261,10 +269,22 @@ #define HAL_INS_ENABLED (!defined(HAL_BUILD_AP_PERIPH)) #endif +#ifndef AP_STATS_ENABLED +#define AP_STATS_ENABLED (!defined(HAL_BUILD_AP_PERIPH)) +#endif + #ifndef HAL_WITH_MCU_MONITORING #define HAL_WITH_MCU_MONITORING 0 #endif +#ifndef AP_CRASHDUMP_ENABLED +#define AP_CRASHDUMP_ENABLED 0 +#endif + +#ifndef AP_SIGNED_FIRMWARE +#define AP_SIGNED_FIRMWARE 0 +#endif + #ifndef HAL_HNF_MAX_FILTERS // On an F7 The difference in CPU load between 1 notch and 24 notches is about 2% // The difference in CPU load between 1Khz backend and 2Khz backend is about 10% @@ -282,6 +302,12 @@ // plus one static notch with one harmonic #define HAL_HNF_MAX_FILTERS 18 #endif +#endif // HAL_HNF_MAX_FILTERS + +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL // allow SITL to have all the CANFD options +#define HAL_CANFD_SUPPORTED 8 +#elif !defined(HAL_CANFD_SUPPORTED) +#define HAL_CANFD_SUPPORTED 0 #endif #ifndef __RAMFUNC__ @@ -291,3 +317,7 @@ #ifndef __FASTRAMFUNC__ #define __FASTRAMFUNC__ #endif + +#ifndef HAL_ENABLE_DFU_BOOT +#define HAL_ENABLE_DFU_BOOT 0 +#endif diff --git a/libraries/AP_HAL/AP_HAL_Macros.h b/libraries/AP_HAL/AP_HAL_Macros.h index 5c198fed060..25e124af666 100644 --- a/libraries/AP_HAL/AP_HAL_Macros.h +++ b/libraries/AP_HAL/AP_HAL_Macros.h @@ -6,7 +6,7 @@ macros to allow code to build on multiple platforms more easily */ -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX || HAL_WITH_EKF_DOUBLE +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX || HAL_WITH_EKF_DOUBLE || (CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && AP_SIM_ENABLED) /* allow double maths on Linux and SITL to avoid problems with system headers */ diff --git a/libraries/AP_HAL/AP_HAL_Namespace.h b/libraries/AP_HAL/AP_HAL_Namespace.h index e22e631cf52..83946aaf31b 100644 --- a/libraries/AP_HAL/AP_HAL_Namespace.h +++ b/libraries/AP_HAL/AP_HAL_Namespace.h @@ -65,6 +65,8 @@ namespace AP_HAL { SPIDevice_Type = -1, }; + class SIMState; + // Must be implemented by the concrete HALs. const HAL& get_HAL(); } diff --git a/libraries/AP_HAL/CANIface.cpp b/libraries/AP_HAL/CANIface.cpp index bce2ed6c1be..e5a712390d1 100644 --- a/libraries/AP_HAL/CANIface.cpp +++ b/libraries/AP_HAL/CANIface.cpp @@ -93,3 +93,83 @@ bool AP_HAL::CANIface::register_frame_callback(FrameCb cb) frame_callback = cb; return true; } + +AP_HAL::CANFrame::CANFrame(uint32_t can_id, const uint8_t* can_data, uint8_t data_len, bool canfd_frame) : + id(can_id), + canfd(canfd_frame) +{ + if ((can_data == nullptr) || (data_len == 0) || (data_len > MaxDataLen)) { + return; + } + memcpy(this->data, can_data, data_len); + if (data_len <= 8) { + dlc = data_len; + } else if (!canfd) { + dlc = 8; + } else { + /* + Data Length Code 9 10 11 12 13 14 15 + Number of data bytes 12 16 20 24 32 48 64 + */ + if (data_len <= 12) { + dlc = 9; + } else if (data_len <= 16) { + dlc = 10; + } else if (data_len <= 20) { + dlc = 11; + } else if (data_len <= 24) { + dlc = 12; + } else if (data_len <= 32) { + dlc = 13; + } else if (data_len <= 48) { + dlc = 14; + } else if (data_len <= 64) { + dlc = 15; + } + } +} + +uint8_t AP_HAL::CANFrame::dataLengthToDlc(uint8_t data_length) +{ + if (data_length <= 8) { + return data_length; + } else if (data_length <= 12) { + return 9; + } else if (data_length <= 16) { + return 10; + } else if (data_length <= 20) { + return 11; + } else if (data_length <= 24) { + return 12; + } else if (data_length <= 32) { + return 13; + } else if (data_length <= 48) { + return 14; + } + return 15; +} + + +uint8_t AP_HAL::CANFrame::dlcToDataLength(uint8_t dlc) +{ + /* + Data Length Code 9 10 11 12 13 14 15 + Number of data bytes 12 16 20 24 32 48 64 + */ + if (dlc <= 8) { + return dlc; + } else if (dlc == 9) { + return 12; + } else if (dlc == 10) { + return 16; + } else if (dlc == 11) { + return 20; + } else if (dlc == 12) { + return 24; + } else if (dlc == 13) { + return 32; + } else if (dlc == 14) { + return 48; + } + return 64; +} diff --git a/libraries/AP_HAL/CANIface.h b/libraries/AP_HAL/CANIface.h index 68988ad0e0c..30a5564e3ef 100644 --- a/libraries/AP_HAL/CANIface.h +++ b/libraries/AP_HAL/CANIface.h @@ -19,6 +19,7 @@ #include #include "AP_HAL_Namespace.h" +#include "AP_HAL_Boards.h" class ExpandingString; @@ -32,31 +33,30 @@ struct AP_HAL::CANFrame { static const uint32_t FlagRTR = 1U << 30; ///< Remote transmission request static const uint32_t FlagERR = 1U << 29; ///< Error frame +#if HAL_CANFD_SUPPORTED + static const uint8_t NonFDCANMaxDataLen = 8; + static const uint8_t MaxDataLen = 64; +#else + static const uint8_t NonFDCANMaxDataLen = 8; static const uint8_t MaxDataLen = 8; - +#endif uint32_t id; ///< CAN ID with flags (above) union { uint8_t data[MaxDataLen]; uint32_t data_32[MaxDataLen/4]; }; uint8_t dlc; ///< Data Length Code + bool canfd; CANFrame() : id(0), - dlc(0) + dlc(0), + canfd(false) { memset(data,0, MaxDataLen); } - CANFrame(uint32_t can_id, const uint8_t* can_data, uint8_t data_len) : - id(can_id), - dlc((data_len > MaxDataLen) ? MaxDataLen : data_len) - { - if ((can_data == nullptr) || (data_len != dlc) || (dlc == 0)) { - return; - } - memcpy(this->data, can_data, dlc); - } + CANFrame(uint32_t can_id, const uint8_t* can_data, uint8_t data_len, bool canfd_frame = false); bool operator!=(const CANFrame& rhs) const { @@ -67,6 +67,11 @@ struct AP_HAL::CANFrame { return (id == rhs.id) && (dlc == rhs.dlc) && (memcmp(data, rhs.data, dlc) == 0); } + // signed version of id, for use by scriping where uint32_t is expensive + int32_t id_signed(void) const { + return isExtended()? int32_t(id & MaskExtID) : int32_t(id & MaskStdID); + } + bool isExtended() const { return id & FlagEFF; @@ -79,7 +84,19 @@ struct AP_HAL::CANFrame { { return id & FlagERR; } + void setCanFD(bool canfd_frame) + { + canfd = canfd_frame; + } + + bool isCanFDFrame() const + { + return canfd; + } + static uint8_t dlcToDataLength(uint8_t dlc); + + static uint8_t dataLengthToDlc(uint8_t data_length); /** * CAN frame arbitration rules, particularly STD vs EXT: * Marco Di Natale - "Understanding and using the Controller Area Network" @@ -127,6 +144,7 @@ class AP_HAL::CANIface bool aborted:1; bool pushed:1; bool setup:1; + bool canfd_frame:1; bool operator<(const CanTxItem& rhs) const { @@ -150,6 +168,10 @@ class AP_HAL::CANIface } }; + virtual bool init(const uint32_t bitrate, const uint32_t fdbitrate, const OperatingMode mode) { + return init(bitrate, mode); + } + // Initialise the interface with hardware configuration required to start comms. virtual bool init(const uint32_t bitrate, const OperatingMode mode) = 0; diff --git a/libraries/AP_HAL/DSP.cpp b/libraries/AP_HAL/DSP.cpp index e3bb320bdc0..bdc59e68bbc 100644 --- a/libraries/AP_HAL/DSP.cpp +++ b/libraries/AP_HAL/DSP.cpp @@ -18,6 +18,12 @@ #include #include "AP_HAL.h" #include "DSP.h" +#ifndef HAL_NO_UARTDRIVER +#include +#endif +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#include +#endif #if HAL_WITH_DSP @@ -28,28 +34,33 @@ extern const AP_HAL::HAL &hal; #define SQRT_2_3 0.816496580927726f #define SQRT_6 2.449489742783178f -DSP::FFTWindowState::FFTWindowState(uint16_t window_size, uint16_t sample_rate) +DSP::FFTWindowState::FFTWindowState(uint16_t window_size, uint16_t sample_rate, uint8_t sliding_window_size) : _window_size(window_size), _bin_count(window_size / 2), - _bin_resolution((float)sample_rate / (float)window_size) + _num_stored_freqs(window_size / 2 + 1), + _bin_resolution((float)sample_rate / (float)window_size), + _sliding_window_size(sliding_window_size), + _current_slice(0) { // includes DC ad Nyquist components and needs to be large enough for intermediate steps - _freq_bins = (float*)hal.util->malloc_type(sizeof(float) * (window_size), DSP_MEM_REGION); - _derivative_freq_bins = (float*)hal.util->malloc_type(sizeof(float) * (_bin_count + 1), DSP_MEM_REGION); - _hanning_window = (float*)hal.util->malloc_type(sizeof(float) * (window_size), DSP_MEM_REGION); + _freq_bins = (float*)hal.util->malloc_type(sizeof(float) * _window_size, DSP_MEM_REGION); + _derivative_freq_bins = (float*)hal.util->malloc_type(sizeof(float) * _num_stored_freqs, DSP_MEM_REGION); + _hanning_window = (float*)hal.util->malloc_type(sizeof(float) * _window_size, DSP_MEM_REGION); // allocate workspace, including Nyquist component _rfft_data = (float*)hal.util->malloc_type(sizeof(float) * (_window_size + 2), DSP_MEM_REGION); + // sliding window of frequency bin frames + if (_sliding_window_size > 0) { + _sliding_window = (float*)hal.util->malloc_type(sizeof(float) * _num_stored_freqs * _sliding_window_size, DSP_MEM_REGION); + _avg_freq_bins = (float*)hal.util->malloc_type(sizeof(float) * _num_stored_freqs, DSP_MEM_REGION); + // we can still fallback to non-averaging if there is not enough memory + if (_avg_freq_bins == nullptr) { + hal.util->free_type(_sliding_window, sizeof(float) * _num_stored_freqs * _sliding_window_size, DSP_MEM_REGION); + _sliding_window = nullptr; + } + } if (_freq_bins == nullptr || _hanning_window == nullptr || _rfft_data == nullptr || _derivative_freq_bins == nullptr) { - hal.util->free_type(_freq_bins, sizeof(float) * (_window_size), DSP_MEM_REGION); - hal.util->free_type(_derivative_freq_bins, sizeof(float) * (_bin_count), DSP_MEM_REGION); - hal.util->free_type(_hanning_window, sizeof(float) * (_window_size), DSP_MEM_REGION); - hal.util->free_type(_rfft_data, sizeof(float) * (_window_size + 2), DSP_MEM_REGION); - - _freq_bins = nullptr; - _derivative_freq_bins = nullptr; - _hanning_window = nullptr; - _rfft_data = nullptr; + free_data_structures(); return; } @@ -59,20 +70,29 @@ DSP::FFTWindowState::FFTWindowState(uint16_t window_size, uint16_t sample_rate) _hanning_window[i] = (0.5f - 0.5f * cosf(2.0f * M_PI * i / ((float)window_size - 1))); _window_scale += _hanning_window[i]; } - // Calculate the inverse of the Effective Noise Bandwidth + // Calculate the inverse of the Effective Noise Bandwidth - equation 24 _window_scale = 2.0f / sq(_window_scale); } DSP::FFTWindowState::~FFTWindowState() { - hal.util->free_type(_freq_bins, sizeof(float) * (_window_size), DSP_MEM_REGION); + free_data_structures(); +} + +void DSP::FFTWindowState::free_data_structures() +{ + hal.util->free_type(_freq_bins, sizeof(float) * _window_size * _sliding_window_size, DSP_MEM_REGION); _freq_bins = nullptr; - hal.util->free_type(_derivative_freq_bins, sizeof(float) * (_bin_count), DSP_MEM_REGION); + hal.util->free_type(_derivative_freq_bins, sizeof(float) * _num_stored_freqs, DSP_MEM_REGION); _derivative_freq_bins = nullptr; hal.util->free_type(_hanning_window, sizeof(float) * (_window_size), DSP_MEM_REGION); _hanning_window = nullptr; hal.util->free_type(_rfft_data, sizeof(float) * (_window_size + 2), DSP_MEM_REGION); _rfft_data = nullptr; + hal.util->free_type(_avg_freq_bins, sizeof(float) * _num_stored_freqs, DSP_MEM_REGION); + _avg_freq_bins = nullptr; + hal.util->free_type(_sliding_window, sizeof(float) * _num_stored_freqs * _sliding_window_size, DSP_MEM_REGION); + _sliding_window = nullptr; } // step 3: find the magnitudes of the complex data @@ -82,11 +102,21 @@ void DSP::step_cmplx_mag(FFTWindowState* fft, uint16_t start_bin, uint16_t end_b // find the maximum power in the range we are interested in // in order to see a peak in the last bin we need to allow all the way up to the nyquist const uint16_t smoothwidth = 1; + float* freq_data = fft->_freq_bins; + + if (fft->_sliding_window != nullptr) { + update_average_from_sliding_window(fft); + freq_data = fft->_avg_freq_bins; + } else { + // scale the power to account for the input window + vector_scale_float(fft->_freq_bins, fft->_window_scale, fft->_freq_bins, fft->_bin_count); + } + uint16_t bin_range = (MIN(end_bin + ((smoothwidth + 1) >> 1) + 2, fft->_bin_count) - start_bin) + 1; // find the three highest peaks using a zero crossing algorithm uint16_t peaks[MAX_TRACKED_PEAKS] {}; memset(fft->_peak_data, 0, sizeof(fft->_peak_data)); - uint16_t numpeaks = find_peaks(&fft->_freq_bins[start_bin], bin_range, fft->_derivative_freq_bins, peaks, MAX_TRACKED_PEAKS, 0.0f, -1.0f, smoothwidth, 2); + uint16_t numpeaks = find_peaks(&freq_data[start_bin], bin_range, fft->_derivative_freq_bins, peaks, MAX_TRACKED_PEAKS, 0.0f, -1.0f, smoothwidth, 2); //hal.console->printf("found %d peaks\n", numpeaks); for (uint16_t i = 0; i < MAX_TRACKED_PEAKS; i++) { @@ -94,20 +124,24 @@ void DSP::step_cmplx_mag(FFTWindowState* fft, uint16_t start_bin, uint16_t end_b } uint16_t top = 0, bottom = 0; - fft->_peak_data[CENTER]._noise_width_hz = find_noise_width(fft, start_bin, end_bin, fft->_peak_data[CENTER]._bin, noise_att_cutoff, top, bottom); + fft->_peak_data[CENTER]._noise_width_hz = find_noise_width(freq_data, start_bin, end_bin, fft->_peak_data[CENTER]._bin, noise_att_cutoff, fft->_bin_resolution, top, bottom); if (numpeaks > 1) { - fft->_peak_data[LOWER_SHOULDER]._noise_width_hz = find_noise_width(fft, start_bin, end_bin, fft->_peak_data[LOWER_SHOULDER]._bin, noise_att_cutoff, top, bottom); + fft->_peak_data[LOWER_SHOULDER]._noise_width_hz = find_noise_width(freq_data, start_bin, end_bin, fft->_peak_data[LOWER_SHOULDER]._bin, noise_att_cutoff, fft->_bin_resolution, top, bottom); } if (numpeaks > 2) { - fft->_peak_data[UPPER_SHOULDER]._noise_width_hz = find_noise_width(fft, start_bin, end_bin, fft->_peak_data[UPPER_SHOULDER]._bin, noise_att_cutoff, top, bottom); + fft->_peak_data[UPPER_SHOULDER]._noise_width_hz = find_noise_width(freq_data, start_bin, end_bin, fft->_peak_data[UPPER_SHOULDER]._bin, noise_att_cutoff, fft->_bin_resolution, top, bottom); } - // scale the power to account for the input window - vector_scale_float(fft->_freq_bins, fft->_window_scale, fft->_freq_bins, fft->_bin_count); + // average the FFT data + if (fft->_averaging) { + vector_add_float(fft->_avg_freq_bins, fft->_freq_bins, fft->_avg_freq_bins, fft->_bin_count); + fft->_averaging_samples++; + } } // calculate the noise width of a peak based on the input parameters -float DSP::find_noise_width(FFTWindowState* fft, uint16_t start_bin, uint16_t end_bin, uint16_t max_energy_bin, float cutoff, uint16_t& peak_top, uint16_t& peak_bottom) const +// freq_bins can be scaled or unscaled for power +float DSP::find_noise_width(float* freq_bins, uint16_t start_bin, uint16_t end_bin, uint16_t max_energy_bin, float cutoff, float bin_resolution, uint16_t& peak_top, uint16_t& peak_bottom) const { // max_energy_bin is guaranteed to be between start_bin and end_bin peak_top = end_bin; @@ -119,7 +153,7 @@ float DSP::find_noise_width(FFTWindowState* fft, uint16_t start_bin, uint16_t en // -attenuation/2 dB point above the center bin if (max_energy_bin < end_bin) { for (uint16_t b = max_energy_bin + 1; b <= end_bin; b++) { - if (fft->_freq_bins[b] < fft->_freq_bins[max_energy_bin] * cutoff) { + if (freq_bins[b] < freq_bins[max_energy_bin] * cutoff) { // we assume that the 3dB point is in the middle of the final shoulder bin noise_width_hz += (b - max_energy_bin - 0.5f); peak_top = b; @@ -130,7 +164,7 @@ float DSP::find_noise_width(FFTWindowState* fft, uint16_t start_bin, uint16_t en // -attenuation/2 dB point below the center bin if (max_energy_bin > start_bin) { for (uint16_t b = max_energy_bin - 1; b >= start_bin; b--) { - if (fft->_freq_bins[b] < fft->_freq_bins[max_energy_bin] * cutoff) { + if (freq_bins[b] < freq_bins[max_energy_bin] * cutoff) { // we assume that the 3dB point is in the middle of the final shoulder bin noise_width_hz += (max_energy_bin - b - 0.5f); peak_bottom = b; @@ -138,7 +172,7 @@ float DSP::find_noise_width(FFTWindowState* fft, uint16_t start_bin, uint16_t en } } } - noise_width_hz *= fft->_bin_resolution; + noise_width_hz *= bin_resolution; return noise_width_hz; } @@ -153,10 +187,38 @@ uint16_t DSP::step_calc_frequencies(FFTWindowState* fft, uint16_t start_bin, uin return fft->_peak_data[CENTER]._bin; } +void DSP::update_average_from_sliding_window(FFTWindowState* fft) +{ +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#define ASSERT_MAX(v) assert((v)<(fft->_num_stored_freqs * fft->_sliding_window_size)) +#else +#define ASSERT_MAX(v) +#endif + + // copy and scale the new slice + const uint16_t slice_index = fft->_current_slice * fft->_num_stored_freqs; + ASSERT_MAX(slice_index); + float* slice = &fft->_sliding_window[slice_index]; + + const uint16_t old_slice_index = ((fft->_current_slice + 1) % fft->_sliding_window_size) * fft->_num_stored_freqs; + ASSERT_MAX(old_slice_index); + float* old_slice = &fft->_sliding_window[old_slice_index]; + + const float inv_ssize = 1.0f / fft->_sliding_window_size; + + for (uint16_t i = 0; i < fft->_bin_count; i++) { + slice[i] = fft->_freq_bins[i] * fft->_window_scale * inv_ssize; + fft->_avg_freq_bins[i] = fft->_avg_freq_bins[i] + slice[i] - old_slice[i]; + } + + // advance the current slice + fft->_current_slice = (fft->_current_slice + 1) % fft->_sliding_window_size; +} + // calculate a single frequency uint16_t DSP::calc_frequency(FFTWindowState* fft, uint16_t start_bin, uint16_t peak_bin, uint16_t end_bin) { - if (peak_bin == 0 || is_zero(fft->_freq_bins[peak_bin])) { + if (peak_bin == 0 || is_zero(fft->get_freq_bin(peak_bin))) { return start_bin * fft->_bin_resolution; } @@ -165,7 +227,11 @@ uint16_t DSP::calc_frequency(FFTWindowState* fft, uint16_t start_bin, uint16_t p // It turns out that Jain is pretty good and works with only magnitudes, but Candan is significantly better // if you have access to the complex values and Quinn is a little better still. Quinn is computationally // more expensive, but compared to the overall FFT cost seems worth it. - return (peak_bin + calculate_quinns_second_estimator(fft, fft->_rfft_data, peak_bin)) * fft->_bin_resolution; + if (fft->_sliding_window != nullptr) { + return (peak_bin + calculate_jains_estimator(fft, fft->_avg_freq_bins, peak_bin)) * fft->_bin_resolution; + } else { + return (peak_bin + calculate_quinns_second_estimator(fft, fft->_rfft_data, peak_bin)) * fft->_bin_resolution; + } } // Interpolate center frequency using https://dspguru.com/dsp/howtos/how-to-interpolate-fft-peak/ @@ -209,6 +275,102 @@ float DSP::tau(const float x) const return (0.25f * p1 - TAU_FACTOR * p2); } +// from https://dspguru.com/dsp/howtos/how-to-interpolate-fft-peak/ +// Works on magnitudes only, which is useful when using averaged data +float DSP::calculate_jains_estimator(const FFTWindowState* fft, const float* real_fft, uint16_t k_max) +{ + if (k_max <= 1 || k_max >= fft->_bin_count) { + return 0.0f; + } + + float y1 = real_fft[k_max-1]; + float y2 = real_fft[k_max]; + float y3 = real_fft[k_max+1]; + float d = 0.0f; + + if (y1 > y3) { + float a = y2 / y1; + d = a / (1 + a) - 1; + } else { + float a = y3 / y2; + d = a / (1 + a); + } + return constrain_float(d, -0.5f, 0.5f); +} + +// initialize averaging FFT windows as they are calculated +bool DSP::fft_init_average(FFTWindowState* fft) +{ + if (fft->_avg_freq_bins == nullptr) { + fft->_avg_freq_bins = (float*)hal.util->malloc_type(sizeof(float) * fft->_num_stored_freqs, DSP_MEM_REGION); + if (fft->_avg_freq_bins == nullptr) { + return false; + } + } + + return true; +} + +// start averaging FFT windows as they are calculated +bool DSP::fft_start_average(FFTWindowState* fft) +{ + if (fft->_averaging) { + return false; + } + + if (!fft_init_average(fft)) { + return false; + } + + fft->_averaging_samples = 0; + fft->_averaging = true; + return true; +} + +// start averaging FFT windows as they are calculated +uint16_t DSP::fft_stop_average(FFTWindowState* fft, uint16_t start_bin, uint16_t end_bin, float* freqs) +{ + // ensure the window has been allocated even if we do nothing else + if (!fft_init_average(fft)) { + return 0; + } + + if (!fft->_averaging) { + return 0; + } + + fft->_averaging = false; + + // scale by the number of samples + vector_scale_float(fft->_avg_freq_bins, fft->_averaging_samples, fft->_avg_freq_bins, fft->_bin_count); + + const uint16_t smoothwidth = 1; + uint16_t bin_range = (MIN(end_bin + ((smoothwidth + 1) >> 1) + 2, fft->_bin_count) - start_bin) + 1; + + // find the three highest peaks using a zero crossing algorithm + // allocate the scratch space locally as we are in a different thread to the regular FFT + float* scratch_space = (float*)hal.util->malloc_type(sizeof(float) * fft->_num_stored_freqs, DSP_MEM_REGION); + if (scratch_space == nullptr) { + return false; + } + uint16_t peaks[MAX_TRACKED_PEAKS] {}; + uint16_t numpeaks = find_peaks(&fft->_avg_freq_bins[start_bin], bin_range, + scratch_space, peaks, MAX_TRACKED_PEAKS, 0.0f, -1.0f, smoothwidth, 2); + hal.util->free_type(scratch_space, sizeof(float) * fft->_num_stored_freqs, DSP_MEM_REGION); + + numpeaks = MIN(numpeaks, uint16_t(MAX_TRACKED_PEAKS)); + + // now try and find the lowest harmonic + for (uint16_t i = 0; i < numpeaks; i++) { + const uint16_t bin = peaks[i] + start_bin; + float d = calculate_jains_estimator(fft, fft->_avg_freq_bins, bin); + freqs[i] = (bin + d) * fft->_bin_resolution; + } + + fft->_averaging_samples = 0; + return numpeaks; +} + // find all the peaks in the fft window using https://terpconnect.umd.edu/~toh/spectrum/PeakFindingandMeasurement.htm // in general peakgrup > 2 is only good for very broad noisy peaks, <= 2 better for spikey peaks, although 1 will miss // a true spike 50% of the time diff --git a/libraries/AP_HAL/DSP.h b/libraries/AP_HAL/DSP.h index 92310e88366..88d306c4119 100644 --- a/libraries/AP_HAL/DSP.h +++ b/libraries/AP_HAL/DSP.h @@ -47,52 +47,80 @@ class AP_HAL::DSP { float _noise_width_hz; }; + static const uint8_t MAX_SLIDING_WINDOW_SIZE = 8; + class FFTWindowState { public: // frequency width of a FFT bin const float _bin_resolution; // number of FFT bins const uint16_t _bin_count; + // number of stored frequencies (_bin_count + DC) + const uint16_t _num_stored_freqs; // size of the FFT window const uint16_t _window_size; + // size of the FFT sliding window + const uint8_t _sliding_window_size; // FFT data float* _freq_bins; // derivative real data scratch space float* _derivative_freq_bins; // intermediate real FFT data float* _rfft_data; + // averaged frequency data via Welch's method + float* _avg_freq_bins; + // sliding window of _bin_count frames + float* _sliding_window; // three highest peaks FrequencyPeakData _peak_data[MAX_TRACKED_PEAKS]; // Hanning window for incoming samples, see https://en.wikipedia.org/wiki/Window_function#Hann_.28Hanning.29_window float* _hanning_window; // Use in calculating the PS of the signal [Heinz] equations (20) & (21) float _window_scale; + // averaging is ongoing + bool _averaging; + // number of samples in the average + uint32_t _averaging_samples; + // current sliding window slice + uint8_t _current_slice; + // get a frequency bin from an arbitrary slice + float get_freq_bin(uint16_t idx) { return _sliding_window == nullptr ? _freq_bins[idx] : _avg_freq_bins[idx]; } + void free_data_structures(); virtual ~FFTWindowState(); - FFTWindowState(uint16_t window_size, uint16_t sample_rate); + FFTWindowState(uint16_t window_size, uint16_t sample_rate, uint8_t sliding_window_size); }; // initialise an FFT instance - virtual FFTWindowState* fft_init(uint16_t window_size, uint16_t sample_rate) = 0; + virtual FFTWindowState* fft_init(uint16_t window_size, uint16_t sample_rate, uint8_t sliding_window_size = 0) = 0; // start an FFT analysis with an ObjectBuffer virtual void fft_start(FFTWindowState* state, FloatBuffer& samples, uint16_t advance) = 0; // perform remaining steps of an FFT analysis virtual uint16_t fft_analyse(FFTWindowState* state, uint16_t start_bin, uint16_t end_bin, float noise_att_cutoff) = 0; + // start averaging FFT data + bool fft_start_average(FFTWindowState* fft); + // finish the averaging process + uint16_t fft_stop_average(FFTWindowState* fft, uint16_t start_bin, uint16_t end_bin, float* peaks); protected: // step 3: find the magnitudes of the complex data void step_cmplx_mag(FFTWindowState* fft, uint16_t start_bin, uint16_t end_bin, float noise_att_cutoff); // calculate the noise width of a peak based on the input parameters - float find_noise_width(FFTWindowState* fft, uint16_t start_bin, uint16_t end_bin, uint16_t max_energy_bin, float cutoff, uint16_t& peak_top, uint16_t& peak_bottom) const; + float find_noise_width(float* freq_bins, uint16_t start_bin, uint16_t end_bin, uint16_t max_energy_bin, float cutoff, + float bin_resolution, uint16_t& peak_top, uint16_t& peak_bottom) const; // step 4: find the bin with the highest energy and interpolate the required frequency uint16_t step_calc_frequencies(FFTWindowState* fft, uint16_t start_bin, uint16_t end_bin); + // calculate the final average output + void update_average_from_sliding_window(FFTWindowState* fft); // calculate a single frequency uint16_t calc_frequency(FFTWindowState* fft, uint16_t start_bin, uint16_t peak_bin, uint16_t end_bin); // find the maximum value in an vector of floats virtual void vector_max_float(const float* vin, uint16_t len, float* max_value, uint16_t* max_index) const = 0; // find the mean value in an vector of floats virtual float vector_mean_float(const float* vin, uint16_t len) const = 0; - // multiple an vector of floats by a scale factor + // multiply an vector of floats by a scale factor virtual void vector_scale_float(const float* vin, float scale, float* vout, uint16_t len) const = 0; + // add two vectors together + virtual void vector_add_float(const float* vin1, const float* vin2, float* vout, uint16_t len) const = 0; // algorithm for finding peaks in noisy data as per https://terpconnect.umd.edu/~toh/spectrum/PeakFindingandMeasurement.htm uint16_t find_peaks(const float* input, uint16_t length, float* output, uint16_t* peaks, uint16_t peaklen, float slopeThreshold, float ampThreshold, uint16_t smoothwidth, uint16_t peakgroup) const; @@ -100,8 +128,13 @@ class AP_HAL::DSP { void derivative(const float* input, float* output, uint16_t n) const; void fastsmooth(float* input, uint16_t n, uint16_t smoothwidth) const; - // quinn's frequency interpolator + // Quinn's frequency interpolator float calculate_quinns_second_estimator(const FFTWindowState* fft, const float* complex_fft, uint16_t k) const; float tau(const float x) const; + // Jain's estimator + float calculate_jains_estimator(const FFTWindowState* fft, const float* real_fft, uint16_t k_max); + // init averaging FFT data + bool fft_init_average(FFTWindowState* fft); + #endif // HAL_WITH_DSP }; diff --git a/libraries/AP_HAL/Device.cpp b/libraries/AP_HAL/Device.cpp index 740562eab6a..beedb242212 100644 --- a/libraries/AP_HAL/Device.cpp +++ b/libraries/AP_HAL/Device.cpp @@ -54,6 +54,26 @@ bool AP_HAL::Device::setup_checked_registers(uint8_t nregs, uint8_t frequency) return true; } +void AP_HAL::Device::set_device_type(uint8_t devtype) { + _bus_id.devid_s.devtype = devtype; +} + + +bool AP_HAL::Device::read_bank_registers(uint8_t bank, uint8_t first_reg, uint8_t *recv, uint32_t recv_len) +{ + first_reg |= _read_flag; + return transfer_bank(bank, &first_reg, 1, recv, recv_len); +} + +bool AP_HAL::Device::write_bank_register(uint8_t bank, uint8_t reg, uint8_t val, bool checked) +{ + uint8_t buf[2] = { reg, val }; + if (checked) { + set_checked_register(bank, reg, val); + } + return transfer_bank(bank, buf, sizeof(buf), nullptr, 0); +} + /* set value of one checked register */ @@ -143,3 +163,111 @@ bool AP_HAL::Device::check_next_register(struct checkreg &fail) fail = _checked.last_reg_fail; return false; } + + +bool AP_HAL::Device::write_register(uint8_t reg, uint8_t val, bool checked) +{ + uint8_t buf[2] = { reg, val }; + if (checked) { + set_checked_register(reg, val); + } + bool result = transfer(buf, sizeof(buf), nullptr, 0); + if (_register_rw_callback && result) { + _register_rw_callback(reg, &val, 1, true); + } + return result; +} + + +bool AP_HAL::Device::read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len) +{ + uint8_t read_reg = first_reg; + first_reg |= _read_flag; + bool result = transfer(&first_reg, 1, recv, recv_len); + if (_register_rw_callback != nullptr && result) { + _register_rw_callback(read_reg, recv, recv_len, false); + } + return result; +} + +bool AP_HAL::Device::transfer_bank(uint8_t bank, const uint8_t *send, uint32_t send_len, + uint8_t *recv, uint32_t recv_len) +{ + if (_bank_select) { + if (!_bank_select(bank)) { + return false; + } + } + return transfer(send, send_len, recv, recv_len); +} + + +/** + * Some devices connected on the I2C or SPI bus require a bit to be set on + * the register address in order to perform a read operation. This sets a + * flag to be used by #read_registers(). The flag's default value is zero. + */ +void AP_HAL::Device::set_read_flag(uint8_t flag) +{ + _read_flag = flag; +} + + +/** + * make a bus id given bus type, bus number, bus address and + * device type This is for use by devices that do not use one of + * the standard HAL Device types, such as UAVCAN devices + */ +uint32_t AP_HAL::Device::make_bus_id(enum BusType bus_type, uint8_t bus, uint8_t address, uint8_t devtype) { + union DeviceId d {}; + d.devid_s.bus_type = bus_type; + d.devid_s.bus = bus; + d.devid_s.address = address; + d.devid_s.devtype = devtype; + return d.devid; +} + +/** + * return a new bus ID for the same bus connection but a new device type. + * This is used for auxiliary bus connections + */ +uint32_t AP_HAL::Device::change_bus_id(uint32_t old_id, uint8_t devtype) { + union DeviceId d; + d.devid = old_id; + d.devid_s.devtype = devtype; + return d.devid; +} + +/** + * return bus ID with a new devtype + */ +uint32_t AP_HAL::Device::get_bus_id_devtype(uint8_t devtype) const { + return change_bus_id(get_bus_id(), devtype); +} + +/** + * get bus type + */ +enum AP_HAL::Device::BusType AP_HAL::Device::devid_get_bus_type(uint32_t dev_id) { + union DeviceId d; + d.devid = dev_id; + return d.devid_s.bus_type; +} + +uint8_t AP_HAL::Device::devid_get_bus(uint32_t dev_id) { + union DeviceId d; + d.devid = dev_id; + return d.devid_s.bus; +} + +uint8_t AP_HAL::Device::devid_get_address(uint32_t dev_id) { + union DeviceId d; + d.devid = dev_id; + return d.devid_s.address; +} + +uint8_t AP_HAL::Device::devid_get_devtype(uint32_t dev_id) { + union DeviceId d; + d.devid = dev_id; + return d.devid_s.devtype; +} diff --git a/libraries/AP_HAL/Device.h b/libraries/AP_HAL/Device.h index 1282ba69915..2568501ab76 100644 --- a/libraries/AP_HAL/Device.h +++ b/libraries/AP_HAL/Device.h @@ -55,6 +55,11 @@ class AP_HAL::Device { FUNCTOR_TYPEDEF(PeriodicCb, void); typedef void* PeriodicHandle; + // Register Read Write Callback + // returns: void parameters: register address, register data, register datasize, direction R:false, W:true + FUNCTOR_TYPEDEF(RegisterRWCb, void, uint8_t, uint8_t*, uint32_t, bool); + typedef void* RegisterRWHandle; + FUNCTOR_TYPEDEF(BankSelectCb, bool, uint8_t); Device(enum BusType type) @@ -83,10 +88,7 @@ class AP_HAL::Device { } // set device type within a device class (eg. AP_COMPASS_TYPE_LSM303D) - void set_device_type(uint8_t devtype) { - _bus_id.devid_s.devtype = devtype; - } - + void set_device_type(uint8_t devtype); virtual ~Device() { delete[] _checked.regs; @@ -139,11 +141,7 @@ class AP_HAL::Device { * * Return: true on a successful transfer, false on failure. */ - bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len) - { - first_reg |= _read_flag; - return transfer(&first_reg, 1, recv, recv_len); - } + bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len); /** * Wrapper function over #transfer() to write a byte to the register reg. @@ -151,13 +149,13 @@ class AP_HAL::Device { * * Return: true on a successful transfer, false on failure. */ - bool write_register(uint8_t reg, uint8_t val, bool checked=false) - { - uint8_t buf[2] = { reg, val }; - if (checked) { - set_checked_register(reg, val); - } - return transfer(buf, sizeof(buf), nullptr, 0); + bool write_register(uint8_t reg, uint8_t val, bool checked=false); + + /* + * Sets a callback to be called when a register is read or written. + */ + virtual void set_register_rw_callback(RegisterRWCb register_rw_callback) { + _register_rw_callback = register_rw_callback; } /** @@ -167,14 +165,7 @@ class AP_HAL::Device { * Return: true on a successful transfer, false on failure. */ bool transfer_bank(uint8_t bank, const uint8_t *send, uint32_t send_len, - uint8_t *recv, uint32_t recv_len) { - if (_bank_select) { - if (!_bank_select(bank)) { - return false; - } - } - return transfer(send, send_len, recv, recv_len); - } + uint8_t *recv, uint32_t recv_len); /** * Wrapper function over #transfer_bank() to read recv_len registers, starting @@ -184,11 +175,7 @@ class AP_HAL::Device { * * Return: true on a successful transfer, false on failure. */ - bool read_bank_registers(uint8_t bank, uint8_t first_reg, uint8_t *recv, uint32_t recv_len) - { - first_reg |= _read_flag; - return transfer_bank(bank, &first_reg, 1, recv, recv_len); - } + bool read_bank_registers(uint8_t bank, uint8_t first_reg, uint8_t *recv, uint32_t recv_len); /** * Wrapper function over #transfer_bank() to write a byte to the register reg. @@ -196,14 +183,7 @@ class AP_HAL::Device { * * Return: true on a successful transfer, false on failure. */ - bool write_bank_register(uint8_t bank, uint8_t reg, uint8_t val, bool checked=false) - { - uint8_t buf[2] = { reg, val }; - if (checked) { - set_checked_register(bank, reg, val); - } - return transfer_bank(bank, buf, sizeof(buf), nullptr, 0); - } + bool write_bank_register(uint8_t bank, uint8_t reg, uint8_t val, bool checked=false); /** * set a value for a checked register in a bank @@ -325,70 +305,36 @@ class AP_HAL::Device { * the register address in order to perform a read operation. This sets a * flag to be used by #read_registers(). The flag's default value is zero. */ - void set_read_flag(uint8_t flag) - { - _read_flag = flag; - } - + void set_read_flag(uint8_t flag); /** * make a bus id given bus type, bus number, bus address and * device type This is for use by devices that do not use one of * the standard HAL Device types, such as UAVCAN devices */ - static uint32_t make_bus_id(enum BusType bus_type, uint8_t bus, uint8_t address, uint8_t devtype) { - union DeviceId d {}; - d.devid_s.bus_type = bus_type; - d.devid_s.bus = bus; - d.devid_s.address = address; - d.devid_s.devtype = devtype; - return d.devid; - } + static uint32_t make_bus_id(enum BusType bus_type, uint8_t bus, uint8_t address, uint8_t devtype); /** * return a new bus ID for the same bus connection but a new device type. - * This is used for auxillary bus connections + * This is used for auxiliary bus connections */ - static uint32_t change_bus_id(uint32_t old_id, uint8_t devtype) { - union DeviceId d; - d.devid = old_id; - d.devid_s.devtype = devtype; - return d.devid; - } + static uint32_t change_bus_id(uint32_t old_id, uint8_t devtype); /** * return bus ID with a new devtype */ - uint32_t get_bus_id_devtype(uint8_t devtype) const { - return change_bus_id(get_bus_id(), devtype); - } + uint32_t get_bus_id_devtype(uint8_t devtype) const; /** * get bus type */ - static enum BusType devid_get_bus_type(uint32_t dev_id) { - union DeviceId d; - d.devid = dev_id; - return d.devid_s.bus_type; - } + static enum BusType devid_get_bus_type(uint32_t dev_id); - static uint8_t devid_get_bus(uint32_t dev_id) { - union DeviceId d; - d.devid = dev_id; - return d.devid_s.bus; - } + static uint8_t devid_get_bus(uint32_t dev_id); - static uint8_t devid_get_address(uint32_t dev_id) { - union DeviceId d; - d.devid = dev_id; - return d.devid_s.address; - } + static uint8_t devid_get_address(uint32_t dev_id); - static uint8_t devid_get_devtype(uint32_t dev_id) { - union DeviceId d; - d.devid = dev_id; - return d.devid_s.devtype; - } + static uint8_t devid_get_devtype(uint32_t dev_id); /* set number of retries on transfers */ @@ -429,7 +375,7 @@ class AP_HAL::Device { private: BankSelectCb _bank_select; - + RegisterRWCb _register_rw_callback; struct { uint8_t n_allocated; uint8_t n_set; diff --git a/libraries/AP_HAL/GPIO.h b/libraries/AP_HAL/GPIO.h index 8298aaac4f7..5bbd4468488 100644 --- a/libraries/AP_HAL/GPIO.h +++ b/libraries/AP_HAL/GPIO.h @@ -55,6 +55,10 @@ class AP_HAL::GPIO { virtual void toggle(uint8_t pin) = 0; virtual bool valid_pin(uint8_t pin) const { return true; } + // return servo channel associated with GPIO pin. Returns true on success and fills in servo_ch argument + // servo_ch uses zero-based indexing + virtual bool pin_to_servo_channel(uint8_t pin, uint8_t& servo_ch) const { return false; } + // allow for save and restore of pin settings virtual bool get_mode(uint8_t pin, uint32_t &mode) { return false; } virtual void set_mode(uint8_t pin, uint32_t mode) {} diff --git a/libraries/AP_HAL/HAL.h b/libraries/AP_HAL/HAL.h index ae9a0861b7d..d2a6815c1ba 100644 --- a/libraries/AP_HAL/HAL.h +++ b/libraries/AP_HAL/HAL.h @@ -43,6 +43,9 @@ class AP_HAL::HAL { AP_HAL::Util* _util, AP_HAL::OpticalFlow*_opticalflow, AP_HAL::Flash* _flash, +#if AP_SIM_ENABLED && CONFIG_HAL_BOARD != HAL_BOARD_SITL + class AP_HAL::SIMState* _simstate, +#endif AP_HAL::DSP* _dsp, #if HAL_NUM_CAN_IFACES > 0 AP_HAL::CANIface* _can_ifaces[HAL_NUM_CAN_IFACES]) @@ -73,6 +76,9 @@ class AP_HAL::HAL { util(_util), opticalflow(_opticalflow), flash(_flash), +#if AP_SIM_ENABLED && CONFIG_HAL_BOARD != HAL_BOARD_SITL + simstate(_simstate), +#endif dsp(_dsp) { #if HAL_NUM_CAN_IFACES > 0 @@ -109,15 +115,15 @@ class AP_HAL::HAL { private: // the uartX ports must be contiguous in ram for the serial() method to work AP_HAL::UARTDriver* uartA; - AP_HAL::UARTDriver* uartB; - AP_HAL::UARTDriver* uartC; - AP_HAL::UARTDriver* uartD; - AP_HAL::UARTDriver* uartE; - AP_HAL::UARTDriver* uartF; - AP_HAL::UARTDriver* uartG; - AP_HAL::UARTDriver* uartH; - AP_HAL::UARTDriver* uartI; - AP_HAL::UARTDriver* uartJ; + AP_HAL::UARTDriver* uartB UNUSED_PRIVATE_MEMBER; + AP_HAL::UARTDriver* uartC UNUSED_PRIVATE_MEMBER; + AP_HAL::UARTDriver* uartD UNUSED_PRIVATE_MEMBER; + AP_HAL::UARTDriver* uartE UNUSED_PRIVATE_MEMBER; + AP_HAL::UARTDriver* uartF UNUSED_PRIVATE_MEMBER; + AP_HAL::UARTDriver* uartG UNUSED_PRIVATE_MEMBER; + AP_HAL::UARTDriver* uartH UNUSED_PRIVATE_MEMBER; + AP_HAL::UARTDriver* uartI UNUSED_PRIVATE_MEMBER; + AP_HAL::UARTDriver* uartJ UNUSED_PRIVATE_MEMBER; public: AP_HAL::I2CDeviceManager* i2c_mgr; @@ -144,4 +150,15 @@ class AP_HAL::HAL { UARTDriver* serial(uint8_t sernum) const; static constexpr uint8_t num_serial = 10; + +#if AP_SIM_ENABLED && CONFIG_HAL_BOARD != HAL_BOARD_SITL + AP_HAL::SIMState *simstate; +#endif + +#ifndef HAL_CONSOLE_DISABLED +# define DEV_PRINTF(fmt, args ...) do { hal.console->printf(fmt, ## args); } while(0) +#else +# define DEV_PRINTF(fmt, args ...) +#endif + }; diff --git a/libraries/AP_HAL/RCOutput.cpp b/libraries/AP_HAL/RCOutput.cpp index 0b36cf1a2c7..b37cfb28e98 100644 --- a/libraries/AP_HAL/RCOutput.cpp +++ b/libraries/AP_HAL/RCOutput.cpp @@ -2,6 +2,10 @@ extern const AP_HAL::HAL &hal; +uint32_t AP_HAL::RCOutput::DSHOT_BIT_WIDTH_TICKS = DSHOT_BIT_WIDTH_TICKS_DEFAULT; +uint32_t AP_HAL::RCOutput::DSHOT_BIT_0_TICKS = DSHOT_BIT_0_TICKS_DEFAULT; +uint32_t AP_HAL::RCOutput::DSHOT_BIT_1_TICKS = DSHOT_BIT_1_TICKS_DEFAULT; + // helper function for implementation of get_output_mode_banner const char* AP_HAL::RCOutput::get_output_mode_string(enum output_mode out_mode) const { @@ -86,15 +90,23 @@ uint32_t AP_HAL::RCOutput::calculate_bitrate_prescaler(uint32_t timer_clock, uin } } - // find the closest value const uint32_t freq = timer_clock / prescaler; - const float delta = fabsf(float(freq) - target_frequency); - if (freq > target_frequency - && delta > fabsf(float(timer_clock / (prescaler+1)) - target_frequency)) { - prescaler++; - } else if (freq < target_frequency - && delta > fabsf(float(timer_clock / (prescaler-1)) - target_frequency)) { - prescaler--; + // if using dshot then always pick the high value. choosing low seems to not agree with some + // ESCs despite the fact that BLHeli32 is supposed not to care what the bitrate is + if (is_dshot) { + if (freq < target_frequency) { + prescaler--; + } + } else { + // find the closest value + const float delta = fabsf(float(freq) - target_frequency); + if (freq > target_frequency + && delta > fabsf(float(timer_clock / (prescaler+1)) - target_frequency)) { + prescaler++; + } else if (freq < target_frequency + && delta > fabsf(float(timer_clock / (prescaler-1)) - target_frequency)) { + prescaler--; + } } return prescaler; diff --git a/libraries/AP_HAL/RCOutput.h b/libraries/AP_HAL/RCOutput.h index 8e90bd670d3..d0875d23c21 100644 --- a/libraries/AP_HAL/RCOutput.h +++ b/libraries/AP_HAL/RCOutput.h @@ -26,6 +26,20 @@ #define CH_16 15 #define CH_17 16 #define CH_18 17 +#define CH_19 18 +#define CH_20 19 +#define CH_21 20 +#define CH_22 21 +#define CH_23 22 +#define CH_24 23 +#define CH_25 24 +#define CH_26 25 +#define CH_27 26 +#define CH_28 27 +#define CH_29 28 +#define CH_30 29 +#define CH_31 30 +#define CH_32 31 #define CH_NONE 255 #endif @@ -57,15 +71,15 @@ class AP_HAL::RCOutput { * so that output scaling can be performed correctly. The chanmask passed is added (ORed) into any existing mask. * The mask uses servo channel numbering */ - virtual void set_reversible_mask(uint16_t chanmask) {} + virtual void set_reversible_mask(uint32_t chanmask) {} /* * mark the channels in chanmask as reversed. * The chanmask passed is added (ORed) into any existing mask. * The mask uses servo channel numbering */ - virtual void set_reversed_mask(uint16_t chanmask) {} - virtual uint16_t get_reversed_mask() { return 0; } + virtual void set_reversed_mask(uint32_t chanmask) {} + virtual uint32_t get_reversed_mask() { return 0; } /* * Update channel masks at 1Hz allowing for actions such as dshot commands to be sent @@ -165,7 +179,7 @@ class AP_HAL::RCOutput { as those in the same channel timer groups) may also be stopped, depending on the implementation */ - virtual bool serial_setup_output(uint8_t chan, uint32_t baudrate, uint16_t chanmask) { return false; } + virtual bool serial_setup_output(uint8_t chan, uint32_t baudrate, uint32_t chanmask) { return false; } /* write a set of bytes to an ESC, using settings from @@ -209,7 +223,8 @@ class AP_HAL::RCOutput { static bool is_dshot_protocol(const enum output_mode mode); - // https://github.com/bitdump/BLHeli/blob/master/BLHeli_32%20ARM/BLHeli_32%20Firmware%20specs/Digital_Cmd_Spec.txt + // BLHeli32: https://github.com/bitdump/BLHeli/blob/master/BLHeli_32%20ARM/BLHeli_32%20Firmware%20specs/Digital_Cmd_Spec.txt + // BLHeli_S: https://github.com/bitdump/BLHeli/blob/master/BLHeli_S%20SiLabs/Dshotprog%20spec%20BLHeli_S.txt enum BLHeliDshotCommand : uint8_t { DSHOT_RESET = 0, DSHOT_BEEP1 = 1, @@ -225,6 +240,7 @@ class AP_HAL::RCOutput { DSHOT_SAVE = 12, DSHOT_NORMAL = 20, DSHOT_REVERSE = 21, + // The following options are only available on BLHeli32 DSHOT_LED0_ON = 22, DSHOT_LED1_ON = 23, DSHOT_LED2_ON = 24, @@ -239,16 +255,22 @@ class AP_HAL::RCOutput { enum DshotEscType { DSHOT_ESC_NONE = 0, - DSHOT_ESC_BLHELI = 1 + DSHOT_ESC_BLHELI = 1, + DSHOT_ESC_BLHELI_S = 2 }; - virtual void set_output_mode(uint16_t mask, enum output_mode mode) {} + virtual void set_output_mode(uint32_t mask, enum output_mode mode) {} /* * get output mode banner to inform user of how outputs are configured */ virtual bool get_output_mode_banner(char banner_msg[], uint8_t banner_msg_len) const { return false; } + /* + * return mask of channels that must be disabled because they share a group with a digital channel + */ + virtual uint32_t get_disabled_channels(uint32_t digital_mask) { return 0; } + /* set default update rate */ @@ -258,18 +280,18 @@ class AP_HAL::RCOutput { enable telemetry request for a mask of channels. This is used with DShot to get telemetry feedback */ - virtual void set_telem_request_mask(uint16_t mask) {} + virtual void set_telem_request_mask(uint32_t mask) {} /* enable bi-directional telemetry request for a mask of channels. This is used with DShot to get telemetry feedback */ - virtual void set_bidir_dshot_mask(uint16_t mask) {} + virtual void set_bidir_dshot_mask(uint32_t mask) {} /* mark escs as active for the purpose of sending dshot commands */ - virtual void set_active_escs_mask(uint16_t mask) {} + virtual void set_active_escs_mask(uint32_t mask) {} /* Set the dshot rate as a multiple of the loop rate @@ -299,7 +321,7 @@ class AP_HAL::RCOutput { setup serial led output for a given channel number, with the given max number of LEDs in the chain. */ - virtual bool set_serial_led_num_LEDs(const uint16_t chan, uint8_t num_leds, output_mode mode = MODE_PWM_NONE, uint16_t clock_mask = 0) { return false; } + virtual bool set_serial_led_num_LEDs(const uint16_t chan, uint8_t num_leds, output_mode mode = MODE_PWM_NONE, uint32_t clock_mask = 0) { return false; } /* setup serial led output data for a given output channel @@ -314,11 +336,52 @@ class AP_HAL::RCOutput { virtual void timer_info(ExpandingString &str) {} + /* + Can this driver handle gpio as well as RC + */ + virtual bool supports_gpio() { return false; }; + + /* + Writes gpio state to a channel + */ + virtual void write_gpio(uint8_t chan, bool active) {}; + /* * calculate the prescaler required to achieve the desire bitrate */ static uint32_t calculate_bitrate_prescaler(uint32_t timer_clock, uint32_t target_frequency, bool is_dshot); + /* + * bit width values for different protocols + */ + /* + * It seems ESCs are quite sensitive to the DSHOT duty cycle. + * Options are (ticks, percentage): + * 20/7/14, 35/70 + * 11/4/8, 36/72 + * 8/3/6, 37/75 + */ + // bitwidths: 8/3/6 == 37%/75% + static constexpr uint32_t DSHOT_BIT_WIDTH_TICKS_DEFAULT = 8; + static constexpr uint32_t DSHOT_BIT_0_TICKS_DEFAULT = 3; + static constexpr uint32_t DSHOT_BIT_1_TICKS_DEFAULT = 6; + // bitwidths: 11/4/8 == 36%/72% + static constexpr uint32_t DSHOT_BIT_WIDTH_TICKS_S = 11; + static constexpr uint32_t DSHOT_BIT_0_TICKS_S = 4; + static constexpr uint32_t DSHOT_BIT_1_TICKS_S = 8; + + static uint32_t DSHOT_BIT_WIDTH_TICKS; + static uint32_t DSHOT_BIT_0_TICKS; + static uint32_t DSHOT_BIT_1_TICKS; + + // See WS2812B spec for expected pulse widths + static constexpr uint32_t NEOP_BIT_WIDTH_TICKS = 20; + static constexpr uint32_t NEOP_BIT_0_TICKS = 7; + static constexpr uint32_t NEOP_BIT_1_TICKS = 14; + // neopixel does not use pulse widths at all + static constexpr uint32_t PROFI_BIT_0_TICKS = 7; + static constexpr uint32_t PROFI_BIT_1_TICKS = 14; + protected: // helper functions for implementation of get_output_mode_banner diff --git a/libraries/AP_HAL/SIMState.cpp b/libraries/AP_HAL/SIMState.cpp new file mode 100644 index 00000000000..8dda977bde9 --- /dev/null +++ b/libraries/AP_HAL/SIMState.cpp @@ -0,0 +1,364 @@ +#include "SIMState.h" + +#if AP_SIM_ENABLED && CONFIG_HAL_BOARD != HAL_BOARD_SITL + +/* + * This is a very-much-cut-down AP_HAL_SITL object. We should make + * PA_HAL_SITL use this object - by moving a lot more code from over + * there into here. + */ + +#include +#include + +#include + +extern const AP_HAL::HAL& hal; + +using namespace AP_HAL; + +#include + +void SIMState::update() +{ + static bool init_done; + if (!init_done) { + init_done = true; +#if APM_BUILD_TYPE(APM_BUILD_ArduCopter) + sitl_model = SITL::MultiCopter::create("+"); +#elif APM_BUILD_TYPE(APM_BUILD_ArduPlane) + sitl_model = SITL::Plane::create("plane"); +#endif + } + + _fdm_input_step(); +} + +/* + setup for SITL handling + */ +void SIMState::_sitl_setup(const char *home_str) +{ + _home_str = home_str; + + printf("Starting SITL input\n"); + + // find the barometer object if it exists + _barometer = AP_Baro::get_singleton(); +} + + +/* + step the FDM by one time step + */ +void SIMState::_fdm_input_step(void) +{ + fdm_input_local(); +} + +/* + get FDM input from a local model + */ +void SIMState::fdm_input_local(void) +{ + struct sitl_input input; + + // construct servos structure for FDM + _simulator_servos(input); + + // read servo inputs from ride along flight controllers + // ride_along.receive(input); + + // update the model + sitl_model->update_model(input); + + // get FDM output from the model + if (_sitl == nullptr) { + _sitl = AP::sitl(); + } + if (_sitl) { + sitl_model->fill_fdm(_sitl->state); + + if (_sitl->rc_fail == SITL::SIM::SITL_RCFail_None) { + for (uint8_t i=0; i< _sitl->state.rcin_chan_count; i++) { + pwm_input[i] = 1000 + _sitl->state.rcin[i]*1000; + } + } + } + + // output JSON state to ride along flight controllers + // ride_along.send(_sitl->state,sitl_model->get_position_relhome()); + +#if HAL_SIM_GIMBAL_ENABLED + if (gimbal != nullptr) { + gimbal->update(); + } +#endif +#if HAL_SIM_ADSB_ENABLED + if (adsb != nullptr) { + adsb->update(); + } +#endif + if (vicon != nullptr) { + Quaternion attitude; + sitl_model->get_attitude(attitude); + vicon->update(sitl_model->get_location(), + sitl_model->get_position_relhome(), + sitl_model->get_velocity_ef(), + attitude); + } + if (benewake_tf02 != nullptr) { + benewake_tf02->update(sitl_model->rangefinder_range()); + } + if (benewake_tf03 != nullptr) { + benewake_tf03->update(sitl_model->rangefinder_range()); + } + if (benewake_tfmini != nullptr) { + benewake_tfmini->update(sitl_model->rangefinder_range()); + } + if (teraranger_serial != nullptr) { + teraranger_serial->update(sitl_model->rangefinder_range()); + } + if (lightwareserial != nullptr) { + lightwareserial->update(sitl_model->rangefinder_range()); + } + if (lightwareserial_binary != nullptr) { + lightwareserial_binary->update(sitl_model->rangefinder_range()); + } + if (lanbao != nullptr) { + lanbao->update(sitl_model->rangefinder_range()); + } + if (blping != nullptr) { + blping->update(sitl_model->rangefinder_range()); + } + if (leddarone != nullptr) { + leddarone->update(sitl_model->rangefinder_range()); + } + if (USD1_v0 != nullptr) { + USD1_v0->update(sitl_model->rangefinder_range()); + } + if (USD1_v1 != nullptr) { + USD1_v1->update(sitl_model->rangefinder_range()); + } + if (maxsonarseriallv != nullptr) { + maxsonarseriallv->update(sitl_model->rangefinder_range()); + } + if (wasp != nullptr) { + wasp->update(sitl_model->rangefinder_range()); + } + if (nmea != nullptr) { + nmea->update(sitl_model->rangefinder_range()); + } + if (rf_mavlink != nullptr) { + rf_mavlink->update(sitl_model->rangefinder_range()); + } + if (gyus42v2 != nullptr) { + gyus42v2->update(sitl_model->rangefinder_range()); + } + if (efi_ms != nullptr) { + efi_ms->update(); + } + + if (frsky_d != nullptr) { + frsky_d->update(); + } + // if (frsky_sport != nullptr) { + // frsky_sport->update(); + // } + // if (frsky_sportpassthrough != nullptr) { + // frsky_sportpassthrough->update(); + // } + +#if AP_SIM_CRSF_ENABLED + if (crsf != nullptr) { + crsf->update(); + } +#endif + +#if HAL_SIM_PS_RPLIDARA2_ENABLED + if (rplidara2 != nullptr) { + rplidara2->update(sitl_model->get_location()); + } +#endif + +#if HAL_SIM_PS_TERARANGERTOWER_ENABLED + if (terarangertower != nullptr) { + terarangertower->update(sitl_model->get_location()); + } +#endif + +#if HAL_SIM_PS_LIGHTWARE_SF45B_ENABLED + if (sf45b != nullptr) { + sf45b->update(sitl_model->get_location()); + } +#endif + + if (vectornav != nullptr) { + vectornav->update(); + } + + if (lord != nullptr) { + lord->update(); + } + +#if HAL_SIM_AIS_ENABLED + if (ais != nullptr) { + ais->update(); + } +#endif + for (uint8_t i=0; iupdate(); + } + } + + // update simulation time + if (_sitl) { + hal.scheduler->stop_clock(_sitl->state.timestamp_us); + } else { + hal.scheduler->stop_clock(AP_HAL::micros64()+100); + } + + set_height_agl(); + + _synthetic_clock_mode = true; + _update_count++; +} + +/* + create sitl_input structure for sending to FDM + */ +void SIMState::_simulator_servos(struct sitl_input &input) +{ + // output at chosen framerate + uint32_t now = AP_HAL::micros(); + // last_update_usec = now; + + float altitude = _barometer?_barometer->get_altitude():0; + float wind_speed = 0; + float wind_direction = 0; + float wind_dir_z = 0; + + // give 5 seconds to calibrate airspeed sensor at 0 wind speed + if (wind_start_delay_micros == 0) { + wind_start_delay_micros = now; + } else if (_sitl && (now - wind_start_delay_micros) > 5000000 ) { + // The EKF does not like step inputs so this LPF keeps it happy. + wind_speed = _sitl->wind_speed_active = (0.95f*_sitl->wind_speed_active) + (0.05f*_sitl->wind_speed); + wind_direction = _sitl->wind_direction_active = (0.95f*_sitl->wind_direction_active) + (0.05f*_sitl->wind_direction); + wind_dir_z = _sitl->wind_dir_z_active = (0.95f*_sitl->wind_dir_z_active) + (0.05f*_sitl->wind_dir_z); + + // pass wind into simulators using different wind types via param SIM_WIND_T*. + switch (_sitl->wind_type) { + case SITL::SIM::WIND_TYPE_SQRT: + if (altitude < _sitl->wind_type_alt) { + wind_speed *= sqrtf(MAX(altitude / _sitl->wind_type_alt, 0)); + } + break; + + case SITL::SIM::WIND_TYPE_COEF: + wind_speed += (altitude - _sitl->wind_type_alt) * _sitl->wind_type_coef; + break; + + case SITL::SIM::WIND_TYPE_NO_LIMIT: + default: + break; + } + + // never allow negative wind velocity + wind_speed = MAX(wind_speed, 0); + } + + input.wind.speed = wind_speed; + input.wind.direction = wind_direction; + input.wind.turbulence = _sitl?_sitl->wind_turbulance:0; + input.wind.dir_z = wind_dir_z; + + for (uint8_t i=0; ifetteconewireesc_sim.enabled()) { + _sitl->fetteconewireesc_sim.update_sitl_input_pwm(input); + for (uint8_t i=0; istate.battery_voltage <= 0) { + } else { + // FDM provides voltage and current + voltage = _sitl->state.battery_voltage; + _current = _sitl->state.battery_current; + } + } + + // assume 3DR power brick + voltage_pin_value = ((voltage / 10.1f) / 5.0f) * 1024; + current_pin_value = ((_current / 17.0f) / 5.0f) * 1024; + // fake battery2 as just a 25% gain on the first one + voltage2_pin_value = ((voltage * 0.25f / 10.1f) / 5.0f) * 1024; + current2_pin_value = ((_current * 0.25f / 17.0f) / 5.0f) * 1024; +} + +/* + set height above the ground in meters + */ +void SIMState::set_height_agl(void) +{ + static float home_alt = -1; + + if (!_sitl) { + // in example program + return; + } + + if (is_equal(home_alt, -1.0f) && _sitl->state.altitude > 0) { + // remember home altitude as first non-zero altitude + home_alt = _sitl->state.altitude; + } + +#if AP_TERRAIN_AVAILABLE + if (_sitl != nullptr && + _sitl->terrain_enable) { + // get height above terrain from AP_Terrain. This assumes + // AP_Terrain is working + float terrain_height_amsl; + struct Location location; + location.lat = _sitl->state.latitude*1.0e7; + location.lng = _sitl->state.longitude*1.0e7; + + AP_Terrain *_terrain = AP_Terrain::get_singleton(); + if (_terrain != nullptr && + _terrain->height_amsl(location, terrain_height_amsl)) { + _sitl->height_agl = _sitl->state.altitude - terrain_height_amsl; + return; + } + } +#endif + + if (_sitl != nullptr) { + // fall back to flat earth model + _sitl->height_agl = _sitl->state.altitude - home_alt; + } +} + +#endif // AP_SIM_ENABLED && CONFIG_HAL_BOARD != HAL_BOARD_SITL diff --git a/libraries/AP_HAL/SIMState.h b/libraries/AP_HAL/SIMState.h new file mode 100644 index 00000000000..5275b8b4d3b --- /dev/null +++ b/libraries/AP_HAL/SIMState.h @@ -0,0 +1,222 @@ +#pragma once + +#include + +#if AP_SIM_ENABLED + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include +#include +#include + +#include + +class AP_HAL::SIMState { +public: + + // simulated airspeed, sonar and battery monitor + uint16_t sonar_pin_value; // pin 0 + uint16_t airspeed_pin_value[2]; // pin 1 + uint16_t voltage_pin_value; // pin 13 + uint16_t current_pin_value; // pin 12 + uint16_t voltage2_pin_value; // pin 15 + uint16_t current2_pin_value; // pin 14 + + void update(); + +#if HAL_SIM_GPS_ENABLED + void set_gps0(SITL::GPS *_gps) { gps[0] = _gps; } +#endif + + uint16_t pwm_output[32]; // was SITL_NUM_CHANNELS + +private: + void _set_param_default(const char *parm); + void _sitl_setup(const char *home_str); + void _setup_timer(void); + void _setup_adc(void); + + void set_height_agl(void); + void _set_signal_handlers(void) const; + + void _update_airspeed(float airspeed); + void _simulator_servos(struct sitl_input &input); + void _fdm_input_step(void); + void fdm_input_local(void); + + void wait_clock(uint64_t wait_time_usec); + + uint16_t pwm_input[16]; // was SITL_RC_INPUT_CHANNELS + + // internal state + // enum vehicle_type _vehicle; + uint8_t _instance; + uint16_t _base_port; + pid_t _parent_pid; + uint32_t _update_count; + + class AP_Baro *_barometer; + +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL + SocketAPM _sitl_rc_in{true}; +#endif + SITL::SIM *_sitl; + uint16_t _rcin_port; + uint16_t _fg_view_port; + uint16_t _irlock_port; + float _current; + + bool _synthetic_clock_mode; + + bool _use_rtscts; + bool _use_fg_view; + + const char *_fg_address; + + // internal SITL model + SITL::Aircraft *sitl_model; + +#if HAL_SIM_GIMBAL_ENABLED + // simulated gimbal + bool enable_gimbal; + SITL::Gimbal *gimbal; +#endif + +#if HAL_SIM_ADSB_ENABLED + // simulated ADSb + SITL::ADSB *adsb; +#endif + + // simulated vicon system: + SITL::Vicon *vicon; + + // simulated Benewake tf02 rangefinder: + SITL::RF_Benewake_TF02 *benewake_tf02; + // simulated Benewake tf03 rangefinder: + SITL::RF_Benewake_TF03 *benewake_tf03; + // simulated Benewake tfmini rangefinder: + SITL::RF_Benewake_TFmini *benewake_tfmini; + // simulated TeraRangerSerial rangefinder: + SITL::RF_TeraRanger_Serial *teraranger_serial; + + // simulated LightWareSerial rangefinder - legacy protocol:: + SITL::RF_LightWareSerial *lightwareserial; + // simulated LightWareSerial rangefinder - binary protocol: + SITL::RF_LightWareSerialBinary *lightwareserial_binary; + // simulated Lanbao rangefinder: + SITL::RF_Lanbao *lanbao; + // simulated BLping rangefinder: + SITL::RF_BLping *blping; + // simulated LeddarOne rangefinder: + SITL::RF_LeddarOne *leddarone; + // simulated USD1 v0 rangefinder: + SITL::RF_USD1_v0 *USD1_v0; + // simulated USD1 v1 rangefinder: + SITL::RF_USD1_v1 *USD1_v1; + // simulated MaxsonarSerialLV rangefinder: + SITL::RF_MaxsonarSerialLV *maxsonarseriallv; + // simulated Wasp rangefinder: + SITL::RF_Wasp *wasp; + // simulated NMEA rangefinder: + SITL::RF_NMEA *nmea; + // simulated MAVLink rangefinder: + SITL::RF_MAVLink *rf_mavlink; + // simulated GYUS42v2 rangefinder: + SITL::RF_GYUS42v2 *gyus42v2; + + // simulated Frsky devices + SITL::Frsky_D *frsky_d; + // SITL::Frsky_SPort *frsky_sport; + // SITL::Frsky_SPortPassthrough *frsky_sportpassthrough; + +#if HAL_SIM_PS_RPLIDARA2_ENABLED + // simulated RPLidarA2: + SITL::PS_RPLidarA2 *rplidara2; +#endif + + // simulated FETtec OneWire ESCs: + SITL::FETtecOneWireESC *fetteconewireesc; + +#if HAL_SIM_PS_LIGHTWARE_SF45B_ENABLED + // simulated SF45B proximity sensor: + SITL::PS_LightWare_SF45B *sf45b; +#endif + +#if HAL_SIM_PS_TERARANGERTOWER_ENABLED + SITL::PS_TeraRangerTower *terarangertower; +#endif + +#if AP_SIM_CRSF_ENABLED + // simulated CRSF devices + SITL::CRSF *crsf; +#endif + + // simulated VectorNav system: + SITL::VectorNav *vectornav; + + // simulated LORD Microstrain system + SITL::LORD *lord; + +#if HAL_SIM_JSON_MASTER_ENABLED + // Ride along instances via JSON SITL backend + SITL::JSON_Master ride_along; +#endif + +#if HAL_SIM_AIS_ENABLED + // simulated AIS stream + SITL::AIS *ais; +#endif + + // simulated EFI MegaSquirt device: + SITL::EFI_MegaSquirt *efi_ms; + +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL + // output socket for flightgear viewing + SocketAPM fg_socket{true}; +#endif + + const char *defaults_path = HAL_PARAM_DEFAULTS_PATH; + + const char *_home_str; + + uint32_t wind_start_delay_micros; + +#if HAL_SIM_GPS_ENABLED + // simulated GPS devices + SITL::GPS *gps[2]; // constrained by # of parameter sets +#endif +}; + +#endif // AP_SIM_ENABLED diff --git a/libraries/AP_HAL/SPIDevice.h b/libraries/AP_HAL/SPIDevice.h index 604a18b040f..725cb223a72 100644 --- a/libraries/AP_HAL/SPIDevice.h +++ b/libraries/AP_HAL/SPIDevice.h @@ -78,6 +78,8 @@ class SPIDeviceManager { /* Get spi device name at @idx */ virtual const char *get_device_name(uint8_t idx) { return nullptr; } + + virtual void set_register_rw_callback(const char* name, AP_HAL::Device::RegisterRWCb cb) {} }; } diff --git a/libraries/AP_HAL/Scheduler.cpp b/libraries/AP_HAL/Scheduler.cpp index 2c65c630659..b22d586b76b 100644 --- a/libraries/AP_HAL/Scheduler.cpp +++ b/libraries/AP_HAL/Scheduler.cpp @@ -1,5 +1,6 @@ #include "Scheduler.h" #include "AP_HAL.h" +#include using namespace AP_HAL; @@ -35,3 +36,23 @@ ExpectDelay::~ExpectDelay() { hal.scheduler->expect_delay_ms(0); } + +/* + implement TimeCheck class for TIME_CHECK() support + */ +TimeCheck::TimeCheck(uint32_t _limit_ms, const char *_file, uint32_t _line) : + limit_ms(_limit_ms), + file(_file), + line(_line) +{ + start_ms = AP_HAL::millis(); +} + +TimeCheck::~TimeCheck() +{ + const uint32_t end_ms = AP_HAL::millis(); + const uint32_t delta_ms = end_ms - start_ms; + if (delta_ms > limit_ms) { + ::printf("Delta %u at %s:%u\n", unsigned(delta_ms), file, unsigned(line)); + } +} diff --git a/libraries/AP_HAL/Scheduler.h b/libraries/AP_HAL/Scheduler.h index 2a82050dae6..0345138d5d9 100644 --- a/libraries/AP_HAL/Scheduler.h +++ b/libraries/AP_HAL/Scheduler.h @@ -143,3 +143,24 @@ class ExpectDelay { #define EXPECT_DELAY_MS(ms) DELAY_JOIN( ms, __COUNTER__ ) #define DELAY_JOIN( ms, counter) _DO_DELAY_JOIN( ms, counter ) #define _DO_DELAY_JOIN( ms, counter ) ExpectDelay _getdelay ## counter(ms) + + +/* + TIME_CHECK() can be used to unexpected detect long delays. Scatter + them in likely places and any long delays will be printed + */ + +class TimeCheck { +public: + TimeCheck(uint32_t limit_ms, const char *file, uint32_t line); + ~TimeCheck(); +private: + const uint32_t limit_ms; + const uint32_t line; + const char *file; + uint32_t start_ms; +}; + +#define TIME_CHECK(limit_ms) JOIN_TC(limit_ms, __FILE__, __LINE__, __COUNTER__ ) +#define JOIN_TC(limit_ms, file, line, counter ) _DO_JOIN_TC( limit_ms, file, line, counter ) +#define _DO_JOIN_TC(limit_ms, file, line, counter ) TimeCheck _gettc ## counter(limit_ms, file, line) diff --git a/libraries/AP_HAL/UARTDriver.h b/libraries/AP_HAL/UARTDriver.h index 9a4cb61ecca..ecd671fda67 100644 --- a/libraries/AP_HAL/UARTDriver.h +++ b/libraries/AP_HAL/UARTDriver.h @@ -135,6 +135,8 @@ class AP_HAL::UARTDriver : public AP_HAL::BetterStream { return 57; } + virtual uint32_t get_baud_rate() const { return 0; } + /* return true if this UART has DMA enabled on both RX and TX */ diff --git a/libraries/AP_HAL/Util.h b/libraries/AP_HAL/Util.h index b730acb1d57..f5e116a593e 100644 --- a/libraries/AP_HAL/Util.h +++ b/libraries/AP_HAL/Util.h @@ -81,6 +81,7 @@ class AP_HAL::Util { int8_t scheduler_task; bool armed; // true if vehicle was armed enum safety_state safety_state; + bool boot_to_dfu; // true if we should reboot to DFU on boot }; struct PersistentData persistent_data; // last_persistent_data is only filled in if we've suffered a watchdog reset @@ -106,6 +107,7 @@ class AP_HAL::Util { NO_CHANGE=1, FAIL=2, NOT_AVAILABLE=3, + NOT_SIGNED=4, }; // overwrite bootloader (probably with one from ROMFS) @@ -118,7 +120,7 @@ class AP_HAL::Util { Buf should be filled with a printable string and must be null terminated */ - virtual bool get_system_id(char buf[40]) { return false; } + virtual bool get_system_id(char buf[50]) { return false; } virtual bool get_system_id_unformatted(uint8_t buf[], uint8_t &len) { return false; } /** @@ -196,8 +198,14 @@ class AP_HAL::Util { // log info on stack usage virtual void log_stack_info(void) {} +#if AP_CRASHDUMP_ENABLED virtual size_t last_crash_dump_size() const { return 0; } virtual void* last_crash_dump_ptr() const { return nullptr; } +#endif + +#if HAL_ENABLE_DFU_BOOT + virtual void boot_to_dfu(void) {} +#endif protected: // we start soft_armed false, so that actuators don't send any // values until the vehicle code has fully started diff --git a/libraries/AP_HAL/examples/DSP_test/DSP_test.cpp b/libraries/AP_HAL/examples/DSP_test/DSP_test.cpp index 92104c40407..f599a8c227a 100644 --- a/libraries/AP_HAL/examples/DSP_test/DSP_test.cpp +++ b/libraries/AP_HAL/examples/DSP_test/DSP_test.cpp @@ -3,6 +3,7 @@ #include #include #include +#include #include "GyroFrame.h" #if HAL_WITH_DSP @@ -39,13 +40,14 @@ class DummyVehicle { class DSPTest : public AP_HAL::DSP { public: - virtual FFTWindowState* fft_init(uint16_t w, uint16_t sample_rate) override { return nullptr; } + virtual FFTWindowState* fft_init(uint16_t w, uint16_t sample_rate, uint8_t sliding_window_size) override { return nullptr; } virtual void fft_start(FFTWindowState* state, FloatBuffer& samples, uint16_t advance) override {} virtual uint16_t fft_analyse(FFTWindowState* state, uint16_t start_bin, uint16_t end_bin, float noise_att_cutoff) override { return 0; } protected: virtual void vector_max_float(const float* vin, uint16_t len, float* maxValue, uint16_t* maxIndex) const override {} virtual void vector_scale_float(const float* vin, float scale, float* vout, uint16_t len) const override {} virtual float vector_mean_float(const float* vin, uint16_t len) const override { return 0.0f; }; + virtual void vector_add_float(const float* vin1, const float* vin2, float* vout, uint16_t len) const override {} public: void run_tests(); } dsptest; diff --git a/libraries/AP_HAL/examples/DSP_test/gyro_isb_reader.py b/libraries/AP_HAL/examples/DSP_test/gyro_isb_reader.py old mode 100644 new mode 100755 diff --git a/libraries/AP_HAL/tests/test_prescaler.cpp b/libraries/AP_HAL/tests/test_prescaler.cpp index f741fb1c378..68125a2a106 100644 --- a/libraries/AP_HAL/tests/test_prescaler.cpp +++ b/libraries/AP_HAL/tests/test_prescaler.cpp @@ -11,24 +11,41 @@ class PrescalerParameterizedTestFixture :public ::testing::TestWithParam 50000000 ? 0.13f : 0.35f; + EXPECT_TRUE(rate_delta < expected_delta); + } + + void test_prescaler_neopixel(uint32_t clock) + { + const uint32_t target_rate = 800000 * AP_HAL::RCOutput::NEOP_BIT_WIDTH_TICKS; + const uint32_t prescaler = AP_HAL::RCOutput::calculate_bitrate_prescaler(clock, target_rate, false); + const uint32_t actual_rate = clock / prescaler; + + const float bit_1_width_us = 1000000.0f * AP_HAL::RCOutput::NEOP_BIT_1_TICKS / actual_rate; + const float bit_0_width_us = 1000000.0f * AP_HAL::RCOutput::NEOP_BIT_0_TICKS / actual_rate; + + // timing requirements from WS2812B spec + EXPECT_TRUE(bit_1_width_us < (0.85f + 0.15f) && bit_1_width_us > (0.85f - 0.15f)); + EXPECT_TRUE(bit_0_width_us < (0.4f + 0.15f) && bit_0_width_us > (0.4f - 0.15f)); + EXPECT_TRUE((bit_0_width_us + bit_1_width_us) < (1.25f + 0.6f) && (bit_0_width_us + bit_1_width_us) > (1.25f - 0.6f)); } }; TEST_P(PrescalerParameterizedTestFixture, DShot150) { - test_prescaler(GetParam(), 150000 * 20, true); + test_prescaler(GetParam(), 150000 * AP_HAL::RCOutput::DSHOT_BIT_WIDTH_TICKS, true); } TEST_P(PrescalerParameterizedTestFixture, DShot300) { - test_prescaler(GetParam(), 300000 * 20, true); + test_prescaler(GetParam(), 300000 * AP_HAL::RCOutput::DSHOT_BIT_WIDTH_TICKS, true); } TEST_P(PrescalerParameterizedTestFixture, DShot600) { - test_prescaler(GetParam(), 600000 * 20, true); + test_prescaler(GetParam(), 600000 * AP_HAL::RCOutput::DSHOT_BIT_WIDTH_TICKS, true); } TEST_P(PrescalerParameterizedTestFixture, DShot1200) { - test_prescaler(GetParam(), 1200000 * 20, true); + test_prescaler(GetParam(), 1200000 * AP_HAL::RCOutput::DSHOT_BIT_WIDTH_TICKS, true); } TEST_P(PrescalerParameterizedTestFixture, Passthrough) { @@ -36,11 +53,11 @@ TEST_P(PrescalerParameterizedTestFixture, Passthrough) { } TEST_P(PrescalerParameterizedTestFixture, NeoPixel) { - test_prescaler(GetParam(), 800000 * 20, false); + test_prescaler_neopixel(GetParam()); } TEST_P(PrescalerParameterizedTestFixture, ProfiLED) { - test_prescaler(GetParam(), 1500000 * 20, false); + test_prescaler(GetParam(), 1500000 * AP_HAL::RCOutput::NEOP_BIT_WIDTH_TICKS, false); } INSTANTIATE_TEST_CASE_P( @@ -51,7 +68,8 @@ INSTANTIATE_TEST_CASE_P( 216000000, // F745 108000000, // F745 84000000, // F405 - 168000000 // F405 + 168000000, // F405 + 50000000 // CUAV_GPS )); AP_GTEST_MAIN() \ No newline at end of file diff --git a/libraries/AP_HAL/utility/RingBuffer.h b/libraries/AP_HAL/utility/RingBuffer.h index 311de1f61b9..08492cfadf6 100644 --- a/libraries/AP_HAL/utility/RingBuffer.h +++ b/libraries/AP_HAL/utility/RingBuffer.h @@ -129,6 +129,9 @@ class ObjectBuffer { // return size of ringbuffer uint32_t get_size(void) const { + if (buffer == nullptr) { + return 0; + } uint32_t size = buffer->get_size() / sizeof(T); return size>0?size-1:0; } @@ -291,6 +294,9 @@ class ObjectBuffer_TS { // return size of ringbuffer uint32_t get_size(void) { WITH_SEMAPHORE(sem); + if (buffer == nullptr) { + return 0; + } uint32_t size = buffer->get_size() / sizeof(T); return size>0?size-1:0; } diff --git a/libraries/AP_HAL_ChibiOS/AnalogIn.cpp b/libraries/AP_HAL_ChibiOS/AnalogIn.cpp index 539acb76656..dd79b1997c6 100644 --- a/libraries/AP_HAL_ChibiOS/AnalogIn.cpp +++ b/libraries/AP_HAL_ChibiOS/AnalogIn.cpp @@ -156,7 +156,7 @@ bool AnalogSource::set_pin(uint8_t pin) return true; } bool found_pin = false; - if (_pin == ANALOG_SERVO_VRSSI_PIN) { + if (pin == ANALOG_SERVO_VRSSI_PIN) { found_pin = true; } else { for (uint8_t i=0; iprintf("Out of analog channels\n"); + DEV_PRINTF("Out of analog channels\n"); return nullptr; } diff --git a/libraries/AP_HAL_ChibiOS/CANFDIface.cpp b/libraries/AP_HAL_ChibiOS/CANFDIface.cpp index 9510c6161f0..f7330c9a836 100644 --- a/libraries/AP_HAL_ChibiOS/CANFDIface.cpp +++ b/libraries/AP_HAL_ChibiOS/CANFDIface.cpp @@ -57,20 +57,16 @@ #define FDCAN2_IT0_IRQHandler STM32_FDCAN2_IT0_HANDLER #define FDCAN2_IT1_IRQHandler STM32_FDCAN2_IT1_HANDLER -#if defined(STM32G4) -// on G4 FIFO elements are spaced at 18 words +// FIFO elements are spaced at 18 words #define FDCAN_FRAME_BUFFER_SIZE 18 -#else -// on H7 they are spaced at 4 words -#define FDCAN_FRAME_BUFFER_SIZE 4 -#endif + //Message RAM Allocations in Word lengths #if defined(STM32H7) -#define MAX_FILTER_LIST_SIZE 80U //80 element Standard Filter List elements or 40 element Extended Filter List -#define FDCAN_NUM_RXFIFO0_SIZE 104U //26 Frames -#define FDCAN_TX_FIFO_BUFFER_SIZE 128U //32 Frames +#define MAX_FILTER_LIST_SIZE 78U //78 element Standard Filter List elements or 40 element Extended Filter List +#define FDCAN_NUM_RXFIFO0_SIZE 108U //6 Frames +#define FDCAN_TX_FIFO_BUFFER_SIZE 126U //7 Frames #define MESSAGE_RAM_END_ADDR 0x4000B5FC #elif defined(STM32G4) @@ -91,7 +87,13 @@ extern AP_HAL::HAL& hal; -static_assert(STM32_FDCANCLK <= 80U*1000U*1000U, "FDCAN clock must be max 80MHz"); +#define STR(x) #x +#define XSTR(x) STR(x) +#if defined(STM32H7) +static_assert(STM32_FDCANCLK == 80U*1000U*1000U, "FDCAN clock must be 80MHz, got " XSTR(STM32_FDCANCLK)); +#else +static_assert(STM32_FDCANCLK <= 80U*1000U*1000U, "FDCAN clock must be max 80MHz, got " XSTR(STM32_FDCANCLK)); +#endif using namespace ChibiOS; @@ -243,6 +245,7 @@ bool CANIface::computeTimings(const uint32_t target_bitrate, Timings& out_timing const uint32_t prescaler = prescaler_bs / (1 + bs1_bs2_sum); if ((prescaler < 1U) || (prescaler > 1024U)) { + Debug("Timings: No Solution found\n"); return false; // No solution } @@ -295,6 +298,9 @@ bool CANIface::computeTimings(const uint32_t target_bitrate, Timings& out_timing solution = BsPair(bs1_bs2_sum, uint8_t((7 * bs1_bs2_sum - 1) / 8)); } + Debug("Timings: quanta/bit: %d, sample point location: %.1f%%\n", + int(1 + solution.bs1 + solution.bs2), float(solution.sample_point_permill) / 10.F); + /* * Final validation * Helpful Python: @@ -305,12 +311,11 @@ bool CANIface::computeTimings(const uint32_t target_bitrate, Timings& out_timing * */ if ((target_bitrate != (pclk / (prescaler * (1 + solution.bs1 + solution.bs2)))) || !solution.isValid()) { + Debug("Timings: Invalid Solution %lu %lu %d %d %lu \n", pclk, prescaler, int(solution.bs1), int(solution.bs2), (pclk / (prescaler * (1 + solution.bs1 + solution.bs2)))); return false; } - Debug("Timings: quanta/bit: %d, sample point location: %.1f%%\n", - int(1 + solution.bs1 + solution.bs2), float(solution.sample_point_permill) / 10.F); - + out_timings.sample_point_permill = solution.sample_point_permill; out_timings.prescaler = uint16_t(prescaler - 1U); out_timings.sjw = 0; // Which means one out_timings.bs1 = uint8_t(solution.bs1 - 1); @@ -321,8 +326,13 @@ bool CANIface::computeTimings(const uint32_t target_bitrate, Timings& out_timing int16_t CANIface::send(const AP_HAL::CANFrame& frame, uint64_t tx_deadline, CanIOFlags flags) { + if (!initialised_) { + return -1; + } + stats.tx_requests++; - if (frame.isErrorFrame() || frame.dlc > 8 || !initialised_) { + if (frame.isErrorFrame() || (frame.dlc > 8 && !frame.isCanFDFrame()) || + frame.dlc > 15) { stats.tx_rejected++; return -1; } @@ -336,7 +346,7 @@ int16_t CANIface::send(const AP_HAL::CANFrame& frame, uint64_t tx_deadline, uint8_t index; if ((can_->TXFQS & FDCAN_TXFQS_TFQF) != 0) { - stats.tx_rejected++; + stats.tx_overflow++; return 0; //we don't have free space } index = ((can_->TXFQS & FDCAN_TXFQS_TFQPI) >> FDCAN_TXFQS_TFQPI_Pos); @@ -357,9 +367,20 @@ int16_t CANIface::send(const AP_HAL::CANFrame& frame, uint64_t tx_deadline, //Write Data Length Code, and Message Marker buffer[1] = frame.dlc << 16 | index << 24; + if (frame.isCanFDFrame()) { + buffer[1] |= FDF | BRS; // do CAN FD transfer and bit rate switching + stats.fdf_tx_requests++; + pending_tx_[index].canfd_frame = true; + } else { + pending_tx_[index].canfd_frame = false; + } + // Write Frame to the message RAM - buffer[2] = frame.data_32[0]; - buffer[3] = frame.data_32[1]; + const uint8_t data_length = AP_HAL::CANFrame::dlcToDataLength(frame.dlc); + uint32_t *data_ptr = &buffer[2]; + for (uint8_t i = 0; i < (data_length+3)/4; i++) { + data_ptr[i] = frame.data_32[i]; + } //Set Add Request can_->TXBAR = (1 << index); @@ -534,7 +555,7 @@ uint16_t CANIface::getNumFilters() const } bool CANIface::clock_init_ = false; -bool CANIface::init(const uint32_t bitrate, const OperatingMode mode) +bool CANIface::init(const uint32_t bitrate, const uint32_t fdbitrate, const OperatingMode mode) { Debug("Bitrate %lu mode %d", static_cast(bitrate), static_cast(mode)); if (self_index_ > HAL_NUM_CAN_IFACES) { @@ -627,8 +648,6 @@ bool CANIface::init(const uint32_t bitrate, const OperatingMode mode) /* * CAN timings for this bitrate */ - Timings timings; - if (!computeTimings(bitrate, timings)) { can_->CCCR &= ~FDCAN_CCCR_INIT; uint32_t while_start_ms = AP_HAL::millis(); @@ -639,20 +658,35 @@ bool CANIface::init(const uint32_t bitrate, const OperatingMode mode) } return false; } + _bitrate = bitrate; Debug("Timings: presc=%u sjw=%u bs1=%u bs2=%u\n", unsigned(timings.prescaler), unsigned(timings.sjw), unsigned(timings.bs1), unsigned(timings.bs2)); //setup timing register - //TODO: Do timing calculations for FDCAN can_->NBTP = ((timings.sjw << FDCAN_NBTP_NSJW_Pos) | (timings.bs1 << FDCAN_NBTP_NTSEG1_Pos) | (timings.bs2 << FDCAN_NBTP_NTSEG2_Pos) | (timings.prescaler << FDCAN_NBTP_NBRP_Pos)); - can_->DBTP = ((timings.bs1 << FDCAN_DBTP_DTSEG1_Pos) | - (timings.bs2 << FDCAN_DBTP_DTSEG2_Pos) | - (timings.prescaler << FDCAN_DBTP_DBRP_Pos)); - + if (fdbitrate) { + if (!computeTimings(fdbitrate, fdtimings)) { + can_->CCCR &= ~FDCAN_CCCR_INIT; + uint32_t while_start_ms = AP_HAL::millis(); + while ((can_->CCCR & FDCAN_CCCR_INIT) == 1) { + if ((AP_HAL::millis() - while_start_ms) > REG_SET_TIMEOUT) { + return false; + } + } + return false; + } + _fdbitrate = fdbitrate; + Debug("CANFD Timings: presc=%u bs1=%u bs2=%u\n", + unsigned(fdtimings.prescaler), unsigned(fdtimings.bs1), unsigned(fdtimings.bs2)); + can_->DBTP = ((fdtimings.bs1 << FDCAN_DBTP_DTSEG1_Pos) | + (fdtimings.bs2 << FDCAN_DBTP_DTSEG2_Pos) | + (fdtimings.prescaler << FDCAN_DBTP_DBRP_Pos)); + } + //RX Config #if defined(STM32H7) can_->RXESC = 0; //Set for 8Byte Frames @@ -684,6 +718,8 @@ bool CANIface::init(const uint32_t bitrate, const OperatingMode mode) #endif can_->ILE = 0x3; + can_->CCCR |= FDCAN_CCCR_FDOE | FDCAN_CCCR_BRSE; // enable sending CAN FD frames, and Bitrate switching + // If mode is Filtered then we finish the initialisation in configureFilter method // otherwise we finish here if (mode != FilteredMode) { @@ -722,6 +758,8 @@ void CANIface::setupMessageRam() #else uint32_t num_elements = 0; + can_->RXESC = 0x777; //Support upto 64byte long frames + can_->TXESC = 0x7; //Support upto 64byte long frames // Rx FIFO 0 start address and element count num_elements = MIN((FDCAN_NUM_RXFIFO0_SIZE/FDCAN_FRAME_BUFFER_SIZE), 64U); if (num_elements) { @@ -753,6 +791,9 @@ void CANIface::handleTxCompleteInterrupt(const uint64_t timestamp_us) if (!pending_tx_[i].pushed) { stats.tx_success++; + if (pending_tx_[i].canfd_frame) { + stats.fdf_tx_success++; + } pending_tx_[i].pushed = true; } else { continue; @@ -821,7 +862,7 @@ bool CANIface::readRxFIFO(uint8_t fifo_index) } // Read the frame contents - AP_HAL::CANFrame frame; + AP_HAL::CANFrame frame {}; uint32_t id = frame_ptr[0]; if ((id & IDE) == 0) { //Standard ID @@ -835,10 +876,18 @@ bool CANIface::readRxFIFO(uint8_t fifo_index) if ((id & RTR) != 0) { frame.id |= AP_HAL::CANFrame::FlagRTR; } + + if (frame_ptr[1] & FDF) { + frame.setCanFD(true); + stats.fdf_rx_received++; + } else { + frame.setCanFD(false); + } + frame.dlc = (frame_ptr[1] & DLC_MASK) >> 16; uint8_t *data = (uint8_t*)&frame_ptr[2]; - //We only handle Data Length of 8 Bytes for now - for (uint8_t i = 0; i < 8; i++) { + + for (uint8_t i = 0; i < AP_HAL::CANFrame::dlcToDataLength(frame.dlc); i++) { frame.data[i] = data[i]; } @@ -1037,8 +1086,16 @@ bool CANIface::select(bool &read, bool &write, void CANIface::get_stats(ExpandingString &str) { CriticalSectionLocker lock; - str.printf("tx_requests: %lu\n" + str.printf("------- Clock Config -------\n" + "CAN_CLK_FREQ: %luMHz\n" + "Std Timings: bitrate=%lu presc=%u\n" + "sjw=%u bs1=%u bs2=%u sample_point=%f%%\n" + "FD Timings: bitrate=%lu presc=%u\n" + "sjw=%u bs1=%u bs2=%u sample_point=%f%%\n" + "------- CAN Interface Stats -------\n" + "tx_requests: %lu\n" "tx_rejected: %lu\n" + "tx_overflow: %lu\n" "tx_success: %lu\n" "tx_timedout: %lu\n" "tx_abort: %lu\n" @@ -1047,9 +1104,20 @@ void CANIface::get_stats(ExpandingString &str) "rx_errors: %lu\n" "num_busoff_err: %lu\n" "num_events: %lu\n" - "ECR: %lx\n", + "ECR: %lx\n" + "fdf_rx: %lu\n" + "fdf_tx_req: %lu\n" + "fdf_tx: %lu\n", + STM32_FDCANCLK/1000000UL, + _bitrate, unsigned(timings.prescaler), + unsigned(timings.sjw), unsigned(timings.bs1), + unsigned(timings.bs2), timings.sample_point_permill/10.0f, + _fdbitrate, unsigned(fdtimings.prescaler), + unsigned(fdtimings.sjw), unsigned(fdtimings.bs1), + unsigned(fdtimings.bs2), timings.sample_point_permill/10.0f, stats.tx_requests, stats.tx_rejected, + stats.tx_overflow, stats.tx_success, stats.tx_timedout, stats.tx_abort, @@ -1058,7 +1126,10 @@ void CANIface::get_stats(ExpandingString &str) stats.rx_errors, stats.num_busoff_err, stats.num_events, - stats.ecr); + stats.ecr, + stats.fdf_rx_received, + stats.fdf_tx_requests, + stats.fdf_tx_success); } #endif diff --git a/libraries/AP_HAL_ChibiOS/CANFDIface.h b/libraries/AP_HAL_ChibiOS/CANFDIface.h index b133c4cc269..6e92fe395b2 100644 --- a/libraries/AP_HAL_ChibiOS/CANFDIface.h +++ b/libraries/AP_HAL_ChibiOS/CANFDIface.h @@ -61,6 +61,9 @@ class ChibiOS::CANIface : public AP_HAL::CANIface static constexpr unsigned long EXID_MASK = (0x1FFFFFFFU); // Extended Identifier Mask static constexpr unsigned long RTR = (0x20000000U); // Remote Transmission Request static constexpr unsigned long DLC_MASK = (0x000F0000U); // Data Length Code + static constexpr unsigned long FDF = (0x00200000U); // CAN FD Frame + static constexpr unsigned long BRS = (0x00100000U); // Bit Rate Switching + /** * CANx register sets @@ -88,13 +91,15 @@ class ChibiOS::CANIface : public AP_HAL::CANIface } MessageRam_; struct Timings { + uint16_t sample_point_permill; uint16_t prescaler; uint8_t sjw; uint8_t bs1; uint8_t bs2; Timings() - : prescaler(0) + : sample_point_permill(0) + , prescaler(0) , sjw(0) , bs1(0) , bs2(0) @@ -147,10 +152,12 @@ class ChibiOS::CANIface : public AP_HAL::CANIface static bool clock_init_; bool _detected_bus_off; - + Timings timings, fdtimings; + uint32_t _bitrate, _fdbitrate; struct { uint32_t tx_requests; uint32_t tx_rejected; + uint32_t tx_overflow; uint32_t tx_success; uint32_t tx_timedout; uint32_t tx_abort; @@ -160,6 +167,9 @@ class ChibiOS::CANIface : public AP_HAL::CANIface uint32_t num_busoff_err; uint32_t num_events; uint32_t ecr; + uint32_t fdf_tx_requests; + uint32_t fdf_tx_success; + uint32_t fdf_rx_received; } stats; public: @@ -171,7 +181,11 @@ class ChibiOS::CANIface : public AP_HAL::CANIface static uint8_t next_interface; // Initialise CAN Peripheral - bool init(const uint32_t bitrate, const OperatingMode mode) override; + bool init(const uint32_t bitrate, const OperatingMode mode) override { + return init(bitrate, 0, mode); + } + + bool init(const uint32_t bitrate, const uint32_t fdbitrate, const OperatingMode mode) override; // Put frame into Tx FIFO returns negative on error, 0 on buffer full, // 1 on successfully pushing a frame into FIFO diff --git a/libraries/AP_HAL_ChibiOS/DSP.cpp b/libraries/AP_HAL_ChibiOS/DSP.cpp index 44c73a0905e..0fb0692e264 100644 --- a/libraries/AP_HAL_ChibiOS/DSP.cpp +++ b/libraries/AP_HAL_ChibiOS/DSP.cpp @@ -50,9 +50,9 @@ extern const AP_HAL::HAL& hal; // important as frequency resolution. Referred to as [Heinz] throughout the code. // initialize the FFT state machine -AP_HAL::DSP::FFTWindowState* DSP::fft_init(uint16_t window_size, uint16_t sample_rate) +AP_HAL::DSP::FFTWindowState* DSP::fft_init(uint16_t window_size, uint16_t sample_rate, uint8_t sliding_window_size) { - DSP::FFTWindowStateARM* fft = new DSP::FFTWindowStateARM(window_size, sample_rate); + DSP::FFTWindowStateARM* fft = new DSP::FFTWindowStateARM(window_size, sample_rate, sliding_window_size); if (fft == nullptr || fft->_hanning_window == nullptr || fft->_rfft_data == nullptr || fft->_freq_bins == nullptr || fft->_derivative_freq_bins == nullptr) { delete fft; return nullptr; @@ -78,8 +78,8 @@ uint16_t DSP::fft_analyse(AP_HAL::DSP::FFTWindowState* state, uint16_t start_bin } // create an instance of the FFT state machine -DSP::FFTWindowStateARM::FFTWindowStateARM(uint16_t window_size, uint16_t sample_rate) - : AP_HAL::DSP::FFTWindowState::FFTWindowState(window_size, sample_rate) +DSP::FFTWindowStateARM::FFTWindowStateARM(uint16_t window_size, uint16_t sample_rate, uint8_t sliding_window_size) + : AP_HAL::DSP::FFTWindowState::FFTWindowState(window_size, sample_rate, sliding_window_size) { if (_freq_bins == nullptr || _hanning_window == nullptr || _rfft_data == nullptr || _derivative_freq_bins == nullptr) { GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Failed to allocate %u bytes for window %u for DSP", @@ -130,6 +130,7 @@ extern "C" { void DSP::step_hanning(FFTWindowStateARM* fft, FloatBuffer& samples, uint16_t advance) { TIMER_START(_hanning_timer); + // 5us // apply hanning window to gyro samples and store result in _freq_bins // hanning starts and ends with 0, could be skipped for minor speed improvement @@ -212,6 +213,7 @@ void DSP::step_stage_rfft_f32(FFTWindowStateARM* fft) void DSP::step_arm_cmplx_mag_f32(FFTWindowStateARM* fft, uint16_t start_bin, uint16_t end_bin, float noise_att_cutoff) { TIMER_START(_arm_cmplx_mag_f32_timer); + // 8us (BF) // 32 - 4us F7, 5us F4, 5us H7 // 64 - 7us F7, 13us F4 diff --git a/libraries/AP_HAL_ChibiOS/DSP.h b/libraries/AP_HAL_ChibiOS/DSP.h index 75450516d88..8d839b53934 100644 --- a/libraries/AP_HAL_ChibiOS/DSP.h +++ b/libraries/AP_HAL_ChibiOS/DSP.h @@ -29,7 +29,7 @@ class ChibiOS::DSP : public AP_HAL::DSP { public: // initialise an FFT instance - virtual FFTWindowState* fft_init(uint16_t window_size, uint16_t sample_rate) override; + virtual FFTWindowState* fft_init(uint16_t window_size, uint16_t sample_rate, uint8_t sliding_window_size) override; // start an FFT analysis with an ObjectBuffer virtual void fft_start(FFTWindowState* state, FloatBuffer& samples, uint16_t advance) override; // perform remaining steps of an FFT analysis @@ -39,7 +39,7 @@ class ChibiOS::DSP : public AP_HAL::DSP { class FFTWindowStateARM : public AP_HAL::DSP::FFTWindowState { friend class ChibiOS::DSP; public: - FFTWindowStateARM(uint16_t window_size, uint16_t sample_rate); + FFTWindowStateARM(uint16_t window_size, uint16_t sample_rate, uint8_t sliding_window_size); virtual ~FFTWindowStateARM(); private: @@ -61,6 +61,9 @@ class ChibiOS::DSP : public AP_HAL::DSP { arm_mean_f32(vin, len, &mean_value); return mean_value; } + void vector_add_float(const float* vin1, const float* vin2, float* vout, uint16_t len) const override { + arm_add_f32(vin1, vin2, vout, len); + } private: // following are the six independent steps for calculating an FFT diff --git a/libraries/AP_HAL_ChibiOS/EventSource.cpp b/libraries/AP_HAL_ChibiOS/EventSource.cpp index dfb21919b6b..4977a46be11 100644 --- a/libraries/AP_HAL_ChibiOS/EventSource.cpp +++ b/libraries/AP_HAL_ChibiOS/EventSource.cpp @@ -1,4 +1,5 @@ #include "EventSource.h" +#include using namespace ChibiOS; @@ -13,7 +14,7 @@ bool EventSource::wait(uint64_t duration, AP_HAL::EventHandle *evt_handle) if (duration == 0) { ret = chEvtWaitAnyTimeout(evt_mask, TIME_IMMEDIATE); } else { - ret = chEvtWaitAnyTimeout(evt_mask, chTimeUS2I(duration)); + ret = chEvtWaitAnyTimeout(evt_mask, MAX(CH_CFG_ST_TIMEDELTA, chTimeUS2I(duration))); } ch_evt_src_.unregister(&evt_listener); return ret == MSG_OK; diff --git a/libraries/AP_HAL_ChibiOS/GPIO.cpp b/libraries/AP_HAL_ChibiOS/GPIO.cpp index 1bb06ab9a05..c0203c7fcde 100644 --- a/libraries/AP_HAL_ChibiOS/GPIO.cpp +++ b/libraries/AP_HAL_ChibiOS/GPIO.cpp @@ -28,6 +28,7 @@ #include #endif #include +#include using namespace ChibiOS; @@ -89,7 +90,7 @@ void GPIO::init() chan_offset = 8; } #endif - // auto-disable pins being used for PWM output based on BRD_PWM_COUNT parameter + // auto-disable pins being used for PWM output for (uint8_t i=0; ipwm_num != 0) { @@ -462,8 +463,7 @@ static void pal_interrupt_wait(void *arg) } /* - block waiting for a pin to change. A timeout of 0 means wait - forever. Return true on pin change, false on timeout + block waiting for a pin to change. Return true on pin change, false on timeout */ bool GPIO::wait_pin(uint8_t pin, INTERRUPT_TRIGGER_TYPE mode, uint32_t timeout_us) { @@ -486,8 +486,11 @@ bool GPIO::wait_pin(uint8_t pin, INTERRUPT_TRIGGER_TYPE mode, uint32_t timeout_u osalSysUnlock(); return false; } - - msg_t msg = osalThreadSuspendTimeoutS(&g->thd_wait, TIME_US2I(timeout_us)); + + // don't allow for very long timeouts, or below the delta + timeout_us = constrain_uint32(TIME_US2I(timeout_us), CH_CFG_ST_TIMEDELTA, TIME_US2I(30000U)); + + msg_t msg = osalThreadSuspendTimeoutS(&g->thd_wait, timeout_us); _attach_interruptI(g->pal_line, palcallback_t(nullptr), nullptr, @@ -508,6 +511,37 @@ bool GPIO::valid_pin(uint8_t pin) const return gpio_by_pin_num(pin) != nullptr; } +// return servo channel associated with GPIO pin. Returns true on success and fills in servo_ch argument +// servo_ch uses zero-based indexing +bool GPIO::pin_to_servo_channel(uint8_t pin, uint8_t& servo_ch) const +{ + uint8_t fmu_chan_offset = 0; +#if HAL_WITH_IO_MCU + if (AP_BoardConfig::io_enabled()) { + // check if this is one of the main pins + uint8_t main_servo_ch = pin; + if (iomcu.convert_pin_number(main_servo_ch)) { + servo_ch = main_servo_ch; + return true; + } + // with IOMCU the local (FMU) channels start at 8 + fmu_chan_offset = 8; + } +#endif + + // search _gpio_tab for matching pin + for (uint8_t i=0; i #endif #include +#include #include @@ -97,6 +98,10 @@ static ChibiOS::Scheduler schedulerInstance; static ChibiOS::Util utilInstance; static Empty::OpticalFlow opticalFlowDriver; +#if AP_SIM_ENABLED +static AP_HAL::SIMState xsimstate; +#endif + #if HAL_WITH_DSP static ChibiOS::DSP dspDriver; #else @@ -152,6 +157,9 @@ HAL_ChibiOS::HAL_ChibiOS() : &utilInstance, &opticalFlowDriver, &flashDriver, +#if AP_SIM_ENABLED + &xsimstate, +#endif &dspDriver, #if HAL_NUM_CAN_IFACES (AP_HAL::CANIface**)canDrivers @@ -205,7 +213,7 @@ static void main_loop() ChibiOS::I2CBus::clear_all(); #endif -#ifndef HAL_NO_SHARED_DMA +#if AP_HAL_SHARED_DMA_ENABLED ChibiOS::Shared_DMA::init(); #endif @@ -241,7 +249,7 @@ static void main_loop() utilInstance.apply_persistent_params(); #endif -#ifdef HAL_FLASH_PROTECTION +#if HAL_FLASH_PROTECTION if (AP_BoardConfig::unlock_flash()) { stm32_flash_unprotect_flash(); } else { diff --git a/libraries/AP_HAL_ChibiOS/I2CDevice.cpp b/libraries/AP_HAL_ChibiOS/I2CDevice.cpp index 36e3ea9952c..cc50bbacad0 100644 --- a/libraries/AP_HAL_ChibiOS/I2CDevice.cpp +++ b/libraries/AP_HAL_ChibiOS/I2CDevice.cpp @@ -267,7 +267,7 @@ I2CDevice::I2CDevice(uint8_t busnum, uint8_t address, uint32_t bus_clock, bool u bus.i2ccfg.duty_cycle = STD_DUTY_CYCLE; } #endif - hal.console->printf("I2C%u clock %ukHz\n", busnum, unsigned(bus.busclock/1000)); + DEV_PRINTF("I2C%u clock %ukHz\n", busnum, unsigned(bus.busclock/1000)); } } @@ -298,7 +298,7 @@ bool I2CDevice::transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) { if (!bus.semaphore.check_owner()) { - hal.console->printf("I2C: not owner of 0x%x for addr 0x%02x\n", (unsigned)get_bus_id(), _address); + DEV_PRINTF("I2C: not owner of 0x%x for addr 0x%02x\n", (unsigned)get_bus_id(), _address); return false; } diff --git a/libraries/AP_HAL_ChibiOS/LogStructure.h b/libraries/AP_HAL_ChibiOS/LogStructure.h new file mode 100644 index 00000000000..236f9bac781 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/LogStructure.h @@ -0,0 +1,77 @@ +#pragma once + +#include + +#define LOG_IDS_FROM_HAL_CHIBIOS \ + LOG_MON_MSG, \ + LOG_WDOG_MSG + +// @LoggerMessage: MON +// @Description: Main loop performance monitoring message. +// @Field: TimeUS: Time since system startup +// @Field: Dly: Loop delay so far +// @Field: Tsk: Current task +// @Field: IErr: Internal error mask +// @Field: IErrCnt: Count of internal error occurances +// @Field: IErrLn: Internal Error line +// @Field: MM: MAVLink message currently being processed +// @Field: MC: MAVLink command currently being processed +// @Field: SmLn: If semaphore taken, line of semaphore take call +// @Field: SPICnt: count of SPI transactions +// @Field: I2CCnt: count of i2c transactions +struct PACKED log_MON { + LOG_PACKET_HEADER; + uint64_t time_us; + uint32_t loop_delay; + int8_t current_task; + uint32_t internal_error_mask; + uint16_t internal_error_count; + uint16_t internal_error_line; + uint16_t mavmsg; + uint16_t mavcmd; + uint16_t semline; + uint32_t spicnt; + uint32_t i2ccnt; +}; + +// @LoggerMessage: WDOG +// @Description: Watchdog diagnostics +// @Field: TimeUS: Time since system startup +// @Field: Tsk: current task number +// @Field: IE: internal error mast +// @Field: IEC: internal error count +// @Field: IEL: line internal error was raised on +// @Field: MvMsg: mavlink message being acted on +// @Field: MvCmd: mavlink command being acted on +// @Field: SmLn: line semaphore was taken on +// @Field: FL: fault_line +// @Field: FT: fault_type +// @Field: FA: fault address +// @Field: FP: fault thread priority +// @Field: ICSR: ICS regiuster +// @Field: LR: long return address +// @Field: TN: Thread name +struct PACKED log_WDOG { + LOG_PACKET_HEADER; + uint64_t time_us; + int8_t scheduler_task; + uint32_t internal_errors; + uint16_t internal_error_count; + uint16_t internal_error_last_line; + uint16_t last_mavlink_msgid; + uint16_t last_mavlink_cmd; + uint16_t semaphore_line; + uint16_t fault_line; + uint16_t fault_type; + uint32_t fault_addr; + uint8_t fault_thd_prio; + uint32_t fault_icsr; + uint32_t fault_lr; + char thread_name4[4]; +}; + +#define LOG_STRUCTURE_FROM_HAL_CHIBIOS \ + { LOG_MON_MSG, sizeof(log_MON), \ + "MON","QIbIHHHHHII","TimeUS,Dly,Tsk,IErr,IErrCnt,IErrLn,MM,MC,SmLn,SPICnt,I2CCnt", "s----------", "F----------", false }, \ + { LOG_WDOG_MSG, sizeof(log_WDOG), \ + "WDOG","QbIHHHHHHHIBIIn","TimeUS,Tsk,IE,IEC,IEL,MvMsg,MvCmd,SmLn,FL,FT,FA,FP,ICSR,LR,TN", "s--------------", "F--------------", false }, diff --git a/libraries/AP_HAL_ChibiOS/QSPIDevice.cpp b/libraries/AP_HAL_ChibiOS/QSPIDevice.cpp index acfa563ebfa..4a7b7e68114 100644 --- a/libraries/AP_HAL_ChibiOS/QSPIDevice.cpp +++ b/libraries/AP_HAL_ChibiOS/QSPIDevice.cpp @@ -27,7 +27,6 @@ #include "Util.h" #include "Scheduler.h" #include -#include "hwdef/common/stm32_util.h" #if HAL_USE_WSPI == TRUE && defined(HAL_QSPI_DEVICE_LIST) diff --git a/libraries/AP_HAL_ChibiOS/QSPIDevice.h b/libraries/AP_HAL_ChibiOS/QSPIDevice.h index 5c04845a57f..f6049a79dba 100644 --- a/libraries/AP_HAL_ChibiOS/QSPIDevice.h +++ b/libraries/AP_HAL_ChibiOS/QSPIDevice.h @@ -29,6 +29,7 @@ #if !defined(HAL_BOOTLOADER_BUILD) #include "Semaphores.h" #endif +#include "hwdef/common/stm32_util.h" #include "Scheduler.h" #include "Device.h" diff --git a/libraries/AP_HAL_ChibiOS/RCInput.cpp b/libraries/AP_HAL_ChibiOS/RCInput.cpp index cbaaf03c7bc..6ea3436d9c1 100644 --- a/libraries/AP_HAL_ChibiOS/RCInput.cpp +++ b/libraries/AP_HAL_ChibiOS/RCInput.cpp @@ -150,6 +150,7 @@ void RCInput::_timer_tick(void) } #ifndef HAL_NO_UARTDRIVER const char *rc_protocol = nullptr; + RCSource source = last_source; #endif #ifndef HAL_BUILD_AP_PERIPH @@ -175,7 +176,13 @@ void RCInput::_timer_tick(void) } #endif - if (rcprot.new_input()) { + uint32_t now = AP_HAL::millis(); + const bool have_iocmu_rc = (_rcin_last_iomcu_ms != 0 && now - _rcin_last_iomcu_ms < 400); + if (!have_iocmu_rc) { + _rcin_last_iomcu_ms = 0; + } + + if (rcprot.new_input() && !have_iocmu_rc) { WITH_SEMAPHORE(rcin_mutex); _rcin_timestamp_last_signal = AP_HAL::micros(); _num_channels = rcprot.num_channels(); @@ -185,12 +192,13 @@ void RCInput::_timer_tick(void) _rx_link_quality = rcprot.get_rx_link_quality(); #ifndef HAL_NO_UARTDRIVER rc_protocol = rcprot.protocol_name(); + source = rcprot.using_uart() ? RCSource::RCPROT_BYTES : RCSource::RCPROT_PULSES; #endif } #endif // HAL_BUILD_AP_PERIPH #if HAL_RCINPUT_WITH_AP_RADIO - if (radio && radio->last_recv_us() != last_radio_us) { + if (radio && radio->last_recv_us() != last_radio_us && !have_iocmu_rc) { last_radio_us = radio->last_recv_us(); WITH_SEMAPHORE(rcin_mutex); _rcin_timestamp_last_signal = last_radio_us; @@ -199,6 +207,9 @@ void RCInput::_timer_tick(void) for (uint8_t i=0; i<_num_channels; i++) { _rc_values[i] = radio->read(i); } +#ifndef HAL_NO_UARTDRIVER + source = RCSource::APRADIO; +#endif } #endif @@ -208,18 +219,21 @@ void RCInput::_timer_tick(void) if (AP_BoardConfig::io_enabled() && iomcu.check_rcinput(last_iomcu_us, _num_channels, _rc_values, RC_INPUT_MAX_CHANNELS)) { _rcin_timestamp_last_signal = last_iomcu_us; + _rcin_last_iomcu_ms = now; #ifndef HAL_NO_UARTDRIVER rc_protocol = iomcu.get_rc_protocol(); _rssi = iomcu.get_RSSI(); + source = RCSource::IOMCU; #endif } } #endif #ifndef HAL_NO_UARTDRIVER - if (rc_protocol && rc_protocol != last_protocol) { + if (rc_protocol && (rc_protocol != last_protocol || source != last_source)) { last_protocol = rc_protocol; - GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "RCInput: decoding %s", last_protocol); + last_source = source; + GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "RCInput: decoding %s(%u)", last_protocol, unsigned(source)); } #endif diff --git a/libraries/AP_HAL_ChibiOS/RCInput.h b/libraries/AP_HAL_ChibiOS/RCInput.h index 6a35ab05986..08ba46d58c5 100644 --- a/libraries/AP_HAL_ChibiOS/RCInput.h +++ b/libraries/AP_HAL_ChibiOS/RCInput.h @@ -69,8 +69,18 @@ class ChibiOS::RCInput : public AP_HAL::RCInput { int16_t _rssi = -1; int16_t _rx_link_quality = -1; uint32_t _rcin_timestamp_last_signal; + uint32_t _rcin_last_iomcu_ms; bool _init; const char *last_protocol; + + enum class RCSource { + NONE = 0, + IOMCU = 1, + RCPROT_PULSES = 2, + RCPROT_BYTES = 3, + APRADIO = 4, + } last_source; + bool pulse_input_enabled; #if HAL_RCINPUT_WITH_AP_RADIO diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.cpp b/libraries/AP_HAL_ChibiOS/RCOutput.cpp index ad8a5861052..5d2f6b44dda 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput.cpp @@ -32,6 +32,10 @@ #include #endif +#if AP_SIM_ENABLED +#include +#endif + #if HAL_USE_PWM == TRUE #include @@ -128,9 +132,7 @@ void RCOutput::init() // setup default output rate of 50Hz set_freq(0xFFFF ^ ((1U<pinMode(54, 1); @@ -148,8 +150,8 @@ void RCOutput::init() */ void RCOutput::rcout_thread() { - uint32_t last_thread_run_us = 0; // last time we did a 1kHz run of rcout - uint32_t last_cycle_run_us = 0; + uint64_t last_thread_run_us = 0; // last time we did a 1kHz run of rcout + uint64_t last_cycle_run_us = 0; rcout_thread_ctx = chThdGetSelfX(); @@ -164,11 +166,11 @@ void RCOutput::rcout_thread() const auto mask = chEvtWaitOne(EVT_PWM_SEND | EVT_PWM_SYNTHETIC_SEND | EVT_LED_SEND); const bool have_pwm_event = (mask & (EVT_PWM_SEND | EVT_PWM_SYNTHETIC_SEND)) != 0; // start the clock - last_thread_run_us = AP_HAL::micros(); + last_thread_run_us = AP_HAL::micros64(); // this is when the cycle is supposed to start if (_dshot_cycle == 0 && have_pwm_event) { - last_cycle_run_us = AP_HAL::micros(); + last_cycle_run_us = AP_HAL::micros64(); // register a timer for the next tick if push() will not be providing it if (_dshot_rate != 1) { chVTSet(&_dshot_rate_timer, chTimeUS2I(_dshot_period_us), dshot_update_tick, this); @@ -177,7 +179,7 @@ void RCOutput::rcout_thread() // if DMA sharing is in effect there can be quite a delay between the request to begin the cycle and // actually sending out data - thus we need to work out how much time we have left to collect the locks - uint32_t time_out_us = (_dshot_cycle + 1) * _dshot_period_us + last_cycle_run_us; + uint64_t time_out_us = (_dshot_cycle + 1) * _dshot_period_us + last_cycle_run_us; if (!_dshot_rate) { time_out_us = last_thread_run_us + _dshot_period_us; } @@ -197,6 +199,16 @@ void RCOutput::rcout_thread() // process any pending RC output requests timer_tick(time_out_us); +#if RCOU_DSHOT_TIMING_DEBUG + static bool output_masks = true; + if (AP_HAL::millis() > 5000 && output_masks) { + output_masks = false; + hal.console->printf("bdmask 0x%x, en_mask 0x%lx, 3dmask 0x%x:\n", _bdshot.mask, en_mask, _reversible_mask); + for (auto &group : pwm_group_list) { + hal.console->printf(" timer %u: ch_mask 0x%x, en_mask 0x%x\n", group.timer_id, group.ch_mask, group.en_mask); + } + } +#endif } } @@ -212,9 +224,9 @@ __RAMFUNC__ void RCOutput::dshot_update_tick(void* p) chSysUnlockFromISR(); } -#ifndef HAL_NO_SHARED_DMA +#if AP_HAL_SHARED_DMA_ENABLED // release locks on the groups that are pending in reverse order -void RCOutput::dshot_collect_dma_locks(uint32_t time_out_us) +void RCOutput::dshot_collect_dma_locks(uint64_t time_out_us) { if (NUM_GROUPS == 0) { return; @@ -223,18 +235,28 @@ void RCOutput::dshot_collect_dma_locks(uint32_t time_out_us) pwm_group &group = pwm_group_list[i]; if (group.dma_handle != nullptr && group.dma_handle->is_locked()) { // calculate how long we have left - uint32_t now = AP_HAL::micros(); + uint64_t now = AP_HAL::micros64(); // if we have time left wait for the event eventmask_t mask = 0; - const uint32_t pulse_elapsed_us = now - group.last_dmar_send_us; + const uint64_t pulse_elapsed_us = now - group.last_dmar_send_us; + uint32_t wait_us = 0; if (now < time_out_us) { - mask = chEvtWaitOneTimeout(group.dshot_event_mask, - chTimeUS2I(MAX(time_out_us - now, group.dshot_pulse_send_time_us - pulse_elapsed_us))); - } else if (pulse_elapsed_us < group.dshot_pulse_send_time_us) { + wait_us = time_out_us - now; + } + if (pulse_elapsed_us < group.dshot_pulse_send_time_us) { // better to let the burst write in progress complete rather than cancelling mid way through - mask = chEvtWaitOneTimeout(group.dshot_event_mask, - chTimeUS2I(group.dshot_pulse_send_time_us - pulse_elapsed_us)); + wait_us = MAX(wait_us, group.dshot_pulse_send_time_us - pulse_elapsed_us); } + + // waiting for a very short period of time can cause a + // timer wrap with ChibiOS timers. Use CH_CFG_ST_TIMEDELTA + // as minimum. Don't allow for a very long delay (over _dshot_period_us) + // to prevent bugs in handling timer wrap + const uint32_t max_delay_us = _dshot_period_us; + const uint32_t min_delay_us = 10; // matches our CH_CFG_ST_TIMEDELTA + wait_us = constrain_uint32(wait_us, min_delay_us, max_delay_us); + mask = chEvtWaitOneTimeout(group.dshot_event_mask, chTimeUS2I(wait_us)); + // no time left cancel and restart if (!mask) { dma_cancel(group); @@ -257,7 +279,7 @@ void RCOutput::dshot_collect_dma_locks(uint32_t time_out_us) } } } -#endif // HAL_NO_SHARED_DMA +#endif // AP_HAL_SHARED_DMA_ENABLED /* setup the output frequency for a group and start pwm output @@ -449,6 +471,28 @@ void RCOutput::set_dshot_rate(uint8_t dshot_rate, uint16_t loop_rate_hz) _dshot_period_us = 1000000UL / drate; } +#ifndef DISABLE_DSHOT +/* + Set/get the dshot esc_type + */ +void RCOutput::set_dshot_esc_type(DshotEscType dshot_esc_type) +{ + _dshot_esc_type = dshot_esc_type; + switch (_dshot_esc_type) { + case DSHOT_ESC_BLHELI_S: + DSHOT_BIT_WIDTH_TICKS = DSHOT_BIT_WIDTH_TICKS_S; + DSHOT_BIT_0_TICKS = DSHOT_BIT_0_TICKS_S; + DSHOT_BIT_1_TICKS = DSHOT_BIT_1_TICKS_S; + break; + default: + DSHOT_BIT_WIDTH_TICKS = DSHOT_BIT_WIDTH_TICKS_DEFAULT; + DSHOT_BIT_0_TICKS = DSHOT_BIT_0_TICKS_DEFAULT; + DSHOT_BIT_1_TICKS = DSHOT_BIT_1_TICKS_DEFAULT; + break; + } +} +#endif + /* find pwm_group and index in group given a channel number */ @@ -473,6 +517,33 @@ RCOutput::pwm_group *RCOutput::find_chan(uint8_t chan, uint8_t &group_idx) return nullptr; } +/* + * return mask of channels that must be disabled because they share a group with a digital channel + */ +uint32_t RCOutput::get_disabled_channels(uint32_t digital_mask) +{ + uint32_t dmask = (digital_mask >> chan_offset); + uint32_t disabled_chan_mask = 0; + for (auto &group : pwm_group_list) { + bool digital_group = false; + for (uint8_t j = 0; j < 4; j++) { + if ((1U << group.chan[j]) & dmask) { + digital_group = true; + } + } + if (digital_group) { + for (uint8_t j = 0; j < 4; j++) { + if (!((1U << group.chan[j]) & dmask)) { + disabled_chan_mask |= (1U << group.chan[j]); + } + } + } + } + + disabled_chan_mask <<= chan_offset; + return disabled_chan_mask; +} + uint16_t RCOutput::get_freq(uint8_t chan) { #if HAL_WITH_IO_MCU @@ -512,11 +583,19 @@ void RCOutput::disable_ch(uint8_t chan) void RCOutput::write(uint8_t chan, uint16_t period_us) { + if (chan >= max_channels) { return; } last_sent[chan] = period_us; +#if AP_SIM_ENABLED + hal.simstate->pwm_output[chan] = period_us; + if (!(AP::sitl()->on_hardware_output_enable_mask & (1U< (AP_HAL::micros() + (_dshot_period_us >> 1)))) { + if (serial_led_pending && (time_out_us > (AP_HAL::micros64() + (_dshot_period_us >> 1)))) { serial_led_pending = false; for (auto &group : pwm_group_list) { serial_led_pending |= !serial_led_send(group); @@ -1164,7 +1241,7 @@ void RCOutput::timer_tick(uint32_t time_out_us) return; } - uint32_t now = AP_HAL::micros(); + uint64_t now = AP_HAL::micros64(); if (now > min_pulse_trigger_us && now - min_pulse_trigger_us > 4000) { @@ -1174,7 +1251,7 @@ void RCOutput::timer_tick(uint32_t time_out_us) } // send dshot for all groups that support it -void RCOutput::dshot_send_groups(uint32_t time_out_us) +void RCOutput::dshot_send_groups(uint64_t time_out_us) { #ifndef DISABLE_DSHOT if (serial_group) { @@ -1283,8 +1360,8 @@ uint16_t RCOutput::create_dshot_packet(const uint16_t value, bool telem_request, */ void RCOutput::fill_DMA_buffer_dshot(uint32_t *buffer, uint8_t stride, uint16_t packet, uint16_t clockmul) { - const uint32_t DSHOT_MOTOR_BIT_0 = 7 * clockmul; - const uint32_t DSHOT_MOTOR_BIT_1 = 14 * clockmul; + const uint32_t DSHOT_MOTOR_BIT_0 = DSHOT_BIT_0_TICKS * clockmul; + const uint32_t DSHOT_MOTOR_BIT_1 = DSHOT_BIT_1_TICKS * clockmul; uint16_t i = 0; for (; i < dshot_pre; i++) { buffer[i * stride] = 0; @@ -1303,7 +1380,7 @@ void RCOutput::fill_DMA_buffer_dshot(uint32_t *buffer, uint8_t stride, uint16_t This call be called in blocking mode from the timer, in which case it waits for the DMA lock. In normal operation it doesn't wait for the DMA lock. */ -void RCOutput::dshot_send(pwm_group &group, uint32_t time_out_us) +void RCOutput::dshot_send(pwm_group &group, uint64_t time_out_us) { #ifndef DISABLE_DSHOT if (irq.waiter || (group.dshot_state != DshotState::IDLE && group.dshot_state != DshotState::RECV_COMPLETE)) { @@ -1317,7 +1394,8 @@ void RCOutput::dshot_send(pwm_group &group, uint32_t time_out_us) // if we are sharing UP channels then it might have taken a long time to get here, // if there's not enough time to actually send a pulse then cancel - if (AP_HAL::micros() + group.dshot_pulse_time_us > time_out_us) { + + if (AP_HAL::micros64() + group.dshot_pulse_time_us > time_out_us) { group.dma_handle->unlock(); return; } @@ -1328,8 +1406,9 @@ void RCOutput::dshot_send(pwm_group &group, uint32_t time_out_us) // assume that we won't be able to get the input capture lock group.bdshot.enabled = false; + uint32_t active_channels = group.ch_mask & group.en_mask; // now grab the input capture lock if we are able, we can only enable bi-dir on a group basis - if (((_bdshot.mask & group.ch_mask) == group.ch_mask) && group.has_ic()) { + if (((_bdshot.mask & active_channels) == active_channels) && group.has_ic()) { if (group.has_shared_ic_up_dma()) { // no locking required group.bdshot.enabled = true; @@ -1388,23 +1467,24 @@ void RCOutput::dshot_send(pwm_group &group, uint32_t time_out_us) #endif _bdshot.erpm[chan] = erpm; #endif - uint16_t pwm = period[chan]; - if (safety_on && !(safety_mask & (1U<<(chan+chan_offset)))) { - // safety is on, overwride pwm - pwm = 0; + // safety is on, don't output anything + continue; } - const uint16_t chan_mask = (1U<>chan_offset)) { + if ((chan_mask & _reversible_mask) != 0) { // this is a DShot-3D output, map so that 1500 PWM is zero throttle reversed if (value < 1000) { value = 1999 - value; @@ -1502,7 +1582,9 @@ void RCOutput::send_pulses_DMAR(pwm_group &group, uint32_t buffer_length) up with this great method. */ TOGGLE_PIN_DEBUG(54); - +#if STM32_DMA_SUPPORTS_DMAMUX + dmaSetRequestSource(group.dma, group.dma_up_channel); +#endif dmaStreamSetPeripheral(group.dma, &(group.pwm_drv->tim->DMAR)); stm32_cacheBufferFlush(group.dma_buffer, buffer_length); dmaStreamSetMemory0(group.dma, group.dma_buffer); @@ -1576,9 +1658,15 @@ void RCOutput::dma_cancel(pwm_group& group) chSysLock(); dmaStreamDisable(group.dma); #ifdef HAL_WITH_BIDIR_DSHOT - if (group.ic_dma_enabled()) { + if (group.ic_dma_enabled() && !group.has_shared_ic_up_dma()) { dmaStreamDisable(group.bdshot.ic_dma[group.bdshot.curr_telem_chan]); } +#if STM32_DMA_SUPPORTS_DMAMUX + // the DMA request source has been switched by the receive path, so reinstate the correct one + if (group.dshot_state == DshotState::RECV_START && group.has_shared_ic_up_dma()) { + dmaSetRequestSource(group.dma, group.dma_up_channel); + } +#endif #endif // normally the CCR registers are reset by the final 0 in the DMA buffer // since we are cancelling early they need to be reset to avoid infinite pulses @@ -1603,7 +1691,7 @@ void RCOutput::dma_cancel(pwm_group& group) While serial output is active normal output to the channel group is suspended. */ -bool RCOutput::serial_setup_output(uint8_t chan, uint32_t baudrate, uint16_t chanmask) +bool RCOutput::serial_setup_output(uint8_t chan, uint32_t baudrate, uint32_t chanmask) { // account for IOMCU channels chan -= chan_offset; @@ -1955,11 +2043,9 @@ bool RCOutput::force_safety_on(void) if (AP_BoardConfig::io_enabled()) { return iomcu.force_safety_on(); } - return false; -#else +#endif safety_state = AP_HAL::Util::SAFETY_DISARMED; return true; -#endif } /* @@ -1970,10 +2056,10 @@ void RCOutput::force_safety_off(void) #if HAL_WITH_IO_MCU if (AP_BoardConfig::io_enabled()) { iomcu.force_safety_off(); + return; } -#else - safety_state = AP_HAL::Util::SAFETY_ARMED; #endif + safety_state = AP_HAL::Util::SAFETY_ARMED; } /* @@ -2015,9 +2101,14 @@ void RCOutput::safety_update(void) } #elif HAL_WITH_IO_MCU safety_state = _safety_switch_state(); - iomcu.set_safety_mask(safety_mask); #endif +#if HAL_WITH_IO_MCU + // regardless of if we have a FMU safety pin, if we have an IOMCU we need + // to pass the BRD_SAFETY_MASK to the IOMCU + iomcu.set_safety_mask(safety_mask); +#endif + #ifdef HAL_GPIO_PIN_LED_SAFETY led_counter = (led_counter+1) % 16; const uint16_t led_pattern = safety_state==AP_HAL::Util::SAFETY_DISARMED?0x5500:0xFFFF; @@ -2065,7 +2156,7 @@ uint32_t RCOutput::protocol_bitrate(const enum output_mode mode) setup serial led output for a given channel number, with the given max number of LEDs in the chain. */ -bool RCOutput::set_serial_led_num_LEDs(const uint16_t chan, uint8_t num_leds, output_mode mode, uint16_t clock_mask) +bool RCOutput::set_serial_led_num_LEDs(const uint16_t chan, uint8_t num_leds, output_mode mode, uint32_t clock_mask) { if (!_initialised || num_leds == 0) { return false; @@ -2171,8 +2262,8 @@ void RCOutput::_set_neopixel_rgb_data(pwm_group *grp, uint8_t idx, uint8_t led, const uint8_t stride = 4; uint32_t *buf = grp->dma_buffer + (led * neopixel_bit_length + pad_start_bits) * stride + idx; uint32_t bits = (green<<16) | (red<<8) | blue; - const uint32_t BIT_0 = 7 * grp->bit_width_mul; - const uint32_t BIT_1 = 14 * grp->bit_width_mul; + const uint32_t BIT_0 = NEOP_BIT_0_TICKS * grp->bit_width_mul; + const uint32_t BIT_1 = NEOP_BIT_1_TICKS * grp->bit_width_mul; for (uint16_t b=0; b < 24; b++) { buf[b * stride] = (bits & 0x800000) ? BIT_1 : BIT_0; bits <<= 1; @@ -2190,7 +2281,7 @@ void RCOutput::_set_profiled_rgb_data(pwm_group *grp, uint8_t idx, uint8_t led, const uint8_t stride = 4; uint32_t *buf = grp->dma_buffer + (led * bit_length + pad_start_bits) * stride + idx; uint32_t bits = 0x1000000 | (blue<<16) | (red<<8) | green; - const uint32_t BIT_1 = 14 * grp->bit_width_mul; + const uint32_t BIT_1 = PROFI_BIT_1_TICKS * grp->bit_width_mul; for (uint16_t b=0; b < bit_length; b++) { buf[b * stride] = (bits & 0x1000000) ? 0 : BIT_1; bits <<= 1; @@ -2207,7 +2298,7 @@ void RCOutput::_set_profiled_blank_frame(pwm_group *grp, uint8_t idx, uint8_t le const uint8_t bit_length = 25; const uint8_t stride = 4; uint32_t *buf = grp->dma_buffer + (led * bit_length + pad_start_bits) * stride + idx; - const uint32_t BIT_1 = 14 * grp->bit_width_mul; + const uint32_t BIT_1 = PROFI_BIT_1_TICKS * grp->bit_width_mul; for (uint16_t b=0; b < bit_length; b++) { buf[b * stride] = BIT_1; } @@ -2222,7 +2313,7 @@ void RCOutput::_set_profiled_clock(pwm_group *grp, uint8_t idx, uint8_t led) const uint8_t bit_length = 25; const uint8_t stride = 4; uint32_t *buf = grp->dma_buffer + (led * bit_length + pad_start_bits) * stride + idx; - const uint32_t BIT_1 = 7 * grp->bit_width_mul; + const uint32_t BIT_1 = PROFI_BIT_0_TICKS * grp->bit_width_mul; for (uint16_t b=0; b < bit_length; b++) { buf[b * stride] = BIT_1; } @@ -2360,7 +2451,14 @@ void RCOutput::timer_info(ExpandingString &str) str.printf("TIMERV1\n"); for (auto &group : pwm_group_list) { - const uint32_t target_freq = &group == serial_group ? 19200 * 10 : protocol_bitrate(group.current_mode) * 20; + uint32_t target_freq; + if (&group == serial_group) { + target_freq = 19200 * 10; + } else if (is_dshot_protocol(group.current_mode)) { + target_freq = protocol_bitrate(group.current_mode) * DSHOT_BIT_WIDTH_TICKS; + } else { + target_freq = protocol_bitrate(group.current_mode) * NEOP_BIT_WIDTH_TICKS; + } const uint32_t prescaler = calculate_bitrate_prescaler(group.pwm_drv->clock, target_freq, is_dshot_protocol(group.current_mode)); str.printf("TIM%-2u CLK=%4uMhz MODE=%5s FREQ=%8u TGT=%8u\n", group.timer_id, unsigned(group.pwm_drv->clock / 1000000), get_output_mode_string(group.current_mode), diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.h b/libraries/AP_HAL_ChibiOS/RCOutput.h index 39708a11c05..fc22bce3da2 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.h +++ b/libraries/AP_HAL_ChibiOS/RCOutput.h @@ -19,6 +19,7 @@ #include "AP_HAL_ChibiOS.h" #include #include +#include #include "shared_dma.h" #include "ch.h" @@ -67,9 +68,14 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput return 100.0f * float(_bdshot.erpm_errors[chan]) / (1 + _bdshot.erpm_errors[chan] + _bdshot.erpm_clean_frames[chan]); } #endif - void set_output_mode(uint16_t mask, const enum output_mode mode) override; + void set_output_mode(uint32_t mask, const enum output_mode mode) override; bool get_output_mode_banner(char banner_msg[], uint8_t banner_msg_len) const override; + /* + * return mask of channels that must be disabled because they share a group with a digital channel + */ + uint32_t get_disabled_channels(uint32_t digital_mask) override; + float scale_esc_to_unity(uint16_t pwm) override { return 2.0 * ((float) pwm - _esc_pwm_min) / (_esc_pwm_max - _esc_pwm_min) - 1.0; } @@ -97,7 +103,7 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput /* timer push (for oneshot min rate) */ - void timer_tick(uint32_t last_run_us); + void timer_tick(uint64_t last_run_us); /* setup for serial output to a set of ESCs, using the given @@ -105,7 +111,7 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput databits. This is used for ESC configuration and firmware flashing */ - bool setup_serial_output(uint16_t chan_mask, ByteBuffer *buffer, uint32_t baudrate); + bool setup_serial_output(uint32_t chan_mask, ByteBuffer *buffer, uint32_t baudrate); /* setup for serial output to an ESC using the given @@ -118,7 +124,7 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput same channel timer group) may also be stopped, depending on the implementation */ - bool serial_setup_output(uint8_t chan, uint32_t baudrate, uint16_t motor_mask) override; + bool serial_setup_output(uint8_t chan, uint32_t baudrate, uint32_t motor_mask) override; /* write a set of bytes to an ESC, using settings from @@ -144,7 +150,7 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput with Dshot to get telemetry feedback The mask uses servo channel numbering */ - void set_telem_request_mask(uint16_t mask) override { telem_request_mask = (mask >> chan_offset); } + void set_telem_request_mask(uint32_t mask) override { telem_request_mask = (mask >> chan_offset); } #ifdef HAL_WITH_BIDIR_DSHOT /* @@ -152,7 +158,7 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput with Dshot to get telemetry feedback The mask uses servo channel numbering */ - void set_bidir_dshot_mask(uint16_t mask) override; + void set_bidir_dshot_mask(uint32_t mask) override; void set_motor_poles(uint8_t poles) override { _bdshot.motor_poles = poles; } #endif @@ -166,7 +172,7 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput /* Set/get the dshot esc_type */ - void set_dshot_esc_type(DshotEscType dshot_esc_type) override { _dshot_esc_type = dshot_esc_type; } + void set_dshot_esc_type(DshotEscType dshot_esc_type) override; DshotEscType get_dshot_esc_type() const override { return _dshot_esc_type; } #endif @@ -184,7 +190,7 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput /* set safety mask for IOMCU */ - void set_safety_mask(uint16_t mask) { safety_mask = mask; } + void set_safety_mask(uint32_t mask) { safety_mask = mask; } #ifndef DISABLE_DSHOT /* @@ -192,21 +198,21 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput * so that output scaling can be performed correctly. The chanmask passed is added (ORed) into any existing mask. * The mask uses servo channel numbering */ - void set_reversible_mask(uint16_t chanmask) override; + void set_reversible_mask(uint32_t chanmask) override; /* * mark the channels in chanmask as reversed. * The chanmask passed is added (ORed) into any existing mask. * The mask uses servo channel numbering */ - void set_reversed_mask(uint16_t chanmask) override; - uint16_t get_reversed_mask() override { return _reversed_mask; } + void set_reversed_mask(uint32_t chanmask) override; + uint32_t get_reversed_mask() override { return _reversed_mask << chan_offset; } /* mark escs as active for the purpose of sending dshot commands The mask uses servo channel numbering */ - void set_active_escs_mask(uint16_t chanmask) override { _active_escs_mask |= (chanmask >> chan_offset); } + void set_active_escs_mask(uint32_t chanmask) override { _active_escs_mask |= (chanmask >> chan_offset); } /* Send a dshot command, if command timout is 0 then 10 commands are sent @@ -230,7 +236,7 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput setup serial LED output for a given channel number, with the given max number of LEDs in the chain. */ - bool set_serial_led_num_LEDs(const uint16_t chan, uint8_t num_leds, output_mode mode = MODE_PWM_NONE, uint16_t clock_mask = 0) override; + bool set_serial_led_num_LEDs(const uint16_t chan, uint8_t num_leds, output_mode mode = MODE_PWM_NONE, uint32_t clock_mask = 0) override; /* setup serial LED output data for a given output channel @@ -304,9 +310,9 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput enum output_mode current_mode; uint16_t frequency_hz; // mask of channels that are able to be enabled - uint16_t ch_mask; + uint32_t ch_mask; // mask of channels that are enabled and active - uint16_t en_mask; + uint32_t en_mask; const stm32_dma_stream_t *dma; Shared_DMA *dma_handle; uint32_t *dma_buffer; @@ -315,9 +321,9 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput uint32_t bit_width_mul; uint32_t rc_frequency; bool in_serial_dma; - uint32_t last_dmar_send_us; - uint32_t dshot_pulse_time_us; - uint32_t dshot_pulse_send_time_us; + uint64_t last_dmar_send_us; + uint64_t dshot_pulse_time_us; + uint64_t dshot_pulse_send_time_us; virtual_timer_t dma_timeout; // serial LED support @@ -461,7 +467,11 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput // number of active fmu channels uint8_t active_fmu_channels; +#if NUM_SERVO_CHANNELS >= 17 + static const uint8_t max_channels = 32; +#else static const uint8_t max_channels = 16; +#endif // last sent values are for all channels uint16_t last_sent[max_channels]; @@ -472,7 +482,7 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput // handling of bi-directional dshot struct { - uint16_t mask; + uint32_t mask; uint16_t erpm[max_channels]; #ifdef HAL_WITH_BIDIR_DSHOT uint16_t erpm_errors[max_channels]; @@ -515,14 +525,14 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput #endif bool corked; // mask of channels that are running in high speed - uint16_t fast_channel_mask; - uint16_t io_fast_channel_mask; + uint32_t fast_channel_mask; + uint32_t io_fast_channel_mask; // mask of channels that are 3D capable - uint16_t _reversible_mask; + uint32_t _reversible_mask; // mask of channels that should be reversed at startup - uint16_t _reversed_mask; + uint32_t _reversed_mask; // mask of active ESCs - uint16_t _active_escs_mask; + uint32_t _active_escs_mask; // min time to trigger next pulse to prevent overlap uint64_t min_pulse_trigger_us; @@ -568,12 +578,12 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput uint8_t safety_press_count; // 0.1s units // mask of channels to allow when safety on - uint16_t safety_mask; + uint32_t safety_mask; // update safety switch and LED void safety_update(void); - uint16_t telem_request_mask; + uint32_t telem_request_mask; /* Serial lED handling. Max of 32 LEDs uses max 12k of memory per group @@ -590,13 +600,13 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput uint16_t create_dshot_packet(const uint16_t value, bool telem_request, bool bidir_telem); void fill_DMA_buffer_dshot(uint32_t *buffer, uint8_t stride, uint16_t packet, uint16_t clockmul); - void dshot_send_groups(uint32_t time_out_us); - void dshot_send(pwm_group &group, uint32_t time_out_us); + void dshot_send_groups(uint64_t time_out_us); + void dshot_send(pwm_group &group, uint64_t time_out_us); bool dshot_send_command(pwm_group &group, uint8_t command, uint8_t chan); static void dshot_update_tick(void* p); static void dshot_send_next_group(void* p); // release locks on the groups that are pending in reverse order - void dshot_collect_dma_locks(uint32_t last_run_us); + void dshot_collect_dma_locks(uint64_t last_run_us); static void dma_up_irq_callback(void *p, uint32_t flags); static void dma_unlock(void *p); void dma_cancel(pwm_group& group); diff --git a/libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp b/libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp index 6b970a13358..de77bc3a8f3 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp @@ -41,7 +41,7 @@ extern const AP_HAL::HAL& hal; * enable bi-directional telemetry request for a mask of channels. This is used * with DShot to get telemetry feedback */ -void RCOutput::set_bidir_dshot_mask(uint16_t mask) +void RCOutput::set_bidir_dshot_mask(uint32_t mask) { _bdshot.mask = (mask >> chan_offset); // we now need to reconfigure the DMA channels since they are affected by the value of the mask @@ -62,18 +62,12 @@ bool RCOutput::bdshot_setup_group_ic_DMA(pwm_group &group) return true; } - bool set_curr_chan = false; - + // allocate input capture DMA handles for (uint8_t i = 0; i < 4; i++) { if (!group.is_chan_enabled(i) || !group.dma_ch[i].have_dma || !(_bdshot.mask & (1 << group.chan[i]))) { continue; } - // make sure we don't start on a disabled channel - if (!set_curr_chan) { - group.bdshot.curr_telem_chan = i; - set_curr_chan = true; - } pwmmode_t mode = group.pwm_cfg.channels[i].mode; if (mode == PWM_COMPLEMENTARY_OUTPUT_ACTIVE_LOW || mode == PWM_COMPLEMENTARY_OUTPUT_ACTIVE_HIGH) { @@ -99,6 +93,15 @@ bool RCOutput::bdshot_setup_group_ic_DMA(pwm_group &group) // We might need to do sharing of timers for telemetry feedback // due to lack of available DMA channels for (uint8_t i = 0; i < 4; i++) { + // we must pull all the allocated channels high to prevent them going low + // when the pwm peripheral is stopped + if (group.chan[i] != CHAN_DISABLED && _bdshot.mask & group.ch_mask) { + // bi-directional dshot requires less than MID2 speed and PUSHPULL in order to avoid noise on the line + // when switching from output to input + palSetLineMode(group.pal_lines[i], PAL_MODE_ALTERNATE(group.alt_functions[i]) + | PAL_STM32_OTYPE_PUSHPULL | PAL_STM32_PUPDR_PULLUP | PAL_STM32_OSPEED_MID1); + } + if (!group.is_chan_enabled(i) || !(_bdshot.mask & (1 << group.chan[i]))) { continue; } @@ -137,10 +140,14 @@ bool RCOutput::bdshot_setup_group_ic_DMA(pwm_group &group) group.bdshot.telem_tim_ch[i] = curr_chan; group.dma_ch[i] = group.dma_ch[curr_chan]; } - // bi-directional dshot requires less than MID2 speed and PUSHPULL in order to avoid noise on the line - // when switching from output to input - palSetLineMode(group.pal_lines[i], PAL_MODE_ALTERNATE(group.alt_functions[i]) - | PAL_STM32_OTYPE_PUSHPULL | PAL_STM32_PUPDR_PULLUP | PAL_STM32_OSPEED_MID1); + } + + // now allocate the starting channel + for (uint8_t i = 0; i < 4; i++) { + if (group.chan[i] != CHAN_DISABLED && group.bdshot.ic_dma_handle[i] != nullptr) { + group.bdshot.curr_telem_chan = i; + break; + } } return true; @@ -470,7 +477,7 @@ __RAMFUNC__ void RCOutput::dma_up_irq_callback(void *p, uint32_t flags) } // check nothing bad happened - if ((flags & STM32_DMA_ISR_TEIF) != 0) { + if ((flags & (STM32_DMA_ISR_TEIF | STM32_DMA_ISR_DMEIF)) != 0) { INTERNAL_ERROR(AP_InternalError::error_t::dma_fail); } dmaStreamDisable(group->dma); @@ -503,7 +510,7 @@ __RAMFUNC__ void RCOutput::bdshot_dma_ic_irq_callback(void *p, uint32_t flags) chSysLockFromISR(); // check nothing bad happened - if ((flags & STM32_DMA_ISR_TEIF) != 0) { + if ((flags & (STM32_DMA_ISR_TEIF | STM32_DMA_ISR_DMEIF)) != 0) { INTERNAL_ERROR(AP_InternalError::error_t::dma_fail); } diff --git a/libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp b/libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp index 13a5578c02e..67a162fb87d 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp @@ -38,7 +38,9 @@ bool RCOutput::dshot_send_command(pwm_group& group, uint8_t command, uint8_t cha return false; } +#ifdef HAL_GPIO_LINE_GPIO81 TOGGLE_PIN_DEBUG(81); +#endif // first make sure we have the DMA channel before anything else osalDbgAssert(!group.dma_handle->is_locked(), "DMA handle is already locked"); @@ -48,9 +50,10 @@ bool RCOutput::dshot_send_command(pwm_group& group, uint8_t command, uint8_t cha group.dshot_waiter = rcout_thread_ctx; bool bdshot_telem = false; #ifdef HAL_WITH_BIDIR_DSHOT + uint32_t active_channels = group.ch_mask & group.en_mask; // no need to get the input capture lock group.bdshot.enabled = false; - if ((_bdshot.mask & group.ch_mask) == group.ch_mask) { + if ((_bdshot.mask & active_channels) == active_channels) { bdshot_telem = true; // it's not clear why this is required, but without it we get no output if (group.pwm_started) { @@ -68,9 +71,13 @@ bool RCOutput::dshot_send_command(pwm_group& group, uint8_t command, uint8_t cha const uint16_t packet = create_dshot_packet(command, true, bdshot_telem); for (uint8_t i = 0; i < 4; i++) { - if (group.chan[i] == chan || (chan == RCOutput::ALL_CHANNELS && group.is_chan_enabled(i))) { + if (!group.is_chan_enabled(i)) { + continue; + } + + if (group.chan[i] == chan || chan == RCOutput::ALL_CHANNELS) { fill_DMA_buffer_dshot(group.dma_buffer + i, 4, packet, group.bit_width_mul); - } else if (group.is_chan_enabled(i)) { + } else { fill_DMA_buffer_dshot(group.dma_buffer + i, 4, zero_packet, group.bit_width_mul); } } @@ -78,7 +85,9 @@ bool RCOutput::dshot_send_command(pwm_group& group, uint8_t command, uint8_t cha chEvtGetAndClearEvents(group.dshot_event_mask); // start sending the pulses out send_pulses_DMAR(group, DSHOT_BUFFER_LENGTH); +#ifdef HAL_GPIO_LINE_GPIO81 TOGGLE_PIN_DEBUG(81); +#endif return true; } @@ -98,7 +107,7 @@ void RCOutput::send_dshot_command(uint8_t command, uint8_t chan, uint32_t comman DshotCommandPacket pkt; pkt.command = command; - pkt.chan = chan + chan_offset; + pkt.chan = chan - chan_offset; if (command_timeout_ms == 0) { pkt.cycle = MAX(10, repeat_count); } else { @@ -114,14 +123,14 @@ void RCOutput::send_dshot_command(uint8_t command, uint8_t chan, uint32_t comman // Set the dshot outputs that should be reversed (as opposed to 3D) // The chanmask passed is added (ORed) into any existing mask. // The mask uses servo channel numbering -void RCOutput::set_reversed_mask(uint16_t chanmask) { +void RCOutput::set_reversed_mask(uint32_t chanmask) { _reversed_mask |= (chanmask >> chan_offset); } // Set the dshot outputs that should be reversible/3D // The chanmask passed is added (ORed) into any existing mask. // The mask uses servo channel numbering -void RCOutput::set_reversible_mask(uint16_t chanmask) { +void RCOutput::set_reversible_mask(uint32_t chanmask) { _reversible_mask |= (chanmask >> chan_offset); } @@ -137,11 +146,12 @@ void RCOutput::update_channel_masks() { for (uint8_t i=0; i(new SPIDevice(*busp, desc)); } +void SPIDeviceManager::set_register_rw_callback(const char* name, AP_HAL::Device::RegisterRWCb cb) +{ + /* Find the bus description in the table */ + uint8_t i; + for (i = 0; iprintf("Waiting for USB\n"); + DEV_PRINTF("Waiting for USB\n"); for (uint8_t i=0; i<3; i++) { hal.scheduler->delay(1000); - hal.console->printf("Waiting %u\n", (unsigned)AP_HAL::millis()); + DEV_PRINTF("Waiting %u\n", (unsigned)AP_HAL::millis()); } - hal.console->printf("CLOCKS=\n"); + DEV_PRINTF("CLOCKS=\n"); for (uint8_t i=0; iprintf("%u:%u ", unsigned(i+1), unsigned(bus_clocks[i])); + DEV_PRINTF("%u:%u ", unsigned(i+1), unsigned(bus_clocks[i])); } - hal.console->printf("\n"); + DEV_PRINTF("\n"); // we will send 1024 bytes without any CS asserted and measure the // time it takes to do the transfer @@ -481,11 +500,11 @@ void SPIDevice::test_clock_freq(void) uint32_t t0 = AP_HAL::micros(); spiStartExchange(spi_devices[i].driver, len, buf1, buf2); chSysLock(); - msg_t msg = osalThreadSuspendTimeoutS(&spi_devices[i].driver->thread, TIME_MS2I(100)); + msg_t msg = osalThreadSuspendTimeoutS(&spi_devices[i].driver->thread, chTimeMS2I(100)); chSysUnlock(); if (msg == MSG_TIMEOUT) { spiAbort(spi_devices[i].driver); - hal.console->printf("SPI[%u] FAIL %p %p\n", spi_devices[i].busid, buf1, buf2); + DEV_PRINTF("SPI[%u] FAIL %p %p\n", spi_devices[i].busid, buf1, buf2); spiStop(spi_devices[i].driver); spiReleaseBus(spi_devices[i].driver); continue; @@ -493,7 +512,7 @@ void SPIDevice::test_clock_freq(void) uint32_t t1 = AP_HAL::micros(); spiStop(spi_devices[i].driver); spiReleaseBus(spi_devices[i].driver); - hal.console->printf("SPI[%u] clock=%u\n", unsigned(spi_devices[i].busid), unsigned(1000000ULL * len * 8ULL / uint64_t(t1 - t0))); + DEV_PRINTF("SPI[%u] clock=%u\n", unsigned(spi_devices[i].busid), unsigned(1000000ULL * len * 8ULL / uint64_t(t1 - t0))); } hal.util->free_type(buf1, len, AP_HAL::Util::MEM_DMA_SAFE); hal.util->free_type(buf2, len, AP_HAL::Util::MEM_DMA_SAFE); diff --git a/libraries/AP_HAL_ChibiOS/SPIDevice.h b/libraries/AP_HAL_ChibiOS/SPIDevice.h index aa1e48ad3c7..325fc264604 100644 --- a/libraries/AP_HAL_ChibiOS/SPIDevice.h +++ b/libraries/AP_HAL_ChibiOS/SPIDevice.h @@ -52,7 +52,7 @@ struct SPIDesc { : name(_name), bus(_bus), device(_device), pal_line(_pal_line), mode(_mode), lowspeed(_lowspeed), highspeed(_highspeed), - bank_select_cb(nullptr) + bank_select_cb(nullptr), register_rw_cb(nullptr) { } @@ -64,6 +64,7 @@ struct SPIDesc { uint32_t lowspeed; uint32_t highspeed; AP_HAL::Device::BankSelectCb bank_select_cb; + AP_HAL::Device::RegisterRWCb register_rw_cb; }; @@ -160,6 +161,8 @@ class SPIDeviceManager : public AP_HAL::SPIDeviceManager { AP_HAL::OwnPtr get_device(const char *name) override; + void set_register_rw_callback(const char* name, AP_HAL::Device::RegisterRWCb cb) override; + private: static SPIDesc device_table[]; SPIBus *buses; diff --git a/libraries/AP_HAL_ChibiOS/Scheduler.cpp b/libraries/AP_HAL_ChibiOS/Scheduler.cpp index c8a566c6091..b0beb3f4770 100644 --- a/libraries/AP_HAL_ChibiOS/Scheduler.cpp +++ b/libraries/AP_HAL_ChibiOS/Scheduler.cpp @@ -226,7 +226,7 @@ void Scheduler::register_timer_process(AP_HAL::MemberProc proc) _timer_proc[_num_timer_procs] = proc; _num_timer_procs++; } else { - hal.console->printf("Out of timer processes\n"); + DEV_PRINTF("Out of timer processes\n"); } chBSemSignal(&_timer_semaphore); } @@ -245,7 +245,7 @@ void Scheduler::register_io_process(AP_HAL::MemberProc proc) _io_proc[_num_io_procs] = proc; _num_io_procs++; } else { - hal.console->printf("Out of IO processes\n"); + DEV_PRINTF("Out of IO processes\n"); } chBSemSignal(&_io_semaphore); } @@ -410,19 +410,22 @@ void Scheduler::_monitor_thread(void *arg) #if HAL_LOGGING_ENABLED const AP_HAL::Util::PersistentData &pd = hal.util->persistent_data; if (AP_Logger::get_singleton()) { - AP::logger().Write("MON", "TimeUS,LDelay,Task,IErr,IErrCnt,IErrLn,MavMsg,MavCmd,SemLine,SPICnt,I2CCnt", "QIbIHHHHHII", - AP_HAL::micros64(), - loop_delay, - pd.scheduler_task, - pd.internal_errors, - pd.internal_error_count, - pd.internal_error_last_line, - pd.last_mavlink_msgid, - pd.last_mavlink_cmd, - pd.semaphore_line, - pd.spi_count, - pd.i2c_count); - } + const struct log_MON mon{ + LOG_PACKET_HEADER_INIT(LOG_MON_MSG), + time_us : AP_HAL::micros64(), + loop_delay : loop_delay, + current_task : pd.scheduler_task, + internal_error_mask : pd.internal_errors, + internal_error_count : pd.internal_error_count, + internal_error_line : pd.internal_error_last_line, + mavmsg : pd.last_mavlink_msgid, + mavcmd : pd.last_mavlink_cmd, + semline : pd.semaphore_line, + spicnt : pd.spi_count, + i2ccnt : pd.i2c_count + }; + AP::logger().WriteCriticalBlock(&mon, sizeof(mon)); + } #endif } if (loop_delay >= 500 && !sched->in_expected_delay()) { @@ -435,22 +438,26 @@ void Scheduler::_monitor_thread(void *arg) log_wd_counter = 0; // log watchdog message once a second const AP_HAL::Util::PersistentData &pd = hal.util->last_persistent_data; - AP::logger().WriteCritical("WDOG", "TimeUS,Tsk,IE,IEC,IEL,MvMsg,MvCmd,SmLn,FL,FT,FA,FP,ICSR,LR,TN", "QbIHHHHHHHIBIIn", - AP_HAL::micros64(), - pd.scheduler_task, - pd.internal_errors, - pd.internal_error_count, - pd.internal_error_last_line, - pd.last_mavlink_msgid, - pd.last_mavlink_cmd, - pd.semaphore_line, - pd.fault_line, - pd.fault_type, - pd.fault_addr, - pd.fault_thd_prio, - pd.fault_icsr, - pd.fault_lr, - pd.thread_name4); + struct log_WDOG wdog{ + LOG_PACKET_HEADER_INIT(LOG_WDOG_MSG), + time_us : AP_HAL::micros64(), + scheduler_task : pd.scheduler_task, + internal_errors : pd.internal_errors, + internal_error_count : pd.internal_error_count, + internal_error_last_line : pd.internal_error_last_line, + last_mavlink_msgid : pd.last_mavlink_msgid, + last_mavlink_cmd : pd.last_mavlink_cmd, + semaphore_line : pd.semaphore_line, + fault_line : pd.fault_line, + fault_type : pd.fault_type, + fault_addr : pd.fault_addr, + fault_thd_prio : pd.fault_thd_prio, + fault_icsr : pd.fault_icsr, + fault_lr : pd.fault_lr + }; + memcpy(wdog.thread_name4, pd.thread_name4, ARRAY_SIZE(wdog.thread_name4)); + + AP::logger().WriteCriticalBlock(&wdog, sizeof(wdog)); } #endif // HAL_LOGGING_ENABLED diff --git a/libraries/AP_HAL_ChibiOS/Scheduler.h b/libraries/AP_HAL_ChibiOS/Scheduler.h index 301ab7e824e..95a9ce4d55e 100644 --- a/libraries/AP_HAL_ChibiOS/Scheduler.h +++ b/libraries/AP_HAL_ChibiOS/Scheduler.h @@ -76,7 +76,7 @@ #endif #ifndef MONITOR_THD_WA_SIZE -#define MONITOR_THD_WA_SIZE 512 +#define MONITOR_THD_WA_SIZE 1024 #endif /* Scheduler implementation: */ diff --git a/libraries/AP_HAL_ChibiOS/Storage.cpp b/libraries/AP_HAL_ChibiOS/Storage.cpp index 4bcd9744c24..56bc9d822d2 100644 --- a/libraries/AP_HAL_ChibiOS/Storage.cpp +++ b/libraries/AP_HAL_ChibiOS/Storage.cpp @@ -346,6 +346,7 @@ void Storage::_flash_load(void) bool Storage::_flash_write(uint16_t line) { #ifdef STORAGE_FLASH_PAGE + EXPECT_DELAY_MS(1); return _flash.write(line*CH_STORAGE_LINE_SIZE, CH_STORAGE_LINE_SIZE); #else return false; @@ -360,6 +361,7 @@ bool Storage::_flash_write_data(uint8_t sector, uint32_t offset, const uint8_t * #ifdef STORAGE_FLASH_PAGE size_t base_address = hal.flash->getpageaddr(_flash_page+sector); for (uint8_t i=0; iwrite(base_address+offset, data, length)) { return true; } @@ -412,13 +414,10 @@ bool Storage::_flash_erase_sector(uint8_t sector) thread. We can't use EXPECT_DELAY_MS() as it checks we are in the main thread */ - ChibiOS::Scheduler *sched = (ChibiOS::Scheduler *)hal.scheduler; - sched->_expect_delay_ms(1000); + EXPECT_DELAY_MS(1000); if (hal.flash->erasepage(_flash_page+sector)) { - sched->_expect_delay_ms(0); return true; } - sched->_expect_delay_ms(0); hal.scheduler->delay(1); } return false; diff --git a/libraries/AP_HAL_ChibiOS/Storage.h b/libraries/AP_HAL_ChibiOS/Storage.h index 54577f67ef4..beccd623b18 100644 --- a/libraries/AP_HAL_ChibiOS/Storage.h +++ b/libraries/AP_HAL_ChibiOS/Storage.h @@ -30,7 +30,11 @@ // when using flash storage we use a small line size to make storage // compact and minimise the number of erase cycles needed #ifdef STORAGE_FLASH_PAGE +#if defined(STM32H7XX) +#define CH_STORAGE_LINE_SHIFT 4 +#else #define CH_STORAGE_LINE_SHIFT 3 +#endif #elif defined(USE_POSIX) && !defined(HAL_WITH_RAMTRON) #define CH_STORAGE_LINE_SHIFT 9 #else diff --git a/libraries/AP_HAL_ChibiOS/UARTDriver.cpp b/libraries/AP_HAL_ChibiOS/UARTDriver.cpp index edbea114710..bd55494bfec 100644 --- a/libraries/AP_HAL_ChibiOS/UARTDriver.cpp +++ b/libraries/AP_HAL_ChibiOS/UARTDriver.cpp @@ -573,6 +573,7 @@ __RAMFUNC__ void UARTDriver::rxbuff_full_irq(void* self, uint32_t flags) we have data to copy out */ uart_drv->_readbuf.write(uart_drv->rx_bounce_buf[bounce_idx], len); + uart_drv->_rx_stats_bytes += len; uart_drv->receive_timestamp_update(); } @@ -634,7 +635,7 @@ void UARTDriver::flush() sduSOFHookI((SerialUSBDriver*)sdef.serial); #endif } else { - //TODO: Handle this for other serial ports + chEvtSignal(uart_thread_ctx, EVT_TRANSMIT_DATA_READY); } } @@ -664,20 +665,12 @@ uint32_t UARTDriver::get_usb_baud() const return 0; } -/* Empty implementations of Stream virtual methods */ uint32_t UARTDriver::available() { - if (!_rx_initialised || lock_read_key) { + if (!_rx_initialised || _uart_owner_thd != chThdGetSelfX()) { return 0; } - if (sdef.is_usb) { -#ifdef HAVE_USB_SERIAL - if (((SerialUSBDriver*)sdef.serial)->config->usbp->state != USB_ACTIVE) { - return 0; - } -#endif - } - return _readbuf.available(); + return UARTDriver::available_locked(0); } uint32_t UARTDriver::available_locked(uint32_t key) @@ -745,22 +738,11 @@ ssize_t UARTDriver::read(uint8_t *buffer, uint16_t count) int16_t UARTDriver::read() { - if (lock_read_key != 0 || _uart_owner_thd != chThdGetSelfX()){ - return -1; - } - if (!_rx_initialised) { + if (_uart_owner_thd != chThdGetSelfX()) { return -1; } - uint8_t byte; - if (!_readbuf.read_byte(&byte)) { - return -1; - } - if (!_rts_is_active) { - update_rts_line(); - } - - return byte; + return UARTDriver::read_locked(0); } int16_t UARTDriver::read_locked(uint32_t key) @@ -1021,7 +1003,7 @@ void UARTDriver::write_pending_bytes_DMA(uint32_t n) if (tx_len > 0) { _last_write_completed_us = AP_HAL::micros(); } - chEvtGetAndClearEvents(EVT_TRANSMIT_DMA_COMPLETE); + chEvtGetAndClearEventsI(EVT_TRANSMIT_DMA_COMPLETE); chSysUnlock(); } // clean up pending locks @@ -1156,7 +1138,7 @@ void UARTDriver::write_pending_bytes(void) } if (AP_HAL::micros() - _first_write_started_us > 500*1000UL) { // it doesn't look like hw flow control is working - hal.console->printf("disabling flow control on serial %u\n", sdef.get_index()); + DEV_PRINTF("disabling flow control on serial %u\n", sdef.get_index()); set_flow_control(FLOW_CONTROL_DISABLE); } } diff --git a/libraries/AP_HAL_ChibiOS/UARTDriver.h b/libraries/AP_HAL_ChibiOS/UARTDriver.h index a770d982ecb..4bf86f2bb71 100644 --- a/libraries/AP_HAL_ChibiOS/UARTDriver.h +++ b/libraries/AP_HAL_ChibiOS/UARTDriver.h @@ -141,6 +141,8 @@ class ChibiOS::UARTDriver : public AP_HAL::UARTDriver { return _baudrate/(9*1024); } + uint32_t get_baud_rate() const override { return _baudrate; } + #if HAL_UART_STATS_ENABLED // request information on uart I/O for one uart void uart_info(ExpandingString &str) override; diff --git a/libraries/AP_HAL_ChibiOS/Util.cpp b/libraries/AP_HAL_ChibiOS/Util.cpp index 0b91931d78f..b4458d4f9df 100644 --- a/libraries/AP_HAL_ChibiOS/Util.cpp +++ b/libraries/AP_HAL_ChibiOS/Util.cpp @@ -45,6 +45,10 @@ extern AP_IOMCU iomcu; #endif +#if AP_SIGNED_FIRMWARE && !defined(HAL_BOOTLOADER_BUILD) +#include +#endif + extern const AP_HAL::HAL& hal; using namespace ChibiOS; @@ -86,16 +90,11 @@ void Util::free_type(void *ptr, size_t size, AP_HAL::Util::Memory_Type mem_type) void *Util::allocate_heap_memory(size_t size) { - void *buf = malloc(size); - if (buf == nullptr) { + memory_heap_t *heap = (memory_heap_t *)malloc(size + sizeof(memory_heap_t)); + if (heap == nullptr) { return nullptr; } - - memory_heap_t *heap = (memory_heap_t *)malloc(sizeof(memory_heap_t)); - if (heap != nullptr) { - chHeapObjectInit(heap, buf, size); - } - + chHeapObjectInit(heap, heap + 1U, size); return heap; } @@ -273,6 +272,18 @@ Util::FlashBootloader Util::flash_bootloader() Debug("failed to find %s\n", fw_name); return FlashBootloader::NOT_AVAILABLE; } + +#if AP_SIGNED_FIRMWARE + if (!AP_CheckFirmware::check_signed_bootloader(fw, fw_size)) { + // don't allow flashing of an unsigned bootloader in a secure + // setup. This prevents the easy mistake of leaving an + // unsigned bootloader in ROMFS, which would give a trivail + // way to bypass signing + AP_ROMFS::free(fw); + return FlashBootloader::NOT_SIGNED; + } +#endif + // make sure size is multiple of 32 fw_size = (fw_size + 31U) & ~31U; @@ -361,22 +372,24 @@ Util::FlashBootloader Util::flash_bootloader() /* display system identifer - board type and serial number */ -bool Util::get_system_id(char buf[40]) +bool Util::get_system_id(char buf[50]) { uint8_t serialid[12]; - char board_name[14]; + char board_name[24]; memcpy(serialid, (const void *)UDID_START, 12); - strncpy(board_name, CHIBIOS_SHORT_BOARD_NAME, 13); - board_name[13] = 0; + // avoid board names greater than 23 chars (sizeof includes null char, so allow 24 bytes total) + static_assert(sizeof(CHIBIOS_SHORT_BOARD_NAME) <= 24, "CHIBIOS_SHORT_BOARD_NAME must be 23 characters or less"); + strncpy(board_name, CHIBIOS_SHORT_BOARD_NAME, 23); + board_name[23] = 0; // this format is chosen to match the format used by HAL_PX4 - snprintf(buf, 40, "%s %02X%02X%02X%02X %02X%02X%02X%02X %02X%02X%02X%02X", + snprintf(buf, 50, "%s %02X%02X%02X%02X %02X%02X%02X%02X %02X%02X%02X%02X", board_name, (unsigned)serialid[3], (unsigned)serialid[2], (unsigned)serialid[1], (unsigned)serialid[0], (unsigned)serialid[7], (unsigned)serialid[6], (unsigned)serialid[5], (unsigned)serialid[4], (unsigned)serialid[11], (unsigned)serialid[10], (unsigned)serialid[9],(unsigned)serialid[8]); - buf[39] = 0; + buf[49] = 0; return true; } @@ -466,7 +479,7 @@ __RAMFUNC__ void Util::thread_info(ExpandingString &str) // request information on dma contention void Util::dma_info(ExpandingString &str) { -#ifndef HAL_NO_SHARED_DMA +#if AP_HAL_SHARED_DMA_ENABLED ChibiOS::Shared_DMA::dma_info(str); #endif } @@ -587,7 +600,7 @@ void Util::apply_persistent_params(void) const errors++; break; } - if (!ap->configured_in_storage()) { + if (!ap->configured()) { ap->save(); } } @@ -727,10 +740,9 @@ void Util::log_stack_info(void) #endif } -#if !defined(HAL_BOOTLOADER_BUILD) +#if AP_CRASHDUMP_ENABLED size_t Util::last_crash_dump_size() const { -#if HAL_GCS_ENABLED && HAL_CRASHDUMP_ENABLE // get dump size uint32_t size = stm32_crash_dump_size(); char* dump_start = (char*)stm32_crash_dump_addr(); @@ -743,22 +755,25 @@ size_t Util::last_crash_dump_size() const size = stm32_crash_dump_max_size(); } return size; -#endif - return 0; } void* Util::last_crash_dump_ptr() const { -#if HAL_GCS_ENABLED && HAL_CRASHDUMP_ENABLE if (last_crash_dump_size() == 0) { return nullptr; } return (void*)stm32_crash_dump_addr(); -#else - return nullptr; -#endif } -#endif // HAL_BOOTLOADER_BUILD +#endif // AP_CRASHDUMP_ENABLED + +#if HAL_ENABLE_DFU_BOOT && !defined(HAL_BOOTLOADER_BUILD) +void Util::boot_to_dfu() +{ + hal.util->persistent_data.boot_to_dfu = true; + stm32_watchdog_save((uint32_t *)&hal.util->persistent_data, (sizeof(hal.util->persistent_data)+3)/4); + hal.scheduler->reboot(false); +} +#endif // set armed state void Util::set_soft_armed(const bool b) diff --git a/libraries/AP_HAL_ChibiOS/Util.h b/libraries/AP_HAL_ChibiOS/Util.h index d5072477e28..53d5880bd5b 100644 --- a/libraries/AP_HAL_ChibiOS/Util.h +++ b/libraries/AP_HAL_ChibiOS/Util.h @@ -20,6 +20,9 @@ #include "AP_HAL_ChibiOS_Namespace.h" #include "AP_HAL_ChibiOS.h" #include +#if !defined(HAL_BOOTLOADER_BUILD) +#include +#endif class ExpandingString; @@ -56,7 +59,7 @@ class ChibiOS::Util : public AP_HAL::Util { enum safety_state safety_switch_state(void) override; // get system ID as a string - bool get_system_id(char buf[40]) override; + bool get_system_id(char buf[50]) override; bool get_system_id_unformatted(uint8_t buf[], uint8_t &len) override; bool toneAlarm_init(uint8_t types) override; @@ -146,10 +149,13 @@ class ChibiOS::Util : public AP_HAL::Util { // log info on stack usage void log_stack_info(void) override; -#if !defined(HAL_BOOTLOADER_BUILD) +#if AP_CRASHDUMP_ENABLED // get last crash dump size_t last_crash_dump_size() const override; void* last_crash_dump_ptr() const override; #endif +#if HAL_ENABLE_DFU_BOOT + void boot_to_dfu() override; +#endif }; diff --git a/libraries/AP_HAL_ChibiOS/hwdef/AIRLink/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/AIRLink/hwdef.dat index 5d21b5c6d4b..b7970d60995 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/AIRLink/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/AIRLink/hwdef.dat @@ -21,7 +21,7 @@ FLASH_SIZE_KB 2048 env OPTIMIZE -O2 # order of UARTs (and USB) -SERIAL_ORDER OTG1 UART7 UART5 USART1 UART8 USART3 OTG2 +SERIAL_ORDER OTG1 UART7 UART5 USART1 UART8 USART3 USART2 OTG2 # default the 2nd interface to MAVLink2 define HAL_OTG1_PROTOCOL SerialProtocol_MAVLink2 @@ -83,10 +83,11 @@ PD15 VDD_3V3_SENSORS2_EN OUTPUT HIGH PE7 VDD_3V3_SENSORS3_EN OUTPUT HIGH PG8 VDD_3V3_SENSORS4_EN OUTPUT HIGH -# start peripheral power off, then enable after init -# this prevents a problem with radios that use RTS for -# bootloader hold -PF12 nVDD_5V_HIPOWER_EN OUTPUT HIGH +# enable peripherals power pin +PF12 VDD_5V_HIPOWER_EN OUTPUT HIGH + +# enable LTE module power pin +PG4 VDD_3V5_LTE_EN OUTPUT HIGH # drdy pins PF2 DRDY4_ICM20602 INPUT @@ -182,6 +183,10 @@ define HAL_HEATER_GPIO_PIN 80 # heater is on when pulled low define HAL_HEATER_GPIO_ON 0 +define HAL_HAVE_IMU_HEATER 1 +define HAL_IMU_TEMP_DEFAULT 45 +define HAL_IMUHEAT_P_DEFAULT 50 +define HAL_IMUHEAT_I_DEFAULT 0.07 # SPI devices SPIDEV icm20602 SPI1 DEVID1 ICM20602_CS MODE3 2*MHZ 8*MHZ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ARKV6X/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/ARKV6X/hwdef-bl.dat new file mode 100644 index 00000000000..4dc19548f3c --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/ARKV6X/hwdef-bl.dat @@ -0,0 +1,76 @@ +# hw definition file for processing by chibios_hwdef.py +# for the ARKV6X hardware + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# board ID for firmware load +APJ_BOARD_ID 57 + +# bootloader is installed at zero offset +FLASH_RESERVE_START_KB 0 + +# the location where the bootloader will put the firmware +FLASH_BOOTLOADER_LOAD_KB 128 + +# flash size +FLASH_SIZE_KB 2048 + +env OPTIMIZE -Os + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 UART7 UART5 USART3 + +# default to all pins low to avoid ESD issues +DEFAULTGPIO OUTPUT LOW PULLDOWN + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 +PA9 VBUS INPUT OPENDRAIN + +# pins for SWD debugging +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# CS pins +PI9 IMU1_CS CS +PH5 ICM42688_CS CS +PI4 BMI088_A_CS CS +PI8 BMI088_G_CS CS +PH15 BMM150_CS CS +PG7 FRAM_CS CS +PI10 EXT1_CS CS + +# telem1 +PE8 UART7_TX UART7 +PF6 UART7_RX UART7 + +# telem2 +PC12 UART5_TX UART5 +PD2 UART5_RX UART5 + +# debug uart +PD8 USART3_TX USART3 +PD9 USART3_RX USART3 + +# armed indication +PE6 nARMED OUTPUT HIGH + +# start peripheral power off +PF12 nVDD_5V_HIPOWER_EN OUTPUT HIGH +PG4 nVDD_5V_PERIPH_EN OUTPUT HIGH + +# LEDs +PE3 LED_ACTIVITY OUTPUT OPENDRAIN HIGH # red +PE5 LED_BOOTLOADER OUTPUT OPENDRAIN HIGH # blue +define HAL_LED_ON 0 + +define HAL_USE_EMPTY_STORAGE 1 +define HAL_STORAGE_SIZE 16384 + +# enable DFU by default +ENABLE_DFU_BOOT 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ARKV6X/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/ARKV6X/hwdef.dat new file mode 100644 index 00000000000..8e97ea73aad --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/ARKV6X/hwdef.dat @@ -0,0 +1,331 @@ +# hw definition file for processing by chibios_hwdef.py +# for the ARKV6X hardware + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# ChibiOS system timer +STM32_ST_USE_TIMER 2 + +# board ID for firmware load +APJ_BOARD_ID 57 + +# Enable all IMUs to be used and therefore three active EKF Lanes +define HAL_EKF_IMU_MASK_DEFAULT 7 + +FLASH_RESERVE_START_KB 128 + +# to be compatible with the px4 bootloader we need +# to use a different RAM_MAP +env USE_ALT_RAM_MAP 1 + +# flash size +FLASH_SIZE_KB 2048 + +env OPTIMIZE -O2 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 UART7 UART5 USART1 UART8 USART2 UART4 USART3 OTG2 + +# default the 2nd interface to MAVLink2 +define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2 + +# default to all pins low to avoid ESD issues +DEFAULTGPIO OUTPUT LOW PULLDOWN + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 +PA9 VBUS INPUT OPENDRAIN + +# pins for SWD debugging +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# telem1 +PE8 UART7_TX UART7 +PF6 UART7_RX UART7 +PF8 UART7_RTS UART7 +PE10 UART7_CTS UART7 + +# telem2 +PC8 UART5_RTS UART5 +PC9 UART5_CTS UART5 +PC12 UART5_TX UART5 +PD2 UART5_RX UART5 + +# telem3 +PA3 USART2_RX USART2 +PD5 USART2_TX USART2 +PD3 USART2_CTS USART2 +PD4 USART2_RTS USART2 + +# GPS1 +PB6 USART1_TX USART1 +PB7 USART1_RX USART1 + +# GPS2 +PE0 UART8_RX UART8 +PE1 UART8_TX UART8 + +# uart4 +PH13 UART4_TX UART4 +PH14 UART4_RX UART4 + +# debug uart +PD8 USART3_TX USART3 +PD9 USART3_RX USART3 + +# USART6 is for IOMCU +PC6 USART6_TX USART6 +PC7 USART6_RX USART6 +IOMCU_UART USART6 + +# uart6, RX only, RC input, if no IOMCU +# PC7 USART6_RX USART6 + +# ethernet (not implemented yet) +#PA1 ETH_REF_CLK +#PA2 ETH_MDIO +#PA7 ETH_CRS_DV +#PB11 ETH_TX_EN +#PC1 ETH_MDC +#PC4 ETH_RXD0 +#PC5 ETH_RXD1 +#PG12 ETH_TXD1 +#PG13 ETH_TXD0 +#PG15 ETH_POWER_EN + +# ADC +PA0 SCALED1_V3V3 ADC1 SCALE(2) +PA4 SCALED2_V3V3 ADC1 SCALE(2) +PB0 SCALED3_V3V3 ADC1 SCALE(2) +PF12 SCALED4_V3V3 ADC1 SCALE(2) + +PB1 VDD_5V_SENS ADC1 SCALE(2) + +# pin7 on AD&IO, analog 12 +PC2 ADC1_6V6 ADC1 SCALE(2) + +# pin6 on AD&IO, analog 13 +PC3 ADC1_3V3 ADC1 SCALE(1) + +# SPI1 - IIM42652 +PA5 SPI1_SCK SPI1 +PB5 SPI1_MOSI SPI1 +PG9 SPI1_MISO SPI1 +PI9 IMU1_CS CS +PF2 IMU1_DRDY INPUT + +# SPI2 - ICM42688 +PI1 SPI2_SCK SPI2 +PI2 SPI2_MISO SPI2 +PI3 SPI2_MOSI SPI2 +PH5 IMU2_CS CS +PA10 IMU2_DRDY INPUT + +# SPI3 - ICM42688 +PB2 SPI3_MOSI SPI3 +PC10 SPI3_SCK SPI3 +PC11 SPI3_MISO SPI3 +PI4 IMU3_CS CS +PI6 IMU3_DRDY INPUT + +# SPI5 - FRAM +PF7 SPI5_SCK SPI5 +PH7 SPI5_MISO SPI5 +PF11 SPI5_MOSI SPI5 +PG7 FRAM_CS CS + +# SPI6 - external1 (disabled to save DMA channels) +# PB3 SPI6_SCK SPI6 +# PA6 SPI6_MISO SPI6 +# PG14 SPI6_MOSI SPI6 +# PI10 EXT1_CS CS + +# PWM output pins +PI0 TIM5_CH4 TIM5 PWM(1) GPIO(50) +PH12 TIM5_CH3 TIM5 PWM(2) GPIO(51) +PH11 TIM5_CH2 TIM5 PWM(3) GPIO(52) +PH10 TIM5_CH1 TIM5 PWM(4) GPIO(53) +PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54) +PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55) + +# we need to disable DMA on the last 2 FMU channels +# as timer 12 doesn't have a TIMn_UP DMA option +PH6 TIM12_CH1 TIM12 PWM(7) GPIO(56) NODMA +PH9 TIM12_CH2 TIM12 PWM(8) GPIO(57) NODMA + +# GPIOs +PE11 FMU_CAP1 INPUT GPIO(58) +PC0 NFC_GPIO INPUT GPIO(60) + + +# CAN bus +PD0 CAN1_RX CAN1 +PD1 CAN1_TX CAN1 + +PB12 CAN2_RX CAN2 +PB13 CAN2_TX CAN2 + + +# I2C buses + +# I2C1, GPS+MAG +PB9 I2C1_SDA I2C1 +PB8 I2C1_SCL I2C1 + +# I2C2, GPS2+MAG +PF1 I2C2_SCL I2C2 +PF0 I2C2_SDA I2C2 +PG5 DRDY1_BMP388 INPUT + +# I2C3, MS5611, external +PA8 I2C3_SCL I2C3 +PH8 I2C3_SDA I2C3 + +# I2C4 internal +PF14 I2C4_SCL I2C4 +PF15 I2C4_SDA I2C4 + +# order of I2C buses +I2C_ORDER I2C4 I2C1 I2C2 I2C3 +define HAL_I2C_INTERNAL_MASK 1 + +# this board is very tight on DMA channels. To allow for more UART DMA +# we disable DMA on I2C. This also prevents a problem with DMA on I2C +# interfering with IMUs +NODMA I2C* +define STM32_I2C_USE_DMA FALSE + +# heater - No heater on Rev 1 +# PB10 HEATER_EN OUTPUT LOW GPIO(80) +# define HAL_HEATER_GPIO_PIN 80 + +# Setup the IMU heater +# define HAL_HAVE_IMU_HEATER 1 +# define HAL_IMU_TEMP_DEFAULT 45 +# define HAL_IMUHEAT_P_DEFAULT 50 +# define HAL_IMUHEAT_I_DEFAULT 0.07 + +# armed indication +PE6 nARMED OUTPUT HIGH + +# power enable pins +PC13 VDD_3V3_SD_CARD_EN OUTPUT HIGH +PI11 VDD_3V3_SENSORS1_EN OUTPUT HIGH +PF4 VDD_3V3_SENSORS2_EN OUTPUT HIGH +PE7 VDD_3V3_SENSORS3_EN OUTPUT HIGH +PG8 VDD_3V3_SENSORS4_EN OUTPUT HIGH +PG15 ETH_PWR_EN OUTPUT LOW # disable power on ethernet + +# start peripheral power off, then enable after init +# this prevents a problem with radios that use RTS for +# bootloader hold +PG10 nVDD_5V_HIPOWER_EN OUTPUT HIGH +PG4 nVDD_5V_PERIPH_EN OUTPUT HIGH + +# Control of Spektrum power pin +PH2 SPEKTRUM_PWR OUTPUT HIGH GPIO(73) +define HAL_GPIO_SPEKTRUM_PWR 73 + +# Spektrum Power is Active High +define HAL_SPEKTRUM_PWR_ENABLED 1 + +# power sensing +PE15 VDD_5V_PERIPH_nOC INPUT PULLUP +PF13 VDD_5V_HIPOWER_nOC INPUT PULLUP + +PG1 VDD_BRICK_nVALID INPUT PULLUP +PG2 VDD_BRICK2_nVALID INPUT PULLUP +PG3 VDD_BRICK3_nVALID INPUT PULLUP + +# microSD support +PD6 SDMMC2_CK SDMMC2 +PD7 SDMMC2_CMD SDMMC2 +PB14 SDMMC2_D0 SDMMC2 +PB15 SDMMC2_D1 SDMMC2 +PG11 SDMMC2_D2 SDMMC2 +PB4 SDMMC2_D3 SDMMC2 +define FATFS_HAL_DEVICE SDCD2 + +# safety +PD10 LED_SAFETY OUTPUT +PF5 SAFETY_IN INPUT PULLDOWN + +# LEDs +PE3 LED_RED OUTPUT OPENDRAIN GPIO(90) HIGH +PE4 LED_GREEN OUTPUT OPENDRAIN GPIO(91) HIGH +PE5 LED_BLUE OUTPUT OPENDRAIN GPIO(92) HIGH + +# setup for "pixracer" RGB LEDs +define HAL_GPIO_A_LED_PIN 90 +define HAL_GPIO_B_LED_PIN 91 +define HAL_GPIO_C_LED_PIN 92 +define HAL_GPIO_LED_ON 0 + +define HAL_HAVE_PIXRACER_LED + +# ID pins +PG0 HW_VER_REV_DRIVE OUTPUT LOW +# PH3 HW_VER_SENS ADC3 SCALE(1) +# PH4 HW_REV_SENS ADC3 SCALE(1) + +# PWM output for buzzer +PF9 TIM14_CH1 TIM14 GPIO(77) ALARM + +# RC input +PI5 TIM8_CH1 TIM8 RCININT PULLDOWN LOW + +# barometers +BARO BMP388 I2C:0:0x76 + +# compass +define HAL_PROBE_EXTERNAL_I2C_COMPASSES + +# builtin compass +COMPASS BMM150 I2C:0:0x10 false ROTATION_NONE + +# IMU devices for ARKV6X +SPIDEV iim42652 SPI1 DEVID1 IMU1_CS MODE3 2*MHZ 8*MHZ +SPIDEV icm42688 SPI2 DEVID1 IMU2_CS MODE3 2*MHZ 8*MHZ +SPIDEV icm42688_ext SPI3 DEVID1 IMU3_CS MODE3 2*MHZ 8*MHZ + +SPIDEV ramtron SPI5 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ + +# ARKV6X 3 IMUs +IMU Invensensev3 SPI:iim42652 ROTATION_ROLL_180_YAW_135 +IMU Invensensev3 SPI:icm42688 ROTATION_YAW_45 +IMU Invensensev3 SPI:icm42688_ext ROTATION_ROLL_180_YAW_270 + +define HAL_DEFAULT_INS_FAST_SAMPLE 7 + +# enable RAMTROM parameter storage +define HAL_STORAGE_SIZE 32768 +define HAL_WITH_RAMTRON 1 + +# INA226 battery monitor +define HAL_BATTMON_INA2XX_BUS 1 +define HAL_BATTMON_INA2XX_ADDR 0x41 +define HAL_BATT_MONITOR_DEFAULT 21 + +# allow to have have a dedicated safety switch pin +define HAL_HAVE_SAFETY_SWITCH 1 + +DMA_PRIORITY SDMMC* USART6* ADC* UART* USART* SPI* TIM* + +# enable FAT filesystem support (needs a microSD defined via SDMMC) +define HAL_OS_FATFS_IO 1 + +define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" +define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" + +ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_lowpolh.bin + +# enable DFU reboot for installing bootloader +# note that if firmware is build with --secure-bl then DFU is +# disabled +ENABLE_DFU_BOOT 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-Airspeed/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-Airspeed/hwdef-bl.dat new file mode 100644 index 00000000000..eb5785215e9 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-Airspeed/hwdef-bl.dat @@ -0,0 +1,9 @@ +include ../f103-periph/hwdef-bl.inc + +define CAN_APP_NODE_NAME "org.ardupilot.AeroFox_Airspeed" + +# board ID for firmware load +APJ_BOARD_ID 1077 + + + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-Airspeed/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-Airspeed/hwdef.dat new file mode 100644 index 00000000000..964323ba786 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-Airspeed/hwdef.dat @@ -0,0 +1,25 @@ +include ../f103-periph/hwdef.inc + +# board ID for firmware load +APJ_BOARD_ID 1077 + +define CAN_APP_NODE_NAME "org.ardupilot.AeroFox_Airspeed" + +define HAL_COMPASS_MAX_SENSORS 1 + +define HAL_AIRSPEED_BUS_DEFAULT 0 + +# 1 I2C-MS4525D0 sensor by default +define HAL_AIRSPEED_TYPE_DEFAULT 1 +define AIRSPEED_MAX_SENSORS 1 + +define HAL_PERIPH_ENABLE_AIRSPEED +define HAL_PERIPH_ENABLE_MAG +COMPASS QMC5883L I2C:0:0x0D false ROTATION_NONE +COMPASS RM3100 I2C:0:0x20 false ROTATION_NONE +COMPASS RM3100 I2C:0:0x21 false ROTATION_NONE +COMPASS RM3100 I2C:0:0x22 false ROTATION_NONE +COMPASS RM3100 I2C:0:0x23 false ROTATION_NONE + +define HAL_PERIPH_ENABLE_NCP5623_LED_WITHOUT_NOTIFY + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/AtomRCF405NAVI/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/AtomRCF405NAVI/hwdef-bl.dat new file mode 100644 index 00000000000..28b7858d68a --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/AtomRCF405NAVI/hwdef-bl.dat @@ -0,0 +1,35 @@ +# hw definition file for processing by chibios_pins.py +# for minimal F405 bootloader + +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +# board ID for firmware load +APJ_BOARD_ID 1078 + +# crystal frequency +OSCILLATOR_HZ 8000000 + +FLASH_SIZE_KB 1024 + +# bootloader is installed at zero offset +FLASH_RESERVE_START_KB 0 + +# LEDs +PA14 LED_BOOTLOADER OUTPUT LOW # blue led +PA13 LED_ACTIVITY OUTPUT LOW # green led +define HAL_LED_ON 0 + +# the location where the bootloader will put the firmware +FLASH_BOOTLOADER_LOAD_KB 64 + +# order of UARTs +SERIAL_ORDER OTG1 + +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# Add CS pins to ensure they are high in bootloader +PA4 IMU_CS CS +PB6 SDCARD_CS CS +PB12 AT7456E_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/AtomRCF405NAVI/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/AtomRCF405NAVI/hwdef.dat new file mode 100644 index 00000000000..6dbc14512f0 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/AtomRCF405NAVI/hwdef.dat @@ -0,0 +1,169 @@ +# hw definition file for AtomRC F405 hardware + +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +# board ID for firmware load +APJ_BOARD_ID 1078 + +# crystal frequency +OSCILLATOR_HZ 8000000 + +define STM32_ST_USE_TIMER 5 + +FLASH_SIZE_KB 1024 + +# only one I2C bus +I2C_ORDER I2C1 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART5 USART6 + +# LEDs +PA14 LED_BLUE OUTPUT LOW GPIO(0) +PA13 LED_GREEN OUTPUT LOW GPIO(1) + +define HAL_GPIO_A_LED_PIN 0 +define HAL_GPIO_B_LED_PIN 1 + +# buzzer +PC5 BUZZER OUTPUT GPIO(80) LOW +define HAL_BUZZER_PIN 80 +define HAL_BUZZER_ON 1 +define HAL_BUZZER_OFF 0 + +# spi1 bus for IMU +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 +PA4 IMU_CS CS + +# spi2 for OSD +PB13 SPI2_SCK SPI2 +PB14 SPI2_MISO SPI2 +PB15 SPI2_MOSI SPI2 +PB12 AT7456E_CS CS + +# spi3 for sdcard +PB3 SPI3_SCK SPI3 +PB4 SPI3_MISO SPI3 +PB5 SPI3_MOSI SPI3 +PB6 SDCARD_CS CS + +# one I2C bus +PB8 I2C1_SCL I2C1 +PB9 I2C1_SDA I2C1 + +# analog pins +PC2 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PC1 BATT_CURRENT_SENS ADC1 SCALE(1) +PC0 RSSI_ADC_PIN ADC1 SCALE(1) +PC3 AIRSPEED_ADC ADC1 SCALE(1) + +define HAL_DEFAULT_AIRSPEED_PIN 13 + +# define default battery setup +define HAL_BATT_VOLT_PIN 12 +define HAL_BATT_CURR_PIN 11 +define HAL_BATT_VOLT_SCALE 11.08836 +define HAL_BATT_CURR_SCALE 30.0 +define HAL_BATT_MONITOR_DEFAULT 4 + +# analog rssi pin +define BOARD_RSSI_ANA_PIN 10 + +# USART1 +PA9 USART1_TX USART1 +PA10 USART1_RX USART1 + +# USART2 - RCIN with inverter +PA2 USART2_TX USART2 +PA3 TIM9_CH2 TIM9 RCININT PULLDOWN + +# alternative with PA3 as USART2_RX +PA3 USART2_RX USART2 NODMA ALT(1) + +# USART3 +PC10 USART3_TX USART3 +PC11 USART3_RX USART3 +define HAL_SERIAL3_PROTOCOL 0 + +# UART4 GPS +PA0 UART4_TX UART4 NODMA +PA1 UART4_RX UART4 NODMA +define HAL_SERIAL4_PROTOCOL 5 + +# UART5 for DJI OSD +PD2 UART5_RX UART5 NODMA +PC12 UART5_TX UART5 NODMA + +# USART6 +PC6 USART6_TX USART6 +PC7 USART6_RX USART6 + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# debug (disabled out to allow for both LEDs) +#PA13 JTMS-SWDIO SWD +#PA14 JTCK-SWCLK SWD + +# PWM out pins. Note that channel order follows the ArduPilot motor +# order conventions +PC8 TIM3_CH3 TIM3 PWM(1) GPIO(50) +PC9 TIM3_CH4 TIM3 PWM(2) GPIO(51) +PA8 TIM1_CH1 TIM1 PWM(3) GPIO(52) +PB1 TIM1_CH3N TIM1 PWM(4) GPIO(53) +PA15 TIM2_CH1 TIM2 PWM(5) GPIO(54) +PB10 TIM2_CH3 TIM2 PWM(6) GPIO(55) +PB11 TIM2_CH4 TIM2 PWM(7) GPIO(56) +PB0 TIM1_CH2N TIM1 PWM(8) GPIO(57) +PB7 TIM4_CH2 TIM4 PWM(9) GPIO(58) # LED strip + +define HAL_STORAGE_SIZE 15360 +STORAGE_FLASH_PAGE 2 + +# reserve 32k for bootloader and 32k for flash storage +FLASH_RESERVE_START_KB 64 + +# one IMU +IMU BMI270 SPI:bmi270 ROTATION_PITCH_180 + +# I2C BMP280 or SPL06 +BARO SPL06 I2C:0:0x76 +BARO BMP280 I2C:0:0x76 + +# no built-in compass, but probe the i2c bus for all possible +# external compass types +define ALLOW_ARM_NO_COMPASS +define HAL_PROBE_EXTERNAL_I2C_COMPASSES +define HAL_I2C_INTERNAL_MASK 0 + +# SPI devices +SPIDEV bmi270 SPI1 DEVID1 IMU_CS MODE3 1*MHZ 10*MHZ +SPIDEV sdcard SPI3 DEVID1 SDCARD_CS MODE0 400*KHZ 25*MHZ +SPIDEV osd SPI2 DEVID1 AT7456E_CS MODE0 10*MHZ 10*MHZ + +# filesystem setup on sdcard +define HAL_OS_FATFS_IO 1 +define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" +define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" + +# setup for OSD +define OSD_ENABLED 1 +define HAL_OSD_TYPE_DEFAULT 1 +ROMFS_WILDCARD libraries/AP_OSD/fonts/font0.bin + +# reduce max size of embedded params for apj_tool.py +define AP_PARAM_MAX_EMBEDDED_PARAM 256 + +# save some flash +define AP_BATTMON_SMBUS_ENABLE 0 +define HAL_GENERATOR_ENABLED 0 +define AC_OAPATHPLANNER_ENABLED 0 +define PRECISION_LANDING 0 +define AP_OPTICALFLOW_ENABLED 0 +define AP_ICENGINE_ENABLED 0 +define HAL_PARACHUTE_ENABLED 0 +define HAL_SPRAYER_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BeastF7/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/BeastF7/hwdef.dat index 4553edc6677..09952f874eb 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/BeastF7/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/BeastF7/hwdef.dat @@ -139,3 +139,8 @@ define HAL_GENERATOR_ENABLED 0 define AC_OAPATHPLANNER_ENABLED 0 define PRECISION_LANDING 0 define AP_OPTICALFLOW_ENABLED 0 +define AP_ICENGINE_ENABLED 0 +define AP_GPS_SIRF_ENABLED 0 +define AP_GPS_NOVA_ENABLED 0 +define AP_GPS_GSOF_ENABLED 0 +define AP_GPS_ERB_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BeastF7v2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/BeastF7v2/hwdef.dat index 8f0aafd7d85..6d6f0cc43a3 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/BeastF7v2/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/BeastF7v2/hwdef.dat @@ -69,5 +69,7 @@ define GRIPPER_ENABLED 0 define HAL_PARACHUTE_ENABLED 0 define HAL_SPRAYER_ENABLED 0 define AP_BATTMON_SMBUS_ENABLE 0 -define AP_BATTMON_FUEL_ENABLE 0 define AP_OPTICALFLOW_ENABLED 0 +define AP_ICENGINE_ENABLED 0 +define AP_GPS_SIRF_ENABLED 0 +define AP_GPS_SBP_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BeastH7/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/BeastH7/hwdef-bl.dat index 33592caca54..cebb47ca312 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/BeastH7/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/BeastH7/hwdef-bl.dat @@ -15,10 +15,6 @@ FLASH_SIZE_KB 2048 # bootloader starts at zero offset FLASH_RESERVE_START_KB 0 -# use last 2 pages for flash storage -# H743 has 16 pages of 128k each -STORAGE_FLASH_PAGE 14 - # the location where the bootloader will put the firmware # the H743 has 128k sectors FLASH_BOOTLOADER_LOAD_KB 128 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BeastH7v2/README.md b/libraries/AP_HAL_ChibiOS/hwdef/BeastH7v2/README.md new file mode 100644 index 00000000000..5f2ee0d6e12 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BeastH7v2/README.md @@ -0,0 +1,87 @@ +# iFlight Beast H7 v2 55A AIO Flight Controller + +https://shop.iflight-rc.com/Beast-H7-V2-55A-AIO-MPU6000-25.5-25.5-pro1588 + +The Beast H7 AIO is a flight controller produced by [iFlight](https://shop.iflight-rc.com/). + +## Features + + - MCU: BGA-STM32H743 + - Gyro: BMI270 + - 16Mb Onboard Flash + - BEC output: 5V 2.5A + - Barometer: DPS310 or None + - OSD: AT7456E + - 5 UARTS: (UART1, UART2, UART3, UART4, UART7) + - I2C for external compass. UART3 pins are used for I2C (BRD_ALT_CONFIG=1) + - 5 PWM outputs (4 motors and 1 LED) + +## Pinout + +![Beast H7 v2 AIO Board](beast_h7v2_pinout.jpg "Beast H7 v2 AIO") + +## UART Mapping + +The UARTs are marked Rn and Tn in the above pinouts. The Rn pin is the +receive pin for UARTn. The Tn pin is the transmit pin for UARTn. +|Name|Pin|Function| +|:-|:-|:-| +|SERIAL0|COMPUTER|USB| +|SERIAL1|RX1/TX1|UART1 (DJI connector)| +|SERIAL2|TX2/RX2|UART2 (DJI connector, TX is on the back side of board)| +|SERIAL3|TX3/RX3|UART3| +|SERIAL4|TX4/RX4|UART4| +|SERIAL7|TX7/RX7|UART7 (GPS)| + +All UARTS support DMA. + +## RC Input + +RC input is configured on the (UART2_RX/UART2_TX) pins which forms part of the DJI connector. It supports all RC protocols. + +## OSD Support + +The Beast H7 v2 AIO supports OSD using OSD_TYPE 1 (MAX7456 driver). + +## PWM Output + +The Beast H7 AIO supports up to 4 PWM outputs. The pads for motor output ESC1 to ESC4 on the above diagram are for the 4 outputs. All 4 outputs support DShot as well as all PWM types. + +The PWM are in in two groups. + +Channels within the same group need to use the same output rate. If +any channel in a group uses DShot then all channels in the group need +to use DShot. + +## Battery Monitoring + +The board has a builtin voltage sensor. The voltage sensor can handle up to 6S +LiPo batteries. + +The correct battery setting parameters are: + + - BATT_MONITOR 4 + - BATT_VOLT_PIN 12 + - BATT_VOLT_MULT around 10.9 + - BATT_CURR_PIN 13 + - BATT_CURR_MULT around 28.5 + +These are set by default in the firmware and shouldn't need to be adjusted + +## Compass + +The Beast H7 v2 AIO does not have a builtin compass, but you can attach an external compass to I2C pins. Default configuration does not have I2C bus enabled. You need to set BRD_ALT_CONFIG=1 to make I2C use RX3/TX3 pins. + +## NeoPixel LED + +The board includes a NeoPixel LED on the underside which is pre-configured to output ArduPilot sequences. This is the fifth PWM output. + +## Loading Firmware + +Initial firmware load can be done with DFU by plugging in USB with the +bootloader button pressed. Then you should load the "with_bl.hex" +firmware, using your favourite DFU loading tool. + +Once the initial firmware is loaded you can update the firmware using +any ArduPilot ground station software. Updates should be done with the +*.apj firmware files. diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BeastH7v2/beast_h7v2_pinout.jpg b/libraries/AP_HAL_ChibiOS/hwdef/BeastH7v2/beast_h7v2_pinout.jpg new file mode 100644 index 00000000000..95c40066b4d Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/BeastH7v2/beast_h7v2_pinout.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BeastH7v2/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/BeastH7v2/defaults.parm new file mode 100644 index 00000000000..c70ba4dea43 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BeastH7v2/defaults.parm @@ -0,0 +1,3 @@ +# setup for LEDs on chan5 +SERVO5_FUNCTION 120 +NTF_LED_TYPES 257 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BeastH7v2/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/BeastH7v2/hwdef-bl.dat new file mode 100644 index 00000000000..dd74ece65c7 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BeastH7v2/hwdef-bl.dat @@ -0,0 +1,3 @@ +include ../BeastH7/hwdef-bl.dat +undef APJ_BOARD_ID +APJ_BOARD_ID 1056 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BeastH7v2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/BeastH7v2/hwdef.dat new file mode 100644 index 00000000000..7e0811717cd --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BeastH7v2/hwdef.dat @@ -0,0 +1,64 @@ +# hw definition file for processing by chibios_pins.py +# for iFlight Beast H7 v2 hardware, based on Beast H7 v1 +# thanks to betaflight for pin information + +include ../BeastH7/hwdef.dat +undef APJ_BOARD_ID +undef HAL_SERIAL3_PROTOCOL +undef IMU +undef BARO +undef PD15 +undef PE9 PE11 PB8 PB9 PB11 PB10 PA10 PA9 PA3 PA2 +undef HAL_DEFAULT_INS_FAST_SAMPLE DMA_PRIORITY DMA_NOSHARE +undef STM32_PWM_USE_ADVANCED +undef I2C1 + +# board ID for firmware load +APJ_BOARD_ID 1056 + +# V2 has different motor mapping +PB4 TIM3_CH1 TIM3 PWM(2) GPIO(51) BIDIR # 2 +PB5 TIM3_CH2 TIM3 PWM(3) GPIO(52) # 3 + +I2C_ORDER I2C1 I2C2 +define HAL_I2C_INTERNAL_MASK 0 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 EMPTY EMPTY UART7 + +# Buzzer - DMA timer channel use by LEDs +PD2 BUZZER OUTPUT GPIO(80) LOW + +# USART1 (DJI) +PA10 USART1_RX USART1 +PA9 USART1_TX USART1 NODMA + +# USART2 (DJI RCIN) +PA3 USART2_RX USART2 +PA2 USART2_TX USART2 NODMA +define HAL_SERIAL2_PROTOCOL SerialProtocol_RCIN + +# USART3 (RCIN) +PB11 USART3_RX USART3 +PB10 USART3_TX USART3 + +# I2C1 for baro +PB8 I2C1_SCL I2C1 PULLUP +PB9 I2C1_SDA I2C1 PULLUP + +# I2C2 for compass. These pins can also be used as USART3 +PB10 I2C2_SCL I2C2 ALT(1) +PB11 I2C2_SDA I2C2 ALT(1) + +# spi devices +SPIDEV bmi270 SPI1 DEVID1 MPU6000_CS MODE3 10*MHZ 10*MHZ + +# no built-in compass and no external I2C so no compass +define HAL_PROBE_EXTERNAL_I2C_COMPASSES + +# one IMU +IMU BMI270 SPI:bmi270 ROTATION_ROLL_180_YAW_225 + +# Some boards have no baro, some have a DPS310 Baro on I2C1 +define HAL_BARO_ALLOW_INIT_NO_BARO 1 +BARO DPS310 I2C:0:0x76 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BirdCANdy/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/BirdCANdy/hwdef.dat index 1e37717eea4..4348ab6a3b6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/BirdCANdy/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/BirdCANdy/hwdef.dat @@ -105,8 +105,6 @@ define HAL_GCS_ENABLED 0 define HAL_NO_LOGGING define HAL_NO_MONITOR_THREAD -define HAL_MINIMIZE_FEATURES 0 - define HAL_DEVICE_THREAD_STACK 768 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora-bdshot/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora-bdshot/defaults.parm new file mode 100644 index 00000000000..53367d845c4 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora-bdshot/defaults.parm @@ -0,0 +1,19 @@ +# setup the temperature compensation +BRD_HEAT_TARG 45 +BRD_HEAT_P 50 +BRD_HEAT_I 0.07 + +# turn on the CAN power monitoring(default) +CAN_P1_DRIVER 1 +BATT_MONITOR 8 + +# setup the parameter for the ADC power module +BATT_VOLT_PIN 16 +BATT_CURR_PIN 17 +BATT_VOLT_MULT 18.000 +BATT_AMP_PERVLT 24.000 + +# turn on CAN RGB LED +NTF_LED_TYPES 231 + +EK2_IMU_MASK 7 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora-bdshot/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora-bdshot/hwdef-bl.dat new file mode 100644 index 00000000000..a05edff6298 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora-bdshot/hwdef-bl.dat @@ -0,0 +1 @@ +include ../CUAV-Nora/hwdef-bl.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora-bdshot/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora-bdshot/hwdef.dat new file mode 100644 index 00000000000..a708da77155 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora-bdshot/hwdef.dat @@ -0,0 +1,14 @@ +# Bi-directional dshot version of CUAV-Nora + +include ../CUAV-Nora/hwdef.dat + +undef PH10 PH12 PD12 PD14 + +# This gives bi-dir dshot on the first eight channels +PH10 TIM5_CH1 TIM5 PWM(1) GPIO(50) BIDIR +PH12 TIM5_CH3 TIM5 PWM(3) GPIO(52) BIDIR +PD12 TIM4_CH1 TIM4 PWM(5) GPIO(54) BIDIR +PD14 TIM4_CH3 TIM4 PWM(7) GPIO(56) BIDIR + +NODMA I2C* +define STM32_I2C_USE_DMA FALSE diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/defaults.parm old mode 100755 new mode 100644 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/hwdef-bl.dat old mode 100755 new mode 100644 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/hwdef.dat old mode 100755 new mode 100644 index 7a4d48d1697..a8e21ee470c --- a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/hwdef.dat @@ -21,7 +21,7 @@ STM32_ST_USE_TIMER 2 FLASH_RESERVE_START_KB 128 # order of UARTs (and USB) -SERIAL_ORDER OTG1 USART2 USART6 USART1 UART4 UART8 UART7 OTG2 +SERIAL_ORDER OTG1 USART2 USART6 USART1 UART4 UART8 UART7 USART3 OTG2 # default the 2nd interface to MAVLink2 until MissionPlanner updates drivers define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2 @@ -63,14 +63,14 @@ PG13 SPI6_SCK SPI6 PG12 SPI6_MISO SPI6 PA7 SPI6_MOSI SPI6 -# sensor +# sensor PF10 ADIS16470_CS CS PF2 RM3100_CS CS PG6 ICM20689_CS CS SPEED_VERYLOW PI12 ICM20649_CS CS SPEED_VERYLOW PE15 ICM20689_BOARD_CS CS SPEED_VERYLOW -PA15 ICM42688_CS CS SPEED_VERYLOW +PA15 ICM42688_CS CS PF3 BMI088_A_CS CS PF4 BMI088_G_CS CS PF5 FRAM_CS CS SPEED_VERYLOW @@ -144,7 +144,7 @@ PD0 UART4_RX UART4 NODMA PD1 UART4_TX UART4 NODMA # USART6 is telem2 -PG9 USART6_RX USART6 +PG9 USART6_RX USART6 PG14 USART6_TX USART6 PG15 USART6_CTS USART6 PG8 USART6_RTS USART6 @@ -155,7 +155,11 @@ PE8 UART7_TX UART7 NODMA # SBUS, DSM port PE0 UART8_RX UART8 -PE1 UART8_TX UART8 +PE1 UART8_TX UART8 + +# USART3 +PD8 USART3_TX USART3 NODMA +PD9 USART3_RX USART3 NODMA # PWM AUX channels PH10 TIM5_CH1 TIM5 PWM(1) GPIO(50) @@ -228,7 +232,7 @@ SPIDEV bmi088_a SPI4 DEVID2 BMI088_A_CS MODE3 10*MHZ 10*MHZ SPIDEV bmi088_g SPI4 DEVID3 BMI088_G_CS MODE3 10*MHZ 10*MHZ SPIDEV ms5611_imu SPI4 DEVID1 MS5611_IMU_CS MODE3 20*MHZ 20*MHZ SPIDEV ms5611_board SPI6 DEVID1 MS5611_BOARD_CS MODE3 20*MHZ 20*MHZ -SPIDEV ramtron SPI2 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ +SPIDEV ramtron SPI2 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ SPIDEV rm3100 SPI2 DEVID2 RM3100_CS MODE3 2*MHZ 8*MHZ #Mount icm20649 or icm20689 on SPI6 @@ -236,7 +240,7 @@ SPIDEV icm20649 SPI6 DEVID2 ICM20649_CS MODE3 2*MHZ 8*MHZ SPIDEV icm20689_board SPI6 DEVID2 ICM20689_BOARD_CS MODE3 2*MHZ 8*MHZ #Mount bmi088_a or icm42688 on SPI4 -SPIDEV icm42688 SPI4 DEVID2 ICM42688_CS MODE3 2*MHZ 8*MHZ +SPIDEV icm42688 SPI4 DEVID2 ICM42688_CS MODE3 2*MHZ 16*MHZ # two baro BARO MS56XX SPI:ms5611_imu @@ -249,7 +253,7 @@ IMU Invensensev3 SPI:icm42688 ROTATION_PITCH_180_YAW_270 IMU Invensensev2 SPI:icm20649 ROTATION_NONE IMU Invensense SPI:icm20689_board ROTATION_NONE -define HAL_DEFAULT_INS_FAST_SAMPLE 5 +define HAL_DEFAULT_INS_FAST_SAMPLE 7 # compasses @@ -257,8 +261,8 @@ define HAL_PROBE_EXTERNAL_I2C_COMPASSES COMPASS IST8310 I2C:ALL_EXTERNAL:0x0E true ROTATION_ROLL_180_YAW_90 COMPASS IST8310 I2C:ALL_INTERNAL:0x0E false ROTATION_ROLL_180_YAW_90 -COMPASS RM3100 SPI:rm3100 false ROTATION_NONE - +COMPASS RM3100 SPI:rm3100 false ROTATION_NONE + # microSD support PC8 SDMMC1_D0 SDMMC1 @@ -300,4 +304,4 @@ define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" DMA_PRIORITY ADC* SPI1* TIM*UP* -DMA_NOSHARE SPI1* TIM*UP* +DMA_NOSHARE SPI1* TIM*UP* diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7/hwdef.dat index 60319bc61f7..250be29f6c8 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7/hwdef.dat @@ -315,3 +315,7 @@ DMA_NOSHARE SPI1* TIM*UP* # default to 45C target temp define HAL_IMU_TEMP_DEFAULT 45 + +# Enable Sagetech MXS ADSB transponder +define HAL_ADSB_SAGETECH_MXS_ENABLED HAL_ADSB_ENABLED + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef.dat index 4d59ab434e0..d4c17abc918 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef.dat @@ -85,6 +85,8 @@ COMPASS RM3100 SPI:rm3100 false ROTATION_PITCH_180 # baro BARO BMP388 I2C:0:0x76 BARO MS56XX SPI:ms5611 +BARO ICP101XX I2C:0:0x63 +BARO ICP101XX I2C:0:0x64 # PWM output for buzzer PB10 TIM2_CH3 TIM2 GPIO(77) LOW ALARM @@ -130,8 +132,6 @@ define CAN_APP_NODE_NAME "org.ardupilot.cuav_gps" define HAL_NO_MONITOR_THREAD -define HAL_MINIMIZE_FEATURES 0 - define HAL_DEVICE_THREAD_STACK 768 @@ -152,3 +152,6 @@ define HAL_PERIPH_ENABLE_BARO # startup define HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY 0 define HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY 8 + +# also enable buzzer +define HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAVv5-bdshot/README.md b/libraries/AP_HAL_ChibiOS/hwdef/CUAVv5-bdshot/README.md index 80ffe0b353b..c93b6c13ab3 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CUAVv5-bdshot/README.md +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAVv5-bdshot/README.md @@ -54,7 +54,7 @@ The CUAVv5 supports up to 14 PWM outputs. First first 8 outputs (labelled "MAIN") are controlled by a dedicated STM32F100 IO controller. These 8 outputs support all PWM output formats, but not DShot. -The remaining 6 outputs (labelled AUX1 to AUX6) are the "auxillary" +The remaining 6 outputs (labelled AUX1 to AUX6) are the "auxiliary" outputs. These are directly attached to the STM32F765 and support all PWM protocols as well as DShot. @@ -67,7 +67,7 @@ The 8 main PWM outputs are in 3 groups: - PWM 3 and 4 in group2 - PWM 5, 6, 7 and 8 in group3 -The 6 auxillary PWM outputs are in 2 groups: +The 6 auxiliary PWM outputs are in 2 groups: - PWM 1, 2, 3 and 4 in group1 - PWM 5 and 6 in group2 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAVv5/README.md b/libraries/AP_HAL_ChibiOS/hwdef/CUAVv5/README.md index 80ffe0b353b..c93b6c13ab3 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CUAVv5/README.md +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAVv5/README.md @@ -54,7 +54,7 @@ The CUAVv5 supports up to 14 PWM outputs. First first 8 outputs (labelled "MAIN") are controlled by a dedicated STM32F100 IO controller. These 8 outputs support all PWM output formats, but not DShot. -The remaining 6 outputs (labelled AUX1 to AUX6) are the "auxillary" +The remaining 6 outputs (labelled AUX1 to AUX6) are the "auxiliary" outputs. These are directly attached to the STM32F765 and support all PWM protocols as well as DShot. @@ -67,7 +67,7 @@ The 8 main PWM outputs are in 3 groups: - PWM 3 and 4 in group2 - PWM 5, 6, 7 and 8 in group3 -The 6 auxillary PWM outputs are in 2 groups: +The 6 auxiliary PWM outputs are in 2 groups: - PWM 1, 2, 3 and 4 in group1 - PWM 5 and 6 in group2 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAVv5/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CUAVv5/hwdef.dat index 923dc6bc5c7..4e39e983c31 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CUAVv5/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAVv5/hwdef.dat @@ -20,4 +20,15 @@ define HAL_GPIO_LED_OFF 1 define HAL_HAVE_PIXRACER_LED +undef IMU +undef PF11 +PF11 ICM42688_CS CS SPEED_VERYLOW + +SPIDEV icm42688 SPI1 DEVID2 ICM42688_CS MODE3 2*MHZ 8*MHZ + +IMU Invensense SPI:icm20689 ROTATION_NONE +IMU Invensense SPI:icm20602 ROTATION_NONE +IMU Invensensev3 SPI:icm42688 ROTATION_PITCH_180_YAW_270 +IMU BMI055 SPI:bmi055_a SPI:bmi055_g ROTATION_ROLL_180_YAW_90 +IMU BMI088 SPI:bmi055_a SPI:bmi055_g ROTATION_ROLL_180_YAW_90 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef-bl.dat new file mode 100644 index 00000000000..c9b65a069f0 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef-bl.dat @@ -0,0 +1,74 @@ +# hw definition file for processing by chibios_pins.py + +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +FLASH_RESERVE_START_KB 0 +FLASH_BOOTLOADER_LOAD_KB 60 + +# reserve some space for params +APP_START_OFFSET_KB 4 + +# board ID for firmware load +APJ_BOARD_ID 1064 + +# setup build for a peripheral firmware +env AP_PERIPH 1 + +# crystal frequency set to 0 to use internal clock +OSCILLATOR_HZ 0 + +# assume 1024K flash part +FLASH_SIZE_KB 1024 + +STDOUT_SERIAL SD2 +STDOUT_BAUDRATE 57600 + +# order of UARTs +SERIAL_ORDER OTG1 USART2 + +# a fault LED +PA15 LED_BOOTLOADER OUTPUT HIGH # blue +define HAL_LED_ON 0 + +# USART1 +PA2 USART2_TX USART2 SPEED_HIGH NODMA +PA3 USART2_RX USART2 SPEED_HIGH NODMA + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +define HAL_USE_SERIAL TRUE + +define STM32_SERIAL_USE_USART2 TRUE + +define HAL_NO_GPIO_IRQ + +define SERIAL_BUFFERS_SIZE 32 +define HAL_USE_EMPTY_IO TRUE +define PORT_INT_REQUIRED_STACK 64 + +define DMA_RESERVE_SIZE 0 + +MAIN_STACK 0x800 +PROCESS_STACK 0x800 + +define HAL_DISABLE_LOOP_DELAY + +# enable CAN support +PB8 CAN1_RX CAN1 +PB9 CAN1_TX CAN1 + +# debugger support +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# make bl baudrate match debug baudrate for easier debugging +define BOOTLOADER_BAUDRATE 57600 + +# use a small bootloader timeout +define HAL_BOOTLOADER_TIMEOUT 1000 + + +define CAN_APP_NODE_NAME "org.ardupilot.CarbonixF405" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef.dat new file mode 100644 index 00000000000..011bf96f83c --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef.dat @@ -0,0 +1,145 @@ +# hw definition file for processing by chibios_pins.py + +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +# bootloader starts firmware at 60+ 4k +FLASH_RESERVE_START_KB 64 + +#MCU F405 store parameters in pages 2 and 3 +STORAGE_FLASH_PAGE 2 +define HAL_STORAGE_SIZE 15360 + +# board ID for firmware load +APJ_BOARD_ID 1064 + +# setup build for a peripheral firmware +env AP_PERIPH 1 + +# crystal frequency set to 0 to use internal clock +OSCILLATOR_HZ 0 + +#MCU F405 Flash 1024 +FLASH_SIZE_KB 1024 + +# order of UARTs +SERIAL_ORDER OTG1 USART2 USART3 UART4 + +define HAL_CAN_POOL_SIZE 6000 + +#STDOUT_SERIAL SD1 +#STDOUT_BAUDRATE 57600 + + +# PWM outputs +PA9 TIM1_CH2 TIM1 PWM(1) GPIO(50) +PA8 TIM1_CH1 TIM1 PWM(2) GPIO(51) + +# USART2, ESC telem +PA2 USART2_TX USART2 SPEED_HIGH NODMA +PA3 USART2_RX USART2 SPEED_HIGH NODMA + +# USART3 +PC10 USART3_TX USART3 SPEED_HIGH NODMA +PC11 USART3_RX USART3 SPEED_HIGH NODMA + +# UART4 +PA0 UART4_TX UART4 SPEED_HIGH NODMA +PA1 UART4_RX UART4 SPEED_HIGH NODMA + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# LED, active low +PA15 LED OUTPUT HIGH GPIO(1) + +# spi2 +PB10 SPI2_SCK SPI2 +PB14 SPI2_MISO SPI2 +PB15 SPI2_MOSI SPI2 + +# CS pins +PC8 BMI088_A_CS CS +PC9 BMI088_G_CS CS + +SPIDEV bmi088_g SPI2 DEVID1 BMI088_G_CS MODE3 10*MHZ 10*MHZ +SPIDEV bmi088_a SPI2 DEVID2 BMI088_A_CS MODE3 10*MHZ 10*MHZ + +# one I2C bus +PB6 I2C1_SCL I2C1 +PB7 I2C1_SDA I2C1 + +I2C_ORDER I2C1 + +# allow for reboot command for faster development +define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0 + +# debugger support +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +define HAL_NO_GPIO_IRQ +define SERIAL_BUFFERS_SIZE 512 + +define DMA_RESERVE_SIZE 2048 + +# stack for fast interrupts +define PORT_INT_REQUIRED_STACK 64 + +# MAIN_STACK is stack for ISR handlers +MAIN_STACK 0x300 + +# PROCESS_STACK controls stack for main thread +PROCESS_STACK 0xA00 + +define HAL_DISABLE_LOOP_DELAY + +# enable CAN support +PB8 CAN1_RX CAN1 +PB9 CAN1_TX CAN1 + +# ADC inputs +define HAL_USE_ADC TRUE +define STM32_ADC_USE_ADC1 TRUE + +PA5 VSENSE1 ADC1 SCALE(1) +PA6 VSENSE2 ADC1 SCALE(1) +PB0 VSENSE3 ADC1 SCALE(1) +PB1 VSENSE4 ADC1 SCALE(1) + +define AP_STATS_ENABLED 1 + +define HAL_NO_GCS +define HAL_NO_MONITOR_THREAD + +define AP_PARAM_MAX_EMBEDDED_PARAM 512 + +define CAN_APP_NODE_NAME "org.ardupilot.CarbonixF405" + +define HAL_PERIPH_ENABLE_MAG +define HAL_PERIPH_ENABLE_BARO +define HAL_PERIPH_ENABLE_RC_OUT + +# enable ESC control +define HAL_SUPPORT_RCOUT_SERIAL 1 +define HAL_WITH_ESC_TELEM 1 + +# enable GPS +define HAL_PERIPH_ENABLE_GPS +define HAL_PERIPH_GPS_PORT_DEFAULT 2 +#define HAL_PERIPH_ENABLE_NOTIFY +#define HAL_PERIPH_ENABLE_NCP5623_LED_WITHOUT_NOTIFY + +# default ADSB off by setting 0 baudrate +define HAL_PERIPH_ENABLE_ADSB +define HAL_PERIPH_ADSB_PORT_DEFAULT 3 +define HAL_PERIPH_ADSB_BAUD_DEFAULT 57600 + +BARO MS56XX I2C:0:0x76 +COMPASS MMC5XX3 I2C:0:0x30 false ROTATION_NONE + + + + + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef-bl.dat index a7b8e7937ac..68b3974cbb1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef-bl.dat @@ -15,8 +15,8 @@ APJ_BOARD_ID 1053 # setup build for a peripheral firmware env AP_PERIPH 1 -# crystal frequency -OSCILLATOR_HZ 12000000 +# crystal frequency set to 0 to use internal clock +OSCILLATOR_HZ 0 # assume 256k flash part FLASH_SIZE_KB 256 @@ -28,7 +28,7 @@ STDOUT_BAUDRATE 57600 SERIAL_ORDER OTG1 USART2 # a fault LED -PA13 LED_BOOTLOADER OUTPUT HIGH # blue +PA15 LED_BOOTLOADER OUTPUT HIGH # blue define HAL_LED_ON 0 # USART1 @@ -60,9 +60,9 @@ define HAL_DISABLE_LOOP_DELAY PB8 CAN1_RX CAN1 PB9 CAN1_TX CAN1 -# debugger support, disabled as PA13 used for LED -# PA13 JTMS-SWDIO SWD -# PA14 JTCK-SWCLK SWD +# debugger support +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD # make bl baudrate match debug baudrate for easier debugging define BOOTLOADER_BAUDRATE 57600 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef.dat index 8ca74a93f54..1b5ff08dc7c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef.dat @@ -18,8 +18,8 @@ env AP_PERIPH 1 # enable watchdog -# crystal frequency -OSCILLATOR_HZ 12000000 +# crystal frequency set to 0 to use internal clock +OSCILLATOR_HZ 0 # assume the 256k flash part FLASH_SIZE_KB 256 @@ -55,7 +55,7 @@ PA11 OTG_FS_DM OTG1 PA12 OTG_FS_DP OTG1 # LED, active low -PA13 LED OUTPUT HIGH GPIO(1) +PA15 LED OUTPUT HIGH GPIO(1) # spi2 PB10 SPI2_SCK SPI2 @@ -78,9 +78,9 @@ I2C_ORDER I2C4 # allow for reboot command for faster development define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0 -# debugger support (disabled as conflicts with LED) -#PA13 JTMS-SWDIO SWD -#PA14 JTCK-SWCLK SWD +# debugger support +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD define HAL_NO_GPIO_IRQ define SERIAL_BUFFERS_SIZE 512 @@ -111,6 +111,8 @@ PA5 VSENSE2 ADC1 SCALE(1) PA6 VSENSE3 ADC1 SCALE(1) PB1 VSENSE4 ADC1 SCALE(1) +define AP_STATS_ENABLED 1 + define HAL_NO_GCS define HAL_NO_MONITOR_THREAD @@ -126,6 +128,17 @@ define HAL_PERIPH_ENABLE_RC_OUT define HAL_SUPPORT_RCOUT_SERIAL 1 define HAL_WITH_ESC_TELEM 1 +# enable GPS +define HAL_PERIPH_ENABLE_GPS +define HAL_PERIPH_GPS_PORT_DEFAULT 2 +#define HAL_PERIPH_ENABLE_NOTIFY +#define HAL_PERIPH_ENABLE_NCP5623_LED_WITHOUT_NOTIFY + +# default ADSB off by setting 0 baudrate +define HAL_PERIPH_ENABLE_ADSB +define HAL_PERIPH_ADSB_PORT_DEFAULT 3 +define HAL_PERIPH_ADSB_BAUD_DEFAULT 57600 + BARO MS56XX I2C:0:0x76 COMPASS MMC5XX3 I2C:0:0x30 false ROTATION_NONE diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack/README.md b/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack/README.md index dcb9fe71eb2..9072c9e0cd5 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack/README.md +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack/README.md @@ -494,7 +494,7 @@ The CubeBlack supports up to 14 PWM outputs. First first 8 outputs (labelled "MAIN") are controlled by a dedicated STM32F100 IO controller. These 8 outputs support all PWM output formats, but not DShot. -The remaining 6 outputs (labelled AUX1 to AUX6) are the "auxillary" +The remaining 6 outputs (labelled AUX1 to AUX6) are the "auxiliary" outputs. These are directly attached to the STM32F427 and support all PWM protocols as well as DShot. @@ -507,7 +507,7 @@ The 8 main PWM outputs are in 3 groups: - PWM 3 and 4 in group2 - PWM 5, 6, 7 and 8 in group3 -The 6 auxillary PWM outputs are in 2 groups: +The 6 auxiliary PWM outputs are in 2 groups: - PWM 1, 2, 3 and 4 in group1 - PWM 5 and 6 in group2 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeGreen-solo/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeGreen-solo/hwdef.dat index de4e9e68c24..385e689ac18 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeGreen-solo/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeGreen-solo/hwdef.dat @@ -9,3 +9,11 @@ include ../CubeBlack/hwdef.dat # pull Solo's default parameters from /Tools/Frame_params # these are parameters the Solo requires for proper operation that are different from the 4 standard defaults. env DEFAULT_PARAMETERS 'Tools/Frame_params/Solo_Copter-4_GreenCube.param' + +undef HAL_OREO_LED_ENABLED +define HAL_OREO_LED_ENABLED 1 + +undef HAL_SOLO_GIMBAL_ENABLED +define HAL_SOLO_GIMBAL_ENABLED HAL_MOUNT_ENABLED + +AUTOBUILD_TARGETS Copter diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-ODID/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-ODID/defaults.parm new file mode 100644 index 00000000000..e79aa27e5d6 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-ODID/defaults.parm @@ -0,0 +1,24 @@ +# setup correct defaults for battery monitoring for cube power brick +BATT2_CURR_PIN 4 +BATT2_VOLT_PIN 13 +BATT_AMP_PERVLT 39.877 +BATT_VOLT_MULT 12.02 +BATT2_AMP_PERVLT 39.877 +BATT2_VOLT_MULT 12.02 +# setup ADSB +ADSB_TYPE 1 +SERIAL5_BAUD 57 +SERIAL5_PROTOCOL 1 + +# enforce OpenDroneID on DroneCAN. Note that we need to lock down key parameters +# to ensure the integrity of the RemoteID system +DID_ENABLE 1 @READONLY +DID_OPTIONS 1 @READONLY +DID_MAVPORT -1 @READONLY +DID_CANDRIVER 1 @READONLY +AHRS_EKF_TYPE 3 @READONLY +GPS_TYPE 1 +GPS_TYPE2 0 + +EK2_PRIMARY 1 +EK3_PRIMARY 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-ODID/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-ODID/hwdef-bl.dat new file mode 100644 index 00000000000..2990bed48eb --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-ODID/hwdef-bl.dat @@ -0,0 +1,8 @@ +include ../CubeOrange/hwdef-bl.dat + +# use a different board ID, so vehicles with OpenDroneID enabled are +# prevented from loading the firmware without OpenDroneID enabled +APJ_BOARD_ID 10140 + +# enable OpenDroneID +define AP_OPENDRONEID_ENABLED 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-ODID/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-ODID/hwdef.dat new file mode 100644 index 00000000000..edba88a70ca --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-ODID/hwdef.dat @@ -0,0 +1,10 @@ +include ../CubeOrange/hwdef.dat + +# use a different board ID, so vehicles with this installed are prevented from loading +# the firmware without OpenDroneID enabled +APJ_BOARD_ID 10140 + +# enable and enforce OpenDroneID +define AP_OPENDRONEID_ENABLED 1 + + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-SimOnHardWare/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-SimOnHardWare/defaults.parm new file mode 100644 index 00000000000..705dee7dc48 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-SimOnHardWare/defaults.parm @@ -0,0 +1,61 @@ +AHRS_EKF_TYPE 10 + +ATC_RAT_YAW_P 0.09 +ATC_RAT_YAW_I 0.009 + +BATT_MONITOR 0 + +COMPASS_OFS_X 5 +COMPASS_OFS_Y 13 +COMPASS_OFS_Z -18 +COMPASS_OFS2_X 5 +COMPASS_OFS2_Y 13 +COMPASS_OFS2_Z -18 + +FENCE_RADIUS 150 + +FRAME_TYPE 0 +FRAME_CLASS 1 + +FS_THR_ENABLE 1 + +RC7_OPTION 7 + +FLTMODE1 7 +FLTMODE2 9 +FLTMODE3 6 +FLTMODE4 3 +FLTMODE5 5 +FLTMODE6 0 + +GPS_TYPE 100 + +INS_ACCOFFS_X 0.001 +INS_ACCOFFS_Y 0.001 +INS_ACCOFFS_Z 0.001 +INS_ACCSCAL_X 1.001 +INS_ACCSCAL_Y 1.001 +INS_ACCSCAL_Z 1.001 +INS_ACC2OFFS_X 0.001 +INS_ACC2OFFS_Y 0.001 +INS_ACC2OFFS_Z 0.001 +INS_ACC2SCAL_X 1.001 +INS_ACC2SCAL_Y 1.001 +INS_ACC2SCAL_Z 1.001 + +MOT_THST_EXPO 0.65 +MOT_THST_HOVER 0.39 +MOT_BAT_VOLT_MIN 9.6 +MOT_BAT_VOLT_MAX 12.8 + +SIM_MAG1_DEVID 97539 +SIM_BARO_RND 0 + +SIM_RATE_HZ 400 +SCHED_LOOP_RATE 400 + +BRD_RTC_TYPES 2 +BRD_OPTIONS 9 + +EK2_PRIMARY 1 +EK3_PRIMARY 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-SimOnHardWare/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-SimOnHardWare/hwdef.dat new file mode 100644 index 00000000000..3195c728b3e --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-SimOnHardWare/hwdef.dat @@ -0,0 +1,9 @@ +# Firmware suitable for flashing into a CubeOrange to experience Simulation-on-Hardware + +include ../CubeOrange/hwdef.dat +include ../include/SimOnHW.inc + +# short board name override (23 chars) +define CHIBIOS_SHORT_BOARD_NAME "CubeOrangeSimOnHardWare" + +AUTOBUILD_TARGETS Copter diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-joey/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-joey/defaults.parm index c696210948b..376ba2763cb 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-joey/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-joey/defaults.parm @@ -47,3 +47,5 @@ SCR_ENABLE 1 @READONLY SCR_DIR_DISABLE 0 @READONLY BRD_HEAT_I 0.07 @READONLY BRD_HEAT_P 50 @READONLY +EK2_PRIMARY 1 @READONLY +EK3_PRIMARY 1 @READONLY diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/defaults.parm index 05d30c8e6f1..fdb083659ef 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/defaults.parm @@ -9,3 +9,5 @@ BATT2_VOLT_MULT 12.02 ADSB_TYPE 1 SERIAL5_BAUD 57 SERIAL5_PROTOCOL 1 +EK2_PRIMARY 1 +EK3_PRIMARY 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef-bl.dat index 83c74ed6312..7abab4dc6e4 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef-bl.dat @@ -4,62 +4,4 @@ # MCU class and specific type MCU STM32H7xx STM32H743xx -# USB setup -USB_VENDOR 0x2DAE # ONLY FOR USE BY HEX! NOBODY ELSE -USB_PRODUCT 0x1016 -USB_STRING_MANUFACTURER "Hex/ProfiCNC" - -# crystal frequency -OSCILLATOR_HZ 24000000 - -# board ID for firmware load -APJ_BOARD_ID 140 - -FLASH_SIZE_KB 2048 - -# bootloader is installed at zero offset -FLASH_RESERVE_START_KB 0 - -# the location where the bootloader will put the firmware -# the H743 has 128k sectors -FLASH_BOOTLOADER_LOAD_KB 128 - -define HAL_LED_ON 0 - -# order of UARTs (and USB) -SERIAL_ORDER OTG1 USART2 USART3 UART7 - -# telem1 -PD5 USART2_TX USART2 -PD6 USART2_RX USART2 - -# telem2 -PD8 USART3_TX USART3 -PD9 USART3_RX USART3 - -# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters). -PE7 UART7_RX UART7 -PE8 UART7_TX UART7 - -# Pin for PWM Voltage Selection -PB4 PWM_VOLT_SEL OUTPUT HIGH - -PA11 OTG_FS_DM OTG1 -PA12 OTG_FS_DP OTG1 - -PA13 JTMS-SWDIO SWD -PA14 JTCK-SWCLK SWD - -# Add CS pins to ensure they are high in bootloader -PC1 MAG_CS CS -PC2 MPU_CS CS -PC13 GYRO_EXT_CS CS -PC14 BARO_EXT_CS CS -PC15 ACCEL_EXT_CS CS -PD7 BARO_CS CS -PE4 MPU_EXT_CS CS -PD10 FRAM_CS CS SPEED_VERYLOW - -# disable peripheral and sensor power in the bootloader -PA8 nVDD_5V_PERIPH_EN OUTPUT HIGH -PE3 VDD_3V3_SENSORS_EN OUTPUT LOW +include hwdef-bl.inc diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef-bl.inc b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef-bl.inc new file mode 100644 index 00000000000..272295bf947 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef-bl.inc @@ -0,0 +1,65 @@ + +# USB setup +USB_VENDOR 0x2DAE # ONLY FOR USE BY HEX! NOBODY ELSE +USB_PRODUCT 0x1016 +USB_STRING_MANUFACTURER "Hex/ProfiCNC" + +# crystal frequency +OSCILLATOR_HZ 24000000 + +# board ID for firmware load +APJ_BOARD_ID 140 + +FLASH_SIZE_KB 2048 + +# bootloader is installed at zero offset +FLASH_RESERVE_START_KB 0 + +# the location where the bootloader will put the firmware +# the H743 has 128k sectors +FLASH_BOOTLOADER_LOAD_KB 128 + +define HAL_LED_ON 0 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART2 USART3 UART7 + +PE12 LED_BOOTLOADER OUTPUT HIGH OPENDRAIN + +# telem1 +PD5 USART2_TX USART2 +PD6 USART2_RX USART2 + +# telem2 +PD8 USART3_TX USART3 +PD9 USART3_RX USART3 + +# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters). +PE7 UART7_RX UART7 +PE8 UART7_TX UART7 + +# Pin for PWM Voltage Selection +PB4 PWM_VOLT_SEL OUTPUT HIGH + +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# Add CS pins to ensure they are high in bootloader +PC1 MAG_CS CS +PC2 MPU_CS CS +PC13 GYRO_EXT_CS CS +PC14 BARO_EXT_CS CS +PC15 ACCEL_EXT_CS CS +PD7 BARO_CS CS +PE4 MPU_EXT_CS CS +PD10 FRAM_CS CS SPEED_VERYLOW + +# disable peripheral and sensor power in the bootloader +PE3 VDD_3V3_SENSORS_EN OUTPUT LOW +PA8 nVDD_5V_PERIPH_EN OUTPUT LOW + +# enable DFU by default +ENABLE_DFU_BOOT 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef.dat index c0d69637842..3ae5a6ecb75 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef.dat @@ -1,332 +1,6 @@ # hw definition file for processing by chibios_hwdef.py -define HAL_CHIBIOS_ARCH_CUBE 1 - -# USB setup -USB_VENDOR 0x2DAE # ONLY FOR USE BY HEX! NOBODY ELSE -USB_PRODUCT 0x1016 -USB_STRING_MANUFACTURER "Hex/ProfiCNC" - # MCU class and specific type MCU STM32H7xx STM32H743xx -# crystal frequency -OSCILLATOR_HZ 24000000 - -# board ID for firmware load -APJ_BOARD_ID 140 - -FLASH_SIZE_KB 2048 - -# with 2M flash we can afford to optimize for speed -env OPTIMIZE -O2 - -FLASH_RESERVE_START_KB 128 - -define HAL_STORAGE_SIZE 32768 - -# order of I2C buses -I2C_ORDER I2C2 I2C1 - -# order of UARTs (and USB) -SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 UART7 OTG2 - -# If the board has an IOMCU connected via a UART then this defines the -# UART to talk to that MCU. Leave it out for boards with no IOMCU. - -# UART for IOMCU -IOMCU_UART USART6 - -# UART4 serial GPS -PA0 UART4_TX UART4 -PA1 UART4_RX UART4 NODMA - -PA2 BATT_VOLTAGE_SENS ADC1 SCALE(1) -PA3 BATT_CURRENT_SENS ADC1 SCALE(1) - -# Now the VDD sense pin. This is used to sense primary board voltage. -PA4 VDD_5V_SENS ADC1 SCALE(2) - -PA5 SPI1_SCK SPI1 -PA6 SPI1_MISO SPI1 -PA7 SPI1_MOSI SPI1 - -# This defines an output pin which will default to output HIGH. It is -# a pin that enables peripheral power on this board. It starts in the -# off state, then is pulled low to enable peripherals in -# peripheral_power_enable() -PA8 nVDD_5V_PERIPH_EN OUTPUT HIGH - -# This is the pin that senses USB being connected. It is an input pin -# setup as OPENDRAIN. -PA9 VBUS INPUT OPENDRAIN - -# Now we define the pins that USB is connected on. -PA11 OTG_FS_DM OTG1 -PA12 OTG_FS_DP OTG1 - -# These are the pins for SWD debugging with a STlinkv2 or black-magic probe. -PA13 JTMS-SWDIO SWD -PA14 JTCK-SWCLK SWD - -# PWM output for buzzer -PA15 TIM2_CH1 TIM2 GPIO(77) ALARM - -# This defines a couple of general purpose outputs, mapped to GPIO -# numbers 1 and 2 for users. -PB0 EXTERN_GPIO1 OUTPUT GPIO(1) -PB1 EXTERN_GPIO2 OUTPUT GPIO(2) - -# This defines some input pins, currently unused. -PB2 BOOT1 INPUT -PB3 FMU_SW0 INPUT - -# This defines the pins for the 2nd CAN interface, if available. -PB6 CAN2_TX CAN2 -PB12 CAN2_RX CAN2 - -# Now the first I2C bus. The pin speeds are automatically setup -# correctly, but can be overridden here if needed. -PB8 I2C1_SCL I2C1 -PB9 I2C1_SDA I2C1 - -# the 2nd I2C bus -PB10 I2C2_SCL I2C2 -PB11 I2C2_SDA I2C2 - -# the 2nd SPI bus -PB13 SPI2_SCK SPI2 -PB14 SPI2_MISO SPI2 -PB15 SPI2_MOSI SPI2 - -# This input pin is used to detect that power is valid on USB. -PC0 VBUS_nVALID INPUT PULLUP - -# This defines the CS pin for the magnetometer and first IMU. Note -# that CS pins are software controlled, and are not tied to a particular -# SPI bus. -PC1 MAG_CS CS -PC2 MPU_CS CS - -# This defines more ADC inputs. -PC3 AUX_POWER ADC1 SCALE(1) -PC4 AUX_ADC2 ADC1 SCALE(1) - -# And the analog input for airspeed (rarely used these days). -PC5 PRESSURE_SENS ADC1 SCALE(2) - -# USART6 to IO -PC6 USART6_TX USART6 -PC7 USART6_RX USART6 - -# Now setup the pins for the microSD card, if available. -PC8 SDMMC1_D0 SDMMC1 -PC9 SDMMC1_D1 SDMMC1 -PC10 SDMMC1_D2 SDMMC1 -PC11 SDMMC1_D3 SDMMC1 -PC12 SDMMC1_CK SDMMC1 -PD2 SDMMC1_CMD SDMMC1 - -# More CS pins for more sensors. The labels for all CS pins need to -# match the SPI device table later in this file. -PC13 GYRO_EXT_CS CS -PC14 BARO_EXT_CS CS -PC15 ACCEL_EXT_CS CS -PD7 BARO_CS CS -PE4 MPU_EXT_CS CS - -# the first CAN bus -PD0 CAN1_RX CAN1 -PD1 CAN1_TX CAN1 - -# Another USART, this one for telem1. This one has RTS and CTS lines. -# USART2 serial2 telem1 -PD3 USART2_CTS USART2 -PD4 USART2_RTS USART2 -PD5 USART2_TX USART2 -PD6 USART2_RX USART2 - -# telem1 RTS and CTS as GPIO in alt config 1 -PD3 EXTERN_GPIO4 OUTPUT GPIO(4) ALT(1) -PD4 EXTERN_GPIO5 OUTPUT GPIO(5) ALT(1) - -# The telem2 USART, also with RTS/CTS available. -# USART3 serial3 telem2 -PD8 USART3_TX USART3 -PD9 USART3_RX USART3 -PD11 USART3_CTS USART3 -PD12 USART3_RTS USART3 - -# The CS pin for FRAM (ramtron). This one is marked as using -# SPEED_VERYLOW, which matches the HAL_PX4 setup. -PD10 FRAM_CS CS SPEED_VERYLOW - -# Now we start defining some PWM pins. We also map these pins to GPIO -# values, so users can set BRD_PWM_COUNT to choose how many of the PWM -# outputs on the primary MCU are setup as PWM and how many as -# GPIOs. To match HAL_PX4 we number the GPIOs for the PWM outputs -# starting at 50. -PE14 TIM1_CH4 TIM1 PWM(1) GPIO(50) -PE13 TIM1_CH3 TIM1 PWM(2) GPIO(51) -PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52) -PE9 TIM1_CH1 TIM1 PWM(4) GPIO(53) -PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54) -PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55) - -# Pin for PWM Voltage Selection -PB4 PWM_VOLT_SEL OUTPUT HIGH GPIO(3) - -# This is the invensense data-ready pin. We don't use it in the -# default driver. -PD15 MPU_DRDY INPUT - -# the 2nd GPS UART -# UART8 serial4 GPS2 -PE0 UART8_RX UART8 -PE1 UART8_TX UART8 NODMA - -# Now setup SPI bus4. -PE2 SPI4_SCK SPI4 -PE5 SPI4_MISO SPI4 -PE6 SPI4_MOSI SPI4 - -# This is the pin to enable the sensors rail. It can be used to power -# cycle sensors to recover them in case there are problems with power on -# timing affecting sensor stability. We pull it LOW on startup, which -# means sensors off, then it is pulled HIGH in peripheral_power_enable() -PE3 VDD_3V3_SENSORS_EN OUTPUT LOW - -# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters). -PE7 UART7_RX UART7 -PE8 UART7_TX UART7 - -# Define a LED, mapping it to GPIO(0). LOW will illuminate the LED -PE12 FMU_LED_AMBER OUTPUT HIGH OPENDRAIN GPIO(0) - -# Power flag pins: these tell the MCU the status of the various power -# supplies that are available. The pin names need to exactly match the -# names used in AnalogIn.cpp. -PB5 VDD_BRICK_nVALID INPUT PULLUP -PB7 VDD_BRICK2_nVALID INPUT PULLUP -PE10 VDD_5V_HIPOWER_nOC INPUT PULLUP -PE15 VDD_5V_PERIPH_nOC INPUT PULLUP - -SPIDEV ms5611 SPI1 DEVID3 BARO_CS MODE3 20*MHZ 20*MHZ -SPIDEV ms5611_ext SPI4 DEVID2 BARO_EXT_CS MODE3 20*MHZ 20*MHZ -SPIDEV mpu6000 SPI1 DEVID4 MPU_CS MODE3 2*MHZ 8*MHZ -SPIDEV icm20608-am SPI1 DEVID2 ACCEL_EXT_CS MODE3 4*MHZ 8*MHZ -SPIDEV mpu9250 SPI1 DEVID4 MPU_CS MODE3 4*MHZ 8*MHZ -SPIDEV mpu9250_ext SPI4 DEVID1 MPU_EXT_CS MODE3 4*MHZ 8*MHZ -SPIDEV icm20948 SPI1 DEVID4 MPU_CS MODE3 4*MHZ 8*MHZ -SPIDEV icm20948_ext SPI4 DEVID1 MPU_EXT_CS MODE3 4*MHZ 8*MHZ -SPIDEV hmc5843 SPI1 DEVID5 MAG_CS MODE3 11*MHZ 11*MHZ -SPIDEV lsm9ds0_g SPI1 DEVID1 GYRO_EXT_CS MODE3 11*MHZ 11*MHZ -SPIDEV lsm9ds0_am SPI1 DEVID2 ACCEL_EXT_CS MODE3 11*MHZ 11*MHZ -SPIDEV lsm9ds0_ext_g SPI4 DEVID4 GYRO_EXT_CS MODE3 11*MHZ 11*MHZ -SPIDEV lsm9ds0_ext_am SPI4 DEVID3 ACCEL_EXT_CS MODE3 11*MHZ 11*MHZ -SPIDEV icm20602_ext SPI4 DEVID4 GYRO_EXT_CS MODE3 4*MHZ 8*MHZ -SPIDEV ramtron SPI2 DEVID10 FRAM_CS MODE3 8*MHZ 8*MHZ -SPIDEV external0m0 SPI4 DEVID5 MPU_EXT_CS MODE0 2*MHZ 2*MHZ -SPIDEV external0m1 SPI4 DEVID5 MPU_EXT_CS MODE1 2*MHZ 2*MHZ -SPIDEV external0m2 SPI4 DEVID5 MPU_EXT_CS MODE2 2*MHZ 2*MHZ -SPIDEV external0m3 SPI4 DEVID5 MPU_EXT_CS MODE3 2*MHZ 2*MHZ -SPIDEV pixartPC15 SPI4 DEVID13 ACCEL_EXT_CS MODE3 2*MHZ 2*MHZ - -# three IMUs, but allow for different variants. First two IMUs are -# isolated, 3rd isn't -IMU Invensense SPI:mpu9250_ext ROTATION_PITCH_180 - -# the 3 rotations for the LSM9DS0 driver are for the accel, the gyro -# and the H variant of the gyro -IMU LSM9DS0 SPI:lsm9ds0_ext_g SPI:lsm9ds0_ext_am ROTATION_ROLL_180_YAW_270 ROTATION_ROLL_180_YAW_90 ROTATION_ROLL_180_YAW_90 - -# 3rd non-isolated IMU -IMU Invensense SPI:mpu9250 ROTATION_YAW_270 - -# alternative IMU set for newer cubes -IMU Invensense SPI:icm20602_ext ROTATION_ROLL_180_YAW_270 -IMU Invensensev2 SPI:icm20948_ext ROTATION_PITCH_180 -IMU Invensensev2 SPI:icm20948 ROTATION_YAW_270 - -# Sensor Check alias for validating board type -CHECK_ICM20649 spi_check_register_inv2("icm20948", INV2REG_WHOAMI, INV2_WHOAMI_ICM20649) -CHECK_ICM20602_EXT spi_check_register("icm20602_ext", MPUREG_WHOAMI, MPU_WHOAMI_ICM20602) -CHECK_ICM20948_EXT spi_check_register_inv2("icm20948_ext", INV2REG_WHOAMI, INV2_WHOAMI_ICM20948) -CHECK_MS5611 check_ms5611("ms5611") -CHECK_MS5611_EXT check_ms5611("ms5611_ext") - -# Sensor Check Macros to be used for validating board type -CHECK_IMU0_PRESENT $CHECK_ICM20602_EXT -CHECK_IMU1_PRESENT $CHECK_ICM20948_EXT -CHECK_IMU2_PRESENT $CHECK_ICM20649 -CHECK_BARO0_PRESENT $CHECK_MS5611 -CHECK_BARO1_PRESENT $CHECK_MS5611_EXT - -BOARD_VALIDATE $CHECK_IMU0_PRESENT $CHECK_IMU1_PRESENT $CHECK_IMU2_PRESENT $CHECK_BARO0_PRESENT $CHECK_BARO1_PRESENT - - -define HAL_DEFAULT_INS_FAST_SAMPLE 7 - -# two baros -BARO MS56XX SPI:ms5611_ext -BARO MS56XX SPI:ms5611 - -# two compasses. First is in the LSM303D -COMPASS LSM303D SPI:lsm9ds0_ext_am ROTATION_YAW_270 -# 2nd compass is part of the 2nd invensense IMU -COMPASS AK8963:probe_mpu9250 1 ROTATION_YAW_270 - -# compass as part of ICM20948 on newer cubes -COMPASS AK09916:probe_ICM20948 0 ROTATION_ROLL_180_YAW_90 - -# offset the internal compass for EM impact of the IMU heater -# this is in sensor frame mGauss -define HAL_AK09916_HEATER_OFFSET Vector3f(30,10,235) - -# also probe for external compasses -define HAL_PROBE_EXTERNAL_I2C_COMPASSES - -define HAL_CHIBIOS_ARCH_FMUV3 1 - -define BOARD_TYPE_DEFAULT 3 - -# Nnow some defines for logging and terrain data files. -define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" -define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" - -# allow to have have a dedicated safety switch pin -define HAL_HAVE_SAFETY_SWITCH 1 - -# Enable RAMTROM parameter storage. -define HAL_WITH_RAMTRON 1 - -# Setup the IMU heater -define HAL_HAVE_IMU_HEATER 1 -define HAL_IMU_TEMP_DEFAULT 45 -define HAL_IMUHEAT_P_DEFAULT 50 -define HAL_IMUHEAT_I_DEFAULT 0.07 -define HAL_IMU_TEMP_MARGIN_LOW_DEFAULT 5 - -# Enable all IMUs to be used and therefore three active EKF Lanes -define HAL_EKF_IMU_MASK_DEFAULT 7 - -# Enable FAT filesystem support (needs a microSD defined via SDMMC). -define HAL_OS_FATFS_IO 1 - -# Now setup the default battery pins driver analog pins and default -# scaling for the power brick. -define HAL_BATT_VOLT_PIN 14 -define HAL_BATT_CURR_PIN 15 -define HAL_BATT_VOLT_SCALE 10.1 -define HAL_BATT_CURR_SCALE 17.0 -define HAL_GPIO_PWM_VOLT_PIN 3 -define HAL_GPIO_PWM_VOLT_3v3 1 - -# List of files to put in ROMFS. For fmuv3 we need an IO firmware so -# we can automatically update the IOMCU firmware on boot. The format -# is "ROMFS ROMFS-filename source-filename". Paths are relative to the -# ardupilot root. -ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_highpolh.bin - -DMA_NOSHARE SPI1* SPI4* USART6* - +include hwdef.inc diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef.inc b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef.inc new file mode 100644 index 00000000000..7492bc55cc0 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef.inc @@ -0,0 +1,344 @@ + +define HAL_CHIBIOS_ARCH_CUBE 1 + +# USB setup +USB_VENDOR 0x2DAE # ONLY FOR USE BY HEX! NOBODY ELSE +USB_PRODUCT 0x1016 +USB_STRING_MANUFACTURER "Hex/ProfiCNC" + +# crystal frequency +OSCILLATOR_HZ 24000000 + +# board ID for firmware load +APJ_BOARD_ID 140 + +FLASH_SIZE_KB 2048 + +# supports upto 8MBits/s +CANFD_SUPPORTED 8 + +# with 2M flash we can afford to optimize for speed +env OPTIMIZE -O2 + +FLASH_RESERVE_START_KB 128 + +define HAL_STORAGE_SIZE 32768 + +# order of I2C buses +I2C_ORDER I2C2 I2C1 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 UART7 OTG2 + +# If the board has an IOMCU connected via a UART then this defines the +# UART to talk to that MCU. Leave it out for boards with no IOMCU. + +# UART for IOMCU +IOMCU_UART USART6 + +# UART4 serial GPS +PA0 UART4_TX UART4 +PA1 UART4_RX UART4 NODMA + +PA2 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PA3 BATT_CURRENT_SENS ADC1 SCALE(1) + +# Now the VDD sense pin. This is used to sense primary board voltage. +PA4 VDD_5V_SENS ADC1 SCALE(2) + +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 + +# This defines an output pin which will default to output HIGH. It is +# a pin that enables peripheral power on this board. It starts in the +# off state, then is pulled low to enable peripherals in +# peripheral_power_enable() +PA8 nVDD_5V_PERIPH_EN OUTPUT LOW + +# This is the pin that senses USB being connected. It is an input pin +# setup as OPENDRAIN. +PA9 VBUS INPUT OPENDRAIN + +# Now we define the pins that USB is connected on. +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# These are the pins for SWD debugging with a STlinkv2 or black-magic probe. +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# PWM output for buzzer +PA15 TIM2_CH1 TIM2 GPIO(77) ALARM + +# This defines a couple of general purpose outputs, mapped to GPIO +# numbers 1 and 2 for users. +PB0 EXTERN_GPIO1 OUTPUT GPIO(1) +PB1 EXTERN_GPIO2 OUTPUT GPIO(2) + +# This defines some input pins, currently unused. +PB2 BOOT1 INPUT +PB3 FMU_SW0 INPUT + +# This defines the pins for the 2nd CAN interface, if available. +PB6 CAN2_TX CAN2 +PB12 CAN2_RX CAN2 + +# Now the first I2C bus. The pin speeds are automatically setup +# correctly, but can be overridden here if needed. +PB8 I2C1_SCL I2C1 +PB9 I2C1_SDA I2C1 + +# the 2nd I2C bus +PB10 I2C2_SCL I2C2 +PB11 I2C2_SDA I2C2 + +# the 2nd SPI bus +PB13 SPI2_SCK SPI2 +PB14 SPI2_MISO SPI2 +PB15 SPI2_MOSI SPI2 + +# This input pin is used to detect that power is valid on USB. +PC0 VBUS_nVALID INPUT PULLUP + +# This defines the CS pin for the magnetometer and first IMU. Note +# that CS pins are software controlled, and are not tied to a particular +# SPI bus. +PC1 MAG_CS CS +PC2 MPU_CS CS + +# This defines more ADC inputs. +PC3 AUX_POWER ADC1 SCALE(1) +PC4 AUX_ADC2 ADC1 SCALE(1) + +# And the analog input for airspeed (rarely used these days). +PC5 PRESSURE_SENS ADC1 SCALE(2) + +# USART6 to IO +PC6 USART6_TX USART6 +PC7 USART6_RX USART6 + +# Now setup the pins for the microSD card, if available. +PC8 SDMMC1_D0 SDMMC1 +PC9 SDMMC1_D1 SDMMC1 +PC10 SDMMC1_D2 SDMMC1 +PC11 SDMMC1_D3 SDMMC1 +PC12 SDMMC1_CK SDMMC1 +PD2 SDMMC1_CMD SDMMC1 + +# More CS pins for more sensors. The labels for all CS pins need to +# match the SPI device table later in this file. +PC13 GYRO_EXT_CS CS +PC14 BARO_EXT_CS CS +PC15 ACCEL_EXT_CS CS +PD7 BARO_CS CS +PE4 MPU_EXT_CS CS + +# the first CAN bus +PD0 CAN1_RX CAN1 +PD1 CAN1_TX CAN1 + +# Another USART, this one for telem1. This one has RTS and CTS lines. +# USART2 serial2 telem1 +PD3 USART2_CTS USART2 +PD4 USART2_RTS USART2 +PD5 USART2_TX USART2 +PD6 USART2_RX USART2 + +# telem1 RTS and CTS as GPIO in alt config 1 +PD3 EXTERN_GPIO4 OUTPUT GPIO(4) ALT(1) +PD4 EXTERN_GPIO5 OUTPUT GPIO(5) ALT(1) + +# The telem2 USART, also with RTS/CTS available. +# USART3 serial3 telem2 +PD8 USART3_TX USART3 +PD9 USART3_RX USART3 +PD11 USART3_CTS USART3 +PD12 USART3_RTS USART3 + +# The CS pin for FRAM (ramtron). This one is marked as using +# SPEED_VERYLOW, which matches the HAL_PX4 setup. +PD10 FRAM_CS CS SPEED_VERYLOW + +# Now we start defining some PWM pins. We also map these pins to GPIO +# values, so users can set SERVOx_FUNCTION=-1 to determine which +# PWM outputs on the primary MCU are set up as GPIOs. +# To match HAL_PX4 we number the GPIOs for the PWM outputs +# starting at 50. +PE14 TIM1_CH4 TIM1 PWM(1) GPIO(50) +PE13 TIM1_CH3 TIM1 PWM(2) GPIO(51) +PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52) +PE9 TIM1_CH1 TIM1 PWM(4) GPIO(53) +PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54) +PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55) + +# Pin for PWM Voltage Selection +PB4 PWM_VOLT_SEL OUTPUT HIGH GPIO(3) + +# This is the invensense data-ready pin. We don't use it in the +# default driver. +PD15 MPU_DRDY INPUT + +# the 2nd GPS UART +# UART8 serial4 GPS2 +PE0 UART8_RX UART8 +PE1 UART8_TX UART8 NODMA + +# Now setup SPI bus4. +PE2 SPI4_SCK SPI4 +PE5 SPI4_MISO SPI4 +PE6 SPI4_MOSI SPI4 + +# This is the pin to enable the sensors rail. It can be used to power +# cycle sensors to recover them in case there are problems with power on +# timing affecting sensor stability. We pull it LOW on startup, which +# means sensors off, then it is pulled HIGH in peripheral_power_enable() +PE3 VDD_3V3_SENSORS_EN OUTPUT LOW + +# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters). +PE7 UART7_RX UART7 +PE8 UART7_TX UART7 + +# Define a LED, mapping it to GPIO(0). LOW will illuminate the LED +PE12 FMU_LED_AMBER OUTPUT HIGH OPENDRAIN GPIO(0) + +# Power flag pins: these tell the MCU the status of the various power +# supplies that are available. The pin names need to exactly match the +# names used in AnalogIn.cpp. +PB5 VDD_BRICK_nVALID INPUT PULLUP +PB7 VDD_BRICK2_nVALID INPUT PULLUP +PE10 VDD_5V_HIPOWER_nOC INPUT PULLUP +PE15 VDD_5V_PERIPH_nOC INPUT PULLUP + +SPIDEV ms5611 SPI1 DEVID3 BARO_CS MODE3 20*MHZ 20*MHZ +SPIDEV ms5611_ext SPI4 DEVID2 BARO_EXT_CS MODE3 20*MHZ 20*MHZ +SPIDEV mpu6000 SPI1 DEVID4 MPU_CS MODE3 2*MHZ 8*MHZ +SPIDEV icm20608-am SPI1 DEVID2 ACCEL_EXT_CS MODE3 4*MHZ 8*MHZ +SPIDEV mpu9250 SPI1 DEVID4 MPU_CS MODE3 4*MHZ 8*MHZ +SPIDEV mpu9250_ext SPI4 DEVID1 MPU_EXT_CS MODE3 4*MHZ 8*MHZ +SPIDEV icm20948 SPI1 DEVID4 MPU_CS MODE3 4*MHZ 8*MHZ +SPIDEV icm20948_ext SPI4 DEVID1 MPU_EXT_CS MODE3 4*MHZ 8*MHZ +SPIDEV hmc5843 SPI1 DEVID5 MAG_CS MODE3 11*MHZ 11*MHZ +SPIDEV lsm9ds0_g SPI1 DEVID1 GYRO_EXT_CS MODE3 11*MHZ 11*MHZ +SPIDEV lsm9ds0_am SPI1 DEVID2 ACCEL_EXT_CS MODE3 11*MHZ 11*MHZ +SPIDEV lsm9ds0_ext_g SPI4 DEVID4 GYRO_EXT_CS MODE3 11*MHZ 11*MHZ +SPIDEV lsm9ds0_ext_am SPI4 DEVID3 ACCEL_EXT_CS MODE3 11*MHZ 11*MHZ +SPIDEV icm20602_ext SPI4 DEVID4 GYRO_EXT_CS MODE3 4*MHZ 8*MHZ +SPIDEV ramtron SPI2 DEVID10 FRAM_CS MODE3 8*MHZ 8*MHZ +SPIDEV external0m0 SPI4 DEVID5 MPU_EXT_CS MODE0 2*MHZ 2*MHZ +SPIDEV external0m1 SPI4 DEVID5 MPU_EXT_CS MODE1 2*MHZ 2*MHZ +SPIDEV external0m2 SPI4 DEVID5 MPU_EXT_CS MODE2 2*MHZ 2*MHZ +SPIDEV external0m3 SPI4 DEVID5 MPU_EXT_CS MODE3 2*MHZ 2*MHZ +SPIDEV pixartPC15 SPI4 DEVID13 ACCEL_EXT_CS MODE3 2*MHZ 2*MHZ + +# three IMUs, but allow for different variants. First two IMUs are +# isolated, 3rd isn't +IMU Invensense SPI:mpu9250_ext ROTATION_PITCH_180 + +# the 3 rotations for the LSM9DS0 driver are for the accel, the gyro +# and the H variant of the gyro +IMU LSM9DS0 SPI:lsm9ds0_ext_g SPI:lsm9ds0_ext_am ROTATION_ROLL_180_YAW_270 ROTATION_ROLL_180_YAW_90 ROTATION_ROLL_180_YAW_90 + +# 3rd non-isolated IMU +IMU Invensense SPI:mpu9250 ROTATION_YAW_270 + +# alternative IMU set for newer cubes +IMU Invensense SPI:icm20602_ext ROTATION_ROLL_180_YAW_270 +IMU Invensensev2 SPI:icm20948_ext ROTATION_PITCH_180 +IMU Invensensev2 SPI:icm20948 ROTATION_YAW_270 + +# Sensor Check alias for validating board type +CHECK_ICM20649 spi_check_register_inv2("icm20948", INV2REG_WHOAMI, INV2_WHOAMI_ICM20649) +CHECK_ICM20602_EXT spi_check_register("icm20602_ext", MPUREG_WHOAMI, MPU_WHOAMI_ICM20602) +CHECK_ICM20948_EXT spi_check_register_inv2("icm20948_ext", INV2REG_WHOAMI, INV2_WHOAMI_ICM20948) +CHECK_MS5611 check_ms5611("ms5611") +CHECK_MS5611_EXT check_ms5611("ms5611_ext") + +# Sensor Check Macros to be used for validating board type +CHECK_IMU0_PRESENT $CHECK_ICM20602_EXT +CHECK_IMU1_PRESENT $CHECK_ICM20948_EXT +CHECK_IMU2_PRESENT $CHECK_ICM20649 +CHECK_BARO0_PRESENT $CHECK_MS5611 +CHECK_BARO1_PRESENT $CHECK_MS5611_EXT + +BOARD_VALIDATE $CHECK_IMU0_PRESENT $CHECK_IMU1_PRESENT $CHECK_IMU2_PRESENT $CHECK_BARO0_PRESENT $CHECK_BARO1_PRESENT + + +define HAL_DEFAULT_INS_FAST_SAMPLE 7 + +# two baros +BARO MS56XX SPI:ms5611_ext +BARO MS56XX SPI:ms5611 + +# two compasses. First is in the LSM303D +COMPASS LSM303D SPI:lsm9ds0_ext_am ROTATION_YAW_270 +# 2nd compass is part of the 2nd invensense IMU +COMPASS AK8963:probe_mpu9250 1 ROTATION_YAW_270 + +# compass as part of ICM20948 on newer cubes +COMPASS AK09916:probe_ICM20948 0 ROTATION_ROLL_180_YAW_90 + +# offset the internal compass for EM impact of the IMU heater +# this is in body frame mGauss +define HAL_HEATER_MAG_OFFSET {AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_SPI,4,1,9),Vector3f(10,30,-235)} + +# also probe for external compasses +define HAL_PROBE_EXTERNAL_I2C_COMPASSES + +define HAL_CHIBIOS_ARCH_FMUV3 1 + +define BOARD_TYPE_DEFAULT 3 + +# Nnow some defines for logging and terrain data files. +define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" +define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" + +# allow to have have a dedicated safety switch pin +define HAL_HAVE_SAFETY_SWITCH 1 + +# Enable RAMTROM parameter storage. +define HAL_WITH_RAMTRON 1 + +# Setup the IMU heater +define HAL_HAVE_IMU_HEATER 1 +define HAL_IMU_TEMP_DEFAULT 45 +define HAL_IMUHEAT_P_DEFAULT 50 +define HAL_IMUHEAT_I_DEFAULT 0.07 +define HAL_IMU_TEMP_MARGIN_LOW_DEFAULT 5 + +# Enable all IMUs to be used and therefore three active EKF Lanes +define HAL_EKF_IMU_MASK_DEFAULT 7 + +# Enable FAT filesystem support (needs a microSD defined via SDMMC). +define HAL_OS_FATFS_IO 1 + +# Now setup the default battery pins driver analog pins and default +# scaling for the power brick. +define HAL_BATT_VOLT_PIN 14 +define HAL_BATT_CURR_PIN 15 +define HAL_BATT_VOLT_SCALE 10.1 +define HAL_BATT_CURR_SCALE 17.0 +define HAL_GPIO_PWM_VOLT_PIN 3 +define HAL_GPIO_PWM_VOLT_3v3 1 + +# List of files to put in ROMFS. For fmuv3 we need an IO firmware so +# we can automatically update the IOMCU firmware on boot. The format +# is "ROMFS ROMFS-filename source-filename". Paths are relative to the +# ardupilot root. +ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_highpolh.bin + +DMA_NOSHARE SPI1* SPI4* USART6* + +# for users who have replaced their CubeSolo with a CubeOrange: +define HAL_OREO_LED_ENABLED 1 +define HAL_SOLO_GIMBAL_ENABLED HAL_MOUNT_ENABLED + +# Enable Sagetech MXS ADSB transponder +define HAL_ADSB_SAGETECH_MXS_ENABLED HAL_ADSB_ENABLED + +# enable DFU reboot for installing bootloader +# note that if firmware is build with --secure-bl then DFU is +# disabled +ENABLE_DFU_BOOT 1 + +define HAL_ENABLE_FAST_FIFO_RESET_ICM20602 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus-bdshot/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus-bdshot/hwdef-bl.dat new file mode 100644 index 00000000000..268bb3097cd --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus-bdshot/hwdef-bl.dat @@ -0,0 +1 @@ +include ../CubeOrangePlus/hwdef-bl.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus-bdshot/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus-bdshot/hwdef.dat new file mode 100644 index 00000000000..db1f4c48414 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus-bdshot/hwdef.dat @@ -0,0 +1,17 @@ +# Bi-directional dshot version of CubeOrange + +include ../CubeOrangePlus/hwdef.dat + +undef PE14 PE13 PE11 PE9 PD13 PD14 + +PE14 TIM1_CH4 TIM1 PWM(1) GPIO(50) BIDIR +PE13 TIM1_CH3 TIM1 PWM(2) GPIO(51) # this will automatically be shared with TIM1_CH4 +PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52) BIDIR +PE9 TIM1_CH1 TIM1 PWM(4) GPIO(53) # this will automatically be shared with TIM1_CH1 +PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54) BIDIR +PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55) BIDIR + +NODMA I2C* +define STM32_I2C_USE_DMA FALSE + +env DEFAULT_PARAMETERS libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus/defaults.parm diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus/defaults.parm new file mode 100644 index 00000000000..05d30c8e6f1 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus/defaults.parm @@ -0,0 +1,11 @@ +# setup correct defaults for battery monitoring for cube power brick +BATT2_CURR_PIN 4 +BATT2_VOLT_PIN 13 +BATT_AMP_PERVLT 39.877 +BATT_VOLT_MULT 12.02 +BATT2_AMP_PERVLT 39.877 +BATT2_VOLT_MULT 12.02 +# setup ADSB +ADSB_TYPE 1 +SERIAL5_BAUD 57 +SERIAL5_PROTOCOL 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus/hwdef-bl.dat new file mode 100644 index 00000000000..f99489039c3 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus/hwdef-bl.dat @@ -0,0 +1,23 @@ +# hw definition file for processing by chibios_hwdef.py + +# MCU class and specific type +MCU STM32H7xx STM32H757xx +define CORE_CM7 +define SMPS_PWR + +include ../CubeOrange/hwdef-bl.inc + +undef USB_STRING_PRODUCT +undef USB_STRING_MANUFACTURER +undef APJ_BOARD_ID +undef USB_PRODUCT + +# USB setup +USB_PRODUCT 0x1058 +USB_STRING_MANUFACTURER "CubePilot" +USB_STRING_PRODUCT "CubeOrange+-BL" + +# Unused chip select for ICM45686 +PG1 ICM45686_CS CS SPEED_VERYLOW + +APJ_BOARD_ID 1063 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus/hwdef.dat new file mode 100644 index 00000000000..ab1cb10d2a0 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus/hwdef.dat @@ -0,0 +1,44 @@ +# hw definition file for processing by chibios_hwdef.py + +# MCU class and specific type +MCU STM32H7xx STM32H757xx + +define CORE_CM7 +define SMPS_PWR + +include ../CubeOrange/hwdef.inc + +undef USB_STRING_PRODUCT +undef USB_STRING_MANUFACTURER +undef APJ_BOARD_ID +undef USB_PRODUCT + +# USB setup +USB_PRODUCT 0x1058 +USB_STRING_MANUFACTURER "CubePilot" +USB_STRING_PRODUCT "CubeOrange+" + +# Unused chip select for ICM45686 +PG1 ICM45686_CS CS SPEED_VERYLOW + +SPIDEV icm42688_ext2 SPI4 DEVID4 GYRO_EXT_CS MODE3 2*MHZ 8*MHZ + +APJ_BOARD_ID 1063 + +undef CHECK_ICM42688_EXT +undef CHECK_IMU0_PRESENT +undef CHECK_IMU1_PRESENT +undef IMU + +SPIDEV icm42688_ext SPI4 DEVID4 ACCEL_EXT_CS MODE3 2*MHZ 8*MHZ + +IMU Invensensev3 SPI:icm42688_ext ROTATION_YAW_90 +IMU Invensensev3 SPI:icm42688_ext2 ROTATION_PITCH_180_YAW_90 +IMU Invensensev2 SPI:icm20948_ext ROTATION_PITCH_180 +IMU Invensensev2 SPI:icm20948 ROTATION_YAW_270 + +CHECK_ICM42688_EXT2 spi_check_register("icm42688_ext2", INV3REG_WHOAMI, INV3_WHOAMI_ICM42688) +CHECK_ICM42688_EXT spi_check_register("icm42688_ext", INV3REG_WHOAMI, INV3_WHOAMI_ICM42688) + +CHECK_IMU0_PRESENT $CHECK_ICM42688_EXT +CHECK_IMU1_PRESENT $CHECK_ICM20948_EXT || $CHECK_ICM42688_EXT2 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeSolo/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeSolo/hwdef.dat index a1f9b08279d..c16fb1fa6fe 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeSolo/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeSolo/hwdef.dat @@ -49,5 +49,12 @@ COMPASS AK09916:probe_ICM20948 0 ROTATION_ROLL_180_YAW_90 # also probe for external compasses define HAL_PROBE_EXTERNAL_I2C_COMPASSES +undef HAL_OREO_LED_ENABLED define HAL_OREO_LED_ENABLED 1 + define HAL_IMU_TEMP_MARGIN_LOW_DEFAULT 5 + +undef HAL_SOLO_GIMBAL_ENABLED +define HAL_SOLO_GIMBAL_ENABLED HAL_MOUNT_ENABLED + +AUTOBUILD_TARGETS Copter diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeYellow/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeYellow/defaults.parm index 1c6554e50c5..bdb241564ce 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeYellow/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeYellow/defaults.parm @@ -9,3 +9,5 @@ BATT2_VOLT_MULT 12.02 # lower heater gains BRD_HEAT_I 0.07 BRD_HEAT_P 50 +EK2_PRIMARY 1 +EK3_PRIMARY 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeYellow/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeYellow/hwdef.dat index 7e8b5154c48..3fee052b4b8 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeYellow/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeYellow/hwdef.dat @@ -479,3 +479,4 @@ STORAGE_FLASH_PAGE 1 # ardupilot root ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_highpolh.bin +define HAL_ENABLE_FAST_FIFO_RESET_ICM20602 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/DevEBoxH7v2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/DevEBoxH7v2/hwdef.dat index 175d3b6c682..2a8bc1d34a8 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/DevEBoxH7v2/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/DevEBoxH7v2/hwdef.dat @@ -16,8 +16,6 @@ STM32_ST_USE_TIMER 2 # reserve 256 bytes for comms between app and bootloader RAM_RESERVE_START 256 -define NO_DATAFLASH TRUE - FLASH_SIZE_KB 128 FLASH_RESERVE_START_KB 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Durandal/README.md b/libraries/AP_HAL_ChibiOS/hwdef/Durandal/README.md index e16394ef18f..9c179c77998 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Durandal/README.md +++ b/libraries/AP_HAL_ChibiOS/hwdef/Durandal/README.md @@ -500,7 +500,7 @@ The Durandal supports up to 16 PWM outputs. First first 8 outputs (labelled "MAIN") are controlled by a dedicated STM32F100 IO controller. These 8 outputs support all PWM output formats, but not DShot. -The remaining 6 outputs (labelled AUX1 to AUX6) are the "auxillary" +The remaining 6 outputs (labelled AUX1 to AUX6) are the "auxiliary" outputs. These are directly attached to the STM32F427 and support all PWM protocols as well as DShot. @@ -513,7 +513,7 @@ The 8 main PWM outputs are in 3 groups: - PWM 3 and 4 in group2 - PWM 5, 6, 7 and 8 in group3 -The 8 auxillary PWM outputs are in 2 groups: +The 8 auxiliary PWM outputs are in 2 groups: - PWM 1, 2, 3 and 4 in group4 - PWM 5 and 6 in group5 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Durandal/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Durandal/hwdef-bl.dat index ce08ee462c9..cedeba3938b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Durandal/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Durandal/hwdef-bl.dat @@ -60,3 +60,6 @@ PI6 EXT2_CS1 CS PI7 EXT2_CS2 CS PI8 EXT2_CS3 CS PH5 TSENSE_CS CS + +# enable DFU by default +ENABLE_DFU_BOOT 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Durandal/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Durandal/hwdef.dat index f17aa5f51e0..873e63525d6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Durandal/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Durandal/hwdef.dat @@ -346,3 +346,10 @@ define HAL_BATT_CURR_SCALE 36.364 # before we enable it #define HAL_SPI_USE_POLLED +# Enable Sagetech MXS ADSB transponder +define HAL_ADSB_SAGETECH_MXS_ENABLED HAL_ADSB_ENABLED + +# enable DFU reboot for installing bootloader +# note that if firmware is build with --secure-bl then DFU is +# disabled +ENABLE_DFU_BOOT 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/F35Lightning/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/F35Lightning/hwdef.dat index 2b654dac4fb..1389685f412 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/F35Lightning/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/F35Lightning/hwdef.dat @@ -161,5 +161,8 @@ define HAL_BATT_CURR_PIN 12 define HAL_BATT_VOLT_SCALE 11 define HAL_BATT_CURR_SCALE 25 +# minimal drivers to reduce flash usage +include ../include/minimal.inc + # enable IMU fast sampling define HAL_DEFAULT_INS_FAST_SAMPLE 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/F4BY/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/F4BY/hwdef.dat old mode 100755 new mode 100644 index 933f94e2cd4..ab3897d07ba --- a/libraries/AP_HAL_ChibiOS/hwdef/F4BY/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/F4BY/hwdef.dat @@ -1,5 +1,5 @@ # hw definition file for processing by chibios_hwdef.py -# for F4BY v2.1.5 board description http://swift-flyer.com/?page_id=83 +# for F4BY v2.1.5 board description http://swift-flyer.com/?page_id=83 # MCU class and specific type MCU STM32F4xx STM32F407xx @@ -8,8 +8,8 @@ MCU STM32F4xx STM32F407xx APJ_BOARD_ID 20 # USB setup -USB_VENDOR 0x27AC # Swift-Flyer -USB_PRODUCT 0x0201 # fmu usb driver +USB_VENDOR 0x27AC # Swift-Flyer +USB_PRODUCT 0x0201 # fmu usb driver USB_STRING_MANUFACTURER "Swift-Flyer" FLASH_SIZE_KB 1024 @@ -61,7 +61,7 @@ PD8 USART3_TX USART3 NODMA PD9 USART3_RX USART3 PC10 UART4_TX UART4 NODMA -PC11 UART4_RX UART4 +PC11 UART4_RX UART4 # SHARE dma with I2C2_TX PC12 UART5_TX UART5 NODMA @@ -85,7 +85,7 @@ PB12 FRAM_CS CS SPEED_VERYLOW PE15 FLASH_CS CS SPIDEV mpu6000 SPI1 DEVID1 MPU_CS MODE3 1*MHZ 8*MHZ -SPIDEV ramtron SPI2 DEVID2 FRAM_CS MODE3 8*MHZ 8*MHZ +SPIDEV ramtron SPI2 DEVID2 FRAM_CS MODE3 8*MHZ 8*MHZ SPIDEV sdcard SPI2 DEVID3 FLASH_CS MODE0 400*KHZ 25*MHZ # one IMU @@ -106,8 +106,8 @@ define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" # this defines the default maximum clock on I2C devices. define HAL_I2C_MAX_CLOCK 100000 I2C_ORDER I2C2 I2C1 -PB8 I2C1_SCL I2C1 -PB9 I2C1_SDA I2C1 +PB8 I2C1_SCL I2C1 +PB9 I2C1_SDA I2C1 PB10 I2C2_SCL I2C2 PB11 I2C2_SDA I2C2 @@ -152,7 +152,7 @@ PC1 RSSI_IN ADC1 PC2 BATT_CURRENT_SENS ADC1 SCALE(2) PC3 BATT_VOLTAGE_SENS ADC1 SCALE(2) PC4 VDD_5V_SENS ADC1 SCALE(2) -PC5 FMU_SERVORAIL_VCC_SENS ADC1 SCALE(2) +PC5 FMU_SERVORAIL_VCC_SENS ADC1 SCALE(2) PE5 TIM9_CH1 TIM9 ALARM diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FlyingMoonF407/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/FlyingMoonF407/hwdef-bl.dat new file mode 100644 index 00000000000..1eda0170a8c --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/FlyingMoonF407/hwdef-bl.dat @@ -0,0 +1,42 @@ +# hw definition file for processing by chibios_hwdef.py +# for FlyingmoonF407 hardware + +MCU STM32F4xx STM32F407xx + +APJ_BOARD_ID 1067 + +OSCILLATOR_HZ 8000000 + +STM32_ST_USE_TIMER 5 + +# flash size +FLASH_SIZE_KB 1024 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART5 + +PE3 LED_BOOTLOADER OUTPUT +PE2 LED_ACTIVITY OUTPUT +define HAL_LED_ON 1 + +PA9 VBUS INPUT + +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +PC12 UART5_TX UART5 NODMA +PD2 UART5_RX UART5 NODMA + +FLASH_USE_MAX_KB 16 +FLASH_RESERVE_START_KB 0 + +# location of application code +FLASH_BOOTLOADER_LOAD_KB 16 + +# Add CS pins to ensure they are high in bootloader +PA4 ICM20689_CS CS +PB12 FRAM_CS CS SPEED_VERYLOW +PE15 FLASH_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FlyingMoonF407/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/FlyingMoonF407/hwdef.dat new file mode 100644 index 00000000000..61cbe1a94f8 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/FlyingMoonF407/hwdef.dat @@ -0,0 +1,182 @@ +# hw definition file for processing by chibios_hwdef.py +# for FlyingmoonF407 hardware + +# MCU class and specific type +MCU STM32F4xx STM32F407xx + +# board ID for firmware load +APJ_BOARD_ID 1067 + +FLASH_SIZE_KB 1024 + +# crystal frequency +OSCILLATOR_HZ 8000000 + +# this is the STM32 timer that ChibiOS will use for the low level +# driver. This must be a 32 bit timer. We currently only support +# timers 2, 3, 4, 5 and 21. See hal_st_lld.c in ChibiOS for details + +# ChibiOS system timer +STM32_ST_USE_TIMER 5 + +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# this is the pin that senses USB being connected. It is an input pin +# setup as OPENDRAIN +PA9 VBUS INPUT OPENDRAIN + +# The normal usage of this ordering is: +# 1) SERIAL0: console (primary mavlink, USB) +# 2) SERIAL1: telem1 +# 3) SERIAL2: telem2 +# 3) SERIAL3: GPS1 +# 4) SERIAL4: GPS2 + +SERIAL_ORDER OTG1 USART2 UART4 USART3 USART1 + +# telem1 +PD5 USART2_TX USART2 NODMA +PD6 USART2_RX USART2 +PD3 USART2_CTS USART2 +PD4 USART2_RTS USART2 + +# UART4 for telem2 +PC10 UART4_TX UART4 NODMA +PC11 UART4_RX UART4 NODMA + +# USART3 for GPS1 +PD8 USART3_TX USART3 NODMA +PD9 USART3_RX USART3 + +# USART1 for GPS2 +PB6 USART1_TX USART1 +PB7 USART1_RX USART1 + +define HAL_STORAGE_SIZE 16384 + +# CAN Busses +# PD0 CAN1_RX CAN1 +# PD1 CAN1_TX CAN1 + +#SPI1 for MPU +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 +PA4 ICM20689_CS CS + +# SPI bus for dataflash AND SD +PB13 SPI2_SCK SPI2 +PB14 SPI2_MISO SPI2 +PB15 SPI2_MOSI SPI2 + +PB12 FRAM_CS CS SPEED_VERYLOW +PE15 FLASH_CS CS + +# SPI3 bus for reserve +PB3 SPI3_SCK SPI3 +PB4 SPI3_MISO SPI3 +PB5 SPI3_MOSI SPI3 + +SPIDEV icm20689 SPI1 DEVID1 ICM20689_CS MODE3 2*MHZ 8*MHZ +SPIDEV ramtron SPI2 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ +SPIDEV sdcard SPI2 DEVID2 FLASH_CS MODE0 1*MHZ 8*MHZ + +# one IMU +IMU Invensense SPI:icm20689 ROTATION_YAW_270 + +# one baro +BARO MS56XX I2C:1:0x77 + +# look for I2C RM3100 compass +COMPASS RM3100 I2C:1:0x20 false ROTATION_NONE + +define HAL_PROBE_EXTERNAL_I2C_COMPASSES + +# enable RAMTROM parameter storage +define HAL_WITH_RAMTRON 1 +# enable FAT filesystem support +define HAL_OS_FATFS_IO 1 +# now some defines for logging and terrain data files +define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" +define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" + +# define the order that I2C buses +I2C_ORDER I2C1 I2C2 + +# 2nd bus is internal +define HAL_I2C_INTERNAL_MASK 2 + +PB8 I2C1_SCL I2C1 +PB9 I2C1_SDA I2C1 + +PB10 I2C2_SCL I2C2 +PB11 I2C2_SDA I2C2 + +# PWM out pins +PA0 TIM2_CH1 TIM2 PWM(1) GPIO(50) +PA1 TIM2_CH2 TIM2 PWM(2) GPIO(51) +PA2 TIM2_CH3 TIM2 PWM(3) GPIO(52) +PA3 TIM2_CH4 TIM2 PWM(4) GPIO(53) +PE9 TIM1_CH1 TIM1 PWM(5) GPIO(54) +PE11 TIM1_CH2 TIM1 PWM(6) GPIO(55) +PE13 TIM1_CH3 TIM1 PWM(7) GPIO(56) +PE14 TIM1_CH4 TIM1 PWM(8) GPIO(57) +PD12 TIM4_CH1 TIM4 PWM(9) GPIO(58) +PD13 TIM4_CH2 TIM4 PWM(10) GPIO(59) +PD14 TIM4_CH3 TIM4 PWM(11) GPIO(60) +PD15 TIM4_CH4 TIM4 PWM(12) GPIO(61) + +PE4 EXTERN_GPIO1 OUTPUT GPIO(1) +PC13 EXTERN_GPIO2 OUTPUT GPIO(2) +PC14 EXTERN_GPIO3 OUTPUT GPIO(3) +PE6 EXTERN_GPIO4 OUTPUT GPIO(4) +PC15 EXTERN_GPIO5 OUTPUT GPIO(5) +define RELAY1_PIN_DEFAULT 1 +define RELAY2_PIN_DEFAULT 2 +define RELAY3_PIN_DEFAULT 3 +define RELAY4_PIN_DEFAULT 4 +define RELAY5_PIN_DEFAULT 5 + +# also USART6_RX for serial RC +PC7 TIM8_CH2 TIM8 RCIN PULLDOWN LOW DMA_CH0 + +# LED setup is similar to PixRacer +define HAL_HAVE_PIXRACER_LED +PE3 LED_RED OUTPUT GPIO(10) +PE2 LED_GREEN OUTPUT GPIO(11) +PE1 LED_BLUE OUTPUT GPIO(12) +PE0 LED_YELOW OUTPUT GPIO(13) + +define HAL_GPIO_A_LED_PIN 10 +define HAL_GPIO_B_LED_PIN 11 +define HAL_GPIO_C_LED_PIN 12 + +define HAL_GPIO_LED_ON 0 +define HAL_GPIO_LED_OFF 1 + +# analog in +PC0 PRESSURE_SENS ADC1 SCALE(2) +PC1 RSSI_IN ADC1 SCALE(2) + +# define the primary battery connectors. +PC2 BATT_CURRENT_SENS ADC1 SCALE(2) +PC3 BATT_VOLTAGE_SENS ADC1 SCALE(2) +PC4 VDD_5V_SENS ADC1 SCALE(2) +PC5 FMU_SERVORAIL_VCC_SENS ADC1 SCALE(2) + +define HAL_BATT_VOLT_PIN 13 +define HAL_BATT_CURR_PIN 12 +define HAL_BATT_VOLT_SCALE 20 +define HAL_BATT_CURR_SCALE 17 + +PE5 TIM9_CH1 TIM9 ALARM + +# IRQ for MPU6000 +PB0 DRDY_ICM20689 INPUT PULLUP +PB1 DRDY_IST8310 INPUT PULLUP + +define AP_FEATURE_BRD_PWM_COUNT_PARAM 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FlyingMoonF427/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/FlyingMoonF427/hwdef-bl.dat new file mode 100644 index 00000000000..4303df691cb --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/FlyingMoonF427/hwdef-bl.dat @@ -0,0 +1,39 @@ +# hw definition file for processing by chibios_hwdef.py +# for FlyingmoonF427 hardware bootloader + +MCU STM32F4xx STM32F427xx + +APJ_BOARD_ID 1068 + +OSCILLATOR_HZ 8000000 + +STM32_ST_USE_TIMER 5 + +FLASH_SIZE_KB 2048 +FLASH_RESERVE_START_KB 0 +FLASH_BOOTLOADER_LOAD_KB 16 + +SERIAL_ORDER OTG1 UART5 + +PE3 LED_BOOTLOADER OUTPUT +PE2 LED_ACTIVITY OUTPUT +define HAL_LED_ON 1 + +PA9 VBUS INPUT + +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +PC12 UART5_TX UART5 NODMA +PD2 UART5_RX UART5 NODMA + +PB0 ICM20689_CS CS +PB1 ICM42605_CS CS +PB2 ICM20649_CS CS +PA4 RM3100_CS CS +PE10 MAX7456_CS CS +PB12 FRAM_CS CS SPEED_VERYLOW +PE15 FLASH_CS CS \ No newline at end of file diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FlyingMoonF427/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/FlyingMoonF427/hwdef.dat new file mode 100644 index 00000000000..a8e6624e1d2 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/FlyingMoonF427/hwdef.dat @@ -0,0 +1,200 @@ +# hw definition file for processing by chibios_hwdef.py +# for FlyingmoonF427 hardware + +# MCU class and specific type +MCU STM32F4xx STM32F427xx + +# board ID for firmware load +APJ_BOARD_ID 1068 + +FLASH_SIZE_KB 2048 + +env OPTIMIZE -O2 + +# crystal frequency +OSCILLATOR_HZ 8000000 + +# this is the STM32 timer that ChibiOS will use for the low level +# driver. This must be a 32 bit timer. We currently only support +# timers 2, 3, 4, 5 and 21. See hal_st_lld.c in ChibiOS for details + +# ChibiOS system timer +STM32_ST_USE_TIMER 5 + +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# this is the pin that senses USB being connected. It is an input pin +# setup as OPENDRAIN +PA9 VBUS INPUT OPENDRAIN + +# The normal usage of this ordering is: +# 1) SERIAL0: console (primary mavlink, usually USB) +# 2) SERIAL1: telem1 +# 5) SERIAL2: telem2 +# 3) SERIAL3: primary GPS1 +# 4) SERIAL4: second GPS2 +# 6) SERIAL5: extra UART or sbus output (usually RTOS debug console) + +SERIAL_ORDER OTG1 USART1 UART4 USART2 USART3 UART5 + +# USART1 for telem1 +PB6 USART1_TX USART1 +PB7 USART1_RX USART1 + +# USART2 for primary GPS1 +PD5 USART2_TX USART2 NODMA +PD6 USART2_RX USART2 + +# USART3 for second GPS2 +PD8 USART3_TX USART3 NODMA +PD9 USART3_RX USART3 + +# UART4 for telem2 +PC10 UART4_TX UART4 NODMA +PC11 UART4_RX UART4 NODMA + +# UART5 +PC12 UART5_TX UART5 NODMA +PD2 UART5_RX UART5 NODMA + +define HAL_STORAGE_SIZE 16384 + +# CAN Busses +PD0 CAN1_RX CAN1 +PD1 CAN1_TX CAN1 + +# SPI1 for IMU OSD +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 +PB0 ICM20689_CS CS +PB1 ICM42605_CS CS +PB2 ICM20649_CS CS +PA4 RM3100_CS CS +PE10 MAX7456_CS CS + +# SPI bus for dataflash AND SD +PB13 SPI2_SCK SPI2 +PB14 SPI2_MISO SPI2 +PB15 SPI2_MOSI SPI2 + +PB12 FRAM_CS CS SPEED_VERYLOW +PE15 FLASH_CS CS + +# SPI3 bus for reserve +PB3 SPI3_SCK SPI3 +PB4 SPI3_MISO SPI3 +PB5 SPI3_MOSI SPI3 + +SPIDEV icm20689 SPI1 DEVID1 ICM20689_CS MODE3 2*MHZ 8*MHZ +SPIDEV icm42605 SPI1 DEVID2 ICM42605_CS MODE3 2*MHZ 8*MHZ +SPIDEV icm20649 SPI1 DEVID3 ICM20649_CS MODE3 2*MHZ 8*MHZ +SPIDEV rm3100 SPI1 DEVID4 RM3100_CS MODE3 2*MHZ 8*MHZ +SPIDEV osd SPI1 DEVID5 MAX7456_CS MODE0 10*MHZ 10*MHZ +SPIDEV ramtron SPI2 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ +SPIDEV sdcard SPI2 DEVID2 FLASH_CS MODE0 1*MHZ 8*MHZ + +# Three IMUs +IMU Invensense SPI:icm20689 ROTATION_NONE +IMU Invensensev3 SPI:icm42605 ROTATION_ROLL_180_YAW_90 +IMU Invensensev2 SPI:icm20649 ROTATION_NONE + +# Two baro +BARO SPL06 I2C:0:0x76 +BARO MS56XX I2C:0:0x77 + +# compass +COMPASS RM3100 SPI:rm3100 false ROTATION_NONE + +# also probe external compasses +define HAL_PROBE_EXTERNAL_I2C_COMPASSES + +# enable RAMTROM parameter storage +define HAL_WITH_RAMTRON 1 +# enable FAT filesystem support +define HAL_OS_FATFS_IO 1 +# now some defines for logging and terrain data files +define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" +define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" + +# define the order that I2C buses +I2C_ORDER I2C1 I2C2 +PB8 I2C1_SCL I2C1 +PB9 I2C1_SDA I2C1 +PB10 I2C2_SCL I2C2 +PB11 I2C2_SDA I2C2 + +define HAL_I2C_INTERNAL_MASK 0 + +# PWM out pins +PA0 TIM2_CH1 TIM2 PWM(1) GPIO(50) +PA1 TIM2_CH2 TIM2 PWM(2) GPIO(51) +PA2 TIM2_CH3 TIM2 PWM(3) GPIO(52) +PA3 TIM2_CH4 TIM2 PWM(4) GPIO(53) +PE9 TIM1_CH1 TIM1 PWM(5) GPIO(54) +PE11 TIM1_CH2 TIM1 PWM(6) GPIO(55) +PE13 TIM1_CH3 TIM1 PWM(7) GPIO(56) +PE14 TIM1_CH4 TIM1 PWM(8) GPIO(57) +PD12 TIM4_CH1 TIM4 PWM(9) GPIO(58) +PD13 TIM4_CH2 TIM4 PWM(10) GPIO(59) +PD14 TIM4_CH3 TIM4 PWM(11) GPIO(60) +PD15 TIM4_CH4 TIM4 PWM(12) GPIO(61) +PC6 TIM3_CH1 TIM3 PWM(13) GPIO(62) NODMA +PC8 TIM3_CH3 TIM3 PWM(14) GPIO(63) NODMA +PC9 TIM3_CH4 TIM3 PWM(15) GPIO(64) NODMA + +PC15 EXTERN_GPIO1 OUTPUT GPIO(1) +PC14 EXTERN_GPIO2 OUTPUT GPIO(2) +PC13 EXTERN_GPIO3 OUTPUT GPIO(3) +PE6 EXTERN_GPIO4 OUTPUT GPIO(4) +PE4 EXTERN_GPIO5 OUTPUT GPIO(5) +define RELAY1_PIN_DEFAULT 1 +define RELAY2_PIN_DEFAULT 2 +define RELAY3_PIN_DEFAULT 3 +define RELAY4_PIN_DEFAULT 4 +define RELAY5_PIN_DEFAULT 5 + +# also USART6_RX for serial RC +PC7 TIM8_CH2 TIM8 RCIN PULLDOWN LOW DMA_CH0 + +# LED setup is similar to PixRacer +define HAL_HAVE_PIXRACER_LED +PE3 LED_RED OUTPUT GPIO(10) +PE2 LED_GREEN OUTPUT GPIO(11) +PE1 LED_BLUE OUTPUT GPIO(12) +PE0 LED_YELOW OUTPUT GPIO(13) + +define HAL_GPIO_A_LED_PIN 10 +define HAL_GPIO_B_LED_PIN 11 +define HAL_GPIO_C_LED_PIN 12 + +define HAL_GPIO_LED_ON 0 +define HAL_GPIO_LED_OFF 1 + +# analog in +PC0 PRESSURE_SENS ADC1 SCALE(2) +PC1 RSSI_IN ADC1 SCALE(2) + +# define the primary battery connectors. +PC2 BATT_CURRENT_SENS ADC1 SCALE(2) +PC3 BATT_VOLTAGE_SENS ADC1 SCALE(2) +PC4 VDD_5V_SENS ADC1 SCALE(2) +PC5 FMU_SERVORAIL_VCC_SENS ADC1 SCALE(4) + +define HAL_BATT_VOLT_PIN 13 +define HAL_BATT_CURR_PIN 12 +define HAL_BATT_VOLT_SCALE 22 +define HAL_BATT_CURR_SCALE 55.55 +define HAL_HAVE_SAFETY_SWITCH 1 +PE7 LED_SAFETY OUTPUT +PE8 SAFETY_IN INPUT PULLDOWN +PE5 TIM9_CH1 TIM9 ALARM + +# setup for OSD +define OSD_ENABLED 1 +define HAL_OSD_TYPE_DEFAULT 1 +ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FlywooF745/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF745/hwdef.dat index 54af8561138..37b78c54515 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/FlywooF745/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF745/hwdef.dat @@ -166,7 +166,11 @@ define PRECISION_LANDING 0 define HAL_BARO_WIND_COMP_ENABLED 0 define GRIPPER_ENABLED 0 define HAL_PARACHUTE_ENABLED 0 + + +# minimal drivers to reduce flash usage +include ../include/minimal.inc define HAL_SPRAYER_ENABLED 0 define AP_BATTMON_SMBUS_ENABLE 0 -define AP_BATTMON_FUEL_ENABLE 0 define AP_OPTICALFLOW_ENABLED 0 +define AP_ICENGINE_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FreeflyRTK/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/FreeflyRTK/hwdef.dat index 5a889940e8c..126ebd67860 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/FreeflyRTK/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/FreeflyRTK/hwdef.dat @@ -120,8 +120,6 @@ define CAN_APP_NODE_NAME "org.ardupilot.FreeflyRTK" define HAL_NO_MONITOR_THREAD -define HAL_MINIMIZE_FEATURES 0 - define HAL_DEVICE_THREAD_STACK 768 # we setup a small defaults.parm @@ -130,6 +128,7 @@ define AP_PARAM_MAX_EMBEDDED_PARAM 256 # disable dual GPS and GPS blending to save flash space define GPS_MAX_RECEIVERS 1 define GPS_MAX_INSTANCES 1 +define GPS_MOVING_BASELINE 1 define HAL_COMPASS_MAX_SENSORS 1 # GPS+MAG+BARO+Buzzer+NeoPixels diff --git a/libraries/AP_HAL_ChibiOS/hwdef/G4-ESC/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/G4-ESC/hwdef.dat index d43e0ecf6df..4042240ca89 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/G4-ESC/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/G4-ESC/hwdef.dat @@ -135,8 +135,6 @@ define HAL_UART_STACK_SIZE 0x200 define HAL_NO_MONITOR_THREAD -define HAL_MINIMIZE_FEATURES 0 - define HAL_DEVICE_THREAD_STACK 0x200 define STORAGE_THD_WA_SIZE 512 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL/hwdef.dat index 20714712df3..275ec38ea78 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL/hwdef.dat @@ -1,6 +1,8 @@ # hw definition file for processing by chibios_hwdef.py # for H757 +AUTOBUILD_TARGETS None + # MCU class and specific type MCU STM32H7xx STM32H757xx diff --git a/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL_intf/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL_intf/hwdef-bl.dat old mode 100755 new mode 100644 index a335710110f..8a023dc9391 --- a/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL_intf/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL_intf/hwdef-bl.dat @@ -73,4 +73,4 @@ PB13 VBUS INPUT OPENDRAIN define CAN_APP_NODE_NAME "org.cubepilot.H757" -define BOOTLOADER_DEBUG SD1 \ No newline at end of file +define BOOTLOADER_DEBUG SD1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL_intf/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL_intf/hwdef.dat old mode 100755 new mode 100644 index 828d25435a3..337fbbfa6d4 --- a/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL_intf/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL_intf/hwdef.dat @@ -1,6 +1,8 @@ # hw definition file for processing by chibios_hwdef.py # for H757 +AUTOBUILD_TARGETS None + # MCU class and specific type MCU STM32H7xx STM32H757xx @@ -70,7 +72,7 @@ define DISABLE_SERIAL_ESC_COMM TRUE PB13 VBUS INPUT OPENDRAIN # QSPI Flash -# we only declare this so that initialisation +# we only declare this so that initialisation # doesn't reset these pins PF8 QUADSPI_BK1_IO0 QUADSPI1 PF9 QUADSPI_BK1_IO1 QUADSPI1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef.dat index ab5ae7a84b9..8c49b59086e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef.dat @@ -71,8 +71,6 @@ define HAL_DISABLE_LOOP_DELAY define USB_USE_WAIT TRUE define HAL_USE_USB_MSD TRUE -define HAL_MINIMIZE_FEATURES 0 - define HAL_DEVICE_THREAD_STACK 2048 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Hitec-Airspeed/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Hitec-Airspeed/hwdef.dat index b5e54966146..a41af41cdcd 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Hitec-Airspeed/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Hitec-Airspeed/hwdef.dat @@ -24,17 +24,21 @@ OSCILLATOR_HZ 24000000 # assume the 128k flash part FLASH_SIZE_KB 128 +# UARTs disabled to save flash # order of UARTs -SERIAL_ORDER USART1 +# SERIAL_ORDER USART1 +SERIAL_ORDER +define HAL_USE_UART FALSE +define HAL_NO_UARTDRIVER TRUE define HAL_CAN_POOL_SIZE 6000 -STDOUT_SERIAL SD1 -STDOUT_BAUDRATE 57600 +# STDOUT_SERIAL SD1 +# STDOUT_BAUDRATE 57600 # USART1, telemetry -PB6 USART1_TX USART1 SPEED_HIGH -PB7 USART1_RX USART1 SPEED_HIGH +# PB6 USART1_TX USART1 SPEED_HIGH +# PB7 USART1_RX USART1 SPEED_HIGH # LEDs PA10 LED OUTPUT LOW @@ -92,8 +96,6 @@ define HAL_DISABLE_ADC_DRIVER TRUE define HAL_NO_MONITOR_THREAD -define HAL_MINIMIZE_FEATURES 0 - define HAL_DEVICE_THREAD_STACK 0x200 define STORAGE_THD_WA_SIZE 512 @@ -101,6 +103,8 @@ define IO_THD_WA_SIZE 512 define AP_PARAM_MAX_EMBEDDED_PARAM 128 +define HAL_NO_RCIN_THREAD +define HAL_NO_RCOUT_THREAD # keep ROMFS uncompressed as we don't have enough RAM diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HitecMosaic/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/HitecMosaic/hwdef.dat index 1af1bed87d0..312495b0b78 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/HitecMosaic/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/HitecMosaic/hwdef.dat @@ -110,8 +110,6 @@ define HAL_UART_STACK_SIZE 0x200 define HAL_NO_MONITOR_THREAD -define HAL_MINIMIZE_FEATURES 0 - # only one I2C bus I2C_ORDER I2C1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_GPS/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_GPS/hwdef-bl.dat new file mode 100644 index 00000000000..ced540c3e47 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_GPS/hwdef-bl.dat @@ -0,0 +1,86 @@ +# hw definition file for processing by chibios_pins.py + +# MCU class and specific type +MCU STM32G4xx STM32G474xx + +FLASH_RESERVE_START_KB 0 +FLASH_BOOTLOADER_LOAD_KB 32 + +# reserve some space for params +APP_START_OFFSET_KB 4 + +# assume 512k flash part +FLASH_SIZE_KB 512 + +# board ID for firmware load +APJ_BOARD_ID 1053 + +# setup build for a peripheral firmware +env AP_PERIPH 1 + +# debug on USART2 +STDOUT_SERIAL SD2 +STDOUT_BAUDRATE 57600 + +# crystal frequency +OSCILLATOR_HZ 16000000 + +define CH_CFG_ST_FREQUENCY 1000000 + +# order of UARTs +SERIAL_ORDER USART2 + +# blue LED +PC10 LED_BOOTLOADER OUTPUT HIGH +define HAL_LED_ON 0 + +PB15 LED_RED OUTPUT HIGH +PC6 LED_GREEN OUTPUT HIGH + +# USART2 +PA2 USART2_TX USART2 +PA3 USART2_RX USART2 + +# SWD debugging +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +define HAL_USE_SERIAL TRUE + +define STM32_SERIAL_USE_USART1 FALSE +define STM32_SERIAL_USE_USART2 TRUE +define STM32_SERIAL_USE_USART3 FALSE + +define HAL_NO_GPIO_IRQ +define HAL_USE_EMPTY_IO TRUE + +# avoid timer and RCIN threads to save memory +define HAL_NO_TIMER_THREAD +define HAL_NO_RCIN_THREAD + +define DMA_RESERVE_SIZE 0 + +define HAL_DISABLE_LOOP_DELAY + +# enable CAN support + +PA11 CAN1_RX CAN1 +PA12 CAN1_TX CAN1 +PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW + +PB12 CAN2_RX CAN2 +PB13 CAN2_TX CAN2 +PB14 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW + +define CAN_APP_NODE_NAME "org.ardupilot.HolybroG4_GPS" + +# make bl baudrate match debug baudrate for easier debugging +define BOOTLOADER_BAUDRATE 57600 + +# use a smaller bootloader timeout +define HAL_BOOTLOADER_TIMEOUT 2500 + +# Add CS pins to ensure they are high in bootloader +PB1 BARO_CS CS +PC4 GYRO_CS CS +PC14 ICM_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_GPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_GPS/hwdef.dat new file mode 100644 index 00000000000..eb5008dfbe3 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_GPS/hwdef.dat @@ -0,0 +1,162 @@ +# hw definition file for processing by chibios_pins.py +# MCU class and specific type + +# MCU class and specific type +MCU STM32G4xx STM32G474xx + +FLASH_RESERVE_START_KB 36 + +STORAGE_FLASH_PAGE 16 +define HAL_STORAGE_SIZE 800 + +# board ID for firmware load +APJ_BOARD_ID 1053 + +# setup build for a peripheral firmware +env AP_PERIPH 1 + +# crystal frequency +OSCILLATOR_HZ 16000000 + +define CH_CFG_ST_FREQUENCY 1000000 + +# assume 512k flash part +FLASH_SIZE_KB 512 + +# debug on USART2 +STDOUT_SERIAL SD2 +STDOUT_BAUDRATE 57600 + +# order of UARTs +SERIAL_ORDER USART2 USART3 + +# sensor power control +PC11 VDD_3V3_SENSORS_EN OUTPUT HIGH + +# LEDs +PC10 LED OUTPUT HIGH GPIO(2) # blue +PB15 LED_R OUTPUT HIGH GPIO(0) +PC6 LED_G OUTPUT HIGH GPIO(1) + +define HAL_GPIO_A_LED_PIN 0 +define HAL_GPIO_B_LED_PIN 1 +define HAL_GPIO_C_LED_PIN 2 + +define HAL_GPIO_LED_ON 0 +define HAL_GPIO_LED_OFF 1 + +define HAL_HAVE_PIXRACER_LED + +# USART3, GPS +PB10 USART3_TX USART3 +PB11 USART3_RX USART3 + +# USART2, debug +PA2 USART2_TX USART2 +PA3 USART2_RX USART2 + +# SWD debugging +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# I2C1 bus +PB7 I2C1_SDA I2C1 +PB8 I2C1_SCL I2C1 + +# I2C2 bus +PA8 I2C2_SDA I2C2 +PA9 I2C2_SCL I2C2 + +define HAL_I2C_INTERNAL_MASK 3 + +# I2C buses +I2C_ORDER I2C1 I2C2 + +# one SPI bus +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 + +# SPI CS +PC4 GYR_CS CS +PB1 ACC_CS CS +PC14 ICM_CS CS + +# GPS PPS +PA15 GPS_PPS_IN INPUT + +# SPI devices +SPIDEV bmi088_a SPI1 DEVID1 ACC_CS MODE3 10*MHZ 10*MHZ +SPIDEV bmi088_g SPI1 DEVID2 GYR_CS MODE3 10*MHZ 10*MHZ + +# compass +COMPASS BMM150 I2C:0:0x10 false ROTATION_YAW_90 + +# baro +BARO BMP388 I2C:0:0x77 + +# IMU +IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_ROLL_180_YAW_90 + +define HAL_BARO_ALLOW_INIT_NO_BARO + +define HAL_USE_ADC FALSE +define STM32_ADC_USE_ADC1 FALSE +define HAL_DISABLE_ADC_DRIVER TRUE + +define HAL_NO_GPIO_IRQ + +# avoid RCIN thread to save memory +define HAL_NO_RCIN_THREAD + +define HAL_USE_RTC FALSE +define DISABLE_SERIAL_ESC_COMM TRUE + +define DMA_RESERVE_SIZE 0 + +define HAL_DISABLE_LOOP_DELAY + +# enable CAN support + +PA11 CAN1_RX CAN1 +PA12 CAN1_TX CAN1 +PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW + +PB12 CAN2_RX CAN2 +PB13 CAN2_TX CAN2 +PB14 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW + +define CAN_APP_NODE_NAME "org.ardupilot.HolybroG4_GPS" + +define HAL_NO_LOGGING +define HAL_NO_MONITOR_THREAD + +define HAL_DEVICE_THREAD_STACK 768 + +# we setup a small defaults.parm +define AP_PARAM_MAX_EMBEDDED_PARAM 256 + +# disable dual GPS and GPS blending to save flash space +define GPS_MAX_RECEIVERS 1 +define GPS_MAX_INSTANCES 1 +define HAL_COMPASS_MAX_SENSORS 1 + +# add support for moving baseline yaw +define GPS_MOVING_BASELINE 1 + +# GPS+MAG+BARO+LEDs +define HAL_PERIPH_ENABLE_GPS +define HAL_PERIPH_ENABLE_MAG +define HAL_PERIPH_ENABLE_BARO +define HAL_PERIPH_ENABLE_NOTIFY +define HAL_PERIPH_ENABLE_RC_OUT + +# single baro +define BARO_MAX_INSTANCES 1 + +# GPS on 2nd port +define HAL_PERIPH_GPS_PORT_DEFAULT 1 + +# keep ROMFS uncompressed as we don't have enough RAM +# to uncompress the bootloader at runtime +env ROMFS_UNCOMPRESSED True diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HolybroGPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/HolybroGPS/hwdef.dat index 1ecc334d96e..6c73e5f3d56 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/HolybroGPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/HolybroGPS/hwdef.dat @@ -142,8 +142,6 @@ define CAN_APP_NODE_NAME "org.ardupilot.HolybroGPS" define HAL_NO_LOGGING define HAL_NO_MONITOR_THREAD -define HAL_MINIMIZE_FEATURES 0 - define HAL_DEVICE_THREAD_STACK 768 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-GSF405A/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-GSF405A/hwdef.dat index b47ea2582ae..9428bb4cccd 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-GSF405A/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-GSF405A/hwdef.dat @@ -156,7 +156,7 @@ define HAL_WITH_DSP FALSE # --------------------- save flash ---------------------- define AP_BATTMON_SMBUS_ENABLE 0 -define AP_BATTMON_FUEL_ENABLE 0 +define AP_BATT_MONITOR_MAX_INSTANCES 1 define HAL_PARACHUTE_ENABLED 0 define HAL_SPRAYER_ENABLED 0 define HAL_GENERATOR_ENABLED 0 @@ -169,3 +169,4 @@ define HAL_NMEA_OUTPUT_ENABLED 0 define HAL_BUTTON_ENABLED 0 define HAL_OREO_LED_ENABLED 0 define HAL_PICCOLO_CAN_ENABLE 0 +define BARO_MAX_INSTANCES 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4/hwdef.dat index f46e377fcac..14b44b12ce0 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4/hwdef.dat @@ -147,3 +147,6 @@ define HAL_LOGGING_DATAFLASH_ENABLED 1 define OSD_ENABLED 1 define HAL_OSD_TYPE_DEFAULT 1 ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin + +# minimal drivers to reduce flash usage +include ../include/minimal.inc diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4Mini/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4Mini/hwdef.dat index 813aa8eac54..a1b3473784d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4Mini/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF4Mini/hwdef.dat @@ -41,7 +41,6 @@ define STM32_PWM_USE_ADVANCED TRUE # save some flash define AP_BATTMON_SMBUS_ENABLE 0 -define AP_BATTMON_FUEL_ENABLE 0 define HAL_PARACHUTE_ENABLED 0 define HAL_SPRAYER_ENABLED 0 define HAL_MOUNT_ENABLED 0 @@ -49,3 +48,4 @@ define HAL_GENERATOR_ENABLED 0 define AC_OAPATHPLANNER_ENABLED 0 define PRECISION_LANDING 0 define AP_OPTICALFLOW_ENABLED 0 +define AP_ICENGINE_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef.dat index d19994e1860..1be67c76387 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef.dat @@ -135,6 +135,8 @@ IMU Invensense SPI:mpu6000 ROTATION_YAW_180 # one BARO BARO BMP280 I2C:0:0x76 +define HAL_PROBE_EXTERNAL_I2C_BAROS +define HAL_BARO_ALLOW_INIT_NO_BARO define HAL_OS_FATFS_IO 1 define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" @@ -148,9 +150,8 @@ ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin define STM32_PWM_USE_ADVANCED TRUE -# disable SMBUS and fuel battery monitors to save flash +# disable SMBUS battery monitors to save flash define AP_BATTMON_SMBUS_ENABLE 0 -define AP_BATTMON_FUEL_ENABLE 0 # disable parachute and sprayer to save flash define HAL_PARACHUTE_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7Mini/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7Mini/hwdef.dat index 3e420242abf..82eeb5d570b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7Mini/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7Mini/hwdef.dat @@ -151,9 +151,8 @@ ROMFS_WILDCARD libraries/AP_OSD/fonts/font0.bin define STM32_PWM_USE_ADVANCED TRUE -# disable SMBUS and fuel battery monitors to save flash +# disable SMBUS battery monitors to save flash define AP_BATTMON_SMBUS_ENABLE 0 -define AP_BATTMON_FUEL_ENABLE 0 # disable parachute and sprayer to save flash define HAL_PARACHUTE_ENABLED 0 @@ -169,3 +168,4 @@ define HAL_GENERATOR_ENABLED 0 define AC_OAPATHPLANNER_ENABLED 0 define PRECISION_LANDING 0 define AP_OPTICALFLOW_ENABLED 0 +define AP_ICENGINE_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7-bdshot/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7-bdshot/hwdef-bl.dat new file mode 100644 index 00000000000..e5069afab06 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7-bdshot/hwdef-bl.dat @@ -0,0 +1 @@ +include ../KakuteH7/hwdef-bl.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7-bdshot/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7-bdshot/hwdef.dat new file mode 100644 index 00000000000..2d1c0934f9a --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7-bdshot/hwdef.dat @@ -0,0 +1,18 @@ +# Bi-directional dshot version of KakuteH7 + +include ../KakuteH7/hwdef.dat + +undef PB0 PB1 PB3 PB10 PC7 + +# Must use USART6 for RCIN rather than RCINT as timer needed for bi-dir dshot +PC7 USART6_RX USART6 NODMA + +define HAL_SERIAL6_PROTOCOL SerialProtocol_RCIN +define HAL_SERIAL6_BAUD 115 +define HAL_SERIAL7_PROTOCOL SerialProtocol_ESCTelemetry +define HAL_SERIAL7_BAUD 115 + +PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50) BIDIR +PB1 TIM3_CH4 TIM3 PWM(2) GPIO(51) +PB3 TIM2_CH2 TIM2 PWM(3) GPIO(52) BIDIR +PB10 TIM2_CH3 TIM2 PWM(4) GPIO(53) BIDIR diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7/hwdef-bl.dat index 1d71a987c6d..a39b0076291 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7/hwdef-bl.dat @@ -18,7 +18,6 @@ FLASH_RESERVE_START_KB 0 # the location where the bootloader will put the firmware FLASH_BOOTLOADER_LOAD_KB 128 -STORAGE_FLASH_PAGE 14 define HAL_STORAGE_SIZE 32768 # order of UARTs (and USB) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7/hwdef.dat index 4f4c844561a..140b1bfb996 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7/hwdef.dat @@ -132,6 +132,10 @@ SPIDEV icm20689 SPI4 DEVID1 ICM20689_CS MODE3 1*MHZ 4*MHZ SPIDEV sdcard SPI1 DEVID1 SDCARD_CS MODE0 400*KHZ 25*MHZ SPIDEV osd SPI2 DEVID4 MAX7456_CS MODE0 10*MHZ 10*MHZ +# bluetooth power switch, turn it off to prevent rf interference +PE13 EVENT_OUT OUTPUT LOW PUSHPULL GPIO(82) +define RELAY3_PIN_DEFAULT 82 + # no built-in compass, but probe the i2c bus for all possible # external compass types define ALLOW_ARM_NO_COMPASS @@ -151,7 +155,6 @@ define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" # setup for OSD define OSD_ENABLED 1 -define OSD_PARAM_ENABLED 0 define HAL_OSD_TYPE_DEFAULT 1 ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini-Nand/README.md b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini-Nand/README.md new file mode 100644 index 00000000000..4896fb1f236 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini-Nand/README.md @@ -0,0 +1,98 @@ +# KakuteH7Mini-Nand Flight Controller + +The KakuteH7Mini-Nand is a flight controller produced by [Holybro](http://www.holybro.com/). + +## Features + + - MCU - STM32H743 32-bit processor running at 480 MHz + - IMU - BMI270 + - Barometer - BMP280 + - OSD - AT7456E + - Onboard Flash: 1GBit + - 6x UARTs (1,2,3,4,6,7) + - 9x PWM Outputs (8 Motor Output, 1 LED) + - Battery input voltage: 2S-6S + - BEC 5V 2A + +## Pinout + +![KakuteH7Mini-Nand Board](../KakuteH7Mini/KakuteH7Mini_Board.jpg "KakuteH7Mini-Nand") + +## UART Mapping + +The UARTs are marked Rn and Tn in the above pinouts. The Rn pin is the +receive pin for UARTn. The Tn pin is the transmit pin for UARTn. + + - SERIAL0 -> USB + - SERIAL1 -> UART1 (DJI VTX, DMA-enabled) + - SERIAL2 -> UART2 (VTX) + - SERIAL3 -> UART3 (GPS, DMA-enabled) + - SERIAL4 -> UART4 (DMA-enabled) + - SERIAL5 -> not available + - SERIAL6 -> UART6 (RX/SBUS, DMA-enabled) + - SERIAL7 -> UART7 (ESC Telemetry) + +## RC Input + +RC input is configured on the R6 (UART6_RX) pin. It supports all serial RC +protocols except PPM. For protocols requiring half-duplex serial to transmit +telemetry (such as FPort) you should setup SERIAL6 with half-duplex, pin-swap +and inversion enabled. + +## FrSky Telemetry + +FrSky Telemetry is supported using the T6 pin (UART6 transmit). You need to set the following parameters to enable support for FrSky S.PORT + + - SERIAL6_PROTOCOL 10 + - SERIAL6_OPTIONS 7 + +## OSD Support + +The KakuteH7Mini-Nand supports OSD using OSD_TYPE 1 (MAX7456 driver). + +## PWM Output + +The KakuteH7Mini-Nand supports up to 9 PWM outputs. The pads for motor output +M1 to M4 on the motor connectors and M5 to M8 on separate pads, plus +M9 for LED strip or another PWM output. + +The PWM is in 5 groups: + + - PWM 1, 2 in group1 + - PWM 3, 4 in group2 + - PWM 5, 6 in group3 + - PWM 7, 8 in group4 + - PWM 9 in group5 + +Channels within the same group need to use the same output rate. If +any channel in a group uses DShot then all channels in the group need +to use DShot. Channels 1-4 support bi-directional dshot. + +## Battery Monitoring + +The board has a builtin voltage and current sensor. The current +sensor can read up to 130 Amps. The voltage sensor can handle up to 6S +LiPo batteries. + +The correct battery setting parameters are: + + - BATT_MONITOR 4 + - BATT_VOLT_PIN 10 + - BATT_CURR_PIN 11 + - BATT_VOLT_MULT 11.1 + - BATT_AMP_PERVLT 59.5 + +## Compass + +The KakuteH7Mini-Nand does not have a builtin compass, but you can attach an external compass using I2C on the SDA and SCL pads. + +## Loading Firmware + +Initial firmware load can be done with DFU by plugging in USB with the +bootloader button pressed. Then you should load the "with_bl.hex" +firmware, using your favourite DFU loading tool. + +Once the initial firmware is loaded you can update the firmware using +any ArduPilot ground station software. Updates should be done with the +*.apj firmware files. + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini-Nand/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini-Nand/hwdef-bl.dat new file mode 100644 index 00000000000..fc8e14b874f --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini-Nand/hwdef-bl.dat @@ -0,0 +1 @@ +include ../KakuteH7Mini/hwdef-bl.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini-Nand/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini-Nand/hwdef.dat new file mode 100644 index 00000000000..98d7f7c0388 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini-Nand/hwdef.dat @@ -0,0 +1,12 @@ +# KakuteH7Mini Nand with larger flash chip + +include ../KakuteH7Mini/hwdef.dat + +undef mpu6000 +undef IMU + +SPIDEV bmi270 SPI4 DEVID1 MPU6000_CS MODE3 1*MHZ 4*MHZ + +IMU BMI270 SPI:bmi270 ROTATION_PITCH_180_YAW_90 + +define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25N01GV diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini/hwdef-bl.dat index 22500bc7881..c66e93ba9df 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini/hwdef-bl.dat @@ -18,7 +18,6 @@ FLASH_RESERVE_START_KB 0 # the location where the bootloader will put the firmware FLASH_BOOTLOADER_LOAD_KB 128 -STORAGE_FLASH_PAGE 14 define HAL_STORAGE_SIZE 32768 # order of UARTs (and USB) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7v2/README.md b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7v2/README.md new file mode 100644 index 00000000000..45610569cee --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7v2/README.md @@ -0,0 +1,102 @@ +# KakuteH7 v2 Flight Controller + +The KakuteH7 v2 is a flight controller produced by [Holybro](http://www.holybro.com/). + +## Features + + - STM32H743 microcontroller + - BMI270 IMU + - BMP280 barometer + - Onboard Flash: 1GBit + - AT7456E OSD + - 6 UARTs + - 9 PWM outputs + +## Pinout + +![KakuteH7 v2 Board](../KakuteH7/Kakkute_H7_Board_Top__Bottom2.jpg "KakuteH7 v2") +![KakuteH7 v2 Board](../KakuteH7/Kakkute_H7_Board_Top__Bottom3.jpg "KakuteH7 v2") + +## UART Mapping + +The UARTs are marked Rn and Tn in the above pinouts. The Rn pin is the +receive pin for UARTn. The Tn pin is the transmit pin for UARTn. + + - SERIAL0 -> USB + - SERIAL1 -> UART1 (DJI-RX, DMA-enabled) + - SERIAL2 -> UART2 (Telem2, DMA-enabled) (connected to internal BT module) + - SERIAL3 -> UART3 (VTX) + - SERIAL4 -> UART4 (GPS, DMA-enabled) + - SERIAL5 -> not available + - SERIAL6 -> UART6 (RX, DMA-enabled) + - SERIAL7 -> UART7 (ESC Telemetry) + +## RC Input + +RC input is configured on the R6 (UART6_RX) pin. It supports all RC +protocols except PPM. For protocols requiring half-duplex serial to transmit +telemetry (such as FPort) you should configure SERIAL6 with half-duplex, pin-swap +and inversion enabled. + +## FrSky Telemetry + +FrSky Telemetry is supported using the Tx pin of any UART including SERIAL6/UART6 . You need to set the following parameters to enable support for FrSky S.PORT (example shows SERIAL6). + + - SERIAL6_PROTOCOL 10 + - SERIAL6_OPTIONS 7 + +## OSD Support + +The KakuteH7 v2 supports OSD using OSD_TYPE 1 (MAX7456 driver). + +## VTX Support + +The JST-GH-6P connector supports a standard DJI HD VTX connection. Pin 1 of the connector is 9v so be careful not to connect +this to a peripheral requiring 5v. The 9v supply is controlled by RELAY_PIN2 and is on by default. It can be configured to be operated by an RC switch by selecting the function RELAY2. + +## PWM Output + +The KakuteH7 supports up to 9 PWM outputs. The pads for motor output +M1 to M8 on the two motor connectors, plus M9 for LED strip or another +PWM output. + +The PWM is in 5 groups: + + - PWM 1, 2 in group1 + - PWM 3, 4 in group2 + - PWM 5, 6 in group3 + - PWM 7, 8 in group4 + - PWM 9 in group5 + +Channels within the same group need to use the same output rate. If +any channel in a group uses DShot then all channels in the group need +to use DShot. Channels 1-8 support bi-directional DShot. + +## Battery Monitoring + +The board has a builtin voltage and current sensor. The current +sensor can read up to 130 Amps. The voltage sensor can handle up to 6S +LiPo batteries. + +The correct battery setting parameters are: + + - BATT_MONITOR 4 + - BATT_VOLT_PIN 10 + - BATT_CURR_PIN 11 + - BATT_VOLT_MULT 10.1 + - BATT_AMP_PERVLT 17.0 + +## Compass + +The KakuteH7 v2 does not have a builtin compass, but you can attach an external compass using I2C on the SDA and SCL pads. + +## Loading Firmware + +Initial firmware load can be done with DFU by plugging in USB with the +bootloader button pressed. Then you should load the "with_bl.hex" +firmware, using your favourite DFU loading tool. + +Once the initial firmware is loaded you can update the firmware using +any ArduPilot ground station software. Updates should be done with the +*.apj firmware files. + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7v2/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7v2/defaults.parm new file mode 100644 index 00000000000..387d905a213 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7v2/defaults.parm @@ -0,0 +1,6 @@ +# setup for LEDs on chan9 +SERVO9_FUNCTION 120 +NTF_LED_TYPES 257 +# Default VTX power to on +RELAY_DEFAULT 1 +SERIAL7_PROTOCOL 16 \ No newline at end of file diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7v2/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7v2/hwdef-bl.dat new file mode 100644 index 00000000000..ca591a491e1 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7v2/hwdef-bl.dat @@ -0,0 +1,4 @@ +include ../KakuteH7-bdshot/hwdef-bl.dat + +## pull up VTX power +PB11 VTX_PWR OUTPUT HIGH GPIO(81) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7v2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7v2/hwdef.dat new file mode 100644 index 00000000000..80fab14ac94 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7v2/hwdef.dat @@ -0,0 +1,57 @@ +# KakuteH7 v2 with flash chip for logging + +include ../KakuteH7-bdshot/hwdef.dat + +undef sdcard +undef icm20689 +undef IMU +undef HAL_OS_FATFS_IO +undef HAL_BOARD_LOG_DIRECTORY +undef HAL_BOARD_TERRAIN_DIRECTORY +undef PA3 PA0 PA2 PC8 PC9 PD8 PD9 PD0 PD1 PC6 PC7 PE7 PE8 + +MCU_CLOCKRATE_MHZ 480 + +# Holybro documentation: +# UART6 - RX +# UART1 - DJI RX +# UART4 - GPS +# UART3 - VTX + +# USART3 (VTX) +PD8 USART3_TX USART3 NODMA +PD9 USART3_RX USART3 NODMA + +# UART4 (GPS) +PD0 UART4_RX UART4 +PD1 UART4_TX UART4 + +# UART6 (RX) +PC7 USART6_RX USART6 +PC6 USART6_TX USART6 + +# UART7 (ESC Telemetry) +PE7 UART7_RX UART7 NODMA +PE8 UART7_TX UART7 NODMA + +PA0 TIM5_CH1 TIM5 PWM(5) GPIO(54) BIDIR +PA2 TIM5_CH3 TIM5 PWM(6) GPIO(55) BIDIR +PC8 TIM8_CH3 TIM8 PWM(7) GPIO(56) BIDIR +PC9 TIM8_CH4 TIM8 PWM(8) GPIO(57) + +# VTX Power control - should be high at startup to ensure power +PB11 VTX_PWR OUTPUT HIGH GPIO(81) +define RELAY2_PIN_DEFAULT 81 + +SPIDEV dataflash SPI1 DEVID1 SDCARD_CS MODE3 104*MHZ 104*MHZ +SPIDEV bmi270 SPI4 DEVID1 ICM20689_CS MODE3 1*MHZ 10*MHZ # Clock is 100Mhz so highest clock <= 10Mhz is 100Mhz/16 + +IMU BMI270 SPI:bmi270 ROTATION_ROLL_180 + +DMA_PRIORITY TIM3* TIM2* TIM5* TIM8* +DMA_NOSHARE *UP + +# Motor order implies Betaflight/X for standard ESCs +define HAL_FRAME_TYPE_DEFAULT 12 +define HAL_LOGGING_DATAFLASH_ENABLED 1 +define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25N01GV diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MambaF405-2022/README.md b/libraries/AP_HAL_ChibiOS/hwdef/MambaF405-2022/README.md new file mode 100644 index 00000000000..8ceae070cdf --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MambaF405-2022/README.md @@ -0,0 +1,88 @@ +# Mamba Basic F405 MK4 Flight Controller + +The Mamba Basic line of flight controllers are produced by [Diatone](https://www.diatone.us). + +## Features + + - STM32F405RGT6 microcontroller + - MPU6000 IMU + - AT7456E OSD + - 4 UARTs + - 7 PWM outputs (6 Motor Output, 1 LED) + +## Pinout + +![Mamba Basic 20x20 Pinout](basic20pinout.png) + +## UART Mapping + +The UARTs are marked Rn and Tn in the above pinouts. The Rn pin is the +receive pin for UARTn. The Tn pin is the transmit pin for UARTn. +|Name|Pin|Function| +|:-|:-|:-| +|SERIAL0|COMPUTER|USB| +|SERIAL1|PPM/RX1/SBUS/TX1|UART1 (RC Input)| +|SERIAL2|TX2/RX2|UART2 (DMA-enabled)| +|SERIAL3|TX3/RX3|UART3 (Telem1)| +|SERIAL4|TX4/RX4|UART4 (Empty)| +|SERIAL6|TX6/RX6|UART6 (GPS, DMA-enabled)| + + +## RC Input + +RC input is configured on the PPM (UART1_RX) pin. It supports all RC protocols. + +## OSD Support + +The Mamba F405 MK4 supports OSD using OSD_TYPE 1 (MAX7456 driver). + +## PWM Output + +The Mamba F405 MK4 supports up to 7 PWM outputs. The pads for motor output ESC1 to ESC4 on the above diagram are for the 4 outputs. All outputs support DShot as well as all PWM types. Motors 1-4 support bi-directional DShot. + +The PWM is in 4 groups: + + - PWM 1,2 in group1 + - PWM 3,4 in group2 + - PWM 5,6 in group3 + - PWM 7 in group4 + +Channels within the same group need to use the same output rate. If +any channel in a group uses DShot then all channels in the group need +to use DShot. + +## Battery Monitoring + +The board has a builting voltage sensor. The voltage sensor can handle up to 6S +LiPo batteries. + +The correct battery setting parameters are: + + - BATT_MONITOR 3 + - BATT_VOLT_PIN 11 + - BATT_VOLT_MULT around 11.0 + - BATT_CURR_PIN 13 + - BATT_CURR_MULT around 28 with the 20x20 40A ESC (calculated, needs to be verified) + +## Compass + +The Mamba Basic flight controllers do not have a builtin compass, but you can attach an external compass using I2C on the SDA and SCL pads. + +## Alternate settings + +It is possible to set alternate configurations with the BRD_ALT_CONFIG parameter. + +|BRD_ALT_CONFIG|RX1 function| +|:----|:----| +|ALT 0(default) |RCININT| +|ALT 1|RX1/TX1| + +## Loading Firmware + +Initial firmware load can be done with DFU by plugging in USB with the +bootloader button pressed. Then you should load the "with_bl.hex" +firmware, using your favourite DFU loading tool. + +Once the initial firmware is loaded you can update the firmware using +any ArduPilot ground station software. Updates should be done with the +*.apj firmware files. diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MambaF405-2022/basic20pinout.png b/libraries/AP_HAL_ChibiOS/hwdef/MambaF405-2022/basic20pinout.png new file mode 100644 index 00000000000..0e477595cfb Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/MambaF405-2022/basic20pinout.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MambaF405-2022/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MambaF405-2022/defaults.parm new file mode 100644 index 00000000000..9197bfd3fe0 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MambaF405-2022/defaults.parm @@ -0,0 +1,5 @@ +# setup for LEDs on chan9 +SERVO7_FUNCTION 120 +NTF_LED_TYPES 257 +# Default VTX power to on +RELAY_DEFAULT 1 \ No newline at end of file diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MambaF405-2022/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MambaF405-2022/hwdef-bl.dat new file mode 100644 index 00000000000..9749cd73ee4 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MambaF405-2022/hwdef-bl.dat @@ -0,0 +1,3 @@ +include ../MambaF405US-I2C/hwdef-bl.dat + +PC5 VTX_PWR OUTPUT HIGH diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MambaF405-2022/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MambaF405-2022/hwdef.dat new file mode 100644 index 00000000000..18910e045c3 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MambaF405-2022/hwdef.dat @@ -0,0 +1,37 @@ +# MambaF405 2022 + +include ../MambaF405US-I2C/hwdef.dat + +undef PA9 PA8 PC9 PC8 PB3 PB11 PC5 + +PA9 TIM1_CH2 TIM1 PWM(1) GPIO(50) BIDIR +PA8 TIM1_CH1 TIM1 PWM(2) GPIO(51) +PC9 TIM8_CH4 TIM8 PWM(3) GPIO(52) BIDIR +PC8 TIM8_CH3 TIM8 PWM(4) GPIO(53) +PB0 TIM3_CH3 TIM3 PWM(5) GPIO(54) +PB1 TIM3_CH4 TIM3 PWM(6) GPIO(55) + +# LED strip +PB3 TIM2_CH2 TIM2 PWM(7) GPIO(56) + +# VTX Power control - should be high at startup to ensure power +PC5 VTX_PWR OUTPUT HIGH GPIO(81) +define RELAY2_PIN_DEFAULT 81 + +PB11 USART3_RX USART3 NODMA + +# MambaF405-2022B board +SPIDEV icm42688 SPI1 DEVID2 MPU6000_CS MODE3 1*MHZ 8*MHZ + +IMU Invensensev3 SPI:icm42688 ROTATION_ROLL_180_YAW_270 + +# enable SPL06 baro +BARO SPL06 I2C:0:0x76 +define AP_BARO_SPL06_ENABLED 1 + +# disable some GPS drivers to save flash +define AP_GPS_SIRF_ENABLED 0 +define AP_GPS_SBP_ENABLED 0 +define AP_GPS_NOVA_ENABLED 0 +define AP_GPS_GSOF_ENABLED 0 +define AP_GPS_ERB_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MambaF405US-I2C/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MambaF405US-I2C/hwdef.dat index 8e58e49bb63..e1f260baff8 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MambaF405US-I2C/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MambaF405US-I2C/hwdef.dat @@ -50,11 +50,11 @@ PB11 USART3_RX USART3 # UART4 PA0 UART4_TX UART4 -PA1 UART4_RX UART4 +PA1 UART4_RX UART4 NODMA # UART5 PC12 UART5_TX UART5 -PD2 UART5_RX UART5 +PD2 UART5_RX UART5 NODMA # USART6 PC6 USART6_TX USART6 @@ -147,7 +147,7 @@ define HAL_BATT_VOLT_SCALE 11 define HAL_BATT_CURR_SCALE 39 # Analog RSSI pin (also could be used as analog airspeed input) -define BOARD_RSSI_ANA_PIN 1 +define BOARD_RSSI_ANA_PIN 12 # Setup for OSD define OSD_ENABLED 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MambaF405v2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MambaF405v2/hwdef.dat index 6c3385a2284..99a1307e9a1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MambaF405v2/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MambaF405v2/hwdef.dat @@ -153,3 +153,6 @@ ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin # To complementary channels work we define this #define STM32_PWM_USE_ADVANCED TRUE + +# minimal drivers to reduce flash usage +include ../include/minimal.inc diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/MambaH743v4_Board.jpg b/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/MambaH743v4_Board.jpg new file mode 100644 index 00000000000..4c6d3faf334 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/MambaH743v4_Board.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/README.md b/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/README.md new file mode 100644 index 00000000000..3d91e0b4687 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/README.md @@ -0,0 +1,100 @@ +# MambaH743v4 Flight Controller + +The MambaH743v4 is a flight controller produced by [Diatone](https://www.diatoneusa.com/). + +## Features + + - MCU - STM32H743 32-bit processor running at 480 MHz + - IMU - Dual MPU6000 (Version A) or BMI270 (Version B) or Dual ICM42688 (v2) + - Barometer - DPS280 + - OSD - AT7456E + - Onboard Flash: 1GBit + - 8x UARTs + - 9x PWM Outputs (8 Motor Output, 1 LED) + - Battery input voltage: 2S-6S + - BEC 3.3V 0.5A + - BEC 5V 3A + - BEC 5V 3A + - BEC 9V 3A + +## Pinout + +![MambaH743v4 Board](MambaH743v4_Board.jpg "MambaH743v4") + +## UART Mapping + +The UARTs are marked Rn and Tn in the above pinouts. The Rn pin is the +receive pin for UARTn. The Tn pin is the transmit pin for UARTn. + + - SERIAL0 -> USB + - SERIAL1 -> UART1 (RX/SBUS, DMA-enabled) + - SERIAL2 -> UART2 + - SERIAL3 -> UART3 + - SERIAL4 -> UART4 (GPS, DMA-enabled) + - SERIAL5 -> UART5 (SPort) + - SERIAL6 -> UART6 (ESC Telemetry) + - SERIAL7 -> UART7 (GPS, DMA-enabled) + +## RC Input + +RC input is configured on the R1 (UART1_RX) pin. It supports all serial RC +protocols. For protocols requiring half-duplex serial to transmit +telemetry (such as FPort) you should setup SERIAL6 as an RC input serial port, +with half-duplex, pin-swap and inversion enabled. + +## FrSky Telemetry + +FrSky Telemetry is supported using the T5 pin (UART5 transmit). You need to set the following parameters to enable support for FrSky S.PORT + + - SERIAL5_PROTOCOL 10 + - SERIAL5_OPTIONS 7 + +## OSD Support + +The MambaH743v4 supports OSD using OSD_TYPE 1 (MAX7456 driver). + +## PWM Output + +The MambaH743v4 supports up to 9 PWM outputs. The pads for motor output +M1 to M8 are provided on both the motor connectors and on separate pads, plus +M9 on a separate pad for LED strip or another PWM output. + +The PWM is in 4 groups: + + - PWM 1-4 in group1 + - PWM 5,6 in group2 + - PWM 7,8 in group3 + - PWM 9 in group4 + +Channels within the same group need to use the same output rate. If +any channel in a group uses DShot then all channels in the group need +to use DShot. Channels 1-8 support bi-directional dshot. + +## Battery Monitoring + +The board has a builting voltage and current sensor. The current +sensor can read up to 130 Amps. The voltage sensor can handle up to 6S +LiPo batteries. + +The correct battery setting parameters are: + + - BATT_MONITOR 4 + - BATT_VOLT_PIN 11 + - BATT_CURR_PIN 13 + - BATT_VOLT_MULT 11.1 + - BATT_AMP_PERVLT 64 + +## Compass + +The MambaH743v4 does not have a builtin compass, but you can attach an external compass using I2C on the SDA and SCL pads. + +## Loading Firmware + +Initial firmware load can be done with DFU by plugging in USB with the +bootloader button pressed. Then you should load the "with_bl.hex" +firmware, using your favourite DFU loading tool. + +Once the initial firmware is loaded you can update the firmware using +any ArduPilot ground station software. Updates should be done with the +*.apj firmware files. + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/defaults.parm new file mode 100644 index 00000000000..d5fa305db60 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/defaults.parm @@ -0,0 +1,5 @@ +# setup for LEDs on chan9 +SERVO9_FUNCTION 120 +NTF_LED_TYPES 257 +# Default VTX power to on +RELAY_DEFAULT 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/hwdef-bl.dat new file mode 100644 index 00000000000..201ffc4df0b --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/hwdef-bl.dat @@ -0,0 +1,45 @@ +# hw definition file for processing by chibios_pins.py +# for Diatone MambaH743 mk4 bootloader + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID 1073 + +# crystal frequency, setup to use external oscillator +OSCILLATOR_HZ 8000000 + +FLASH_SIZE_KB 2048 + +# bootloader starts at zero offset +FLASH_RESERVE_START_KB 0 + +# the location where the bootloader will put the firmware +FLASH_BOOTLOADER_LOAD_KB 384 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 + +# PA10 IO-debug-console +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +PE3 BUZZER OUTPUT LOW PULLDOWN + +PE5 LED_BOOTLOADER OUTPUT LOW +define HAL_LED_ON 1 + +# default to all pins low to avoid ESD issues +DEFAULTGPIO OUTPUT LOW PULLDOWN + +PC5 VTX_PWR OUTPUT HIGH + +# Add CS pins to ensure they are high in bootloader +PA15 FLASH_CS CS +PB12 MAX7456_CS CS +PA4 MPU6000_CS CS +PE11 MPU6000_2_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/hwdef.dat new file mode 100644 index 00000000000..c0c234cb378 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/hwdef.dat @@ -0,0 +1,196 @@ +# hw definition file for processing by chibios_pins.py +# for Diatone MambaH743 mk4 hardware. + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID 1073 + +# crystal frequency, setup to use external oscillator +OSCILLATOR_HZ 8000000 + +MCU_CLOCKRATE_MHZ 480 + +FLASH_SIZE_KB 2048 + +# ChibiOS system timer +STM32_ST_USE_TIMER 12 +define CH_CFG_ST_RESOLUTION 16 + +# leave 1 sectors free +FLASH_RESERVE_START_KB 384 + +# use last 2 pages for flash storage +# H743 has 16 pages of 128k each +STORAGE_FLASH_PAGE 1 +define HAL_STORAGE_SIZE 32768 + +# enable logging to dataflash +define HAL_LOGGING_DATAFLASH_ENABLED 1 + +# one I2C bus +I2C_ORDER I2C1 I2C2 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART5 USART6 UART7 UART8 + +# buzzer +PE3 BUZZER OUTPUT LOW PULLDOWN GPIO(80) +define HAL_BUZZER_PIN 80 +define HAL_BUZZER_ON 1 +define HAL_BUZZER_OFF 0 +define HAL_PWM_ALT_ALARM + +# PA10 IO-debug-console +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# SPI1 for BMI270 / MPU6000 +PA4 MPU6000_CS CS +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 + +# SPI2 for MAX7456 OSD +PB12 MAX7456_CS CS +PB13 SPI2_SCK SPI2 +PB14 SPI2_MISO SPI2 +PB15 SPI2_MOSI SPI2 + +# SPI3 for flash +PA15 FLASH_CS CS +PC10 SPI3_SCK SPI3 +PC11 SPI3_MISO SPI3 +PB2 SPI3_MOSI SPI3 + +# SPI4 for MPU6000_2 +PE11 MPU6000_2_CS CS +PE12 SPI4_SCK SPI4 +PE13 SPI4_MISO SPI4 +PE14 SPI4_MOSI SPI4 + +# I2C1 for baro +PB6 I2C1_SCL I2C1 +PB7 I2C1_SDA I2C1 + +# I2C2 for baro +PB10 I2C2_SCL I2C2 +PB11 I2C2_SDA I2C2 + +PC1 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PC3 BATT_CURRENT_SENS ADC1 SCALE(1) + +# define default battery setup +define HAL_BATT_MONITOR_DEFAULT 4 +define HAL_BATT_VOLT_PIN 11 +define HAL_BATT_CURR_PIN 13 +define HAL_BATT_VOLT_SCALE 11.1 +define HAL_BATT_CURR_SCALE 64 + +PC2 RSSI_ADC ADC1 +define BOARD_RSSI_ANA_PIN 12 + +PE5 LED0 OUTPUT LOW GPIO(90) # blue +PE4 LED1 OUTPUT LOW GPIO(91) # orange +define HAL_GPIO_A_LED_PIN 91 +define HAL_GPIO_B_LED_PIN 90 +define HAL_GPIO_LED_OFF 1 + +# USART1 (RX / SBUS) +PA9 USART1_TX USART1 +PA10 USART1_RX USART1 + +# USART2 +PD5 USART2_TX USART2 NODMA +PD6 USART2_RX USART2 NODMA + +# USART3 (VTX) +PD8 USART3_TX USART3 NODMA +PD9 USART3_RX USART3 NODMA + +# UART4 (GPS) +PD1 UART4_TX UART4 +PD0 UART4_RX UART4 + +# UART5 (SPORT) +PC12 UART5_TX UART5 NODMA +PD2 UART5_RX UART5 NODMA + +# USART6 (ESC Telemetry) +PC6 USART6_TX USART6 NODMA +PC7 USART6_RX USART6 NODMA + +# UART7 (GPS) +PE8 UART7_TX UART7 +PE7 UART7_RX UART7 + +PE1 UART8_TX UART8 NODMA +PE0 UART8_RX UART8 NODMA + +define HAL_SERIAL1_PROTOCOL SerialProtocol_RCIN +define HAL_SERIAL1_BAUD 115 +define HAL_SERIAL6_PROTOCOL SerialProtocol_ESCTelemetry +define HAL_SERIAL6_BAUD 115 + +# Motors +PA0 TIM5_CH1 TIM5 PWM(1) GPIO(50) BIDIR +PA1 TIM5_CH2 TIM5 PWM(2) GPIO(51) +PA2 TIM5_CH3 TIM5 PWM(3) GPIO(52) BIDIR +PA3 TIM5_CH4 TIM5 PWM(4) GPIO(53) +PB0 TIM3_CH3 TIM3 PWM(5) GPIO(54) BIDIR +PB1 TIM3_CH4 TIM3 PWM(6) GPIO(55) +PC8 TIM8_CH3 TIM8 PWM(7) GPIO(56) BIDIR +PC9 TIM8_CH4 TIM8 PWM(8) GPIO(57) + +# VTX Power control - should be high at startup to ensure power +PC5 VTX_PWR OUTPUT HIGH GPIO(81) +define RELAY2_PIN_DEFAULT 81 + +# Motor order implies Betaflight/X for standard ESCs +define HAL_FRAME_TYPE_DEFAULT 12 + +# LED strip +PA8 TIM1_CH1 TIM1 PWM(9) GPIO(58) + +DMA_NOSHARE SPI3* SPI1* + +# spi devices +SPIDEV mpu6000 SPI1 DEVID1 MPU6000_CS MODE3 1*MHZ 4*MHZ +SPIDEV bmi270 SPI1 DEVID2 MPU6000_CS MODE3 1*MHZ 10*MHZ # Clock is 100Mhz so highest clock <= 10Mhz is 100Mhz/16 +SPIDEV mpu6000_2 SPI4 DEVID4 MPU6000_2_CS MODE3 1*MHZ 4*MHZ +SPIDEV dataflash SPI3 DEVID1 FLASH_CS MODE3 104*MHZ 104*MHZ +SPIDEV osd SPI2 DEVID4 MAX7456_CS MODE0 10*MHZ 10*MHZ +# v2 board has dual ICM42688 +SPIDEV icm42688 SPI1 DEVID1 MPU6000_CS MODE3 2*MHZ 16*MHZ +SPIDEV icm42688_2 SPI4 DEVID4 MPU6000_2_CS MODE3 2*MHZ 16*MHZ + +# no built-in compass, but probe the i2c bus for all possible +# external compass types +define ALLOW_ARM_NO_COMPASS +define HAL_PROBE_EXTERNAL_I2C_COMPASSES +define HAL_I2C_INTERNAL_MASK 0 +define HAL_COMPASS_AUTO_ROT_DEFAULT 2 +define HAL_DEFAULT_INS_FAST_SAMPLE 3 + +# Two MPU6000s or one BMI270 +IMU Invensense SPI:mpu6000 ROTATION_YAW_90 +IMU Invensense SPI:mpu6000_2 ROTATION_YAW_180 +IMU BMI270 SPI:bmi270 ROTATION_PITCH_180 +IMU Invensensev3 SPI:icm42688 ROTATION_ROLL_180 +IMU Invensensev3 SPI:icm42688_2 ROTATION_ROLL_180_YAW_270 + +define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25N01GV + +# one BARO +BARO DPS280 I2C:0:0x76 + +# setup for OSD +define OSD_ENABLED 1 +define HAL_OSD_TYPE_DEFAULT 1 +ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin + +define STM32_PWM_USE_ADVANCED TRUE diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-CAN/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-CAN/hwdef.dat index d24c761a2b5..07e70f7879f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-CAN/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-CAN/hwdef.dat @@ -81,6 +81,9 @@ PB8 CAN1_RX CAN1 PB9 CAN1_TX CAN1 PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(70) +# reduce memory usage +define UAVCAN_NODE_POOL_SIZE 1024 + # --------------------- UARTs --------------------------- SERIAL_ORDER OTG1 USART1 USART3 UART4 UART5 USART2 @@ -166,7 +169,6 @@ define HAL_BATT2_VOLT_SCALE 11.0 define HAL_MINIMIZE_FEATURES 1 define AP_BATTMON_SMBUS_ENABLE 0 -define AP_BATTMON_FUEL_ENABLE 0 define HAL_PARACHUTE_ENABLED 0 define HAL_SPRAYER_ENABLED 0 @@ -175,4 +177,10 @@ define HAL_WITH_DSP FALSE # reduce max size of embedded params for apj_tool.py define AP_PARAM_MAX_EMBEDDED_PARAM 1024 +# disable some GPS drivers to save flash +define AP_GPS_SIRF_ENABLED 0 +define AP_GPS_SBP_ENABLED 0 +define AP_GPS_NOVA_ENABLED 0 +define AP_GPS_GSOF_ENABLED 0 +define AP_GPS_ERB_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-STD/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-STD/hwdef.dat index 48b1c5fa0b5..31be3dc4aab 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-STD/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-STD/hwdef.dat @@ -5,3 +5,15 @@ include ../MatekF405/hwdef.dat # different IMU orientation undef IMU IMU Invensense SPI:mpu6000 ROTATION_YAW_90 + +# Use TIM5 for ST clock +undef STM32_ST_USE_TIMER +undef CH_CFG_ST_RESOLUTION +define STM32_ST_USE_TIMER 5 +define CH_CFG_ST_RESOLUTION 32 + +# Add S7 Pad for MatekF405 STD +PB8 TIM4_CH3 TIM4 PWM(7) GPIO(56) NODMA + +define AP_GPS_SIRF_ENABLED 0 +define AP_GPS_SBP_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-TE/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-TE/hwdef-bl.dat index d6398e7f001..87a6bc14582 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-TE/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-TE/hwdef-bl.dat @@ -33,3 +33,6 @@ PB12 OSD_CS CS PC13 FLASH_CS CS PC1 SDCARD_CS CS +# Turn on switched supply and camera switch/output during bootloader to match default +PA4 PINIO1 OUTPUT LOW +PB5 PINIO2 OUTPUT LOW diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-TE/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-TE/hwdef.dat index 3e9e05420a3..36b9c2ff6f6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-TE/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-TE/hwdef.dat @@ -177,7 +177,6 @@ define HAL_WITH_DSP FALSE # --------------------- save flash ---------------------- define AP_BATTMON_SMBUS_ENABLE 0 -define AP_BATTMON_FUEL_ENABLE 0 define HAL_PARACHUTE_ENABLED 0 define HAL_SPRAYER_ENABLED 0 define HAL_GENERATOR_ENABLED 0 @@ -192,3 +191,4 @@ define HAL_BUTTON_ENABLED 0 define HAL_OREO_LED_ENABLED 0 define HAL_PICCOLO_CAN_ENABLE 0 define AP_OPTICALFLOW_ENABLED 0 +define AP_ICENGINE_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-Wing-bdshot/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-Wing-bdshot/hwdef-bl.dat new file mode 100644 index 00000000000..ce86b81104b --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-Wing-bdshot/hwdef-bl.dat @@ -0,0 +1 @@ +include ../MatekF405-Wing/hwdef-bl.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-Wing-bdshot/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-Wing-bdshot/hwdef.dat new file mode 100644 index 00000000000..4531c681683 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-Wing-bdshot/hwdef.dat @@ -0,0 +1,16 @@ +# Bi-directional dshot version of MatekF405 + +include ../MatekF405-Wing/hwdef.dat + +undef PB7 PB6 PB0 PB1 PC8 PC9 + +PB7 TIM4_CH2 TIM4 PWM(1) GPIO(50) +PB6 TIM4_CH1 TIM4 PWM(2) GPIO(51) BIDIR +PB0 TIM3_CH3 TIM3 PWM(3) GPIO(52) BIDIR +PB1 TIM3_CH4 TIM3 PWM(4) GPIO(53) + +# Can only do bdshot on M1-4, so give up DMA channel on M5/M6 to get full DMA on USART3 +PC8 TIM8_CH3 TIM8 PWM(5) GPIO(54) NODMA +PC9 TIM8_CH4 TIM8 PWM(6) GPIO(55) NODMA + +DMA_NOSHARE TIM3_UP diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-Wing/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-Wing/hwdef-bl.dat index 0aeb2f3e8ca..c362e9967f3 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-Wing/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-Wing/hwdef-bl.dat @@ -19,7 +19,7 @@ FLASH_SIZE_KB 1024 FLASH_BOOTLOADER_LOAD_KB 64 # order of UARTs -SERIAL_ORDER OTG1 USART1 USART3 UART4 UART5 USART6 +SERIAL_ORDER OTG1 PA0 UART4_TX UART4 PA1 UART4_RX UART4 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-Wing/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-Wing/hwdef.dat index 8c6d32195b6..146368651e1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-Wing/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-Wing/hwdef.dat @@ -179,9 +179,8 @@ ROMFS_WILDCARD libraries/AP_OSD/fonts/font0.bin define STM32_PWM_USE_ADVANCED TRUE -# disable SMBUS and fuel battery monitors to save flash +# disable SMBUS battery monitors to save flash define AP_BATTMON_SMBUS_ENABLE 0 -define AP_BATTMON_FUEL_ENABLE 0 # disable parachute and sprayer to save flash define HAL_PARACHUTE_ENABLED 0 @@ -198,3 +197,10 @@ define PRECISION_LANDING 0 define HAL_BARO_WIND_COMP_ENABLED 0 define GRIPPER_ENABLED 0 define AP_OPTICALFLOW_ENABLED 0 +define AP_ICENGINE_ENABLED 0 +define AP_GPS_SIRF_ENABLED 0 +define AP_GPS_SBP_ENABLED 0 +define AP_GPS_NOVA_ENABLED 0 +define AP_GPS_GSOF_ENABLED 0 +define AP_GPS_ERB_ENABLED 0 + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-bdshot/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-bdshot/hwdef.dat index 5d9f76f2ca2..5c4ea93b692 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-bdshot/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-bdshot/hwdef.dat @@ -1,6 +1,7 @@ # Bi-directional dshot version of MatekF405 include ../MatekF405/hwdef.dat +include ../include/minimal_GPS.inc undef PC6 PC9 PA8 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405/hwdef.dat index 2aadf8cb6a5..831e50acca4 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405/hwdef.dat @@ -157,9 +157,8 @@ define OSD_ENABLED 1 define HAL_OSD_TYPE_DEFAULT 1 ROMFS_WILDCARD libraries/AP_OSD/fonts/font0.bin -# disable SMBUS and fuel battery monitors to save flash +# disable SMBUS battery monitors to save flash define AP_BATTMON_SMBUS_ENABLE 0 -define AP_BATTMON_FUEL_ENABLE 0 # disable parachute and sprayer to save flash define HAL_PARACHUTE_ENABLED 0 @@ -173,3 +172,10 @@ define HAL_GENERATOR_ENABLED 0 define AC_OAPATHPLANNER_ENABLED 0 define PRECISION_LANDING 0 define AP_OPTICALFLOW_ENABLED 0 +define AP_ICENGINE_ENABLED 0 + +# minimise GPS backends to save flash +define AP_GPS_NOVA_ENABLED 0 +define AP_GPS_GSOF_ENABLED 0 +define AP_GPS_ERB_ENABLED 0 +define AP_GPS_SIRF_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF765-Wing-bdshot/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MatekF765-Wing-bdshot/defaults.parm new file mode 100644 index 00000000000..7b610d2326f --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekF765-Wing-bdshot/defaults.parm @@ -0,0 +1,2 @@ +SERVO13_FUNCTION 120 +NTF_LED_TYPES 455 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF765-Wing-bdshot/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekF765-Wing-bdshot/hwdef-bl.dat new file mode 100644 index 00000000000..b3863b4997b --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekF765-Wing-bdshot/hwdef-bl.dat @@ -0,0 +1,4 @@ +# hw definition file for processing by chibios_pins.py +# for Matek F765-Wing bootloader + +include ../MatekF765-Wing/hwdef-bl.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF765-Wing-bdshot/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekF765-Wing-bdshot/hwdef.dat new file mode 100644 index 00000000000..ec6b1ee22da --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekF765-Wing-bdshot/hwdef.dat @@ -0,0 +1,14 @@ +# Bi-directional dshot version of MatekF765-Wing + +include ../MatekF765-Wing/hwdef.dat + +# undefine the pins we are going to change +undef PA0 PA1 PA2 PA3 + +# hw definition file for processing by chibios_pins.py +# for Matek F765-Wing + +PA0 TIM2_CH1 TIM2 PWM(1) GPIO(50) BIDIR +PA1 TIM2_CH2 TIM2 PWM(2) GPIO(51) +PA2 TIM5_CH3 TIM5 PWM(3) GPIO(52) BIDIR +PA3 TIM5_CH4 TIM5 PWM(4) GPIO(53) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF765-Wing/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekF765-Wing/hwdef-bl.dat index d3862451d58..f2799e4460f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekF765-Wing/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekF765-Wing/hwdef-bl.dat @@ -41,3 +41,6 @@ PC4 IMU1_CS CS PB12 MAX7456_CS CS PD7 IMU2_CS CS PE11 SPARE_CS CS + +# turn switched supply on at power up +PE4 PINIO1 OUTPUT LOW diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekH743-bdshot/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MatekH743-bdshot/defaults.parm new file mode 100644 index 00000000000..1b77a4b9f3b --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekH743-bdshot/defaults.parm @@ -0,0 +1,3 @@ +# SERIAL7 is RCIN by default +SERIAL7_PROTOCOL 23 +SERIAL7_BAUD 115 \ No newline at end of file diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekH743-bdshot/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekH743-bdshot/hwdef.dat index 06e4834e908..32dcab38568 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekH743-bdshot/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekH743-bdshot/hwdef.dat @@ -5,15 +5,29 @@ include ../MatekH743/hwdef.dat # undefine the pins we are going to change -undef PC7 PB0 PB1 PA0 PA1 PA15 PD14 PD15 PE5 PE6 +undef PC7 PC6 PB0 PB1 PA0 PA1 PA15 PD14 PD15 PE5 PE6 PA2 PA3 PD12 PD13 PB9 PB8 PE0 PE1 +# UART4 (spare) +PB9 UART4_TX UART4 NODMA +PB8 UART4_RX UART4 NODMA + +# UART8 (ESC Telemetry), SERIAL5 +PE0 UART8_RX UART8 NODMA +PE1 UART8_TX UART8 NODMA + +# USART6 (RC input), SERIAL7 PC7 USART6_RX USART6 +PC6 USART6_TX USART6 # Motors PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50) BIDIR PB1 TIM3_CH4 TIM3 PWM(2) GPIO(51) PA0 TIM2_CH1 TIM2 PWM(3) GPIO(52) BIDIR PA1 TIM2_CH2 TIM2 PWM(4) GPIO(53) +PA2 TIM5_CH3 TIM5 PWM(5) GPIO(54) BIDIR +PA3 TIM5_CH4 TIM5 PWM(6) GPIO(55) +PD12 TIM4_CH1 TIM4 PWM(7) GPIO(56) BIDIR +PD13 TIM4_CH2 TIM4 PWM(8) GPIO(57) # Disable DMA on PWM9-12 so that the LEDs get a channel PD14 TIM4_CH3 TIM4 PWM(9) GPIO(58) NODMA @@ -27,5 +41,7 @@ define HAL_BUZZER_PIN 32 define HAL_BUZZER_ON 1 define HAL_BUZZER_OFF 0 -DMA_PRIORITY S* TIM3* TIM2* -DMA_NOSHARE SPI1* SPI4* TIM3* TIM2* +DMA_PRIORITY SPI1* SPI4* +DMA_NOSHARE SPI1* SPI4* TIM3* TIM2* TIM5* TIM4* +NODMA I2C* +define STM32_I2C_USE_DMA FALSE diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekH743/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekH743/hwdef-bl.dat index 72e272971d8..b9e691cb3ea 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekH743/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekH743/hwdef-bl.dat @@ -15,10 +15,6 @@ FLASH_SIZE_KB 2048 # bootloader starts at zero offset FLASH_RESERVE_START_KB 0 -# use last 2 pages for flash storage -# H743 has 16 pages of 128k each -STORAGE_FLASH_PAGE 14 - # the location where the bootloader will put the firmware # the H743 has 128k sectors FLASH_BOOTLOADER_LOAD_KB 128 @@ -38,6 +34,9 @@ PA12 OTG_FS_DP OTG1 PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD +# make sure Vsw is on during bootloader +PD10 PINIO1 OUTPUT LOW + PE3 LED_BOOTLOADER OUTPUT LOW define HAL_LED_ON 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekH743/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekH743/hwdef.dat index 6f930300db3..95718f2c3a9 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekH743/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekH743/hwdef.dat @@ -181,11 +181,13 @@ define HAL_STORAGE_SIZE 16384 STORAGE_FLASH_PAGE 14 # spi devices +SPIDEV icm42688 SPI1 DEVID1 IMU1_CS MODE3 2*MHZ 16*MHZ # Clock is 100Mhz so highest clock <= 24Mhz is 100Mhz/8 SPIDEV mpu6000 SPI1 DEVID1 IMU1_CS MODE3 1*MHZ 4*MHZ SPIDEV icm20602 SPI4 DEVID1 IMU2_CS MODE3 1*MHZ 4*MHZ -SPIDEV icm42605 SPI4 DEVID1 IMU3_CS MODE3 2*MHZ 8*MHZ +SPIDEV icm42605 SPI4 DEVID1 IMU3_CS MODE3 2*MHZ 16*MHZ SPIDEV osd SPI2 DEVID4 MAX7456_CS MODE0 10*MHZ 10*MHZ + DMA_NOSHARE SPI1* SPI4* # SPI3 external connections @@ -198,9 +200,13 @@ define HAL_PROBE_EXTERNAL_I2C_COMPASSES define HAL_I2C_INTERNAL_MASK 0 define HAL_COMPASS_AUTO_ROT_DEFAULT 2 -# two IMUs. We put icm20602 first as we can sample accel at 4kHz -IMU Invensense SPI:icm20602 ROTATION_ROLL_180_YAW_270 +# two IMUs +# H743-V1, ICM20602, MPU6000 +# H743-V1.5/V2, ICM42605, MPU6000 +# H743-V3, ICM42688P, ICM42605 +IMU Invensensev3 SPI:icm42688 ROTATION_YAW_180 IMU Invensensev3 SPI:icm42605 ROTATION_YAW_270 +IMU Invensense SPI:icm20602 ROTATION_ROLL_180_YAW_270 IMU Invensense SPI:mpu6000 ROTATION_ROLL_180_YAW_270 define HAL_DEFAULT_INS_FAST_SAMPLE 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Airspeed/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Airspeed/hwdef-bl.dat new file mode 100644 index 00000000000..887b18aeacc --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Airspeed/hwdef-bl.dat @@ -0,0 +1,3 @@ +include ../MatekL431/hwdef-bl.inc + +define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-Airspeed" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Airspeed/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Airspeed/hwdef.dat new file mode 100644 index 00000000000..302d5c8d88f --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Airspeed/hwdef.dat @@ -0,0 +1,15 @@ +include ../MatekL431/hwdef.inc + +define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-Airspeed" + +define HAL_USE_ADC FALSE +define STM32_ADC_USE_ADC1 FALSE +define HAL_DISABLE_ADC_DRIVER TRUE + +# ------------------ I2C airspeed ------------------------- +define HAL_PERIPH_ENABLE_AIRSPEED + +# 10" DLVR sensor by default +define HAL_AIRSPEED_TYPE_DEFAULT 9 +define AIRSPEED_MAX_SENSORS 1 + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-DShot/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-DShot/defaults.parm new file mode 100644 index 00000000000..693494c06d6 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-DShot/defaults.parm @@ -0,0 +1,20 @@ +# up to 9 motors/servos + +OUT1_FUNCTION 33 +OUT2_FUNCTION 34 +OUT3_FUNCTION 35 +OUT4_FUNCTION 36 +OUT5_FUNCTION 51 +OUT6_FUNCTION 52 +OUT7_FUNCTION 53 +OUT8_FUNCTION 54 +OUT9_FUNCTION 55 + +# DShot 600 +ESC_PWM_TYPE 7 +OUT_BLH_OTYPE 6 + +OUT_BLH_MASK 15 + +# DShot telem on RX1 +ESC_TELEM_PORT 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-DShot/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-DShot/hwdef-bl.dat new file mode 100644 index 00000000000..fe94bb635e4 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-DShot/hwdef-bl.dat @@ -0,0 +1,3 @@ +include ../MatekL431/hwdef-bl.inc + +define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-DShot" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-DShot/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-DShot/hwdef.dat new file mode 100644 index 00000000000..3d809de636e --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-DShot/hwdef.dat @@ -0,0 +1,35 @@ +include ../MatekL431/hwdef.inc + +define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-DShot" + +define HAL_USE_ADC FALSE + +undef SERIAL_ORDER +undef USART2 USART2_TX USART2_RX +undef PA2 PA3 + +SERIAL_ORDER USART1 EMPTY USART3 + +# --------------------- PWM ----------------------- +PA8 TIM1_CH1 TIM1 PWM(1) GPIO(50) +PA9 TIM1_CH2 TIM1 PWM(2) GPIO(51) +PA10 TIM1_CH3 TIM1 PWM(3) GPIO(52) +PA11 TIM1_CH4 TIM1 PWM(4) GPIO(53) +PA15 TIM2_CH1 TIM2 PWM(5) GPIO(54) + +# TX2/RX2 -- PWM6/7 +PA2 TIM2_CH3 TIM2 PWM(6) GPIO(55) +PA3 TIM2_CH4 TIM2 PWM(7) GPIO(56) + +# "curr" pin -- PWM8 +PA1 TIM2_CH2 TIM2 PWM(8) GPIO(57) + +# "beeper" pin -- PWM9 +PA6 TIM16_CH1 TIM16 PWM(9) GPIO(58) NODMA + +define HAL_PERIPH_ENABLE_RC_OUT +define HAL_PERIPH_ENABLE_NOTIFY + +# enable ESC control +define HAL_SUPPORT_RCOUT_SERIAL 1 +define HAL_WITH_ESC_TELEM 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-EFI/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-EFI/hwdef-bl.dat new file mode 100644 index 00000000000..173d1fc2fc4 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-EFI/hwdef-bl.dat @@ -0,0 +1,3 @@ +include ../MatekL431/hwdef-bl.inc + +define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-EFI" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-EFI/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-EFI/hwdef.dat new file mode 100644 index 00000000000..2b122aa0c5a --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-EFI/hwdef.dat @@ -0,0 +1,13 @@ +include ../MatekL431/hwdef.inc + +define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-EFI" + +define HAL_USE_ADC FALSE +define STM32_ADC_USE_ADC1 FALSE +define HAL_DISABLE_ADC_DRIVER TRUE + +# support all serial EFI types +define HAL_PERIPH_ENABLE_EFI +define HAL_EFI_ENABLED 1 + +define AP_PERIPH_EFI_PORT_DEFAULT 2 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Periph/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Periph/hwdef-bl.dat new file mode 100644 index 00000000000..dd6b5cc8873 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Periph/hwdef-bl.dat @@ -0,0 +1,3 @@ +include ../MatekL431/hwdef-bl.inc + +define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-Periph" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Periph/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Periph/hwdef.dat new file mode 100644 index 00000000000..f0bbdf1f653 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Periph/hwdef.dat @@ -0,0 +1,88 @@ +include ../MatekL431/hwdef.inc + +define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-Periph" + + +# --------------------- PWM ----------------------- +PA8 TIM1_CH1 TIM1 PWM(1) GPIO(50) +PA9 TIM1_CH2 TIM1 PWM(2) GPIO(51) +PA10 TIM1_CH3 TIM1 PWM(3) GPIO(52) +PA11 TIM1_CH4 TIM1 PWM(4) GPIO(53) +PA15 TIM2_CH1 TIM2 PWM(5) GPIO(54) + +# Beeper +PA6 TIM16_CH1 TIM16 GPIO(32) ALARM + +# ----------------------- GPS ---------------------------- +define HAL_PERIPH_ENABLE_GPS +define GPS_MAX_RATE_MS 200 + +define GPS_MAX_RECEIVERS 1 +define GPS_MAX_INSTANCES 1 + +define HAL_PERIPH_GPS_PORT_DEFAULT 2 + +# allow for F9P GPS modules with moving baseline +define GPS_MOVING_BASELINE 1 + + +# ---------------------- COMPASS --------------------------- +define HAL_PERIPH_ENABLE_MAG + +SPIDEV rm3100 SPI1 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ +COMPASS RM3100 SPI:rm3100 false ROTATION_PITCH_180 + +define HAL_COMPASS_MAX_SENSORS 1 + +# added QMC5883L for different board varients +COMPASS QMC5883L I2C:0:0xd false ROTATION_PITCH_180_YAW_90 + + +# --------------------- Barometer --------------------------- +define HAL_PERIPH_ENABLE_BARO +define HAL_BARO_ALLOW_INIT_NO_BARO + +BARO SPL06 I2C:0:0x76 + +# ------------------ I2C airspeed ------------------------- +define HAL_PERIPH_ENABLE_AIRSPEED + +# MS4525 sensor by default +define HAL_AIRSPEED_TYPE_DEFAULT 1 +define AIRSPEED_MAX_SENSORS 1 + +# -------------------- MSP -------------------------------- +define HAL_PERIPH_ENABLE_MSP +define HAL_MSP_ENABLED 1 +define AP_PERIPH_MSP_PORT_DEFAULT 1 + +# ------------------ BATTERY Monitor ----------------------- +define HAL_PERIPH_ENABLE_BATTERY + +define HAL_USE_ADC TRUE +define STM32_ADC_USE_ADC1 TRUE + +PA0 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PA1 BATT_CURRENT_SENS ADC1 SCALE(1) + +define HAL_BATT_MONITOR_DEFAULT 0 +define HAL_BATT_VOLT_PIN 5 +define HAL_BATT_VOLT_SCALE 21.0 +define HAL_BATT_CURR_PIN 6 +define HAL_BATT_CURR_SCALE 40.0 + + +PB0 BATT2_VOLTAGE_SENS ADC1 SCALE(1) +PB1 BATT2_CURRENT_SENS ADC1 SCALE(1) + +define HAL_BATT2_MONITOR_DEFAULT 0 +define HAL_BATT2_VOLT_PIN 15 +define HAL_BATT2_VOLT_SCALE 21.0 +define HAL_BATT2_CURR_PIN 16 +define HAL_BATT2_CURR_SCALE 40.0 + + +# -------------------- Buzzer+NeoPixels --------------d------ +define HAL_PERIPH_ENABLE_RC_OUT +define HAL_PERIPH_ENABLE_NOTIFY + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Rangefinder/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Rangefinder/hwdef-bl.dat new file mode 100644 index 00000000000..ffb40904b01 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Rangefinder/hwdef-bl.dat @@ -0,0 +1,3 @@ +include ../MatekL431/hwdef-bl.inc + +define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-Rangefinder" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Rangefinder/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Rangefinder/hwdef.dat new file mode 100644 index 00000000000..97d9233199d --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Rangefinder/hwdef.dat @@ -0,0 +1,13 @@ +include ../MatekL431/hwdef.inc + +define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-Rangefinder" + +define HAL_USE_ADC FALSE +define STM32_ADC_USE_ADC1 FALSE +define HAL_DISABLE_ADC_DRIVER TRUE + +# support all rangefinder types +define HAL_PERIPH_ENABLE_RANGEFINDER + +define AP_PERIPH_RANGEFINDER_PORT_DEFAULT 2 +define RANGEFINDER_MAX_INSTANCES 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431/hwdef-bl.inc b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431/hwdef-bl.inc new file mode 100644 index 00000000000..06fd4b629e1 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431/hwdef-bl.inc @@ -0,0 +1,61 @@ +# hw definition file Matek L431 CAN node + +# MCU class and specific type +MCU STM32L431 STM32L431xx + +# crystal frequency +OSCILLATOR_HZ 8000000 + +# board ID for firmware load +APJ_BOARD_ID 1062 + +# setup build for a peripheral firmware +env AP_PERIPH 1 + +FLASH_RESERVE_START_KB 0 +FLASH_BOOTLOADER_LOAD_KB 36 +FLASH_SIZE_KB 256 + +# reserve some space for params +APP_START_OFFSET_KB 4 + +# --------------------------------------------- +PB3 LED_BOOTLOADER OUTPUT LOW # blue +define HAL_LED_ON 0 + +# enable CAN support +PB8 CAN1_RX CAN1 +PB9 CAN1_TX CAN1 +# PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW + +CAN_ORDER 1 + +# --------------------------------------------- + +# make bl baudrate match debug baudrate for easier debugging +define BOOTLOADER_BAUDRATE 57600 + +# use a small bootloader timeout +define HAL_BOOTLOADER_TIMEOUT 1000 + +define HAL_USE_SERIAL FALSE + +define HAL_NO_GPIO_IRQ +define SERIAL_BUFFERS_SIZE 32 +define HAL_USE_EMPTY_IO TRUE +define PORT_INT_REQUIRED_STACK 64 +define DMA_RESERVE_SIZE 0 + +MAIN_STACK 0x800 +PROCESS_STACK 0x800 + +define HAL_DISABLE_LOOP_DELAY + +# Add CS pins to ensure they are high in bootloader +PA4 MAG_CS CS +PB2 SPARE_CS CS + +# debugger support +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431/hwdef.inc b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431/hwdef.inc new file mode 100644 index 00000000000..131207d14b7 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431/hwdef.inc @@ -0,0 +1,106 @@ +# hw definition file for Matek L431 CAN node + +# MCU class and specific type +MCU STM32L431 STM32L431xx + +# bootloader starts firmware at 36k + 4k (STORAGE_FLASH) +FLASH_RESERVE_START_KB 40 +FLASH_SIZE_KB 256 + +# store parameters in pages 18 and 19 +STORAGE_FLASH_PAGE 18 +define HAL_STORAGE_SIZE 800 + +# ChibiOS system timer +STM32_ST_USE_TIMER 15 +define CH_CFG_ST_RESOLUTION 16 + +# board ID for firmware load +APJ_BOARD_ID 1062 + +# crystal frequency +OSCILLATOR_HZ 8000000 + +env AP_PERIPH 1 + +STDOUT_SERIAL SD1 +STDOUT_BAUDRATE 57600 + +define HAL_NO_GPIO_IRQ +define SERIAL_BUFFERS_SIZE 512 +define PORT_INT_REQUIRED_STACK 64 + +define DMA_RESERVE_SIZE 0 + +# MAIN_STACK is stack for ISR handlers +MAIN_STACK 0x300 + +# PROCESS_STACK controls stack for main thread +PROCESS_STACK 0xA00 + +define HAL_DISABLE_LOOP_DELAY + +define HAL_GCS_ENABLED 0 +define HAL_NO_MONITOR_THREAD +define HAL_NO_LOGGING + +# we setup a small defaults.parm +define AP_PARAM_MAX_EMBEDDED_PARAM 512 + +# blue LED0 marked as ACT +PB3 LED OUTPUT HIGH +define HAL_LED_ON 1 + +# debugger support +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# --------------------- SPI1 RM3100 ----------------------- +PA5 SPI1_SCK SPI1 +PB4 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 +PA4 MAG_CS CS +PB2 SPARE_CS CS + + +# ---------------------- I2C bus ------------------------ +I2C_ORDER I2C2 + +PB13 I2C2_SCL I2C2 +PB14 I2C2_SDA I2C2 + +define HAL_I2C_CLEAR_ON_TIMEOUT 0 +define HAL_I2C_INTERNAL_MASK 1 + + +# ---------------------- CAN bus ------------------------- +CAN_ORDER 1 + +PB8 CAN1_RX CAN1 +PB9 CAN1_TX CAN1 +# PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW + +define HAL_CAN_POOL_SIZE 6000 + +# ---------------------- UARTs --------------------------- +# | sr0 | MSP | GPS | +SERIAL_ORDER USART1 USART2 USART3 + +# USART1 for debug +PB6 USART1_TX USART1 SPEED_HIGH +PB7 USART1_RX USART1 SPEED_HIGH + +# USART2 for MSP +PA2 USART2_TX USART2 SPEED_HIGH +PA3 USART2_RX USART2 SPEED_HIGH + +# USART3 for GPS +PB10 USART3_TX USART3 SPEED_HIGH NODMA +PB11 USART3_RX USART3 SPEED_HIGH NODMA + +# allow for reboot command for faster development +define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0 + +# keep ROMFS uncompressed as we don't have enough RAM +# to uncompress the bootloader at runtime +env ROMFS_UNCOMPRESSED True diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-G491/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-G491/hwdef-bl.dat index 8123d675e8b..f58271dcc8b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-G491/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-G491/hwdef-bl.dat @@ -4,7 +4,7 @@ MCU STM32G491 STM32G491xx FLASH_RESERVE_START_KB 0 -FLASH_BOOTLOADER_LOAD_KB 26 +FLASH_BOOTLOADER_LOAD_KB 36 # reserve some space for params APP_START_OFFSET_KB 4 @@ -12,29 +12,31 @@ APP_START_OFFSET_KB 4 # board ID for firmware load APJ_BOARD_ID 1040 +# setup build for a peripheral firmware +env AP_PERIPH 1 + +# enable CAN support +PB8 CAN1_RX CAN1 +PB9 CAN1_TX CAN1 + +CAN_ORDER 1 + # crystal frequency OSCILLATOR_HZ 24000000 # assume 256k flash part FLASH_SIZE_KB 256 -STDOUT_SERIAL SD1 -STDOUT_BAUDRATE 115200 +#STDOUT_SERIAL SD1 +#STDOUT_BAUDRATE 115200 # order of UARTs -SERIAL_ORDER USART1 +SERIAL_ORDER # a fault LED PA5 LED_BOOTLOADER OUTPUT LOW define HAL_LED_ON 1 -# USART1 -PA9 USART1_TX USART1 SPEED_HIGH NODMA -PA10 USART1_RX USART1 SPEED_HIGH NODMA - -define HAL_USE_SERIAL TRUE -define STM32_SERIAL_USE_USART1 TRUE - define HAL_NO_GPIO_IRQ define HAL_USE_EMPTY_IO TRUE diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-G491/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-G491/hwdef.dat index f29ec3ed2b8..4a9fc1c45b8 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-G491/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-G491/hwdef.dat @@ -1,18 +1,23 @@ # hw definition file for processing by chibios_pins.py +AUTOBUILD_TARGETS None + # MCU class and specific type MCU STM32G491 STM32G491xx -# bootloader starts firmware at 26k + 4k (STORAGE_FLASH) -FLASH_RESERVE_START_KB 30 +# bootloader starts firmware at 36k + 4k (STORAGE_FLASH) +FLASH_RESERVE_START_KB 40 -# store parameters in pages 13 and 14 -STORAGE_FLASH_PAGE 13 +# store parameters in pages 18/19 +STORAGE_FLASH_PAGE 18 define HAL_STORAGE_SIZE 800 # board ID for firmware load APJ_BOARD_ID 1040 +# setup build for a peripheral firmware +env AP_PERIPH 1 + # crystal frequency OSCILLATOR_HZ 24000000 @@ -29,6 +34,12 @@ STDOUT_BAUDRATE 57600 PA9 USART1_TX USART1 SPEED_HIGH PA10 USART1_RX USART1 SPEED_HIGH +# enable CAN support +PB8 CAN1_RX CAN1 +PB9 CAN1_TX CAN1 + +CAN_ORDER 1 + # LEDs PA5 LED OUTPUT LOW @@ -56,8 +67,6 @@ define DMA_RESERVE_SIZE 2048 define HAL_DISABLE_LOOP_DELAY -define HAL_MINIMIZE_FEATURES 0 - define AP_PARAM_MAX_EMBEDDED_PARAM 512 define HAL_USE_ADC TRUE diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L476/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L476/hwdef.dat index cbd13e18b27..1d7e9c52033 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L476/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L476/hwdef.dat @@ -1,5 +1,7 @@ # hw definition file for processing by chibios_pins.py +AUTOBUILD_TARGETS None + # MCU class and specific type MCU STM32L476 STM32L476xx @@ -89,8 +91,6 @@ PA4 VSENSE ADC1 SCALE(2) define HAL_NO_MONITOR_THREAD -define HAL_MINIMIZE_FEATURES 0 - define AP_PARAM_MAX_EMBEDDED_PARAM 512 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L496/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L496/hwdef.dat index a1beacc03ac..2c30a5dc47f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L496/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L496/hwdef.dat @@ -1,5 +1,7 @@ # hw definition file for processing by chibios_pins.py +AUTOBUILD_TARGETS None + # MCU class and specific type MCU STM32L496 STM32L496xx diff --git a/libraries/AP_HAL_ChibiOS/hwdef/NucleoH743/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/NucleoH743/hwdef.dat index 09cc01d0fca..516279d4382 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/NucleoH743/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/NucleoH743/hwdef.dat @@ -1,6 +1,8 @@ # hw definition file for processing by chibios_hwdef.py # for H743 bootloader +AUTOBUILD_TARGETS None + # MCU class and specific type MCU STM32H7xx STM32H743xx @@ -54,19 +56,21 @@ PB4 SPI3_MISO SPI3 PB5 SPI3_MOSI SPI3 # SPI devices -SPIDEV mpu6000 SPI3 DEVID1 MPU_CS MODE3 2*MHZ 8*MHZ -SPIDEV ms5611 SPI3 DEVID2 BARO_CS MODE3 8*MHZ 8*MHZ +# SPIDEV mpu6000 SPI3 DEVID1 MPU_CS MODE3 2*MHZ 8*MHZ +# SPIDEV ms5611 SPI3 DEVID2 BARO_CS MODE3 8*MHZ 8*MHZ # analog in PA0 BATT_VOLTAGE_SENS ADC1 SCALE(1) PA1 BATT_CURRENT_SENS ADC1 SCALE(1) -define ALLOW_ARM_NO_COMPASS +# define ALLOW_ARM_NO_COMPASS # probe for an invensense IMU -IMU Invensense SPI:mpu6000 ROTATION_NONE +#IMU Invensense SPI:mpu6000 ROTATION_NONE # and ms5611 baro -BARO MS56XX SPI:ms56xx +#BARO MS56XX SPI:ms5611 # define HAL_DISABLE_DCACHE + +include ../include/SimOnHW.inc diff --git a/libraries/AP_HAL_ChibiOS/hwdef/NucleoH755/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/NucleoH755/defaults.parm new file mode 100644 index 00000000000..8dd37bd7f1a --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/NucleoH755/defaults.parm @@ -0,0 +1,9 @@ +SERIAL3_BAUD 57 +SERIAL3_PROTOCOL 5 +SERIAL3_OPTIONS 256 + +SERIAL4_BAUD 115 +SERIAL4_PROTOCOL 23 +SERIAL4_OPTIONS 0 + + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/NucleoH755/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/NucleoH755/hwdef-bl.dat new file mode 100644 index 00000000000..c74391c2bda --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/NucleoH755/hwdef-bl.dat @@ -0,0 +1,43 @@ +# hw definition file for processing by chibios_hwdef.py +# for H755 bootloader - H755 is almost identical to H757, so utilizing its STM32H757xx.py file + +# MCU class and specific type +MCU STM32H7xx STM32H757xx + +# crystal frequency +OSCILLATOR_HZ 8000000 + +define CORE_CM7 +define SMPS_PWR + +# board ID for firmware load +APJ_BOARD_ID 139 + +# the nucleo seems to have trouble with flashing the last sector? +FLASH_SIZE_KB 2048 + +# the location where the bootloader will put the firmware +# the H755 has 128k sectors +FLASH_BOOTLOADER_LOAD_KB 256 + +# bootloader is installed at zero offset +FLASH_RESERVE_START_KB 0 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 + +#LED setup +PB0 LED_BOOTLOADER OUTPUT LOW +PB14 LED_ACTIVITY OUTPUT LOW +define HAL_LED_ON 0 + +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# Add CS pins to ensure they are high in bootloader +PA4 MPU_CS CS +PC7 BARO_CS CS + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/NucleoH755/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/NucleoH755/hwdef.dat new file mode 100644 index 00000000000..b14421a04ca --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/NucleoH755/hwdef.dat @@ -0,0 +1,147 @@ +# hw definition file for processing by chibios_hwdef.py +# for H755 - H755 is almost identical to H757, so utilizing its STM32H757xx.py file + +AUTOBUILD_TARGETS None + +# MCU class and specific type +MCU STM32H7xx STM32H757xx + +# crystal frequency +OSCILLATOR_HZ 8000000 + +STM32_ST_USE_TIMER 5 + +define CORE_CM7 +define SMPS_PWR + +# board ID for firmware load +APJ_BOARD_ID 139 + +# the nucleo seems to have trouble with flashing the last sector? +FLASH_SIZE_KB 2048 + +FLASH_BOOTLOADER_LOAD_KB 256 +FLASH_RESERVE_START_KB 256 + +define HAL_STORAGE_SIZE 32768 +STORAGE_FLASH_PAGE 14 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART2 UART7 USART1 UART4 UART5 + +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# order of UARTs and suggested uses +# USART2 TELEM1 +# UART7 TELEM2 +# USART1 GPS +# UART4 RCIN/OUT Telem +# UART5 DEBUG + +# telem1 USART2 +PD3 USART2_CTS USART2 +PD4 USART2_RTS USART2 +PD5 USART2_TX USART2 +PD6 USART2_RX USART2 + +# telem2 UART7 +PF9 UART7_CTS UART7 +PF8 UART7_RTS UART7 +PF7 UART7_TX UART7 +PF6 UART7_RX UART7 + +# GPS USART1 +PB7 USART1_RX USART1 +PB6 USART1_TX USART1 + +# RCIN/OUT UART4 +PB9 UART4_TX UART4 +PB8 UART4_RX UART4 + +# debug uart5 +PB13 UART5_TX UART5 +PB12 UART5_RX UART5 + +# Now setup the pins for the microSD card, if available. +PC8 SDMMC1_D0 SDMMC1 +PC9 SDMMC1_D1 SDMMC1 +PC10 SDMMC1_D2 SDMMC1 +PC11 SDMMC1_D3 SDMMC1 +PC12 SDMMC1_CK SDMMC1 +PD2 SDMMC1_CMD SDMMC1 + +# CAN Busses +PD0 CAN1_RX CAN1 +PD1 CAN1_TX CAN1 + +# PWM Output +PB1 TIM8_CH3N TIM8 PWM(1) GPIO(50) +PA0 TIM2_CH1 TIM2 PWM(2) GPIO(51) +PE9 TIM1_CH1 TIM1 PWM(3) GPIO(52) +PA2 TIM2_CH3 TIM2 PWM(4) GPIO(53) +PA3 TIM2_CH4 TIM2 PWM(5) GPIO(54) +PD12 TIM4_CH1 TIM4 PWM(6) GPIO(55) +PD13 TIM4_CH2 TIM4 PWM(7) GPIO(56) +PD14 TIM4_CH3 TIM4 PWM(8) GPIO(57) +PD15 TIM4_CH4 TIM4 PWM(9) GPIO(58) +PE5 TIM15_CH1 TIM15 PWM(10) GPIO(59) +PE6 TIM15_CH2 TIM15 PWM(11) GPIO(60) +PA8 TIM1_CH1 TIM1 PWM(12) GPIO(61) # for WS2812 LED + +define HAL_SPI_CHECK_CLOCK_FREQ + +# sensor CS +PC7 MPU_CS CS + +# status LEDs +define HAL_LED_ON 0 +PB0 LED OUTPUT HIGH GPIO(0) #Green +PE1 LED1 OUTPUT HIGH GPIO(2) #Yellow +PB14 LED2 OUTPUT HIGH GPIO(1) #Red +define HAL_GPIO_A_LED_PIN 0 +define HAL_GPIO_B_LED_PIN 1 +define HAL_GPIO_C_LED_PIN 2 +define HAL_GPIO_LED_OFF 1 +define HAL_GPIO_LED_ON 0 + +# I2C +I2C_ORDER I2C2 +define HAL_I2C_INTERNAL_MASK 0 +PB10 I2C2_SCL I2C2 +PB11 I2C2_SDA I2C2 + +# Enable FAT filesystem support (needs a microSD defined via SDMMC). +define HAL_OS_FATFS_IO 1 +# Now some defines for logging and terrain data files. +define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" +define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" + +# barometers +BARO BMP388 I2C:0:0x77 + +# SPI1 +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 + +# SPI3 +PB3 SPI3_SCK SPI3 +PB4 SPI3_MISO SPI3 +PB5 SPI3_MOSI SPI3 + +# SPI devices +SPIDEV icm20948 SPI3 DEVID1 MPU_CS MODE3 4*MHZ 8*MHZ + +# analog in +PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PC3 BATT_CURRENT_SENS ADC1 SCALE(1) + +# probe for an invensense IMU +IMU Invensensev2 SPI:icm20948 ROTATION_YAW_270 + +# compass as part of ICM20948 on newer cubes +COMPASS AK09916:probe_ICM20948 0 ROTATION_ROLL_180_YAW_90 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/OMNIBUSF7V2-bdshot/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/OMNIBUSF7V2-bdshot/hwdef.dat index 3d201024d49..5f3f32d3fac 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/OMNIBUSF7V2-bdshot/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/OMNIBUSF7V2-bdshot/hwdef.dat @@ -127,9 +127,8 @@ define HAL_PROBE_EXTERNAL_I2C_COMPASSES define HAL_I2C_INTERNAL_MASK 0 define HAL_COMPASS_AUTO_ROT_DEFAULT 2 -# disable SMBUS and fuel battery monitors to save flash +# disable SMBUS monitors to save flash define AP_BATTMON_SMBUS_ENABLE 0 -define AP_BATTMON_FUEL_ENABLE 0 # disable parachute and sprayer to save flash define HAL_PARACHUTE_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/OMNIBUSF7V2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/OMNIBUSF7V2/hwdef.dat index 6ea941c6495..6a65cc92214 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/OMNIBUSF7V2/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/OMNIBUSF7V2/hwdef.dat @@ -125,9 +125,8 @@ define HAL_PROBE_EXTERNAL_I2C_COMPASSES define HAL_I2C_INTERNAL_MASK 0 define HAL_COMPASS_AUTO_ROT_DEFAULT 2 -# disable SMBUS and fuel battery monitors to save flash +# disable SMBUS monitors to save flash define AP_BATTMON_SMBUS_ENABLE 0 -define AP_BATTMON_FUEL_ENABLE 0 # disable parachute and sprayer to save flash define HAL_PARACHUTE_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/OmnibusNanoV6/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/OmnibusNanoV6/hwdef.dat index d68019ed64d..b05872e0e00 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/OmnibusNanoV6/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/OmnibusNanoV6/hwdef.dat @@ -150,3 +150,6 @@ define STM32_PWM_USE_ADVANCED TRUE ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin define HAL_MOUNT_ENABLED 0 + +# minimal drivers to reduce flash usage +include ../include/minimal.inc diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PH4-mini-bdshot/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/PH4-mini-bdshot/hwdef-bl.dat new file mode 100644 index 00000000000..41c33fb2957 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/PH4-mini-bdshot/hwdef-bl.dat @@ -0,0 +1 @@ +include ../PH4-mini/hwdef-bl.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PH4-mini-bdshot/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/PH4-mini-bdshot/hwdef.dat new file mode 100644 index 00000000000..1581d528ce5 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/PH4-mini-bdshot/hwdef.dat @@ -0,0 +1,16 @@ +# hw definition file for processing by chibios_hwdef.py +# for Holybro PH4-mini hardware. + +include ../PH4-mini/hwdef.dat + +undef PD8 PD9 PA10 PE11 + +# This resolve DMA problem +PD8 USART3_TX USART3 NODMA +PD9 USART3_RX USART3 NODMA + +# This gives bi-dir dshot on the first four channels and regular dshot on the next two +PA10 TIM1_CH3 TIM1 PWM(2) GPIO(51) BIDIR +PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52) BIDIR + +DMA_PRIORITY TIM1_CH3 TIM1_CH2 TIM1_UP SDMMC* USART2* ADC* SPI* TIM* diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pix32v5/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pix32v5/hwdef.dat index 61c3bf6cc0c..ae5a92e3f60 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pix32v5/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pix32v5/hwdef.dat @@ -17,5 +17,5 @@ define HAL_IMUHEAT_I_DEFAULT 0.07 PG14 USART6_TX USART6 NODMA # offset the internal compass for EM impact of the IMU heater -# this is in sensor frame mGauss -define HAL_IST8310_I2C_HEATER_OFFSET Vector3f(-3,14,-6) +# this is in body frame mGauss +define HAL_HEATER_MAG_OFFSET {AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_I2C,0,0xe,0xa),Vector3f(18,0,8)} diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6/PixPilot-V6.png b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6/PixPilot-V6.png new file mode 100644 index 00000000000..b078a410046 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6/PixPilot-V6.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6/PixPilot-V6_2.png b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6/PixPilot-V6_2.png new file mode 100644 index 00000000000..d97db4754ea Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6/PixPilot-V6_2.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6/README.md b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6/README.md new file mode 100644 index 00000000000..82c572c3abc --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6/README.md @@ -0,0 +1,367 @@ +## PixPilot-V6 Flight Controller + +The PixPilot-V6 flight controller is sold by a range of resellers listed on the makeflyeasy(http://www.makeflyeasy.com) + +## Features + +• STM32H743VIT6 and STM32F103C8T6 microcontroller + +• Three IMUs, two ICM42688-P(SPI), one ICM40605(SPI) + +• internal heater for IMUs temperature control + +• internal Soft Rubber Damping Ball isolation for All interna IMUs + +• Two barometers, MS5611(SPI) + +• builtin IST8310 magnetometer(internal I2C) + +• builtin RAMTRON(SPI) + +• microSD card slot + +• 5 UARTs + +• USB(Type-C) + +• PPM & S.Bus input + +• 14 PWM outputs + +• tow I2C ports and two FDCAN ports + +• one S.Bus output + +• External Buzzer + +• builtin RGB LED + +• two voltage & current monitoring + +• servo rail BEC independent power input for servos + +• external safety Switch + + +## Pinout + +![PixPilot-V6](PixPilot-V6.png "PixPilot-V6") +![PixPilot-V6](PixPilot-V6_2.png "PixPilot-V6_2") + +UART Mapping +============ + + - SERIAL0 -> console (primary mavlink, usually USB) + - SERIAL1 -> USART2 (telem1) + - SERIAL2 -> USART3 (Telem2) + - SERIAL3 -> UART4 (GPS1) + - SERIAL4 -> UART8 (GPS2) + - SERIAL5 -> UART7 (USER) + + Connector pin assignments +========================= + +TELEM1, TELEM2 ports +-------------------- + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PinSignalVolt
1VCC+5V
2TX (OUT)+3.3V
3RX (IN)+3.3V
4GNDGND
+ +I2C1, I2C2 ports +--------------- + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PINSIGNALVOLT
1VCC+5V
2SCL+3.3V
3SDA+3.3V
4GNDGND
+ +CAN1, CAN2 ports +--------------- + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PINSIGNALVOLT
1VCC+5V
2CAN_H+12V
3CAN_L+12V
4GNDGND
+ +Safety and buzzer port +----------- + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PINSIGNALVOLT
1VCC+5V
2LED+5V
3SAFKEY+5V
4BUZZER+5V
53V++3.3V
6GNDGND
+ +GPS1/I2C1, GPS2/I2C2 ports +-------------------------- + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PINSIGNALVOLT
1VCC+5V
2TX+3.3V
3RX+3.3V
4SCL+3.3V
5SDA+3.3V
6GNDGND
+ +Serial5 port +-------------------- + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PinSignalVolt
1VCC+5V
2TX (OUT)+3.3V
3RX (IN)+3.3V
4GNDGND
+Power1, Power2 ports +-------------------- + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PINSIGNALVOLT
1VCC+5V
2VCC+5V
3CURRENT+3.3V
4VOLTAGE+3.3V
5GNDGND
6GNDGND
+ +RC Input +-------- + +All compatible RC protocols can be decoded by attaching the Receiver's output to the SBUS input pin next to the Servo/Output VCC input connector. Note that some protocols such as CRSF or FPort including telemetry, require connection to, and setup of, one of the UARTs instead of this pin. + +Battery Monitor Settings +======================== + +These should already be set by default. However, if lost or changed: + +Enable Battery monitor with these parameter settings : + +:ref:`BATT_MONITOR` =4 + +Then reboot. + +:ref:`BATT_VOLT_PIN` 14 + +:ref:`BATT_CURR_PIN` 15 + +:ref:`BATT_VOLT_MULT` 18.0 + +:ref:`BATT_AMP_PERVLT` 24.0 + +:ref:`BATT2_VOLT_PIN` 13 + +:ref:`BATT2_CURR_PIN` 4 + +:ref:`BATT2_VOLT_MULT` 18.0 + +:ref:`BATT2_AMP_PERVLT` 24.0 + +DroneCAN capability +=================== +There are 2 CAN ports which allow connecting two independant CAN bus outputs. Each of these can have multiple CAN peripheral devices connected. + +Where to Buy +============ + +`makeflyeasy `_ + + +[copywiki destination="plane,copter,rover,blimp"] diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6/hwdef-bl.dat new file mode 100644 index 00000000000..a833003a0c4 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6/hwdef-bl.dat @@ -0,0 +1,60 @@ +# hw definition file for processing by chibios_hwdef.py +# for H743 bootloader + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# crystal frequency +OSCILLATOR_HZ 24000000 + +# board ID for firmware load +APJ_BOARD_ID 1083 + +FLASH_SIZE_KB 2048 + +# bootloader is installed at zero offset +FLASH_RESERVE_START_KB 0 + +# the location where the bootloader will put the firmware +# the H743 has 128k sectors +FLASH_BOOTLOADER_LOAD_KB 128 + +env OPTIMIZE -Os +PB3 LED_ACTIVITY OUTPUT OPENDRAIN HIGH # red +PE12 LED_BOOTLOADER OUTPUT OPENDRAIN HIGH # blue +define HAL_LED_ON 0 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART2 USART3 UART7 + +# telem1 +PD5 USART2_TX USART2 +PD6 USART2_RX USART2 + +# telem2 +PD8 USART3_TX USART3 +PD9 USART3_RX USART3 + +# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters). +PE7 UART7_RX UART7 +PE8 UART7_TX UART7 + + +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# Add CS pins to ensure they are high in bootloader +PC2 42688_EXT_CS CS +PD7 BARO_EXT_CS CS +PC13 40605_EXT_CS CS +PE4 42688_CS CS +PC14 BARO_CS CS +PD10 FRAM_CS CS +PD2 SDCARD_CS CS + + +define HAL_USE_EMPTY_STORAGE 1 +define HAL_STORAGE_SIZE 32768 \ No newline at end of file diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6/hwdef.dat new file mode 100644 index 00000000000..bbd1a60eb90 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6/hwdef.dat @@ -0,0 +1,247 @@ +# hw definition file for processing by chibios_hwdef.py + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# crystal frequency +OSCILLATOR_HZ 24000000 + +# board ID for firmware load +APJ_BOARD_ID 1083 + +FLASH_SIZE_KB 2048 + + +# with 2M flash we can afford to optimize for speed +env OPTIMIZE -O2 + +FLASH_RESERVE_START_KB 128 + +define HAL_STORAGE_SIZE 32768 + +# order of I2C buses +I2C_ORDER I2C3 I2C2 I2C1 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 UART7 OTG2 + +#DEFAULTGPIO OUTPUT LOW PULLDOWN + +# USB. +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 +PA9 VBUS INPUT OPENDRAIN +PC0 VBUS_nVALID INPUT PULLUP + + +# telem1 +PD5 USART2_TX USART2 +PD6 USART2_RX USART2 +PD3 USART2_CTS USART2 +PD4 USART2_RTS USART2 + +PD3 EXTERN_GPIO4 OUTPUT GPIO(4) ALT(1) +PD4 EXTERN_GPIO5 OUTPUT GPIO(5) ALT(1) + +# telem2 +PD8 USART3_TX USART3 +PD9 USART3_RX USART3 +PD11 USART3_CTS USART3 +PD12 USART3_RTS USART3 + +# GPS +PA0 UART4_TX UART4 +PA1 UART4_RX UART4 NODMA + +# GPS2 +PE0 UART8_RX UART8 +PE1 UART8_TX UART8 NODMA + +# UART7 +PE7 UART7_RX UART7 +PE8 UART7_TX UART7 + +# UART for IOMCU +IOMCU_UART USART6 +PC6 USART6_TX USART6 +PC7 USART6_RX USART6 + + +PA2 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PA3 BATT_CURRENT_SENS ADC1 SCALE(1) + +# Now the VDD sense pin. This is used to sense primary board voltage. +PA4 VDD_5V_SENS ADC1 SCALE(2) + +# This defines an output pin which will default to output HIGH. It is +# a pin that enables peripheral power on this board. It starts in the +# off state, then is pulled low to enable peripherals in +# peripheral_power_enable() +#PA8 nVDD_5V_PERIPH_EN OUTPUT HIGH +PE3 VDD_3V3_SENSORS_EN OUTPUT LOW +# SWD debug +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# PWM output for buzzer +PA15 TIM2_CH1 TIM2 GPIO(77) ALARM + + +# CAN1 +PD0 CAN1_RX CAN1 +PD1 CAN1_TX CAN1 + +# CAN2 +PB6 CAN2_TX CAN2 +PB12 CAN2_RX CAN2 + +# I2C1 +PB8 I2C1_SCL I2C1 +PB9 I2C1_SDA I2C1 + +# I2C2 +PB10 I2C2_SCL I2C2 +PB11 I2C2_SDA I2C2 + +# I2C3 for onboard mag +PA8 I2C3_SCL I2C3 +PC9 I2C3_SDA I2C3 + +# SPI1. +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 + + +# SPI4. +PE2 SPI4_SCK SPI4 +PE5 SPI4_MISO SPI4 +PE6 SPI4_MOSI SPI4 + +# SPI2 +PB13 SPI2_SCK SPI2 +PB14 SPI2_MISO SPI2 +PB15 SPI2_MOSI SPI2 + + +# This defines more ADC inputs. +PC3 AUX_POWER ADC1 SCALE(1) +PC4 AUX_ADC2 ADC1 SCALE(1) + +# And the analog input for airspeed (rarely used these days). +PC5 PRESSURE_SENS ADC1 SCALE(2) + +# More CS pins for more sensors. The labels for all CS pins need to +# match the SPI device table later in this file. +PC2 42688_EXT_CS CS +PD7 BARO_EXT_CS CS +PC13 40605_EXT_CS CS +PE4 42688_CS CS +PC14 BARO_CS CS +PD10 FRAM_CS CS +PD2 SDCARD_CS CS + +PC1 42688_EXT_DRDY INPUT +PC15 40605_EXT_DRDY INPUT +PD15 42688_DRDY INPUT + +# Now we start defining some PWM pins. We also map these pins to GPIO +# values, so users can set SERVOx_FUNCTION=-1 to determine which +# PWM outputs on the primary MCU are set up as GPIOs. +# To match HAL_PX4 we number the GPIOs for the PWM outputs +# starting at 50. +PE14 TIM1_CH4 TIM1 PWM(1) GPIO(50) +PE13 TIM1_CH3 TIM1 PWM(2) GPIO(51) +PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52) +PE9 TIM1_CH1 TIM1 PWM(4) GPIO(53) +PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54) +PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55) + + +PB4 LED_RED OUTPUT OPENDRAIN GPIO(11) HIGH +PB3 LED_GREEN OUTPUT OPENDRAIN GPIO(12) HIGH +PB5 LED_BLUE OUTPUT OPENDRAIN GPIO(13) HIGH +define HAL_GPIO_LED_ON 0 +define HAL_GPIO_LED_OFF 1 + +define HAL_GPIO_A_LED_PIN 11 +define HAL_GPIO_B_LED_PIN 13 +define HAL_GPIO_C_LED_PIN 12 + +define HAL_HAVE_PIXRACER_LED + +# Power flag pins: these tell the MCU the status of the various power +# supplies that are available. The pin names need to exactly match the +# names used in AnalogIn.cpp. +PB2 VDD_BRICK_nVALID INPUT PULLUP +PB7 VDD_BRICK2_nVALID INPUT PULLUP +PE10 VDD_5V_HIPOWER_nOC INPUT PULLUP +PE15 VDD_5V_PERIPH_nOC INPUT PULLUP + +SPIDEV ms5611 SPI1 DEVID5 BARO_CS MODE3 20*MHZ 20*MHZ +SPIDEV ms5611_ext SPI4 DEVID2 BARO_EXT_CS MODE3 20*MHZ 20*MHZ + +SPIDEV ICM40605_ext SPI4 DEVID4 40605_EXT_CS MODE3 2*MHZ 8*MHZ +SPIDEV ICM42688_ext SPI4 DEVID5 42688_EXT_CS MODE3 2*MHZ 8*MHZ +SPIDEV ICM42688 SPI1 DEVID6 42688_CS MODE3 2*MHZ 8*MHZ +#SPIDEV iim42652 SPI1 DEVID6 42688_CS MODE3 2*MHZ 8*MHZ + +SPIDEV ramtron SPI2 DEVID10 FRAM_CS MODE3 8*MHZ 8*MHZ +SPIDEV sdcard SPI2 DEVID1 SDCARD_CS MODE0 400*KHZ 25*MHZ + + +# IMUs +IMU Invensensev3 SPI:ICM42688 ROTATION_NONE +IMU Invensensev3 SPI:ICM42688_ext ROTATION_NONE +IMU Invensensev3 SPI:ICM40605_ext ROTATION_NONE + +#IMU Invensensev3 SPI:iim42652 ROTATION_NONE + +define HAL_DEFAULT_INS_FAST_SAMPLE 7 + +# two baros +BARO MS56XX SPI:ms5611 +BARO MS56XX SPI:ms5611_ext + +# probe external I2C compasses plus some internal IST8310 +COMPASS IST8310 I2C:0:0x0E false ROTATION_ROLL_180 +define HAL_PROBE_EXTERNAL_I2C_COMPASSES +define HAL_I2C_INTERNAL_MASK 1 + +undef AP_FEATURE_SBUS_OUT + + +# Enable FAT filesystem support. +define HAL_OS_FATFS_IO 1 +define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" +define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" + +# allow to have have a dedicated safety switch pin +define HAL_HAVE_SAFETY_SWITCH 1 + +# Enable RAMTROM parameter storage. +define HAL_WITH_RAMTRON 1 +define HAL_STORAGE_SIZE 32768 + +# Setup the IMU heater +define HAL_HAVE_IMU_HEATER 1 +define HAL_IMU_TEMP_DEFAULT 45 +define HAL_IMUHEAT_P_DEFAULT 50 +define HAL_IMUHEAT_I_DEFAULT 0.07 +define HAL_IMU_TEMP_MARGIN_LOW_DEFAULT 5 + +# Enable all IMUs to be used and therefore three active EKF Lanes +define HAL_EKF_IMU_MASK_DEFAULT 7 + +# Now setup the default battery pins driver analog pins and default +# scaling for the power brick. +define HAL_BATT_VOLT_PIN 14 +define HAL_BATT_CURR_PIN 15 +define HAL_BATT_VOLT_SCALE 18.0 +define HAL_BATT_CURR_SCALE 24.0 +define HAL_GPIO_PWM_VOLT_PIN 3 +define HAL_GPIO_PWM_VOLT_3v3 1 + +ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_lowpolh.bin + +DMA_NOSHARE SPI1* SPI4* USART6* diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PixSurveyA1/README.md b/libraries/AP_HAL_ChibiOS/hwdef/PixSurveyA1/README.md new file mode 100644 index 00000000000..e487737ff6f --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/PixSurveyA1/README.md @@ -0,0 +1,37 @@ +## PixSurveyA1 Flight Controller +The flight controller is based on FMUv3, with added MPU9250 or ICM20948 internal compass support + +## Features +• STM32F427VIT6 and STM32F103C8T6 microcontroller + +• Three IMUs, one MPU6000(SPI), one ICM20602(SPI), one ICM20948 or MPU9250(SPI) + +• internal heater for IMUs temperature control + +• internal Soft Rubber Damping Ball isolation for interna IMUs + +• Two barometers, MS5611(SPI) + +• Internal compass use MPU9250 or ICM20948 + +• builtin RAMTRON(SPI) + +• microSD card slot + +• 5 UARTs plus USB(Type-C) + +• PPM & S.Bus input + +• 14 PWM outputs + +• two I2C and two CAN ports + +• one S.Bus output + +• External Buzzer + +• two voltage & current monitoring and servo rail voltage monitoring + +• servo rail BEC independent power input for servos + +• external safety Switch diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PixSurveyA1/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/PixSurveyA1/hwdef-bl.dat new file mode 100644 index 00000000000..107aad626ff --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/PixSurveyA1/hwdef-bl.dat @@ -0,0 +1,2 @@ +include ../fmuv3/hwdef-bl.dat +APJ_BOARD_ID 1076 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PixSurveyA1/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/PixSurveyA1/hwdef.dat new file mode 100644 index 00000000000..d096e54a45b --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/PixSurveyA1/hwdef.dat @@ -0,0 +1,21 @@ +# hw definition file for processing by chibios_hwdef.py +# for MFE-V3, based on fmuv3 +include ../fmuv3/hwdef.dat + +APJ_BOARD_ID 1076 + +#Use MPU9250 or ICM20948 on the new hardware +COMPASS AK8963:probe_mpu9250 0 ROTATION_PITCH_180 +COMPASS AK09916:probe_ICM20948 0 ROTATION_ROLL_180_YAW_90 + +COMPASS LSM303D SPI:lsm9ds0_ext_am ROTATION_YAW_270 +define HAL_PROBE_EXTERNAL_I2C_COMPASSES + +# two baros +BARO MS56XX SPI:ms5611_ext +BARO MS56XX SPI:ms5611 + +define HAL_IMU_TEMP_DEFAULT 45 +define HAL_IMUHEAT_P_DEFAULT 50 +define HAL_IMUHEAT_I_DEFAULT 0.07 +define HAL_IMU_TEMP_MARGIN_LOW_DEFAULT 5 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk1-1M/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk1-1M/hwdef.dat index 91534d170ff..c9fb1f51808 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk1-1M/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk1-1M/hwdef.dat @@ -3,6 +3,13 @@ include ../Pixhawk1/hwdef.dat +# only include UBLOX and NMEA GPS drivers +define AP_GPS_NMEA_ENABLED 1 +include ../include/minimal_GPS.inc + FLASH_SIZE_KB 1024 define HAL_MINIMIZE_FEATURES 1 undef STORAGE_FLASH_PAGE + +# produce this error if we are on a 2M board and using 1M firmware +define BOARD_CHECK_F427_USE_2M "2M flash - use Pixhawk1 firmware" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk1/README.md b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk1/README.md index 1dde31ef2e0..9252d0e51e2 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk1/README.md +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk1/README.md @@ -438,7 +438,7 @@ The Pixhawk1 supports up to 14 PWM outputs. First first 8 outputs (labelled "MAIN") are controlled by a dedicated STM32F100 IO controller. These 8 outputs support all PWM output formats, but not DShot. -The remaining 6 outputs (labelled AUX1 to AUX6) are the "auxillary" +The remaining 6 outputs (labelled AUX1 to AUX6) are the "auxiliary" outputs. These are directly attached to the STM32F427 and support all PWM protocols as well as DShot. @@ -448,7 +448,7 @@ The 8 main PWM outputs are in 3 groups: - PWM 3 and 4 in group2 - PWM 5, 6, 7 and 8 in group3 -The 6 auxillary PWM outputs are in 2 groups: +The 6 auxiliary PWM outputs are in 2 groups: - PWM 1, 2, 3 and 4 in group1 - PWM 5 and 6 in group2 @@ -459,7 +459,7 @@ to use DShot. ## Battery Monitoring -The board has a dedicatd power monitor port on a 6 pin DF13 +The board has a dedicated power monitor port on a 6 pin DF13 connector. The correct battery setting parameters are dependent on the type of power brick which is connected. @@ -471,7 +471,7 @@ part of a GPS/Compass combination. ## GPIOs -The 6 auxillary PWM ports can be used as GPIOs (relays, buttons, RPM +The 6 auxiliary PWM ports can be used as GPIOs (relays, buttons, RPM etc). To use them you need to limit the number of these pins that is used for PWM by setting the BRD_PWM_COUNT to a number less than 6. For example if you set BRD_PWM_COUNT to 4 then AUX5 and AUX6 will be diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk1/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk1/hwdef.dat index 1f8f36a2448..59759bd34ae 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk1/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk1/hwdef.dat @@ -33,3 +33,7 @@ COMPASS LSM303D SPI:lsm9ds0_am ROTATION_NONE # also probe for external compasses define HAL_PROBE_EXTERNAL_I2C_COMPASSES + +# produce this error if we are on a 1M board +undef BOARD_CHECK_F427_USE_1M +define BOARD_CHECK_F427_USE_1M "ERROR: 1M flash use Pixhawk1-1M" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk4/README.md b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk4/README.md index 1caf9ceec10..c9ae3027c91 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk4/README.md +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk4/README.md @@ -155,9 +155,9 @@ The Pixhawk4 supports up to 16 PWM outputs. First first 8 outputs (labelled "MAIN") are controlled by a dedicated STM32F100 IO controller. These 8 outputs support all PWM output formats, but not DShot. -The remaining 8 outputs (labelled AUX1 to AUX8) are the "auxillary" +The remaining 8 outputs (labelled AUX1 to AUX8) are the "auxiliary" outputs. These are directly attached to the STM32F765 and support all -PWM protocols. The first 4 of the auxillary PWM outputs support DShot. +PWM protocols. The first 4 of the auxiliary PWM outputs support DShot. The 8 main PWM outputs are in 3 groups: @@ -165,7 +165,7 @@ The 8 main PWM outputs are in 3 groups: - PWM 3 and 4 in group2 - PWM 5, 6, 7 and 8 in group3 -The 8 auxillary PWM outputs are in 3 groups: +The 8 auxiliary PWM outputs are in 3 groups: - PWM 1, 2, 3 and 4 in group1 - PWM 5 and 6 in group2 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/defaults.parm new file mode 100644 index 00000000000..311a84783e1 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/defaults.parm @@ -0,0 +1,5 @@ +# setup correct defaults for battery monitoring for holybro power brick +BATT_MONITOR 4 + +BATT2_CURR_PIN 14 +BATT2_VOLT_PIN 5 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef-bl.dat new file mode 100644 index 00000000000..da0f10b9928 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef-bl.dat @@ -0,0 +1,72 @@ +# hw definition file for processing by chibios_hwdef.py +# for the HolybroV6C hardware + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# USB setup +USB_VENDOR 0x3162 # ONLY FOR USE BY Holybro +USB_PRODUCT 0x0053 +USB_STRING_MANUFACTURER "Holybro" + +# board ID for firmware load +APJ_BOARD_ID 56 + +# bootloader is installed at zero offset +FLASH_RESERVE_START_KB 0 + +# the location where the bootloader will put the firmware +FLASH_BOOTLOADER_LOAD_KB 128 + +# flash size +FLASH_SIZE_KB 2048 + +env OPTIMIZE -Os + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 UART7 UART5 USART3 + +# default to all pins low to avoid ESD issues +DEFAULTGPIO OUTPUT LOW PULLDOWN + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 +PA9 VBUS INPUT OPENDRAIN + +# pins for SWD debugging +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# CS pins +PC13 ICM42688_CS CS +PC14 BMI055_G_CS CS +PC15 BMI055_A_CS CS +PD4 FRAM_CS CS + +# telem1 +PE8 UART7_TX UART7 +PE7 UART7_RX UART7 + +# telem2 +PC12 UART5_TX UART5 +PD2 UART5_RX UART5 + +# debug uart +PD8 USART3_TX USART3 +PD9 USART3_RX USART3 + +# start peripheral power off +PC10 nVDD_5V_HIPOWER_EN OUTPUT HIGH +PE2 nVDD_5V_PERIPH_EN OUTPUT HIGH + +# LEDs +PD10 LED_ACTIVITY OUTPUT OPENDRAIN GPIO(90) HIGH # red +PD11 LED_BOOTLOADER OUTPUT OPENDRAIN GPIO(92) HIGH # blue +define HAL_LED_ON 0 + +define HAL_USE_EMPTY_STORAGE 1 +define HAL_STORAGE_SIZE 16384 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef.dat new file mode 100644 index 00000000000..51385a38b44 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef.dat @@ -0,0 +1,264 @@ +# hw definition file for processing by chibios_hwdef.py +# for the HolybroV6C hardware + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# ChibiOS system timer +STM32_ST_USE_TIMER 2 + +# USB setup +USB_VENDOR 0x3162 # ONLY FOR USE BY Holybro +USB_PRODUCT 0x0053 +USB_STRING_MANUFACTURER "Holybro" + +# board ID for firmware load +APJ_BOARD_ID 56 + +FLASH_RESERVE_START_KB 128 + +# to be compatible with the px4 bootloader we need +# to use a different RAM_MAP +env USE_ALT_RAM_MAP 1 + +# flash size +FLASH_SIZE_KB 2048 + +env OPTIMIZE -O2 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 UART7 UART5 USART1 UART8 USART2 USART3 OTG2 + +# default the 2nd interface to MAVLink2 +define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2 + +# default to all pins low to avoid ESD issues +DEFAULTGPIO OUTPUT LOW PULLDOWN + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 +PA9 VBUS INPUT OPENDRAIN + +# pins for SWD debugging +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# telem1 +PE8 UART7_TX UART7 +PE7 UART7_RX UART7 +PE9 UART7_RTS UART7 +PE10 UART7_CTS UART7 + +# telem2 +PC12 UART5_TX UART5 +PD2 UART5_RX UART5 +PC8 UART5_RTS UART5 +PC9 UART5_CTS UART5 + +# GPS1 +PB6 USART1_TX USART1 +PA10 USART1_RX USART1 + +# GPS2 +PE1 UART8_TX UART8 +PE0 UART8_RX UART8 + +# uart2 telem3 +PD5 USART2_TX USART2 +PA3 USART2_RX USART2 + +# debug uart +PD8 USART3_TX USART3 +PD9 USART3_RX USART3 + +# USART6 is for IOMCU +PC6 USART6_TX USART6 +PC7 USART6_RX USART6 + +IOMCU_UART USART6 + +# ADC + +PC5 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PC4 BATT_CURRENT_SENS ADC1 SCALE(1) + +PB1 BATT2_VOLTAGE_SENS ADC1 SCALE(1) +PA2 BATT2_CURRENT_SENS ADC1 SCALE(1) + +define HAL_BATT_VOLT_PIN 8 +define HAL_BATT_CURR_PIN 4 +define HAL_BATT_VOLT_SCALE 18.18 +define HAL_BATT_CURR_SCALE 36.36 + +PA4 VDD_5V_SENS ADC1 SCALE(2) + +# SPI1 - IMUs +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 +PC13 ICM42688_CS CS +PC14 BMI055_G_CS CS +PC15 BMI055_A_CS CS +PE4 BMI055_DRDY_A INPUT +PE5 BMI055_DRDY_G INPUT +PE6 ICM42688_DRDY INPUT + +# SPI2 - FRAM +PD3 SPI2_SCK SPI2 +PC2 SPI2_MISO SPI2 +PC3 SPI2_MOSI SPI2 +PD4 FRAM_CS CS + +# PWM output pins +PA8 TIM1_CH1 TIM1 PWM(1) GPIO(50) +PE11 TIM1_CH2 TIM1 PWM(2) GPIO(51) +PE13 TIM1_CH3 TIM1 PWM(3) GPIO(52) +PE14 TIM1_CH4 TIM1 PWM(4) GPIO(53) +PD14 TIM4_CH3 TIM4 PWM(5) GPIO(54) +PD15 TIM4_CH4 TIM4 PWM(6) GPIO(55) +PA0 TIM5_CH1 TIM5 PWM(7) GPIO(56) +PA1 TIM5_CH2 TIM5 PWM(8) GPIO(57) + +# CAN bus +PD0 CAN1_RX CAN1 +PD1 CAN1_TX CAN1 + +PB5 CAN2_RX CAN2 +PB13 CAN2_TX CAN2 + + +# I2C buses + +# I2C1, GPS+MAG +PB7 I2C1_SDA I2C1 +PB8 I2C1_SCL I2C1 + +# I2C2, GPS2+MAG +PB10 I2C2_SCL I2C2 +PB11 I2C2_SDA I2C2 + +# I2C4 internal +PD12 I2C4_SCL I2C4 +PD13 I2C4_SDA I2C4 + +# order of I2C buses +I2C_ORDER I2C4 I2C1 I2C2 +define HAL_I2C_INTERNAL_MASK 1 + +# this board is tight on DMA channels. To allow for more UART DMA we +# disable DMA on I2C. This also prevents a problem with DMA on I2C +# interfering with IMUs +NODMA I2C* +define STM32_I2C_USE_DMA FALSE + +# heater +PB9 HEATER_EN OUTPUT LOW GPIO(80) +define HAL_HEATER_GPIO_PIN 80 + +# Setup the IMU heater +define HAL_HAVE_IMU_HEATER 1 +define HAL_IMU_TEMP_DEFAULT 45 +define HAL_IMUHEAT_P_DEFAULT 50 +define HAL_IMUHEAT_I_DEFAULT 0.07 + +# power enable pins +PB2 VDD_3V3_SENSORS1_EN OUTPUT HIGH + +# start peripheral power off, then enable after init +# this prevents a problem with radios that use RTS for +# bootloader hold +PC10 nVDD_5V_HIPOWER_EN OUTPUT HIGH +PE2 nVDD_5V_PERIPH_EN OUTPUT HIGH + +# Control of Spektrum power pin +PH2 SPEKTRUM_PWR OUTPUT HIGH GPIO(73) +define HAL_GPIO_SPEKTRUM_PWR 73 + +# Spektrum Power is Active High +define HAL_SPEKTRUM_PWR_ENABLED 1 + +# power sensing +PE3 VDD_5V_PERIPH_nOC INPUT PULLUP +PF13 VDD_5V_HIPOWER_nOC INPUT PULLUP + +PA15 VDD_BRICK_nVALID INPUT PULLUP +PB12 VDD_BRICK2_nVALID INPUT PULLUP + +# microSD support +PD6 SDMMC2_CK SDMMC2 +PD7 SDMMC2_CMD SDMMC2 +PB14 SDMMC2_D0 SDMMC2 +PB15 SDMMC2_D1 SDMMC2 +PB3 SDMMC2_D2 SDMMC2 +PB4 SDMMC2_D3 SDMMC2 +define FATFS_HAL_DEVICE SDCD2 + +# LEDs +PD10 LED_RED OUTPUT OPENDRAIN GPIO(90) HIGH +PD11 LED_BLUE OUTPUT OPENDRAIN GPIO(92) HIGH + +# setup for BoardLED2 +define HAL_GPIO_A_LED_PIN 90 +define HAL_GPIO_B_LED_PIN 92 +define HAL_GPIO_LED_ON 0 + +# ID pins +PE12 HW_VER_REV_DRIVE OUTPUT LOW +# PC0 HW_REV_SENS ADC1 SCALE(1) +# PC1 HW_VER_SENS ADC1 SCALE(1) + +# PWM output for buzzer +PB0 TIM3_CH3 TIM3 GPIO(77) ALARM + +# barometers +BARO MS56XX I2C:0:0x76 +BARO MS56XX I2C:0:0x77 +BARO BMP388 I2C:0:0x77 + +# prototypes may have no baro +define HAL_BARO_ALLOW_INIT_NO_BARO 1 + +# compass +define HAL_PROBE_EXTERNAL_I2C_COMPASSES +COMPASS IST8310 I2C:0:0x0C false ROTATION_NONE + +# compensate for magnetic field generated by the heater on 6C IST8310 +define HAL_HEATER_MAG_OFFSET {AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_I2C,0,0xc,0xa),Vector3f(17,14,0)} + + +# we need to stop the probe of an IST8310 as an internal compass with PITCH_180 +define HAL_COMPASS_DISABLE_IST8310_INTERNAL_PROBE + + +# SPI devices +SPIDEV bmi055_g SPI1 DEVID1 BMI055_G_CS MODE3 10*MHZ 10*MHZ +SPIDEV bmi055_a SPI1 DEVID2 BMI055_A_CS MODE3 10*MHZ 10*MHZ +SPIDEV icm42688 SPI1 DEVID3 ICM42688_CS MODE3 2*MHZ 8*MHZ +SPIDEV ramtron SPI2 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ + +# 2 IMUs +IMU Invensensev3 SPI:icm42688 ROTATION_PITCH_180_YAW_90 +IMU BMI055 SPI:bmi055_a SPI:bmi055_g ROTATION_PITCH_180 + +define HAL_DEFAULT_INS_FAST_SAMPLE 3 + +# enable RAMTROM parameter storage +define HAL_STORAGE_SIZE 32768 +define HAL_WITH_RAMTRON 1 + +# allow to have have a dedicated safety switch pin +define HAL_HAVE_SAFETY_SWITCH 1 + +DMA_PRIORITY SDMMC* USART6* ADC* UART* USART* SPI* TIM* + +# enable FAT filesystem support (needs a microSD defined via SDMMC) +define HAL_OS_FATFS_IO 1 + +define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" +define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" + +ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_lowpolh.bin diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-ODID/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-ODID/defaults.parm new file mode 100644 index 00000000000..b0387763a0f --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-ODID/defaults.parm @@ -0,0 +1,10 @@ +# enforce OpenDroneID on DroneCAN. Note that we need to lock down key parameters +# to ensure the integrity of the RemoteID system +DID_ENABLE 1 @READONLY +DID_OPTIONS 1 @READONLY +DID_MAVPORT -1 @READONLY +DID_CANDRIVER 1 @READONLY +AHRS_EKF_TYPE 3 @READONLY +GPS_TYPE 1 +GPS_TYPE2 0 + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-ODID/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-ODID/hwdef-bl.dat new file mode 100644 index 00000000000..11440d48ef0 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-ODID/hwdef-bl.dat @@ -0,0 +1,8 @@ +include ../Pixhawk6X/hwdef-bl.dat + +# use a different board ID, so vehicles with OpenDroneID enabled are +# prevented from loading the firmware without OpenDroneID enabled +APJ_BOARD_ID 10053 + +# enable OpenDroneID +define AP_OPENDRONEID_ENABLED 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-ODID/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-ODID/hwdef.dat new file mode 100644 index 00000000000..99d89a5bd4b --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-ODID/hwdef.dat @@ -0,0 +1,10 @@ +include ../Pixhawk6X/hwdef.dat + +# use a different board ID, so vehicles with OpenDroneID enabled are +# prevented from loading the firmware without OpenDroneID enabled +APJ_BOARD_ID 10053 + +# enable OpenDroneID +define AP_OPENDRONEID_ENABLED 1 + + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef-bl.dat new file mode 100644 index 00000000000..a5441cf790b --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef-bl.dat @@ -0,0 +1,76 @@ +# hw definition file for processing by chibios_hwdef.py +# for the HolybroV6X hardware + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# board ID for firmware load +APJ_BOARD_ID 53 + +# bootloader is installed at zero offset +FLASH_RESERVE_START_KB 0 + +# the location where the bootloader will put the firmware +FLASH_BOOTLOADER_LOAD_KB 128 + +# flash size +FLASH_SIZE_KB 2048 + +env OPTIMIZE -Os + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 UART7 UART5 USART3 + +# default to all pins low to avoid ESD issues +DEFAULTGPIO OUTPUT LOW PULLDOWN + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 +PA9 VBUS INPUT OPENDRAIN + +# pins for SWD debugging +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# CS pins +PI9 IMU1_CS CS +PH5 ICM42688_CS CS +PI4 BMI088_A_CS CS +PI8 BMI088_G_CS CS +PH15 BMM150_CS CS +PG7 FRAM_CS CS +PI10 EXT1_CS CS + +# telem1 +PE8 UART7_TX UART7 +PF6 UART7_RX UART7 + +# telem2 +PC12 UART5_TX UART5 +PD2 UART5_RX UART5 + +# debug uart +PD8 USART3_TX USART3 +PD9 USART3_RX USART3 + +# armed indication +PE6 nARMED OUTPUT HIGH + +# start peripheral power off +PF12 nVDD_5V_HIPOWER_EN OUTPUT HIGH +PG4 nVDD_5V_PERIPH_EN OUTPUT HIGH + +# LEDs +PE3 LED_ACTIVITY OUTPUT OPENDRAIN HIGH # red +PE5 LED_BOOTLOADER OUTPUT OPENDRAIN HIGH # blue +define HAL_LED_ON 0 + +define HAL_USE_EMPTY_STORAGE 1 +define HAL_STORAGE_SIZE 16384 + +# enable DFU by default +ENABLE_DFU_BOOT 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef.dat new file mode 100644 index 00000000000..d0399f20751 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef.dat @@ -0,0 +1,371 @@ +# hw definition file for processing by chibios_hwdef.py +# for the HolybroV6X hardware + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# ChibiOS system timer +STM32_ST_USE_TIMER 2 + +# board ID for firmware load +APJ_BOARD_ID 53 + +# enable board sub-type detection for FMUV6 +define HAL_CHIBIOS_ARCH_FMUV6 1 +define AP_FEATURE_BOARD_DETECT 1 + +FLASH_RESERVE_START_KB 128 + +# to be compatible with the px4 bootloader we need +# to use a different RAM_MAP +env USE_ALT_RAM_MAP 1 + +# flash size +FLASH_SIZE_KB 2048 + +env OPTIMIZE -O2 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 UART7 UART5 USART1 UART8 USART2 UART4 USART3 OTG2 + +# default the 2nd interface to MAVLink2 +define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2 + +# default to all pins low to avoid ESD issues +DEFAULTGPIO OUTPUT LOW PULLDOWN + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 +PA9 VBUS INPUT OPENDRAIN + +# pins for SWD debugging +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# telem1 +PE8 UART7_TX UART7 +PF6 UART7_RX UART7 +PF8 UART7_RTS UART7 +PE10 UART7_CTS UART7 + +# telem2 +PC8 UART5_RTS UART5 +PC9 UART5_CTS UART5 +PC12 UART5_TX UART5 +PD2 UART5_RX UART5 + +# telem3 +PA3 USART2_RX USART2 +PD5 USART2_TX USART2 +PD3 USART2_CTS USART2 +PD4 USART2_RTS USART2 + +# GPS1 +PB6 USART1_TX USART1 +PB7 USART1_RX USART1 + +# GPS2 +PE0 UART8_RX UART8 +PE1 UART8_TX UART8 + +# uart4 +PH13 UART4_TX UART4 +PH14 UART4_RX UART4 + +# debug uart +PD8 USART3_TX USART3 +PD9 USART3_RX USART3 + +# USART6 is for IOMCU +PC6 USART6_TX USART6 +PC7 USART6_RX USART6 +IOMCU_UART USART6 + +# uart6, RX only, RC input, if no IOMCU +# PC7 USART6_RX USART6 + +# ethernet (not implemented yet) +#PA1 ETH_REF_CLK +#PA2 ETH_MDIO +#PA7 ETH_CRS_DV +#PB11 ETH_TX_EN +#PC1 ETH_MDC +#PC4 ETH_RXD0 +#PC5 ETH_RXD1 +#PG12 ETH_TXD1 +#PG13 ETH_TXD0 +#PG15 ETH_POWER_EN + +# ADC +PA0 SCALED1_V3V3 ADC1 SCALE(2) +PA4 SCALED2_V3V3 ADC1 SCALE(2) +PB0 SCALED3_V3V3 ADC1 SCALE(2) +PF12 SCALED4_V3V3 ADC1 SCALE(2) + +PB1 VDD_5V_SENS ADC1 SCALE(2) + +# pin7 on AD&IO, analog 12 +PC2 ADC1_6V6 ADC1 SCALE(2) + +# pin6 on AD&IO, analog 13 +PC3 ADC1_3V3 ADC1 SCALE(1) + +# SPI1 - IMU1 +PA5 SPI1_SCK SPI1 +PB5 SPI1_MOSI SPI1 +PG9 SPI1_MISO SPI1 +PI9 IMU1_CS CS + +# SPI2 - ICM42688 +PI1 SPI2_SCK SPI2 +PI2 SPI2_MISO SPI2 +PI3 SPI2_MOSI SPI2 +PH5 ICM42688_CS CS +PA10 ICM42688_DRDY INPUT + +# SPI3 - BMI088 +PB2 SPI3_MOSI SPI3 +PC10 SPI3_SCK SPI3 +PC11 SPI3_MISO SPI3 +PI4 BMI088_A_CS CS +PI8 BMI088_G_CS CS +PI6 BMI088_DRDY_ACC INPUT +PI7 BMI088_DRDY_GYR INPUT + +# SPI4 - BMM150 +PE12 SPI4_SCK SPI4 +PE13 SPI4_MISO SPI4 +PE14 SPI4_MOSI SPI4 +PF3 BMM150_DRDY INPUT +PH15 BMM150_CS CS + +# SPI5 - FRAM +PF7 SPI5_SCK SPI5 +PH7 SPI5_MISO SPI5 +PF11 SPI5_MOSI SPI5 +PG7 FRAM_CS CS + +# SPI6 - external1 (disabled to save DMA channels) +# PB3 SPI6_SCK SPI6 +# PA6 SPI6_MISO SPI6 +# PG14 SPI6_MOSI SPI6 +# PI10 EXT1_CS CS + +# PWM output pins +PI0 TIM5_CH4 TIM5 PWM(1) GPIO(50) +PH12 TIM5_CH3 TIM5 PWM(2) GPIO(51) +PH11 TIM5_CH2 TIM5 PWM(3) GPIO(52) +PH10 TIM5_CH1 TIM5 PWM(4) GPIO(53) +PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54) +PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55) + +# we need to disable DMA on the last 2 FMU channels +# as timer 12 doesn't have a TIMn_UP DMA option +PH6 TIM12_CH1 TIM12 PWM(7) GPIO(56) NODMA +PH9 TIM12_CH2 TIM12 PWM(8) GPIO(57) NODMA + +# GPIOs +PE11 FMU_CAP1 INPUT GPIO(58) +PC0 NFC_GPIO INPUT GPIO(60) + + +# CAN bus +PD0 CAN1_RX CAN1 +PD1 CAN1_TX CAN1 + +PB12 CAN2_RX CAN2 +PB13 CAN2_TX CAN2 + + +# I2C buses + +# I2C1, GPS+MAG +PB9 I2C1_SDA I2C1 +PB8 I2C1_SCL I2C1 + +# I2C2, GPS2+MAG +PF1 I2C2_SCL I2C2 +PF0 I2C2_SDA I2C2 +PG5 DRDY1_BMP388 INPUT + +# I2C3, MS5611, external +PA8 I2C3_SCL I2C3 +PH8 I2C3_SDA I2C3 + +# I2C4 internal +PF14 I2C4_SCL I2C4 +PF15 I2C4_SDA I2C4 + +# order of I2C buses +I2C_ORDER I2C4 I2C1 I2C2 I2C3 +define HAL_I2C_INTERNAL_MASK 1 + +# this board is very tight on DMA channels. To allow for more UART DMA +# we disable DMA on I2C. This also prevents a problem with DMA on I2C +# interfering with IMUs +NODMA I2C* +define STM32_I2C_USE_DMA FALSE + +# heater +PB10 HEATER_EN OUTPUT LOW GPIO(80) +define HAL_HEATER_GPIO_PIN 80 + +# Setup the IMU heater +define HAL_HAVE_IMU_HEATER 1 +define HAL_IMU_TEMP_DEFAULT 45 +define HAL_IMUHEAT_P_DEFAULT 50 +define HAL_IMUHEAT_I_DEFAULT 0.07 + +# armed indication +PE6 nARMED OUTPUT HIGH + +# power enable pins +PC13 VDD_3V3_SD_CARD_EN OUTPUT HIGH +PI11 VDD_3V3_SENSORS1_EN OUTPUT HIGH +PF4 VDD_3V3_SENSORS2_EN OUTPUT HIGH +PE7 VDD_3V3_SENSORS3_EN OUTPUT HIGH +PG8 VDD_3V3_SENSORS4_EN OUTPUT HIGH +PG15 ETH_PWR_EN OUTPUT LOW # disable power on ethernet + +# start peripheral power off, then enable after init +# this prevents a problem with radios that use RTS for +# bootloader hold +PG10 nVDD_5V_HIPOWER_EN OUTPUT HIGH +PG4 nVDD_5V_PERIPH_EN OUTPUT HIGH + +# Control of Spektrum power pin +PH2 SPEKTRUM_PWR OUTPUT HIGH GPIO(73) +define HAL_GPIO_SPEKTRUM_PWR 73 + +# Spektrum Power is Active High +define HAL_SPEKTRUM_PWR_ENABLED 1 + +# power sensing +PE15 VDD_5V_PERIPH_nOC INPUT PULLUP +PF13 VDD_5V_HIPOWER_nOC INPUT PULLUP + +PG1 VDD_BRICK_nVALID INPUT PULLUP +PG2 VDD_BRICK2_nVALID INPUT PULLUP +PG3 VDD_BRICK3_nVALID INPUT PULLUP + +# microSD support +PD6 SDMMC2_CK SDMMC2 +PD7 SDMMC2_CMD SDMMC2 +PB14 SDMMC2_D0 SDMMC2 +PB15 SDMMC2_D1 SDMMC2 +PG11 SDMMC2_D2 SDMMC2 +PB4 SDMMC2_D3 SDMMC2 +define FATFS_HAL_DEVICE SDCD2 + +# safety +PD10 LED_SAFETY OUTPUT +PF5 SAFETY_IN INPUT PULLDOWN + +# LEDs +PE3 LED_RED OUTPUT OPENDRAIN GPIO(90) HIGH +PE4 LED_GREEN OUTPUT OPENDRAIN GPIO(91) HIGH +PE5 LED_BLUE OUTPUT OPENDRAIN GPIO(92) HIGH + +# setup for "pixracer" RGB LEDs +define HAL_GPIO_A_LED_PIN 90 +define HAL_GPIO_B_LED_PIN 91 +define HAL_GPIO_C_LED_PIN 92 +define HAL_GPIO_LED_ON 0 + +define HAL_HAVE_PIXRACER_LED + +# ID pins +PG0 HW_VER_REV_DRIVE OUTPUT LOW +# PH3 HW_VER_SENS ADC3 SCALE(1) +# PH4 HW_REV_SENS ADC3 SCALE(1) + +# PWM output for buzzer +PF9 TIM14_CH1 TIM14 GPIO(77) ALARM + +# RC input +PI5 TIM8_CH1 TIM8 RCININT PULLDOWN LOW + +# barometers (Holybro 6X) +BARO BMP388 I2C:2:0x76 +BARO BMP388 I2C:0:0x77 + +# barometers (CUAV 6X) +BARO ICP201XX I2C:0:0x64 +BARO ICP201XX I2C:2:0x63 + +# compass +define HAL_PROBE_EXTERNAL_I2C_COMPASSES + +# builtin compass on Holybro 6X +COMPASS BMM150 I2C:0:0x10 false ROTATION_NONE + +# builtin compass on CUAV 6X +COMPASS RM3100 I2C:0:0x20 false ROTATION_PITCH_180 + +# compensate for magnetic field generated by the heater on CUAV-6X RM3100 +define HAL_HEATER_MAG_OFFSET_RM3100 AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_I2C,0,0x20,0x11),Vector3f(-19,37,-24) + +# compensate for magnetic field generated by the heater on Holybro6X BMM150 +define HAL_HEATER_MAG_OFFSET_BMM150 AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_I2C,0,0x10,0x05),Vector3f(12,-38,23) + +define HAL_HEATER_MAG_OFFSET {HAL_HEATER_MAG_OFFSET_RM3100, HAL_HEATER_MAG_OFFSET_BMM150} + +# IMU devices for Holybro6X +SPIDEV bmi088_g SPI3 DEVID1 BMI088_G_CS MODE3 10*MHZ 10*MHZ +SPIDEV bmi088_a SPI3 DEVID2 BMI088_A_CS MODE3 10*MHZ 10*MHZ +# alternative to bmi088 +SPIDEV icm20649 SPI3 DEVID1 BMI088_A_CS MODE3 10*MHZ 10*MHZ +SPIDEV icm42688 SPI2 DEVID1 ICM42688_CS MODE3 2*MHZ 8*MHZ +SPIDEV icm42670 SPI1 DEVID1 IMU1_CS MODE3 2*MHZ 8*MHZ + +# IMU devices for CUAV-6X. The CUAV board has a BMI088, ICM20649 and +# ICM42688 the ICM42688 and BMI088 are on the same SPI buses and CS +# pins as the Holybro board, but the orientation of the BMI088 is +# different. The ICM20649 is on a different bus +SPIDEV icm20649_2 SPI1 DEVID1 IMU1_CS MODE3 2*MHZ 8*MHZ + +SPIDEV ramtron SPI5 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ + +# Holybro6X 3 IMUs +IMU Invensensev3 SPI:icm42688 ROTATION_PITCH_180_YAW_90 BOARD_MATCH(FMUV6_BOARD_HOLYBRO_6X) +IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_PITCH_180 BOARD_MATCH(FMUV6_BOARD_HOLYBRO_6X) +IMU Invensensev2 SPI:icm20649 ROTATION_YAW_180 BOARD_MATCH(FMUV6_BOARD_HOLYBRO_6X) # alternative to BMI088 +IMU Invensensev3 SPI:icm42670 ROTATION_YAW_90 BOARD_MATCH(FMUV6_BOARD_HOLYBRO_6X) + +# CUAV-6X 3 IMUs +IMU Invensensev3 SPI:icm42688 ROTATION_ROLL_180_YAW_270 BOARD_MATCH(FMUV6_BOARD_CUAV_6X) +IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_PITCH_180 BOARD_MATCH(FMUV6_BOARD_CUAV_6X) +IMU Invensensev2 SPI:icm20649_2 ROTATION_ROLL_180 BOARD_MATCH(FMUV6_BOARD_CUAV_6X) + +define HAL_DEFAULT_INS_FAST_SAMPLE 7 + +# enable RAMTROM parameter storage +define HAL_STORAGE_SIZE 32768 +define HAL_WITH_RAMTRON 1 + +# INA226 battery monitor +define HAL_BATTMON_INA2XX_BUS 1 +define HAL_BATTMON_INA2XX_ADDR 0x41 +define HAL_BATT_MONITOR_DEFAULT 21 + +# allow to have have a dedicated safety switch pin +define HAL_HAVE_SAFETY_SWITCH 1 + +DMA_PRIORITY SDMMC* USART6* ADC* UART* USART* SPI* TIM* + +# enable FAT filesystem support (needs a microSD defined via SDMMC) +define HAL_OS_FATFS_IO 1 + +define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" +define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" + +ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_lowpolh.bin + +# enable DFU reboot for installing bootloader +# note that if firmware is build with --secure-bl then DFU is +# disabled +ENABLE_DFU_BOOT 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/param/CUAV_V6X_defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/param/CUAV_V6X_defaults.parm new file mode 100644 index 00000000000..1d631c53281 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/param/CUAV_V6X_defaults.parm @@ -0,0 +1,3 @@ +BATT_MONITOR=8 +CAN_P1_DRIVER=1 +CAN_P2_DRIVER=1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotH743/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotH743/defaults.parm index fb5477cba0b..65b893da7cb 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotH743/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotH743/defaults.parm @@ -2,10 +2,10 @@ BRD_HEAT_TARG 45 # setup serial2 port defaults for ESP8266 -define HAL_SERIAL2_PROTOCOL SerialProtocol_MAVLink2 -define HAL_SERIAL2_BAUD 921600 +SERIAL2_BAUD 921600 # setup the parameter for the ADC power module +BATT_MONITOR 4 BATT_VOLT_PIN 16 BATT_CURR_PIN 17 BATT_VOLT_MULT 20.000 @@ -16,5 +16,5 @@ BATT2_VOLT_MULT 20.000 BATT2_AMP_PERVLT 17.000 # setup the parameter for the two Relays GPIO others for reserve -define RELAY1_PIN_DEFAULT 1 -define RELAY2_PIN_DEFAULT 2 \ No newline at end of file +RELAY_PIN 1 +RELAY_PIN2 2 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotH743/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotH743/hwdef.dat index bed152a23be..dfca39149e9 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotH743/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotH743/hwdef.dat @@ -20,7 +20,7 @@ STM32_ST_USE_TIMER 2 FLASH_RESERVE_START_KB 128 # order of UARTs (and USB) -SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART7 +SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART7 OTG2 # now we define the pins that USB is connected on PA11 OTG_FS_DM OTG1 @@ -167,6 +167,7 @@ IMU Invensensev3 SPI:imu1 ROTATION_YAW_270 IMU Invensense SPI:imu2 ROTATION_ROLL_180 IMU Invensensev3 SPI:imu2 ROTATION_YAW_270 IMU Invensense SPI:imu3 ROTATION_ROLL_180 +IMU Invensensev3 SPI:imu3 ROTATION_YAW_270 # two Baro sensors diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ReaperF745v2/README.md b/libraries/AP_HAL_ChibiOS/hwdef/ReaperF745v2/README.md new file mode 100644 index 00000000000..69c3d26d049 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/ReaperF745v2/README.md @@ -0,0 +1,96 @@ +# Foxeer ReaperF745v2 Flight Controller + +The ReaperF745v2 is a flight controller produced by [Foxeer](https://www.foxeer.com/). + +## Features + + - MCU - STM32F745 32-bit processor + - IMU - BMI270 + - OSD - AT7456E + - Onboard Flash: 128MBit + - 5x UARTs + - 5x PWM Outputs (4 Motor Output, 1 LED) + - Battery input voltage: 2S-6S + - Integrated 45A BlueJay ESCs + +## Pinout + +![ReaperF745v2 Board](ReaperF745v2_Board.jpg "ReaperF745v2") + +## UART Mapping + +The UARTs are marked Rn and Tn in the above pinouts. The Rn pin is the +receive pin for UARTn. The Tn pin is the transmit pin for UARTn. + + - SERIAL0 -> USB + - SERIAL1 -> UART1 (DJI RCIN) + - SERIAL2 -> UART2 (RX, DMA-enabled) + - SERIAL3 -> UART3 + - SERIAL4 -> UART4 (Camera) + - SERIAL7 -> UART7 (GPS, DMA-enabled) + +## RC Input + +RC input is configured on the R2 (UART2_RX) pin. It supports all serial RC +protocols. For protocols requiring half-duplex serial to transmit +telemetry (such as FPort) you should setup the TX PIN as an RC input serial port, +with half-duplex, pin-swap and inversion enabled. + +## FrSky Telemetry + +FrSky Telemetry is supported using the T2 pin (UART2 transmit). You need to set the following parameters to enable support for FrSky S.PORT + + - SERIAL5_PROTOCOL 10 + - SERIAL5_OPTIONS 7 + +## OSD Support + +The ReaperF745v2 supports OSD using OSD_TYPE 1 (MAX7456 driver). + +## PWM Output + +The ReaperF745v2 supports up to 5 PWM outputs. There are no pads for motor output +M1 to M4 as these are connected directly to the onboard ESCs. M5 is on a separate pad for LED strip or another PWM output. + +The PWM is in 2 groups: + + - PWM 1-4 in group1 + - PWM 5 in group2 + +Channels within the same group need to use the same output rate. If +any channel in a group uses DShot then all channels in the group need +to use DShot. Channels 1-4 support bi-directional dshot and this is configured by +default to take advantage of the BlueJay ESC firmware that is installed by default. + +## Battery Monitoring + +The board has a builtin voltage and current sensor. The current +sensor can read up to 130 Amps. The voltage sensor can handle up to 6S +LiPo batteries. + +The correct battery setting parameters are: + + - BATT_MONITOR 4 + - BATT_VOLT_PIN 13 + - BATT_CURR_PIN 12 + - BATT_VOLT_MULT 10.9 + - BATT_AMP_PERVLT 100 + +## Compass + +The ReaperF745v2 does not have a builtin compass, but you can attach an external compass using I2C on the SDA and SCL pads. + +## Barometer + +The ReaperF745v2 does not have a builtin barometer, but you can attach an external barometer using I2C on the SDA and SCL pads. + +## Loading Firmware + +Initial firmware load can be done with DFU by plugging in USB with the +bootloader button pressed. Then you should load the "with_bl.hex" +firmware, using your favourite DFU loading tool. + +Once the initial firmware is loaded you can update the firmware using +any ArduPilot ground station software. Updates should be done with the +*.apj firmware files. + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ReaperF745v2/ReaperF745v2_Board.jpg b/libraries/AP_HAL_ChibiOS/hwdef/ReaperF745v2/ReaperF745v2_Board.jpg new file mode 100644 index 00000000000..a34183563e0 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/ReaperF745v2/ReaperF745v2_Board.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ReaperF745v2/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/ReaperF745v2/defaults.parm new file mode 100644 index 00000000000..c1272aee931 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/ReaperF745v2/defaults.parm @@ -0,0 +1,10 @@ +# setup for LEDs on chan5 +SERVO5_FUNCTION 120 +NTF_LED_TYPES 257 +# setup SERIAL3 for RCIN +SERIAL2_BAUD 115 +# Board has BlueJay by default +SERVO_BLH_BDMASK 15 +SERVO_BLH_AUTO 1 +SERVO_BLH_TRATE 0 +MOT_PWM_TYPE 6 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ReaperF745v2/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/ReaperF745v2/hwdef-bl.dat new file mode 100644 index 00000000000..c8e18b0d9ac --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/ReaperF745v2/hwdef-bl.dat @@ -0,0 +1,41 @@ +# hw definition file for processing by chibios_pins.py +# for Foxeer Reaper AIO V2 F745 + +# MCU class and specific type +MCU STM32F7xx STM32F745xx + +# board ID for firmware load +APJ_BOARD_ID 1074 + +# crystal frequency, setup to use external oscillator +OSCILLATOR_HZ 8000000 + +FLASH_SIZE_KB 1024 + +# bootloader starts at zero offset +FLASH_RESERVE_START_KB 0 + +# the location where the bootloader will put the firmware +FLASH_BOOTLOADER_LOAD_KB 96 + +# order of UARTs (and USB). Allow bootloading on USB and telem1 +SERIAL_ORDER OTG1 USART1 + +# USART1 +PA10 USART1_RX USART1 +PA9 USART1_TX USART1 + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +PC13 LED_BOOTLOADER OUTPUT LOW +define HAL_LED_ON 0 + +# Add CS pins to ensure they are high in bootloader +PA4 AT7456E_CS CS +PA15 BMI270_CS CS +PE4 FLASH_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ReaperF745v2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/ReaperF745v2/hwdef.dat new file mode 100644 index 00000000000..003b927b2ea --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/ReaperF745v2/hwdef.dat @@ -0,0 +1,156 @@ +# hw definition file for processing by chibios_pins.py +# for Foxeer Reaper AIO V2 F745 + +# thanks to betaflight for pin information + +# MCU class and specific type +MCU STM32F7xx STM32F745xx + +# board ID for firmware load +APJ_BOARD_ID 1074 + +# crystal frequency, setup to use external oscillator +OSCILLATOR_HZ 8000000 + +FLASH_SIZE_KB 1024 + +# bootloader takes first sector +FLASH_RESERVE_START_KB 96 + +# only one I2C bus +I2C_ORDER I2C1 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 EMPTY EMPTY UART7 + +# Buzzer - DMA timer channel use by LEDs +PD2 BUZZER OUTPUT GPIO(80) LOW +define HAL_BUZZER_PIN 80 +define HAL_BUZZER_ON 1 +define HAL_BUZZER_OFF 0 + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# Debug +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# SPI1 for OSD +PA4 AT7456E_CS CS +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 + +# SPI2 +#PA15 FLASH_CS CS +#PB13 SPI2_SCK SPI2 +#PB14 SPI2_MISO SPI2 +#PB15 SPI2_MOSI SPI2 + +# SPI3 for Gyro +PA15 BMI270_CS CS +PC10 SPI3_SCK SPI3 +PC11 SPI3_MISO SPI3 +PC12 SPI3_MOSI SPI3 + +# SPI4 for Flash +PE4 FLASH_CS CS +PE2 SPI4_SCK SPI4 +PE5 SPI4_MISO SPI4 +PE6 SPI4_MOSI SPI4 + +# I2C1 for baro +PB8 I2C1_SCL I2C1 PULLUP +PB9 I2C1_SDA I2C1 PULLUP + +PC3 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PC2 BATT_CURRENT_SENS ADC1 SCALE(1) + +# define default battery setup +define HAL_BATT_VOLT_PIN 13 +define HAL_BATT_CURR_PIN 12 +define HAL_BATT_VOLT_SCALE 10.9 +define HAL_BATT_CURR_SCALE 100 +define HAL_BATT_MONITOR_DEFAULT 4 + +PC5 RSSI_ADC ADC1 + +# USART1 (DJI RCIN) +PA10 USART1_RX USART1 NODMA + +# USART2 (RX) +PA2 USART2_TX USART2 +PA3 USART2_RX USART2 +define HAL_SERIAL2_PROTOCOL SerialProtocol_RCIN + +# USART3 +PB10 USART3_TX USART3 NODMA +PB11 USART3_RX USART3 NODMA + +# UART4 (Camera) +PA0 UART4_TX UART4 NODMA +PA1 UART4_RX UART4 NODMA + +# UART7 (GPS) +PE7 UART7_RX UART7 +PE8 UART7_TX UART7 + +# Motor order implies Betaflight/X for standard ESCs +define HAL_FRAME_TYPE_DEFAULT 12 + +# Motors +PB4 TIM3_CH1 TIM3 PWM(1) GPIO(50) BIDIR # 1 +PB5 TIM3_CH2 TIM3 PWM(2) GPIO(51) # 2 +PB1 TIM3_CH4 TIM3 PWM(3) GPIO(52) BIDIR # 3 +PB0 TIM3_CH3 TIM3 PWM(4) GPIO(53) # 4 + +# NeoPixel LED strip +PA8 TIM1_CH1 TIM1 PWM(5) GPIO(54) +PC13 LED0 OUTPUT LOW GPIO(90) # Blue LED + +DMA_PRIORITY USART2* TIM3* TIM1* + +define HAL_STORAGE_SIZE 16384 +STORAGE_FLASH_PAGE 1 + +# enable logging to dataflash +define HAL_LOGGING_DATAFLASH_ENABLED 1 + +# spi devices +SPIDEV bmi270 SPI3 DEVID1 BMI270_CS MODE3 1*MHZ 4*MHZ +SPIDEV dataflash SPI4 DEVID1 FLASH_CS MODE3 32*MHZ 32*MHZ +SPIDEV osd SPI1 DEVID1 AT7456E_CS MODE0 10*MHZ 10*MHZ + +# no built-in compass +define ALLOW_ARM_NO_COMPASS +define HAL_PROBE_EXTERNAL_I2C_COMPASSES +define HAL_I2C_INTERNAL_MASK 0 + +# one IMU bmi270 +IMU BMI270 SPI:bmi270 ROTATION_ROLL_180 +define HAL_DEFAULT_INS_FAST_SAMPLE 1 + +# no BARO +define HAL_BARO_ALLOW_INIT_NO_BARO 1 + +# setup for OSD +define OSD_ENABLED 1 +define HAL_OSD_TYPE_DEFAULT 1 +ROMFS_WILDCARD libraries/AP_OSD/fonts/font0.bin + +define STM32_PWM_USE_ADVANCED TRUE + +# save some flash +define HAL_GENERATOR_ENABLED 0 +define AC_OAPATHPLANNER_ENABLED 0 +define PRECISION_LANDING 0 +define HAL_BARO_WIND_COMP_ENABLED 0 +define GRIPPER_ENABLED 0 +define HAL_PARACHUTE_ENABLED 0 +define HAL_SPRAYER_ENABLED 0 +define AP_BATTMON_SMBUS_ENABLE 0 +define AP_BATTMON_FUEL_ENABLE 0 +define AP_OPTICALFLOW_ENABLED 0 +define AP_ICENGINE_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/README.md b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/README.md index f31370c7e9c..b7df41f712b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/README.md +++ b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/README.md @@ -5,8 +5,8 @@ The SPRacingH7 Extreme is a flight controller produced by [Seriously Pro Racing] ## Features - MCU - STM32H750 32-bit processor running at 400 MHz - - 16MByte Serial NOR flash via QuadSPI - - IMUs - 2x ICM20602 + - 128MByte Serial NOR flash via QuadSPI + - IMUs - 2x ICM20602 (only one enabled by default due to CPU limitations) - Barometer - BMP388 - OSD - AT7456E - Onboard Flash: 128Mbits @@ -25,8 +25,8 @@ The UARTs are marked Rn and Tn in the above pinouts. The Rn pin is the receive pin for UARTn. The Tn pin is the transmit pin for UARTn. - SERIAL0 -> USB - - SERIAL1 -> UART1 (DMA-enabled) - - SERIAL2 -> UART2 (RCIN one wire, DMA-enabled) + - SERIAL1 -> UART1 (DMA-enabled) RCin + - SERIAL2 -> UART2 (SmartPort, DMA-enabled, only TX pin) - SERIAL3 -> UART3 (DMA-enabled) - SERIAL4 -> UART4 (DMA-enabled) - SERIAL5 -> UART5 (DMA-enabled) @@ -35,9 +35,9 @@ receive pin for UARTn. The Tn pin is the transmit pin for UARTn. ## RC Input -RC input is configured on the T2 (UART2_TX) pin. It supports all serial RC +RC input is configured on the R1 (UART1_RX) pin. It supports all serial RC protocols. For protocols requiring half-duplex serial to transmit -telemetry (such as FPort) you should setup SERIAL2 as an RC input serial port, +telemetry (such as FPort) you should setup SERIAL1 with half-duplex, pin-swap and inversion enabled. ## FrSky Telemetry @@ -45,7 +45,7 @@ with half-duplex, pin-swap and inversion enabled. FrSky Telemetry is supported using the T2 pin (UART2 transmit). You need to set the following parameters to enable support for FrSky S.PORT - SERIAL2_PROTOCOL 10 - - SERIAL2_OPTIONS 7 + - SERIAL2_OPTIONS 15 ## OSD Support @@ -61,9 +61,9 @@ The PWM is in 5 groups: - PWM 1-4 in group1 - PWM 5, 6 in group2 - - PWM 7, 8 in group3 + - PWM 7, 8 in group3 (can be changed to UART6 TX/RX with alt config 1) - PWM 9, 10 in group4 - - PWM 11 in group5 + - PWM 11 in group5 (used for NeoPixel LED) Channels within the same group need to use the same output rate. If any channel in a group uses DShot then all channels in the group need @@ -80,8 +80,8 @@ The correct battery setting parameters are: - BATT_MONITOR 4 - BATT_VOLT_PIN 10 - BATT_CURR_PIN 11 - - BATT_VOLT_MULT 11.1 - - BATT_AMP_PERVLT 59.5 + - BATT_VOLT_MULT 10.9 + - BATT_AMP_PERVLT 28.5 ## Compass diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/defaults.parm index d521a5f59d2..d30f89aa1ca 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/defaults.parm @@ -2,6 +2,9 @@ SERVO11_FUNCTION 120 NTF_LED_TYPES 257 -# setup SERIAL2 for RCIN -SERIAL2_BAUD 115 -SERIAL2_OPTIONS 8 +# setup SERIAL2 for SmartPort +SERIAL2_PROTOCOL 10 +SERIAL2_OPTIONS 15 + +# currently using both IMUs is too CPU intensive +INS_ENABLE_MASK 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/hwdef-bl.dat index 887fc131470..d1e7543e1a8 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/hwdef-bl.dat @@ -35,7 +35,7 @@ PA12 OTG_FS_DP OTG1 PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD -PE3 LED_BOOTLOADER OUTPUT LOW # Blue LED +PE3 LED_BOOTLOADER OUTPUT LOW # Red LED define HAL_LED_ON 0 # QuadSPI Flash @@ -57,3 +57,6 @@ DEFAULTGPIO OUTPUT LOW PULLDOWN PB12 ICM20602_2_CS CS PA15 ICM20602_1_CS CS PE11 AT7456E_CS CS + +## pull up VTX power +PB01 VTX_PWR OUTPUT HIGH GPIO(81) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/hwdef.dat index 5d317955279..13538e105fa 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7/hwdef.dat @@ -11,8 +11,12 @@ APJ_BOARD_ID 1060 # crystal frequency, setup to use external oscillator OSCILLATOR_HZ 8000000 +MCU_CLOCKRATE_MHZ 480 + env OPTIMIZE -O2 +define HAL_WITH_EKF_DOUBLE 0 + STM32_ST_USE_TIMER 2 # internal flash is off limits @@ -66,28 +70,33 @@ PE14 SPI4_MOSI SPI4 PB8 I2C1_SCL I2C1 PULLUP PB9 I2C1_SDA I2C1 PULLUP +# Internal current sensor PC1 BATT_VOLTAGE_SENS ADC1 SCALE(1) PC0 BATT_CURRENT_SENS ADC1 SCALE(1) +# External current sensor +PC5 BATT_CURRENT_SENS2 ADC1 SCALE(1) # analog pin 8 + +# VTX Power control - should be high at startup to ensure power +PB01 VTX_PWR OUTPUT HIGH GPIO(81) +define RELAY2_PIN_DEFAULT 81 PC4 RSSI_IN ADC1 define BOARD_RSSI_ANA_PIN 0 # define default battery setup -define HAL_BATT_VOLT_PIN 13 -define HAL_BATT_CURR_PIN 12 +define HAL_BATT_VOLT_PIN 11 +define HAL_BATT_CURR_PIN 10 define HAL_BATT_VOLT_SCALE 10.9 define HAL_BATT_CURR_SCALE 28.5 define HAL_BATT_MONITOR_DEFAULT 4 -PC5 RSSI_ADC ADC1 - -# USART1 +# USART1 (RCIN) PB15 USART1_RX USART1 PB14 USART1_TX USART1 +define HAL_SERIAL1_PROTOCOL SerialProtocol_RCIN -# USART2 (RCIN) +# USART2 (SmartPort) PD5 USART2_TX USART2 -define HAL_SERIAL2_PROTOCOL SerialProtocol_RCIN # USART3 PD9 USART3_RX USART3 @@ -148,7 +157,8 @@ PD15 TIM4_CH4 TIM4 PWM(10) GPIO(59) # M10 # NeoPixel LED strip PA8 TIM1_CH1 TIM1 PWM(11) GPIO(60) -PE3 LED0 OUTPUT LOW GPIO(90) # Blue LED + # Red LED +PE3 LED0 OUTPUT LOW GPIO(90) # spi devices SPIDEV icm20602_1 SPI3 DEVID1 ICM20602_1_CS MODE3 2*MHZ 10*MHZ @@ -160,6 +170,7 @@ DMA_PRIORITY SPI3* SPI2* TIM5* define HAL_COMPASS_DEFAULT HAL_COMPASS_NONE define ALLOW_ARM_NO_COMPASS define HAL_PROBE_EXTERNAL_I2C_COMPASSES +define HAL_I2C_INTERNAL_MASK 0 # two IMUs IMU Invensense SPI:icm20602_1 ROTATION_YAW_90 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/H7-16MHz/H7-16MHz.ioc b/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/H7-16MHz/H7-16MHz.ioc index 1a9138e8fa2..e95f668d462 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/H7-16MHz/H7-16MHz.ioc +++ b/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/H7-16MHz/H7-16MHz.ioc @@ -510,7 +510,7 @@ RCC.D1PPRE=RCC_APB3_DIV2 RCC.D2PPRE1=RCC_APB1_DIV2 RCC.D2PPRE2=RCC_APB2_DIV2 RCC.D3PPRE=RCC_APB4_DIV2 -RCC.DFSDMACLkFreq_Value=100000000 +RCC.DFSDMACLkFreq_Value=80000000 RCC.DFSDMFreq_Value=100000000 RCC.DIVM1=2 RCC.DIVM2=2 @@ -522,8 +522,8 @@ RCC.DIVP1Freq_Value=400000000 RCC.DIVP2Freq_Value=180000000 RCC.DIVP3=3 RCC.DIVP3Freq_Value=96000000 -RCC.DIVQ1=8 -RCC.DIVQ1Freq_Value=100000000 +RCC.DIVQ1=10 +RCC.DIVQ1Freq_Value=80000000 RCC.DIVQ2=5 RCC.DIVQ2Freq_Value=72000000 RCC.DIVQ3=6 @@ -533,8 +533,7 @@ RCC.DIVR2=1 RCC.DIVR2Freq_Value=360000000 RCC.DIVR3=9 RCC.DIVR3Freq_Value=32000000 -RCC.FDCANCLockSelection=RCC_FDCANCLKSOURCE_PLL2 -RCC.FDCANFreq_Value=72000000 +RCC.FDCANFreq_Value=80000000 RCC.FMCFreq_Value=200000000 RCC.FamilyName=M RCC.HCLK3ClockFreq_Value=200000000 @@ -547,7 +546,7 @@ RCC.I2C123CLockSelection=RCC_I2C123CLKSOURCE_PLL3 RCC.I2C123Freq_Value=32000000 RCC.I2C4CLockSelection=RCC_I2C4CLKSOURCE_PLL3 RCC.I2C4Freq_Value=32000000 -RCC.IPParameters=ADCCLockSelection,ADCFreq_Value,AHB12Freq_Value,AHB4Freq_Value,APB1Freq_Value,APB2Freq_Value,APB3Freq_Value,APB4Freq_Value,AXIClockFreq_Value,CECFreq_Value,CKPERFreq_Value,CPU2Freq_Value,CPU2SystikFreq_Value,CortexFreq_Value,CpuClockFreq_Value,D1CPREFreq_Value,D1PPRE,D2PPRE1,D2PPRE2,D3PPRE,DFSDMACLkFreq_Value,DFSDMFreq_Value,DIVM1,DIVM2,DIVM3,DIVN1,DIVN2,DIVN3,DIVP1Freq_Value,DIVP2Freq_Value,DIVP3,DIVP3Freq_Value,DIVQ1,DIVQ1Freq_Value,DIVQ2,DIVQ2Freq_Value,DIVQ3,DIVQ3Freq_Value,DIVR1Freq_Value,DIVR2,DIVR2Freq_Value,DIVR3,DIVR3Freq_Value,FDCANCLockSelection,FDCANFreq_Value,FMCFreq_Value,FamilyName,HCLK3ClockFreq_Value,HCLKFreq_Value,HPRE,HRTIMFreq_Value,HSE_VALUE,HSIDiv,I2C123CLockSelection,I2C123Freq_Value,I2C4CLockSelection,I2C4Freq_Value,LPTIM1Freq_Value,LPTIM2Freq_Value,LPTIM345Freq_Value,LPUART1Freq_Value,LTDCFreq_Value,MCO1PinFreq_Value,MCO2PinFreq_Value,PLL1_VCI_Range-AdvancedSettings,PLL1_VCO_SEL-AdvancedSettings,PLL2_VCI_Range-AdvancedSettings,PLL2_VCO_SEL-AdvancedSettings,PLL3FRACN,PLLFRACN,PLLSourceVirtual,PWR_Regulator_Voltage_Scale,QSPIFreq_Value,RNGFreq_Value,RTCFreq_Value,SAI1Freq_Value,SAI23Freq_Value,SAI4AFreq_Value,SAI4BFreq_Value,SDMMCFreq_Value,SPDIFRXFreq_Value,SPI123Freq_Value,SPI45Freq_Value,SPI6Freq_Value,SWPMI1Freq_Value,SYSCLKFreq_VALUE,SYSCLKSource,Tim1OutputFreq_Value,Tim2OutputFreq_Value,TraceFreq_Value,USART16Freq_Value,USART234578Freq_Value,USBCLockSelection,USBFreq_Value,VCO1OutputFreq_Value,VCO2OutputFreq_Value,VCO3OutputFreq_Value,VCOInput1Freq_Value,VCOInput2Freq_Value,VCOInput3Freq_Value +RCC.IPParameters=ADCCLockSelection,ADCFreq_Value,AHB12Freq_Value,AHB4Freq_Value,APB1Freq_Value,APB2Freq_Value,APB3Freq_Value,APB4Freq_Value,AXIClockFreq_Value,CECFreq_Value,CKPERFreq_Value,CPU2Freq_Value,CPU2SystikFreq_Value,CortexFreq_Value,CpuClockFreq_Value,D1CPREFreq_Value,D1PPRE,D2PPRE1,D2PPRE2,D3PPRE,DFSDMACLkFreq_Value,DFSDMFreq_Value,DIVM1,DIVM2,DIVM3,DIVN1,DIVN2,DIVN3,DIVP1Freq_Value,DIVP2Freq_Value,DIVP3,DIVP3Freq_Value,DIVQ1,DIVQ1Freq_Value,DIVQ2,DIVQ2Freq_Value,DIVQ3,DIVQ3Freq_Value,DIVR1Freq_Value,DIVR2,DIVR2Freq_Value,DIVR3,DIVR3Freq_Value,FDCANFreq_Value,FMCFreq_Value,FamilyName,HCLK3ClockFreq_Value,HCLKFreq_Value,HPRE,HRTIMFreq_Value,HSE_VALUE,HSIDiv,I2C123CLockSelection,I2C123Freq_Value,I2C4CLockSelection,I2C4Freq_Value,LPTIM1Freq_Value,LPTIM2Freq_Value,LPTIM345Freq_Value,LPUART1Freq_Value,LTDCFreq_Value,MCO1PinFreq_Value,MCO2PinFreq_Value,PLL1_VCI_Range-AdvancedSettings,PLL1_VCO_SEL-AdvancedSettings,PLL2_VCI_Range-AdvancedSettings,PLL2_VCO_SEL-AdvancedSettings,PLL3FRACN,PLLFRACN,PLLSourceVirtual,PWR_Regulator_Voltage_Scale,QSPIFreq_Value,RNGFreq_Value,RTCFreq_Value,SAI1Freq_Value,SAI23Freq_Value,SAI4AFreq_Value,SAI4BFreq_Value,SDMMCFreq_Value,SPDIFRXFreq_Value,SPI123Freq_Value,SPI45Freq_Value,SPI6Freq_Value,SWPMI1Freq_Value,SYSCLKFreq_VALUE,SYSCLKSource,Tim1OutputFreq_Value,Tim2OutputFreq_Value,TraceFreq_Value,USART16Freq_Value,USART234578Freq_Value,USBCLockSelection,USBFreq_Value,VCO1OutputFreq_Value,VCO2OutputFreq_Value,VCO3OutputFreq_Value,VCOInput1Freq_Value,VCOInput2Freq_Value,VCOInput3Freq_Value RCC.LPTIM1Freq_Value=100000000 RCC.LPTIM2Freq_Value=100000000 RCC.LPTIM345Freq_Value=100000000 @@ -566,13 +565,13 @@ RCC.PWR_Regulator_Voltage_Scale=PWR_REGULATOR_VOLTAGE_SCALE1 RCC.QSPIFreq_Value=200000000 RCC.RNGFreq_Value=48000000 RCC.RTCFreq_Value=32000 -RCC.SAI1Freq_Value=100000000 -RCC.SAI23Freq_Value=100000000 -RCC.SAI4AFreq_Value=100000000 -RCC.SAI4BFreq_Value=100000000 -RCC.SDMMCFreq_Value=100000000 -RCC.SPDIFRXFreq_Value=100000000 -RCC.SPI123Freq_Value=100000000 +RCC.SAI1Freq_Value=80000000 +RCC.SAI23Freq_Value=80000000 +RCC.SAI4AFreq_Value=80000000 +RCC.SAI4BFreq_Value=80000000 +RCC.SDMMCFreq_Value=80000000 +RCC.SPDIFRXFreq_Value=80000000 +RCC.SPI123Freq_Value=80000000 RCC.SPI45Freq_Value=100000000 RCC.SPI6Freq_Value=100000000 RCC.SWPMI1Freq_Value=100000000 @@ -597,12 +596,12 @@ SH.ADCx_INP4.0=ADC1_INP4,IN4-Single-Ended SH.ADCx_INP4.ConfNb=1 SH.S_TIM1_CH1.0=TIM1_CH1,Input_Capture1_from_TI1 SH.S_TIM1_CH1.ConfNb=1 -SPI1.CalculateBaudRate=50.0 MBits/s +SPI1.CalculateBaudRate=40.0 MBits/s SPI1.Direction=SPI_DIRECTION_2LINES SPI1.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate SPI1.Mode=SPI_MODE_MASTER SPI1.VirtualType=VM_MASTER -SPI2.CalculateBaudRate=50.0 MBits/s +SPI2.CalculateBaudRate=40.0 MBits/s SPI2.Direction=SPI_DIRECTION_2LINES SPI2.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate SPI2.Mode=SPI_MODE_MASTER diff --git a/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/H7-24MHz/H7-24MHz.ioc b/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/H7-24MHz/H7-24MHz.ioc index 819e948d241..721b69d23ec 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/H7-24MHz/H7-24MHz.ioc +++ b/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/H7-24MHz/H7-24MHz.ioc @@ -510,7 +510,7 @@ RCC.D1PPRE=RCC_APB3_DIV2 RCC.D2PPRE1=RCC_APB1_DIV2 RCC.D2PPRE2=RCC_APB2_DIV2 RCC.D3PPRE=RCC_APB4_DIV2 -RCC.DFSDMACLkFreq_Value=100000000 +RCC.DFSDMACLkFreq_Value=80000000 RCC.DFSDMFreq_Value=100000000 RCC.DIVM1=3 RCC.DIVM2=2 @@ -522,8 +522,8 @@ RCC.DIVP1Freq_Value=400000000 RCC.DIVP2Freq_Value=180000000 RCC.DIVP3=3 RCC.DIVP3Freq_Value=96000000 -RCC.DIVQ1=8 -RCC.DIVQ1Freq_Value=100000000 +RCC.DIVQ1=10 +RCC.DIVQ1Freq_Value=80000000 RCC.DIVQ2=5 RCC.DIVQ2Freq_Value=72000000 RCC.DIVQ3=6 @@ -533,8 +533,7 @@ RCC.DIVR2=1 RCC.DIVR2Freq_Value=360000000 RCC.DIVR3=9 RCC.DIVR3Freq_Value=32000000 -RCC.FDCANCLockSelection=RCC_FDCANCLKSOURCE_PLL2 -RCC.FDCANFreq_Value=72000000 +RCC.FDCANFreq_Value=80000000 RCC.FMCFreq_Value=200000000 RCC.FamilyName=M RCC.HCLK3ClockFreq_Value=200000000 @@ -547,7 +546,7 @@ RCC.I2C123CLockSelection=RCC_I2C123CLKSOURCE_PLL3 RCC.I2C123Freq_Value=32000000 RCC.I2C4CLockSelection=RCC_I2C4CLKSOURCE_PLL3 RCC.I2C4Freq_Value=32000000 -RCC.IPParameters=ADCCLockSelection,ADCFreq_Value,AHB12Freq_Value,AHB4Freq_Value,APB1Freq_Value,APB2Freq_Value,APB3Freq_Value,APB4Freq_Value,AXIClockFreq_Value,CECFreq_Value,CKPERFreq_Value,CPU2Freq_Value,CPU2SystikFreq_Value,CortexFreq_Value,CpuClockFreq_Value,D1CPREFreq_Value,D1PPRE,D2PPRE1,D2PPRE2,D3PPRE,DFSDMACLkFreq_Value,DFSDMFreq_Value,DIVM1,DIVM2,DIVM3,DIVN1,DIVN2,DIVN3,DIVP1Freq_Value,DIVP2Freq_Value,DIVP3,DIVP3Freq_Value,DIVQ1,DIVQ1Freq_Value,DIVQ2,DIVQ2Freq_Value,DIVQ3,DIVQ3Freq_Value,DIVR1Freq_Value,DIVR2,DIVR2Freq_Value,DIVR3,DIVR3Freq_Value,FDCANCLockSelection,FDCANFreq_Value,FMCFreq_Value,FamilyName,HCLK3ClockFreq_Value,HCLKFreq_Value,HPRE,HRTIMFreq_Value,HSE_VALUE,HSIDiv,I2C123CLockSelection,I2C123Freq_Value,I2C4CLockSelection,I2C4Freq_Value,LPTIM1Freq_Value,LPTIM2Freq_Value,LPTIM345Freq_Value,LPUART1Freq_Value,LTDCFreq_Value,MCO1PinFreq_Value,MCO2PinFreq_Value,PLL2_VCI_Range-AdvancedSettings,PLL3FRACN,PLLFRACN,PLLSourceVirtual,PWR_Regulator_Voltage_Scale,QSPIFreq_Value,RNGFreq_Value,RTCFreq_Value,SAI1Freq_Value,SAI23Freq_Value,SAI4AFreq_Value,SAI4BFreq_Value,SDMMCFreq_Value,SPDIFRXFreq_Value,SPI123Freq_Value,SPI45Freq_Value,SPI6Freq_Value,SWPMI1Freq_Value,SYSCLKFreq_VALUE,SYSCLKSource,Tim1OutputFreq_Value,Tim2OutputFreq_Value,TraceFreq_Value,USART16Freq_Value,USART234578Freq_Value,USBCLockSelection,USBFreq_Value,VCO1OutputFreq_Value,VCO2OutputFreq_Value,VCO3OutputFreq_Value,VCOInput1Freq_Value,VCOInput2Freq_Value,VCOInput3Freq_Value +RCC.IPParameters=ADCCLockSelection,ADCFreq_Value,AHB12Freq_Value,AHB4Freq_Value,APB1Freq_Value,APB2Freq_Value,APB3Freq_Value,APB4Freq_Value,AXIClockFreq_Value,CECFreq_Value,CKPERFreq_Value,CPU2Freq_Value,CPU2SystikFreq_Value,CortexFreq_Value,CpuClockFreq_Value,D1CPREFreq_Value,D1PPRE,D2PPRE1,D2PPRE2,D3PPRE,DFSDMACLkFreq_Value,DFSDMFreq_Value,DIVM1,DIVM2,DIVM3,DIVN1,DIVN2,DIVN3,DIVP1Freq_Value,DIVP2Freq_Value,DIVP3,DIVP3Freq_Value,DIVQ1,DIVQ1Freq_Value,DIVQ2,DIVQ2Freq_Value,DIVQ3,DIVQ3Freq_Value,DIVR1Freq_Value,DIVR2,DIVR2Freq_Value,DIVR3,DIVR3Freq_Value,FDCANFreq_Value,FMCFreq_Value,FamilyName,HCLK3ClockFreq_Value,HCLKFreq_Value,HPRE,HRTIMFreq_Value,HSE_VALUE,HSIDiv,I2C123CLockSelection,I2C123Freq_Value,I2C4CLockSelection,I2C4Freq_Value,LPTIM1Freq_Value,LPTIM2Freq_Value,LPTIM345Freq_Value,LPUART1Freq_Value,LTDCFreq_Value,MCO1PinFreq_Value,MCO2PinFreq_Value,PLL2_VCI_Range-AdvancedSettings,PLL3FRACN,PLLFRACN,PLLSourceVirtual,PWR_Regulator_Voltage_Scale,QSPIFreq_Value,RNGFreq_Value,RTCFreq_Value,SAI1Freq_Value,SAI23Freq_Value,SAI4AFreq_Value,SAI4BFreq_Value,SDMMCFreq_Value,SPDIFRXFreq_Value,SPI123Freq_Value,SPI45Freq_Value,SPI6Freq_Value,SWPMI1Freq_Value,SYSCLKFreq_VALUE,SYSCLKSource,Tim1OutputFreq_Value,Tim2OutputFreq_Value,TraceFreq_Value,USART16Freq_Value,USART234578Freq_Value,USBCLockSelection,USBFreq_Value,VCO1OutputFreq_Value,VCO2OutputFreq_Value,VCO3OutputFreq_Value,VCOInput1Freq_Value,VCOInput2Freq_Value,VCOInput3Freq_Value RCC.LPTIM1Freq_Value=100000000 RCC.LPTIM2Freq_Value=100000000 RCC.LPTIM345Freq_Value=100000000 @@ -563,13 +562,13 @@ RCC.PWR_Regulator_Voltage_Scale=PWR_REGULATOR_VOLTAGE_SCALE1 RCC.QSPIFreq_Value=200000000 RCC.RNGFreq_Value=48000000 RCC.RTCFreq_Value=32000 -RCC.SAI1Freq_Value=100000000 -RCC.SAI23Freq_Value=100000000 -RCC.SAI4AFreq_Value=100000000 -RCC.SAI4BFreq_Value=100000000 -RCC.SDMMCFreq_Value=100000000 -RCC.SPDIFRXFreq_Value=100000000 -RCC.SPI123Freq_Value=100000000 +RCC.SAI1Freq_Value=80000000 +RCC.SAI23Freq_Value=80000000 +RCC.SAI4AFreq_Value=80000000 +RCC.SAI4BFreq_Value=80000000 +RCC.SDMMCFreq_Value=80000000 +RCC.SPDIFRXFreq_Value=80000000 +RCC.SPI123Freq_Value=80000000 RCC.SPI45Freq_Value=100000000 RCC.SPI6Freq_Value=100000000 RCC.SWPMI1Freq_Value=100000000 @@ -594,12 +593,12 @@ SH.ADCx_INP4.0=ADC1_INP4,IN4-Single-Ended SH.ADCx_INP4.ConfNb=1 SH.S_TIM1_CH1.0=TIM1_CH1,Input_Capture1_from_TI1 SH.S_TIM1_CH1.ConfNb=1 -SPI1.CalculateBaudRate=50.0 MBits/s +SPI1.CalculateBaudRate=40.0 MBits/s SPI1.Direction=SPI_DIRECTION_2LINES SPI1.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate SPI1.Mode=SPI_MODE_MASTER SPI1.VirtualType=VM_MASTER -SPI2.CalculateBaudRate=50.0 MBits/s +SPI2.CalculateBaudRate=40.0 MBits/s SPI2.Direction=SPI_DIRECTION_2LINES SPI2.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate SPI2.Mode=SPI_MODE_MASTER diff --git a/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/H7-25MHz/H7-25MHz.ioc b/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/H7-25MHz/H7-25MHz.ioc index 7121819484a..f324f458d9f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/H7-25MHz/H7-25MHz.ioc +++ b/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/H7-25MHz/H7-25MHz.ioc @@ -510,7 +510,7 @@ RCC.D1PPRE=RCC_APB3_DIV2 RCC.D2PPRE1=RCC_APB1_DIV2 RCC.D2PPRE2=RCC_APB2_DIV2 RCC.D3PPRE=RCC_APB4_DIV2 -RCC.DFSDMACLkFreq_Value=100000000 +RCC.DFSDMACLkFreq_Value=80000000 RCC.DFSDMFreq_Value=100000000 RCC.DIVM1=2 RCC.DIVM2=5 @@ -522,8 +522,8 @@ RCC.DIVP1Freq_Value=400000000 RCC.DIVP2Freq_Value=180000000 RCC.DIVP3=3 RCC.DIVP3Freq_Value=80000000 -RCC.DIVQ1=8 -RCC.DIVQ1Freq_Value=100000000 +RCC.DIVQ1=10 +RCC.DIVQ1Freq_Value=80000000 RCC.DIVQ2=5 RCC.DIVQ2Freq_Value=72000000 RCC.DIVQ3=5 @@ -533,8 +533,7 @@ RCC.DIVR2=1 RCC.DIVR2Freq_Value=360000000 RCC.DIVR3=8 RCC.DIVR3Freq_Value=30000000 -RCC.FDCANCLockSelection=RCC_FDCANCLKSOURCE_PLL2 -RCC.FDCANFreq_Value=72000000 +RCC.FDCANFreq_Value=80000000 RCC.FMCFreq_Value=200000000 RCC.FamilyName=M RCC.HCLK3ClockFreq_Value=200000000 @@ -547,7 +546,7 @@ RCC.I2C123CLockSelection=RCC_I2C123CLKSOURCE_PLL3 RCC.I2C123Freq_Value=30000000 RCC.I2C4CLockSelection=RCC_I2C4CLKSOURCE_PLL3 RCC.I2C4Freq_Value=30000000 -RCC.IPParameters=ADCCLockSelection,ADCFreq_Value,AHB12Freq_Value,AHB4Freq_Value,APB1Freq_Value,APB2Freq_Value,APB3Freq_Value,APB4Freq_Value,AXIClockFreq_Value,CECFreq_Value,CKPERFreq_Value,CPU2Freq_Value,CPU2SystikFreq_Value,CortexFreq_Value,CpuClockFreq_Value,D1CPREFreq_Value,D1PPRE,D2PPRE1,D2PPRE2,D3PPRE,DFSDMACLkFreq_Value,DFSDMFreq_Value,DIVM1,DIVM2,DIVM3,DIVN1,DIVN2,DIVN3,DIVP1Freq_Value,DIVP2Freq_Value,DIVP3,DIVP3Freq_Value,DIVQ1,DIVQ1Freq_Value,DIVQ2,DIVQ2Freq_Value,DIVQ3,DIVQ3Freq_Value,DIVR1Freq_Value,DIVR2,DIVR2Freq_Value,DIVR3,DIVR3Freq_Value,FDCANCLockSelection,FDCANFreq_Value,FMCFreq_Value,FamilyName,HCLK3ClockFreq_Value,HCLKFreq_Value,HPRE,HRTIMFreq_Value,HSE_VALUE,HSIDiv,I2C123CLockSelection,I2C123Freq_Value,I2C4CLockSelection,I2C4Freq_Value,LPTIM1Freq_Value,LPTIM2Freq_Value,LPTIM345Freq_Value,LPUART1Freq_Value,LTDCFreq_Value,MCO1PinFreq_Value,MCO2PinFreq_Value,PLL2_VCI_Range-AdvancedSettings,PLL3FRACN,PLLFRACN,PLLSourceVirtual,PWR_Regulator_Voltage_Scale,QSPIFreq_Value,RNGFreq_Value,RTCFreq_Value,SAI1Freq_Value,SAI23Freq_Value,SAI4AFreq_Value,SAI4BFreq_Value,SDMMCFreq_Value,SPDIFRXFreq_Value,SPI123Freq_Value,SPI45Freq_Value,SPI6Freq_Value,SWPMI1Freq_Value,SYSCLKFreq_VALUE,SYSCLKSource,Tim1OutputFreq_Value,Tim2OutputFreq_Value,TraceFreq_Value,USART16Freq_Value,USART234578Freq_Value,USBCLockSelection,USBFreq_Value,VCO1OutputFreq_Value,VCO2OutputFreq_Value,VCO3OutputFreq_Value,VCOInput1Freq_Value,VCOInput2Freq_Value,VCOInput3Freq_Value +RCC.IPParameters=ADCCLockSelection,ADCFreq_Value,AHB12Freq_Value,AHB4Freq_Value,APB1Freq_Value,APB2Freq_Value,APB3Freq_Value,APB4Freq_Value,AXIClockFreq_Value,CECFreq_Value,CKPERFreq_Value,CPU2Freq_Value,CPU2SystikFreq_Value,CortexFreq_Value,CpuClockFreq_Value,D1CPREFreq_Value,D1PPRE,D2PPRE1,D2PPRE2,D3PPRE,DFSDMACLkFreq_Value,DFSDMFreq_Value,DIVM1,DIVM2,DIVM3,DIVN1,DIVN2,DIVN3,DIVP1Freq_Value,DIVP2Freq_Value,DIVP3,DIVP3Freq_Value,DIVQ1,DIVQ1Freq_Value,DIVQ2,DIVQ2Freq_Value,DIVQ3,DIVQ3Freq_Value,DIVR1Freq_Value,DIVR2,DIVR2Freq_Value,DIVR3,DIVR3Freq_Value,FDCANFreq_Value,FMCFreq_Value,FamilyName,HCLK3ClockFreq_Value,HCLKFreq_Value,HPRE,HRTIMFreq_Value,HSE_VALUE,HSIDiv,I2C123CLockSelection,I2C123Freq_Value,I2C4CLockSelection,I2C4Freq_Value,LPTIM1Freq_Value,LPTIM2Freq_Value,LPTIM345Freq_Value,LPUART1Freq_Value,LTDCFreq_Value,MCO1PinFreq_Value,MCO2PinFreq_Value,PLL2_VCI_Range-AdvancedSettings,PLL3FRACN,PLLFRACN,PLLSourceVirtual,PWR_Regulator_Voltage_Scale,QSPIFreq_Value,RNGFreq_Value,RTCFreq_Value,SAI1Freq_Value,SAI23Freq_Value,SAI4AFreq_Value,SAI4BFreq_Value,SDMMCFreq_Value,SPDIFRXFreq_Value,SPI123Freq_Value,SPI45Freq_Value,SPI6Freq_Value,SWPMI1Freq_Value,SYSCLKFreq_VALUE,SYSCLKSource,Tim1OutputFreq_Value,Tim2OutputFreq_Value,TraceFreq_Value,USART16Freq_Value,USART234578Freq_Value,USBCLockSelection,USBFreq_Value,VCO1OutputFreq_Value,VCO2OutputFreq_Value,VCO3OutputFreq_Value,VCOInput1Freq_Value,VCOInput2Freq_Value,VCOInput3Freq_Value RCC.LPTIM1Freq_Value=100000000 RCC.LPTIM2Freq_Value=100000000 RCC.LPTIM345Freq_Value=100000000 @@ -563,13 +562,13 @@ RCC.PWR_Regulator_Voltage_Scale=PWR_REGULATOR_VOLTAGE_SCALE1 RCC.QSPIFreq_Value=200000000 RCC.RNGFreq_Value=48000000 RCC.RTCFreq_Value=32000 -RCC.SAI1Freq_Value=100000000 -RCC.SAI23Freq_Value=100000000 -RCC.SAI4AFreq_Value=100000000 -RCC.SAI4BFreq_Value=100000000 -RCC.SDMMCFreq_Value=100000000 -RCC.SPDIFRXFreq_Value=100000000 -RCC.SPI123Freq_Value=100000000 +RCC.SAI1Freq_Value=80000000 +RCC.SAI23Freq_Value=80000000 +RCC.SAI4AFreq_Value=80000000 +RCC.SAI4BFreq_Value=80000000 +RCC.SDMMCFreq_Value=80000000 +RCC.SPDIFRXFreq_Value=80000000 +RCC.SPI123Freq_Value=80000000 RCC.SPI45Freq_Value=100000000 RCC.SPI6Freq_Value=100000000 RCC.SWPMI1Freq_Value=100000000 @@ -594,12 +593,12 @@ SH.ADCx_INP4.0=ADC1_INP4,IN4-Single-Ended SH.ADCx_INP4.ConfNb=1 SH.S_TIM1_CH1.0=TIM1_CH1,Input_Capture1_from_TI1 SH.S_TIM1_CH1.ConfNb=1 -SPI1.CalculateBaudRate=50.0 MBits/s +SPI1.CalculateBaudRate=40.0 MBits/s SPI1.Direction=SPI_DIRECTION_2LINES SPI1.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate SPI1.Mode=SPI_MODE_MASTER SPI1.VirtualType=VM_MASTER -SPI2.CalculateBaudRate=50.0 MBits/s +SPI2.CalculateBaudRate=40.0 MBits/s SPI2.Direction=SPI_DIRECTION_2LINES SPI2.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate SPI2.Mode=SPI_MODE_MASTER diff --git a/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/H7-8MHz/H7-8MHz.ioc b/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/H7-8MHz/H7-8MHz.ioc index 5a67f5bc5b1..862b90d42d7 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/H7-8MHz/H7-8MHz.ioc +++ b/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/H7-8MHz/H7-8MHz.ioc @@ -510,7 +510,7 @@ RCC.D1PPRE=RCC_APB3_DIV2 RCC.D2PPRE1=RCC_APB1_DIV2 RCC.D2PPRE2=RCC_APB2_DIV2 RCC.D3PPRE=RCC_APB4_DIV2 -RCC.DFSDMACLkFreq_Value=100000000 +RCC.DFSDMACLkFreq_Value=80000000 RCC.DFSDMFreq_Value=100000000 RCC.DIVM1=1 RCC.DIVM2=1 @@ -522,8 +522,8 @@ RCC.DIVP1Freq_Value=400000000 RCC.DIVP2Freq_Value=180000000 RCC.DIVP3=3 RCC.DIVP3Freq_Value=96000000 -RCC.DIVQ1=8 -RCC.DIVQ1Freq_Value=100000000 +RCC.DIVQ1=10 +RCC.DIVQ1Freq_Value=80000000 RCC.DIVQ2=5 RCC.DIVQ2Freq_Value=72000000 RCC.DIVQ3=6 @@ -533,8 +533,7 @@ RCC.DIVR2=1 RCC.DIVR2Freq_Value=360000000 RCC.DIVR3=9 RCC.DIVR3Freq_Value=32000000 -RCC.FDCANCLockSelection=RCC_FDCANCLKSOURCE_PLL2 -RCC.FDCANFreq_Value=72000000 +RCC.FDCANFreq_Value=80000000 RCC.FMCFreq_Value=200000000 RCC.FamilyName=M RCC.HCLK3ClockFreq_Value=200000000 @@ -547,7 +546,7 @@ RCC.I2C123CLockSelection=RCC_I2C123CLKSOURCE_PLL3 RCC.I2C123Freq_Value=32000000 RCC.I2C4CLockSelection=RCC_I2C4CLKSOURCE_PLL3 RCC.I2C4Freq_Value=32000000 -RCC.IPParameters=ADCCLockSelection,ADCFreq_Value,AHB12Freq_Value,AHB4Freq_Value,APB1Freq_Value,APB2Freq_Value,APB3Freq_Value,APB4Freq_Value,AXIClockFreq_Value,CECFreq_Value,CKPERFreq_Value,CPU2Freq_Value,CPU2SystikFreq_Value,CortexFreq_Value,CpuClockFreq_Value,D1CPREFreq_Value,D1PPRE,D2PPRE1,D2PPRE2,D3PPRE,DFSDMACLkFreq_Value,DFSDMFreq_Value,DIVM1,DIVM2,DIVM3,DIVN1,DIVN2,DIVN3,DIVP1Freq_Value,DIVP2Freq_Value,DIVP3,DIVP3Freq_Value,DIVQ1,DIVQ1Freq_Value,DIVQ2,DIVQ2Freq_Value,DIVQ3,DIVQ3Freq_Value,DIVR1Freq_Value,DIVR2,DIVR2Freq_Value,DIVR3,DIVR3Freq_Value,FDCANCLockSelection,FDCANFreq_Value,FMCFreq_Value,FamilyName,HCLK3ClockFreq_Value,HCLKFreq_Value,HPRE,HRTIMFreq_Value,HSE_VALUE,HSIDiv,I2C123CLockSelection,I2C123Freq_Value,I2C4CLockSelection,I2C4Freq_Value,LPTIM1Freq_Value,LPTIM2Freq_Value,LPTIM345Freq_Value,LPUART1Freq_Value,LTDCFreq_Value,MCO1PinFreq_Value,MCO2PinFreq_Value,PLL2_VCI_Range-AdvancedSettings,PLL3FRACN,PLLFRACN,PLLSourceVirtual,PWR_Regulator_Voltage_Scale,QSPIFreq_Value,RNGFreq_Value,RTCFreq_Value,SAI1Freq_Value,SAI23Freq_Value,SAI4AFreq_Value,SAI4BFreq_Value,SDMMCFreq_Value,SPDIFRXFreq_Value,SPI123Freq_Value,SPI45Freq_Value,SPI6Freq_Value,SWPMI1Freq_Value,SYSCLKFreq_VALUE,SYSCLKSource,Tim1OutputFreq_Value,Tim2OutputFreq_Value,TraceFreq_Value,USART16Freq_Value,USART234578Freq_Value,USBCLockSelection,USBFreq_Value,VCO1OutputFreq_Value,VCO2OutputFreq_Value,VCO3OutputFreq_Value,VCOInput1Freq_Value,VCOInput2Freq_Value,VCOInput3Freq_Value +RCC.IPParameters=ADCCLockSelection,ADCFreq_Value,AHB12Freq_Value,AHB4Freq_Value,APB1Freq_Value,APB2Freq_Value,APB3Freq_Value,APB4Freq_Value,AXIClockFreq_Value,CECFreq_Value,CKPERFreq_Value,CPU2Freq_Value,CPU2SystikFreq_Value,CortexFreq_Value,CpuClockFreq_Value,D1CPREFreq_Value,D1PPRE,D2PPRE1,D2PPRE2,D3PPRE,DFSDMACLkFreq_Value,DFSDMFreq_Value,DIVM1,DIVM2,DIVM3,DIVN1,DIVN2,DIVN3,DIVP1Freq_Value,DIVP2Freq_Value,DIVP3,DIVP3Freq_Value,DIVQ1,DIVQ1Freq_Value,DIVQ2,DIVQ2Freq_Value,DIVQ3,DIVQ3Freq_Value,DIVR1Freq_Value,DIVR2,DIVR2Freq_Value,DIVR3,DIVR3Freq_Value,FDCANFreq_Value,FMCFreq_Value,FamilyName,HCLK3ClockFreq_Value,HCLKFreq_Value,HPRE,HRTIMFreq_Value,HSE_VALUE,HSIDiv,I2C123CLockSelection,I2C123Freq_Value,I2C4CLockSelection,I2C4Freq_Value,LPTIM1Freq_Value,LPTIM2Freq_Value,LPTIM345Freq_Value,LPUART1Freq_Value,LTDCFreq_Value,MCO1PinFreq_Value,MCO2PinFreq_Value,PLL2_VCI_Range-AdvancedSettings,PLL3FRACN,PLLFRACN,PLLSourceVirtual,PWR_Regulator_Voltage_Scale,QSPIFreq_Value,RNGFreq_Value,RTCFreq_Value,SAI1Freq_Value,SAI23Freq_Value,SAI4AFreq_Value,SAI4BFreq_Value,SDMMCFreq_Value,SPDIFRXFreq_Value,SPI123Freq_Value,SPI45Freq_Value,SPI6Freq_Value,SWPMI1Freq_Value,SYSCLKFreq_VALUE,SYSCLKSource,Tim1OutputFreq_Value,Tim2OutputFreq_Value,TraceFreq_Value,USART16Freq_Value,USART234578Freq_Value,USBCLockSelection,USBFreq_Value,VCO1OutputFreq_Value,VCO2OutputFreq_Value,VCO3OutputFreq_Value,VCOInput1Freq_Value,VCOInput2Freq_Value,VCOInput3Freq_Value RCC.LPTIM1Freq_Value=100000000 RCC.LPTIM2Freq_Value=100000000 RCC.LPTIM345Freq_Value=100000000 @@ -563,13 +562,13 @@ RCC.PWR_Regulator_Voltage_Scale=PWR_REGULATOR_VOLTAGE_SCALE1 RCC.QSPIFreq_Value=200000000 RCC.RNGFreq_Value=48000000 RCC.RTCFreq_Value=32000 -RCC.SAI1Freq_Value=100000000 -RCC.SAI23Freq_Value=100000000 -RCC.SAI4AFreq_Value=100000000 -RCC.SAI4BFreq_Value=100000000 -RCC.SDMMCFreq_Value=100000000 -RCC.SPDIFRXFreq_Value=100000000 -RCC.SPI123Freq_Value=100000000 +RCC.SAI1Freq_Value=80000000 +RCC.SAI23Freq_Value=80000000 +RCC.SAI4AFreq_Value=80000000 +RCC.SAI4BFreq_Value=80000000 +RCC.SDMMCFreq_Value=80000000 +RCC.SPDIFRXFreq_Value=80000000 +RCC.SPI123Freq_Value=80000000 RCC.SPI45Freq_Value=100000000 RCC.SPI6Freq_Value=100000000 RCC.SWPMI1Freq_Value=100000000 @@ -594,12 +593,12 @@ SH.ADCx_INP4.0=ADC1_INP4,IN4-Single-Ended SH.ADCx_INP4.ConfNb=1 SH.S_TIM1_CH1.0=TIM1_CH1,Input_Capture1_from_TI1 SH.S_TIM1_CH1.ConfNb=1 -SPI1.CalculateBaudRate=50.0 MBits/s +SPI1.CalculateBaudRate=40.0 MBits/s SPI1.Direction=SPI_DIRECTION_2LINES SPI1.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate SPI1.Mode=SPI_MODE_MASTER SPI1.VirtualType=VM_MASTER -SPI2.CalculateBaudRate=50.0 MBits/s +SPI2.CalculateBaudRate=40.0 MBits/s SPI2.Direction=SPI_DIRECTION_2LINES SPI2.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate SPI2.Mode=SPI_MODE_MASTER diff --git a/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/H7-no-xtal/H7-no-xtal.ioc b/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/H7-no-xtal/H7-no-xtal.ioc index 1d72c3411e8..21bd5497de5 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/H7-no-xtal/H7-no-xtal.ioc +++ b/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/H7-no-xtal/H7-no-xtal.ioc @@ -507,7 +507,7 @@ RCC.D1PPRE=RCC_APB3_DIV2 RCC.D2PPRE1=RCC_APB1_DIV2 RCC.D2PPRE2=RCC_APB2_DIV2 RCC.D3PPRE=RCC_APB4_DIV2 -RCC.DFSDMACLkFreq_Value=100000000 +RCC.DFSDMACLkFreq_Value=80000000 RCC.DFSDMFreq_Value=100000000 RCC.DIVM1=4 RCC.DIVM2=8 @@ -519,8 +519,8 @@ RCC.DIVP1Freq_Value=400000000 RCC.DIVP2Freq_Value=180000000 RCC.DIVP3=3 RCC.DIVP3Freq_Value=80000000 -RCC.DIVQ1=8 -RCC.DIVQ1Freq_Value=100000000 +RCC.DIVQ1=10 +RCC.DIVQ1Freq_Value=80000000 RCC.DIVQ2=5 RCC.DIVQ2Freq_Value=72000000 RCC.DIVQ3=5 @@ -530,8 +530,7 @@ RCC.DIVR2=1 RCC.DIVR2Freq_Value=360000000 RCC.DIVR3=8 RCC.DIVR3Freq_Value=30000000 -RCC.FDCANCLockSelection=RCC_FDCANCLKSOURCE_PLL2 -RCC.FDCANFreq_Value=72000000 +RCC.FDCANFreq_Value=80000000 RCC.FMCFreq_Value=200000000 RCC.FamilyName=M RCC.HCLK3ClockFreq_Value=200000000 @@ -543,7 +542,7 @@ RCC.I2C123CLockSelection=RCC_I2C123CLKSOURCE_PLL3 RCC.I2C123Freq_Value=30000000 RCC.I2C4CLockSelection=RCC_I2C4CLKSOURCE_PLL3 RCC.I2C4Freq_Value=30000000 -RCC.IPParameters=ADCCLockSelection,ADCFreq_Value,AHB12Freq_Value,AHB4Freq_Value,APB1Freq_Value,APB2Freq_Value,APB3Freq_Value,APB4Freq_Value,AXIClockFreq_Value,CECFreq_Value,CKPERFreq_Value,CPU2Freq_Value,CPU2SystikFreq_Value,CortexFreq_Value,CpuClockFreq_Value,D1CPREFreq_Value,D1PPRE,D2PPRE1,D2PPRE2,D3PPRE,DFSDMACLkFreq_Value,DFSDMFreq_Value,DIVM1,DIVM2,DIVM3,DIVN1,DIVN2,DIVN3,DIVP1Freq_Value,DIVP2Freq_Value,DIVP3,DIVP3Freq_Value,DIVQ1,DIVQ1Freq_Value,DIVQ2,DIVQ2Freq_Value,DIVQ3,DIVQ3Freq_Value,DIVR1Freq_Value,DIVR2,DIVR2Freq_Value,DIVR3,DIVR3Freq_Value,FDCANCLockSelection,FDCANFreq_Value,FMCFreq_Value,FamilyName,HCLK3ClockFreq_Value,HCLKFreq_Value,HPRE,HRTIMFreq_Value,HSE_VALUE,I2C123CLockSelection,I2C123Freq_Value,I2C4CLockSelection,I2C4Freq_Value,LPTIM1Freq_Value,LPTIM2Freq_Value,LPTIM345Freq_Value,LPUART1Freq_Value,LTDCFreq_Value,MCO1PinFreq_Value,MCO2PinFreq_Value,PLL2FRACN,PLL2_VCI_Range-AdvancedSettings,PLL3FRACN,PLLFRACN,PLLSource,PLLSourceVirtual,PWR_Regulator_Voltage_Scale,QSPIFreq_Value,RNGFreq_Value,RTCFreq_Value,SAI1Freq_Value,SAI23Freq_Value,SAI4AFreq_Value,SAI4BFreq_Value,SDMMCFreq_Value,SPDIFRXFreq_Value,SPI123Freq_Value,SPI45Freq_Value,SPI6Freq_Value,SWPMI1Freq_Value,SYSCLKFreq_VALUE,SYSCLKSource,Tim1OutputFreq_Value,Tim2OutputFreq_Value,TraceFreq_Value,USART16Freq_Value,USART234578Freq_Value,USBCLockSelection,USBFreq_Value,VCO1OutputFreq_Value,VCO2OutputFreq_Value,VCO3OutputFreq_Value,VCOInput1Freq_Value,VCOInput2Freq_Value,VCOInput3Freq_Value +RCC.IPParameters=ADCCLockSelection,ADCFreq_Value,AHB12Freq_Value,AHB4Freq_Value,APB1Freq_Value,APB2Freq_Value,APB3Freq_Value,APB4Freq_Value,AXIClockFreq_Value,CECFreq_Value,CKPERFreq_Value,CPU2Freq_Value,CPU2SystikFreq_Value,CortexFreq_Value,CpuClockFreq_Value,D1CPREFreq_Value,D1PPRE,D2PPRE1,D2PPRE2,D3PPRE,DFSDMACLkFreq_Value,DFSDMFreq_Value,DIVM1,DIVM2,DIVM3,DIVN1,DIVN2,DIVN3,DIVP1Freq_Value,DIVP2Freq_Value,DIVP3,DIVP3Freq_Value,DIVQ1,DIVQ1Freq_Value,DIVQ2,DIVQ2Freq_Value,DIVQ3,DIVQ3Freq_Value,DIVR1Freq_Value,DIVR2,DIVR2Freq_Value,DIVR3,DIVR3Freq_Value,FDCANFreq_Value,FMCFreq_Value,FamilyName,HCLK3ClockFreq_Value,HCLKFreq_Value,HPRE,HRTIMFreq_Value,HSE_VALUE,I2C123CLockSelection,I2C123Freq_Value,I2C4CLockSelection,I2C4Freq_Value,LPTIM1Freq_Value,LPTIM2Freq_Value,LPTIM345Freq_Value,LPUART1Freq_Value,LTDCFreq_Value,MCO1PinFreq_Value,MCO2PinFreq_Value,PLL2FRACN,PLL2_VCI_Range-AdvancedSettings,PLL3FRACN,PLLFRACN,PLLSource,PLLSourceVirtual,PWR_Regulator_Voltage_Scale,QSPIFreq_Value,RNGFreq_Value,RTCFreq_Value,SAI1Freq_Value,SAI23Freq_Value,SAI4AFreq_Value,SAI4BFreq_Value,SDMMCFreq_Value,SPDIFRXFreq_Value,SPI123Freq_Value,SPI45Freq_Value,SPI6Freq_Value,SWPMI1Freq_Value,SYSCLKFreq_VALUE,SYSCLKSource,Tim1OutputFreq_Value,Tim2OutputFreq_Value,TraceFreq_Value,USART16Freq_Value,USART234578Freq_Value,USBCLockSelection,USBFreq_Value,VCO1OutputFreq_Value,VCO2OutputFreq_Value,VCO3OutputFreq_Value,VCOInput1Freq_Value,VCOInput2Freq_Value,VCOInput3Freq_Value RCC.LPTIM1Freq_Value=100000000 RCC.LPTIM2Freq_Value=100000000 RCC.LPTIM345Freq_Value=100000000 @@ -561,13 +560,13 @@ RCC.PWR_Regulator_Voltage_Scale=PWR_REGULATOR_VOLTAGE_SCALE1 RCC.QSPIFreq_Value=200000000 RCC.RNGFreq_Value=48000000 RCC.RTCFreq_Value=32000 -RCC.SAI1Freq_Value=100000000 -RCC.SAI23Freq_Value=100000000 -RCC.SAI4AFreq_Value=100000000 -RCC.SAI4BFreq_Value=100000000 -RCC.SDMMCFreq_Value=100000000 -RCC.SPDIFRXFreq_Value=100000000 -RCC.SPI123Freq_Value=100000000 +RCC.SAI1Freq_Value=80000000 +RCC.SAI23Freq_Value=80000000 +RCC.SAI4AFreq_Value=80000000 +RCC.SAI4BFreq_Value=80000000 +RCC.SDMMCFreq_Value=80000000 +RCC.SPDIFRXFreq_Value=80000000 +RCC.SPI123Freq_Value=80000000 RCC.SPI45Freq_Value=100000000 RCC.SPI6Freq_Value=100000000 RCC.SWPMI1Freq_Value=100000000 @@ -593,13 +592,13 @@ SH.ADCx_INP4.ConfNb=1 SH.S_TIM1_CH1.0=TIM1_CH1,Input_Capture1_from_TI1 SH.S_TIM1_CH1.ConfNb=1 SPI1.BaudRatePrescaler=SPI_BAUDRATEPRESCALER_2 -SPI1.CalculateBaudRate=50.0 MBits/s +SPI1.CalculateBaudRate=40.0 MBits/s SPI1.Direction=SPI_DIRECTION_2LINES SPI1.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate,BaudRatePrescaler SPI1.Mode=SPI_MODE_MASTER SPI1.VirtualType=VM_MASTER SPI2.BaudRatePrescaler=SPI_BAUDRATEPRESCALER_2 -SPI2.CalculateBaudRate=50.0 MBits/s +SPI2.CalculateBaudRate=40.0 MBits/s SPI2.Direction=SPI_DIRECTION_2LINES SPI2.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate,BaudRatePrescaler SPI2.Mode=SPI_MODE_MASTER diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F405/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F405/hwdef.dat index 7a22fbd3bf4..310789d9c30 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F405/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F405/hwdef.dat @@ -7,8 +7,8 @@ MCU STM32F4xx STM32F405xx FLASH_RESERVE_START_KB 64 FLASH_SIZE_KB 1024 -# store parameters in pages 11 and 12 -STORAGE_FLASH_PAGE 1 +# store parameters in pages 2 and 3 +STORAGE_FLASH_PAGE 2 define HAL_STORAGE_SIZE 15360 # board ID for firmware load @@ -20,6 +20,7 @@ define STM32_ST_USE_TIMER 5 define CH_CFG_ST_RESOLUTION 32 # enable watchdog +define HAL_WATCHDOG_ENABLED_DEFAULT true # crystal frequency OSCILLATOR_HZ 16000000 @@ -33,14 +34,12 @@ define HAL_NO_GPIO_IRQ define HAL_NO_RCIN_THREAD define HAL_USE_RTC FALSE -define NO_DATAFLASH TRUE define DMA_RESERVE_SIZE 0 define HAL_DISABLE_LOOP_DELAY define HAL_NO_MONITOR_THREAD define HAL_NO_LOGGING -define HAL_MINIMIZE_FEATURES 0 define DISABLE_SERIAL_ESC_COMM TRUE define HAL_DEVICE_THREAD_STACK 768 @@ -101,6 +100,7 @@ define HAL_PERIPH_ENABLE_MAG SPIDEV rm3100 SPI1 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ COMPASS RM3100 SPI:rm3100 false ROTATION_PITCH_180 +define AP_RM3100_REVERSAL_MASK 7 define HAL_COMPASS_MAX_SENSORS 1 # --------------------- DPS310 --------------------------- @@ -128,4 +128,3 @@ PC7 M9SB INPUT # allow for reboot command for faster development define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0 - diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F412/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F412/hwdef-bl.dat index 609fc8440c4..d5553d7573e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F412/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F412/hwdef-bl.dat @@ -24,7 +24,6 @@ define CH_CFG_ST_FREQUENCY 1000000 FLASH_SIZE_KB 1024 define HAL_STORAGE_SIZE 16384 -define STORAGE_FLASH_PAGE 1 # Enable the sensor voltage pin PC13 VDD_3V3_SENSORS_EN OUTPUT HIGH diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F412/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F412/hwdef.dat index 040ab4caac2..94d8009d974 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F412/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F412/hwdef.dat @@ -69,6 +69,7 @@ BARO DPS310 SPI:dps310 # Mag probe SPIDEV rm3100 SPI1 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ COMPASS RM3100 SPI:rm3100 false ROTATION_PITCH_180 +define AP_RM3100_REVERSAL_MASK 7 # PWM, WS2812 LED PB8 TIM4_CH3 TIM4 PWM(1) GPIO(50) @@ -100,7 +101,6 @@ define HAL_CAN_DEFAULT_NODE_ID 0 define CAN_APP_NODE_NAME "org.ardupilot.Sierra-F412" define HAL_NO_MONITOR_THREAD -define HAL_MINIMIZE_FEATURES 0 define HAL_BUILD_AP_PERIPH define HAL_DEVICE_THREAD_STACK 768 @@ -117,9 +117,6 @@ define HAL_PERIPH_ENABLE_BARO define HAL_PERIPH_ENABLE_RC_OUT define HAL_PERIPH_ENABLE_NOTIFY -# use the app descriptor needed by MissionPlanner for CAN upload -env APP_DESCRIPTOR MissionPlanner - # reserve 256 bytes for comms between app and bootloader RAM_RESERVE_START 256 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F9P/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F9P/hwdef-bl.dat new file mode 100644 index 00000000000..84bc95a9d63 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F9P/hwdef-bl.dat @@ -0,0 +1,79 @@ +# hw definition file for processing by chibios_pins.py + +# Sierra-F9P bootloader + +# MCU class and specific type +MCU STM32F4xx STM32F412Rx + +FLASH_RESERVE_START_KB 0 +# two sectors for bootloader, two for storage +FLASH_BOOTLOADER_LOAD_KB 64 + +# board ID for firmware load +APJ_BOARD_ID 1034 + +# setup build for a peripheral firmware +env AP_PERIPH 1 + +# crystal frequency +OSCILLATOR_HZ 16000000 + +define CH_CFG_ST_FREQUENCY 1000000 + +# Available Flash +FLASH_SIZE_KB 1024 + +define HAL_STORAGE_SIZE 16384 + +STDOUT_SERIAL SD1 +STDOUT_BAUDRATE 57600 + +# order of UARTs +SERIAL_ORDER + +# USART1 +PA9 USART1_TX USART1 +PA10 USART1_RX USART1 + +# USART2 +PA2 USART2_TX USART2 +PA3 USART2_RX USART2 + +# SWD debugging +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD +define HAL_USE_SERIAL TRUE + +define STM32_SERIAL_USE_USART1 TRUE +define STM32_SERIAL_USE_USART2 TRUE +define STM32_SERIAL_USE_USART3 FALSE + +define HAL_NO_GPIO_IRQ +define HAL_USE_EMPTY_IO TRUE + +define DMA_RESERVE_SIZE 0 + +define HAL_DISABLE_LOOP_DELAY + +# enable CAN support +PB8 CAN1_RX CAN1 +PB9 CAN1_TX CAN1 +PC1 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW +define HAL_USE_CAN TRUE +define STM32_CAN_USE_CAN1 TRUE + +define CAN_APP_NODE_NAME "org.ardupilot.Sierra-F9P" + +# make bl baudrate match debug baudrate for easier debugging +define BOOTLOADER_BAUDRATE 57600 + +# use a small bootloader timeout +define HAL_BOOTLOADER_TIMEOUT 1000 + +# Add CS pins to ensure they are high in bootloader +#PC6 ICM_CS CS +PC12 BARO_CS CS + +#Sensors Enable & ESP Enable +PB0 VDD_3V3_SENSORS_EN OUTPUT HIGH +PC2 ESP_PWR_EN OUTPUT LOW diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F9P/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F9P/hwdef.dat new file mode 100644 index 00000000000..9523eb78a6e --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F9P/hwdef.dat @@ -0,0 +1,158 @@ +# hw definition file for processing by chibios_pins.py + +# Sierra-F9P Firmware + +# MCU class and specific type +MCU STM32F4xx STM32F412Rx + +# bootloader starts firmware at 64k +FLASH_RESERVE_START_KB 64 + +# store parameters in pages 2 and 3 +STORAGE_FLASH_PAGE 2 +define HAL_STORAGE_SIZE 8192 + +# board ID for firmware load +APJ_BOARD_ID 1034 + +# setup build for a peripheral firmware +env AP_PERIPH 1 +#env AP_PERIPH_HEAVY 1 + +STM32_ST_USE_TIMER 5 + +# enable watchdog +define HAL_WATCHDOG_ENABLED_DEFAULT true + +# crystal frequency +OSCILLATOR_HZ 16000000 + +define CH_CFG_ST_FREQUENCY 1000000 + +# Available Flash +FLASH_SIZE_KB 1024 + +STDOUT_SERIAL SD1 +STDOUT_BAUDRATE 57600 + +# order of UARTs +SERIAL_ORDER USART1 EMPTY EMPTY USART2 + +# USART1 for debug +PA9 USART1_TX USART1 NODMA +PA10 USART1_RX USART1 NODMA +define HAL_SERIAL0_BAUD_DEFAULT 57600 + +# USART2 for GPS +PA2 USART2_TX USART2 SPEED_HIGH +PA3 USART2_RX USART2 SPEED_HIGH + +# SWD debugging +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# only one I2C bus in normal config +PB7 I2C1_SDA I2C1 +PB6 I2C1_SCL I2C1 + +define HAL_USE_I2C TRUE +define STM32_I2C_USE_I2C1 TRUE +define HAL_I2C_CLEAR_ON_TIMEOUT 0 +define HAL_I2C_INTERNAL_MASK 0 + +# only one I2C bus +I2C_ORDER I2C1 + +# only one SPI bus in normal config +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 + +# SPI CS +#PC6 ICM_CS CS +PC12 BARO_CS CS + +# SPI devices +# ToDo SPI devices +#SPIDEV icm20948 SPI1 DEVID1 MPU_CS MODE3 4*MHZ 8*MHZ +SPIDEV dps310 SPI1 DEVID3 BARO_CS MODE3 5*MHZ 5*MHZ + +# Compass +COMPASS QMC5883L I2C:0:0xd false ROTATION_PITCH_180_YAW_90 + +# Baro +BARO DPS310 SPI:dps310 + +# PWM output for buzzer +PB5 TIM3_CH2 TIM3 GPIO(77) LOW ALARM + +# WS2812 LEDs +PA15 TIM2_CH1 TIM2 PWM(1) + +define HAL_USE_ADC TRUE +define STM32_ADC_USE_ADC1 TRUE +#define HAL_DISABLE_ADC_DRIVER TRUE +PA0 VSENSE ADC1 SCALE(2) + +define HAL_NO_GPIO_IRQ + +# avoid RCIN thread to save memory +define HAL_NO_RCIN_THREAD +define HAL_USE_RTC TRUE +define DISABLE_SERIAL_ESC_COMM TRUE +define DMA_RESERVE_SIZE 0 +define HAL_DISABLE_LOOP_DELAY +define PERIPH_FW TRUE + +# enable CAN support +PB8 CAN1_RX CAN1 +PB9 CAN1_TX CAN1 +PC1 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW + +define CAN_APP_NODE_NAME "org.ardupilot.Sierra-F9P" + +define HAL_NO_MONITOR_THREAD +define HAL_BUILD_AP_PERIPH +define HAL_DEVICE_THREAD_STACK 768 + +# we setup a small defaults.parm +define AP_PARAM_MAX_EMBEDDED_PARAM 256 + +# disable dual GPS and GPS blending to save flash space +define GPS_MAX_RECEIVERS 1 +define GPS_MAX_INSTANCES 1 +define HAL_COMPASS_MAX_SENSORS 1 + +# GPS+MAG+BARO+Buzzer+NeoPixels +define HAL_PERIPH_ENABLE_GPS +define HAL_PERIPH_ENABLE_MAG +define HAL_PERIPH_ENABLE_BARO +define HAL_PERIPH_ENABLE_RC_OUT +define HAL_PERIPH_ENABLE_NOTIFY +define CONFIGURE_PPS_PIN TRUE +#define HAL_INS_ENABLED 1 +define GPS_MOVING_BASELINE 1 + +# Logging +define HAL_LOGGING_ENABLED 1 +define HAL_OS_FATFS_IO 1 +define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" +define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" + +# SD Card pins +PC8 SDIO_D0 SDIO +PC9 SDIO_D1 SDIO +PC10 SDIO_D2 SDIO +PC11 SDIO_D3 SDIO +PB15 SDIO_CK SDIO +PD2 SDIO_CMD SDIO + +# reserve 256 bytes for comms between app and bootloader +RAM_RESERVE_START 256 + +# allow for reboot command for faster development +define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0 + +#Sensors Enable & ESP Enable +PB0 VDD_3V3_SENSORS_EN OUTPUT HIGH +PC2 ESP_PWR_EN OUTPUT LOW diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-L431/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-L431/hwdef.dat index 6f941affc5b..1b3f6a787dd 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-L431/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-L431/hwdef.dat @@ -43,9 +43,7 @@ SERIAL_ORDER USART1 PA9 USART1_TX USART1 SPEED_HIGH NODMA PA10 USART1_RX USART1 SPEED_HIGH NODMA -define HAL_USE_SERIAL TRUE -define STM32_SERIAL_USE_USART1 TRUE -define SERIAL_BUFFERS_SIZE 32 +define SERIAL_BUFFERS_SIZE 512 # SPI1 bus for RM3100 PA5 SPI1_SCK SPI1 @@ -55,12 +53,15 @@ PB12 MAG_CS CS # compass SPIDEV rm3100 SPI1 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ -COMPASS RM3100 SPI:rm3100 false ROTATION_PITCH_180 +COMPASS RM3100 SPI:rm3100 false ROTATION_NONE # MS4525DO Airspeed PB6 I2C1_SCL I2C1 PB7 I2C1_SDA I2C1 +define HAL_I2C_CLEAR_ON_TIMEOUT 0 +define HAL_I2C_INTERNAL_MASK 1 + I2C_ORDER I2C1 # allow for reboot command for faster development @@ -71,7 +72,7 @@ PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD define HAL_NO_GPIO_IRQ -define DMA_RESERVE_SIZE 2048 +define DMA_RESERVE_SIZE 0 # stack for fast interrupts define PORT_INT_REQUIRED_STACK 64 @@ -91,12 +92,11 @@ CAN_ORDER 1 define HAL_USE_ADC TRUE define STM32_ADC_USE_ADC1 TRUE -PA0 VSENSE ADC1 SCALE(2) +PA0 VDD_5V_SENS ADC1 SCALE(2) define HAL_GCS_ENABLED 0 define HAL_NO_MONITOR_THREAD define HAL_NO_LOGGING -define HAL_MINIMIZE_FEATURES 0 define AP_PARAM_MAX_EMBEDDED_PARAM 512 define CAN_APP_NODE_NAME "org.ardupilot.Sierra-L431" @@ -105,3 +105,7 @@ define HAL_PERIPH_ENABLE_MAG define HAL_PERIPH_ENABLE_AIRSPEED define AIRSPEED_MAX_SENSORS 1 define HAL_AIRSPEED_TYPE_DEFAULT 1 + +# keep ROMFS uncompressed as we don't have enough RAM +# to uncompress the bootloader at runtime +env ROMFS_UNCOMPRESSED True diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD-bdshot/README.md b/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD-bdshot/README.md new file mode 100644 index 00000000000..19f3e6d33b7 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD-bdshot/README.md @@ -0,0 +1,87 @@ +# Skystars H7 Flight Controller + +The Skystars H7 is a flight controller produced by [Skystars](http://www.skystars-rc.com/). + +## Features + + - STM32H743 microcontroller + - BMI270 IMU x2 + - BMP280 barometer + - AT7456E OSD + - 8 UARTs + - 9 PWM outputs + +## Pinout + +![Skystars H7HD Board](SkystarsH7HD.jpg.jpg "Skystars H7HD") + +## UART Mapping + +The UARTs are marked RX and TX in the above pinouts. The RX pin is the +receive pin for UARTn. The TX pin is the transmit pin for UARTn. + + - SERIAL0 -> USB + - SERIAL1 -> UART1 (RX, DMA-enabled) + - SERIAL2 -> UART2 (DMA-enabled) + - SERIAL3 -> UART3 (ESC Telem) + - SERIAL4 -> UART4 (GPS, DMA-enabled) + - SERIAL5 -> UART5 (VTX) + - SERIAL6 -> UART6 (DJI FPV, DMA-enabled) + - SERIAL7 -> UART7 (DMA-enabled) + - SERIAL8 -> UART8 + +## RC Input + +RC input is configured on the R1 (UART1_RX) pin in the DJI connector or via the R1/T1 (UART1) pads. +It supports all serial RC protocols. For protocols requiring half-duplex serial to transmit +telemetry (such as FPort) you should setup SERIAL1 with half-duplex and connect to T1 or use +R1 with pin-swap. You also need to set inversion enabled if using FPort. + +## OSD Support + +The Skystars H7 supports OSD using OSD_TYPE 1 (MAX7456 driver). + +## PWM Output + +The Skystars H7 supports up to 9 PWM outputs. The pads for motor output +M1 to M8 on the two motor connectors, plus M9 for LED strip or another +PWM output. + +The PWM is in 5 groups: + + - PWM 1, 2 in group1 + - PWM 3, 4 in group2 + - PWM 5-8 in group3 + - PWM 9 in group4 + +Channels within the same group need to use the same output rate. If +any channel in a group uses DShot then all channels in the group need +to use DShot. Outputs 1-8 support bi-directional dshot. + +## Battery Monitoring + +The board has a builtin voltage and current sensor. The current +sensor can read up to 130 Amps. The voltage sensor can handle up to 6S +LiPo batteries. + +The correct battery setting parameters are: + + - BATT_MONITOR 4 + - BATT_VOLT_PIN 10 + - BATT_CURR_PIN 11 + - BATT_VOLT_MULT 10.1 + - BATT_AMP_PERVLT 17.0 + +## Compass + +The Skystars H7 does not have a builtin compass, but you can attach an external compass using I2C on the SDA and SCL pads. + +## Loading Firmware + +Initial firmware load can be done with DFU by plugging in USB with the +bootloader button pressed. Then you should load the "with_bl.hex" +firmware, using your favourite DFU loading tool. + +Once the initial firmware is loaded you can update the firmware using +any ArduPilot ground station software. Updates should be done with the +*.apj firmware files. diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD-bdshot/SkystarsH7HD.jpg b/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD-bdshot/SkystarsH7HD.jpg new file mode 100644 index 00000000000..35e6481b06a Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD-bdshot/SkystarsH7HD.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD-bdshot/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD-bdshot/defaults.parm new file mode 100644 index 00000000000..1812ebbd8e9 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD-bdshot/defaults.parm @@ -0,0 +1,8 @@ +# setup for Neopixel +SERVO9_FUNCTION 120 +NTF_LED_TYPES 257 +NTF_LED_LEN 1 +# Default VTX power to on +RELAY_DEFAULT 1 +SERIAL3_PROTOCOL 16 +RSSI_TYPE 3 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD-bdshot/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD-bdshot/hwdef-bl.dat new file mode 100644 index 00000000000..4fa4f1f622f --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD-bdshot/hwdef-bl.dat @@ -0,0 +1,4 @@ +# hw definition file for processing by chibios_pins.py +# for SkystarsH7HD bootloader + +include ../SkystarsH7HD/hwdef-bl.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD-bdshot/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD-bdshot/hwdef.dat new file mode 100644 index 00000000000..807301c22d9 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD-bdshot/hwdef.dat @@ -0,0 +1,48 @@ +# hw definition file for processing by chibios_pins.py +# for SkystarsH7HD + +include ../SkystarsH7HD/hwdef.dat + +undef PB0 PB1 PD12 PA0 PA2 PC7 PC6 PD8 PD9 PB5 PB6 PE0 PE1 +undef HAL_I2C_INTERNAL_MASK DMA_PRIORITY DMA_NOSHARE +undef HAL_SERIAL6_PROTOCOL HAL_SERIAL6_BAUD + +MCU_CLOCKRATE_MHZ 480 + +DMA_PRIORITY TIM3* TIM4* TIM2* SPI1* SPI3* SPI4* TIM1* +DMA_NOSHARE TIM3* TIM4* TIM2* SPI1* SPI3* + +define HAL_I2C_INTERNAL_MASK 2 +NODMA I2C* +define STM32_I2C_USE_DMA FALSE + +define RELAY2_PIN_DEFAULT 81 # Pit-1 +define RELAY3_PIN_DEFAULT 82 # PIN-EN + +# Motor order Betaflight/X +define HAL_FRAME_TYPE_DEFAULT 12 + +# USART1 (RX) +define HAL_SERIAL1_PROTOCOL SerialProtocol_RCIN +define HAL_SERIAL1_BAUD 115 +# USART3 (ESC Telem) +PD8 USART3_TX USART3 NODMA +PD9 USART3_RX USART3 NODMA +# UART4 (GPS) +# UART5 (VTX) +PB5 UART5_RX UART5 NODMA +PB6 UART5_TX UART5 NODMA +# USART6 (DJI FPV) +define HAL_SERIAL6_PROTOCOL SerialProtocol_DJI_FPV +define HAL_SERIAL6_BAUD 115 +# UART7 +# UART8 +PE0 UART8_RX UART8 NODMA +PE1 UART8_TX UART8 NODMA + +# Motors +PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50) BIDIR +PB1 TIM3_CH4 TIM3 PWM(2) GPIO(51) +PD12 TIM4_CH1 TIM4 PWM(3) GPIO(52) BIDIR +PA0 TIM2_CH1 TIM2 PWM(5) GPIO(54) BIDIR +PA2 TIM2_CH3 TIM2 PWM(7) GPIO(56) BIDIR diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD/README.md b/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD/README.md new file mode 100644 index 00000000000..b9ee4a9db34 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD/README.md @@ -0,0 +1,88 @@ +# Skystars H7 Flight Controller + +The Skystars H7 is a flight controller produced by [Skystars](http://www.skystars-rc.com/). + +## Features + + - STM32H743 microcontroller + - BMI270 IMU + - BMP280 barometer + - AT7456E OSD + - 6 UARTs + - 9 PWM outputs + +## Pinout + +![Skystars H7HD Board](SkystarsH7HD.jpg.jpg "Skystars H7HD") + +## UART Mapping + +The UARTs are marked RX and TX in the above pinouts. The RX pin is the +receive pin for UARTn. The TX pin is the transmit pin for UARTn. + + - SERIAL0 -> USB + - SERIAL1 -> UART1 (Telem1) + - SERIAL2 -> UART2 (Telem2) + - SERIAL3 -> UART3 (GPS) + - SERIAL4 -> UART4 + - SERIAL5 -> not available + - SERIAL6 -> UART6 + - SERIAL7 -> UART7 + +## RC Input + +RC input is configured on the R6 (UART6_RX) pin. It supports all RC +protocols. For protocols requiring half-duplex serial to transmit +telemetry (such as FPort) you should set BRD_ALT_CONFIG=1 and setup +SERIAL6 as an RC input serial port, with half-duplex, pin-swap +and inversion enabled. + + +## OSD Support + +The Skystars H7 supports OSD using OSD_TYPE 1 (MAX7456 driver). + +## PWM Output + +The Skystars H7 supports up to 9 PWM outputs. The pads for motor output +M1 to M8 on the two motor connectors, plus M9 for LED strip or another +PWM output. + +The PWM is in 5 groups: + + - PWM 1, 2 in group1 + - PWM 3, 4 in group2 + - PWM 5, 6 in group3 + - PWM 7, 8 in group4 + - PWM 9 in group5 + +Channels within the same group need to use the same output rate. If +any channel in a group uses DShot then all channels in the group need +to use DShot. + +## Battery Monitoring + +The board has a builtin voltage and current sensor. The current +sensor can read up to 130 Amps. The voltage sensor can handle up to 6S +LiPo batteries. + +The correct battery setting parameters are: + + - BATT_MONITOR 4 + - BATT_VOLT_PIN 10 + - BATT_CURR_PIN 11 + - BATT_VOLT_MULT 10.1 + - BATT_AMP_PERVLT 17.0 + +## Compass + +The Skystars H7 does not have a builtin compass, but you can attach an external compass using I2C on the SDA and SCL pads. +## Loading Firmware + +Initial firmware load can be done with DFU by plugging in USB with the +bootloader button pressed. Then you should load the "with_bl.hex" +firmware, using your favourite DFU loading tool. + +Once the initial firmware is loaded you can update the firmware using +any ArduPilot ground station software. Updates should be done with the +*.apj firmware files. diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD/SkystarsH7HD.jpg b/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD/SkystarsH7HD.jpg new file mode 100644 index 00000000000..35e6481b06a Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD/SkystarsH7HD.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD/defaults.parm new file mode 100644 index 00000000000..835e84805fc --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD/defaults.parm @@ -0,0 +1,16 @@ +# setup for Neopixel +SERVO9_FUNCTION 120 +NTF_LED_TYPES 257 +NTF_LED_LEN 1 + +# set up Sbus-in +SERIAL7_PROTOCOL 23 +SERIAL7_BAUDRATE 115 +SERIAL7_OPTIONS 3 + +# set up ExpressLRS (ELRS) +SERIAL1_PROTOCOL 23 +SERIAL1_BAUDRATE 115 +RSSI_TYPE 3 + + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD/hwdef-bl.dat new file mode 100644 index 00000000000..e51f307f0ea --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD/hwdef-bl.dat @@ -0,0 +1,54 @@ +# hw definition file for processing by chibios_pins.py +# for SkystarsH7HD bootloader + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID 1075 + +# crystal frequency, setup to use external oscillator +OSCILLATOR_HZ 8000000 + +FLASH_SIZE_KB 2048 + +# bootloader starts at zero offset +FLASH_RESERVE_START_KB 0 + +# the location where the bootloader will put the firmware +FLASH_BOOTLOADER_LOAD_KB 128 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 + +# H743 has 16 pages of 128k each +define HAL_STORAGE_SIZE 32768 + +# PA10 IO-debug-console +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +PB3 BUZZER OUTPUT LOW + +PE3 LED_BOOTLOADER OUTPUT HIGH +PE4 LED_ACTIVITY OUTPUT HIGH +define HAL_LED_ON 0 +define HAL_LED_OFF 1 + +# default to all pins low to avoid ESD issues +DEFAULTGPIO OUTPUT LOW PULLDOWN + +# Add CS pins to ensure they are high in bootloader +PC15 BMI270_CS1 CS +PB12 AT7456E_CS CS +PA15 FLASH_CS CS +PE11 BMI270_CS2 CS + +## pull up VTX power so that it is enabled in bootloader +PC5 VTX_PWR OUTPUT HIGH # labelled as "Pit-1" +# pull up PIN-EN so that Video 1 is selected by default +PC2 VID_SELECT OUTPUT HIGH # labelled as "PIN-EN" +PD2 CAM_C OUTPUT LOW # labelled as "CAM-C" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD/hwdef.dat new file mode 100644 index 00000000000..b14d1053cb1 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD/hwdef.dat @@ -0,0 +1,198 @@ +# hw definition file for processing by chibios_pins.py +# for SkystarsH7HD + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID 1075 + +# crystal frequency, setup to use external oscillator +OSCILLATOR_HZ 8000000 + +FLASH_SIZE_KB 2048 + +env OPTIMIZE -O2 + +# ChibiOS system timer +STM32_ST_USE_TIMER 12 +define CH_CFG_ST_RESOLUTION 16 + +# leave 1 sectors free +FLASH_RESERVE_START_KB 128 + +# use last 2 pages for flash storage +# H743 has 16 pages of 128k each +STORAGE_FLASH_PAGE 14 +define HAL_STORAGE_SIZE 32768 + +# enable logging to dataflash +define HAL_LOGGING_DATAFLASH_ENABLED 1 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART5 USART6 UART7 UART8 + +# buzzer +PB3 BUZZER OUTPUT LOW PULLDOWN GPIO(80) +define HAL_BUZZER_PIN 80 +define HAL_BUZZER_ON 1 +define HAL_BUZZER_OFF 0 +define HAL_PWM_ALT_ALARM + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# SPI1 for BMI270 (Gyro 1) +PC15 BMI270_CS1 CS +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PD7 SPI1_MOSI SPI1 +PB2 BMI270_INT1 INPUT + +# SPI2 for AT7456E OSD +PB12 AT7456E_CS CS +PB13 SPI2_SCK SPI2 +PB14 SPI2_MISO SPI2 +PB15 SPI2_MOSI SPI2 + +# SPI3 for W25Q128 dataflash +PA15 FLASH_CS CS +PC10 SPI3_SCK SPI3 +PC11 SPI3_MISO SPI3 +PC12 SPI3_MOSI SPI3 + +# SPI4 for BMI270 (Gyro 2) +PE11 BMI270_CS2 CS +PE12 SPI4_SCK SPI4 +PE13 SPI4_MISO SPI4 +PE14 SPI4_MOSI SPI4 +PE15 BMI270_INT2 INPUT + +DMA_PRIORITY TIM1* TIM4* TIM3* TIM2* SPI1* SPI4* +DMA_NOSHARE SPI1_RX SPI2_TX SPI4_RX USART6_RX + +# spi devices +SPIDEV bmi270_1 SPI1 DEVID1 BMI270_CS1 MODE3 1*MHZ 10*MHZ +SPIDEV osd SPI2 DEVID2 AT7456E_CS MODE0 10*MHZ 10*MHZ +SPIDEV dataflash SPI3 DEVID3 FLASH_CS MODE3 32*MHZ 32*MHZ +SPIDEV bmi270_2 SPI4 DEVID4 BMI270_CS2 MODE3 1*MHZ 10*MHZ + +# one I2C bus +I2C_ORDER I2C2 I2C1 + +# I2C1 - external +PB8 I2C1_SCL I2C1 +PB9 I2C1_SDA I2C1 + +# I2C2 - internal Baro +PB10 I2C2_SCL I2C2 +PB11 I2C2_SDA I2C2 + +PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PC1 BATT_CURRENT_SENS ADC1 SCALE(1) + +# VTX Power control - should be high at startup to ensure power +PC5 VTX_PWR OUTPUT HIGH GPIO(81) # labelled as "Pit-1" +# Camera selection - should be high so that Video 1 is selected by default +PC2 VID_SELECT OUTPUT HIGH GPIO(82) # labelled as "PIN-EN" +# OSD pad for TTL based OSD control, not supported by AP +PD2 CAM_C OUTPUT LOW GPIO(83) # labelled as "CAM-C" + + +# define default battery setup +define HAL_BATT_MONITOR_DEFAULT 4 +define HAL_BATT_VOLT_PIN 10 +define HAL_BATT_CURR_PIN 11 +define HAL_BATT2_VOLT_PIN 10 +define HAL_BATT2_CURR_PIN 12 +define HAL_BATT_VOLT_SCALE 11.1 +define HAL_BATT_CURR_SCALE 59.5 +define HAL_BATT2_VOLT_SCALE 11.1 +define HAL_BATT2_CURR_SCALE 59.5 + +PC3 RSSI_ADC ADC1 +define BOARD_RSSI_ANA_PIN 13 + +PE3 LED0 OUTPUT LOW GPIO(90) # red, labelled as LED1 +PE4 LED1 OUTPUT LOW GPIO(91) # blue, labelled as LED2 +define HAL_GPIO_A_LED_PIN 90 +define HAL_GPIO_B_LED_PIN 91 +define HAL_GPIO_LED_OFF 1 + +# USART1 +PA9 USART1_TX USART1 +PA10 USART1_RX USART1 + +# USART2 +PD5 USART2_TX USART2 +PD6 USART2_RX USART2 + +# USART3 +PD8 USART3_TX USART3 +PD9 USART3_RX USART3 + +# UART4 +PD0 UART4_RX UART4 +PD1 UART4_TX UART4 + +# UART5 +PB5 UART5_RX UART5 +PB6 UART5_TX UART5 + +# USART6 (RX / SBUS) +# as an alternative config setup the RX6 pin as a uart. This allows +# for bi-directional UART based receiver protocols such as FPort +# without any extra hardware +PC6 USART6_TX USART6 NODMA +PC7 USART6_RX USART6 NODMA ALT(1) + +# UART7 +PE7 UART7_RX UART7 +PE8 UART7_TX UART7 + +# UART8 +PE0 UART8_RX UART8 +PE1 UART8_TX UART8 + +define HAL_SERIAL6_PROTOCOL SerialProtocol_RCIN +define HAL_SERIAL6_BAUD 115 + +# Motors +PB0 TIM1_CH2N TIM1 PWM(1) GPIO(50) +PB1 TIM1_CH3N TIM1 PWM(2) GPIO(51) +PD12 TIM4_CH1 TIM4 PWM(3) GPIO(52) +PD13 TIM4_CH2 TIM4 PWM(4) GPIO(53) +PA0 TIM2_CH1 TIM2 PWM(5) GPIO(54) +PA1 TIM2_CH2 TIM2 PWM(6) GPIO(55) +PA2 TIM2_CH3 TIM2 PWM(7) GPIO(56) +PA3 TIM2_CH4 TIM2 PWM(8) GPIO(57) + +# LED strip WS2812 / Neopixel +PA8 TIM1_CH1 TIM1 PWM(9) GPIO(58) + +# RC input defaults to timer capture +PC7 TIM3_CH2 TIM3 RCININT PULLDOWN LOW + +# no built-in compass, but probe the i2c bus for all possible +# external compass types +define ALLOW_ARM_NO_COMPASS +define HAL_PROBE_EXTERNAL_I2C_COMPASSES +define HAL_I2C_INTERNAL_MASK 0 + +# two IMU +IMU BMI270 SPI:bmi270_1 ROTATION_ROLL_180_YAW_90 +IMU BMI270 SPI:bmi270_2 ROTATION_ROLL_180 + +# one BARO +BARO BMP280 I2C:0:0x76 + +# setup for OSD +define OSD_ENABLED 1 +define HAL_OSD_TYPE_DEFAULT 1 +ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin + +define STM32_PWM_USE_ADVANCED TRUE diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SuccexF4/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/SuccexF4/hwdef.dat index 429f37c7317..af9715dfcd1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/SuccexF4/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/SuccexF4/hwdef.dat @@ -131,3 +131,6 @@ define HAL_SPRAYER_ENABLED 0 # reduce max size of embedded params for apj_tool.py define AP_PARAM_MAX_EMBEDDED_PARAM 1024 + +# minimal drivers to reduce flash usage +include ../include/minimal.inc diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Swan-K1/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Swan-K1/hwdef.dat index b5214322ff4..c00287cb2b3 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Swan-K1/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Swan-K1/hwdef.dat @@ -36,3 +36,5 @@ define HAL_WITH_RAMTRON 1 # use a longer frame gap detector for more robust SBUS with H12 controller define HAL_SBUS_FRAME_GAP 5000U + +AUTOBUILD_TARGETS Plane diff --git a/libraries/AP_HAL_ChibiOS/hwdef/VRBrain-v51/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/VRBrain-v51/hwdef.dat index 0136868e5c2..fb6571bf1d0 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/VRBrain-v51/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/VRBrain-v51/hwdef.dat @@ -171,3 +171,4 @@ define HAL_GENERATOR_ENABLED 0 define AC_OAPATHPLANNER_ENABLED 0 define PRECISION_LANDING 0 define AP_OPTICALFLOW_ENABLED 0 +define AP_ICENGINE_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/VRUBrain-v51/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/VRUBrain-v51/hwdef.dat index 7fc8e316d51..aa154ac0e1e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/VRUBrain-v51/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/VRUBrain-v51/hwdef.dat @@ -180,3 +180,7 @@ define HAL_RUNCAM_ENABLED 0 define HAL_SPEKTRUM_TELEM_ENABLED 0 define HAL_SOARING_ENABLED 0 define AP_OPTICALFLOW_ENABLED 0 +define AP_ICENGINE_ENABLED 0 + +# minimal drivers to reduce flash usage +include ../include/minimal.inc diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef-bl.dat index 4daf80faeb1..53f4626d9ea 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef-bl.dat @@ -27,7 +27,6 @@ define CH_CFG_ST_FREQUENCY 1000 FLASH_SIZE_KB 256 # store parameters in last 2 pages -STORAGE_FLASH_PAGE 126 define HAL_STORAGE_SIZE 800 # USART3 for debug @@ -95,8 +94,6 @@ define STORAGE_THD_WA_SIZE 512 define HAL_NO_MONITOR_THREAD -define HAL_MINIMIZE_FEATURES 0 - define HAL_DEVICE_THREAD_STACK 768 define AP_PARAM_MAX_EMBEDDED_PARAM 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef.dat index 7105534c03b..a508ceda532 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef.dat @@ -120,8 +120,6 @@ define HAL_UART_MIN_RX_SIZE 128 define HAL_UART_STACK_SIZE 256 define STORAGE_THD_WA_SIZE 512 -define HAL_MINIMIZE_FEATURES 0 - define HAL_I2C_CLEAR_ON_TIMEOUT 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/board.c b/libraries/AP_HAL_ChibiOS/hwdef/common/board.c index 5c2fb63a01c..a6f88d64ec6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/board.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/board.c @@ -238,6 +238,12 @@ void __early_init(void) { SCB_DisableDCache(); #endif #if defined(STM32H7) + + // ensure ITCM and DTCM are enabled. These could be disabled by the px4 + // bootloader + SCB->ITCMCR |= 1; // ITCM enable + SCB->DTCMCR |= 1; // DTCM enable + // disable cache on SRAM4 so we can use it for DMA mpuConfigureRegion(MPU_REGION_5, 0x38000000U, diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk b/libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk index 58db18730dc..1ac719658a8 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk @@ -18,6 +18,16 @@ ifeq ($(USE_CPPOPT),) USE_CPPOPT = -fno-rtti -std=gnu++11 endif +# Assembly specific options here (added to USE_OPT). +ifeq ($(USE_ASOPT),) + USE_ASOPT = +endif + +# Assembly specific options here (added to USE_ASXOPT). +ifeq ($(USE_ASXOPT),) + USE_ASXOPT = +endif + # Enable this if you want the linker to remove unused code and data ifeq ($(USE_LINK_GC),) USE_LINK_GC = yes diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/chibios_common.mk b/libraries/AP_HAL_ChibiOS/hwdef/common/chibios_common.mk index 7341a1f18f3..24047fd10bb 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/chibios_common.mk +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/chibios_common.mk @@ -7,6 +7,8 @@ OPT := $(USE_OPT) COPT := $(USE_COPT) CPPOPT := $(USE_CPPOPT) +ASOPT := $(USE_ASOPT) +ASXOPT := $(USE_ASXOPT) # Garbage collection ifeq ($(USE_LINK_GC),yes) @@ -117,8 +119,8 @@ LIBS := $(DLIBS) $(ULIBS) # Various settings MCFLAGS := -mcpu=$(MCU) ODFLAGS = -x --syms -ASFLAGS = $(MCFLAGS) $(ADEFS) -ASXFLAGS = $(MCFLAGS) $(ADEFS) +ASFLAGS = $(MCFLAGS) $(ADEFS) $(ASOPT) +ASXFLAGS = $(MCFLAGS) $(ADEFS) $(ASXOPT) ifneq ($(USE_FPU),no) LIBCC_ASXFLAGS = $(ASXFLAGS) $(USE_FPU_OPT) else diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/common.ld b/libraries/AP_HAL_ChibiOS/hwdef/common/common.ld index 5c54b962adb..2ef25a8248b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/common.ld +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/common.ld @@ -72,6 +72,7 @@ SECTIONS { /* we want app_descriptor near the start of flash so a false positive isn't found by the bootloader (eg. ROMFS) */ + KEEP(*(.apsec_data)); KEEP(*(.app_descriptor)); *(.text) *(.text.*) @@ -201,4 +202,5 @@ SECTIONS . = ORIGIN(flash) + LENGTH(flash); __crash_log_end__ = .; } > flash + } diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/common_extf.ld b/libraries/AP_HAL_ChibiOS/hwdef/common/common_extf.ld index 4aec753fb9b..07b4530b26e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/common_extf.ld +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/common_extf.ld @@ -135,6 +135,7 @@ SECTIONS lib/lib*.a:*Filter.*(.text* .rodata*) lib/lib*.a:*Filter2p.*(.text* .rodata*) lib/lib*.a:SPIDevice.*(.text* .rodata*) + lib/lib*.a:I2CDevice.*(.text* .rodata*) lib/lib*.a:Util.*(.text* .rodata*) lib/lib*.a:Device.*(.text* .rodata*) lib/lib*.a:Scheduler.*(.text* .rodata*) @@ -143,8 +144,15 @@ SECTIONS lib/lib*.a:crc.*(.text* .rodata*) lib/lib*.a:matrixN.*(.text* .rodata*) lib/lib*.a:matrix_alg.*(.text* .rodata*) - lib/lib*.a:AP_NavEKF*.*(.text* .rodata*) - lib/lib*.a:EKFGSF*.*(.text* .rodata*) + lib/lib*.a:AP_NavEKF3*.*(.text* .rodata*) + lib/lib*.a:AP_NavEKF_*.*(.text* .rodata*) + lib/lib*.a:EKF*.*(.text* .rodata*) + lib/lib*.a:AP_Compass_Backend.*(.text* .rodata*) + lib/lib*.a:AP_RCProtocol_Backend.*(.text* .rodata*) + lib/lib*.a:AP_RCProtocol.*(.text* .rodata*) + lib/lib*.a:AP_RCProtocol_CRSF.*(.text* .rodata*) + lib/lib*.a:AP_RCTelemetry.*(.text* .rodata*) + lib/lib*.a:AP_CRSF_Telem.*(.text* .rodata*) lib/lib*.a:vector2.*(.text* .rodata*) lib/lib*.a:quaternion.*(.text* .rodata*) lib/lib*.a:polygon.*(.text* .rodata*) @@ -212,6 +220,7 @@ SECTIONS positive isn't found by the bootloader (eg. ROMFS) */ KEEP(*libch.a:vectors.o); KEEP(*libch.a:crt0_v7m.o); + KEEP(*(.apsec_data)); KEEP(*(.app_descriptor)); *(.text) *(.text.*) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/flash.c b/libraries/AP_HAL_ChibiOS/hwdef/common/flash.c index 89d2b2c755f..3ea2c423c68 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/flash.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/flash.c @@ -75,7 +75,7 @@ // optionally disable interrupts during flash writes #ifndef STM32_FLASH_DISABLE_ISR -#define STM32_FLASH_DISABLE_ISR 0 +#define STM32_FLASH_DISABLE_ISR 1 #endif // the 2nd bank of flash needs to be handled differently @@ -284,7 +284,7 @@ void stm32_flash_lock(void) #endif } -#if defined(STM32H7) && defined(HAL_FLASH_PROTECTION) +#if defined(STM32H7) && HAL_FLASH_PROTECTION static void stm32_flash_wait_opt_idle(void) { __DSB(); @@ -546,28 +546,37 @@ static bool stm32_flash_write_h7(uint32_t addr, const void *buf, uint32_t count) return false; } - // check for erasure - if (!stm32h7_check_all_ones(addr, count >> 2)) { - return false; - } + stm32_flash_unlock(); + bool success = true; + + while (count >= 32) { + const uint8_t *b2 = (const uint8_t *)addr; + // if the bytes already match then skip this chunk + if (memcmp(b, b2, 32) != 0) { + // check for erasure + if (!stm32h7_check_all_ones(addr, 8)) { + return false; + } #if STM32_FLASH_DISABLE_ISR - syssts_t sts = chSysGetStatusAndLockX(); + syssts_t sts = chSysGetStatusAndLockX(); #endif - stm32_flash_unlock(); - bool success = true; + bool ok = stm32h7_flash_write32(addr, b); - while (count >= 32) { - if (!stm32h7_flash_write32(addr, b)) { - success = false; - goto failed; - } +#if STM32_FLASH_DISABLE_ISR + chSysRestoreStatusX(sts); +#endif - // check contents - if (memcmp((void*)addr, b, 32) != 0) { - success = false; - goto failed; + if (!ok) { + success = false; + goto failed; + } + // check contents + if (memcmp((void*)addr, b, 32) != 0) { + success = false; + goto failed; + } } addr += 32; @@ -577,9 +586,6 @@ static bool stm32_flash_write_h7(uint32_t addr, const void *buf, uint32_t count) failed: stm32_flash_lock(); -#if STM32_FLASH_DISABLE_ISR - chSysRestoreStatusX(sts); -#endif return success; } @@ -857,7 +863,7 @@ void stm32_flash_protect_flash(bool bootloader, bool protect) { (void)bootloader; (void)protect; -#if defined(STM32H7) && !defined(HAL_BOOTLOADER_BUILD) && defined(HAL_FLASH_PROTECTION) +#if defined(STM32H7) && HAL_FLASH_PROTECTION uint32_t prg1 = FLASH->WPSN_CUR1; uint32_t prg2 = FLASH->WPSN_CUR2; #ifndef STORAGE_FLASH_PAGE @@ -919,7 +925,7 @@ void stm32_flash_protect_flash(bool bootloader, bool protect) */ void stm32_flash_unprotect_flash() { -#if defined(STM32H7) && defined(HAL_FLASH_PROTECTION) +#if defined(STM32H7) && HAL_FLASH_PROTECTION stm32_flash_opt_clear_errors(); stm32_flash_clear_errors(); diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/malloc.c b/libraries/AP_HAL_ChibiOS/hwdef/common/malloc.c index b6cb8f9adbb..b193ec3b8d9 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/malloc.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/malloc.c @@ -85,7 +85,13 @@ void malloc_init(void) // check for changes which indicate a write to an uninitialised // object. We start at address 0x1 as writing the first byte // causes a fault +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Warray-bounds" +#if defined(__GNUC__) && __GNUC__ >= 10 +#pragma GCC diagnostic ignored "-Wstringop-overflow" +#endif memset((void*)0x00000001, 0, 1023); +#pragma GCC diagnostic pop #endif uint8_t i; diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/mcuconf.h b/libraries/AP_HAL_ChibiOS/hwdef/common/mcuconf.h index da2b77a23c5..50ac6afe44d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/mcuconf.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/mcuconf.h @@ -37,6 +37,12 @@ // include generated config #include "hwdef.h" +#ifdef HAL_CHIBIOS_ENABLE_ASSERTS +#define STM32_DMA_ERROR_HOOK(devp) osalSysHalt("DMA failure") +#else +#define STM32_DMA_ERROR_HOOK(devp) do {} while(0) +#endif + #if defined(STM32F1) #include "stm32f1_mcuconf.h" #elif defined(STM32F3) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.c b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.c index f85f765cdb6..aa85c75d33a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.c @@ -298,7 +298,7 @@ void get_rtc_backup(uint8_t idx, uint32_t *v, uint8_t n) */ void peripheral_power_enable(void) { -#if defined(HAL_GPIO_PIN_nVDD_5V_PERIPH_EN) || defined(HAL_GPIO_PIN_nVDD_5V_HIPOWER_EN) || defined(HAL_GPIO_PIN_VDD_3V3_SENSORS_EN)|| defined(HAL_GPIO_PIN_VDD_3V3_SENSORS2_EN) || defined(HAL_GPIO_PIN_VDD_3V3_SENSORS3_EN) || defined(HAL_GPIO_PIN_VDD_3V3_SENSORS4_EN) || defined(HAL_GPIO_PIN_nVDD_3V3_SD_CARD_EN) || defined(HAL_GPIO_PIN_VDD_3V3_SD_CARD_EN) +#if defined(HAL_GPIO_PIN_nVDD_5V_PERIPH_EN) || defined(HAL_GPIO_PIN_nVDD_5V_HIPOWER_EN) || defined(HAL_GPIO_PIN_VDD_3V3_SENSORS_EN)|| defined(HAL_GPIO_PIN_VDD_3V3_SENSORS2_EN) || defined(HAL_GPIO_PIN_VDD_3V3_SENSORS3_EN) || defined(HAL_GPIO_PIN_VDD_3V3_SENSORS4_EN) || defined(HAL_GPIO_PIN_nVDD_3V3_SD_CARD_EN) || defined(HAL_GPIO_PIN_VDD_3V3_SD_CARD_EN) || defined(HAL_GPIO_PIN_VDD_3V5_LTE_EN) // we don't know what state the bootloader had the CTS pin in, so // wait here with it pulled up from the PAL table for enough time // for the radio to be definately powered down @@ -336,6 +336,9 @@ void peripheral_power_enable(void) #ifdef HAL_GPIO_PIN_VDD_3V3_SD_CARD_EN // others need it active high palWriteLine(HAL_GPIO_PIN_VDD_3V3_SD_CARD_EN, 1); +#endif +#ifdef HAL_GPIO_PIN_VDD_3V5_LTE_EN + palWriteLine(HAL_GPIO_PIN_VDD_3V5_LTE_EN, 1); #endif for (i=0; i<20; i++) { // give 20ms for sensors to settle @@ -558,3 +561,20 @@ unsigned int stm32_rand_generate_nonblocking(unsigned char* output, unsigned int } #endif // #if HAL_USE_HW_RNG && defined(RNG) + +/* + see if we should limit flash to 1M on devices with older revisions of STM32F427 + */ +bool check_limit_flash_1M(void) +{ +#ifdef STM32F427xx + const uint16_t revid = (*(uint32_t *)DBGMCU_BASE) >> 16; + static const uint16_t badrevs[4] = { 0x1000, 0x1001, 0x1003, 0x1007 }; + for (uint8_t i=0; i<4; i++) { + if (revid == badrevs[i]) { + return true; + } + } +#endif + return false; +} diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h index 437bc91a01a..8424a370be2 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h @@ -54,6 +54,11 @@ uint64_t stm32_get_utc_usec(void); // hook for FAT timestamps uint32_t get_fattime(void); +/* + see if we should limit flash to 1M on devices with older revisions of STM32F427 + */ +bool check_limit_flash_1M(void); + // one-time programmable area #if defined(FLASH_OTP_BASE) #define OTP_BASE FLASH_OTP_BASE diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32f1_mcuconf.h b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32f1_mcuconf.h index c9f8b039103..535f09edbd3 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32f1_mcuconf.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32f1_mcuconf.h @@ -113,7 +113,7 @@ #define STM32_I2C_I2C2_IRQ_PRIORITY 5 #define STM32_I2C_I2C1_DMA_PRIORITY 3 #define STM32_I2C_I2C2_DMA_PRIORITY 3 -#define STM32_I2C_DMA_ERROR_HOOK(i2cp) osalSysHalt("DMA failure") +#define STM32_I2C_DMA_ERROR_HOOK(i2cp) STM32_DMA_ERROR_HOOK(i2cp) /* * ICU driver system settings. @@ -154,7 +154,7 @@ #define STM32_SPI_SPI2_DMA_PRIORITY 1 #define STM32_SPI_SPI1_IRQ_PRIORITY 10 #define STM32_SPI_SPI2_IRQ_PRIORITY 10 -#define STM32_SPI_DMA_ERROR_HOOK(spip) osalSysHalt("DMA failure") +#define STM32_SPI_DMA_ERROR_HOOK(spip) STM32_DMA_ERROR_HOOK(spip) /* * ST driver system settings. @@ -172,7 +172,7 @@ #define STM32_UART_USART1_DMA_PRIORITY 0 #define STM32_UART_USART2_DMA_PRIORITY 0 #define STM32_UART_USART3_DMA_PRIORITY 0 -#define STM32_UART_DMA_ERROR_HOOK(uartp) osalSysHalt("DMA failure") +#define STM32_UART_DMA_ERROR_HOOK(uartp) STM32_DMA_ERROR_HOOK(uartp) /* * WDG driver system settings. diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32f3_mcuconf.h b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32f3_mcuconf.h index aed727582a1..92d28e121e1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32f3_mcuconf.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32f3_mcuconf.h @@ -127,7 +127,7 @@ #define STM32_I2C_I2C2_IRQ_PRIORITY 5 #define STM32_I2C_I2C1_DMA_PRIORITY 3 #define STM32_I2C_I2C2_DMA_PRIORITY 3 -#define STM32_I2C_DMA_ERROR_HOOK(i2cp) osalSysHalt("DMA failure") +#define STM32_I2C_DMA_ERROR_HOOK(i2cp) STM32_DMA_ERROR_HOOK(i2cp) /* * ICU driver system settings. @@ -168,7 +168,7 @@ #define STM32_SPI_SPI2_DMA_PRIORITY 1 #define STM32_SPI_SPI1_IRQ_PRIORITY 10 #define STM32_SPI_SPI2_IRQ_PRIORITY 10 -#define STM32_SPI_DMA_ERROR_HOOK(spip) osalSysHalt("DMA failure") +#define STM32_SPI_DMA_ERROR_HOOK(spip) STM32_DMA_ERROR_HOOK(spip) /* * ST driver system settings. @@ -186,7 +186,7 @@ #define STM32_UART_USART1_DMA_PRIORITY 0 #define STM32_UART_USART2_DMA_PRIORITY 0 #define STM32_UART_USART3_DMA_PRIORITY 0 -#define STM32_UART_DMA_ERROR_HOOK(uartp) osalSysHalt("DMA failure") +#define STM32_UART_DMA_ERROR_HOOK(uartp) STM32_DMA_ERROR_HOOK(uartp) /* * WDG driver system settings. diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32f47_mcuconf.h b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32f47_mcuconf.h index 1044902f55f..9a9fb6e011f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32f47_mcuconf.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32f47_mcuconf.h @@ -178,6 +178,11 @@ #define STM32_PLLN_VALUE 336 #define STM32_PLLP_VALUE 2 #define STM32_PLLQ_VALUE 7 +#elif STM32_HSECLK == 12000000U +#define STM32_PLLM_VALUE 12 +#define STM32_PLLN_VALUE 336 +#define STM32_PLLP_VALUE 2 +#define STM32_PLLQ_VALUE 7 #elif STM32_HSECLK == 16000000U #define STM32_PLLM_VALUE 16 #define STM32_PLLN_VALUE 336 @@ -389,7 +394,7 @@ #define STM32_I2C_I2C1_DMA_PRIORITY 3 #define STM32_I2C_I2C2_DMA_PRIORITY 3 #define STM32_I2C_I2C3_DMA_PRIORITY 3 -#define STM32_I2C_DMA_ERROR_HOOK(i2cp) osalSysHalt("DMA failure") +#define STM32_I2C_DMA_ERROR_HOOK(i2cp) STM32_DMA_ERROR_HOOK(i2cp) /* * I2S driver system settings. @@ -398,7 +403,7 @@ #define STM32_I2S_SPI3_IRQ_PRIORITY 10 #define STM32_I2S_SPI2_DMA_PRIORITY 1 #define STM32_I2S_SPI3_DMA_PRIORITY 1 -#define STM32_I2S_DMA_ERROR_HOOK(i2sp) osalSysHalt("DMA failure") +#define STM32_I2S_DMA_ERROR_HOOK(i2sp) STM32_DMA_ERROR_HOOK(i2sp) /* * ICU driver system settings. @@ -485,7 +490,7 @@ #define STM32_SPI_SPI2_IRQ_PRIORITY 10 #define STM32_SPI_SPI3_IRQ_PRIORITY 10 #define STM32_SPI_SPI4_IRQ_PRIORITY 10 -#define STM32_SPI_DMA_ERROR_HOOK(spip) osalSysHalt("DMA failure") +#define STM32_SPI_DMA_ERROR_HOOK(spip) STM32_DMA_ERROR_HOOK(spip) /* * ST driver system settings. @@ -523,7 +528,7 @@ #define STM32_UART_UART4_DMA_PRIORITY 0 #define STM32_UART_UART5_DMA_PRIORITY 0 #define STM32_UART_USART6_DMA_PRIORITY 0 -#define STM32_UART_DMA_ERROR_HOOK(uartp) osalSysHalt("DMA failure") +#define STM32_UART_DMA_ERROR_HOOK(uartp) STM32_DMA_ERROR_HOOK(uartp) #define STM32_IRQ_UART1_PRIORITY 12 #define STM32_IRQ_UART2_PRIORITY 12 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32g4_mcuconf.h b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32g4_mcuconf.h index 7b95516834b..7cd46d1ac22 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32g4_mcuconf.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32g4_mcuconf.h @@ -239,7 +239,7 @@ #define STM32_I2C_I2C2_DMA_PRIORITY 3 #define STM32_I2C_I2C3_DMA_PRIORITY 3 #define STM32_I2C_I2C4_DMA_PRIORITY 3 -#define STM32_I2C_DMA_ERROR_HOOK(i2cp) osalSysHalt("DMA failure") +#define STM32_I2C_DMA_ERROR_HOOK(i2cp) STM32_DMA_ERROR_HOOK(i2cp) /* * SPI driver system settings. @@ -252,7 +252,7 @@ #define STM32_SPI_SPI2_IRQ_PRIORITY 10 #define STM32_SPI_SPI3_IRQ_PRIORITY 10 #define STM32_SPI_SPI4_IRQ_PRIORITY 10 -#define STM32_SPI_DMA_ERROR_HOOK(spip) osalSysHalt("DMA failure") +#define STM32_SPI_DMA_ERROR_HOOK(spip) STM32_DMA_ERROR_HOOK(spip) /* * ST driver system settings. @@ -276,7 +276,7 @@ #define STM32_UART_USART3_DMA_PRIORITY 0 #define STM32_UART_UART4_DMA_PRIORITY 0 #define STM32_UART_UART5_DMA_PRIORITY 0 -#define STM32_UART_DMA_ERROR_HOOK(uartp) osalSysHalt("DMA failure") +#define STM32_UART_DMA_ERROR_HOOK(uartp) STM32_DMA_ERROR_HOOK(uartp) /* * USB driver system settings. diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h index f0d3cc314c4..97ca23092c0 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h @@ -19,7 +19,7 @@ #pragma once // we want to cope with both revision XY chips and newer chips -#ifndef STM32H750xx +#if !defined(HAL_CUSTOM_MCU_CLOCKRATE) || HAL_CUSTOM_MCU_CLOCKRATE <= 400000000 #define STM32_ENFORCE_H7_REV_XY #endif @@ -146,7 +146,7 @@ // no crystal #define STM32_PLL1_DIVN_VALUE 50 #define STM32_PLL1_DIVP_VALUE 2 -#define STM32_PLL1_DIVQ_VALUE 8 +#define STM32_PLL1_DIVQ_VALUE 10 #define STM32_PLL1_DIVR_VALUE 2 #define STM32_PLL2_DIVN_VALUE 45 @@ -161,13 +161,17 @@ #elif (STM32_HSECLK == 8000000U) || (STM32_HSECLK == 16000000U) // common clock tree for multiples of 8MHz crystals -#ifdef STM32H750xx +#ifdef HAL_CUSTOM_MCU_CLOCKRATE +#if HAL_CUSTOM_MCU_CLOCKRATE == 480000000 #define STM32_PLL1_DIVN_VALUE 120 #else +#error "Unable to configure custom clockrate" +#endif +#else #define STM32_PLL1_DIVN_VALUE 100 #endif #define STM32_PLL1_DIVP_VALUE 2 -#define STM32_PLL1_DIVQ_VALUE 8 +#define STM32_PLL1_DIVQ_VALUE 10 #define STM32_PLL1_DIVR_VALUE 2 #define STM32_PLL2_DIVN_VALUE 45 @@ -181,13 +185,17 @@ #define STM32_PLL3_DIVR_VALUE 9 #elif STM32_HSECLK == 24000000U -#ifdef STM32H750xx +#ifdef HAL_CUSTOM_MCU_CLOCKRATE +#if HAL_CUSTOM_MCU_CLOCKRATE == 480000000 #define STM32_PLL1_DIVN_VALUE 120 #else +#error "Unable to configure custom clockrate" +#endif +#else #define STM32_PLL1_DIVN_VALUE 100 #endif #define STM32_PLL1_DIVP_VALUE 2 -#define STM32_PLL1_DIVQ_VALUE 8 +#define STM32_PLL1_DIVQ_VALUE 10 #define STM32_PLL1_DIVR_VALUE 2 #define STM32_PLL2_DIVN_VALUE 30 @@ -201,9 +209,12 @@ #define STM32_PLL3_DIVR_VALUE 9 #elif STM32_HSECLK == 25000000U +#ifdef HAL_CUSTOM_MCU_CLOCKRATE +#error "Unable to configure custom clockrate" +#endif #define STM32_PLL1_DIVN_VALUE 64 #define STM32_PLL1_DIVP_VALUE 2 -#define STM32_PLL1_DIVQ_VALUE 8 +#define STM32_PLL1_DIVQ_VALUE 10 #define STM32_PLL1_DIVR_VALUE 2 #define STM32_PLL2_DIVN_VALUE 72 @@ -280,7 +291,7 @@ #define STM32_QSPISEL STM32_QSPISEL_PLL2_R_CK #define STM32_FMCSEL STM32_QSPISEL_HCLK #define STM32_SWPSEL STM32_SWPSEL_PCLK1 -#define STM32_FDCANSEL STM32_FDCANSEL_PLL2_Q_CK +#define STM32_FDCANSEL STM32_FDCANSEL_PLL1_Q_CK #define STM32_DFSDM1SEL STM32_DFSDM1SEL_PCLK2 #define STM32_SPDIFSEL STM32_SPDIFSEL_PLL1_Q_CK #define STM32_SPI45SEL STM32_SPI45SEL_PCLK2 @@ -420,7 +431,7 @@ #define STM32_I2C_I2C2_DMA_PRIORITY 3 #define STM32_I2C_I2C3_DMA_PRIORITY 3 #define STM32_I2C_I2C4_DMA_PRIORITY 3 -#define STM32_I2C_DMA_ERROR_HOOK(i2cp) osalSysHalt("DMA failure") +#define STM32_I2C_DMA_ERROR_HOOK(i2cp) STM32_DMA_ERROR_HOOK(i2cp) /* * ICU driver system settings. @@ -527,7 +538,7 @@ #define STM32_SPI_SPI4_IRQ_PRIORITY 10 #define STM32_SPI_SPI5_IRQ_PRIORITY 10 #define STM32_SPI_SPI6_IRQ_PRIORITY 10 -#define STM32_SPI_DMA_ERROR_HOOK(spip) osalSysHalt("DMA failure") +#define STM32_SPI_DMA_ERROR_HOOK(spip) STM32_DMA_ERROR_HOOK(spip) /* * ST driver system settings. @@ -554,7 +565,7 @@ #define STM32_UART_USART6_DMA_PRIORITY 0 #define STM32_UART_UART7_DMA_PRIORITY 0 #define STM32_UART_UART8_DMA_PRIORITY 0 -#define STM32_UART_DMA_ERROR_HOOK(uartp) osalSysHalt("DMA failure") +#define STM32_UART_DMA_ERROR_HOOK(uartp) STM32_DMA_ERROR_HOOK(uartp) #define STM32_IRQ_LPUART1_PRIORITY 12 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32l4_mcuconf.h b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32l4_mcuconf.h index 3909d8a5528..73dea046289 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32l4_mcuconf.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32l4_mcuconf.h @@ -220,7 +220,7 @@ #define STM32_I2C_I2C2_DMA_PRIORITY 3 #define STM32_I2C_I2C3_DMA_PRIORITY 3 #define STM32_I2C_I2C4_DMA_PRIORITY 3 -#define STM32_I2C_DMA_ERROR_HOOK(i2cp) osalSysHalt("DMA failure") +#define STM32_I2C_DMA_ERROR_HOOK(i2cp) STM32_DMA_ERROR_HOOK(i2cp) /* * PWM driver system settings. @@ -266,7 +266,7 @@ #define STM32_SPI_SPI1_IRQ_PRIORITY 10 #define STM32_SPI_SPI2_IRQ_PRIORITY 10 #define STM32_SPI_SPI3_IRQ_PRIORITY 10 -#define STM32_SPI_DMA_ERROR_HOOK(spip) osalSysHalt("DMA failure") +#define STM32_SPI_DMA_ERROR_HOOK(spip) STM32_DMA_ERROR_HOOK(spip) /* * ST driver system settings. @@ -294,7 +294,7 @@ #define STM32_UART_USART3_DMA_PRIORITY 0 #define STM32_UART_UART4_DMA_PRIORITY 0 #define STM32_UART_UART5_DMA_PRIORITY 0 -#define STM32_UART_DMA_ERROR_HOOK(uartp) osalSysHalt("DMA failure") +#define STM32_UART_DMA_ERROR_HOOK(uartp) STM32_DMA_ERROR_HOOK(uartp) /* * USB driver system settings. diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-GPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-GPS/hwdef.dat index 7348b44ce41..97f3199056b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-GPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-GPS/hwdef.dat @@ -10,8 +10,14 @@ define HAL_PROBE_EXTERNAL_I2C_COMPASSES undef HAL_UART_MIN_TX_SIZE define HAL_UART_MIN_TX_SIZE 256 -# GPS+MAG +# GPS define HAL_PERIPH_ENABLE_GPS +# restrict backends available on f103: +define AP_GPS_NOVA_ENABLED 0 +define AP_GPS_SBF_ENABLED 0 +define AP_GPS_GSOF_ENABLED 0 + +# MAG define HAL_PERIPH_ENABLE_MAG #define HAL_PERIPH_ENABLE_NCP5623_LED_WITHOUT_NOTIFY define HAL_PERIPH_ENABLE_TOSHIBA_LED_WITHOUT_NOTIFY diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef.inc b/libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef.inc index 35c93f1eab2..d321768a40d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef.inc @@ -103,8 +103,6 @@ define IO_THD_WA_SIZE 300 define HAL_NO_MONITOR_THREAD -define HAL_MINIMIZE_FEATURES 0 - # only one I2C bus I2C_ORDER I2C1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-GPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-GPS/hwdef.dat index bfe5edf0a42..67e512fa463 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-GPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-GPS/hwdef.dat @@ -14,3 +14,6 @@ define HAL_PROBE_EXTERNAL_I2C_COMPASSES define HAL_PERIPH_ENABLE_GPS define HAL_PERIPH_ENABLE_MAG define HAL_PERIPH_ENABLE_NCP5623_LED_WITHOUT_NOTIFY + +# allow for F9P GPS modules with moving baseline +define GPS_MOVING_BASELINE 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat index 49e5de57469..45f83e68ec9 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat @@ -78,8 +78,6 @@ define HAL_UART_STACK_SIZE 512 define STORAGE_THD_WA_SIZE 512 define IO_THD_WA_SIZE 512 -define HAL_MINIMIZE_FEATURES 0 - # only one I2C bus I2C_ORDER I2C1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-Universal/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-Universal/hwdef.dat index 507a90719f1..b9bbb9c0bf5 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-Universal/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-Universal/hwdef.dat @@ -16,6 +16,9 @@ define HAL_PERIPH_ENABLE_ADSB define HAL_PERIPH_ENABLE_NCP5623_LED_WITHOUT_NOTIFY define HAL_PERIPH_ENABLE_RANGEFINDER +# allow for F9P GPS modules with moving baseline +define GPS_MOVING_BASELINE 1 + define HAL_PERIPH_ADSB_PORT_DEFAULT 3 define HAL_AIRSPEED_BUS_DEFAULT 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef.inc b/libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef.inc index 3f89778263a..68674e6b6e3 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef.inc @@ -101,8 +101,6 @@ define HAL_UART_STACK_SIZE 0x300 define STORAGE_THD_WA_SIZE 512 define IO_THD_WA_SIZE 512 -define HAL_MINIMIZE_FEATURES 0 - # only one I2C bus I2C_ORDER I2C1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f405-MatekGPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f405-MatekGPS/hwdef.dat index 29c900b546a..6cc0dc03c1f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f405-MatekGPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f405-MatekGPS/hwdef.dat @@ -51,8 +51,6 @@ define HAL_DISABLE_LOOP_DELAY define HAL_NO_MONITOR_THREAD -define HAL_MINIMIZE_FEATURES 0 - define HAL_DEVICE_THREAD_STACK 768 # we setup a small defaults.parm diff --git a/libraries/AP_HAL_ChibiOS/hwdef/fmuv2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/fmuv2/hwdef.dat index f07eddc94e2..f58c1332ab0 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/fmuv2/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/fmuv2/hwdef.dat @@ -13,3 +13,9 @@ define HAL_MINIMIZE_FEATURES 1 # we don't have a flash page spare to write parameters to: undef STORAGE_FLASH_PAGE + +# minimal drivers to reduce flash usage +include ../include/minimal.inc + +# produce this error if we are on a 2M board and using 1M firmware +define BOARD_CHECK_F427_USE_2M "2M flash - use fmuv3 firmware" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/fmuv3/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/fmuv3/hwdef.dat index fec01b85833..5e330b84252 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/fmuv3/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/fmuv3/hwdef.dat @@ -468,3 +468,10 @@ DMA_PRIORITY USART6* SPI* # is "ROMFS ROMFS-filename source-filename". Paths are relative to the # ardupilot root. ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_lowpolh.bin + +# for users running fmuv3 on their Solo: +define HAL_OREO_LED_ENABLED (BOARD_FLASH_SIZE > 1024) +define HAL_SOLO_GIMBAL_ENABLED (HAL_MOUNT_ENABLED && BOARD_FLASH_SIZE > 1024) + +# produce this error if we are on a 1M board +define BOARD_CHECK_F427_USE_1M "ERROR: 1M flash use fmuv2" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/include/SimOnHW.inc b/libraries/AP_HAL_ChibiOS/hwdef/include/SimOnHW.inc new file mode 100644 index 00000000000..d4311931106 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/include/SimOnHW.inc @@ -0,0 +1,26 @@ +env SIM_ENABLED 1 + +define INS_MAX_INSTANCES 2 +define HAL_COMPASS_MAX_SENSORS 2 + +define HAL_NAVEKF2_AVAILABLE 0 +define EK3_FEATURE_BODY_ODOM 0 +define EK3_FEATURE_EXTERNAL_NAV 0 +define EK3_FEATURE_DRAG_FUSION 0 +define HAL_ADSB_ENABLED 0 +define HAL_MOUNT_ENABLED 0 +define HAL_PROXIMITY_ENABLED 0 +define HAL_VISUALODOM_ENABLED 0 +define HAL_GENERATOR_ENABLED 0 +# define HAL_LOGGING_ENABLED 0 +define HAL_CRSF_TELEM_ENABLED 0 +#define OSD_ENABLED 0 + +define AP_MOTORS_FRAME_DEFAULT_ENABLED 0 +define AP_MOTORS_FRAME_QUAD_ENABLED 1 + +define LANDING_GEAR_ENABLED 0 +define HAL_MSP_OPTICALFLOW_ENABLED 0 +define HAL_SUPPORT_RCOUT_SERIAL 0 +define HAL_HOTT_TELEM_ENABLED 0 +# define HAL_WITH_DSP 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/include/minimal.inc b/libraries/AP_HAL_ChibiOS/hwdef/include/minimal.inc new file mode 100644 index 00000000000..11b5127c1ce --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/include/minimal.inc @@ -0,0 +1,2 @@ +include minimal_GPS.inc +include minimal_Airspeed.inc diff --git a/libraries/AP_HAL_ChibiOS/hwdef/include/minimal_Airspeed.inc b/libraries/AP_HAL_ChibiOS/hwdef/include/minimal_Airspeed.inc new file mode 100644 index 00000000000..3201ff23e4e --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/include/minimal_Airspeed.inc @@ -0,0 +1,10 @@ +# include file to reduce flash by including *fewer* Airspeed drivers + +define AP_AIRSPEED_BACKEND_DEFAULT_ENABLED 0 +define AP_AIRSPEED_MS4525_ENABLED 1 +define AP_AIRSPEED_ANALOG_ENABLED 1 +define AP_AIRSPEED_MS5525_ENABLED 1 +define AP_AIRSPEED_SDP3X_ENABLED 1 +define AP_AIRSPEED_NMEA_ENABLED 1 # additional checks for vehicle type in .cpp + +define AP_AIRSPEED_UAVCAN_ENABLED HAL_ENABLE_LIBUAVCAN_DRIVERS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/include/minimal_GPS.inc b/libraries/AP_HAL_ChibiOS/hwdef/include/minimal_GPS.inc new file mode 100644 index 00000000000..e5e18f3d682 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/include/minimal_GPS.inc @@ -0,0 +1,5 @@ +# include file to reduce flash by including less GPS drivers + +define AP_GPS_BACKEND_DEFAULT_ENABLED 0 +define AP_GPS_UBLOX_ENABLED 1 + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/iomcu/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/iomcu/hwdef.dat index 2684fbf2113..e4a8d306077 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/iomcu/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/iomcu/hwdef.dat @@ -95,10 +95,6 @@ define RCIN_ICU_TIMER ICUD1 define RCIN_ICU_CHANNEL ICU_CHANNEL_1 define STM32_RCIN_DMA_STREAM STM32_DMA_STREAM_ID(1, 2) -# only use pulse input for PPM, other protocols -# are on serial -define HAL_RCIN_PULSE_PPM_ONLY - #DMA Channel Not relevant for F1 series define STM32_RCIN_DMA_CHANNEL 0 @@ -119,7 +115,7 @@ define HAL_NO_TIMER_THREAD define HAL_NO_RCIN_THREAD define HAL_NO_MONITOR_THREAD define HAL_NO_RCOUT_THREAD -define HAL_NO_SHARED_DMA +define AP_HAL_SHARED_DMA_ENABLED 0 #defined to turn off undef warnings define __FPU_PRESENT 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/iomcu_f103_8MHz/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/iomcu_f103_8MHz/hwdef.dat index 0a9416a9ae0..c28e82e3d31 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/iomcu_f103_8MHz/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/iomcu_f103_8MHz/hwdef.dat @@ -95,10 +95,6 @@ define RCIN_ICU_TIMER ICUD1 define RCIN_ICU_CHANNEL ICU_CHANNEL_1 define STM32_RCIN_DMA_STREAM STM32_DMA_STREAM_ID(1, 2) -# only use pulse input for PPM, other protocols -# are on serial -define HAL_RCIN_PULSE_PPM_ONLY - #DMA Channel Not relevant for F1 series define STM32_RCIN_DMA_CHANNEL 0 @@ -119,7 +115,7 @@ define HAL_NO_TIMER_THREAD define HAL_NO_RCIN_THREAD define HAL_NO_MONITOR_THREAD define HAL_NO_RCOUT_THREAD -define HAL_NO_SHARED_DMA +define AP_HAL_SHARED_DMA_ENABLED 0 #defined to turn off undef warnings define __FPU_PRESENT 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/mRo-M10095/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/mRo-M10095/hwdef.dat index b8dfa9aca4c..eaa64232a6a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/mRo-M10095/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/mRo-M10095/hwdef.dat @@ -84,8 +84,6 @@ PA12 CAN1_TX CAN1 define HAL_NO_MONITOR_THREAD -define HAL_MINIMIZE_FEATURES 0 - define AP_PARAM_MAX_EMBEDDED_PARAM 512 # keep ROMFS uncompressed as we don't have enough RAM diff --git a/libraries/AP_HAL_ChibiOS/hwdef/omnibusf4pro-bdshot/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/omnibusf4pro-bdshot/hwdef.dat index acaaf00f87b..499368ce201 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/omnibusf4pro-bdshot/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/omnibusf4pro-bdshot/hwdef.dat @@ -2,6 +2,7 @@ # Buzzer timer is required so becomes single tone include ../omnibusf4pro/hwdef.dat +include ../include/minimal_GPS.inc undef PB0 PB1 PA3 PB4 PA2 PA1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/omnibusf4pro/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/omnibusf4pro/hwdef.dat index 4820d3b4b62..036714d9741 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/omnibusf4pro/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/omnibusf4pro/hwdef.dat @@ -147,9 +147,8 @@ define STM32_PWM_USE_ADVANCED TRUE #font for the osd ROMFS_WILDCARD libraries/AP_OSD/fonts/font0.bin -# disable SMBUS and fuel battery monitors to save flash +# disable SMBUS monitors to save flash define AP_BATTMON_SMBUS_ENABLE 0 -define AP_BATTMON_FUEL_ENABLE 0 # disable parachute and sprayer to save flash define HAL_PARACHUTE_ENABLED 0 @@ -163,3 +162,6 @@ define HAL_GENERATOR_ENABLED 0 define AC_OAPATHPLANNER_ENABLED 0 define PRECISION_LANDING 0 define AP_OPTICALFLOW_ENABLED 0 +define AP_ICENGINE_ENABLED 0 +define AP_GPS_SIRF_ENABLED 0 +define AP_GPS_SBP_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/omnibusf4v6/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/omnibusf4v6/hwdef.dat index 9413ed81bd1..442d66928c5 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/omnibusf4v6/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/omnibusf4v6/hwdef.dat @@ -149,3 +149,6 @@ define STM32_PWM_USE_ADVANCED TRUE define OSD_ENABLED 1 #font for the osd ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin + +# minimal drivers to reduce flash usage +include ../include/minimal.inc diff --git a/libraries/AP_HAL_ChibiOS/hwdef/revo-mini-sd/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/revo-mini-sd/hwdef-bl.dat new file mode 100644 index 00000000000..a0d2d0cfabe --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/revo-mini-sd/hwdef-bl.dat @@ -0,0 +1,2 @@ + +include ../revo-mini-i2c/hwdef-bl.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/revo-mini-sd/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/revo-mini-sd/hwdef.dat new file mode 100644 index 00000000000..9eb2a739fde --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/revo-mini-sd/hwdef.dat @@ -0,0 +1,40 @@ +# Revo-mini target with I2C and SD card support + +AUTOBUILD_TARGETS + +include ../revo-mini-i2c/hwdef.dat + +PA0 UART4_TX UART4 ALT(6) +PA1 UART4_RX UART4 ALT(6) + +PA15 SDCARD_CS CS + +SPIDEV sdcard SPI3 DEVID2 SDCARD_CS MODE0 400*KHZ 25*MHZ + +# disable logging to dataflash +undef HAL_LOGGING_DATAFLASH_ENABLED + +# filesystem setup on sdcard +define HAL_OS_FATFS_IO 1 +define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" +define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" + +# disable SMBUS monitors to save flash +define AP_BATTMON_SMBUS_ENABLE 0 + +# disable parachute and sprayer to save flash +define HAL_PARACHUTE_ENABLED 0 +define HAL_SPRAYER_ENABLED 0 + +# reduce max size of embedded params for apj_tool.py +define AP_PARAM_MAX_EMBEDDED_PARAM 1024 +define HAL_WITH_DSP FALSE + +# save some flash +define HAL_GENERATOR_ENABLED 0 +define AC_OAPATHPLANNER_ENABLED 0 +define PRECISION_LANDING 0 +define HAL_BARO_WIND_COMP_ENABLED 0 +define GRIPPER_ENABLED 0 +define AP_OPTICALFLOW_ENABLED 0 +define AP_ICENGINE_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H743xx.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H743xx.py index 90323a9106b..82c860195e0 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H743xx.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H743xx.py @@ -34,6 +34,16 @@ (0x38000000, 64, 1), # SRAM4. ], + # alternative RAM_MAP needed for px4 bootloader compatibility + 'ALT_RAM_MAP' : [ + (0x24000000, 512, 4), # AXI SRAM. Use this for SDMMC IDMA ops + (0x30000000, 256, 0), # SRAM1, SRAM2 + (0x20000000, 128, 2), # DTCM, tightly coupled, no DMA, fast + (0x00000400, 63, 2), # ITCM (first 1k removed, to keep address 0 unused) + (0x30040000, 32, 0), # SRAM3. + (0x38000000, 64, 1), # SRAM4. + ], + # avoid a problem in the bootloader by making DTCM first. The DCache init # when using SRAM1 as primary memory gets a hard fault in bootloader # we can't use DTCM first for main firmware as some builds overflow the first segment diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H750xx.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H750xx.py index e0e43fddcc8..1d7d9ac4334 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H750xx.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H750xx.py @@ -61,7 +61,7 @@ (0x38000000, 64, 1), # SRAM4. ], - 'EXPECTED_CLOCK' : 480000000, + 'EXPECTED_CLOCK' : 400000000, # this MCU has M7 instructions and hardware double precision 'CORTEX' : 'cortex-m7', diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H757xx.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H757xx.py index 53b571e560c..625f1f3e07d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H757xx.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32H757xx.py @@ -69,6 +69,7 @@ 'DEFINES' : { 'HAL_HAVE_HARDWARE_DOUBLE' : '1', + 'HAL_WITH_MCU_MONITORING' : '1', 'STM32H7' : '1', } } diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py index b8158c9f212..f3acfb703b1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py @@ -19,6 +19,8 @@ '-D', '--outdir', type=str, default=None, help='Output directory') parser.add_argument( '--bootloader', action='store_true', default=False, help='configure for bootloader') +parser.add_argument( + '--signed-fw', action='store_true', default=False, help='configure for signed FW') parser.add_argument( 'hwdef', type=str, nargs='+', default=None, help='hardware definition file') parser.add_argument( @@ -690,6 +692,15 @@ def enable_can(f): f.write('#define CAN1_BASE CAN_BASE\n') env_vars['HAL_NUM_CAN_IFACES'] = str(len(base_list)) + if mcu_series.startswith("STM32H7") and not args.bootloader: + # set maximum supported canfd bit rate in MBits/sec + canfd_supported = int(get_config('CANFD_SUPPORTED', 0, default=4, required=False)) + f.write('#define HAL_CANFD_SUPPORTED %d\n' % canfd_supported) + env_vars['HAL_CANFD_SUPPORTED'] = canfd_supported + else: + canfd_supported = int(get_config('CANFD_SUPPORTED', 0, default=0, required=False)) + f.write('#define HAL_CANFD_SUPPORTED %d\n' % canfd_supported) + env_vars['HAL_CANFD_SUPPORTED'] = canfd_supported def has_sdcard_spi(): '''check for sdcard connected to spi bus''' @@ -701,14 +712,24 @@ def has_sdcard_spi(): def get_ram_map(): '''get RAM_MAP. May be different for bootloader''' + env_vars['APP_RAM_START'] = None if args.bootloader: ram_map = get_mcu_config('RAM_MAP_BOOTLOADER', False) if ram_map is not None: + app_ram_map = get_mcu_config('RAM_MAP', True) + if app_ram_map[0][0] != ram_map[0][0]: + # we need to find the location of app_ram_map[0] in ram_map + for i in range(len(ram_map)): + if app_ram_map[0][0] == ram_map[i][0]: + env_vars['APP_RAM_START'] = i return ram_map elif env_vars['EXT_FLASH_SIZE_MB']: ram_map = get_mcu_config('RAM_MAP_EXTERNAL_FLASH', False) if ram_map is not None: return ram_map + elif int(env_vars.get('USE_ALT_RAM_MAP',0)) == 1: + print("Using ALT_RAM_MAP") + return get_mcu_config('ALT_RAM_MAP', True) return get_mcu_config('RAM_MAP', True) def get_flash_pages_sizes(): @@ -764,6 +785,20 @@ def get_flash_page_offset_kb(sector): offset += pages[i] return offset +def load_file_with_include(fname): + '''load a file as an array of lines, processing any include lines''' + lines = open(fname,'r').readlines() + ret = [] + for line in lines: + if line.startswith("include"): + a = shlex.split(line) + if len(a) > 1 and a[0] == "include": + fname2 = os.path.relpath(os.path.join(os.path.dirname(fname), a[1])) + ret.extend(load_file_with_include(fname2)) + continue + ret.append(line) + return ret + def get_storage_flash_page(): '''get STORAGE_FLASH_PAGE either from this hwdef or from hwdef.dat in the same directory if this is a bootloader @@ -775,7 +810,7 @@ def get_storage_flash_page(): hwdefdat = args.hwdef[0].replace("-bl", "") if os.path.exists(hwdefdat): ret = None - lines = open(hwdefdat,'r').readlines() + lines = load_file_with_include(hwdefdat) for line in lines: result = re.match(r'STORAGE_FLASH_PAGE\s*([0-9]+)', line) if result: @@ -938,20 +973,25 @@ def write_mcu_config(f): f.write('#define CRT1_RAMFUNC_ENABLE FALSE\n') storage_flash_page = get_storage_flash_page() + flash_reserve_end = get_config('FLASH_RESERVE_END_KB', default=0, type=int) if storage_flash_page is not None: if not args.bootloader: f.write('#define STORAGE_FLASH_PAGE %u\n' % storage_flash_page) validate_flash_storage_size() - else: + elif get_config('FLASH_RESERVE_END_KB', type=int, required = False) is None: # ensure the flash page leaves room for bootloader offset = get_flash_page_offset_kb(storage_flash_page) + bl_offset = get_config('FLASH_BOOTLOADER_LOAD_KB', type=int) + # storage at end of flash - leave room + if offset > bl_offset: + flash_reserve_end = flash_size - offset if flash_size >= 2048 and not args.bootloader: # lets pick a flash sector for Crash log - f.write('#define HAL_CRASHDUMP_ENABLE 1\n') + f.write('#define AP_CRASHDUMP_ENABLED 1\n') env_vars['ENABLE_CRASHDUMP'] = 1 else: - f.write('#define HAL_CRASHDUMP_ENABLE 0\n') + f.write('#define AP_CRASHDUMP_ENABLED 0\n') env_vars['ENABLE_CRASHDUMP'] = 0 if args.bootloader: @@ -961,7 +1001,7 @@ def write_mcu_config(f): 'EXT_FLASH_RESERVE_START_KB', default=0, type=int)*1024)) f.write('#define BOOT_FROM_EXT_FLASH 1\n') f.write('#define FLASH_BOOTLOADER_LOAD_KB %u\n' % get_config('FLASH_BOOTLOADER_LOAD_KB', type=int)) - f.write('#define FLASH_RESERVE_END_KB %u\n' % get_config('FLASH_RESERVE_END_KB', default=0, type=int)) + f.write('#define FLASH_RESERVE_END_KB %u\n' % flash_reserve_end) f.write('#define APP_START_OFFSET_KB %u\n' % get_config('APP_START_OFFSET_KB', default=0, type=int)) f.write('\n') @@ -971,14 +1011,21 @@ def write_mcu_config(f): cc_regions = [] total_memory = 0 for (address, size, flags) in ram_map: - regions.append('{(void*)0x%08x, 0x%08x, 0x%02x }' % (address, size*1024, flags)) cc_regions.append('{0x%08x, 0x%08x, CRASH_CATCHER_BYTE }' % (address, address + size*1024)) + if env_vars['APP_RAM_START'] is not None and address == ram_map[env_vars['APP_RAM_START']][0]: + ram_reserve_start = get_ram_reserve_start() + address += ram_reserve_start + size -= ram_reserve_start + regions.append('{(void*)0x%08x, 0x%08x, 0x%02x }' % (address, size*1024, flags)) total_memory += size f.write('#define HAL_MEMORY_REGIONS %s\n' % ', '.join(regions)) f.write('#define HAL_CC_MEMORY_REGIONS %s\n' % ', '.join(cc_regions)) f.write('#define HAL_MEMORY_TOTAL_KB %u\n' % total_memory) - f.write('#define HAL_RAM0_START 0x%08x\n' % ram_map[0][0]) + if env_vars['APP_RAM_START'] is not None: + f.write('#define HAL_RAM0_START 0x%08x\n' % ram_map[env_vars['APP_RAM_START']][0]) + else: + f.write('#define HAL_RAM0_START 0x%08x\n' % ram_map[0][0]) ram_reserve_start = get_ram_reserve_start() if ram_reserve_start > 0: f.write('#define HAL_RAM_RESERVE_START 0x%08x\n' % ram_reserve_start) @@ -1028,7 +1075,11 @@ def write_mcu_config(f): #endif ''') - if get_mcu_config('EXPECTED_CLOCK', required=True): + if get_config('MCU_CLOCKRATE_MHZ', required=False): + clockrate = int(get_config('MCU_CLOCKRATE_MHZ')) + f.write('#define HAL_CUSTOM_MCU_CLOCKRATE %u\n' % (clockrate * 1000000)) + f.write('#define HAL_EXPECTED_SYSCLOCK %u\n' % (clockrate * 1000000)) + elif get_mcu_config('EXPECTED_CLOCK', required=True): f.write('#define HAL_EXPECTED_SYSCLOCK %u\n' % get_mcu_config('EXPECTED_CLOCK')) env_vars['CORTEX'] = cortex @@ -1079,7 +1130,9 @@ def write_mcu_config(f): #define HAL_NO_TIMER_THREAD #define HAL_NO_RCOUT_THREAD #define HAL_NO_RCIN_THREAD -#define HAL_NO_SHARED_DMA FALSE +#ifndef AP_HAL_SHARED_DMA_ENABLED +#define AP_HAL_SHARED_DMA_ENABLED 0 +#endif #define HAL_NO_ROMFS_SUPPORT TRUE #define CH_CFG_USE_TM FALSE #define CH_CFG_USE_REGISTRY FALSE @@ -1097,7 +1150,7 @@ def write_mcu_config(f): #define DISABLE_SERIAL_ESC_COMM TRUE #define CH_CFG_USE_DYNAMIC FALSE ''') - if not env_vars['EXT_FLASH_SIZE_MB']: + if not env_vars['EXT_FLASH_SIZE_MB'] and not args.signed_fw: f.write(''' #define CH_CFG_USE_MEMCORE FALSE #define CH_CFG_USE_SEMAPHORES FALSE @@ -1109,6 +1162,21 @@ def write_mcu_config(f): if not args.bootloader: f.write('''#define STM32_DMA_REQUIRED TRUE\n\n''') + if args.bootloader: + # do not enable flash protection in bootloader, even if hwdef + # requests it: + f.write(''' +#undef HAL_FLASH_PROTECTION +#define HAL_FLASH_PROTECTION 0 +''') + else: + # flash protection is off by default: + f.write(''' +#ifndef HAL_FLASH_PROTECTION +#define HAL_FLASH_PROTECTION 0 +#endif +''') + def write_ldscript(fname): '''write ldscript.ld for this board''' flash_size = get_config('FLASH_USE_MAX_KB', type=int, default=0) @@ -1184,11 +1252,12 @@ def write_ldscript(fname): f = open(fname, 'w') ram0_start = ram_map[0][0] ram0_len = ram_map[0][1] * 1024 - - # possibly reserve some memory for app/bootloader comms - ram_reserve_start = get_ram_reserve_start() - ram0_start += ram_reserve_start - ram0_len -= ram_reserve_start + if env_vars['APP_RAM_START'] is None: + # default to start of ram for shared ram + # possibly reserve some memory for app/bootloader comms + ram_reserve_start = get_ram_reserve_start() + ram0_start += ram_reserve_start + ram0_len -= ram_reserve_start if ext_flash_length == 0 or args.bootloader: env_vars['HAS_EXTERNAL_FLASH_SECTIONS'] = 0 f.write('''/* generated ldscript.ld */ @@ -1255,7 +1324,11 @@ def write_USB_config(f): default_product = "%BOARD%" if args.bootloader: default_product += "-BL" - f.write('#define HAL_USB_STRING_PRODUCT %s\n' % get_config("USB_STRING_PRODUCT", default="\"%s\""%default_product)) + product_string = get_config("USB_STRING_PRODUCT", default="\"%s\""%default_product) + if args.bootloader and args.signed_fw: + product_string = product_string.replace("-BL", "-Secure-BL-v10") + f.write('#define HAL_USB_STRING_PRODUCT %s\n' % product_string) + f.write('#define HAL_USB_STRING_SERIAL %s\n' % get_config("USB_STRING_SERIAL", default="\"%SERIAL%\"")) f.write('\n\n') @@ -1378,6 +1451,14 @@ def write_QSPI_config(f): f.write('#define HAL_QSPI_BUS_LIST %s\n\n' % ','.join(devlist)) write_QSPI_table(f) +def write_check_firmware(f): + '''add AP_CHECK_FIRMWARE_ENABLED if needed''' + if env_vars.get('AP_PERIPH',0) != 0 or intdefines.get('AP_OPENDRONEID_ENABLED',0) == 1: + f.write(''' +#ifndef AP_CHECK_FIRMWARE_ENABLED +#define AP_CHECK_FIRMWARE_ENABLED 1 +#endif +''') def parse_spi_device(dev): '''parse a SPI:xxx device item''' @@ -1405,8 +1486,10 @@ def parse_i2c_device(dev): def seen_str(dev): '''return string representation of device for checking for duplicates''' - return str(dev[:2]) - + ret = dev[:2] + if dev[-1].startswith("BOARD_MATCH("): + ret.append(dev[-1]) + return str(ret) def write_IMU_config(f): '''write IMU config defines''' @@ -1426,9 +1509,14 @@ def write_IMU_config(f): (wrapper, dev[i]) = parse_i2c_device(dev[i]) n = len(devlist)+1 devlist.append('HAL_INS_PROBE%u' % n) - f.write( - '#define HAL_INS_PROBE%u %s ADD_BACKEND(AP_InertialSensor_%s::probe(*this,%s))\n' - % (n, wrapper, driver, ','.join(dev[1:]))) + if dev[-1].startswith("BOARD_MATCH("): + f.write( + '#define HAL_INS_PROBE%u %s ADD_BACKEND_BOARD_MATCH(%s, AP_InertialSensor_%s::probe(*this,%s))\n' + % (n, wrapper, dev[-1], driver, ','.join(dev[1:-1]))) + else: + f.write( + '#define HAL_INS_PROBE%u %s ADD_BACKEND(AP_InertialSensor_%s::probe(*this,%s))\n' + % (n, wrapper, driver, ','.join(dev[1:]))) if len(devlist) > 0: if len(devlist) < 3: f.write('#define INS_MAX_INSTANCES %u\n' % len(devlist)) @@ -2235,6 +2323,27 @@ def write_hwdef_header(outfilename): #define MHZ (1000U*1000U) #define KHZ (1000U) +''') + + if args.signed_fw: + f.write(''' +#define AP_SIGNED_FIRMWARE 1 +''') + else: + f.write(''' +#define AP_SIGNED_FIRMWARE 0 +''') + + enable_dfu_boot = get_config('ENABLE_DFU_BOOT', default=0) + if enable_dfu_boot: + env_vars['ENABLE_DFU_BOOT'] = 1 + f.write(''' +#define HAL_ENABLE_DFU_BOOT TRUE +''') + else: + env_vars['ENABLE_DFU_BOOT'] = 0 + f.write(''' +#define HAL_ENABLE_DFU_BOOT FALSE ''') dma_noshare.extend(get_config('DMA_NOSHARE', default='', aslist=True)) @@ -2250,6 +2359,7 @@ def write_hwdef_header(outfilename): write_AIRSPEED_config(f) write_board_validate_macro(f) add_apperiph_defaults(f) + write_check_firmware(f) write_peripheral_enable(f) @@ -2626,6 +2736,9 @@ def process_line(line): bylabel.pop(u, '') alttype.pop(u, '') altlabel.pop(u, '') + for dev in spidev: + if u == dev[0]: + spidev.remove(dev) # also remove all occurences of defines in previous lines if any for line in alllines[:]: if line.startswith('define') and u == line.split()[1]: @@ -2683,21 +2796,20 @@ def add_apperiph_defaults(f): # not AP_Periph return - if not args.bootloader: - # use the app descriptor needed by MissionPlanner for CAN upload - env_vars['APP_DESCRIPTOR'] = 'MissionPlanner' - print("Setting up as AP_Periph") f.write(''' #ifndef HAL_SCHEDULER_ENABLED #define HAL_SCHEDULER_ENABLED 0 #endif + #ifndef HAL_LOGGING_ENABLED #define HAL_LOGGING_ENABLED 0 #endif + #ifndef HAL_GCS_ENABLED #define HAL_GCS_ENABLED 0 #endif + // default to no protocols, AP_Periph enables with params #define HAL_SERIAL1_PROTOCOL -1 #define HAL_SERIAL2_PROTOCOL -1 @@ -2707,17 +2819,22 @@ def add_apperiph_defaults(f): #ifndef HAL_LOGGING_MAVLINK_ENABLED #define HAL_LOGGING_MAVLINK_ENABLED 0 #endif -#ifndef HAL_MISSION_ENABLED -#define HAL_MISSION_ENABLED 0 + +#ifndef AP_MISSION_ENABLED +#define AP_MISSION_ENABLED 0 #endif + #ifndef HAL_RALLY_ENABLED #define HAL_RALLY_ENABLED 0 #endif + #ifndef HAL_CAN_DEFAULT_NODE_ID #define HAL_CAN_DEFAULT_NODE_ID 0 #endif + #define PERIPH_FW TRUE #define HAL_BUILD_AP_PERIPH + #ifndef HAL_WATCHDOG_ENABLED_DEFAULT #define HAL_WATCHDOG_ENABLED_DEFAULT true #endif @@ -2725,14 +2842,89 @@ def add_apperiph_defaults(f): #ifndef AP_FETTEC_ONEWIRE_ENABLED #define AP_FETTEC_ONEWIRE_ENABLED 0 #endif + #ifndef HAL_BARO_WIND_COMP_ENABLED #define HAL_BARO_WIND_COMP_ENABLED 0 +#endif #ifndef HAL_UART_STATS_ENABLED #define HAL_UART_STATS_ENABLED (HAL_GCS_ENABLED || HAL_LOGGING_ENABLED) #endif +#ifndef AP_AIRSPEED_AUTOCAL_ENABLE +#define AP_AIRSPEED_AUTOCAL_ENABLE 0 +#endif + +#ifndef AP_VOLZ_ENABLED +#define AP_VOLZ_ENABLED 0 +#endif + +#ifndef AP_ROBOTISSERVO_ENABLED +#define AP_ROBOTISSERVO_ENABLED 0 +#endif + +#ifndef AP_STATS_ENABLED +#define AP_STATS_ENABLED 0 +#endif + +/* + * GPS Backends - we selectively turn backends on. + * Note also that f103-GPS explicitly disables some of these backends. + */ +#define AP_GPS_BACKEND_DEFAULT_ENABLED 0 + +#ifndef AP_GPS_ERB_ENABLED +#define AP_GPS_ERB_ENABLED 0 +#endif + +#ifndef AP_GPS_GSOF_ENABLED +#define AP_GPS_GSOF_ENABLED defined(HAL_PERIPH_ENABLE_GPS) #endif + +#ifndef AP_GPS_NMEA_ENABLED +#define AP_GPS_NMEA_ENABLED 0 +#endif + +#ifndef AP_GPS_SBF_ENABLED +#define AP_GPS_SBF_ENABLED defined(HAL_PERIPH_ENABLE_GPS) +#endif + +#ifndef AP_GPS_SBP_ENABLED +#define AP_GPS_SBP_ENABLED 0 +#endif + +#ifndef AP_GPS_SBP2_ENABLED +#define AP_GPS_SBP2_ENABLED 0 +#endif + +#ifndef AP_GPS_SIRF_ENABLED +#define AP_GPS_SIRF_ENABLED 0 +#endif + +#ifndef AP_GPS_MAV_ENABLED +#define AP_GPS_MAV_ENABLED 0 +#endif + +#ifndef AP_GPS_NOVA_ENABLED +#define AP_GPS_NOVA_ENABLED defined(HAL_PERIPH_ENABLE_GPS) +#endif + +#ifndef HAL_SIM_GPS_ENABLED +#define HAL_SIM_GPS_ENABLED (AP_SIM_ENABLED && defined(HAL_PERIPH_ENABLE_GPS)) +#endif + +/* + * Airspeed Backends - we selectively turn backends *off* + */ +#ifndef AP_AIRSPEED_ANALOG_ENABLED +#define AP_AIRSPEED_ANALOG_ENABLED 0 +#endif + +// disable various rangefinder backends +#define AP_RANGEFINDER_ANALOG_ENABLED 0 +#define AP_RANGEFINDER_HC_SR04_ENABLED 0 +#define AP_RANGEFINDER_PWM_ENABLED 0 + ''') @@ -2763,6 +2955,7 @@ def add_apperiph_defaults(f): write_ldscript(os.path.join(outdir, "ldscript.ld")) romfs_add_dir(['scripts']) +romfs_add_dir(['param']) write_ROMFS(outdir) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-f412-rev1/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-f412-rev1/hwdef.dat index 65de1ed0b7b..7d51457fc9b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-f412-rev1/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-f412-rev1/hwdef.dat @@ -6,6 +6,9 @@ MCU STM32F4xx STM32F412Rx # board ID for firmware load APJ_BOARD_ID 9 +# short board name override (13 chars) to match original max length; can't change because name is used for transmitter bind CRC +define CHIBIOS_SHORT_BOARD_NAME "skyviper-f412" + # crystal frequency OSCILLATOR_HZ 24000000 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-journey/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-journey/defaults.parm index 375c5df8ec0..701276db1f3 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-journey/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-journey/defaults.parm @@ -126,10 +126,10 @@ DISARM_DELAY 8 INS_FAST_SAMPLE 0 INS_GYRO_FILTER 20 LOG_BITMASK 65534 -INS_NOTCH_ENABLE 1 -INS_NOTCH_ATT 50 -INS_NOTCH_BW 80 -INS_NOTCH_FREQ 80 +INS_HNTC2_ENABLE 1 +INS_HNTC2_ATT 50 +INS_HNTC2_BW 80 +INS_HNTC2_FREQ 80 # profile parameters TMODE_P1_ANG_MAX 2500 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-journey/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-journey/hwdef.dat index e30d74f8f54..eddb9ad0393 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-journey/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-journey/hwdef.dat @@ -6,6 +6,9 @@ MCU STM32F4xx STM32F412Rx # board ID for firmware load APJ_BOARD_ID 9 +# short board name override (13 chars) to match original max length; can't change because name is used for transmitter bind CRC +define CHIBIOS_SHORT_BOARD_NAME "skyviper-jour" + # crystal frequency OSCILLATOR_HZ 24000000 @@ -128,3 +131,5 @@ define AP_PARAM_MAX_EMBEDDED_PARAM 8192 # Disable un-needed hardware drivers define HAL_WITH_ESC_TELEM 0 define AP_FETTEC_ONEWIRE_ENABLED 0 + +AUTOBUILD_TARGETS Copter diff --git a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat index ce2aa4eeb29..f47378b9234 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat @@ -27,6 +27,9 @@ undef SDIO undef HAL_BOARD_LOG_DIRECTORY undef HAL_BOARD_TERRAIN_DIRECTORY +# short board name override (13 chars) to match original max length; can't change because name is used for transmitter bind CRC +define CHIBIOS_SHORT_BOARD_NAME "skyviper-v245" + SERIAL_ORDER OTG1 USART2 EMPTY UART4 # enable AP_Radio support @@ -67,15 +70,13 @@ env BUILD_ABIN True # Disable un-needed hardware drivers define AP_AIRSPEED_ENABLED 0 -define AP_FETTEC_ONEWIRE_ENABLED 0 define AP_OPTICALFLOW_ENABLED 0 define BEACON_ENABLED 0 define GPS_MOVING_BASELINE 0 define GRIPPER_ENABLED 0 define HAL_ADSB_SAGETECH_ENABLED 0 define HAL_ADSB_UAVIONIX_MAVLINK_ENABLED 0 -define HAL_AIS_ENABLED 0 -define AP_BATTMON_FUEL_ENABLE 0 +define AP_AIS_ENABLED 0 define HAL_BATTMON_INA2XX_ENABLED 0 define AP_BATTMON_SMBUS_ENABLE 0 define HAL_CRSF_TELEM_ENABLED 0 @@ -92,13 +93,22 @@ define HAL_RUNCAM_ENABLED 0 define HAL_SMARTAUDIO_ENABLED 0 define HAL_SPEKTRUM_TELEM_ENABLED 0 define HAL_SPRAYER_ENABLED 0 -define HAL_SUPPORT_RCOUT_SERIAL 0 -define HAL_TORQEEDO_ENABLED 0 -define HAL_WITH_ESC_TELEM 0 define HAL_WITH_ESC_TELEM 0 define LANDING_GEAR_ENABLED 0 define MODE_TURTLE_ENABLED 0 define WINCH_ENABLED 0 +define AP_ICENGINE_ENABLED 0 + +# serially-attached actuators aren't relevant on SkyViper: +define AP_FETTEC_ONEWIRE_ENABLED 0 +define AP_ROBOTISSERVO_ENABLED 0 +define AP_VOLZ_ENABLED 0 +define HAL_SUPPORT_RCOUT_SERIAL 0 +define HAL_TORQEEDO_ENABLED 0 + +# the SkyViper only has a single Baro: +define AP_BARO_BACKEND_DEFAULT_ENABLED 0 +define AP_BARO_ICM20789_ENABLED 1 # SkyViper has only one physical GPS but can also take from mavlink: define AP_GPS_BACKEND_DEFAULT_ENABLED 0 @@ -113,3 +123,9 @@ define AP_MOTORS_FRAME_QUAD_ENABLED 1 define COMPASS_MAX_SENSORS 1 define BARO_MAX_INSTANCES 1 define INS_MAX_INSTANCES 1 + +# SkyViper doesn't have any rangefinder, but might get mavlink? +define AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED 0 +define AP_RANGEFINDER_MAVLINK_ENABLED 1 + +AUTOBUILD_TARGETS Copter diff --git a/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4/hwdef.dat index e0048a9b3f8..9141e7602c4 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4/hwdef.dat @@ -145,3 +145,6 @@ define HAL_LOGGING_DATAFLASH_ENABLED 1 define OSD_ENABLED 1 define HAL_OSD_TYPE_DEFAULT 1 ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin + +# minimal drivers to reduce flash usage +include ../include/minimal.inc diff --git a/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v3/README.md b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v3/README.md new file mode 100644 index 00000000000..ac8a8f12533 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v3/README.md @@ -0,0 +1,98 @@ +# SpeedyBee F405 v3 Flight Controller + +The SpeedyBee F405 v3 is a flight controller produced by [SpeedyBee](http://www.speedybee.com/). + +## Features + + - STM32F405 microcontroller + - BMI270 IMU + - DPS280 barometer + - SDCard + - AT7456E OSD + - 6 UARTs + - 9 PWM outputs + +## Pinout + +![SpeedyBee F405 v3](SpeedyBee_F405_v3_Board_Top.JPG "SpeedyBee F405 v3") +![SpeedyBee F405 v3](SpeedyBee_F405_v3_Board_Bottom.JPG "SpeedyBee F405 v3") + +## UART Mapping + +The UARTs are marked Rn and Tn in the above pinouts. The Rn pin is the +receive pin for UARTn. The Tn pin is the transmit pin for UARTn. + + - SERIAL0 -> USB + - SERIAL1 -> UART1 (DJI-VTX, DMA-enabled) + - SERIAL2 -> UART2 (RCIN, DMA-enabled) + - SERIAL3 -> UART3 (CAM) + - SERIAL4 -> UART4 (connected to internal BT module, not currently usable by ArduPilot) + - SERIAL5 -> UART5 (ESC Telemetry) + - SERIAL6 -> UART6 (GPS, DMA-enabled) + +## RC Input + +RC input is configured on the R2 (UART2_RX) pin for most RC unidirectional protocols except SBUS which should be applied at the SBUS pin. PPM is not supported. +For Fport, a bi-directional inverter will be required. See https://ardupilot.org/plane/docs/common-connecting-sport-fport.html +For CRSF/ELRS/SRXL2 connection of the receiver to T2 will also be required. + +## FrSky Telemetry + +FrSky Telemetry is supported using the Tx pin of any UART including SERIAL2/UART2. You need to set the following parameters to enable support for FrSky S.PORT (example shows SERIAL3). + + - SERIAL3_PROTOCOL 10 + - SERIAL3_OPTIONS 7 + +## OSD Support + +The SpeedyBee F405 v3 supports OSD using OSD_TYPE 1 (MAX7456 driver). + +## VTX Support + +The JST-GH-6P connector supports a standard DJI HD VTX connection. Pin 1 of the connector is 9v so be careful not to connect +this to a peripheral requiring 5v. + +## PWM Output + +The SpeedyBee F405 v3 supports up to 9 PWM outputs. The pads for motor output +M1 to M4 on the motor connector, plus M9 for LED strip or another +PWM output. + +The PWM is in 3 groups: + + - PWM 1-4 in group1 + - PWM 5-8 in group2 + - PWM 9 in group3 + +Channels within the same group need to use the same output rate. If +any channel in a group uses DShot then all channels in the group need +to use DShot. Channels 1-4 support bi-directional DShot. + +## Battery Monitoring + +The board has a internal voltage sensor and connections on the ESC connector for an external current sensor input. +The voltage sensor can handle up to 6S. +LiPo batteries. + +The default battery parameters are: + + - BATT_MONITOR 4 + - BATT_VOLT_PIN 10 + - BATT_CURR_PIN 11 + - BATT_VOLT_MULT 11.2 + - BATT_AMP_PERVLT 52.7 (will need to be adjusted for whichever current sensor is attached) + +## Compass + +The SpeedyBee F405 v3 does not have a builtin compass, but you can attach an external compass using I2C on the SDA and SCL pads. + +## Loading Firmware + +Initial firmware load can be done with DFU by plugging in USB with the +bootloader button pressed. Then you should load the "with_bl.hex" +firmware, using your favourite DFU loading tool. + +Once the initial firmware is loaded you can update the firmware using +any ArduPilot ground station software. Updates should be done with the +*.apj firmware files. + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v3/SpeedyBee_F405_v3_Board_Bottom.JPG b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v3/SpeedyBee_F405_v3_Board_Bottom.JPG new file mode 100644 index 00000000000..cb60e4f6908 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v3/SpeedyBee_F405_v3_Board_Bottom.JPG differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v3/SpeedyBee_F405_v3_Board_Top.JPG b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v3/SpeedyBee_F405_v3_Board_Top.JPG new file mode 100644 index 00000000000..86b76deb621 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v3/SpeedyBee_F405_v3_Board_Top.JPG differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v3/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v3/defaults.parm new file mode 100644 index 00000000000..ea0adaf59c3 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v3/defaults.parm @@ -0,0 +1,2 @@ +SERVO9_FUNCTION 120 +NTF_LED_TYPES 257 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v3/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v3/hwdef-bl.dat new file mode 100644 index 00000000000..658ee1b32f0 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v3/hwdef-bl.dat @@ -0,0 +1,39 @@ +# hw definition file for processing by chibios_pins.py +# for speedybeef4 bootloader + +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +# board ID for firmware load +APJ_BOARD_ID 1082 + +# crystal frequency +OSCILLATOR_HZ 8000000 + +FLASH_SIZE_KB 1024 + +# don't allow bootloader to use more than 16k +FLASH_USE_MAX_KB 16 + +# bootloader is installed at zero offset +FLASH_RESERVE_START_KB 0 + +# the location where the bootloader will put the firmware +FLASH_BOOTLOADER_LOAD_KB 48 + +# LEDs +PC8 LED_BOOTLOADER OUTPUT LOW +define HAL_LED_ON 0 + +# order of UARTs +SERIAL_ORDER OTG1 + +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +DEFAULTGPIO OUTPUT LOW PULLDOWN + +# Add CS pins to ensure they are high in bootloader +PA4 MPU6000_CS CS +PB12 MAX7456_CS CS +PA15 SDCARD_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v3/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v3/hwdef.dat new file mode 100644 index 00000000000..6bb549c6e41 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v3/hwdef.dat @@ -0,0 +1,157 @@ +# hw definition file for SpeedyBee F4 v3 hardware +# tested on the Speedybee F4 v3 board +# with thanks to betaflight for pinout + +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +# board ID for firmware load +APJ_BOARD_ID 1082 + +# crystal frequency +OSCILLATOR_HZ 8000000 + +define STM32_ST_USE_TIMER 5 + +FLASH_SIZE_KB 1024 + +# only one I2C bus +I2C_ORDER I2C2 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART5 USART6 + +# LEDs +PC8 LED_BLUE OUTPUT LOW GPIO(0) + +define HAL_GPIO_A_LED_PIN 0 + +# buzzer +PC5 BUZZER OUTPUT GPIO(80) LOW +define HAL_BUZZER_PIN 80 +define HAL_BUZZER_ON 1 +define HAL_BUZZER_OFF 0 + +# spi1 bus for IMU +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 +PA4 BMI270_CS CS + +# spi2 for OSD and sdcard +PB13 SPI2_SCK SPI2 +PB14 SPI2_MISO SPI2 +PB15 SPI2_MOSI SPI2 +PB12 MAX7456_CS CS +PA15 SDCARD_CS CS + +# only one I2C bus in normal config +PB10 I2C2_SCL I2C2 +PB11 I2C2_SDA I2C2 + +# analog pins +PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PC1 BATT_CURRENT_SENS ADC1 SCALE(1) +PC2 RSSI_ADC_PIN ADC1 SCALE(1) + +# define default battery setup +define HAL_BATT_MONITOR_DEFAULT 4 +define HAL_BATT_VOLT_PIN 10 +define HAL_BATT_CURR_PIN 11 +define HAL_BATT_VOLT_SCALE 11.2 # matched to ESC output +define HAL_BATT_CURR_SCALE 52.7 # appropriate for a T-Motor F55A Pro II + +# analog rssi pin +define BOARD_RSSI_ANA_PIN 12 + +# USART1 (DJI / VTX) +PA9 USART1_TX USART1 +PA10 USART1_RX USART1 +define HAL_SERIAL1_PROTOCOL SerialProtocol_DJI_FPV + +# USART2 (RCIN) +PA2 USART2_TX USART2 +PA3 USART2_RX USART2 +define HAL_SERIAL2_PROTOCOL SerialProtocol_RCIN + +# USART3 (CAM) +PC10 USART3_TX USART3 NODMA +PC11 USART3_RX USART3 NODMA +define HAL_SERIAL3_PROTOCOL SerialProtocol_None + +# UART4 (Bluetooth) +PA0 UART4_TX UART4 NODMA +PA1 UART4_RX UART4 NODMA +define HAL_SERIAL4_PROTOCOL SerialProtocol_None + +# UART5 (ESC Telemetry) +PC12 UART5_TX UART5 NODMA +PD2 UART5_RX UART5 NODMA +define HAL_SERIAL5_PROTOCOL SerialProtocol_ESCTelemetry +define HAL_SERIAL5_BAUD 19200 + +# UART6 (GPS) +PC6 USART6_TX USART6 +PC7 USART6_RX USART6 +define HAL_SERIAL6_PROTOCOL SerialProtocol_GPS +define HAL_SERIAL6_BAUD AP_SERIALMANAGER_GPS_BAUD + +# PA10 IO-debug-console +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# PWM out pins. Note that channel order follows the ArduPilot motor +# order conventions +PB6 TIM4_CH1 TIM4 PWM(1) GPIO(50) BIDIR +PB7 TIM4_CH2 TIM4 PWM(2) GPIO(51) +PB8 TIM4_CH3 TIM4 PWM(3) GPIO(52) BIDIR # DMA channel shared with I2C2_TX, beware - no alternatives +PB9 TIM4_CH4 TIM4 PWM(4) GPIO(53) +PB0 TIM3_CH3 TIM3 PWM(5) GPIO(54) +PB1 TIM3_CH4 TIM3 PWM(6) GPIO(55) +PB5 TIM3_CH2 TIM3 PWM(7) GPIO(56) +PB4 TIM3_CH1 TIM3 PWM(8) GPIO(57) +PC9 TIM8_CH4 TIM8 PWM(9) GPIO(58) # LED + +# OSD pad for TTL based OSD control, not supported by AP +PB3 CAM_C OUTPUT LOW GPIO(83) # labelled as "CC" + +define HAL_STORAGE_SIZE 15360 +STORAGE_FLASH_PAGE 1 + +# reserve 16k for bootloader and 32k for flash storage +FLASH_RESERVE_START_KB 48 + +# one IMU +IMU BMI270 SPI:bmi270 ROTATION_ROLL_180 + +# built-in barometer +BARO SPL06 I2C:0:0x76 +define AP_BARO_BACKEND_DEFAULT_ENABLED 0 +define AP_BARO_SPL06_ENABLED 1 + +# no built-in compass, but probe the i2c bus for all possible +# external compass types +define ALLOW_ARM_NO_COMPASS +define HAL_PROBE_EXTERNAL_I2C_COMPASSES +define HAL_I2C_INTERNAL_MASK 0 + +# Motor order implies Betaflight/X for standard ESCs +define HAL_FRAME_TYPE_DEFAULT 12 + +# SPI devices +SPIDEV bmi270 SPI1 DEVID1 BMI270_CS MODE3 1*MHZ 8*MHZ +SPIDEV osd SPI2 DEVID1 MAX7456_CS MODE0 10*MHZ 10*MHZ +SPIDEV sdcard SPI2 DEVID2 SDCARD_CS MODE0 400*KHZ 25*MHZ + +# filesystem setup on sdcard +define HAL_OS_FATFS_IO 1 +define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" +define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" + +# setup for OSD +define OSD_ENABLED 1 +define HAL_OSD_TYPE_DEFAULT 1 +ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin + +# minimal drivers to reduce flash usage +include ../include/minimal.inc diff --git a/libraries/AP_HAL_ChibiOS/shared_dma.cpp b/libraries/AP_HAL_ChibiOS/shared_dma.cpp index c9f4c98e929..2f6c8c7be88 100644 --- a/libraries/AP_HAL_ChibiOS/shared_dma.cpp +++ b/libraries/AP_HAL_ChibiOS/shared_dma.cpp @@ -22,7 +22,7 @@ code to handle sharing of DMA channels between peripherals */ -#if CH_CFG_USE_MUTEXES == TRUE && !defined(HAL_NO_SHARED_DMA) +#if CH_CFG_USE_MUTEXES == TRUE && AP_HAL_SHARED_DMA_ENABLED #include diff --git a/libraries/AP_HAL_ChibiOS/shared_dma.h b/libraries/AP_HAL_ChibiOS/shared_dma.h index 7bd05708314..0157c399b72 100644 --- a/libraries/AP_HAL_ChibiOS/shared_dma.h +++ b/libraries/AP_HAL_ChibiOS/shared_dma.h @@ -23,7 +23,7 @@ // DMA stream ID for stream_id2 when only one is needed #define SHARED_DMA_NONE 255 -#ifndef HAL_NO_SHARED_DMA +#if AP_HAL_SHARED_DMA_ENABLED class ChibiOS::Shared_DMA { @@ -114,4 +114,4 @@ class ChibiOS::Shared_DMA } *_contention_stats; }; -#endif // HAL_NO_SHARED_DMA +#endif // AP_HAL_SHARED_DMA_ENABLED diff --git a/libraries/AP_HAL_ChibiOS/system.cpp b/libraries/AP_HAL_ChibiOS/system.cpp index b4b3b3b4c7d..e14b0400e12 100644 --- a/libraries/AP_HAL_ChibiOS/system.cpp +++ b/libraries/AP_HAL_ChibiOS/system.cpp @@ -23,7 +23,7 @@ #include "hwdef/common/watchdog.h" #include "hwdef/common/stm32_util.h" #include -#if HAL_CRASHDUMP_ENABLE +#if AP_CRASHDUMP_ENABLED #include #endif #include @@ -52,7 +52,7 @@ extern "C" { #define bkpt() __asm volatile("BKPT #0\n") -#if !HAL_CRASHDUMP_ENABLE +#if !AP_CRASHDUMP_ENABLED // do legacy hardfault handling void HardFault_Handler(void); void HardFault_Handler(void) { @@ -240,6 +240,28 @@ void __cxa_pure_virtual() { while (1); } //TODO: Handle properly, maybe generate void NMI_Handler(void); void NMI_Handler(void) { while (1); } +#if defined(HAL_BOOTLOADER_BUILD) && HAL_ENABLE_DFU_BOOT +void __entry_hook(void); +void __entry_hook() +{ + // read the persistent data + AP_HAL::Util::PersistentData pd; + stm32_watchdog_load((uint32_t *)&pd, (sizeof(pd)+3)/4); + if (pd.boot_to_dfu) { + pd.boot_to_dfu = false; + stm32_watchdog_save((uint32_t *)&pd, (sizeof(pd)+3)/4); +#if defined(STM32H7) + const uint32_t *app_base = (const uint32_t *)(0x1FF09800); +#else + const uint32_t *app_base = (const uint32_t *)(0x1FFF0000); +#endif + __set_MSP(*app_base); + ((void (*)())*(&app_base[1]))(); + while(true); + } +} +#endif + } namespace AP_HAL { diff --git a/libraries/AP_HAL_ESP32/AnalogIn.cpp b/libraries/AP_HAL_ESP32/AnalogIn.cpp index 95ced8ef9ad..0cb88f3e173 100644 --- a/libraries/AP_HAL_ESP32/AnalogIn.cpp +++ b/libraries/AP_HAL_ESP32/AnalogIn.cpp @@ -179,7 +179,7 @@ bool AnalogSource::set_pin(uint8_t ardupin) int8_t pinconfig_offset = AnalogIn::find_pinconfig(ardupin); if (pinconfig_offset == -1 ) { - hal.console->printf("AnalogIn: sorry set_pin() can't determine ADC1 offset from ardupin : %d \n",ardupin); + DEV_PRINTF("AnalogIn: sorry set_pin() can't determine ADC1 offset from ardupin : %d \n",ardupin); return false; } @@ -208,7 +208,7 @@ bool AnalogSource::set_pin(uint8_t ardupin) esp_adc_cal_characterize(ADC_UNIT_1, atten, ADC_WIDTH_BIT_12, DEFAULT_VREF, &adc_chars); printf("AnalogIn: Adding gpio on: %d\n", gpio); - hal.console->printf("AnalogIn: set_pin() FROM (ardupin:%d adc1_offset:%d gpio:%d) TO (ardupin:%d adc1_offset:%d gpio:%d)\n", \ + DEV_PRINTF("AnalogIn: set_pin() FROM (ardupin:%d adc1_offset:%d gpio:%d) TO (ardupin:%d adc1_offset:%d gpio:%d)\n", \ _ardupin,_pin,_gpio,ardupin,newgpioAdcPin,gpio); _pin = newgpioAdcPin; _ardupin = ardupin; @@ -336,7 +336,7 @@ AP_HAL::AnalogSource *AnalogIn::channel(int16_t ardupin) float scaler = -1; if ((ardupin != ANALOG_INPUT_NONE) && (pinconfig_offset == -1 )) { - hal.console->printf("AnalogIn: sorry channel() can't determine ADC1 offset from ardupin : %d \n",ardupin); + DEV_PRINTF("AnalogIn: sorry channel() can't determine ADC1 offset from ardupin : %d \n",ardupin); ardupin = ANALOG_INPUT_NONE; // default it to this not terrible value and allow to continue } // although ANALOG_INPUT_NONE=255 is not a valid pin, we let it through here as @@ -351,18 +351,18 @@ AP_HAL::AnalogSource *AnalogIn::channel(int16_t ardupin) _channels[j] = new AnalogSource(ardupin,gpioAdcPin, scaler,0.0f,1); if (ardupin != ANALOG_INPUT_NONE) { - hal.console->printf("AnalogIn: channel:%d attached to ardupin:%d at adc1_offset:%d on gpio:%d\n",\ + DEV_PRINTF("AnalogIn: channel:%d attached to ardupin:%d at adc1_offset:%d on gpio:%d\n",\ j,ardupin, gpioAdcPin, _channels[j]->_gpio); } if (ardupin == ANALOG_INPUT_NONE) { - hal.console->printf("AnalogIn: channel:%d created but using delayed adc and gpio pin configuration\n",j ); + DEV_PRINTF("AnalogIn: channel:%d created but using delayed adc and gpio pin configuration\n",j ); } return _channels[j]; } } - hal.console->printf("AnalogIn: out of channels\n"); + DEV_PRINTF("AnalogIn: out of channels\n"); return nullptr; } diff --git a/libraries/AP_HAL_ESP32/RCOutput.h b/libraries/AP_HAL_ESP32/RCOutput.h index 9e3bb3d8b46..cf70a8fb89d 100644 --- a/libraries/AP_HAL_ESP32/RCOutput.h +++ b/libraries/AP_HAL_ESP32/RCOutput.h @@ -86,7 +86,7 @@ class RCOutput : public AP_HAL::RCOutput /* set safety mask for IOMCU */ - void set_safety_mask(uint16_t mask) + void set_safety_mask(uint32_t mask) { safety_mask = mask; } @@ -126,7 +126,7 @@ class RCOutput : public AP_HAL::RCOutput uint8_t safety_press_count; // 0.1s units // mask of channels to allow when safety on - uint16_t safety_mask; + uint32_t safety_mask; // update safety switch and LED void safety_update(void); diff --git a/libraries/AP_HAL_ESP32/Storage.cpp b/libraries/AP_HAL_ESP32/Storage.cpp index 61faf15fb27..2cb71f73d3f 100644 --- a/libraries/AP_HAL_ESP32/Storage.cpp +++ b/libraries/AP_HAL_ESP32/Storage.cpp @@ -156,7 +156,7 @@ bool Storage::_flash_write_data(uint8_t sector, uint32_t offset, const uint8_t * if (now - _last_re_init_ms > 5000) { _last_re_init_ms = now; bool ok = _flash.re_initialise(); - hal.console->printf("Storage: failed at %u:%u for %u - re-init %u\n", + DEV_PRINTF("Storage: failed at %u:%u for %u - re-init %u\n", (unsigned)sector, (unsigned)offset, (unsigned)length, (unsigned)ok); #ifdef STORAGEDEBUG printf("Storage: failed at %u:%u for %u - re-init %u\n", diff --git a/libraries/AP_HAL_ESP32/Util.cpp b/libraries/AP_HAL_ESP32/Util.cpp index 013d241617d..26bcdffa11a 100644 --- a/libraries/AP_HAL_ESP32/Util.cpp +++ b/libraries/AP_HAL_ESP32/Util.cpp @@ -214,7 +214,7 @@ Util::FlashBootloader Util::flash_bootloader() */ -bool Util::get_system_id(char buf[40]) +bool Util::get_system_id(char buf[50]) { //uint8_t serialid[12]; char board_name[14] = "esp32-buzz "; diff --git a/libraries/AP_HAL_ESP32/Util.h b/libraries/AP_HAL_ESP32/Util.h index 93ae6fe69d7..c4039cdcef9 100644 --- a/libraries/AP_HAL_ESP32/Util.h +++ b/libraries/AP_HAL_ESP32/Util.h @@ -51,7 +51,7 @@ class ESP32::Util : public AP_HAL::Util enum safety_state safety_switch_state(void) override; // get system ID as a string - bool get_system_id(char buf[40]) override; + bool get_system_id(char buf[50]) override; bool get_system_id_unformatted(uint8_t buf[], uint8_t &len) override; #ifdef HAL_PWM_ALARM diff --git a/libraries/AP_HAL_ESP32/targets/partitions.csv b/libraries/AP_HAL_ESP32/targets/partitions.csv index d245f35d50e..70f23f3af89 100644 --- a/libraries/AP_HAL_ESP32/targets/partitions.csv +++ b/libraries/AP_HAL_ESP32/targets/partitions.csv @@ -1,5 +1,5 @@ # Name, Type, SubType, Offset, Size nvs, data, nvs, , 0x6000 phy_init, data, phy, , 0x1000 -factory, app, factory, , 2M +factory, app, factory, , 3M storage, 0x45, 0x0, , 128K diff --git a/libraries/AP_HAL_Empty/DSP.h b/libraries/AP_HAL_Empty/DSP.h index 0dc5b62e3e3..708a367e9ab 100644 --- a/libraries/AP_HAL_Empty/DSP.h +++ b/libraries/AP_HAL_Empty/DSP.h @@ -21,12 +21,13 @@ class Empty::DSP : public AP_HAL::DSP { #if HAL_WITH_DSP public: - virtual FFTWindowState* fft_init(uint16_t window_size, uint16_t sample_rate) override { return nullptr; } + virtual FFTWindowState* fft_init(uint16_t window_size, uint16_t sample_rate, uint8_t sliding_window_size) override { return nullptr; } virtual void fft_start(FFTWindowState* state, FloatBuffer& samples, uint16_t advance) override {} virtual uint16_t fft_analyse(FFTWindowState* state, uint16_t start_bin, uint16_t end_bin, float noise_att_cutoff) override { return 0; } protected: virtual void vector_max_float(const float* vin, uint16_t len, float* maxValue, uint16_t* maxIndex) const override {} virtual void vector_scale_float(const float* vin, float scale, float* vout, uint16_t len) const override {} virtual float vector_mean_float(const float* vin, uint16_t len) const override { return 0.0f; }; + virtual void vector_add_float(const float* vin1, const float* vin2, float* vout, uint16_t len) const override {}; #endif // HAL_WITH_DSP }; diff --git a/libraries/AP_HAL_Empty/Scheduler.cpp b/libraries/AP_HAL_Empty/Scheduler.cpp deleted file mode 100644 index 76d3746a5b0..00000000000 --- a/libraries/AP_HAL_Empty/Scheduler.cpp +++ /dev/null @@ -1,36 +0,0 @@ - -#include "Scheduler.h" - -#include - -using namespace Empty; - -extern const AP_HAL::HAL& hal; - -Scheduler::Scheduler() -{} - -void Scheduler::init() -{} - -void Scheduler::delay(uint16_t ms) -{} - -void Scheduler::delay_microseconds(uint16_t us) -{} - -void Scheduler::register_timer_process(AP_HAL::MemberProc k) -{} - -void Scheduler::register_io_process(AP_HAL::MemberProc k) -{} - -void Scheduler::register_timer_failsafe(AP_HAL::Proc, uint32_t period_us) -{} - -void Scheduler::set_system_initialized() -{} - -void Scheduler::reboot(bool hold_in_bootloader) { - for(;;); -} diff --git a/libraries/AP_HAL_Empty/Scheduler.h b/libraries/AP_HAL_Empty/Scheduler.h index 740fc737de1..66c44669e2c 100644 --- a/libraries/AP_HAL_Empty/Scheduler.h +++ b/libraries/AP_HAL_Empty/Scheduler.h @@ -4,18 +4,18 @@ class Empty::Scheduler : public AP_HAL::Scheduler { public: - Scheduler(); - void init() override; - void delay(uint16_t ms) override; - void delay_microseconds(uint16_t us) override; - void register_timer_process(AP_HAL::MemberProc) override; - void register_io_process(AP_HAL::MemberProc) override; + Scheduler() {} + void init() override {} + void delay(uint16_t ms) override {} + void delay_microseconds(uint16_t us) override {} + void register_timer_process(AP_HAL::MemberProc) override {} + void register_io_process(AP_HAL::MemberProc) override {} - void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us) override; + void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us) override {} - void set_system_initialized() override; + void set_system_initialized() override {} bool is_system_initialized() override { return true; } - void reboot(bool hold_in_bootloader) override; + void reboot(bool hold_in_bootloader) override { for (;;); } }; diff --git a/libraries/AP_HAL_Linux/GPIO.h b/libraries/AP_HAL_Linux/GPIO.h index c63cb4c026e..0281c14be6e 100644 --- a/libraries/AP_HAL_Linux/GPIO.h +++ b/libraries/AP_HAL_Linux/GPIO.h @@ -28,9 +28,10 @@ class DigitalSource : public AP_HAL::DigitalSource { CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH || \ CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DARK || \ CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXFMINI || \ - CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIGATOR || \ CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_OBAL_V1 #include "GPIO_RPI.h" +#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIGATOR +#include "GPIO_Navigator.h" #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO #include "GPIO_Navio.h" #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO2 diff --git a/libraries/AP_HAL_Linux/GPIO_Navigator.cpp b/libraries/AP_HAL_Linux/GPIO_Navigator.cpp new file mode 100644 index 00000000000..0c92e9fdbce --- /dev/null +++ b/libraries/AP_HAL_Linux/GPIO_Navigator.cpp @@ -0,0 +1,47 @@ +#include "GPIO_Navigator.h" + +uint8_t GPIO_Navigator::read(uint8_t pin) +{ + if (pinAllowed(pin)) { + return GPIO_RPI::read(pin); + } + if (hal.rcout->supports_gpio()) { + return (uint8_t)hal.rcout->read(pin - 1); + } + return 0; +} + +void GPIO_Navigator::write(uint8_t pin, uint8_t value) +{ + if (pinAllowed(pin)) { + GPIO_RPI::write(pin, value); + return; + } + if (hal.rcout->supports_gpio()) { + hal.rcout->write_gpio(pin - 1, value); + } +} + +void GPIO_Navigator::pinMode(uint8_t pin, uint8_t output) +{ + if (pinAllowed(pin)) { + GPIO_RPI::pinMode(pin, output); + } +} + +void GPIO_Navigator::pinMode(uint8_t pin, uint8_t output, uint8_t alt) +{ + if (pinAllowed(pin)) { + GPIO_RPI::pinMode(pin, output, alt); + } +} + +bool GPIO_Navigator::pinAllowed(uint8_t pin) +{ + for (const auto &gpio : AllowedGPIOS) { + if (pin == gpio) { + return true; + } + } + return false; +} diff --git a/libraries/AP_HAL_Linux/GPIO_Navigator.h b/libraries/AP_HAL_Linux/GPIO_Navigator.h new file mode 100644 index 00000000000..508024b9e10 --- /dev/null +++ b/libraries/AP_HAL_Linux/GPIO_Navigator.h @@ -0,0 +1,21 @@ +#pragma once +#include "GPIO_RPI.h" + +using namespace Linux; + +extern const AP_HAL::HAL& hal; + +class GPIO_Navigator : public GPIO_RPI +{ + +public: + void pinMode(uint8_t pin, uint8_t output) override; + void pinMode(uint8_t pin, uint8_t output, uint8_t alt) override; + uint8_t read(uint8_t pin) override; + void write(uint8_t pin, uint8_t value) override; +private: + uint8_t AllowedGPIOS[1] = {RPI_GPIO_<26>()}; + bool pinAllowed(uint8_t pin); +}; + + diff --git a/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp b/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp index 4710f632575..b9a73248ba2 100644 --- a/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp +++ b/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp @@ -123,9 +123,10 @@ static GPIO_BBB gpioDriver; CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH || \ CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DARK || \ CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXFMINI || \ - CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIGATOR || \ CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_OBAL_V1 static GPIO_RPI gpioDriver; +#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIGATOR +static GPIO_Navigator gpioDriver; #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || \ CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO2 || \ CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_EDGE diff --git a/libraries/AP_HAL_Linux/OpticalFlow_Onboard.cpp b/libraries/AP_HAL_Linux/OpticalFlow_Onboard.cpp index 1c58a5223bf..981afc77bba 100644 --- a/libraries/AP_HAL_Linux/OpticalFlow_Onboard.cpp +++ b/libraries/AP_HAL_Linux/OpticalFlow_Onboard.cpp @@ -171,6 +171,11 @@ void OpticalFlow_Onboard::init() } _gyro_ring_buffer = new ObjectBuffer(OPTICAL_FLOW_GYRO_BUFFER_LEN); + if (_gyro_ring_buffer != nullptr && _gyro_ring_buffer->get_size() == 0) { + // allocation failed + delete _gyro_ring_buffer; + _gyro_ring_buffer = nullptr; + } _initialized = true; } diff --git a/libraries/AP_HAL_Linux/RCInput_RCProtocol.cpp b/libraries/AP_HAL_Linux/RCInput_RCProtocol.cpp index 321c5bf33a7..1880003e43b 100644 --- a/libraries/AP_HAL_Linux/RCInput_RCProtocol.cpp +++ b/libraries/AP_HAL_Linux/RCInput_RCProtocol.cpp @@ -23,6 +23,10 @@ #include #include #include +#include + +#include +#include "RCInput.h" #include "RCInput_RCProtocol.h" #include diff --git a/libraries/AP_HAL_Linux/RCInput_RCProtocol.h b/libraries/AP_HAL_Linux/RCInput_RCProtocol.h index d15a3417fee..4fa6cafcf71 100644 --- a/libraries/AP_HAL_Linux/RCInput_RCProtocol.h +++ b/libraries/AP_HAL_Linux/RCInput_RCProtocol.h @@ -18,10 +18,7 @@ */ #pragma once -#include -#include -#include "RCInput.h" -#include +#include #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO || \ CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BLUE || \ diff --git a/libraries/AP_HAL_Linux/RCOutput_PCA9685.cpp b/libraries/AP_HAL_Linux/RCOutput_PCA9685.cpp index 3a6b7dab2fa..d6c1fed519c 100644 --- a/libraries/AP_HAL_Linux/RCOutput_PCA9685.cpp +++ b/libraries/AP_HAL_Linux/RCOutput_PCA9685.cpp @@ -42,6 +42,9 @@ #define PCA9685_MODE2_OUTNE1_BIT (1 << 1) #define PCA9685_MODE2_OUTNE0_BIT (1 << 0) +#define PCA9685_LED_ON_H_ALWAYS_ON_BIT (1 << 4) +#define PCA9685_LED_OFF_H_ALWAYS_OFF_BIT (1 << 4) + /* * Drift for internal oscillator * see: https://github.com/ArduPilot/ardupilot/commit/50459bdca0b5a1adf95 @@ -193,7 +196,23 @@ void RCOutput_PCA9685::write(uint8_t ch, uint16_t period_us) if (ch >= (PWM_CHAN_COUNT - _channel_offset)) { return; } + if (_is_gpio_mask & (1U << ch)) { + return; + } + write_raw(ch, period_us); +} +void RCOutput_PCA9685::write_gpio(uint8_t chan, bool active) +{ + if (chan >= (PWM_CHAN_COUNT - _channel_offset)) { + return; + } + _is_gpio_mask |= (1U << chan); + write_raw(chan, active); +} + +void RCOutput_PCA9685::write_raw(uint8_t ch, uint16_t period_us) { + /* Common code used by both write() and write_gpio() */ _pulses_buffer[ch] = period_us; _pending_write_mask |= (1U << ch); @@ -240,10 +259,18 @@ void RCOutput_PCA9685::push() } uint8_t *d = &pwm_values.data[(ch - min_ch) * 4]; - *d++ = 0; - *d++ = 0; - *d++ = length & 0xFF; - *d++ = length >> 8; + + if (_is_gpio_mask & (1 << ch)) { + *d++ = 0; // LEDn_ON_L + *d++ = period_us ? PCA9685_LED_ON_H_ALWAYS_ON_BIT : 0; // LEDn_ON_H + *d++ = 0; // LEDn_OFF_L + *d++ = period_us ? 0 : PCA9685_LED_OFF_H_ALWAYS_OFF_BIT; // LEDn_OFF_H + } else { + *d++ = 0; // LEDn_ON_L + *d++ = 0; // LEDn_ON_H + *d++ = length & 0xFF; // LEDn_OFF_L + *d++ = length >> 8; // LEDn_OFF_H + } } if (!_dev || !_dev->get_semaphore()->take_nonblocking()) { diff --git a/libraries/AP_HAL_Linux/RCOutput_PCA9685.h b/libraries/AP_HAL_Linux/RCOutput_PCA9685.h index c4b55d953ed..5d057203f2a 100644 --- a/libraries/AP_HAL_Linux/RCOutput_PCA9685.h +++ b/libraries/AP_HAL_Linux/RCOutput_PCA9685.h @@ -33,9 +33,12 @@ class RCOutput_PCA9685 : public AP_HAL::RCOutput { void push() override; uint16_t read(uint8_t ch) override; void read(uint16_t* period_us, uint8_t len) override; + bool supports_gpio() override { return true; }; + void write_gpio(uint8_t chan, bool active) override; private: void reset(); + void write_raw(uint8_t ch, uint16_t period_us); AP_HAL::DigitalSource *_enable_pin; AP_HAL::OwnPtr _dev; @@ -48,7 +51,8 @@ class RCOutput_PCA9685 : public AP_HAL::RCOutput { bool _corking = false; uint8_t _channel_offset; int16_t _oe_pin_number; - uint16_t _pending_write_mask; + uint32_t _pending_write_mask; + uint32_t _is_gpio_mask; }; } diff --git a/libraries/AP_HAL_Linux/Scheduler.cpp b/libraries/AP_HAL_Linux/Scheduler.cpp index 82ed1dc28f0..b8a8f48706a 100644 --- a/libraries/AP_HAL_Linux/Scheduler.cpp +++ b/libraries/AP_HAL_Linux/Scheduler.cpp @@ -325,7 +325,7 @@ void Scheduler::reboot(bool hold_in_bootloader) exit(1); } -#if APM_BUILD_TYPE(APM_BUILD_Replay) +#if APM_BUILD_TYPE(APM_BUILD_Replay) || APM_BUILD_TYPE(APM_BUILD_UNKNOWN) void Scheduler::stop_clock(uint64_t time_usec) { if (time_usec < _stopped_clock_usec) { diff --git a/libraries/AP_HAL_Linux/Util.cpp b/libraries/AP_HAL_Linux/Util.cpp index 5492fc99eef..0312af31091 100644 --- a/libraries/AP_HAL_Linux/Util.cpp +++ b/libraries/AP_HAL_Linux/Util.cpp @@ -150,7 +150,7 @@ bool Util::get_system_id_unformatted(uint8_t buf[], uint8_t &len) as get_system_id_unformatted will already be ascii, we use the same ID here */ -bool Util::get_system_id(char buf[40]) +bool Util::get_system_id(char buf[50]) { uint8_t len = 40; return get_system_id_unformatted((uint8_t *)buf, len); diff --git a/libraries/AP_HAL_Linux/Util.h b/libraries/AP_HAL_Linux/Util.h index 98b6440d196..8cf83dc49fe 100644 --- a/libraries/AP_HAL_Linux/Util.h +++ b/libraries/AP_HAL_Linux/Util.h @@ -69,7 +69,7 @@ class Util : public AP_HAL::Util { uint32_t available_memory(void) override; - bool get_system_id(char buf[40]) override; + bool get_system_id(char buf[50]) override; bool get_system_id_unformatted(uint8_t buf[], uint8_t &len) override; #ifdef ENABLE_HEAP diff --git a/libraries/AP_HAL_Linux/Util_RPI.cpp b/libraries/AP_HAL_Linux/Util_RPI.cpp index de0b3ecab54..9250f728ffe 100644 --- a/libraries/AP_HAL_Linux/Util_RPI.cpp +++ b/libraries/AP_HAL_Linux/Util_RPI.cpp @@ -27,72 +27,44 @@ using namespace Linux; UtilRPI::UtilRPI() { - _check_rpi_version(); + _check_rpi_version_by_rev(); } -int UtilRPI::_check_rpi_version() +int UtilRPI::_check_rpi_version_by_rev() { - const unsigned int MAX_SIZE_LINE = 50; - char buffer[MAX_SIZE_LINE]; - int hw; + // assume 2 if unknown + _rpi_version = 2; + const char *SOC[]= {"Broadcom BCM2835","Broadcom BCM2836","Broadcom BCM2837","Broadcom BCM2711"}; + const char *revision_file_ = "/proc/device-tree/system/linux,revision"; + uint8_t revision[4] = { 0 }; + uint32_t cpu = 0; + FILE *fd; - memset(buffer, 0, MAX_SIZE_LINE); - FILE *f = fopen("/sys/firmware/devicetree/base/model", "r"); - if (f != nullptr && fgets(buffer, MAX_SIZE_LINE, f) != nullptr) { - fclose(f); - - int ret = strncmp(buffer, "Raspberry Pi Compute Module 4", 28); - if (ret == 0) { - _rpi_version = 4; // compute module 4 e.g. Raspberry Pi Compute Module 4 Rev 1.0. - printf("%s. (intern: %d)\n", buffer, _rpi_version); - return _rpi_version; - } - - ret = strncmp(buffer, "Raspberry Pi Zero 2", 19); - if (ret == 0) { - _rpi_version = 2; // Raspberry PI Zero 2 W e.g. Raspberry Pi Zero 2 Rev 1.0. - printf("%s. (intern: %d)\n", buffer, _rpi_version); - return _rpi_version; - } - - ret = sscanf(buffer + 12, "%d", &_rpi_version); - if (ret != EOF) { - if (_rpi_version > 3) { - _rpi_version = 4; - } else if (_rpi_version > 2) { - // Preserving old behavior. - _rpi_version = 2; - } else if (_rpi_version == 0) { - // RPi 1 doesn't have a number there, so sscanf() won't have read anything. - _rpi_version = 1; + if ((fd = fopen(revision_file_, "rb")) == NULL) { + printf("Can't open '%s'\n", revision_file_); + } + else { + if (fread(revision, 1, sizeof(revision), fd) == 4) { + cpu = (revision[2] >> 4) & 0xf; + + _rpi_version = cpu; + + if (_rpi_version==0) { + _rpi_version=1; //RPI-Zero } - printf("%s. (intern: %d)\n", buffer, _rpi_version); - - return _rpi_version; + printf("SOC: %s use intern: %d \r\n",SOC[cpu], _rpi_version); } + else { + printf("Revision data too short\n"); + } + fclose(fd); } - // Attempting old method if the version couldn't be read with the new one. - hw = Util::from(hal.util)->get_hw_arm32(); - - if (hw == UTIL_HARDWARE_RPI4) { - printf("Raspberry Pi 4 with BCM2711!\n"); - _rpi_version = 4; - } else if (hw == UTIL_HARDWARE_RPI2) { - printf("Raspberry Pi 2/3 with BCM2709!\n"); - _rpi_version = 2; - } else if (hw == UTIL_HARDWARE_RPI1) { - printf("Raspberry Pi 1 with BCM2708!\n"); - _rpi_version = 1; - } else { - /* defaults to RPi version 2/3 */ - fprintf(stderr, "Could not detect RPi version, defaulting to 2/3\n"); - _rpi_version = 2; - } return _rpi_version; } + int UtilRPI::get_rpi_version() const { return _rpi_version; diff --git a/libraries/AP_HAL_Linux/Util_RPI.h b/libraries/AP_HAL_Linux/Util_RPI.h index fdd0aca365f..9735a63f8f0 100644 --- a/libraries/AP_HAL_Linux/Util_RPI.h +++ b/libraries/AP_HAL_Linux/Util_RPI.h @@ -17,7 +17,7 @@ class UtilRPI : public Util { protected: // Called in the constructor once - int _check_rpi_version(); + int _check_rpi_version_by_rev(); private: int _rpi_version = 0; diff --git a/libraries/AP_HAL_SITL/AnalogIn.cpp b/libraries/AP_HAL_SITL/AnalogIn.cpp index a31025db73f..50ed481ee1c 100644 --- a/libraries/AP_HAL_SITL/AnalogIn.cpp +++ b/libraries/AP_HAL_SITL/AnalogIn.cpp @@ -35,10 +35,10 @@ float ADCSource::read_latest() { return _sitlState->sonar_pin_value; case 1: - return _sitlState->airspeed_pin_value; + return _sitlState->airspeed_pin_value[0]; case 2: - return _sitlState->airspeed_2_pin_value; + return _sitlState->airspeed_pin_value[1]; case 12: return _sitlState->current_pin_value; diff --git a/libraries/AP_HAL_SITL/CANSocketIface.cpp b/libraries/AP_HAL_SITL/CANSocketIface.cpp index 33e2bd104a3..02501a94863 100644 --- a/libraries/AP_HAL_SITL/CANSocketIface.cpp +++ b/libraries/AP_HAL_SITL/CANSocketIface.cpp @@ -71,19 +71,50 @@ static can_frame makeSocketCanFrame(const AP_HAL::CANFrame& uavcan_frame) return sockcan_frame; } -static AP_HAL::CANFrame makeUavcanFrame(const can_frame& sockcan_frame) +static canfd_frame makeSocketCanFDFrame(const AP_HAL::CANFrame& uavcan_frame) { - AP_HAL::CANFrame uavcan_frame(sockcan_frame.can_id & CAN_EFF_MASK, sockcan_frame.data, sockcan_frame.can_dlc); + canfd_frame sockcan_frame { uavcan_frame.id& AP_HAL::CANFrame::MaskExtID, AP_HAL::CANFrame::dlcToDataLength(uavcan_frame.dlc), CANFD_BRS, 0, 0, { } }; + std::copy(uavcan_frame.data, uavcan_frame.data + AP_HAL::CANFrame::dlcToDataLength(uavcan_frame.dlc), sockcan_frame.data); + if (uavcan_frame.isExtended()) { + sockcan_frame.can_id |= CAN_EFF_FLAG; + } + if (uavcan_frame.isErrorFrame()) { + sockcan_frame.can_id |= CAN_ERR_FLAG; + } + if (uavcan_frame.isRemoteTransmissionRequest()) { + sockcan_frame.can_id |= CAN_RTR_FLAG; + } + return sockcan_frame; +} + +static AP_HAL::CANFrame makeCanFrame(const can_frame& sockcan_frame) +{ + AP_HAL::CANFrame can_frame(sockcan_frame.can_id & CAN_EFF_MASK, sockcan_frame.data, sockcan_frame.can_dlc); if (sockcan_frame.can_id & CAN_EFF_FLAG) { - uavcan_frame.id |= AP_HAL::CANFrame::FlagEFF; + can_frame.id |= AP_HAL::CANFrame::FlagEFF; } if (sockcan_frame.can_id & CAN_ERR_FLAG) { - uavcan_frame.id |= AP_HAL::CANFrame::FlagERR; + can_frame.id |= AP_HAL::CANFrame::FlagERR; } if (sockcan_frame.can_id & CAN_RTR_FLAG) { - uavcan_frame.id |= AP_HAL::CANFrame::FlagRTR; + can_frame.id |= AP_HAL::CANFrame::FlagRTR; } - return uavcan_frame; + return can_frame; +} + +static AP_HAL::CANFrame makeCanFDFrame(const canfd_frame& sockcan_frame) +{ + AP_HAL::CANFrame can_frame(sockcan_frame.can_id & CAN_EFF_MASK, sockcan_frame.data, sockcan_frame.len); + if (sockcan_frame.can_id & CAN_EFF_FLAG) { + can_frame.id |= AP_HAL::CANFrame::FlagEFF; + } + if (sockcan_frame.can_id & CAN_ERR_FLAG) { + can_frame.id |= AP_HAL::CANFrame::FlagERR; + } + if (sockcan_frame.can_id & CAN_RTR_FLAG) { + can_frame.id |= AP_HAL::CANFrame::FlagRTR; + } + return can_frame; } bool CANIface::is_initialized() const @@ -135,6 +166,10 @@ int CANIface::_openSocket(const std::string& iface_name) if (setsockopt(s, SOL_CAN_RAW, CAN_RAW_RECV_OWN_MSGS, &on, sizeof(on)) < 0) { return -1; } + // Allow CANFD + if (setsockopt(s, SOL_CAN_RAW, CAN_RAW_FD_FRAMES, &on, sizeof(on)) < 0) { + return -1; + } // Non-blocking if (fcntl(s, F_SETFL, O_NONBLOCK) < 0) { return -1; @@ -308,7 +343,12 @@ bool CANIface::_pollRead() CanRxItem rx; rx.timestamp_us = AP_HAL::native_micros64(); // Monotonic timestamp is not required to be precise (unlike UTC) bool loopback = false; - const int res = _read(rx.frame, rx.timestamp_us, loopback); + int res; + if (iterations_count % 2 == 0) { + res = _read(rx.frame, rx.timestamp_us, loopback); + } else { + res = _readfd(rx.frame, rx.timestamp_us, loopback); + } if (res == 1) { bool accept = true; if (loopback) { // We receive loopback for all CAN frames @@ -339,19 +379,27 @@ int CANIface::_write(const AP_HAL::CANFrame& frame) const return -1; } errno = 0; + int res = 0; - const can_frame sockcan_frame = makeSocketCanFrame(frame); - - const int res = write(_fd, &sockcan_frame, sizeof(sockcan_frame)); + if (frame.isCanFDFrame()) { + const canfd_frame sockcan_frame = makeSocketCanFDFrame(frame); + res = write(_fd, &sockcan_frame, sizeof(sockcan_frame)); + if (res > 0 && res != sizeof(sockcan_frame)) { + return -1; + } + } else { + const can_frame sockcan_frame = makeSocketCanFrame(frame); + res = write(_fd, &sockcan_frame, sizeof(sockcan_frame)); + if (res > 0 && res != sizeof(sockcan_frame)) { + return -1; + } + } if (res <= 0) { if (errno == ENOBUFS || errno == EAGAIN) { // Writing is not possible atm, not an error return 0; } return res; } - if (res != sizeof(sockcan_frame)) { - return -1; - } return 1; } @@ -389,7 +437,48 @@ int CANIface::_read(AP_HAL::CANFrame& frame, uint64_t& timestamp_us, bool& loopb return 0; } - frame = makeUavcanFrame(sockcan_frame); + frame = makeCanFrame(sockcan_frame); + /* + * Timestamp + */ + timestamp_us = AP_HAL::native_micros64(); + return 1; +} + +int CANIface::_readfd(AP_HAL::CANFrame& frame, uint64_t& timestamp_us, bool& loopback) const +{ + if (_fd < 0) { + return -1; + } + auto iov = iovec(); + auto sockcan_frame = canfd_frame(); + iov.iov_base = &sockcan_frame; + iov.iov_len = sizeof(sockcan_frame); + union { + uint8_t data[CMSG_SPACE(sizeof(::timeval))]; + struct cmsghdr align; + } control; + + auto msg = msghdr(); + msg.msg_iov = &iov; + msg.msg_iovlen = 1; + msg.msg_control = control.data; + msg.msg_controllen = sizeof(control.data); + + const int res = recvmsg(_fd, &msg, MSG_DONTWAIT); + if (res <= 0) { + return (res < 0 && errno == EWOULDBLOCK) ? 0 : res; + } + /* + * Flags + */ + loopback = (msg.msg_flags & static_cast(MSG_CONFIRM)) != 0; + + if (!loopback && !_checkHWFilters(sockcan_frame)) { + return 0; + } + + frame = makeCanFDFrame(sockcan_frame); /* * Timestamp */ @@ -450,6 +539,20 @@ bool CANIface::_checkHWFilters(const can_frame& frame) const } } +bool CANIface::_checkHWFilters(const canfd_frame& frame) const +{ + if (!_hw_filters_container.empty()) { + for (auto& f : _hw_filters_container) { + if (((frame.can_id & f.can_mask) ^ f.can_id) == 0) { + return true; + } + } + return false; + } else { + return true; + } +} + void CANIface::_updateDownStatusFromPollResult(const pollfd& pfd) { if (!_down && (pfd.revents & POLLERR)) { @@ -463,6 +566,12 @@ void CANIface::_updateDownStatusFromPollResult(const pollfd& pfd) } } +bool CANIface::init(const uint32_t bitrate, const uint32_t fdbitrate, const OperatingMode mode) +{ + // we are using vcan, so bitrate is irrelevant + return init(bitrate, mode); +} + bool CANIface::init(const uint32_t bitrate, const OperatingMode mode) { char iface_name[16]; diff --git a/libraries/AP_HAL_SITL/CANSocketIface.h b/libraries/AP_HAL_SITL/CANSocketIface.h index 5a4c4310b17..a9e9ac486c9 100644 --- a/libraries/AP_HAL_SITL/CANSocketIface.h +++ b/libraries/AP_HAL_SITL/CANSocketIface.h @@ -67,6 +67,7 @@ class CANIface: public AP_HAL::CANIface { ~CANIface() { } // Initialise CAN Peripheral + bool init(const uint32_t bitrate, const uint32_t fdbitrate, const OperatingMode mode) override; bool init(const uint32_t bitrate, const OperatingMode mode) override; // Put frame into Tx FIFO returns negative on error, 0 on buffer full, @@ -136,6 +137,8 @@ class CANIface: public AP_HAL::CANIface { int _read(AP_HAL::CANFrame& frame, uint64_t& ts_usec, bool& loopback) const; + int _readfd(AP_HAL::CANFrame& frame, uint64_t& ts_usec, bool& loopback) const; + void _incrementNumFramesInSocketTxQueue(); void _confirmSentFrame(); @@ -143,6 +146,7 @@ class CANIface: public AP_HAL::CANIface { bool _wasInPendingLoopbackSet(const AP_HAL::CANFrame& frame); bool _checkHWFilters(const can_frame& frame) const; + bool _checkHWFilters(const canfd_frame& frame) const; bool _hasReadyTx(); diff --git a/libraries/AP_HAL_SITL/DSP.cpp b/libraries/AP_HAL_SITL/DSP.cpp index b8ca3243428..c67223bfe7e 100644 --- a/libraries/AP_HAL_SITL/DSP.cpp +++ b/libraries/AP_HAL_SITL/DSP.cpp @@ -35,9 +35,9 @@ extern const AP_HAL::HAL& hal; // important as frequency resolution. Referred to as [Heinz] throughout the code. // initialize the FFT state machine -AP_HAL::DSP::FFTWindowState* DSP::fft_init(uint16_t window_size, uint16_t sample_rate) +AP_HAL::DSP::FFTWindowState* DSP::fft_init(uint16_t window_size, uint16_t sample_rate, uint8_t sliding_window_size) { - DSP::FFTWindowStateSITL* fft = new DSP::FFTWindowStateSITL(window_size, sample_rate); + DSP::FFTWindowStateSITL* fft = new DSP::FFTWindowStateSITL(window_size, sample_rate, sliding_window_size); if (fft == nullptr || fft->_hanning_window == nullptr || fft->_rfft_data == nullptr || fft->_freq_bins == nullptr || fft->_derivative_freq_bins == nullptr) { delete fft; return nullptr; @@ -61,8 +61,8 @@ uint16_t DSP::fft_analyse(AP_HAL::DSP::FFTWindowState* state, uint16_t start_bin } // create an instance of the FFT state machine -DSP::FFTWindowStateSITL::FFTWindowStateSITL(uint16_t window_size, uint16_t sample_rate) - : AP_HAL::DSP::FFTWindowState::FFTWindowState(window_size, sample_rate) +DSP::FFTWindowStateSITL::FFTWindowStateSITL(uint16_t window_size, uint16_t sample_rate, uint8_t sliding_window_size) + : AP_HAL::DSP::FFTWindowState::FFTWindowState(window_size, sample_rate, sliding_window_size) { if (_freq_bins == nullptr || _hanning_window == nullptr || _rfft_data == nullptr || _derivative_freq_bins == nullptr) { GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Failed to allocate window for DSP"); @@ -91,7 +91,7 @@ void DSP::step_hanning(FFTWindowStateSITL* fft, FloatBuffer& samples, uint16_t a mult_f32(&fft->_freq_bins[0], &fft->_hanning_window[0], &fft->_freq_bins[0], fft->_window_size); } -// step 2: performm an in-place FFT on the windowed data +// step 2: perform an in-place FFT on the windowed data void DSP::step_fft(FFTWindowStateSITL* fft) { for (uint16_t i = 0; i < fft->_window_size; i++) { @@ -137,6 +137,13 @@ void DSP::vector_scale_float(const float* vin, float scale, float* vout, uint16_ } } +void DSP::vector_add_float(const float* vin1, const float* vin2, float* vout, uint16_t len) const +{ + for (uint16_t i = 0; i < len; i++) { + vout[i] = vin1[i] + vin2[i]; + } +} + float DSP::vector_mean_float(const float* vin, uint16_t len) const { float mean_value = 0.0f; diff --git a/libraries/AP_HAL_SITL/DSP.h b/libraries/AP_HAL_SITL/DSP.h index 04bb410a61b..9813fe4bfe5 100644 --- a/libraries/AP_HAL_SITL/DSP.h +++ b/libraries/AP_HAL_SITL/DSP.h @@ -27,7 +27,7 @@ typedef std::complex complexf; class HALSITL::DSP : public AP_HAL::DSP { public: // initialise an FFT instance - virtual FFTWindowState* fft_init(uint16_t window_size, uint16_t sample_rate) override; + virtual FFTWindowState* fft_init(uint16_t window_size, uint16_t sample_rate, uint8_t sliding_window_size) override; // start an FFT analysis with an ObjectBuffer virtual void fft_start(FFTWindowState* state, FloatBuffer& samples, uint16_t advance) override; // perform remaining steps of an FFT analysis @@ -38,7 +38,7 @@ class HALSITL::DSP : public AP_HAL::DSP { friend class HALSITL::DSP; public: - FFTWindowStateSITL(uint16_t window_size, uint16_t sample_rate); + FFTWindowStateSITL(uint16_t window_size, uint16_t sample_rate, uint8_t sliding_window_size); virtual ~FFTWindowStateSITL(); private: @@ -52,5 +52,6 @@ class HALSITL::DSP : public AP_HAL::DSP { void vector_max_float(const float* vin, uint16_t len, float* maxValue, uint16_t* maxIndex) const override; void vector_scale_float(const float* vin, float scale, float* vout, uint16_t len) const override; float vector_mean_float(const float* vin, uint16_t len) const override; + void vector_add_float(const float* vin1, const float* vin2, float* vout, uint16_t len) const override; void calculate_fft(complexf* f, uint16_t length); }; diff --git a/libraries/AP_HAL_SITL/GPIO.cpp b/libraries/AP_HAL_SITL/GPIO.cpp index 27c9b06c0aa..9ad575b9082 100644 --- a/libraries/AP_HAL_SITL/GPIO.cpp +++ b/libraries/AP_HAL_SITL/GPIO.cpp @@ -29,6 +29,9 @@ uint8_t GPIO::read(uint8_t pin) if (!_sitlState->_sitl) { return 0; } + if (!valid_pin(pin)) { + return 0; + } // weight on wheels pin support if (pin == _sitlState->_sitl->wow_pin.get()) { @@ -45,6 +48,9 @@ void GPIO::write(uint8_t pin, uint8_t value) return; } + if (!valid_pin(pin)) { + return; + } if (pin < 8) { if (!(pin_mode_is_write & (1U<get_instance(); } +#if defined(HAL_BUILD_AP_PERIPH) +bool HAL_SITL::run_in_maintenance_mode() const +{ + return _sitl_state->run_in_maintenance_mode(); +} +#endif + void HAL_SITL::run(int argc, char * const argv[], Callbacks* callbacks) const { assert(callbacks); diff --git a/libraries/AP_HAL_SITL/HAL_SITL_Class.h b/libraries/AP_HAL_SITL/HAL_SITL_Class.h index eaa18f58ac7..2f3a890b644 100644 --- a/libraries/AP_HAL_SITL/HAL_SITL_Class.h +++ b/libraries/AP_HAL_SITL/HAL_SITL_Class.h @@ -37,6 +37,10 @@ class HAL_SITL : public AP_HAL::HAL { uint8_t get_instance() const; +#if defined(HAL_BUILD_AP_PERIPH) + bool run_in_maintenance_mode() const; +#endif + private: HALSITL::SITL_State *_sitl_state; diff --git a/libraries/AP_HAL_SITL/RCOutput.cpp b/libraries/AP_HAL_SITL/RCOutput.cpp index b1df8706a14..6bbe40f30c7 100644 --- a/libraries/AP_HAL_SITL/RCOutput.cpp +++ b/libraries/AP_HAL_SITL/RCOutput.cpp @@ -35,7 +35,7 @@ void RCOutput::enable_ch(uint8_t ch) if (!(_enable_mask & (1U << ch))) { Debug("enable_ch(%u)\n", ch); } - _enable_mask |= 1U << ch; + _enable_mask |= (1U << ch); } void RCOutput::disable_ch(uint8_t ch) @@ -43,13 +43,14 @@ void RCOutput::disable_ch(uint8_t ch) if (_enable_mask & (1U << ch)) { Debug("disable_ch(%u)\n", ch); } - _enable_mask &= ~1U << ch; + _enable_mask &= ~(1U << ch); } void RCOutput::write(uint8_t ch, uint16_t period_us) { _sitlState->output_ready = true; - if (ch < SITL_NUM_CHANNELS && (_enable_mask & (1U<pwm_output[ch]; } return 0; @@ -104,7 +106,7 @@ void RCOutput::push(void) /* Serial LED emulation */ -bool RCOutput::set_serial_led_num_LEDs(const uint16_t chan, uint8_t num_leds, output_mode mode, uint16_t clock_mask) +bool RCOutput::set_serial_led_num_LEDs(const uint16_t chan, uint8_t num_leds, output_mode mode, uint32_t clock_mask) { if (chan > 15 || num_leds > 64) { return false; diff --git a/libraries/AP_HAL_SITL/RCOutput.h b/libraries/AP_HAL_SITL/RCOutput.h index 3472b7c49e4..12c79a3da29 100644 --- a/libraries/AP_HAL_SITL/RCOutput.h +++ b/libraries/AP_HAL_SITL/RCOutput.h @@ -31,7 +31,7 @@ class HALSITL::RCOutput : public AP_HAL::RCOutput { /* Serial LED emulation */ - bool set_serial_led_num_LEDs(const uint16_t chan, uint8_t num_leds, output_mode mode = MODE_PWM_NONE, uint16_t clock_mask = 0) override; + bool set_serial_led_num_LEDs(const uint16_t chan, uint8_t num_leds, output_mode mode = MODE_PWM_NONE, uint32_t clock_mask = 0) override; void set_serial_led_rgb_data(const uint16_t chan, int8_t led, uint8_t red, uint8_t green, uint8_t blue) override; void serial_led_send(const uint16_t chan) override; @@ -40,7 +40,7 @@ class HALSITL::RCOutput : public AP_HAL::RCOutput { AP_ESC_Telem_SITL *esc_telem; uint16_t _freq_hz; - uint16_t _enable_mask; + uint32_t _enable_mask; bool _corked; uint16_t _pending[SITL_NUM_CHANNELS]; }; diff --git a/libraries/AP_HAL_SITL/SITL_Periph_State.cpp b/libraries/AP_HAL_SITL/SITL_Periph_State.cpp index 521bf17b004..ce0a51809b2 100644 --- a/libraries/AP_HAL_SITL/SITL_Periph_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_Periph_State.cpp @@ -29,12 +29,13 @@ void SITL_State::init(int argc, char * const argv[]) { const struct GetOptLong::option options[] = { {"help", false, 0, 'h'}, {"instance", true, 0, 'I'}, + {"maintenance", false, 0, 'M'}, }; setvbuf(stdout, (char *)0, _IONBF, 0); setvbuf(stderr, (char *)0, _IONBF, 0); - GetOptLong gopt(argc, argv, "hI:", + GetOptLong gopt(argc, argv, "hI:M", options); while((opt = gopt.getoption()) != -1) { @@ -42,10 +43,15 @@ void SITL_State::init(int argc, char * const argv[]) { case 'I': _instance = atoi(gopt.optarg); break; + case 'M': + printf("Running in Maintenance Mode\n"); + _maintenance = true; + break; default: printf("Options:\n" "\t--help|-h display this help information\n" - "\t--instance|-I N set instance of SITL Periph\n"); + "\t--instance|-I N set instance of SITL Periph\n" + "\t--maintenance|-M run in maintenance mode\n"); exit(1); } } diff --git a/libraries/AP_HAL_SITL/SITL_Periph_State.h b/libraries/AP_HAL_SITL/SITL_Periph_State.h index 6f89a13456b..222abf54d4b 100644 --- a/libraries/AP_HAL_SITL/SITL_Periph_State.h +++ b/libraries/AP_HAL_SITL/SITL_Periph_State.h @@ -41,8 +41,7 @@ class HALSITL::SITL_State { // simulated airspeed, sonar and battery monitor uint16_t sonar_pin_value; // pin 0 - uint16_t airspeed_pin_value; // pin 1 - uint16_t airspeed_2_pin_value; // pin 2 + uint16_t airspeed_pin_value[2]; // pin 1 uint16_t voltage_pin_value; // pin 13 uint16_t current_pin_value; // pin 12 uint16_t voltage2_pin_value; // pin 15 @@ -62,6 +61,8 @@ class HALSITL::SITL_State { uint8_t get_instance() const { return _instance; } + bool run_in_maintenance_mode() const { return _maintenance; } + SITL::SerialDevice *create_serial_sim(const char *name, const char *arg) { return nullptr; } @@ -75,6 +76,7 @@ class HALSITL::SITL_State { const char *defaults_path = HAL_PARAM_DEFAULTS_PATH; uint8_t _instance; + bool _maintenance; }; #endif diff --git a/libraries/AP_HAL_SITL/SITL_State.cpp b/libraries/AP_HAL_SITL/SITL_State.cpp index 491b330a237..ca03aaf360f 100644 --- a/libraries/AP_HAL_SITL/SITL_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_State.cpp @@ -236,6 +236,12 @@ SITL::SerialDevice *SITL_State::create_serial_sim(const char *name, const char * } benewake_tfmini = new SITL::RF_Benewake_TFmini(); return benewake_tfmini; + } else if (streq(name, "teraranger_serial")) { + if (teraranger_serial != nullptr) { + AP_HAL::panic("Only one teraranger_serial at a time"); + } + teraranger_serial = new SITL::RF_TeraRanger_Serial(); + return teraranger_serial; } else if (streq(name, "lightwareserial")) { if (lightwareserial != nullptr) { AP_HAL::panic("Only one lightwareserial at a time"); @@ -434,6 +440,22 @@ bool SITL_State::_read_rc_sitl_input() } pwm_pkt; const ssize_t size = _sitl_rc_in.recv(&pwm_pkt, sizeof(pwm_pkt), 0); + + // if we are simulating no pulses RC failure, do not update pwm_input + if (_sitl->rc_fail == SITL::SIM::SITL_RCFail_NoPulses) { + return size != -1; // we must continue to drain _sitl_rc + } + + if (_sitl->rc_fail == SITL::SIM::SITL_RCFail_Throttle950) { + // discard anything we just read from the "receiver" and set + // values to bind values: + for (uint8_t i=0; irc_fail == SITL::SIM::SITL_RCFail_Throttle950) { - if (i == 2) { - // set throttle (assumed to be on channel 3...) - pwm = 950; - } else { - // centre all other inputs - pwm = 1500; - } - } pwm_input[i] = pwm; } } @@ -567,6 +580,9 @@ void SITL_State::_fdm_input_local(void) if (benewake_tfmini != nullptr) { benewake_tfmini->update(sitl_model->rangefinder_range()); } + if (teraranger_serial != nullptr) { + teraranger_serial->update(sitl_model->rangefinder_range()); + } if (lightwareserial != nullptr) { lightwareserial->update(sitl_model->rangefinder_range()); } @@ -698,6 +714,10 @@ void SITL_State::_simulator_servos(struct sitl_input &input) if (_vehicle == Rover) { pwm_output[0] = pwm_output[1] = pwm_output[2] = pwm_output[3] = 1500; } + if (_vehicle == ArduSub) { + pwm_output[0] = pwm_output[1] = pwm_output[2] = pwm_output[3] = + pwm_output[4] = pwm_output[5] = pwm_output[6] = pwm_output[7] = 1500; + } } // output at chosen framerate @@ -788,8 +808,12 @@ void SITL_State::_simulator_servos(struct sitl_input &input) // do a little quadplane dance float hover_throttle = 0.0f; uint8_t running_motors = 0; - for (uint8_t i=0; i < sitl_model->get_num_motors() - 1; i++) { - float motor_throttle = constrain_float((input.servos[sitl_model->get_motors_offset() + i] - 1000) / 1000.0f, 0.0f, 1.0f); + uint32_t mask = _sitl->state.motor_mask; + uint8_t bit; + while ((bit = __builtin_ffs(mask)) != 0) { + uint8_t motor = bit-1; + mask &= ~(1U<get_num_motors(); i++) { - float motor_throttle = constrain_float((input.servos[i] - 1000) / 1000.0f, 0.0f, 1.0f); + uint32_t mask = _sitl->state.motor_mask; + uint8_t bit; + while ((bit = __builtin_ffs(mask)) != 0) { + const uint8_t motor = bit-1; + mask &= ~(1U< #include #include +#include #include #include #include @@ -96,8 +97,7 @@ class HALSITL::SITL_State { // simulated airspeed, sonar and battery monitor uint16_t sonar_pin_value; // pin 0 - uint16_t airspeed_pin_value; // pin 1 - uint16_t airspeed_2_pin_value; // pin 2 + uint16_t airspeed_pin_value[AIRSPEED_MAX_SENSORS]; // pin 1 uint16_t voltage_pin_value; // pin 13 uint16_t current_pin_value; // pin 12 uint16_t voltage2_pin_value; // pin 15 @@ -186,7 +186,6 @@ class HALSITL::SITL_State { uint8_t store_index_wind; uint32_t last_store_time_wind; VectorN buffer_wind; - VectorN buffer_wind_2; uint32_t time_delta_wind; uint32_t delayed_time_wind; uint32_t wind_start_delay_micros; @@ -214,6 +213,8 @@ class HALSITL::SITL_State { SITL::RF_Benewake_TF03 *benewake_tf03; // simulated Benewake tfmini rangefinder: SITL::RF_Benewake_TFmini *benewake_tfmini; + // simulated TeraRanger Serial: + SITL::RF_TeraRanger_Serial *teraranger_serial; // simulated LightWareSerial rangefinder - legacy protocol:: SITL::RF_LightWareSerial *lightwareserial; diff --git a/libraries/AP_HAL_SITL/Scheduler.cpp b/libraries/AP_HAL_SITL/Scheduler.cpp index 941648432d6..97d4c63d019 100644 --- a/libraries/AP_HAL_SITL/Scheduler.cpp +++ b/libraries/AP_HAL_SITL/Scheduler.cpp @@ -13,6 +13,9 @@ #include #endif #include +#ifdef UBSAN_ENABLED +#include +#endif using namespace HALSITL; @@ -49,6 +52,45 @@ Scheduler::Scheduler(SITL_State *sitlState) : { } +#ifdef UBSAN_ENABLED +/* + catch ubsan errors and append to a log file + */ +extern "C" { +void __ubsan_get_current_report_data(const char **OutIssueKind, + const char **OutMessage, + const char **OutFilename, unsigned *OutLine, + unsigned *OutCol, char **OutMemoryAddr); + +void __ubsan_on_report() +{ + static int fd = -1; + if (fd == -1) { + const char *ubsan_log_path = getenv("UBSAN_LOG_PATH"); + if (ubsan_log_path == nullptr) { + ubsan_log_path = "ubsan.log"; + } + if (ubsan_log_path != nullptr) { + fd = open(ubsan_log_path, O_APPEND|O_CREAT|O_WRONLY, 0644); + } + } + if (fd != -1) { + const char *OutIssueKind = nullptr; + const char *OutMessage = nullptr; + const char *OutFilename = nullptr; + unsigned OutLine=0; + unsigned OutCol=0; + char *OutMemoryAddr=nullptr; + __ubsan_get_current_report_data(&OutIssueKind, &OutMessage, &OutFilename, + &OutLine, &OutCol, &OutMemoryAddr); + dprintf(fd, "ubsan error: %s:%u:%u %s:%s\n", + OutFilename, OutLine, OutCol, + OutIssueKind, OutMessage); + } +} +} +#endif + void Scheduler::init() { _main_ctx = pthread_self(); diff --git a/libraries/AP_HAL_SITL/Util.cpp b/libraries/AP_HAL_SITL/Util.cpp index fd03effb1d0..4f8eec1950b 100644 --- a/libraries/AP_HAL_SITL/Util.cpp +++ b/libraries/AP_HAL_SITL/Util.cpp @@ -72,7 +72,7 @@ bool HALSITL::Util::get_system_id_unformatted(uint8_t buf[], uint8_t &len) as get_system_id_unformatted will already be ascii, we use the same ID here */ -bool HALSITL::Util::get_system_id(char buf[40]) +bool HALSITL::Util::get_system_id(char buf[50]) { uint8_t len = 40; return get_system_id_unformatted((uint8_t *)buf, len); diff --git a/libraries/AP_HAL_SITL/Util.h b/libraries/AP_HAL_SITL/Util.h index 816ff7876fa..3c7576556db 100644 --- a/libraries/AP_HAL_SITL/Util.h +++ b/libraries/AP_HAL_SITL/Util.h @@ -42,7 +42,7 @@ class HALSITL::Util : public AP_HAL::Util { void set_hw_rtc(uint64_t time_utc_usec) override { /* fail silently */ } - bool get_system_id(char buf[40]) override; + bool get_system_id(char buf[50]) override; bool get_system_id_unformatted(uint8_t buf[], uint8_t &len) override; void dump_stack_trace(); diff --git a/libraries/AP_HAL_SITL/sitl_airspeed.cpp b/libraries/AP_HAL_SITL/sitl_airspeed.cpp index c5508b9b0be..0bddc20d4b5 100644 --- a/libraries/AP_HAL_SITL/sitl_airspeed.cpp +++ b/libraries/AP_HAL_SITL/sitl_airspeed.cpp @@ -20,101 +20,67 @@ extern const AP_HAL::HAL& hal; using namespace HALSITL; +// return current scale factor that converts from equivalent to true airspeed +// valid for altitudes up to 10km AMSL +// assumes standard atmosphere lapse rate +static float get_EAS2TAS(float altitude) +{ + float pressure = AP::baro().get_pressure(); + if (is_zero(pressure)) { + return 1.0f; + } + + float sigma, delta, theta; + AP_Baro::SimpleAtmosphere(altitude * 0.001, sigma, delta, theta); + + float tempK = C_TO_KELVIN(25) - ISA_LAPSE_RATE * altitude; + const float eas2tas_squared = SSL_AIR_DENSITY / (pressure / (ISA_GAS_CONSTANT * tempK)); + if (!is_positive(eas2tas_squared)) { + return 1.0; + } + return sqrtf(eas2tas_squared); +} + /* convert airspeed in m/s to an airspeed sensor value */ -void SITL_State::_update_airspeed(float airspeed) +void SITL_State::_update_airspeed(float true_airspeed) { - float airspeed2 = airspeed; - const float airspeed_ratio = 1.9936f; - const float diff_pressure = sq(airspeed) * 0.5; + for (uint8_t i=0; iairspeed[i]; + float airspeed = true_airspeed / get_EAS2TAS(_sitl->state.altitude); + const float diff_pressure = sq(airspeed) / arspd.ratio; + float airspeed_raw; - // apply noise to the differential pressure. This emulates the way - // airspeed noise reduces with speed - airspeed = sqrtf(fabsf(2*(diff_pressure + _sitl->arspd_noise[0] * rand_float()))); - airspeed2 = sqrtf(fabsf(2*(diff_pressure + _sitl->arspd_noise[1] * rand_float()))); - - // check sensor failure - if (is_positive(_sitl->arspd_fail[0])) { - airspeed = _sitl->arspd_fail[0]; - } - if (is_positive(_sitl->arspd_fail[1])) { - airspeed2 = _sitl->arspd_fail[1]; - } - - if (!is_zero(_sitl->arspd_fail_pressure[0])) { - // compute a realistic pressure report given some level of trapper air pressure in the tube and our current altitude - // algorithm taken from https://en.wikipedia.org/wiki/Calibrated_airspeed#Calculation_from_impact_pressure - float tube_pressure = fabsf(_sitl->arspd_fail_pressure[0] - AP::baro().get_pressure() + _sitl->arspd_fail_pitot_pressure[0]); - airspeed = 340.29409348 * sqrt(5 * (pow((tube_pressure / SSL_AIR_PRESSURE + 1), 2.0/7.0) - 1.0)); - } - if (!is_zero(_sitl->arspd_fail_pressure[1])) { - // compute a realistic pressure report given some level of trapper air pressure in the tube and our current altitude - // algorithm taken from https://en.wikipedia.org/wiki/Calibrated_airspeed#Calculation_from_impact_pressure - float tube_pressure = fabsf(_sitl->arspd_fail_pressure[1] - AP::baro().get_pressure() + _sitl->arspd_fail_pitot_pressure[1]); - airspeed2 = 340.29409348 * sqrt(5 * (pow((tube_pressure / SSL_AIR_PRESSURE + 1), 2.0/7.0) - 1.0)); - } + // apply noise to the differential pressure. This emulates the way + // airspeed noise reduces with speed + airspeed = sqrtf(fabsf(arspd.ratio*(diff_pressure + arspd.noise * rand_float()))); - float airspeed_pressure = (airspeed * airspeed) / airspeed_ratio; - float airspeed2_pressure = (airspeed2 * airspeed2) / airspeed_ratio; + // check sensor failure + if (is_positive(arspd.fail)) { + airspeed = arspd.fail; + } - // flip sign here for simulating reversed pitot/static connections - if (_sitl->arspd_signflip) airspeed_pressure *= -1; - if (_sitl->arspd_signflip) airspeed2_pressure *= -1; + if (!is_zero(arspd.fail_pressure)) { + // compute a realistic pressure report given some level of trapper air pressure in the tube and our current altitude + // algorithm taken from https://en.wikipedia.org/wiki/Calibrated_airspeed#Calculation_from_impact_pressure + float tube_pressure = fabsf(arspd.fail_pressure - AP::baro().get_pressure() + arspd.fail_pitot_pressure); + airspeed = 340.29409348 * sqrt(5 * (pow((tube_pressure / SSL_AIR_PRESSURE + 1), 2.0/7.0) - 1.0)); + } + float airspeed_pressure = (airspeed * airspeed) / arspd.ratio; - // apply airspeed sensor offset in m/s - float airspeed_raw = airspeed_pressure + _sitl->arspd_offset[0]; - float airspeed2_raw = airspeed2_pressure + _sitl->arspd_offset[1]; + // flip sign here for simulating reversed pitot/static connections + if (arspd.signflip) { + airspeed_pressure *= -1; + } - _sitl->state.airspeed_raw_pressure[0] = airspeed_pressure; - _sitl->state.airspeed_raw_pressure[1] = airspeed2_pressure; + // apply airspeed sensor offset in m/s + airspeed_raw = airspeed_pressure + arspd.offset; - if (airspeed_raw / 4 > 0xFFFF) { - airspeed_pin_value = 0xFFFF; - return; - } - if (airspeed2_raw / 4 > 0xFFFF) { - airspeed_2_pin_value = 0xFFFF; - return; - } - // add delay - const uint32_t now = AP_HAL::millis(); - uint32_t best_time_delta_wind = 200; // initialise large time representing buffer entry closest to current time - delay. - uint8_t best_index_wind = 0; // initialise number representing the index of the entry in buffer closest to delay. - - // storing data from sensor to buffer - if (now - last_store_time_wind >= 10) { // store data every 10 ms. - last_store_time_wind = now; - if (store_index_wind > wind_buffer_length - 1) { // reset buffer index if index greater than size of buffer - store_index_wind = 0; - } - buffer_wind[store_index_wind].data = airspeed_raw; // add data to current index - buffer_wind[store_index_wind].time = last_store_time_wind; // add time to current index - buffer_wind_2[store_index_wind].data = airspeed2_raw; // add data to current index - buffer_wind_2[store_index_wind].time = last_store_time_wind; // add time to current index - store_index_wind = store_index_wind + 1; // increment index - } + _sitl->state.airspeed_raw_pressure[i] = airspeed_pressure; - // return delayed measurement - delayed_time_wind = now - _sitl->wind_delay; // get time corresponding to delay - // find data corresponding to delayed time in buffer - for (uint8_t i = 0; i <= wind_buffer_length - 1; i++) { - // find difference between delayed time and time stamp in buffer - time_delta_wind = abs( - (int32_t)(delayed_time_wind - buffer_wind[i].time)); - // if this difference is smaller than last delta, store this time - if (time_delta_wind < best_time_delta_wind) { - best_index_wind = i; - best_time_delta_wind = time_delta_wind; - } + airspeed_pin_value[i] = MIN(0xFFFF, airspeed_raw / 4); } - if (best_time_delta_wind < 200) { // only output stored state if < 200 msec retrieval error - airspeed_raw = buffer_wind[best_index_wind].data; - airspeed2_raw = buffer_wind_2[best_index_wind].data; - } - - airspeed_pin_value = airspeed_raw / 4; - airspeed_2_pin_value = airspeed2_raw / 4; } #endif diff --git a/libraries/AP_HAL_SITL/system.cpp b/libraries/AP_HAL_SITL/system.cpp index bc189c71d38..8b1c35d7ddd 100644 --- a/libraries/AP_HAL_SITL/system.cpp +++ b/libraries/AP_HAL_SITL/system.cpp @@ -52,7 +52,7 @@ void WEAK panic(const char *errormsg, ...) } // partly flogged from: https://github.com/tridge/junkcode/blob/master/segv_handler/segv_handler.c -void run_command_on_ownpid(const char *commandname) +static void run_command_on_ownpid(const char *commandname) { // find dumpstack command: const char *command_filepath = commandname; // if we can't find it trust in PATH diff --git a/libraries/AP_Hott_Telem/AP_Hott_Telem.cpp b/libraries/AP_Hott_Telem/AP_Hott_Telem.cpp index b013f0f7f38..817dbd1030c 100644 --- a/libraries/AP_Hott_Telem/AP_Hott_Telem.cpp +++ b/libraries/AP_Hott_Telem/AP_Hott_Telem.cpp @@ -34,7 +34,7 @@ #include #include #include -#include +#include #include #define PROT_BINARY 0x80 @@ -73,7 +73,7 @@ void AP_Hott_Telem::init() if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Hott_Telem::loop, void), "Hott", 1024, AP_HAL::Scheduler::PRIORITY_BOOST, 1)) { - hal.console->printf("Failed to create Hott thread\n"); + DEV_PRINTF("Failed to create Hott thread\n"); } } } diff --git a/libraries/AP_Hott_Telem/AP_Hott_Telem.h b/libraries/AP_Hott_Telem/AP_Hott_Telem.h index 606c4bc5a52..9d6d52bff0a 100644 --- a/libraries/AP_Hott_Telem/AP_Hott_Telem.h +++ b/libraries/AP_Hott_Telem/AP_Hott_Telem.h @@ -15,7 +15,6 @@ #pragma once #include -#include #ifndef HAL_HOTT_TELEM_ENABLED #define HAL_HOTT_TELEM_ENABLED !HAL_MINIMIZE_FEATURES diff --git a/libraries/AP_ICEngine/AP_ICEngine.cpp b/libraries/AP_ICEngine/AP_ICEngine.cpp index 7600fdb2b1b..6e36b3c133c 100644 --- a/libraries/AP_ICEngine/AP_ICEngine.cpp +++ b/libraries/AP_ICEngine/AP_ICEngine.cpp @@ -13,13 +13,17 @@ along with this program. If not, see . */ +#include "AP_ICEngine.h" + +#if AP_ICENGINE_ENABLED #include #include #include #include #include -#include "AP_ICEngine.h" +#include +#include extern const AP_HAL::HAL& hal; @@ -131,8 +135,8 @@ const AP_Param::GroupInfo AP_ICEngine::var_info[] = { // @Param: OPTIONS // @DisplayName: ICE options - // @Description: Options for ICE control - // @Bitmask: 0:DisableIgnitionRCFailsafe + // @Description: Options for ICE control. The DisableIgnitionRCFailsafe option will cause the ignition to be set off on any R/C failsafe. If ThrottleWhileDisarmed is set then throttle control will be allowed while disarmed for planes when in MANUAL mode. + // @Bitmask: 0:DisableIgnitionRCFailsafe,1:DisableRedineGovernor,2:ThrottleWhileDisarmed AP_GROUPINFO("OPTIONS", 15, AP_ICEngine, options, 0), // @Param: STARTCHN_MIN @@ -142,6 +146,14 @@ const AP_Param::GroupInfo AP_ICEngine::var_info[] = { // @Range: 0 1300 AP_GROUPINFO("STARTCHN_MIN", 16, AP_ICEngine, start_chan_min_pwm, 0), + // @Param: REDLINE_RPM + // @DisplayName: RPM of the redline limit for the engine + // @Description: Maximum RPM for the engine provided by the manufacturer. A value of 0 disables this feature. See ICE_OPTIONS to enable or disable the governor. + // @User: Advanced + // @Range: 0 2000000 + // @Units: RPM + AP_GROUPINFO("REDLINE_RPM", 17, AP_ICEngine, redline_rpm, 0), + AP_GROUPEND }; @@ -156,6 +168,9 @@ AP_ICEngine::AP_ICEngine(const AP_RPM &_rpm) : AP_HAL::panic("AP_ICEngine must be singleton"); } _singleton = this; + + // ICEngine runs at 10Hz + _rpm_filter.set_cutoff_frequency(10, 0.5f); } /* @@ -202,6 +217,12 @@ void AP_ICEngine::update(void) start_chan_last_value = cvalue; } + if (state == ICE_START_HEIGHT_DELAY && start_chan_last_value >= RC_Channel::AUX_PWM_TRIGGER_HIGH) { + // user is overriding the height start delay and asking for + // immediate start. Put into ICE_OFF so that the logic below + // can start the engine now + state = ICE_OFF; + } if (state == ICE_OFF && start_chan_last_value >= RC_Channel::AUX_PWM_TRIGGER_HIGH) { should_run = true; @@ -211,11 +232,13 @@ void AP_ICEngine::update(void) should_run = true; } - if ((options & uint16_t(Options::DISABLE_IGNITION_RC_FAILSAFE)) && AP_Notify::flags.failsafe_radio) { + if (option_set(Options::DISABLE_IGNITION_RC_FAILSAFE) && AP_Notify::flags.failsafe_radio) { // user has requested ignition kill on RC failsafe should_run = false; } + float rpm_value; + // switch on current state to work out new state switch (state) { case ICE_OFF: @@ -254,6 +277,7 @@ void AP_ICEngine::update(void) if (!should_run) { state = ICE_OFF; } else if (now - starter_start_time_ms >= starter_time*1000) { + gcs().send_text(MAV_SEVERITY_INFO, "Engine running"); state = ICE_RUNNING; } break; @@ -264,11 +288,11 @@ void AP_ICEngine::update(void) gcs().send_text(MAV_SEVERITY_INFO, "Stopped engine"); } else if (rpm_instance > 0) { // check RPM to see if still running - float rpm_value; if (!rpm.get_rpm(rpm_instance-1, rpm_value) || rpm_value < rpm_threshold) { // engine has stopped when it should be running state = ICE_START_DELAY; + gcs().send_text(MAV_SEVERITY_INFO, "Uncommanded engine stop"); } } break; @@ -282,12 +306,31 @@ void AP_ICEngine::update(void) // reset initial height while disarmed initial_height = -pos.z; } - } else if (idle_percent <= 0) { // check if we should idle + } else if (idle_percent <= 0 && !option_set(Options::THROTTLE_WHILE_DISARMED)) { // force ignition off when disarmed state = ICE_OFF; } } + // check against redline RPM + if (rpm_instance > 0 && redline_rpm > 0 && rpm.get_rpm(rpm_instance-1, rpm_value)) { + // update the filtered RPM value + filtered_rpm_value = _rpm_filter.apply(rpm_value); + if (!redline.flag && filtered_rpm_value > redline_rpm) { + // redline governor is off. rpm is too high. enable the governor + gcs().send_text(MAV_SEVERITY_INFO, "Engine: Above redline RPM"); + redline.flag = true; + } else if (redline.flag && filtered_rpm_value < redline_rpm * 0.9f) { + // redline governor is on. rpm is safely below. disable the governor + redline.flag = false; + // reset redline governor + redline.throttle_percentage = 0.0f; + redline.governor_integrator = 0.0f; + } + } else { + redline.flag = false; + } + /* now set output channels */ switch (state) { case ICE_OFF: @@ -323,8 +366,11 @@ void AP_ICEngine::update(void) /* check for throttle override. This allows the ICE controller to force the correct starting throttle when starting the engine and maintain idle when disarmed + + base_throttle is the throttle before the disarmed override + check. This allows for throttle control while disarmed */ -bool AP_ICEngine::throttle_override(uint8_t &percentage) +bool AP_ICEngine::throttle_override(float &percentage, const float base_throttle) { if (!enable) { return false; @@ -333,16 +379,54 @@ bool AP_ICEngine::throttle_override(uint8_t &percentage) if (state == ICE_RUNNING && idle_percent > 0 && idle_percent < 100 && - (int16_t)idle_percent > SRV_Channels::get_output_scaled(SRV_Channel::k_throttle)) + idle_percent > percentage) { - percentage = (uint8_t)idle_percent; + percentage = idle_percent; + if (option_set(Options::THROTTLE_WHILE_DISARMED) && !hal.util->get_soft_armed()) { + percentage = MAX(percentage, base_throttle); + } return true; } if (state == ICE_STARTING || state == ICE_START_DELAY) { - percentage = (uint8_t)start_percent.get(); + percentage = start_percent.get(); + return true; + } else if (state != ICE_RUNNING && hal.util->get_soft_armed()) { + percentage = 0; return true; } + + if (redline.flag && !option_set(Options::DISABLE_REDLINE_GOVERNOR)) { + // limit the throttle from increasing above what the current output is + if (redline.throttle_percentage < 1.0f) { + redline.throttle_percentage = percentage; + } + if (percentage < redline.throttle_percentage - redline.governor_integrator) { + // the throttle before the override is much lower than what the integrator is at + // reset the integrator + redline.governor_integrator = 0; + redline.throttle_percentage = percentage; + } else if (percentage < redline.throttle_percentage) { + // the throttle is below the integrator set point + // remove the difference from the integrator + redline.governor_integrator -= redline.throttle_percentage - percentage; + redline.throttle_percentage = percentage; + } else if (filtered_rpm_value > redline_rpm) { + // reduce the throttle if still over the redline RPM + const float redline_setpoint_step = idle_slew * AP::scheduler().get_loop_period_s(); + redline.governor_integrator += redline_setpoint_step; + } + percentage = redline.throttle_percentage - redline.governor_integrator; + return true; + } + + // if THROTTLE_WHILE_DISARMED is set then we use the base_throttle, allowing the pilot to control throttle while disarmed + if (option_set(Options::THROTTLE_WHILE_DISARMED) && !hal.util->get_soft_armed() && + base_throttle > percentage) { + percentage = base_throttle; + return true; + } + return false; } @@ -356,6 +440,10 @@ bool AP_ICEngine::engine_control(float start_control, float cold_start, float he state = ICE_OFF; return true; } + if (state == ICE_RUNNING || state == ICE_START_DELAY || state == ICE_STARTING) { + gcs().send_text(MAV_SEVERITY_INFO, "Engine: already running"); + return false; + } RC_Channel *c = rc().channel(start_chan-1); if (c != nullptr && rc().has_valid_input()) { // get starter control channel @@ -457,3 +545,5 @@ AP_ICEngine *ice() { return AP_ICEngine::get_singleton(); } } + +#endif // AP_ICENGINE_ENABLED diff --git a/libraries/AP_ICEngine/AP_ICEngine.h b/libraries/AP_ICEngine/AP_ICEngine.h index 9e894d7e7f9..f5a1818f227 100644 --- a/libraries/AP_ICEngine/AP_ICEngine.h +++ b/libraries/AP_ICEngine/AP_ICEngine.h @@ -18,13 +18,17 @@ */ #pragma once -#include -#include +#include "AP_ICEngine_config.h" + +#if AP_ICENGINE_ENABLED + +#include +#include class AP_ICEngine { public: // constructor - AP_ICEngine(const AP_RPM &_rpm); + AP_ICEngine(const class AP_RPM &_rpm); static const struct AP_Param::GroupInfo var_info[]; @@ -32,7 +36,7 @@ class AP_ICEngine { void update(void); // check for throttle override - bool throttle_override(uint8_t &percent); + bool throttle_override(float &percent, const float base_throttle); enum ICE_State { ICE_OFF=0, @@ -56,10 +60,14 @@ class AP_ICEngine { private: static AP_ICEngine *_singleton; - const AP_RPM &rpm; + const class AP_RPM &rpm; enum ICE_State state; + // filter for RPM value + LowPassFilterFloat _rpm_filter; + float filtered_rpm_value; + // enable library AP_Int8 enable; @@ -122,15 +130,31 @@ class AP_ICEngine { enum class Options : uint16_t { DISABLE_IGNITION_RC_FAILSAFE=(1U<<0), + DISABLE_REDLINE_GOVERNOR = (1U << 1), + THROTTLE_WHILE_DISARMED = (1U << 2), }; AP_Int16 options; + bool option_set(Options option) const { + return (options & uint16_t(option)) != 0; + } + // start_chan debounce uint16_t start_chan_last_value = 1500; uint32_t start_chan_last_ms; + + // redline rpm + AP_Int32 redline_rpm; + struct { + bool flag; + float governor_integrator; + float throttle_percentage; + } redline; }; namespace AP { AP_ICEngine *ice(); }; + +#endif // AP_ICENGINE_ENABLED diff --git a/libraries/AP_ICEngine/AP_ICEngine_config.h b/libraries/AP_ICEngine/AP_ICEngine_config.h new file mode 100644 index 00000000000..c609d429f12 --- /dev/null +++ b/libraries/AP_ICEngine/AP_ICEngine_config.h @@ -0,0 +1,7 @@ +#pragma once + +#include + +#ifndef AP_ICENGINE_ENABLED +#define AP_ICENGINE_ENABLED 1 +#endif diff --git a/libraries/AP_IOMCU/AP_IOMCU.cpp b/libraries/AP_IOMCU/AP_IOMCU.cpp index 8cfca628e32..d143be8f07b 100644 --- a/libraries/AP_IOMCU/AP_IOMCU.cpp +++ b/libraries/AP_IOMCU/AP_IOMCU.cpp @@ -18,6 +18,7 @@ #include #include #include +#include #include extern const AP_HAL::HAL &hal; @@ -242,6 +243,7 @@ void AP_IOMCU::thread_main(void) // read status at 20Hz read_status(); last_status_read_ms = AP_HAL::millis(); + write_log(); } if (now - last_servo_read_ms > 50) { @@ -350,7 +352,10 @@ void AP_IOMCU::read_status() force_safety_off(); } } +} +void AP_IOMCU::write_log() +{ uint32_t now = AP_HAL::millis(); if (now - last_log_ms >= 1000U) { last_log_ms = now; @@ -358,14 +363,16 @@ void AP_IOMCU::read_status() // @LoggerMessage: IOMC // @Description: IOMCU diagnostic information // @Field: TimeUS: Time since system startup +// @Field: RSErr: Status Read error count (zeroed on successful read) // @Field: Mem: Free memory // @Field: TS: IOMCU uptime // @Field: NPkt: Number of packets received by IOMCU // @Field: Nerr: Protocol failures on MCU side // @Field: Nerr2: Reported number of failures on IOMCU side // @Field: NDel: Number of delayed packets received by MCU - AP::logger().WriteStreaming("IOMC", "TimeUS,Mem,TS,NPkt,Nerr,Nerr2,NDel", "QHIIIII", + AP::logger().WriteStreaming("IOMC", "TimeUS,RSErr,Mem,TS,NPkt,Nerr,Nerr2,NDel", "QHHIIIII", AP_HAL::micros64(), + read_status_errors, reg_status.freemem, reg_status.timestamp_ms, reg_status.total_pkts, @@ -779,7 +786,7 @@ void AP_IOMCU::update_safety_options(void) if (!(options & AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_ON)) { desired_options |= P_SETUP_ARMING_SAFETY_DISABLE_ON; } - if (!(options & AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_ARMED) && hal.util->get_soft_armed()) { + if (!(options & AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_ARMED) && AP::arming().is_armed()) { desired_options |= (P_SETUP_ARMING_SAFETY_DISABLE_ON | P_SETUP_ARMING_SAFETY_DISABLE_OFF); } if (last_safety_options != desired_options) { @@ -814,7 +821,7 @@ bool AP_IOMCU::check_crc(void) fw = AP_ROMFS::find_decompress(fw_name, fw_size); if (!fw) { - hal.console->printf("failed to find %s\n", fw_name); + DEV_PRINTF("failed to find %s\n", fw_name); return false; } uint32_t crc = crc32_small(0, fw, fw_size); @@ -833,13 +840,13 @@ bool AP_IOMCU::check_crc(void) } } if (io_crc == crc) { - hal.console->printf("IOMCU: CRC ok\n"); + DEV_PRINTF("IOMCU: CRC ok\n"); crc_is_ok = true; AP_ROMFS::free(fw); fw = nullptr; return true; } else { - hal.console->printf("IOMCU: CRC mismatch expected: 0x%X got: 0x%X\n", (unsigned)crc, (unsigned)io_crc); + DEV_PRINTF("IOMCU: CRC mismatch expected: 0x%X got: 0x%X\n", (unsigned)crc, (unsigned)io_crc); } const uint16_t magic = REBOOT_BL_MAGIC; @@ -909,7 +916,7 @@ void AP_IOMCU::shutdown(void) */ void AP_IOMCU::bind_dsm(uint8_t mode) { - if (!is_chibios_backend || hal.util->get_soft_armed()) { + if (!is_chibios_backend || AP::arming().is_armed()) { // only with ChibiOS IO firmware, and disarmed return; } @@ -1011,11 +1018,13 @@ void AP_IOMCU::check_iomcu_reset(void) if (last_iocmu_timestamp_ms == 0) { // initialisation last_iocmu_timestamp_ms = reg_status.timestamp_ms; - hal.console->printf("IOMCU startup\n"); + DEV_PRINTF("IOMCU startup\n"); return; } uint32_t dt_ms = reg_status.timestamp_ms - last_iocmu_timestamp_ms; - uint32_t ts1 = last_iocmu_timestamp_ms; +#if IOMCU_DEBUG_ENABLE + const uint32_t ts1 = last_iocmu_timestamp_ms; +#endif // when we are in an expected delay allow for a larger time // delta. This copes with flash erase, such as bootloader update const uint32_t max_delay = hal.scheduler->in_expected_delay()?5000:500; @@ -1028,19 +1037,23 @@ void AP_IOMCU::check_iomcu_reset(void) } detected_io_reset = true; INTERNAL_ERROR(AP_InternalError::error_t::iomcu_reset); - hal.console->printf("IOMCU reset t=%u %u %u dt=%u\n", - unsigned(AP_HAL::millis()), unsigned(ts1), unsigned(reg_status.timestamp_ms), unsigned(dt_ms)); + debug("IOMCU reset t=%u %u %u dt=%u\n", + unsigned(AP_HAL::millis()), unsigned(ts1), unsigned(reg_status.timestamp_ms), unsigned(dt_ms)); - if (last_safety_off && !reg_status.flag_safety_off && hal.util->get_soft_armed()) { + bool have_forced_off = false; + if (last_safety_off && !reg_status.flag_safety_off && AP::arming().is_armed()) { AP_BoardConfig *boardconfig = AP_BoardConfig::get_singleton(); uint16_t options = boardconfig?boardconfig->get_safety_button_options():0; if (safety_forced_off || (options & AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_ARMED) == 0) { // IOMCU has reset while armed with safety off - force it off // again so we can keep flying + have_forced_off = true; force_safety_off(); } } - last_safety_off = reg_status.flag_safety_off; + if (!have_forced_off) { + last_safety_off = reg_status.flag_safety_off; + } // we need to ensure the mixer data and the rates are sent over to // the IOMCU @@ -1064,22 +1077,25 @@ void AP_IOMCU::check_iomcu_reset(void) last_rc_protocols = 0; } -// Check if pin number is valid for GPIO +// Check if pin number is valid and configured for GPIO bool AP_IOMCU::valid_GPIO_pin(uint8_t pin) const { - return convert_pin_number(pin); + // sanity check pin number + if (!convert_pin_number(pin)) { + return false; + } + + // check pin is enabled as GPIO + return ((GPIO.channel_mask & (1U << pin)) != 0); } // convert external pin numbers 101 to 108 to internal 0 to 7 bool AP_IOMCU::convert_pin_number(uint8_t& pin) const { - if (pin < 101) { + if (pin < 101 || pin > 108) { return false; } pin -= 101; - if (pin > 7) { - return false; - } return true; } diff --git a/libraries/AP_IOMCU/AP_IOMCU.h b/libraries/AP_IOMCU/AP_IOMCU.h index a4f0f962c22..d792731f9a6 100644 --- a/libraries/AP_IOMCU/AP_IOMCU.h +++ b/libraries/AP_IOMCU/AP_IOMCU.h @@ -107,7 +107,7 @@ class AP_IOMCU { bool setup_mixing(RCMapper *rcmap, int8_t override_chan, float mixing_gain, uint16_t manual_rc_mask); - // Check if pin number is valid for GPIO + // Check if pin number is valid and configured for GPIO bool valid_GPIO_pin(uint8_t pin) const; // convert external pin numbers 101 to 108 to internal 0 to 7 @@ -269,6 +269,8 @@ class AP_IOMCU { void handle_repeated_failures(); void check_iomcu_reset(); + void write_log(); // handle onboard logging + static AP_IOMCU *singleton; enum { diff --git a/libraries/AP_IOMCU/iofirmware/iofirmware.cpp b/libraries/AP_IOMCU/iofirmware/iofirmware.cpp index 4bf32f98c83..ea30c0077af 100644 --- a/libraries/AP_IOMCU/iofirmware/iofirmware.cpp +++ b/libraries/AP_IOMCU/iofirmware/iofirmware.cpp @@ -301,12 +301,14 @@ void AP_IOMCU_FW::rcin_update() { ((ChibiOS::RCInput *)hal.rcin)->_timer_tick(); if (hal.rcin->new_input()) { + const auto &rc = AP::RC(); rc_input.count = hal.rcin->num_channels(); rc_input.flags_rc_ok = true; hal.rcin->read(rc_input.pwm, IOMCU_MAX_CHANNELS); rc_last_input_ms = last_ms; - rc_input.rc_protocol = (uint16_t)AP::RC().protocol_detected(); - rc_input.rssi = AP::RC().get_RSSI(); + rc_input.rc_protocol = (uint16_t)rc.protocol_detected(); + rc_input.rssi = rc.get_RSSI(); + rc_input.flags_failsafe = rc.failsafe_active(); } else if (last_ms - rc_last_input_ms > 200U) { rc_input.flags_rc_ok = false; } diff --git a/libraries/AP_IOMCU/iofirmware/ioprotocol.h b/libraries/AP_IOMCU/iofirmware/ioprotocol.h index 7dbf319e666..4256b6d1953 100644 --- a/libraries/AP_IOMCU/iofirmware/ioprotocol.h +++ b/libraries/AP_IOMCU/iofirmware/ioprotocol.h @@ -159,9 +159,11 @@ struct page_mixing { // enabled needs to be 1 to enable mixing uint8_t enabled; - uint8_t pad; // pad to even size + uint8_t pad; }; +static_assert(sizeof(struct page_mixing) % 2 == 0, "page_mixing must be even size"); + struct __attribute__((packed, aligned(2))) page_GPIO { uint8_t channel_mask; uint8_t output_mask; diff --git a/libraries/AP_IOMCU/iofirmware/rc.cpp b/libraries/AP_IOMCU/iofirmware/rc.cpp index 8bde774f1b3..4cee86c774a 100644 --- a/libraries/AP_IOMCU/iofirmware/rc.cpp +++ b/libraries/AP_IOMCU/iofirmware/rc.cpp @@ -61,6 +61,12 @@ static const SerialConfig dsm_cfg = { nullptr, // ctx }; +static enum { + RC_SEARCHING, + RC_DSM_PORT, + RC_SBUS_PORT +} rc_state; + /* init rcin on DSM USART1 */ @@ -95,16 +101,25 @@ void AP_IOMCU_FW::rcin_serial_update(void) uint8_t b[16]; uint32_t n; uint32_t now = AP_HAL::millis(); + auto &rc = AP::RC(); + + if (rc.should_search(now)) { + rc_state = RC_SEARCHING; + } // read from DSM port - if ((n = chnReadTimeout(&SD1, b, sizeof(b), TIME_IMMEDIATE)) > 0) { + if ((rc_state == RC_SEARCHING || rc_state == RC_DSM_PORT) && + (n = chnReadTimeout(&SD1, b, sizeof(b), TIME_IMMEDIATE)) > 0) { n = MIN(n, sizeof(b)); // don't mix two 115200 uarts if (sd3_config == 0) { rc_stats.num_dsm_bytes += n; for (uint8_t i=0; i 0) { + if ((rc_state == RC_SEARCHING || rc_state == RC_SBUS_PORT) && + (n = chnReadTimeout(&SD3, b, sizeof(b), TIME_IMMEDIATE)) > 0) { eventflags_t flags; if (sd3_config == 0 && ((flags = chEvtGetAndClearFlags(&sd3_listener)) & SD_PARITY_ERROR)) { rc_stats.sbus_error = flags; @@ -121,8 +137,11 @@ void AP_IOMCU_FW::rcin_serial_update(void) n = MIN(n, sizeof(b)); rc_stats.num_sbus_bytes += n; for (uint8_t i=0; i 2000 && (sd3_config==1 || !sbus_out_enabled)) { + if (rc_state == RC_SEARCHING && + now - rc_stats.last_good_ms > 2000 && (sd3_config==1 || !sbus_out_enabled)) { rc_stats.last_good_ms = now; sd3_config ^= 1; sdStop(&SD3); diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index e9834911348..e2855b73d69 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -11,7 +11,9 @@ #include #include #include +#include #include +#include #if !APM_BUILD_TYPE(APM_BUILD_Rover) #include #endif @@ -62,7 +64,17 @@ extern const AP_HAL::HAL& hal; #else #define DEFAULT_GYRO_FILTER 20 #define DEFAULT_ACCEL_FILTER 20 -#define DEFAULT_STILL_THRESH 0.1f +#if APM_BUILD_TYPE(APM_BUILD_ArduPlane) && CONFIG_HAL_BOARD == HAL_BOARD_SITL + // In steady-state level flight on SITL Plane, especially while the motor is off, the INS system + // returns ins.is_still()==true. Baseline vibes while airborne are unrealistically low: around 0.07. + // A real aircraft would be experiencing micro turbulence and be rocking around a tiny bit. Therefore, + // for Plane SIM the vibe threshold needs to be a little lower. Since plane.is_flying() uses + // ins.is_still() during gps loss to detect if we're flying, we want to make sure we are not "perfectly" + // still in the air like we are on the ground. + #define DEFAULT_STILL_THRESH 0.05f +#else + #define DEFAULT_STILL_THRESH 0.1f +#endif #endif #if defined(STM32H7) || defined(STM32F7) @@ -188,7 +200,7 @@ const AP_Param::GroupInfo AP_InertialSensor::var_info[] = { // @Range: 0.8 1.2 // @User: Advanced // @Calibration: 1 - AP_GROUPINFO("ACCSCAL", 12, AP_InertialSensor, _accel_scale[0], 0), + AP_GROUPINFO("ACCSCAL", 12, AP_InertialSensor, _accel_scale[0], 1.0), // @Param: ACCOFFS_X // @DisplayName: Accelerometer offsets of X axis @@ -237,7 +249,7 @@ const AP_Param::GroupInfo AP_InertialSensor::var_info[] = { // @Calibration: 1 #if INS_MAX_INSTANCES > 1 - AP_GROUPINFO("ACC2SCAL", 14, AP_InertialSensor, _accel_scale[1], 0), + AP_GROUPINFO("ACC2SCAL", 14, AP_InertialSensor, _accel_scale[1], 1.0), #endif // @Param: ACC2OFFS_X @@ -290,7 +302,7 @@ const AP_Param::GroupInfo AP_InertialSensor::var_info[] = { // @Calibration: 1 #if INS_MAX_INSTANCES > 2 - AP_GROUPINFO("ACC3SCAL", 16, AP_InertialSensor, _accel_scale[2], 0), + AP_GROUPINFO("ACC3SCAL", 16, AP_InertialSensor, _accel_scale[2], 1.0), #endif // @Param: ACC3OFFS_X @@ -533,9 +545,7 @@ const AP_Param::GroupInfo AP_InertialSensor::var_info[] = { // @Bitmask: 0:FirstIMU,1:SecondIMU,2:ThirdIMU AP_GROUPINFO("FAST_SAMPLE", 36, AP_InertialSensor, _fast_sampling_mask, HAL_DEFAULT_INS_FAST_SAMPLE), - // @Group: NOTCH_ - // @Path: ../Filter/HarmonicNotchFilter.cpp - AP_SUBGROUPINFO(_notch_filter, "NOTCH_", 37, AP_InertialSensor, HarmonicNotchFilterParams), + // index 37 was NOTCH_ // @Group: LOG_ // @Path: ../AP_InertialSensor/BatchSampler.cpp @@ -545,12 +555,18 @@ const AP_Param::GroupInfo AP_InertialSensor::var_info[] = { // @DisplayName: IMU enable mask // @Description: Bitmask of IMUs to enable. It can be used to prevent startup of specific detected IMUs // @User: Advanced - // @Bitmask: 0:FirstIMU,1:SecondIMU,2:ThirdIMU + // @Bitmask: 0:FirstIMU,1:SecondIMU,2:ThirdIMU,3:FourthIMU,4:FifthIMU,5:SixthIMU,6:SeventhIMU AP_GROUPINFO("ENABLE_MASK", 40, AP_InertialSensor, _enable_mask, 0x7F), // @Group: HNTCH_ // @Path: ../Filter/HarmonicNotchFilter.cpp - AP_SUBGROUPINFO(_harmonic_notch_filter, "HNTCH_", 41, AP_InertialSensor, HarmonicNotchFilterParams), + AP_SUBGROUPINFO(harmonic_notches[0].params, "HNTCH_", 41, AP_InertialSensor, HarmonicNotchFilterParams), + +#if HAL_INS_NUM_HARMONIC_NOTCH_FILTERS > 1 + // @Group: HNTC2_ + // @Path: ../Filter/HarmonicNotchFilter.cpp + AP_SUBGROUPINFO(harmonic_notches[1].params, "HNTC2_", 53, AP_InertialSensor, HarmonicNotchFilterParams), +#endif // @Param: GYRO_RATE // @DisplayName: Gyro rate for IMUs with Fast Sampling enabled @@ -746,7 +762,7 @@ bool AP_InertialSensor::register_accel(uint8_t &instance, uint16_t raw_sample_ra _accel_id[_accel_count].set((int32_t) id); -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || (CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && AP_SIM_ENABLED) // assume this is the same sensor and save its ID to allow seamless // transition from when we didn't have the IDs. _accel_id_ok[_accel_count] = true; @@ -845,14 +861,6 @@ AP_InertialSensor::init(uint16_t loop_rate) _start_backends(); } - // initialise accel scale if need be. This is needed as we can't - // give non-zero default values for vectors in AP_Param - for (uint8_t i=0; ienabled(); +#else + bool fft_enabled = false; +#endif // the center frequency of the harmonic notch is always taken from the calculated value so that it can be updated // dynamically, the calculated value is always some multiple of the configured center frequency, so start with the // configured value - _calculated_harmonic_notch_freq_hz[0] = _harmonic_notch_filter.center_freq_hz(); - _num_calculated_harmonic_notch_frequencies = 1; - _num_dynamic_harmonic_notches = 1; - - uint8_t num_filters = 0; - const bool double_notch = _harmonic_notch_filter.hasOption(HarmonicNotchFilterParams::Options::DoubleNotch); + for (auto ¬ch : harmonic_notches) { + if (!notch.params.enabled() && !fft_enabled) { + continue; + } + notch.calculated_notch_freq_hz[0] = notch.params.center_freq_hz(); + notch.num_calculated_notch_frequencies = 1; + notch.num_dynamic_notches = 1; #if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane) - if (_harmonic_notch_filter.hasOption(HarmonicNotchFilterParams::Options::DynamicHarmonic)) { + if (notch.params.hasOption(HarmonicNotchFilterParams::Options::DynamicHarmonic)) { #if HAL_WITH_DSP - if (get_gyro_harmonic_notch_tracking_mode() == HarmonicNotchDynamicMode::UpdateGyroFFT) { - _num_dynamic_harmonic_notches = AP_HAL::DSP::MAX_TRACKED_PEAKS; // only 3 peaks supported currently - } else + if (notch.params.tracking_mode() == HarmonicNotchDynamicMode::UpdateGyroFFT) { + notch.num_dynamic_notches = AP_HAL::DSP::MAX_TRACKED_PEAKS; // only 3 peaks supported currently + } else #endif - { - AP_Motors *motors = AP::motors(); - _num_dynamic_harmonic_notches = __builtin_popcount(motors->get_motor_mask()); + { + AP_Motors *motors = AP::motors(); + if (motors != nullptr) { + notch.num_dynamic_notches = __builtin_popcount(motors->get_motor_mask()); + } + } + // avoid harmonics unless actually configured by the user + notch.params.set_default_harmonics(1); } - // avoid harmonics unless actually configured by the user - _harmonic_notch_filter.set_default_harmonics(1); - } #endif + } // count number of used sensors uint8_t sensors_used = 0; for (uint8_t i = 0; i < INS_MAX_INSTANCES; i++) { sensors_used += _use[i]; } - // calculate number of notches we might want to use for harmonic notch - if (_harmonic_notch_filter.enabled()) { - num_filters = __builtin_popcount( _harmonic_notch_filter.harmonics()) - * _num_dynamic_harmonic_notches * (double_notch ? 2 : 1) - * sensors_used; - } - // add filters used by static notch - if (_notch_filter.enabled()) { - _notch_filter.set_default_harmonics(1); - num_filters += __builtin_popcount(_notch_filter.harmonics()) - * (_notch_filter.hasOption(HarmonicNotchFilterParams::Options::DoubleNotch) ? 2 : 1) - * sensors_used; + uint8_t num_filters = 0; + for (auto ¬ch : harmonic_notches) { + // calculate number of notches we might want to use for harmonic notch + if (notch.params.enabled() || fft_enabled) { + const bool double_notch = notch.params.hasOption(HarmonicNotchFilterParams::Options::DoubleNotch); + const bool triple_notch = notch.params.hasOption(HarmonicNotchFilterParams::Options::TripleNotch); + const bool all_sensors = notch.params.hasOption(HarmonicNotchFilterParams::Options::EnableOnAllIMUs); + num_filters += __builtin_popcount(notch.params.harmonics()) + * notch.num_dynamic_notches * (double_notch ? 2 : triple_notch ? 3 : 1) + * (all_sensors?sensors_used:1); + } } if (num_filters > HAL_HNF_MAX_FILTERS) { @@ -921,18 +938,16 @@ AP_InertialSensor::init(uint16_t loop_rate) for (uint8_t i=0; iget_device(bus, address) @@ -1156,7 +1175,7 @@ AP_InertialSensor::detect_backends(void) #if CONFIG_HAL_BOARD == HAL_BOARD_ESP32 ADD_BACKEND(AP_InertialSensor_NONE::detect(*this, INS_NONE_SENSOR_A)); #else - hal.console->printf("INS: unable to initialise driver\n"); + DEV_PRINTF("INS: unable to initialise driver\n"); GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "INS: unable to initialise driver"); AP_BoardConfig::config_error("INS: unable to initialise driver"); #endif @@ -1187,48 +1206,51 @@ void AP_InertialSensor::periodic() */ bool AP_InertialSensor::_calculate_trim(const Vector3f &accel_sample, Vector3f &trim) { - // allow multiple rotations, this allows us to cope with tailsitters - const enum Rotation rotations[] = {ROTATION_NONE, -#ifndef HAL_BUILD_AP_PERIPH - AP::ahrs().get_view_rotation() + Rotation rotation = ROTATION_NONE; +#if APM_BUILD_TYPE(APM_BUILD_ArduPlane) + AP_AHRS_View *view = AP::ahrs().get_view(); + if (view != nullptr) { + // Use pitch to guess which axis the user is trying to trim + // 5 deg buffer to favor normal AHRS and avoid floating point funny business + if (fabsf(view->pitch) < (fabsf(AP::ahrs().pitch)+radians(5)) ) { + // user is trying to calibrate view + rotation = view->get_rotation(); + if (!is_zero(view->get_pitch_trim())) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Cannot calibrate with Q_TRIM_PITCH set"); + return false; + } + } + } #endif - }; - bool good_trim = false; - Vector3f newtrim; - for (const auto r : rotations) { - newtrim = trim; - switch (r) { - case ROTATION_NONE: - newtrim.y = atan2f(accel_sample.x, norm(accel_sample.y, accel_sample.z)); - newtrim.x = atan2f(-accel_sample.y, -accel_sample.z); - break; - case ROTATION_PITCH_90: { - newtrim.y = atan2f(accel_sample.z, norm(accel_sample.y, -accel_sample.x)); - newtrim.z = atan2f(-accel_sample.y, accel_sample.x); - break; - } - default: - // unsupported - continue; - } - if (fabsf(newtrim.x) <= radians(HAL_INS_TRIM_LIMIT_DEG) && - fabsf(newtrim.y) <= radians(HAL_INS_TRIM_LIMIT_DEG) && - fabsf(newtrim.z) <= radians(HAL_INS_TRIM_LIMIT_DEG)) { - good_trim = true; - break; - } + Vector3f newtrim = trim; + switch (rotation) { + case ROTATION_NONE: + newtrim.y = atan2f(accel_sample.x, norm(accel_sample.y, accel_sample.z)); + newtrim.x = atan2f(-accel_sample.y, -accel_sample.z); + break; + + case ROTATION_PITCH_90: { + newtrim.y = atan2f(accel_sample.z, norm(accel_sample.y, -accel_sample.x)); + newtrim.z = atan2f(-accel_sample.y, accel_sample.x); + break; } - if (!good_trim) { - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "trim over maximum of 10 degrees"); + default: + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "unsupported trim rotation"); return false; } - trim = newtrim; - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Trim OK: roll=%.2f pitch=%.2f yaw=%.2f", - (double)degrees(trim.x), - (double)degrees(trim.y), - (double)degrees(trim.z)); - return true; + if (fabsf(newtrim.x) <= radians(HAL_INS_TRIM_LIMIT_DEG) && + fabsf(newtrim.y) <= radians(HAL_INS_TRIM_LIMIT_DEG) && + fabsf(newtrim.z) <= radians(HAL_INS_TRIM_LIMIT_DEG)) { + trim = newtrim; + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Trim OK: roll=%.2f pitch=%.2f yaw=%.2f", + (double)degrees(trim.x), + (double)degrees(trim.y), + (double)degrees(trim.z)); + return true; + } + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "trim over maximum of 10 degrees"); + return false; } void @@ -1433,7 +1455,7 @@ AP_InertialSensor::_init_gyro() AP_Notify::flags.initialising = true; // cold start - hal.console->printf("Init Gyro"); + DEV_PRINTF("Init Gyro"); /* we do the gyro calibration with no board rotation. This avoids @@ -1484,7 +1506,7 @@ AP_InertialSensor::_init_gyro() memset(diff_norm, 0, sizeof(diff_norm)); - hal.console->printf("*"); + DEV_PRINTF("*"); for (uint8_t k=0; kprintf("\n"); + DEV_PRINTF("\n"); for (uint8_t k=0; kprintf("gyro[%u] did not converge: diff=%f dps (expected < %f)\n", + DEV_PRINTF("gyro[%u] did not converge: diff=%f dps (expected < %f)\n", (unsigned)k, (double)ToDeg(best_diff[k]), (double)GYRO_INIT_MAX_DIFF_DPS); - _gyro_offset[k] = best_avg[k]; + _gyro_offset[k].set(best_avg[k]); // flag calibration as failed for this gyro _gyro_cal_ok[k] = false; } else { _gyro_cal_ok[k] = true; - _gyro_offset[k] = new_gyro_offset[k]; + _gyro_offset[k].set(new_gyro_offset[k]); #if HAL_INS_TEMPERATURE_CAL_ENABLE - caltemp_gyro[k] = 0.5 * (get_temperature(k) + start_temperature[k]); + caltemp_gyro[k].set(0.5 * (get_temperature(k) + start_temperature[k])); #endif } } @@ -1585,6 +1607,32 @@ void AP_InertialSensor::_save_gyro_calibration() } } +/* + update harmonic notch parameters + */ +void AP_InertialSensor::HarmonicNotch::update_params(uint8_t instance, bool converging, float gyro_rate) +{ + const float center_freq = calculated_notch_freq_hz[0]; + if (!is_equal(last_bandwidth_hz[instance], params.bandwidth_hz()) || + !is_equal(last_attenuation_dB[instance], params.attenuation_dB()) || + (params.tracking_mode() == HarmonicNotchDynamicMode::Fixed && !is_equal(last_center_freq_hz[instance], center_freq)) || + converging) { + filter[instance].init(gyro_rate, + center_freq, + params.bandwidth_hz(), + params.attenuation_dB()); + last_center_freq_hz[instance] = center_freq; + last_bandwidth_hz[instance] = params.bandwidth_hz(); + last_attenuation_dB[instance] = params.attenuation_dB(); + } else if (params.tracking_mode() != HarmonicNotchDynamicMode::Fixed) { + if (num_calculated_notch_frequencies > 1) { + filter[instance].update(num_calculated_notch_frequencies, calculated_notch_freq_hz); + } else { + filter[instance].update(center_freq); + } + last_center_freq_hz[instance] = center_freq; + } +} /* update gyro and accel values from backends @@ -1960,7 +2008,15 @@ bool AP_InertialSensor::is_still() // return true if we are in a calibration bool AP_InertialSensor::calibrating() const { - return _calibrating_accel || _calibrating_gyro || (_acal && _acal->running()); + if (_calibrating_accel || _calibrating_gyro) { + return true; + } +#if HAL_INS_ACCELCAL_ENABLED + if (_acal && _acal->running()) { + return true; + } +#endif + return false; } /// calibrating - returns true if a temperature calibration is running @@ -1976,6 +2032,7 @@ bool AP_InertialSensor::temperature_cal_running() const return false; } +#if HAL_INS_ACCELCAL_ENABLED // initialise and register accel calibrator // called during the startup of accel cal void AP_InertialSensor::acal_init() @@ -2003,26 +2060,47 @@ void AP_InertialSensor::acal_update() _acal->cancel(); } } +#endif // Update the harmonic notch frequency -void AP_InertialSensor::update_harmonic_notch_freq_hz(float scaled_freq) { +void AP_InertialSensor::HarmonicNotch::update_freq_hz(float scaled_freq) +{ // protect against zero as the scaled frequency if (is_positive(scaled_freq)) { - _calculated_harmonic_notch_freq_hz[0] = scaled_freq; + calculated_notch_freq_hz[0] = scaled_freq; } - _num_calculated_harmonic_notch_frequencies = 1; + num_calculated_notch_frequencies = 1; } // Update the harmonic notch frequency -void AP_InertialSensor::update_harmonic_notch_frequencies_hz(uint8_t num_freqs, const float scaled_freq[]) { +void AP_InertialSensor::HarmonicNotch::update_frequencies_hz(uint8_t num_freqs, const float scaled_freq[]) { // protect against zero as the scaled frequency for (uint8_t i = 0; i < num_freqs; i++) { if (is_positive(scaled_freq[i])) { - _calculated_harmonic_notch_freq_hz[i] = scaled_freq[i]; + calculated_notch_freq_hz[i] = scaled_freq[i]; } } // any uncalculated frequencies will float at the previous value or the initialized freq if none - _num_calculated_harmonic_notch_frequencies = num_freqs; + num_calculated_notch_frequencies = num_freqs; +} + +// setup the notch for throttle based tracking, called from FFT based tuning +bool AP_InertialSensor::setup_throttle_gyro_harmonic_notch(float center_freq_hz, float ref) +{ + for (auto ¬ch : harmonic_notches) { + if (notch.params.tracking_mode() != HarmonicNotchDynamicMode::UpdateThrottle) { + continue; + } + notch.params.enable(); + notch.params.set_center_freq_hz(center_freq_hz); + notch.params.set_reference(ref); + notch.params.set_bandwidth_hz(center_freq_hz / 2.0f); + notch.params.save_params(); + // only enable the first notch + return true; + } + + return false; } /* @@ -2096,7 +2174,7 @@ void AP_InertialSensor::_acal_save_calibrations() if (fabsf(_trim_rad.x) > radians(HAL_INS_TRIM_LIMIT_DEG) || fabsf(_trim_rad.y) > radians(HAL_INS_TRIM_LIMIT_DEG) || fabsf(_trim_rad.z) > radians(HAL_INS_TRIM_LIMIT_DEG)) { - hal.console->printf("ERR: Trim over maximum of %.1f degrees!!", float(HAL_INS_TRIM_LIMIT_DEG)); + DEV_PRINTF("ERR: Trim over maximum of %.1f degrees!!", float(HAL_INS_TRIM_LIMIT_DEG)); _new_trim = false; //we have either got faulty level during acal or highly misaligned accelerometers } @@ -2133,11 +2211,7 @@ bool AP_InertialSensor::get_fixed_mount_accel_cal_sample(uint8_t sample_num, Vec return false; } _accel_calibrator[_acc_body_aligned-1].get_sample_corrected(sample_num, ret); - if (_board_orientation == ROTATION_CUSTOM && _custom_rotation) { - ret = *_custom_rotation * ret; - } else { - ret.rotate(_board_orientation); - } + ret.rotate(_board_orientation); return true; } @@ -2162,11 +2236,7 @@ bool AP_InertialSensor::get_primary_accel_cal_sample_avg(uint8_t sample_num, Vec } avg /= count; ret = avg; - if (_board_orientation == ROTATION_CUSTOM && _custom_rotation) { - ret = *_custom_rotation * ret; - } else { - ret.rotate(_board_orientation); - } + ret.rotate(_board_orientation); return true; } @@ -2242,7 +2312,7 @@ MAV_RESULT AP_InertialSensor::simple_accel_cal() memset(diff_norm, 0, sizeof(diff_norm)); - hal.console->printf("*"); + DEV_PRINTF("*"); for (uint8_t k=0; kprintf("\nPASSED\n"); + DEV_PRINTF("\nPASSED\n"); for (uint8_t k=0; kprintf("\nFAILED\n"); + DEV_PRINTF("\nFAILED\n"); // restore old values for (uint8_t k=0; k +#include /** maximum number of INS instances available on this platform. If more @@ -35,6 +35,14 @@ #define HAL_INS_TEMPERATURE_CAL_ENABLE !HAL_MINIMIZE_FEATURES && BOARD_FLASH_SIZE > 1024 #endif +#ifndef HAL_INS_NUM_HARMONIC_NOTCH_FILTERS +#define HAL_INS_NUM_HARMONIC_NOTCH_FILTERS 2 +#endif + +// time for the estimated gyro rates to converge +#ifndef HAL_INS_CONVERGANCE_MS +#define HAL_INS_CONVERGANCE_MS 30000 +#endif #include @@ -48,7 +56,7 @@ #include #ifndef AP_SIM_INS_ENABLED -#define AP_SIM_INS_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL) +#define AP_SIM_INS_ENABLED AP_SIM_ENABLED #endif class AP_InertialSensor_Backend; @@ -152,14 +160,11 @@ class AP_InertialSensor : AP_AccelCal_Client const Vector3f &get_accel(uint8_t i) const { return _accel[i]; } const Vector3f &get_accel(void) const { return get_accel(_primary_accel); } - uint32_t get_gyro_error_count(uint8_t i) const { return _gyro_error_count[i]; } - uint32_t get_accel_error_count(uint8_t i) const { return _accel_error_count[i]; } - // multi-device interface bool get_gyro_health(uint8_t instance) const { return (instance<_gyro_count) ? _gyro_healthy[instance] : false; } bool get_gyro_health(void) const { return get_gyro_health(_primary_gyro); } bool get_gyro_health_all(void) const; - uint8_t get_gyro_count(void) const { return MIN(INS_MAX_INSTANCES, _accel_count); } + uint8_t get_gyro_count(void) const { return MIN(INS_MAX_INSTANCES, _gyro_count); } bool gyro_calibrated_ok(uint8_t instance) const { return _gyro_cal_ok[instance]; } bool gyro_calibrated_ok_all() const; bool use_gyro(uint8_t instance) const; @@ -215,18 +220,17 @@ class AP_InertialSensor : AP_AccelCal_Client float get_gyro_drift_rate(void) const { return ToRad(0.5f/60); } // update gyro and accel values from accumulated samples - void update(void); + void update(void) __RAMFUNC__; // wait for a sample to be available - void wait_for_sample(void); + void wait_for_sample(void) __RAMFUNC__; // class level parameters static const struct AP_Param::GroupInfo var_info[]; // set overall board orientation - void set_board_orientation(enum Rotation orientation, Matrix3f* custom_rotation = nullptr) { + void set_board_orientation(enum Rotation orientation) { _board_orientation = orientation; - _custom_rotation = custom_rotation; } // return the selected loop rate at which samples are made avilable @@ -240,45 +244,14 @@ class AP_InertialSensor : AP_AccelCal_Client uint8_t get_primary_accel(void) const { return _primary_accel; } uint8_t get_primary_gyro(void) const { return _primary_gyro; } - // Update the harmonic notch frequency - void update_harmonic_notch_freq_hz(float scaled_freq); - // Update the harmonic notch frequencies - void update_harmonic_notch_frequencies_hz(uint8_t num_freqs, const float scaled_freq[]); - // get the gyro filter rate in Hz uint16_t get_gyro_filter_hz(void) const { return _gyro_filter_cutoff; } // get the accel filter rate in Hz uint16_t get_accel_filter_hz(void) const { return _accel_filter_cutoff; } - // harmonic notch current center frequency - float get_gyro_dynamic_notch_center_freq_hz(void) const { return _calculated_harmonic_notch_freq_hz[0]; } - - // number of dynamic harmonic notches - uint8_t get_num_gyro_dynamic_notches(void) const { return _num_dynamic_harmonic_notches; } - - // set of harmonic notch current center frequencies - const float* get_gyro_dynamic_notch_center_frequencies_hz(void) const { return _calculated_harmonic_notch_freq_hz; } - - // number of harmonic notch current center frequencies - uint8_t get_num_gyro_dynamic_notch_center_frequencies(void) const { return _num_calculated_harmonic_notch_frequencies; } - - // harmonic notch reference center frequency - float get_gyro_harmonic_notch_center_freq_hz(void) const { return _harmonic_notch_filter.center_freq_hz(); } - - // harmonic notch reference scale factor - float get_gyro_harmonic_notch_reference(void) const { return _harmonic_notch_filter.reference(); } - - // harmonic notch tracking mode - HarmonicNotchDynamicMode get_gyro_harmonic_notch_tracking_mode(void) const { return _harmonic_notch_filter.tracking_mode(); } - - // harmonic notch harmonics - uint8_t get_gyro_harmonic_notch_harmonics(void) const { return _harmonic_notch_filter.harmonics(); } - - // harmonic notch options - bool has_harmonic_option(HarmonicNotchFilterParams::Options option) { - return _harmonic_notch_filter.hasOption(option); - } + // setup the notch for throttle based tracking + bool setup_throttle_gyro_harmonic_notch(float center_freq_hz, float ref); // write out harmonic notch log messages void write_notch_log_messages() const; @@ -303,9 +276,6 @@ class AP_InertialSensor : AP_AccelCal_Client // check for vibration movement. True when all axis show nearly zero movement bool is_still(); - // return true if harmonic notch enabled - bool gyro_harmonic_notch_enabled(void) const { return _harmonic_notch_filter.enabled(); } - AuxiliaryBus *get_auxiliary_bus(int16_t backend_id) { return get_auxiliary_bus(backend_id, 0); } AuxiliaryBus *get_auxiliary_bus(int16_t backend_id, uint8_t instance); @@ -327,12 +297,14 @@ class AP_InertialSensor : AP_AccelCal_Client // Returns newly calculated trim values if calculated bool get_new_trim(Vector3f &trim_rad); +#if HAL_INS_ACCELCAL_ENABLED // initialise and register accel calibrator // called during the startup of accel cal void acal_init(); // update accel calibrator void acal_update(); +#endif // simple accel calibration #if HAL_GCS_ENABLED @@ -367,13 +339,17 @@ class AP_InertialSensor : AP_AccelCal_Client void periodic(); bool doing_sensor_rate_logging() const { return _doing_sensor_rate_logging; } - bool doing_post_filter_logging() const { return _doing_post_filter_logging; } + bool doing_post_filter_logging() const { + return (_doing_post_filter_logging && (post_filter || !_doing_sensor_rate_logging)) + || (_doing_pre_post_filter_logging && post_filter); + } // class level parameters static const struct AP_Param::GroupInfo var_info[]; // Parameters AP_Int16 _required_count; + uint16_t _real_required_count; AP_Int8 _sensor_mask; AP_Int8 _batch_options_mask; @@ -395,6 +371,7 @@ class AP_InertialSensor : AP_AccelCal_Client enum batch_opt_t { BATCH_OPT_SENSOR_RATE = (1<<0), BATCH_OPT_POST_FILTER = (1<<1), + BATCH_OPT_PRE_POST_FILTER = (1<<2), }; void rotate_to_next_sensor(); @@ -407,14 +384,18 @@ class AP_InertialSensor : AP_AccelCal_Client bool Write_ISBH(const float sample_rate_hz) const; bool Write_ISBD() const; + bool has_option(batch_opt_t option) const { return _batch_options_mask & uint16_t(option); } + uint64_t measurement_started_us; - bool initialised : 1; - bool isbh_sent : 1; - bool _doing_sensor_rate_logging : 1; - bool _doing_post_filter_logging : 1; - uint8_t instance : 3; // instance we are sending data for - AP_InertialSensor::IMU_SENSOR_TYPE type : 1; + bool initialised; + bool isbh_sent; + bool _doing_sensor_rate_logging; + bool _doing_post_filter_logging; + bool _doing_pre_post_filter_logging; + uint8_t instance; // instance we are sending data for + bool post_filter; // whether we are sending post-filter data + AP_InertialSensor::IMU_SENSOR_TYPE type; uint16_t isb_seqnum; int16_t *data_x; int16_t *data_y; @@ -446,6 +427,49 @@ class AP_InertialSensor : AP_AccelCal_Client // force save of current calibration as valid void force_save_calibration(void); + // structure per harmonic notch filter. This is public to allow for + // easy iteration + class HarmonicNotch { + public: + HarmonicNotchFilterParams params; + HarmonicNotchFilterVector3f filter[INS_MAX_INSTANCES]; + + uint8_t num_dynamic_notches; + + // the current center frequency for the notch + float calculated_notch_freq_hz[INS_MAX_NOTCHES]; + uint8_t num_calculated_notch_frequencies; + + // Update the harmonic notch frequency + void update_notch_freq_hz(float scaled_freq); + + // Update the harmonic notch frequencies + void update_notch_frequencies_hz(uint8_t num_freqs, const float scaled_freq[]); + + // runtime update of notch parameters + void update_params(uint8_t instance, bool converging, float gyro_rate); + + // Update the harmonic notch frequencies + void update_freq_hz(float scaled_freq); + void update_frequencies_hz(uint8_t num_freqs, const float scaled_freq[]); + + // enable/disable the notch + void set_inactive(bool _inactive) { + inactive = _inactive; + } + + bool is_inactive(void) const { + return inactive; + } + + private: + // support for updating harmonic filter at runtime + float last_center_freq_hz[INS_MAX_INSTANCES]; + float last_bandwidth_hz[INS_MAX_INSTANCES]; + float last_attenuation_dB[INS_MAX_INSTANCES]; + bool inactive; + } harmonic_notches[HAL_INS_NUM_HARMONIC_NOTCH_FILTERS]; + private: // load backend drivers bool _add_backend(AP_InertialSensor_Backend *backend); @@ -506,19 +530,6 @@ class AP_InertialSensor : AP_AccelCal_Client bool _new_accel_data[INS_MAX_INSTANCES]; bool _new_gyro_data[INS_MAX_INSTANCES]; - // optional notch filter on gyro - HarmonicNotchFilterParams _notch_filter; - HarmonicNotchFilterVector3f _gyro_notch_filter[INS_MAX_INSTANCES]; - - // optional harmonic notch filter on gyro - HarmonicNotchFilterParams _harmonic_notch_filter; - HarmonicNotchFilterVector3f _gyro_harmonic_notch_filter[INS_MAX_INSTANCES]; - // number of independent notches in the filter - uint8_t _num_dynamic_harmonic_notches; - // the current center frequency for the notch - float _calculated_harmonic_notch_freq_hz[INS_MAX_NOTCHES]; - uint8_t _num_calculated_harmonic_notch_frequencies; - // Most recent gyro reading Vector3f _gyro[INS_MAX_INSTANCES]; Vector3f _delta_angle[INS_MAX_INSTANCES]; @@ -595,7 +606,6 @@ class AP_InertialSensor : AP_AccelCal_Client // board orientation from AHRS enum Rotation _board_orientation; - Matrix3f* _custom_rotation; // per-sensor orientation to allow for board type defaults at runtime enum Rotation _gyro_orientation[INS_MAX_INSTANCES]; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_BMI055.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_BMI055.cpp index 07fe5f203b2..f916e0e063c 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_BMI055.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_BMI055.cpp @@ -161,7 +161,7 @@ bool AP_InertialSensor_BMI055::accel_init() goto failed; } - hal.console->printf("BMI055: found accel\n"); + DEV_PRINTF("BMI055: found accel\n"); dev_accel->get_semaphore()->give(); return true; @@ -215,7 +215,7 @@ bool AP_InertialSensor_BMI055::gyro_init() goto failed; } - hal.console->printf("BMI055: found gyro\n"); + DEV_PRINTF("BMI055: found gyro\n"); dev_gyro->get_semaphore()->give(); return true; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_BMI088.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_BMI088.cpp index f6df2e247fe..9188e99fb90 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_BMI088.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_BMI088.cpp @@ -28,8 +28,8 @@ #define REGA_STATUS 0x03 #define REGA_X_LSB 0x12 #define REGA_INT_STATUS_1 0x1D -#define REGA_TEMP_LSB 0x22 -#define REGA_TEMP_MSB 0x23 +#define REGA_TEMP_MSB 0x22 +#define REGA_TEMP_LSB 0x23 #define REGA_CONF 0x40 #define REGA_RANGE 0x41 #define REGA_PWR_CONF 0x7C @@ -97,7 +97,7 @@ AP_InertialSensor_BMI088::probe(AP_InertialSensor &imu, void AP_InertialSensor_BMI088::start() { - if (!_imu.register_accel(accel_instance, ACCEL_BACKEND_SAMPLE_RATE, dev_accel->get_bus_id_devtype(DEVTYPE_INS_BMI088)) || + if (!_imu.register_accel(accel_instance, ACCEL_BACKEND_SAMPLE_RATE, dev_accel->get_bus_id_devtype(_accel_devtype)) || !_imu.register_gyro(gyro_instance, GYRO_BACKEND_SAMPLE_RATE, dev_gyro->get_bus_id_devtype(DEVTYPE_INS_BMI088))) { return; } @@ -155,13 +155,13 @@ static const struct { uint8_t value; } accel_config[] = { { REGA_CONF, 0xAC }, - // setup 24g range + // setup 24g range (16g for BMI085) { REGA_RANGE, 0x03 }, // disable low-power mode { REGA_PWR_CONF, 0 }, { REGA_PWR_CTRL, 0x04 }, // setup FIFO for streaming X,Y,Z - { REGA_FIFO_CONFIG0, 0x00 }, + { REGA_FIFO_CONFIG0, 0x02 }, { REGA_FIFO_CONFIG1, 0x50 }, }; @@ -184,7 +184,7 @@ bool AP_InertialSensor_BMI088::setup_accel_config(void) } } done_accel_config = true; - hal.console->printf("BMI088: accel config OK (%u tries)\n", (unsigned)accel_config_count); + DEV_PRINTF("BMI088: accel config OK (%u tries)\n", (unsigned)accel_config_count); return true; } @@ -200,15 +200,30 @@ bool AP_InertialSensor_BMI088::accel_init() // dummy ready on accel ChipID to init accel (see section 3 of datasheet) read_accel_registers(REGA_CHIPID, &v, 1); - if (!read_accel_registers(REGA_CHIPID, &v, 1) || v != 0x1E) { + if (!read_accel_registers(REGA_CHIPID, &v, 1)) { return false; } + switch (v) { + case 0x1E: + _accel_devtype = DEVTYPE_INS_BMI088; + accel_range = 24.0; + hal.console->printf("BMI088: Found device\n"); + break; + case 0x1F: + _accel_devtype = DEVTYPE_INS_BMI085; + accel_range = 16.0; + hal.console->printf("BMI085: Found device\n"); + break; + default: + return false; + } + if (!setup_accel_config()) { - hal.console->printf("BMI088: delaying accel config\n"); + DEV_PRINTF("BMI08x: delaying accel config\n"); } - hal.console->printf("BMI088: found accel\n"); + DEV_PRINTF("BMI08x: found accel\n"); return true; } @@ -254,12 +269,12 @@ bool AP_InertialSensor_BMI088::gyro_init() return false; } - // setup FIFO for streaming X,Y,Z - if (!dev_gyro->write_register(REGG_FIFO_CONFIG_1, 0x80, true)) { + // setup FIFO for streaming X,Y,Z, with stop-at-full + if (!dev_gyro->write_register(REGG_FIFO_CONFIG_1, 0x40, true)) { return false; } - hal.console->printf("BMI088: found gyro\n"); + DEV_PRINTF("BMI088: found gyro\n"); return true; } @@ -304,8 +319,8 @@ void AP_InertialSensor_BMI088::read_fifo_accel(void) _inc_accel_error_count(accel_instance); return; } - // assume configured for 24g range - const float scale = (1.0/32768.0) * GRAVITY_MSS * 24.0; + // use new accel_range depending on sensor type + const float scale = (1.0/32768.0) * GRAVITY_MSS * accel_range; const uint8_t *p = &data[0]; while (fifo_length >= 7) { /* @@ -353,7 +368,7 @@ void AP_InertialSensor_BMI088::read_fifo_accel(void) if (temperature_counter++ == 100) { temperature_counter = 0; uint8_t tbuf[2]; - if (!read_accel_registers(REGA_TEMP_LSB, tbuf, 2)) { + if (!read_accel_registers(REGA_TEMP_MSB, tbuf, 2)) { _inc_accel_error_count(accel_instance); } else { uint16_t temp_uint11 = (tbuf[0]<<3) | (tbuf[1]>>5); @@ -374,38 +389,41 @@ void AP_InertialSensor_BMI088::read_fifo_gyro(void) _inc_gyro_error_count(gyro_instance); return; } + const float scale = radians(2000.0f) / 32767.0f; + const uint8_t max_frames = 8; + Vector3i data[max_frames]; + + if (num_frames & 0x80) { + // fifo overrun, reset, likely caused by scheduling error + dev_gyro->write_register(REGG_FIFO_CONFIG_1, 0x40, true); + goto check_next; + } + num_frames &= 0x7F; // don't read more than 8 frames at a time - if (num_frames > 8) { - num_frames = 8; - } + num_frames = MIN(num_frames, max_frames); if (num_frames == 0) { - return; + goto check_next; } - uint8_t data[6*num_frames]; - if (!dev_gyro->read_registers(REGG_FIFO_DATA, data, num_frames*6)) { + + if (!dev_gyro->read_registers(REGG_FIFO_DATA, (uint8_t *)data, num_frames*6)) { _inc_gyro_error_count(gyro_instance); - return; + goto check_next; } // data is 16 bits with 2000dps range - const float scale = radians(2000.0f) / 32767.0f; for (uint8_t i = 0; i < num_frames; i++) { - const uint8_t *d = &data[i*6]; - int16_t xyz[3] { - int16_t(uint16_t(d[0] | d[1]<<8)), - int16_t(uint16_t(d[2] | d[3]<<8)), - int16_t(uint16_t(d[4] | d[5]<<8)) }; - Vector3f gyro(xyz[0], xyz[1], xyz[2]); + Vector3f gyro(data[i].x, data[i].y, data[i].z); gyro *= scale; _rotate_and_correct_gyro(gyro_instance, gyro); _notify_new_gyro_raw_sample(gyro_instance, gyro); } +check_next: AP_HAL::Device::checkreg reg; - if (!dev_gyro->check_next_register()) { + if (!dev_gyro->check_next_register(reg)) { log_register_change(dev_gyro->get_bus_id(), reg); _inc_gyro_error_count(gyro_instance); } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_BMI088.h b/libraries/AP_InertialSensor/AP_InertialSensor_BMI088.h index cf1abd775f5..51b2cdcabc9 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_BMI088.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_BMI088.h @@ -81,6 +81,8 @@ class AP_InertialSensor_BMI088 : public AP_InertialSensor_Backend { uint8_t gyro_instance; enum Rotation rotation; uint8_t temperature_counter; + enum DevTypes _accel_devtype; + float accel_range; bool done_accel_config; uint32_t accel_config_count; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_BMI160.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_BMI160.cpp index a4fb2e7e809..aff58e5b350 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_BMI160.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_BMI160.cpp @@ -293,14 +293,14 @@ bool AP_InertialSensor_BMI160::_configure_int1_pin() r = _dev->write_register(BMI160_REG_INT_EN_1, BMI160_INT_FWM_EN); if (!r) { - hal.console->printf("BMI160: Unable to enable FIFO watermark interrupt engine\n"); + DEV_PRINTF("BMI160: Unable to enable FIFO watermark interrupt engine\n"); return false; } hal.scheduler->delay(1); r = _dev->write_register(BMI160_REG_INT_MAP_1, BMI160_INT_MAP_INT1_FWM); if (!r) { - hal.console->printf("BMI160: Unable to configure interrupt mapping\n"); + DEV_PRINTF("BMI160: Unable to configure interrupt mapping\n"); return false; } hal.scheduler->delay(1); @@ -308,14 +308,14 @@ bool AP_InertialSensor_BMI160::_configure_int1_pin() r = _dev->write_register(BMI160_REG_INT_OUT_CTRL, BMI160_INT1_OUTPUT_EN | BMI160_INT1_LVL); if (!r) { - hal.console->printf("BMI160: Unable to configure interrupt output\n"); + DEV_PRINTF("BMI160: Unable to configure interrupt output\n"); return false; } hal.scheduler->delay(1); _int1_pin = hal.gpio->channel(BMI160_INT1_GPIO); if (_int1_pin == nullptr) { - hal.console->printf("BMI160: Couldn't request data ready GPIO channel\n"); + DEV_PRINTF("BMI160: Couldn't request data ready GPIO channel\n"); return false; } _int1_pin->mode(HAL_GPIO_INPUT); @@ -331,7 +331,7 @@ bool AP_InertialSensor_BMI160::_configure_fifo() r = _dev->write_register(BMI160_REG_FIFO_CONFIG_0, sizeof(struct RawData) / 4); if (!r) { - hal.console->printf("BMI160: Unable to configure FIFO watermark level\n"); + DEV_PRINTF("BMI160: Unable to configure FIFO watermark level\n"); return false; } hal.scheduler->delay(1); @@ -339,7 +339,7 @@ bool AP_InertialSensor_BMI160::_configure_fifo() r = _dev->write_register(BMI160_REG_FIFO_CONFIG_1, BMI160_FIFO_ACC_EN | BMI160_FIFO_GYR_EN); if (!r) { - hal.console->printf("BMI160: Unable to enable FIFO\n"); + DEV_PRINTF("BMI160: Unable to enable FIFO\n"); return false; } hal.scheduler->delay(1); @@ -348,7 +348,7 @@ bool AP_InertialSensor_BMI160::_configure_fifo() r = _dev->write_register(BMI160_REG_CMD, BMI160_CMD_FIFO_FLUSH); if (!r) { - hal.console->printf("BMI160: Unable to flush FIFO\n"); + DEV_PRINTF("BMI160: Unable to flush FIFO\n"); return false; } @@ -399,7 +399,7 @@ void AP_InertialSensor_BMI160::_read_fifo() /* Read again just once */ if (excess && num_samples) { - hal.console->printf("BMI160: dropping %u samples from fifo\n", + DEV_PRINTF("BMI160: dropping %u samples from fifo\n", (uint8_t)(excess / sizeof(struct RawData))); _dev->write_register(BMI160_REG_CMD, BMI160_CMD_FIFO_FLUSH); excess = 0; @@ -434,7 +434,7 @@ void AP_InertialSensor_BMI160::_read_fifo() read_fifo_end: if (!r) { - hal.console->printf("BMI160: error on reading FIFO\n"); + DEV_PRINTF("BMI160: error on reading FIFO\n"); } } @@ -510,7 +510,7 @@ bool AP_InertialSensor_BMI160::_init() ret = _hardware_init(); if (!ret) { - hal.console->printf("BMI160: failed to init\n"); + DEV_PRINTF("BMI160: failed to init\n"); } return ret; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_BMI270.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_BMI270.cpp index 9800db8a266..79655c278bc 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_BMI270.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_BMI270.cpp @@ -143,6 +143,8 @@ const uint8_t AP_InertialSensor_BMI270::maximum_fifo_config_file[] = { BMI270_RE #define BMI270_HARDWARE_INIT_MAX_TRIES 5 +const uint32_t BACKEND_PERIOD_US = 1000000UL / BMI270_BACKEND_SAMPLE_RATE; + extern const AP_HAL::HAL& hal; AP_InertialSensor_BMI270::AP_InertialSensor_BMI270(AP_InertialSensor &imu, @@ -210,7 +212,6 @@ void AP_InertialSensor_BMI270::start() _dev->get_semaphore()->give(); - // using headerless mode so gyro and accel ODRs must match if (!_imu.register_accel(_accel_instance, BMI270_BACKEND_SAMPLE_RATE, _dev->get_bus_id_devtype(DEVTYPE_BMI270)) || !_imu.register_gyro(_gyro_instance, BMI270_BACKEND_SAMPLE_RATE, _dev->get_bus_id_devtype(DEVTYPE_BMI270))) { return; @@ -220,9 +221,8 @@ void AP_InertialSensor_BMI270::start() set_gyro_orientation(_gyro_instance, _rotation); set_accel_orientation(_accel_instance, _rotation); - /* Call _poll_data() at 1600Hz */ - _dev->register_periodic_callback(1000000UL / BMI270_BACKEND_SAMPLE_RATE, - FUNCTOR_BIND_MEMBER(&AP_InertialSensor_BMI270::poll_data, void)); + /* Call read_fifo() at 1600Hz */ + periodic_handle = _dev->register_periodic_callback(BACKEND_PERIOD_US, FUNCTOR_BIND_MEMBER(&AP_InertialSensor_BMI270::read_fifo, void)); } bool AP_InertialSensor_BMI270::update() @@ -318,8 +318,10 @@ void AP_InertialSensor_BMI270::check_err_reg() void AP_InertialSensor_BMI270::configure_accel() { - // set acc in high performance mode with normal filtering at 1600Hz - write_register(BMI270_REG_ACC_CONF, 1U<<7 | 0x2U<<4 | 0x0C); + // set acc in high performance mode with OSR4 filtering (751Hz/4) at 1600Hz + // see https://community.bosch-sensortec.com/t5/MEMS-sensors-forum/BMI270-OSR-mode-behaviour/td-p/52020 + // OSR4 is a 188Hz filter cutoff, acc_bwp == 0, equivalent to other driver filters + write_register(BMI270_REG_ACC_CONF, 1U<<7 | 0x0C); // set acc to 16G full scale write_register(BMI270_REG_ACC_RANGE, 0x03); @@ -328,8 +330,9 @@ void AP_InertialSensor_BMI270::configure_accel() void AP_InertialSensor_BMI270::configure_gyro() { - // set gyro in high performance filter mode, high performance noise mode. normal filtering at 1600Hz - write_register(BMI270_REG_GYRO_CONF, 1U<<7 | 1<<6 | 2<<4 | 0x0C); + // set gyro in high performance filter mode, high performance noise mode, normal filtering at 3.2KHz + // filter cutoff 751hz + write_register(BMI270_REG_GYRO_CONF, 1U<<7 | 1<<6 | 2<<4 | 0x0D); // set gyro to 2000dps full scale // for some reason you have to enable the ois_range bit (bit 3) for 2000dps as well // or else the gyro scale will be 250dps when in prefiltered FIFO mode (not documented in datasheet!) @@ -340,27 +343,44 @@ void AP_InertialSensor_BMI270::configure_gyro() void AP_InertialSensor_BMI270::configure_fifo() { - // don't stop when full, disable sensortime frame - write_register(BMI270_REG_FIFO_CONFIG_0, 0x00); + // stop when full, disable sensortime frame + write_register(BMI270_REG_FIFO_CONFIG_0, 0x01); // accel + gyro data in FIFO together with headers write_register(BMI270_REG_FIFO_CONFIG_1, 1U<<7 | 1U<<6 | 1U<<4); - // unfiltered with gyro downsampled by 2^2 to give 1600Hz - write_register(BMI270_REG_FIFO_DOWNS, 0x02); + // filtered data downsampled by 2**1 to 1600Hz + write_register(BMI270_REG_FIFO_DOWNS, 1U<<7 | 1U<<3 | 0x01); // disable advanced power save, enable FIFO self-wake write_register(BMI270_REG_PWR_CONF, 0x02); // Enable the gyro, accelerometer and temperature sensor - disable aux interface write_register(BMI270_REG_PWR_CTRL, 0x0E); - // flush FIFO - write_register(BMI270_REG_CMD, BMI270_CMD_FIFOFLUSH); + + fifo_reset(); check_err_reg(); } +void AP_InertialSensor_BMI270::fifo_reset() +{ + // flush and reset FIFO + write_register(BMI270_REG_CMD, BMI270_CMD_FIFOFLUSH); + + notify_accel_fifo_reset(_accel_instance); + notify_gyro_fifo_reset(_gyro_instance); +} + /* read fifo */ void AP_InertialSensor_BMI270::read_fifo(void) { + // check for FIFO errors/overflow + uint8_t err = 0; + read_registers(BMI270_REG_ERR_REG, &err, 1); + if ((err>>6 & 1) == 1) { + fifo_reset(); + return; + } + uint8_t len[2]; if (!read_registers(BMI270_REG_FIFO_LENGTH_LSB, len, 2)) { _inc_accel_error_count(_accel_instance); @@ -388,6 +408,10 @@ void AP_InertialSensor_BMI270::read_fifo(void) return; } + // adjust the periodic callback to be synchronous with the incoming data + // this means that we rarely run read_fifo() without updating the sensor data + _dev->adjust_periodic_callback(periodic_handle, BACKEND_PERIOD_US); + const uint8_t *p = &data[0]; while (fifo_length >= 12) { /* @@ -418,17 +442,22 @@ void AP_InertialSensor_BMI270::read_fifo(void) break; case 0x48: // fifo config frame - frame_len = 2; + frame_len = 5; break; case 0x50: // sample drop frame frame_len = 2; break; + case 0x80: + // invalid frame + fifo_reset(); + return; } p += frame_len; fifo_length -= frame_len; } + // temperature sensor updated every 10ms if (temperature_counter++ == 100) { temperature_counter = 0; uint8_t tbuf[2]; @@ -436,10 +465,12 @@ void AP_InertialSensor_BMI270::read_fifo(void) _inc_accel_error_count(_accel_instance); _inc_gyro_error_count(_gyro_instance); } else { - uint16_t temp_uint11 = (tbuf[0]<<3) | (tbuf[1]>>5); - int16_t temp_int11 = temp_uint11>1023?temp_uint11-2048:temp_uint11; - float temp_degc = temp_int11 * 0.125f + 23; - _publish_temperature(_accel_instance, temp_degc); + uint16_t tval = tbuf[0] | (tbuf[1] << 8); + if (tval != 0x8000) { // 0x8000 is invalid + int16_t klsb = static_cast(tval); + float temp_degc = klsb * 0.002f + 23.0f; + _publish_temperature(_accel_instance, temp_degc); + } } } } @@ -475,18 +506,14 @@ void AP_InertialSensor_BMI270::parse_gyro_frame(const uint8_t* d) _notify_new_gyro_raw_sample(_gyro_instance, gyro); } -void AP_InertialSensor_BMI270::poll_data() -{ - read_fifo(); -} - bool AP_InertialSensor_BMI270::hardware_init() { - bool ret = false; + bool init = false; + bool read_chip_id = false; hal.scheduler->delay(BMI270_POWERUP_DELAY_MSEC); - _dev->get_semaphore()->take_blocking(); + WITH_SEMAPHORE(_dev->get_semaphore()); _dev->set_speed(AP_HAL::Device::SPEED_LOW); @@ -512,6 +539,9 @@ bool AP_InertialSensor_BMI270::hardware_init() continue; } + // successfully identified the chip, proceed with initialisation + read_chip_id = true; + // disable power save write_register(BMI270_REG_PWR_CONF, 0x00); hal.scheduler->delay(1); // needs to be at least 450us @@ -532,27 +562,24 @@ bool AP_InertialSensor_BMI270::hardware_init() read_registers(BMI270_REG_INTERNAL_STATUS, &status, 1); if ((status & 1) == 1) { - ret = true; - hal.console->printf("BMI270 initialized after %d retries\n", i+1); + init = true; + DEV_PRINTF("BMI270 initialized after %d retries\n", i+1); break; } } _dev->set_speed(AP_HAL::Device::SPEED_HIGH); - _dev->get_semaphore()->give(); - return ret; + if (read_chip_id && !init) { + DEV_PRINTF("BMI270: failed to init\n"); + } + + return init; } bool AP_InertialSensor_BMI270::init() { - bool ret = false; _dev->set_read_flag(0x80); - ret = hardware_init(); - if (!ret) { - hal.console->printf("BMI270: failed to init\n"); - } - - return ret; + return hardware_init(); } \ No newline at end of file diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_BMI270.h b/libraries/AP_InertialSensor/AP_InertialSensor_BMI270.h index 4879832f012..fb21ca0f57d 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_BMI270.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_BMI270.h @@ -94,16 +94,14 @@ class AP_InertialSensor_BMI270 : public AP_InertialSensor_Backend { void configure_gyro(); /** - * Configure FIFO. - * - * @return true on success, false otherwise. + * Reset FIFO. */ - void configure_fifo(); + void fifo_reset(); /** - * Device periodic callback to read data from the sensors. + * Configure FIFO. */ - void poll_data(); + void configure_fifo(); /** * Read samples from fifo. @@ -113,6 +111,8 @@ class AP_InertialSensor_BMI270 : public AP_InertialSensor_Backend { void parse_gyro_frame(const uint8_t* d); AP_HAL::OwnPtr _dev; + AP_HAL::Device::PeriodicHandle periodic_handle; + enum Rotation _rotation; uint8_t _accel_instance; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp index e0c8dc21ad0..49bd6ac91b8 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp @@ -126,11 +126,7 @@ void AP_InertialSensor_Backend::_rotate_and_correct_accel(uint8_t instance, Vect } // rotate to body frame - if (_imu._board_orientation == ROTATION_CUSTOM && _imu._custom_rotation) { - accel = *_imu._custom_rotation * accel; - } else { - accel.rotate(_imu._board_orientation); - } + accel.rotate(_imu._board_orientation); } void AP_InertialSensor_Backend::_rotate_and_correct_gyro(uint8_t instance, Vector3f &gyro) @@ -155,11 +151,7 @@ void AP_InertialSensor_Backend::_rotate_and_correct_gyro(uint8_t instance, Vecto gyro -= _imu._gyro_offset[instance]; } - if (_imu._board_orientation == ROTATION_CUSTOM && _imu._custom_rotation) { - gyro = *_imu._custom_rotation * gyro; - } else { - gyro.rotate(_imu._board_orientation); - } + gyro.rotate(_imu._board_orientation); } /* @@ -182,6 +174,51 @@ void AP_InertialSensor_Backend::_publish_gyro(uint8_t instance, const Vector3f & _imu._delta_angle_acc_dt[instance] = 0; } +/* + apply harmonic notch and low pass gyro filters + */ +void AP_InertialSensor_Backend::apply_gyro_filters(const uint8_t instance, const Vector3f &gyro) +{ + Vector3f gyro_filtered = gyro; + + // apply the harmonic notch filters + for (auto ¬ch : _imu.harmonic_notches) { + if (!notch.params.enabled()) { + continue; + } + bool inactive = notch.is_inactive(); +#ifndef HAL_BUILD_AP_PERIPH + // by default we only run the expensive notch filters on the + // currently active IMU we reset the inactive notch filters so + // that if we switch IMUs we're not left with old data + if (!notch.params.hasOption(HarmonicNotchFilterParams::Options::EnableOnAllIMUs) && + instance != AP::ahrs().get_primary_gyro_index()) { + inactive = true; + } +#endif + if (inactive) { + // while inactive we reset the filter so when it activates the first output + // will be the first input sample + notch.filter[instance].reset(); + } else { + gyro_filtered = notch.filter[instance].apply(gyro_filtered); + } + } + + // apply the low pass filter last to attentuate any notch induced noise + gyro_filtered = _imu._gyro_filter[instance].apply(gyro_filtered); + + // if the filtering failed in any way then reset the filters and keep the old value + if (gyro_filtered.is_nan() || gyro_filtered.is_inf()) { + _imu._gyro_filter[instance].reset(); + for (auto ¬ch : _imu.harmonic_notches) { + notch.filter[instance].reset(); + } + } else { + _imu._gyro_filtered[instance] = gyro_filtered; + } +} + void AP_InertialSensor_Backend::_notify_new_gyro_raw_sample(uint8_t instance, const Vector3f &gyro, uint64_t sample_us) @@ -272,33 +309,14 @@ void AP_InertialSensor_Backend::_notify_new_gyro_raw_sample(uint8_t instance, _imu._gyro_window[instance][2].push(scaled_gyro.z); } #endif - Vector3f gyro_filtered = gyro; - - // apply the notch filter - if (_gyro_notch_enabled()) { - gyro_filtered = _imu._gyro_notch_filter[instance].apply(gyro_filtered); - } - // apply the harmonic notch filter - if (gyro_harmonic_notch_enabled()) { - gyro_filtered = _imu._gyro_harmonic_notch_filter[instance].apply(gyro_filtered); - } - - // apply the low pass filter last to attentuate any notch induced noise - gyro_filtered = _imu._gyro_filter[instance].apply(gyro_filtered); - - // if the filtering failed in any way then reset the filters and keep the old value - if (gyro_filtered.is_nan() || gyro_filtered.is_inf()) { - _imu._gyro_filter[instance].reset(); - _imu._gyro_notch_filter[instance].reset(); - _imu._gyro_harmonic_notch_filter[instance].reset(); - } else { - _imu._gyro_filtered[instance] = gyro_filtered; - } + // apply gyro filters + apply_gyro_filters(instance, gyro); _imu._new_gyro_data[instance] = true; } + // 5us if (!_imu.batchsampler.doing_post_filter_logging()) { log_gyro_raw(instance, sample_us, gyro); } @@ -393,29 +411,9 @@ void AP_InertialSensor_Backend::_notify_new_delta_angle(uint8_t instance, const _imu._gyro_window[instance][2].push(scaled_gyro.z); } #endif - Vector3f gyro_filtered = gyro; - - // apply the notch filter - if (_gyro_notch_enabled()) { - gyro_filtered = _imu._gyro_notch_filter[instance].apply(gyro_filtered); - } - - // apply the harmonic notch filter - if (gyro_harmonic_notch_enabled()) { - gyro_filtered = _imu._gyro_harmonic_notch_filter[instance].apply(gyro_filtered); - } - // apply the low pass filter last to attentuate any notch induced noise - gyro_filtered = _imu._gyro_filter[instance].apply(gyro_filtered); - - // if the filtering failed in any way then reset the filters and keep the old value - if (gyro_filtered.is_nan() || gyro_filtered.is_inf()) { - _imu._gyro_filter[instance].reset(); - _imu._gyro_notch_filter[instance].reset(); - _imu._gyro_harmonic_notch_filter[instance].reset(); - } else { - _imu._gyro_filtered[instance] = gyro_filtered; - } + // apply gyro filters + apply_gyro_filters(instance, gyro); _imu._new_gyro_data[instance] = true; } @@ -430,6 +428,7 @@ void AP_InertialSensor_Backend::_notify_new_delta_angle(uint8_t instance, const void AP_InertialSensor_Backend::log_gyro_raw(uint8_t instance, const uint64_t sample_us, const Vector3f &gyro) { +#if HAL_LOGGING_ENABLED AP_Logger *logger = AP_Logger::get_singleton(); if (logger == nullptr) { // should not have been called @@ -442,6 +441,7 @@ void AP_InertialSensor_Backend::log_gyro_raw(uint8_t instance, const uint64_t sa _imu.batchsampler.sample(instance, AP_InertialSensor::IMU_SENSOR_TYPE_GYRO, sample_us, gyro); } } +#endif } /* @@ -544,6 +544,7 @@ void AP_InertialSensor_Backend::_notify_new_accel_raw_sample(uint8_t instance, _imu._new_accel_data[instance] = true; } + // 5us if (!_imu.batchsampler.doing_post_filter_logging()) { log_accel_raw(instance, sample_us, accel); } else { @@ -643,6 +644,7 @@ void AP_InertialSensor_Backend::_notify_new_gyro_sensor_rate_sample(uint8_t inst void AP_InertialSensor_Backend::log_accel_raw(uint8_t instance, const uint64_t sample_us, const Vector3f &accel) { +#if HAL_LOGGING_ENABLED AP_Logger *logger = AP_Logger::get_singleton(); if (logger == nullptr) { // should not have been called @@ -655,6 +657,7 @@ void AP_InertialSensor_Backend::log_accel_raw(uint8_t instance, const uint64_t s _imu.batchsampler.sample(instance, AP_InertialSensor::IMU_SENSOR_TYPE_ACCEL, sample_us, accel); } } +#endif } void AP_InertialSensor_Backend::_set_accel_max_abs_offset(uint8_t instance, @@ -663,18 +666,6 @@ void AP_InertialSensor_Backend::_set_accel_max_abs_offset(uint8_t instance, _imu._accel_max_abs_offsets[instance] = max_offset; } -// set accelerometer error_count -void AP_InertialSensor_Backend::_set_accel_error_count(uint8_t instance, uint32_t error_count) -{ - _imu._accel_error_count[instance] = error_count; -} - -// set gyro error_count -void AP_InertialSensor_Backend::_set_gyro_error_count(uint8_t instance, uint32_t error_count) -{ - _imu._gyro_error_count[instance] = error_count; -} - // increment accelerometer error_count void AP_InertialSensor_Backend::_inc_accel_error_count(uint8_t instance) { @@ -728,36 +719,17 @@ void AP_InertialSensor_Backend::update_gyro(uint8_t instance) /* front end */ } // possibly update filter frequency + const float gyro_rate = _gyro_raw_sample_rate(instance); + if (_last_gyro_filter_hz != _gyro_filter_cutoff() || sensors_converging()) { - _imu._gyro_filter[instance].set_cutoff_frequency(_gyro_raw_sample_rate(instance), _gyro_filter_cutoff()); + _imu._gyro_filter[instance].set_cutoff_frequency(gyro_rate, _gyro_filter_cutoff()); _last_gyro_filter_hz = _gyro_filter_cutoff(); } - // possily update the harmonic notch filter parameters - if (!is_equal(_last_harmonic_notch_bandwidth_hz, gyro_harmonic_notch_bandwidth_hz()) || - !is_equal(_last_harmonic_notch_attenuation_dB, gyro_harmonic_notch_attenuation_dB()) || - sensors_converging()) { - _imu._gyro_harmonic_notch_filter[instance].init(_gyro_raw_sample_rate(instance), gyro_harmonic_notch_center_freq_hz(), gyro_harmonic_notch_bandwidth_hz(), gyro_harmonic_notch_attenuation_dB()); - _last_harmonic_notch_center_freq_hz = gyro_harmonic_notch_center_freq_hz(); - _last_harmonic_notch_bandwidth_hz = gyro_harmonic_notch_bandwidth_hz(); - _last_harmonic_notch_attenuation_dB = gyro_harmonic_notch_attenuation_dB(); - } else if (!is_equal(_last_harmonic_notch_center_freq_hz, gyro_harmonic_notch_center_freq_hz())) { - if (num_gyro_harmonic_notch_center_frequencies() > 1) { - _imu._gyro_harmonic_notch_filter[instance].update(num_gyro_harmonic_notch_center_frequencies(), gyro_harmonic_notch_center_frequencies_hz()); - } else { - _imu._gyro_harmonic_notch_filter[instance].update(gyro_harmonic_notch_center_freq_hz()); + for (auto ¬ch : _imu.harmonic_notches) { + if (notch.params.enabled()) { + notch.update_params(instance, sensors_converging(), gyro_rate); } - _last_harmonic_notch_center_freq_hz = gyro_harmonic_notch_center_freq_hz(); - } - // possily update the notch filter parameters - if (!is_equal(_last_notch_center_freq_hz, _gyro_notch_center_freq_hz()) || - !is_equal(_last_notch_bandwidth_hz, _gyro_notch_bandwidth_hz()) || - !is_equal(_last_notch_attenuation_dB, _gyro_notch_attenuation_dB()) || - sensors_converging()) { - _imu._gyro_notch_filter[instance].init(_gyro_raw_sample_rate(instance), _gyro_notch_center_freq_hz(), _gyro_notch_bandwidth_hz(), _gyro_notch_attenuation_dB()); - _last_notch_center_freq_hz = _gyro_notch_center_freq_hz(); - _last_notch_bandwidth_hz = _gyro_notch_bandwidth_hz(); - _last_notch_attenuation_dB = _gyro_notch_attenuation_dB(); } } @@ -802,10 +774,12 @@ bool AP_InertialSensor_Backend::should_log_imu_raw() const // log an unexpected change in a register for an IMU void AP_InertialSensor_Backend::log_register_change(uint32_t bus_id, const AP_HAL::Device::checkreg ®) { +#if HAL_LOGGING_ENABLED AP::logger().Write("IREG", "TimeUS,DevID,Bank,Reg,Val", "QIBBB", AP_HAL::micros64(), bus_id, reg.bank, reg.regnum, reg.value); +#endif } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Backend.h b/libraries/AP_InertialSensor/AP_InertialSensor_Backend.h index 7c0f1d23c1b..7cad5fb321b 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Backend.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Backend.h @@ -121,6 +121,8 @@ class AP_InertialSensor_Backend DEVTYPE_INS_ICM40605 = 0x36, DEVTYPE_INS_IIM42652 = 0x37, DEVTYPE_BMI270 = 0x38, + DEVTYPE_INS_BMI085 = 0x39, + DEVTYPE_INS_ICM42670 = 0x3A, }; protected: @@ -137,7 +139,10 @@ class AP_InertialSensor_Backend void _rotate_and_correct_gyro(uint8_t instance, Vector3f &gyro) __RAMFUNC__; // rotate gyro vector, offset and publish - void _publish_gyro(uint8_t instance, const Vector3f &gyro); /* front end */ + void _publish_gyro(uint8_t instance, const Vector3f &gyro) __RAMFUNC__; /* front end */ + + // apply notch and lowpass gyro filters + void apply_gyro_filters(const uint8_t instance, const Vector3f &gyro); // this should be called every time a new gyro raw sample is // available - be it published or not the sample is raw in the @@ -151,7 +156,7 @@ class AP_InertialSensor_Backend void _notify_new_delta_angle(uint8_t instance, const Vector3f &dangle); // rotate accel vector, scale, offset and publish - void _publish_accel(uint8_t instance, const Vector3f &accel); /* front end */ + void _publish_accel(uint8_t instance, const Vector3f &accel) __RAMFUNC__; /* front end */ // this should be called every time a new accel raw sample is available - // be it published or not @@ -200,7 +205,7 @@ class AP_InertialSensor_Backend void _update_sensor_rate(uint16_t &count, uint32_t &start_us, float &rate_hz) const __RAMFUNC__; // return true if the sensors are still converging and sampling rates could change significantly - bool sensors_converging() const { return AP_HAL::millis() < 30000; } + bool sensors_converging() const { return AP_HAL::millis() < HAL_INS_CONVERGANCE_MS; } // set accelerometer max absolute offset for calibration void _set_accel_max_abs_offset(uint8_t instance, float offset); @@ -230,12 +235,6 @@ class AP_InertialSensor_Backend // publish a temperature value void _publish_temperature(uint8_t instance, float temperature); /* front end */ - // set accelerometer error_count - void _set_accel_error_count(uint8_t instance, uint32_t error_count); - - // set gyro error_count - void _set_gyro_error_count(uint8_t instance, uint32_t error_count); - // increment accelerometer error_count void _inc_accel_error_count(uint8_t instance) __RAMFUNC__; @@ -257,51 +256,15 @@ class AP_InertialSensor_Backend return (uint16_t)_imu._loop_rate; } - // return the notch filter center in Hz for the sample rate - float _gyro_notch_center_freq_hz(void) const { return _imu._notch_filter.center_freq_hz(); } - - // return the notch filter bandwidth in Hz for the sample rate - float _gyro_notch_bandwidth_hz(void) const { return _imu._notch_filter.bandwidth_hz(); } - - // return the notch filter attenuation in dB for the sample rate - float _gyro_notch_attenuation_dB(void) const { return _imu._notch_filter.attenuation_dB(); } - - bool _gyro_notch_enabled(void) const { return _imu._notch_filter.enabled(); } - - // return the harmonic notch filter center in Hz for the sample rate - float gyro_harmonic_notch_center_freq_hz() const { return _imu.get_gyro_dynamic_notch_center_freq_hz(); } - - // set of harmonic notch current center frequencies - const float* gyro_harmonic_notch_center_frequencies_hz(void) const { return _imu.get_gyro_dynamic_notch_center_frequencies_hz(); } - - // number of harmonic notch current center frequencies - uint8_t num_gyro_harmonic_notch_center_frequencies(void) const { return _imu.get_num_gyro_dynamic_notch_center_frequencies(); } - - // return the harmonic notch filter bandwidth in Hz for the sample rate - float gyro_harmonic_notch_bandwidth_hz(void) const { return _imu._harmonic_notch_filter.bandwidth_hz(); } - - // return the harmonic notch filter attenuation in dB for the sample rate - float gyro_harmonic_notch_attenuation_dB(void) const { return _imu._harmonic_notch_filter.attenuation_dB(); } - - bool gyro_harmonic_notch_enabled(void) const { return _imu._harmonic_notch_filter.enabled(); } - // common gyro update function for all backends - void update_gyro(uint8_t instance); /* front end */ + void update_gyro(uint8_t instance) __RAMFUNC__; /* front end */ // common accel update function for all backends - void update_accel(uint8_t instance); /* front end */ + void update_accel(uint8_t instance) __RAMFUNC__; /* front end */ // support for updating filter at runtime uint16_t _last_accel_filter_hz; uint16_t _last_gyro_filter_hz; - float _last_notch_center_freq_hz; - float _last_notch_bandwidth_hz; - float _last_notch_attenuation_dB; - - // support for updating harmonic filter at runtime - float _last_harmonic_notch_center_freq_hz; - float _last_harmonic_notch_bandwidth_hz; - float _last_harmonic_notch_attenuation_dB; void set_gyro_orientation(uint8_t instance, enum Rotation rotation) { _imu._gyro_orientation[instance] = rotation; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Invensense.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_Invensense.cpp index afeace96608..0f6e5e3070e 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Invensense.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Invensense.cpp @@ -27,6 +27,7 @@ #include #include "AP_InertialSensor_Invensense.h" +#include extern const AP_HAL::HAL& hal; @@ -46,6 +47,10 @@ extern const AP_HAL::HAL& hal; #define debug(fmt, args ...) do {printf("MPU: " fmt "\n", ## args); } while(0) #endif +#ifndef HAL_ENABLE_FAST_FIFO_RESET_ICM20602 +#define HAL_ENABLE_FAST_FIFO_RESET_ICM20602 0 +#endif + /* EXT_SYNC allows for frame synchronisation with an external device such as a camera. When enabled the LSB of AccelZ holds the FSYNC bit @@ -195,6 +200,16 @@ void AP_InertialSensor_Invensense::_fifo_reset(bool log_error) notify_gyro_fifo_reset(_gyro_instance); } +void AP_InertialSensor_Invensense::_fast_fifo_reset() +{ + fast_reset_count++; + _register_write(MPUREG_USER_CTRL, _last_stat_user_ctrl | BIT_USER_CTRL_FIFO_RESET); + + notify_accel_fifo_reset(_accel_instance); + notify_gyro_fifo_reset(_gyro_instance); +} + + bool AP_InertialSensor_Invensense::_has_auxiliary_bus() { return _dev->bus_type() != AP_HAL::Device::BUS_TYPE_I2C; @@ -225,6 +240,10 @@ void AP_InertialSensor_Invensense::start() case Invensense_ICM20602: gdev = DEVTYPE_INS_ICM20602; adev = DEVTYPE_INS_ICM20602; + // ICM20602 has a bug where sometimes the data gets a huge offset + // this seems to be fixed by doing a quick FIFO reset via USR_CTRL + // reg + _enable_fast_fifo_reset = HAL_ENABLE_FAST_FIFO_RESET_ICM20602; _enable_offset_checking = true; break; case Invensense_ICM20601: @@ -417,7 +436,7 @@ void AP_InertialSensor_Invensense::start() bool AP_InertialSensor_Invensense::get_output_banner(char* banner, uint8_t banner_len) { if (_fast_sampling) { snprintf(banner, banner_len, "IMU%u: fast sampling enabled %.1fkHz/%.1fkHz", - _gyro_instance, _gyro_backend_rate_hz * _gyro_fifo_downsample_rate / 1000.0, _gyro_backend_rate_hz / 1000.0); + _gyro_instance, _gyro_backend_rate_hz * _gyro_fifo_downsample_rate * 0.001, _gyro_backend_rate_hz * 0.001); return true; } return false; @@ -434,6 +453,27 @@ bool AP_InertialSensor_Invensense::update() /* front end */ _publish_temperature(_accel_instance, _temp_filtered); +#if HAL_ENABLE_FAST_FIFO_RESET_ICM20602 + if (fast_reset_count) { + // check if we have reported in the last 1 seconds or + // fast_reset_count changed +#if HAL_GCS_ENABLED && BOARD_FLASH_SIZE > 1024 + const uint32_t now = AP_HAL::millis(); + if (now - last_fast_reset_count_report_ms > 5000U) { + last_fast_reset_count_report_ms = now; + char param_name[sizeof("IMUxx_RST")]; + snprintf(param_name, sizeof(param_name), "IMU%u_RST", MIN(_gyro_instance,9)); + gcs().send_named_float(param_name, fast_reset_count); + } +#endif +#if HAL_LOGGING_ENABLED + if (last_fast_reset_count != fast_reset_count) { + AP::logger().Write_MessageF("IMU%u fast fifo reset %u", _gyro_instance, fast_reset_count); + last_fast_reset_count = fast_reset_count; + } +#endif + } +#endif return true; } @@ -547,11 +587,16 @@ bool AP_InertialSensor_Invensense::_accumulate(uint8_t *samples, uint8_t n_sampl int16_t t2 = int16_val(data, 3); if (!_check_raw_temp(t2)) { - if (!hal.scheduler->in_expected_delay()) { - debug("temp reset IMU[%u] %d %d", _accel_instance, _raw_temp, t2); + if (_enable_fast_fifo_reset) { + _fast_fifo_reset(); + return false; + } else { + if (!hal.scheduler->in_expected_delay()) { + debug("temp reset IMU[%u] %d %d", _accel_instance, _raw_temp, t2); + } + _fifo_reset(true); + return false; } - _fifo_reset(true); - return false; } float temp = t2 * temp_sensitivity + temp_zero; @@ -589,14 +634,22 @@ bool AP_InertialSensor_Invensense::_accumulate_sensor_rate_sampling(uint8_t *sam for (uint8_t i = 0; i < n_samples; i++) { const uint8_t *data = samples + MPU_SAMPLE_SIZE * i; - // use temperatue to detect FIFO corruption + // use temperature to detect FIFO corruption int16_t t2 = int16_val(data, 3); if (!_check_raw_temp(t2)) { - if (!hal.scheduler->in_expected_delay()) { - debug("temp reset IMU[%u] %d %d", _accel_instance, _raw_temp, t2); +#if HAL_ENABLE_FAST_FIFO_RESET_ICM20602 + if (_enable_fast_fifo_reset) { + _fast_fifo_reset(); + ret = false; + } else +#endif + { + if (!hal.scheduler->in_expected_delay()) { + debug("temp reset IMU[%u] %d %d", _accel_instance, _raw_temp, t2); + } + _fifo_reset(true); + ret = false; } - _fifo_reset(true); - ret = false; break; } tsum += t2; @@ -727,7 +780,7 @@ void AP_InertialSensor_Invensense::_read_fifo() if (_fast_sampling) { if (!_accumulate_sensor_rate_sampling(rx, n)) { - if (!hal.scheduler->in_expected_delay()) { + if (!hal.scheduler->in_expected_delay() && !_enable_fast_fifo_reset) { debug("IMU[%u] stop at %u of %u", _accel_instance, n_samples, bytes_read/MPU_SAMPLE_SIZE); } break; @@ -759,7 +812,9 @@ void AP_InertialSensor_Invensense::_read_fifo() events to help with log analysis, but don't shout at the GCS to prevent possible flood */ +#if HAL_LOGGING_ENABLED AP::logger().Write_MessageF("ICM20602 yofs fix: %x %x", y_ofs, _saved_y_ofs_high); +#endif _register_write(MPUREG_ACC_OFF_Y_H, _saved_y_ofs_high); } } @@ -971,6 +1026,13 @@ bool AP_InertialSensor_Invensense::_hardware_init(void) /* bus-dependent initialization */ if (_dev->bus_type() == AP_HAL::Device::BUS_TYPE_SPI) { + /* reset signal path as recommended in the datasheet */ + if (_mpu_type == Invensense_MPU6000 || _mpu_type == Invensense_MPU6500) { + _register_write(MPUREG_SIGNAL_PATH_RESET, + BIT_SIGNAL_PATH_RESET_TEMP_RESET|BIT_SIGNAL_PATH_RESET_ACCEL_RESET|BIT_SIGNAL_PATH_RESET_GYRO_RESET); + hal.scheduler->delay(100); + } + /* Disable I2C bus if SPI selected (Recommended in Datasheet to be * done just after the device is reset) */ _last_stat_user_ctrl |= BIT_USER_CTRL_I2C_IF_DIS; @@ -1004,7 +1066,7 @@ bool AP_InertialSensor_Invensense::_hardware_init(void) _dev->set_speed(AP_HAL::Device::SPEED_HIGH); if (tries == 5) { - hal.console->printf("Failed to boot Invensense 5 times\n"); + DEV_PRINTF("Failed to boot Invensense 5 times\n"); return false; } @@ -1055,7 +1117,7 @@ int AP_Invensense_AuxiliaryBusSlave::passthrough_read(uint8_t reg, uint8_t *buf, uint8_t size) { if (_registered) { - hal.console->printf("Error: can't passthrough when slave is already configured\n"); + DEV_PRINTF("Error: can't passthrough when slave is already configured\n"); return -1; } @@ -1081,7 +1143,7 @@ int AP_Invensense_AuxiliaryBusSlave::passthrough_read(uint8_t reg, uint8_t *buf, int AP_Invensense_AuxiliaryBusSlave::passthrough_write(uint8_t reg, uint8_t val) { if (_registered) { - hal.console->printf("Error: can't passthrough when slave is already configured\n"); + DEV_PRINTF("Error: can't passthrough when slave is already configured\n"); return -1; } @@ -1104,7 +1166,7 @@ int AP_Invensense_AuxiliaryBusSlave::passthrough_write(uint8_t reg, uint8_t val) int AP_Invensense_AuxiliaryBusSlave::read(uint8_t *buf) { if (!_registered) { - hal.console->printf("Error: can't read before configuring slave\n"); + DEV_PRINTF("Error: can't read before configuring slave\n"); return -1; } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Invensense.h b/libraries/AP_InertialSensor/AP_InertialSensor_Invensense.h index 798dea82a18..7f77e35e48a 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Invensense.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Invensense.h @@ -45,7 +45,7 @@ class AP_InertialSensor_Invensense : public AP_InertialSensor_Backend enum Rotation rotation); /* update accel and gyro state */ - bool update() override; /* front end */ + bool update() override __RAMFUNC__; /* front end */ void accumulate() override; /* front end */ /* @@ -86,6 +86,8 @@ class AP_InertialSensor_Invensense : public AP_InertialSensor_Backend void _set_filter_register(void); void _fifo_reset(bool log_error) __RAMFUNC__; + void _fast_fifo_reset() __RAMFUNC__; + bool _has_auxiliary_bus(); /* Read samples from FIFO (FIFO enabled) */ @@ -129,12 +131,18 @@ class AP_InertialSensor_Invensense : public AP_InertialSensor_Backend LowPassFilter2pFloat _temp_filter; uint32_t last_reset_ms; uint8_t reset_count; + uint8_t fast_reset_count; + uint8_t last_fast_reset_count; + uint32_t last_fast_reset_count_report_ms; enum Rotation _rotation; // enable checking of unexpected resets of offsets bool _enable_offset_checking; + // enable fast fifo reset instead of full fifo reset + bool _enable_fast_fifo_reset; + // ICM-20602 y offset register. See usage for explanation uint8_t _saved_y_ofs_high; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Invensense_registers.h b/libraries/AP_InertialSensor/AP_InertialSensor_Invensense_registers.h index 601f91a5c46..9ca418caee5 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Invensense_registers.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Invensense_registers.h @@ -113,6 +113,11 @@ # define BIT_I2C_SLV1_DLY_EN 0x02 # define BIT_I2C_SLV2_DLY_EN 0x04 # define BIT_I2C_SLV3_DLY_EN 0x08 +#define MPUREG_SIGNAL_PATH_RESET 0x68 +// bit definitions for MPUREG_SIGNAL_PATH_RESET +# define BIT_SIGNAL_PATH_RESET_TEMP_RESET 0x01 // resets temp signal path +# define BIT_SIGNAL_PATH_RESET_ACCEL_RESET 0x02 // resets accel signal path +# define BIT_SIGNAL_PATH_RESET_GYRO_RESET 0x04 // resets gyro signal path #define MPUREG_USER_CTRL 0x6A // bit definitions for MPUREG_USER_CTRL # define BIT_USER_CTRL_SIG_COND_RESET 0x01 // resets signal paths and results registers for all sensors (gyros, accel, temp) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Invensensev2.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_Invensensev2.cpp index 28bbc2aa9f3..8cf151c5b0f 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Invensensev2.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Invensensev2.cpp @@ -244,7 +244,7 @@ void AP_InertialSensor_Invensensev2::start() bool AP_InertialSensor_Invensensev2::get_output_banner(char* banner, uint8_t banner_len) { if (_fast_sampling) { snprintf(banner, banner_len, "IMU%u: fast sampling enabled %.1fkHz/%.1fkHz", - _gyro_instance, _gyro_backend_rate_hz * _gyro_fifo_downsample_rate / 1000.0, _gyro_backend_rate_hz / 1000.0); + _gyro_instance, _gyro_backend_rate_hz * _gyro_fifo_downsample_rate * 0.001, _gyro_backend_rate_hz * 0.001); return true; } return false; @@ -564,7 +564,6 @@ uint8_t AP_InertialSensor_Invensensev2::_register_read(uint16_t reg) void AP_InertialSensor_Invensensev2::_register_write(uint16_t reg, uint8_t val, bool checked) { - (void)checked; _dev->write_bank_register(GET_BANK(reg), GET_REG(reg), val, checked); } @@ -724,7 +723,7 @@ bool AP_InertialSensor_Invensensev2::_hardware_init(void) _dev->set_speed(AP_HAL::Device::SPEED_HIGH); if (tries == 5) { - hal.console->printf("Failed to boot Invensense 5 times\n"); + DEV_PRINTF("Failed to boot Invensense 5 times\n"); return false; } @@ -771,7 +770,7 @@ int AP_Invensensev2_AuxiliaryBusSlave::passthrough_read(uint8_t reg, uint8_t *bu uint8_t size) { if (_registered) { - hal.console->printf("Error: can't passthrough when slave is already configured\n"); + DEV_PRINTF("Error: can't passthrough when slave is already configured\n"); return -1; } @@ -797,7 +796,7 @@ int AP_Invensensev2_AuxiliaryBusSlave::passthrough_read(uint8_t reg, uint8_t *bu int AP_Invensensev2_AuxiliaryBusSlave::passthrough_write(uint8_t reg, uint8_t val) { if (_registered) { - hal.console->printf("Error: can't passthrough when slave is already configured\n"); + DEV_PRINTF("Error: can't passthrough when slave is already configured\n"); return -1; } @@ -820,7 +819,7 @@ int AP_Invensensev2_AuxiliaryBusSlave::passthrough_write(uint8_t reg, uint8_t va int AP_Invensensev2_AuxiliaryBusSlave::read(uint8_t *buf) { if (!_registered) { - hal.console->printf("Error: can't read before configuring slave\n"); + DEV_PRINTF("Error: can't read before configuring slave\n"); return -1; } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Invensensev3.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_Invensensev3.cpp index c83203fc01b..06e28d211fe 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Invensensev3.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Invensensev3.cpp @@ -19,22 +19,20 @@ ICM-40609 ICM-42688 ICM-42605 - ICM-40605 + ICM-40605 - EOL IIM-42652 + ICM-42670 Note that this sensor includes 32kHz internal sampling and an anti-aliasing filter, which means this driver can be a lot simpler than the Invensense and Invensensev2 drivers which need to handle 8kHz sample rates to achieve decent aliasing protection - - The sensor is a multi-bank design (4 banks) but as this driver only - needs access to the first bank and the default bank is the first - bank we can treat it as a single bank design */ #include #include "AP_InertialSensor_Invensensev3.h" #include +#include extern const AP_HAL::HAL& hal; @@ -48,30 +46,65 @@ static const float GYRO_SCALE = (0.0174532f / 16.4f); // registers we use #define INV3REG_WHOAMI 0x75 -#define INV3REG_INT_CONFIG 0x14 #define INV3REG_FIFO_CONFIG 0x16 #define INV3REG_PWR_MGMT0 0x4e #define INV3REG_GYRO_CONFIG0 0x4f #define INV3REG_ACCEL_CONFIG0 0x50 +#define INV3REG_GYRO_CONFIG1 0x51 +#define INV3REG_GYRO_ACCEL_CONFIG0 0x52 +#define INV3REG_ACCEL_CONFIG1 0x53 #define INV3REG_FIFO_CONFIG1 0x5f #define INV3REG_FIFO_CONFIG2 0x60 #define INV3REG_FIFO_CONFIG3 0x61 -#define INV3REG_INT_SOURCE0 0x65 #define INV3REG_SIGNAL_PATH_RESET 0x4b #define INV3REG_INTF_CONFIG0 0x4c #define INV3REG_FIFO_COUNTH 0x2e #define INV3REG_FIFO_DATA 0x30 #define INV3REG_BANK_SEL 0x76 +// ICM42688 bank1 +#define INV3REG_GYRO_CONFIG_STATIC2 0x0B +#define INV3REG_GYRO_CONFIG_STATIC3 0x0C +#define INV3REG_GYRO_CONFIG_STATIC4 0x0D +#define INV3REG_GYRO_CONFIG_STATIC5 0x0E + +// ICM42688 bank2 +#define INV3REG_ACCEL_CONFIG_STATIC2 0x03 +#define INV3REG_ACCEL_CONFIG_STATIC3 0x04 +#define INV3REG_ACCEL_CONFIG_STATIC4 0x05 + +// registers for ICM-42670, multi-bank +#define INV3REG_70_PWR_MGMT0 0x1F +#define INV3REG_70_GYRO_CONFIG0 0x20 +#define INV3REG_70_GYRO_CONFIG1 0x23 +#define INV3REG_70_ACCEL_CONFIG0 0x21 +#define INV3REG_70_ACCEL_CONFIG1 0x24 +#define INV3REG_70_FIFO_COUNTH 0x3D +#define INV3REG_70_FIFO_DATA 0x3F +#define INV3REG_70_INTF_CONFIG0 0x35 +#define INV3REG_70_MCLK_RDY 0x00 +#define INV3REG_70_SIGNAL_PATH_RESET 0x02 +#define INV3REG_70_FIFO_CONFIG1 0x28 +#define INV3REG_BLK_SEL_W 0x79 +#define INV3REG_BLK_SEL_R 0x7C +#define INV3REG_MADDR_W 0x7A +#define INV3REG_MADDR_R 0x7D +#define INV3REG_M_W 0x7B +#define INV3REG_M_R 0x7E +#define INV3REG_BANK_MREG1 0x00 +#define INV3REG_BANK_MREG2 0x28 +#define INV3REG_BANK_MREG3 0x50 + +#define INV3REG_MREG1_FIFO_CONFIG5 0x1 +#define INV3REG_MREG1_SENSOR_CONFIG3 0x06 + // WHOAMI values #define INV3_ID_ICM40605 0x33 #define INV3_ID_ICM40609 0x3b #define INV3_ID_ICM42605 0x42 #define INV3_ID_ICM42688 0x47 #define INV3_ID_IIM42652 0x6f - -// run output data at 2kHz -#define INV3_ODR 2000 +#define INV3_ID_ICM42670 0x67 /* really nice that this sensor has an option to request little-endian @@ -128,13 +161,18 @@ AP_InertialSensor_Backend *AP_InertialSensor_Invensensev3::probe(AP_InertialSens void AP_InertialSensor_Invensensev3::fifo_reset() { - // FIFO_MODE stop-on-full - register_write(INV3REG_FIFO_CONFIG, 0x80); - // FIFO partial disable, enable accel, gyro, temperature - register_write(INV3REG_FIFO_CONFIG1, fifo_config1); - // little-endian, fifo count in records, last data hold for ODR mismatch - register_write(INV3REG_INTF_CONFIG0, 0xC0); - register_write(INV3REG_SIGNAL_PATH_RESET, 2); + if (inv3_type == Invensensev3_Type::ICM42670) { + // FIFO_FLUSH + register_write(INV3REG_70_SIGNAL_PATH_RESET, 0x04); + } else { + // FIFO_MODE stop-on-full + register_write(INV3REG_FIFO_CONFIG, 0x80); + // FIFO partial disable, enable accel, gyro, temperature + register_write(INV3REG_FIFO_CONFIG1, fifo_config1); + // little-endian, fifo count in records, last data hold for ODR mismatch + register_write(INV3REG_INTF_CONFIG0, 0xC0); + register_write(INV3REG_SIGNAL_PATH_RESET, 2); + } notify_accel_fifo_reset(accel_instance); notify_gyro_fifo_reset(gyro_instance); @@ -170,6 +208,10 @@ void AP_InertialSensor_Invensensev3::start() fifo_config1 = 0x0F; temp_sensitivity = 1.0 * 128 / 115.49; break; + case Invensensev3_Type::ICM42670: + devtype = DEVTYPE_INS_ICM42670; + temp_sensitivity = 1.0 / 2.0; + break; case Invensensev3_Type::ICM40609: default: devtype = DEVTYPE_INS_ICM40609; @@ -181,17 +223,24 @@ void AP_InertialSensor_Invensensev3::start() // always use FIFO fifo_reset(); - if (!_imu.register_gyro(gyro_instance, INV3_ODR, dev->get_bus_id_devtype(devtype)) || - !_imu.register_accel(accel_instance, INV3_ODR, dev->get_bus_id_devtype(devtype))) { - return; + // setup on-sensor filtering and scaling and backend rate + if (inv3_type == Invensensev3_Type::ICM42670) { + set_filter_and_scaling_icm42670(); + } else { + set_filter_and_scaling(); } - // setup on-sensor filtering and scaling - set_filter_and_scaling(); + // pre-calculate backend period + backend_period_us = 1000000UL / backend_rate_hz; + + if (!_imu.register_gyro(gyro_instance, backend_rate_hz, dev->get_bus_id_devtype(devtype)) || + !_imu.register_accel(accel_instance, backend_rate_hz, dev->get_bus_id_devtype(devtype))) { + return; + } // update backend sample rate - _set_accel_raw_sample_rate(accel_instance, INV3_ODR); - _set_gyro_raw_sample_rate(gyro_instance, INV3_ODR); + _set_accel_raw_sample_rate(accel_instance, backend_rate_hz); + _set_gyro_raw_sample_rate(gyro_instance, backend_rate_hz); // indicate what multiplier is appropriate for the sensors' // readings to fit them into an int16_t: @@ -210,8 +259,18 @@ void AP_InertialSensor_Invensensev3::start() AP_HAL::panic("Invensensev3: Unable to allocate FIFO buffer"); } - // start the timer process to read samples - dev->register_periodic_callback(1e6 / INV3_ODR, FUNCTOR_BIND_MEMBER(&AP_InertialSensor_Invensensev3::read_fifo, void)); + // start the timer process to read samples, using the fastest rate avilable + periodic_handle = dev->register_periodic_callback(backend_period_us, FUNCTOR_BIND_MEMBER(&AP_InertialSensor_Invensensev3::read_fifo, void)); +} + +// get a startup banner to output to the GCS +bool AP_InertialSensor_Invensensev3::get_output_banner(char* banner, uint8_t banner_len) { + if (fast_sampling) { + snprintf(banner, banner_len, "IMU%u: fast sampling enabled %.1fkHz", + gyro_instance, backend_rate_hz * 0.001); + return true; + } + return false; } /* @@ -241,7 +300,7 @@ bool AP_InertialSensor_Invensensev3::accumulate_samples(const FIFOData *data, ui // we have a header to confirm we don't have FIFO corruption! no more mucking // about with the temperature registers - if ((d.header & 0xF8) != 0x68) { + if ((d.header & 0xFC) != 0x68) { // no or bad data return false; } @@ -251,9 +310,9 @@ bool AP_InertialSensor_Invensensev3::accumulate_samples(const FIFOData *data, ui accel *= accel_scale; gyro *= GYRO_SCALE; - const float temp = d.temperature * temp_sensitivity + temp_zero; + // these four calls are about 40us _rotate_and_correct_accel(accel_instance, accel); _rotate_and_correct_gyro(gyro_instance, gyro); @@ -273,7 +332,9 @@ void AP_InertialSensor_Invensensev3::read_fifo() bool need_reset = false; uint16_t n_samples; - if (!block_read(INV3REG_FIFO_COUNTH, (uint8_t*)&n_samples, 2)) { + const uint8_t reg_counth = (inv3_type == Invensensev3_Type::ICM42670)?INV3REG_70_FIFO_COUNTH:INV3REG_FIFO_COUNTH; + const uint8_t reg_data = (inv3_type == Invensensev3_Type::ICM42670)?INV3REG_70_FIFO_DATA:INV3REG_FIFO_DATA; + if (!block_read(reg_counth, (uint8_t*)&n_samples, 2)) { goto check_registers; } @@ -282,9 +343,13 @@ void AP_InertialSensor_Invensensev3::read_fifo() goto check_registers; } + // adjust the periodic callback to be synchronous with the incoming data + // this means that we rarely run read_fifo() without updating the sensor data + dev->adjust_periodic_callback(periodic_handle, backend_period_us); + while (n_samples > 0) { uint8_t n = MIN(n_samples, INV3_FIFO_BUFFER_LEN); - if (!block_read(INV3REG_FIFO_DATA, (uint8_t*)fifo_buffer, n * INV3_SAMPLE_SIZE)) { + if (!block_read(reg_data, (uint8_t*)fifo_buffer, n * INV3_SAMPLE_SIZE)) { goto check_registers; } @@ -328,20 +393,223 @@ void AP_InertialSensor_Invensensev3::register_write(uint8_t reg, uint8_t val, bo dev->write_register(reg, val, checked); } +/* + read a bank register, only used on startup + */ +uint8_t AP_InertialSensor_Invensensev3::register_read_bank(uint8_t bank, uint8_t reg) +{ + if (inv3_type == Invensensev3_Type::ICM42670) { + // the ICM42670 has a complex bank setup + register_write(INV3REG_BLK_SEL_R, bank); + register_write(INV3REG_MADDR_R, reg); + hal.scheduler->delay_microseconds(10); + const uint8_t val = register_read(INV3REG_M_R); + hal.scheduler->delay_microseconds(10); + register_write(INV3REG_BLK_SEL_R, 0); + return val; + } + register_write(INV3REG_BANK_SEL, bank); + const uint8_t val = register_read(reg); + register_write(INV3REG_BANK_SEL, 0); + return val; +} + +/* + write to a bank register. This is only used on startup, so can use + sleeps to wait for success + */ +void AP_InertialSensor_Invensensev3::register_write_bank(uint8_t bank, uint8_t reg, uint8_t val) +{ + if (inv3_type == Invensensev3_Type::ICM42670) { + // the ICM42670 has a complex bank setup + register_write(INV3REG_BLK_SEL_W, bank); + register_write(INV3REG_MADDR_W, reg); + register_write(INV3REG_M_W, val); + hal.scheduler->delay_microseconds(10); + register_write(INV3REG_BLK_SEL_W, 0); + hal.scheduler->delay_microseconds(10); + } else { + register_write(INV3REG_BANK_SEL, bank); + register_write(reg, val); + register_write(INV3REG_BANK_SEL, 0); + } +} + /* set the filter frequencies and scaling + + The AAF for gyros needs to be high enough to avoid group delay and low enough to have + (ideally) 40dB at the nyquist frequency so that noise above this is not folded into the + range seen by ArduPilot. A reasonable approximation for the former is 1Khz and for the latter + 1/4 of the sample frequency, so for 1/4 sample frequency > 1Khz we pick 1Khz and for 1/4 sample + frequency < 1Khz we use 1/4 sample frequency. + + The AAF for accels is set lower to minimise noise and clipping. The constraint is that the + group delay between gyros and accels should be <5ms to avoid inertial nav errors. + + The UI filter block cannot be disabled and is fixed at ODR/4. This is a 2p filter by default + (as is the AAF). Since the order of the UI filter does not appear to significantly affect + group delay at higher ODRs it is left at the default. The group delay of the AAF is not documented, + but we assume it is similar to the UI 2p performance: + + 2Khz - 0.2ms + 1Khz - 0.4ms + 666Hz - 0.6ms + 500Hz - 0.8ms + 333Hz - 2.0ms + 190Hz - 2.4ms + + Since the UI group delay is the same for both accels and gyros we only need to consider the + difference in group delay for the AAFs. At the highest ODR of 4Khz or 8Khz the group delay for + gyros will be 0.4ms thus the accel AAF can safely be set to ~190Hz. */ void AP_InertialSensor_Invensensev3::set_filter_and_scaling(void) { + // 1KHz by default + backend_rate_hz = 1000; + uint8_t odr_config = 0x06; + + // AAF at ~1/4 of 1Khz by default for gyros- 258Hz + // AAF at 213Hz for accels + uint8_t aaf_delt = 6, accel_aaf_delt = 5; + uint16_t aaf_deltsqr = 36, accel_aaf_deltsqr = 25; + uint8_t aaf_bitshift = 10, accel_aaf_bitshift = 10; + + // limited filtering on ICM-42605 + if (inv3_type == Invensensev3_Type::ICM42605) { + // 249Hz AAF gyros + aaf_delt = 21; + aaf_deltsqr = 440; + aaf_bitshift = 6; + // 184Hz AAF accels + accel_aaf_delt = 16; + accel_aaf_deltsqr = 256; + accel_aaf_bitshift = 7; + } + + // checked for + // ICM-40609 + // ICM-42688 + // ICM-42605 + // IIM-42652 + if (enable_fast_sampling(accel_instance) && get_fast_sampling_rate() > 1) { + fast_sampling = dev->bus_type() == AP_HAL::Device::BUS_TYPE_SPI; + + if (fast_sampling) { + // constrain the gyro rate to be at least the loop rate + uint8_t loop_limit = 1; + if (get_loop_rate_hz() > 1000) { + loop_limit = 2; + } + if (get_loop_rate_hz() > 2000) { + loop_limit = 4; + } + // constrain the gyro rate to be a 2^N multiple + uint8_t fast_sampling_rate = constrain_int16(get_fast_sampling_rate(), loop_limit, 8); + + // calculate rate we will be giving samples to the backend + backend_rate_hz *= fast_sampling_rate; + + // limited filtering on ICM-42605 + if (inv3_type == Invensensev3_Type::ICM42605) { + switch (fast_sampling_rate) { + case 2: // 2KHz + odr_config = 0x05; + // 507Hz AAF + aaf_delt = 47; + aaf_deltsqr = 2208; + aaf_bitshift = 4; + break; + case 4: // 4KHz + // 995Hz AAF + aaf_delt = 63; + aaf_deltsqr = 3968; + aaf_bitshift = 3; + odr_config = 0x04; + break; + case 8: // 8Khz + // 995Hz AAF + aaf_delt = 63; + aaf_deltsqr = 3968; + aaf_bitshift = 3; + odr_config = 0x03; + break; + default: // 1Khz, 334Hz AAF + break; + } + } else { + // ICM-42688 / ICM-40609 / IIM-426525 + switch (fast_sampling_rate) { + case 2: // 2KHz + odr_config = 0x05; + // 536Hz AAF + aaf_delt = 12; + aaf_deltsqr = 144; + aaf_bitshift = 8; + break; + case 4: // 4KHz + odr_config = 0x04; + // 997Hz AAF + aaf_delt = 21; + aaf_deltsqr = 440; + aaf_bitshift = 6; + break; + case 8: // 8Khz + odr_config = 0x03; + // 997Hz AAF + aaf_delt = 21; + aaf_deltsqr = 440; + aaf_bitshift = 6; + break; + default: // 1KHz, 348Hz AAF + break; + } + } + } + } + // enable gyro and accel in low-noise modes register_write(INV3REG_PWR_MGMT0, 0x0F); hal.scheduler->delay_microseconds(300); - // setup gyro for 2kHz - register_write(INV3REG_GYRO_CONFIG0, 0x05); + // setup gyro for backend rate + register_write(INV3REG_GYRO_CONFIG0, odr_config); + // setup accel for backend rate + register_write(INV3REG_ACCEL_CONFIG0, odr_config); + + // setup anti-alias filters for gyro at 1/4 ODR, notch left at default + // The defaults for 42605 and 42609 are different to the 42688, make sure AAF and notch are enabled on all + uint8_t aaf_enable = register_read_bank(1, INV3REG_GYRO_CONFIG_STATIC2); + register_write_bank(1, INV3REG_GYRO_CONFIG_STATIC2, aaf_enable & ~0x03); + register_write_bank(1, INV3REG_GYRO_CONFIG_STATIC3, aaf_delt); // GYRO_AAF_DELT + register_write_bank(1, INV3REG_GYRO_CONFIG_STATIC4, (aaf_deltsqr & 0xFF)); // GYRO_AAF_DELTSQR + register_write_bank(1, INV3REG_GYRO_CONFIG_STATIC5, ((aaf_bitshift<<4) & 0xF0) | ((aaf_deltsqr>>8) & 0x0F)); // GYRO_AAF_BITSHIFT | GYRO_AAF_DELTSQR + + // setup accel AAF at fixed ~500Hz + register_write_bank(2, INV3REG_ACCEL_CONFIG_STATIC2, accel_aaf_delt<<1); // ACCEL_AAF_DELT | enabled bit + register_write_bank(2, INV3REG_ACCEL_CONFIG_STATIC3, (accel_aaf_deltsqr & 0xFF)); // ACCEL_AAF_DELTSQR + register_write_bank(2, INV3REG_ACCEL_CONFIG_STATIC4, ((accel_aaf_bitshift<<4) & 0xF0) | ((accel_aaf_deltsqr>>8) & 0x0F)); // ACCEL_AAF_BITSHIFT | ACCEL_AAF_DELTSQR +} + +/* + set the filter frequencies and scaling for the ICM-42670 + */ +void AP_InertialSensor_Invensensev3::set_filter_and_scaling_icm42670(void) +{ + backend_rate_hz = 1600; + // use low-noise mode + register_write(INV3REG_70_PWR_MGMT0, 0x0f); + hal.scheduler->delay_microseconds(300); + + // setup gyro for 1.6kHz, 2000dps range + register_write(INV3REG_70_GYRO_CONFIG0, 0x05); + // Low noise mode uses an AAF with fixed bandwidth, so disable LPF + register_write(INV3REG_70_GYRO_CONFIG1, 0x30); - // setup accel for 2kHz - register_write(INV3REG_ACCEL_CONFIG0, 0x05); + // setup accel for 1.6kHz, 16g range + register_write(INV3REG_70_ACCEL_CONFIG0, 0x05); + // AAF is not available for accels, so LPF at 180Hz + register_write(INV3REG_70_ACCEL_CONFIG1, 0x01); } /* @@ -350,6 +618,7 @@ void AP_InertialSensor_Invensensev3::set_filter_and_scaling(void) bool AP_InertialSensor_Invensensev3::check_whoami(void) { uint8_t whoami = register_read(INV3REG_WHOAMI); + switch (whoami) { case INV3_ID_ICM40609: inv3_type = Invensensev3_Type::ICM40609; @@ -371,6 +640,10 @@ bool AP_InertialSensor_Invensensev3::check_whoami(void) inv3_type = Invensensev3_Type::IIM42652; accel_scale = (GRAVITY_MSS / 2048); return true; + case INV3_ID_ICM42670: + inv3_type = Invensensev3_Type::ICM42670; + accel_scale = (GRAVITY_MSS / 2048); + return true; } // not a value WHOAMI result return false; @@ -399,9 +672,39 @@ bool AP_InertialSensor_Invensensev3::hardware_init(void) case Invensensev3_Type::IIM42652: case Invensensev3_Type::ICM42605: case Invensensev3_Type::ICM40605: + case Invensensev3_Type::ICM42670: _clip_limit = 15.5f * GRAVITY_MSS; break; } + if (inv3_type == Invensensev3_Type::ICM42670) { + // the ICM-42670 needs some more power-up config + for (uint8_t tries=0; tries<50; tries++) { + // initiate a power up sequence + register_write(INV3REG_70_SIGNAL_PATH_RESET, 0x10); + hal.scheduler->delay_microseconds(1000); + register_write(INV3REG_70_PWR_MGMT0, 0x0f, true); + if (register_read(INV3REG_70_MCLK_RDY) != 0) { + break; + } + hal.scheduler->delay(5); + } + if (register_read(INV3REG_70_MCLK_RDY) == 0) { + return false; + } + + // disable APEX for larger FIFO + register_write_bank(INV3REG_BANK_MREG1, INV3REG_MREG1_SENSOR_CONFIG3, 0x40); + + // use 16 bit data, gyro+accel + register_write_bank(INV3REG_BANK_MREG1, INV3REG_MREG1_FIFO_CONFIG5, 0x3); + + // FIFO stop-on-full, disable bypass + register_write(INV3REG_70_FIFO_CONFIG1, 0x2, true); + + // little-endian, fifo count in records + register_write(INV3REG_70_INTF_CONFIG0, 0x40, true); + } + return true; } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Invensensev3.h b/libraries/AP_InertialSensor/AP_InertialSensor_Invensensev3.h index eaf1616f447..d8b5b3aac41 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Invensensev3.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Invensensev3.h @@ -28,6 +28,8 @@ class AP_InertialSensor_Invensensev3 : public AP_InertialSensor_Backend void accumulate() override; void start() override; + // get a startup banner to output to the GCS + bool get_output_banner(char* banner, uint8_t banner_len) override; enum class Invensensev3_Type : uint8_t { ICM40609 = 0, @@ -35,6 +37,7 @@ class AP_InertialSensor_Invensensev3 : public AP_InertialSensor_Backend ICM42605, ICM40605, IIM42652, + ICM42670, }; // acclerometers on Invensense sensors will return values up to 32G @@ -50,6 +53,7 @@ class AP_InertialSensor_Invensensev3 : public AP_InertialSensor_Backend bool check_whoami(); void set_filter_and_scaling(void); + void set_filter_and_scaling_icm42670(void); void fifo_reset(); /* Read samples from FIFO */ @@ -59,6 +63,9 @@ class AP_InertialSensor_Invensensev3 : public AP_InertialSensor_Backend uint8_t register_read(uint8_t reg); void register_write(uint8_t reg, uint8_t val, bool checked=false); + uint8_t register_read_bank(uint8_t bank, uint8_t reg); + void register_write_bank(uint8_t bank, uint8_t reg, uint8_t val); + bool accumulate_samples(const struct FIFOData *data, uint8_t n_samples); // instance numbers of accel and gyro data @@ -76,7 +83,16 @@ class AP_InertialSensor_Invensensev3 : public AP_InertialSensor_Backend float accel_scale; + // are we doing more than 1kHz sampling? + bool fast_sampling; + + // what rate are we generating samples into the backend for gyros and accels? + uint16_t backend_rate_hz; + // pre-calculated backend period + uint32_t backend_period_us; + AP_HAL::OwnPtr dev; + AP_HAL::Device::PeriodicHandle periodic_handle; // which sensor type this is enum Invensensev3_Type inv3_type; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_LSM9DS0.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_LSM9DS0.cpp index f3eac505bb0..a872ddc7b5a 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_LSM9DS0.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_LSM9DS0.cpp @@ -492,7 +492,7 @@ bool AP_InertialSensor_LSM9DS0::_hardware_init() #endif } if (tries == 5) { - hal.console->printf("Failed to boot LSM9DS0 5 times\n\n"); + DEV_PRINTF("Failed to boot LSM9DS0 5 times\n\n"); goto fail_tries; } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_LSM9DS1.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_LSM9DS1.cpp index 57a55e551bf..295f1ebccad 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_LSM9DS1.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_LSM9DS1.cpp @@ -255,7 +255,7 @@ bool AP_InertialSensor_LSM9DS1::_hardware_init() whoami = _register_read(LSM9DS1XG_WHO_AM_I); if (whoami != WHO_AM_I) { - hal.console->printf("LSM9DS1: unexpected acc/gyro WHOAMI 0x%x\n", whoami); + DEV_PRINTF("LSM9DS1: unexpected acc/gyro WHOAMI 0x%x\n", whoami); goto fail_whoami; } @@ -284,7 +284,7 @@ bool AP_InertialSensor_LSM9DS1::_hardware_init() #endif } if (tries == 5) { - hal.console->printf("Failed to boot LSM9DS1 5 times\n\n"); + DEV_PRINTF("Failed to boot LSM9DS1 5 times\n\n"); goto fail_tries; } @@ -448,7 +448,7 @@ void AP_InertialSensor_LSM9DS1::_read_data_transaction_x(uint16_t samples) struct sensor_raw_data raw_data_temp = { }; if (!_dev->transfer(&_reg, 1, (uint8_t *) &raw_data_temp, sizeof(raw_data_temp))) { - hal.console->printf("LSM9DS1: error reading accelerometer\n"); + DEV_PRINTF("LSM9DS1: error reading accelerometer\n"); return; } @@ -485,7 +485,7 @@ void AP_InertialSensor_LSM9DS1::_read_data_transaction_g(uint16_t samples) struct sensor_raw_data raw_data_temp = { }; if (!_dev->transfer(&_reg, 1, (uint8_t *) &raw_data_temp, sizeof(raw_data_temp))) { - hal.console->printf("LSM9DS1: error reading gyroscope\n"); + DEV_PRINTF("LSM9DS1: error reading gyroscope\n"); return; } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Logging.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_Logging.cpp index ebe8a982e30..742932691f1 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Logging.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Logging.cpp @@ -50,8 +50,8 @@ void AP_InertialSensor::Write_IMU_instance(const uint64_t time_us, const uint8_t accel_x : accel.x, accel_y : accel.y, accel_z : accel.z, - gyro_error : get_gyro_error_count(imu_instance), - accel_error : get_accel_error_count(imu_instance), + gyro_error : _gyro_error_count[imu_instance], + accel_error : _accel_error_count[imu_instance], temperature : get_temperature(imu_instance), gyro_health : (uint8_t)get_gyro_health(imu_instance), accel_health : (uint8_t)get_accel_health(imu_instance), @@ -98,14 +98,19 @@ void AP_InertialSensor::Write_Vibration() const // Write information about a series of IMU readings to log: bool AP_InertialSensor::BatchSampler::Write_ISBH(const float sample_rate_hz) const { + uint8_t instance_to_write = instance; + if (post_filter && (_doing_pre_post_filter_logging + || (_doing_post_filter_logging && _doing_sensor_rate_logging))) { + instance_to_write += (type == IMU_SENSOR_TYPE_ACCEL ? _imu._accel_count : _imu._gyro_count); + } const struct log_ISBH pkt{ LOG_PACKET_HEADER_INIT(LOG_ISBH_MSG), time_us : AP_HAL::micros64(), seqno : isb_seqnum, sensor_type : (uint8_t)type, - instance : instance, + instance : instance_to_write, multiplier : multiplier, - sample_count : (uint16_t)_required_count, + sample_count : (uint16_t)_real_required_count, sample_us : measurement_started_us, sample_rate_hz : sample_rate_hz, }; @@ -132,6 +137,7 @@ bool AP_InertialSensor::BatchSampler::Write_ISBD() const // @LoggerMessage: FTN // @Description: Filter Tuning Messages // @Field: TimeUS: microseconds since system startup +// @Field: I: instance // @Field: NDn: number of active dynamic harmonic notches // @Field: NF1: dynamic harmonic notch centre frequency for motor 1 // @Field: NF2: dynamic harmonic notch centre frequency for motor 2 @@ -147,10 +153,19 @@ bool AP_InertialSensor::BatchSampler::Write_ISBD() const // @Field: NF12: dynamic harmonic notch centre frequency for motor 12 void AP_InertialSensor::write_notch_log_messages() const { - const float* notches = get_gyro_dynamic_notch_center_frequencies_hz(); - AP::logger().WriteStreaming( - "FTN", "TimeUS,NDn,NF1,NF2,NF3,NF4,NF5,NF6,NF7,NF8,NF9,NF10,NF11,NF12", "s-zzzzzzzzzzzz", "F-------------", "QBffffffffffff", AP_HAL::micros64(), get_num_gyro_dynamic_notch_center_frequencies(), + for (auto ¬ch : harmonic_notches) { + const uint8_t i = ¬ch - &harmonic_notches[0]; + if (!notch.params.enabled()) { + continue; + } + const float* notches = notch.calculated_notch_freq_hz; + AP::logger().WriteStreaming( + "FTN", "TimeUS,I,NDn,NF1,NF2,NF3,NF4,NF5,NF6,NF7,NF8,NF9,NF10,NF11,NF12", "s#-zzzzzzzzzzzz", "F--------------", "QBBffffffffffff", + AP_HAL::micros64(), + i, + notch.num_calculated_notch_frequencies, notches[0], notches[1], notches[2], notches[3], notches[4], notches[5], notches[6], notches[7], notches[8], notches[9], notches[10], notches[11]); + } } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_NONE.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_NONE.cpp index 7501902df8c..e51a97d618e 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_NONE.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_NONE.cpp @@ -261,7 +261,7 @@ void AP_InertialSensor_NONE::timer_update(void) static uint64_t last_msg_sent = 0; if (now > last_msg_sent + 2000000) { //2sec= 2000ms = 2000000us //gcs().send_text(MAV_SEVERITY_WARNING, "NO IMU FOUND"); - hal.console->printf("INS: NO IMU FOUND\n"); + DEV_PRINTF("INS: NO IMU FOUND\n"); last_msg_sent = now; } if (now >= next_accel_sample) { diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_NONE.h b/libraries/AP_InertialSensor/AP_InertialSensor_NONE.h index effe33920f1..715e3491f9d 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_NONE.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_NONE.h @@ -1,8 +1,5 @@ #pragma once -#include -#include - /* This is a 'mock' implementation of an INS that does nothing and gives a level HUD, but does it successfully. Its useful for boards that don't have any form of IMU accel/gyro etc connected just yet, but where u want to boot-up "successfully" anyway, @@ -50,8 +47,8 @@ class AP_InertialSensor_NONE : public AP_InertialSensor_Backend uint64_t next_accel_sample; float gyro_time; float accel_time; - float gyro_motor_phase[12]; - float accel_motor_phase[12]; + float gyro_motor_phase[32]; + float accel_motor_phase[32]; static uint8_t bus_id; }; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_RST.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_RST.cpp index e1f186870fc..761e2e9100b 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_RST.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_RST.cpp @@ -291,7 +291,7 @@ bool AP_InertialSensor_RST::_init_accel(void) _dev_accel->read_registers(ACCEL_WHO_AM_I, &whoami, sizeof(whoami)); if (whoami != ACCEL_WHO_I_AM) { - hal.console->printf("RST: unexpected accel WHOAMI 0x%x\n", (unsigned)whoami); + DEV_PRINTF("RST: unexpected accel WHOAMI 0x%x\n", (unsigned)whoami); printf("RST: unexpected accel WHOAMI 0x%x\n", (unsigned)whoami); goto fail_whoami; } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_SITL.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_SITL.cpp index 3d4b248c311..841046c25df 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_SITL.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_SITL.cpp @@ -136,20 +136,23 @@ void AP_InertialSensor_SITL::generate_accel() // VIB_MOT_MAX is a rpm-scaled vibration applied to each axis if (!is_zero(sitl->vibe_motor) && motors_on) { - for (uint8_t i = 0; i < sitl->state.num_motors; i++) { - float &phase = accel_motor_phase[i]; - float motor_freq = calculate_noise(sitl->state.rpm[sitl->state.vtol_motor_start+i] / 60.0f, freq_variation); - float phase_incr = motor_freq * 2 * M_PI / (accel_sample_hz * nsamples); - phase += phase_incr; - if (phase_incr > M_PI) { - phase -= 2 * M_PI; + uint32_t mask = sitl->state.motor_mask; + uint8_t mbit; + while ((mbit = __builtin_ffs(mask)) != 0) { + const uint8_t motor = mbit-1; + mask &= ~(1U<vibe_motor_harmonics); + const float base_freq = calculate_noise(sitl->state.rpm[motor] / 60.0f, freq_variation); + while (harmonics != 0) { + const uint8_t bit = __builtin_ffs(harmonics); + harmonics &= ~(1U<<(bit-1U)); + const float phase = accel_motor_phase[motor] * float(bit); + accel.x += sinf(phase) * calculate_noise(accel_noise * sitl->vibe_motor_scale, noise_variation); + accel.y += sinf(phase) * calculate_noise(accel_noise * sitl->vibe_motor_scale, noise_variation); + accel.z += sinf(phase) * calculate_noise(accel_noise * sitl->vibe_motor_scale, noise_variation); } - else if (phase_incr < -M_PI) { - phase += 2 * M_PI; - } - accel.x += sinf(phase) * calculate_noise(accel_noise * sitl->vibe_motor_scale, noise_variation); - accel.y += sinf(phase) * calculate_noise(accel_noise * sitl->vibe_motor_scale, noise_variation); - accel.z += sinf(phase) * calculate_noise(accel_noise * sitl->vibe_motor_scale, noise_variation); + const float phase_incr = base_freq * 2 * M_PI / (accel_sample_hz * nsamples); + accel_motor_phase[motor] = wrap_PI(accel_motor_phase[motor] + phase_incr); } } @@ -242,20 +245,23 @@ void AP_InertialSensor_SITL::generate_gyro() // VIB_MOT_MAX is a rpm-scaled vibration applied to each axis if (!is_zero(sitl->vibe_motor) && motors_on) { - for (uint8_t i = 0; i < sitl->state.num_motors; i++) { - float motor_freq = calculate_noise(sitl->state.rpm[sitl->state.vtol_motor_start+i] / 60.0f, freq_variation); - float phase_incr = motor_freq * 2 * M_PI / (gyro_sample_hz * nsamples); - float &phase = gyro_motor_phase[i]; - phase += phase_incr; - if (phase_incr > M_PI) { - phase -= 2 * M_PI; - } - else if (phase_incr < -M_PI) { - phase += 2 * M_PI; + uint32_t mask = sitl->state.motor_mask; + uint8_t mbit; + while ((mbit = __builtin_ffs(mask)) != 0) { + const uint8_t motor = mbit-1; + mask &= ~(1U<vibe_motor_harmonics); + const float base_freq = calculate_noise(sitl->state.rpm[motor] / 60.0f, freq_variation); + while (harmonics != 0) { + const uint8_t bit = __builtin_ffs(harmonics); + harmonics &= ~(1U<<(bit-1U)); + const float phase = gyro_motor_phase[motor] * float(bit); + p += sinf(phase) * calculate_noise(gyro_noise * sitl->vibe_motor_scale, noise_variation); + q += sinf(phase) * calculate_noise(gyro_noise * sitl->vibe_motor_scale, noise_variation); + r += sinf(phase) * calculate_noise(gyro_noise * sitl->vibe_motor_scale, noise_variation); } - p += sinf(phase) * calculate_noise(gyro_noise * sitl->vibe_motor_scale, noise_variation); - q += sinf(phase) * calculate_noise(gyro_noise * sitl->vibe_motor_scale, noise_variation); - r += sinf(phase) * calculate_noise(gyro_noise * sitl->vibe_motor_scale, noise_variation); + const float phase_incr = base_freq * 2 * M_PI / (gyro_sample_hz * nsamples); + gyro_motor_phase[motor] = wrap_PI(gyro_motor_phase[motor] + phase_incr); } } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_SITL.h b/libraries/AP_InertialSensor/AP_InertialSensor_SITL.h index d1f4c9b1e9b..b46dd37121c 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_SITL.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_SITL.h @@ -43,8 +43,8 @@ class AP_InertialSensor_SITL : public AP_InertialSensor_Backend uint64_t next_accel_sample; float gyro_time; float accel_time; - float gyro_motor_phase[12]; - float accel_motor_phase[12]; + float gyro_motor_phase[32]; + float accel_motor_phase[32]; uint32_t temp_start_ms; static uint8_t bus_id; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_tempcal.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_tempcal.cpp index e344d59d2d1..fd3d37b26a1 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_tempcal.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_tempcal.cpp @@ -24,6 +24,7 @@ #include #include #include +#include // this scale factor ensures params are easy to work with in GUI parameter editors #define SCALE_FACTOR 1.0e6 @@ -303,7 +304,7 @@ void AP_InertialSensor::TCal::Learn::add_sample(const Vector3f &sample, float te } const float tdiff = T - TEMP_REFERENCE; - +#if HAL_LOGGING_ENABLED AP::logger().Write("TCLR", "TimeUS,I,SType,Temp,X,Y,Z,NSamp", "s#------", "F000000-", @@ -314,6 +315,7 @@ void AP_InertialSensor::TCal::Learn::add_sample(const Vector3f &sample, float te T, st.sum.x, st.sum.y, st.sum.z, st.sum_count); +#endif st.pfit.update(tdiff, st.sum); diff --git a/libraries/AP_InertialSensor/BatchSampler.cpp b/libraries/AP_InertialSensor/BatchSampler.cpp index b6e8ac72af4..376331cd1e9 100644 --- a/libraries/AP_InertialSensor/BatchSampler.cpp +++ b/libraries/AP_InertialSensor/BatchSampler.cpp @@ -24,8 +24,8 @@ const AP_Param::GroupInfo AP_InertialSensor::BatchSampler::var_info[] = { // @Param: BAT_OPT // @DisplayName: Batch Logging Options Mask - // @Description: Options for the BatchSampler. Post-filter and sensor-rate logging cannot be used at the same time. - // @Bitmask: 0:Sensor-Rate Logging (sample at full sensor rate seen by AP), 1: Sample post-filtering + // @Description: Options for the BatchSampler. + // @Bitmask: 0:Sensor-Rate Logging (sample at full sensor rate seen by AP), 1: Sample post-filtering, 2: Sample pre- and post-filter // @User: Advanced AP_GROUPINFO("BAT_OPT", 3, AP_InertialSensor::BatchSampler, _batch_options_mask, 0), @@ -56,14 +56,16 @@ void AP_InertialSensor::BatchSampler::init() return; } - _required_count -= _required_count % 32; // round down to nearest multiple of 32 + _required_count.set(_required_count - (_required_count % 32)); // round down to nearest multiple of 32 - const uint32_t total_allocation = 3*_required_count*sizeof(uint16_t); + _real_required_count = _required_count; + + const uint32_t total_allocation = 3*_real_required_count*sizeof(uint16_t); GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "INS: alloc %u bytes for ISB (free=%u)", (unsigned int)total_allocation, (unsigned int)hal.util->available_memory()); - data_x = (int16_t*)calloc(_required_count, sizeof(int16_t)); - data_y = (int16_t*)calloc(_required_count, sizeof(int16_t)); - data_z = (int16_t*)calloc(_required_count, sizeof(int16_t)); + data_x = (int16_t*)calloc(_real_required_count, sizeof(int16_t)); + data_y = (int16_t*)calloc(_real_required_count, sizeof(int16_t)); + data_z = (int16_t*)calloc(_real_required_count, sizeof(int16_t)); if (data_x == nullptr || data_y == nullptr || data_z == nullptr) { free(data_x); free(data_y); @@ -90,14 +92,13 @@ void AP_InertialSensor::BatchSampler::periodic() void AP_InertialSensor::BatchSampler::update_doing_sensor_rate_logging() { - // We can't do post-filter sensor rate logging - if ((batch_opt_t)(_batch_options_mask.get()) & BATCH_OPT_POST_FILTER) { + if (has_option(BATCH_OPT_POST_FILTER)) { _doing_post_filter_logging = true; - _doing_sensor_rate_logging = false; - return; } - _doing_post_filter_logging = false; - if (!((batch_opt_t)(_batch_options_mask.get()) & BATCH_OPT_SENSOR_RATE)) { + if (has_option(BATCH_OPT_PRE_POST_FILTER)) { + _doing_pre_post_filter_logging = true; + } + if (!has_option(BATCH_OPT_SENSOR_RATE)) { _doing_sensor_rate_logging = false; return; } @@ -121,6 +122,7 @@ void AP_InertialSensor::BatchSampler::rotate_to_next_sensor() if ((1U< (uint8_t)_sensor_mask) { // should only ever happen if user resets _sensor_mask instance = 0; + post_filter = false; } if (type == IMU_SENSOR_TYPE_ACCEL) { @@ -154,6 +156,7 @@ void AP_InertialSensor::BatchSampler::rotate_to_next_sensor() if (_sensor_mask & (1U<= _required_count) { + if (data_read_offset >= _real_required_count) { // that was the last one. Clean up: data_read_offset = 0; isb_seqnum++; @@ -249,7 +253,7 @@ bool AP_InertialSensor::BatchSampler::should_log(uint8_t _instance, IMU_SENSOR_T if (_type != type) { return false; } - if (data_write_offset >= _required_count) { + if (data_write_offset >= _real_required_count) { return false; } AP_Logger *logger = AP_Logger::get_singleton(); @@ -265,6 +269,7 @@ bool AP_InertialSensor::BatchSampler::should_log(uint8_t _instance, IMU_SENSOR_T void AP_InertialSensor::BatchSampler::sample(uint8_t _instance, AP_InertialSensor::IMU_SENSOR_TYPE _type, uint64_t sample_us, const Vector3f &_sample) { +#if HAL_LOGGING_ENABLED if (!should_log(_instance, _type)) { return; } @@ -277,5 +282,6 @@ void AP_InertialSensor::BatchSampler::sample(uint8_t _instance, AP_InertialSenso data_z[data_write_offset] = multiplier*_sample.z; data_write_offset++; // may unblock the reading process +#endif } #endif //#if HAL_INS_ENABLED diff --git a/libraries/AP_InertialSensor/examples/INS_generic/INS_generic.cpp b/libraries/AP_InertialSensor/examples/INS_generic/INS_generic.cpp index d8f7b17498f..1856e6f801e 100644 --- a/libraries/AP_InertialSensor/examples/INS_generic/INS_generic.cpp +++ b/libraries/AP_InertialSensor/examples/INS_generic/INS_generic.cpp @@ -7,6 +7,7 @@ #include #include #include +#include const AP_HAL::HAL &hal = AP_HAL::get_HAL(); @@ -184,4 +185,9 @@ static void run_test() } } +const struct AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { + AP_GROUPEND +}; +GCS_Dummy _gcs; + AP_HAL_MAIN(); diff --git a/libraries/AP_KDECAN/AP_KDECAN.cpp b/libraries/AP_KDECAN/AP_KDECAN.cpp index ea82a4f82a0..344b69f8227 100644 --- a/libraries/AP_KDECAN/AP_KDECAN.cpp +++ b/libraries/AP_KDECAN/AP_KDECAN.cpp @@ -606,7 +606,7 @@ bool AP_KDECAN::pre_arm_check(char* reason, uint8_t reason_len) _enum_sem.give(); - uint16_t motors_mask = 0; + uint32_t motors_mask = 0; AP_Motors *motors = AP_Motors::get_singleton(); if (motors) { diff --git a/libraries/AP_KDECAN/AP_KDECAN.h b/libraries/AP_KDECAN/AP_KDECAN.h index 3664067f694..39264e4c67f 100644 --- a/libraries/AP_KDECAN/AP_KDECAN.h +++ b/libraries/AP_KDECAN/AP_KDECAN.h @@ -72,7 +72,7 @@ class AP_KDECAN : public AP_CANDriver, public AP_ESC_Telem_Backend { AP_Int8 _num_poles; // ESC detected information - uint16_t _esc_present_bitmask; + uint32_t _esc_present_bitmask; uint8_t _esc_max_node_id; // enumeration diff --git a/libraries/AP_L1_Control/AP_L1_Control.cpp b/libraries/AP_L1_Control/AP_L1_Control.cpp index 2ff3696c53e..ff1294289c1 100644 --- a/libraries/AP_L1_Control/AP_L1_Control.cpp +++ b/libraries/AP_L1_Control/AP_L1_Control.cpp @@ -36,7 +36,7 @@ const AP_Param::GroupInfo AP_L1_Control::var_info[] = { // @Units: deg // @Range: 0 89 // @User: Advanced - AP_GROUPINFO_FRAME("LIM_BANK", 3, AP_L1_Control, _loiter_bank_limit, 0.0f, AP_PARAM_FRAME_PLANE), + AP_GROUPINFO("LIM_BANK", 3, AP_L1_Control, _loiter_bank_limit, 0.0f), AP_GROUPEND }; diff --git a/libraries/AP_LTM_Telem/AP_LTM_Telem.cpp b/libraries/AP_LTM_Telem/AP_LTM_Telem.cpp index c9267b19851..8d4dc952c01 100644 --- a/libraries/AP_LTM_Telem/AP_LTM_Telem.cpp +++ b/libraries/AP_LTM_Telem/AP_LTM_Telem.cpp @@ -17,6 +17,8 @@ #include "AP_LTM_Telem.h" +#if AP_LTM_TELEM_ENABLED + #include #include #include @@ -168,9 +170,9 @@ void AP_LTM_Telem::send_Aframe(void) { AP_AHRS &ahrs = AP::ahrs(); WITH_SEMAPHORE(ahrs.get_semaphore()); - pitch = roundf(ahrs.pitch_sensor / 100.0); // attitude pitch in degrees - roll = roundf(ahrs.roll_sensor / 100.0); // attitude roll in degrees - heading = roundf(ahrs.yaw_sensor / 100.0); // heading in degrees + pitch = roundf(ahrs.pitch_sensor * 0.01); // attitude pitch in degrees + roll = roundf(ahrs.roll_sensor * 0.01); // attitude roll in degrees + heading = roundf(ahrs.yaw_sensor * 0.01); // heading in degrees } uint8_t lt_buff[LTM_AFRAME_SIZE]; @@ -216,3 +218,5 @@ void AP_LTM_Telem::tick(void) generate_LTM(); } } + +#endif // AP_LTM_TELEM_ENABLED diff --git a/libraries/AP_LTM_Telem/AP_LTM_Telem.h b/libraries/AP_LTM_Telem/AP_LTM_Telem.h index 2461a9534a4..03a3833fd76 100644 --- a/libraries/AP_LTM_Telem/AP_LTM_Telem.h +++ b/libraries/AP_LTM_Telem/AP_LTM_Telem.h @@ -16,6 +16,12 @@ #include +#ifndef AP_LTM_TELEM_ENABLED +#define AP_LTM_TELEM_ENABLED !HAL_MINIMIZE_FEATURES +#endif + +#if AP_LTM_TELEM_ENABLED + static const uint8_t LTM_GFRAME_SIZE = 18; static const uint8_t LTM_AFRAME_SIZE = 10; static const uint8_t LTM_SFRAME_SIZE = 11; @@ -45,3 +51,5 @@ class AP_LTM_Telem { void send_LTM(uint8_t lt_packet[], uint8_t lt_packet_size); void tick(void); // tick - main call to send updates to transmitter (called by scheduler at 1kHz) }; + +#endif diff --git a/libraries/AP_Landing/AP_Landing.cpp b/libraries/AP_Landing/AP_Landing.cpp index 588f92977ee..f966576da7c 100644 --- a/libraries/AP_Landing/AP_Landing.cpp +++ b/libraries/AP_Landing/AP_Landing.cpp @@ -124,7 +124,7 @@ const AP_Param::GroupInfo AP_Landing::var_info[] = { // @Param: ABORT_THR // @DisplayName: Landing abort using throttle - // @Description: Allow a landing abort to trigger with a throttle > 95% + // @Description: Allow a landing abort to trigger with an input throttle >= 90%. This works with or without stick-mixing enabled. // @Values: 0:Disabled, 1:Enabled // @User: Advanced AP_GROUPINFO("ABORT_THR", 12, AP_Landing, abort_throttle_enable, 0), @@ -267,11 +267,12 @@ bool AP_Landing::verify_abort_landing(const Location &prev_WP_loc, Location &nex mission.resume(); } // else we're in AUTO with a stopped mission and handle_auto_mode() will set RTL - +#if AP_FENCE_ENABLED AC_Fence *fence = AP::fence(); if (fence) { fence->auto_enable_fence_after_takeoff(); } +#endif } Log(); @@ -408,7 +409,7 @@ bool AP_Landing::override_servos(void) { // returns a PID_Info object if there is one available for the selected landing // type, otherwise returns a nullptr, indicating no data to be logged/sent -const AP_Logger::PID_Info* AP_Landing::get_pid_info(void) const +const AP_PIDInfo* AP_Landing::get_pid_info(void) const { switch (type) { #if HAL_LANDING_DEEPSTALL_ENABLED diff --git a/libraries/AP_Landing/AP_Landing.h b/libraries/AP_Landing/AP_Landing.h index 1715bb3b50d..6b7d1621e69 100644 --- a/libraries/AP_Landing/AP_Landing.h +++ b/libraries/AP_Landing/AP_Landing.h @@ -109,7 +109,7 @@ class AP_Landing { void set_initial_slope(void) { initial_slope = slope; } bool is_expecting_impact(void) const; void Log(void) const; - const AP_Logger::PID_Info * get_pid_info(void) const; + const AP_PIDInfo * get_pid_info(void) const; // landing altitude offset (meters) float alt_offset; diff --git a/libraries/AP_Landing/AP_Landing_Deepstall.cpp b/libraries/AP_Landing/AP_Landing_Deepstall.cpp index 8d771741228..a0c04c75354 100644 --- a/libraries/AP_Landing/AP_Landing_Deepstall.cpp +++ b/libraries/AP_Landing/AP_Landing_Deepstall.cpp @@ -26,6 +26,7 @@ #include #include #include +#include // table of user settable parameters for deepstall const AP_Param::GroupInfo AP_Landing_Deepstall::var_info[] = { @@ -448,13 +449,13 @@ bool AP_Landing_Deepstall::send_deepstall_message(mavlink_channel_t chan) const return true; } -const AP_Logger::PID_Info& AP_Landing_Deepstall::get_pid_info(void) const +const AP_PIDInfo& AP_Landing_Deepstall::get_pid_info(void) const { return ds_PID.get_pid_info(); } void AP_Landing_Deepstall::Log(void) const { - const AP_Logger::PID_Info& pid_info = ds_PID.get_pid_info(); + const AP_PIDInfo& pid_info = ds_PID.get_pid_info(); struct log_DSTL pkt = { LOG_PACKET_HEADER_INIT(LOG_DSTL_MSG), time_us : AP_HAL::micros64(), @@ -600,7 +601,7 @@ bool AP_Landing_Deepstall::verify_breakout(const Location ¤t_loc, const Lo const Vector2f location_delta = current_loc.get_distance_NE(target_loc); const float heading_error = degrees(landing.ahrs.groundspeed_vector().angle(location_delta)); - // Check to see if the the plane is heading toward the land waypoint. We use 20 degrees (+/-10 deg) + // Check to see if the plane is heading toward the land waypoint. We use 20 degrees (+/-10 deg) // of margin so that the altitude to be within 5 meters of desired if (heading_error <= 10.0 && fabsf(height_error) < DEEPSTALL_LOITER_ALT_TOLERANCE) { diff --git a/libraries/AP_Landing/AP_Landing_Deepstall.h b/libraries/AP_Landing/AP_Landing_Deepstall.h index b8b90686b8b..b668054855d 100644 --- a/libraries/AP_Landing/AP_Landing_Deepstall.h +++ b/libraries/AP_Landing/AP_Landing_Deepstall.h @@ -100,7 +100,7 @@ class AP_Landing_Deepstall bool send_deepstall_message(mavlink_channel_t chan) const; - const AP_Logger::PID_Info& get_pid_info(void) const; + const AP_PIDInfo& get_pid_info(void) const; //private helpers void build_approach_path(bool use_current_heading); diff --git a/libraries/AP_Landing/AP_Landing_Slope.cpp b/libraries/AP_Landing/AP_Landing_Slope.cpp index 4f624af2e93..d2db6d4cf88 100644 --- a/libraries/AP_Landing/AP_Landing_Slope.cpp +++ b/libraries/AP_Landing/AP_Landing_Slope.cpp @@ -23,6 +23,7 @@ #include #include #include +#include void AP_Landing::type_slope_do_land(const AP_Mission::Mission_Command& cmd, const float relative_altitude) { @@ -283,7 +284,7 @@ void AP_Landing::type_slope_setup_landing_glide_slope(const Location &prev_WP_lo } // time before landing that we will flare - float flare_time = aim_height / tecs_Controller->get_land_sinkrate(); + float flare_time = aim_height / MAX(tecs_Controller->get_land_sinkrate(), 0.1); // distance to flare is based on ground speed, adjusted as we // get closer. This takes into account the wind @@ -408,7 +409,7 @@ void AP_Landing::type_slope_log(void) const // @Field: slopeInit: Initial slope to landing point // @Field: altO: Rangefinder correction // @Field: fh: Height for flare timing. - AP::logger().Write("LAND", "TimeUS,stage,f1,f2,slope,slopeInit,altO,fh", "QBBBffff", + AP::logger().WriteStreaming("LAND", "TimeUS,stage,f1,f2,slope,slopeInit,altO,fh", "QBBBffff", AP_HAL::micros64(), type_slope_stage, flags, diff --git a/libraries/AP_LandingGear/AP_LandingGear.cpp b/libraries/AP_LandingGear/AP_LandingGear.cpp index 949ed506c0d..807b4350f98 100644 --- a/libraries/AP_LandingGear/AP_LandingGear.cpp +++ b/libraries/AP_LandingGear/AP_LandingGear.cpp @@ -6,6 +6,10 @@ #include #include +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#include +#endif + extern const AP_HAL::HAL& hal; const AP_Param::GroupInfo AP_LandingGear::var_info[] = { @@ -28,7 +32,7 @@ const AP_Param::GroupInfo AP_LandingGear::var_info[] = { // @Param: DEPLOY_PIN // @DisplayName: Chassis deployment feedback pin - // @Description: Pin number to use for detection of gear deployment. If set to -1 feedback is disabled. + // @Description: Pin number to use for detection of gear deployment. If set to -1 feedback is disabled. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot. // @Values: -1:Disabled,50:AUX1,51:AUX2,52:AUX3,53:AUX4,54:AUX5,55:AUX6 // @User: Standard // @RebootRequired: True @@ -43,18 +47,18 @@ const AP_Param::GroupInfo AP_LandingGear::var_info[] = { // @Param: WOW_PIN // @DisplayName: Weight on wheels feedback pin - // @Description: Pin number to use for feedback of weight on wheels condition. If set to -1 feedback is disabled. + // @Description: Pin number to use for feedback of weight on wheels condition. If set to -1 feedback is disabled. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot. // @Values: -1:Disabled,50:AUX1,51:AUX2,52:AUX3,53:AUX4,54:AUX5,55:AUX6 // @User: Standard // @RebootRequired: True - AP_GROUPINFO("WOW_PIN", 5, AP_LandingGear, _pin_weight_on_wheels, DEFAULT_PIN_WOW), + AP_GROUPINFO("WOW_PIN", 5, AP_LandingGear, _pin_weight_on_wheels, -1), // @Param: WOW_POL // @DisplayName: Weight on wheels feedback pin polarity // @Description: Polarity for feedback pin. If this is 1 then the pin should be high when there is weight on wheels. If set to 0 then then weight on wheels level is low. // @Values: 0:Low,1:High // @User: Standard - AP_GROUPINFO("WOW_POL", 6, AP_LandingGear, _pin_weight_on_wheels_polarity, DEFAULT_PIN_WOW_POL), + AP_GROUPINFO("WOW_POL", 6, AP_LandingGear, _pin_weight_on_wheels_polarity, 0), // @Param: DEPLOY_ALT // @DisplayName: Landing gear deployment altitude @@ -91,6 +95,13 @@ AP_LandingGear *AP_LandingGear::_singleton; /// initialise state of landing gear void AP_LandingGear::init() { +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL + if (AP::sitl()->wow_pin > 0) { + _pin_weight_on_wheels.set_and_default(AP::sitl()->wow_pin); + _pin_weight_on_wheels_polarity.set_and_default(1); + } +#endif + if (!_enable.configured() && (SRV_Channels::function_assigned(SRV_Channel::k_landing_gear_control) || (_pin_deployed > 0) || (_pin_weight_on_wheels > 0))) { // if not configured set enable param if output servo or sense pins are defined diff --git a/libraries/AP_LandingGear/AP_LandingGear.h b/libraries/AP_LandingGear/AP_LandingGear.h index 22222207c0d..51ee1702ea3 100644 --- a/libraries/AP_LandingGear/AP_LandingGear.h +++ b/libraries/AP_LandingGear/AP_LandingGear.h @@ -5,14 +5,6 @@ #include #include -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL -#define DEFAULT_PIN_WOW 8 -#define DEFAULT_PIN_WOW_POL 1 -#else -#define DEFAULT_PIN_WOW -1 -#define DEFAULT_PIN_WOW_POL 0 -#endif - /// @class AP_LandingGear /// @brief Class managing the control of landing gear class AP_LandingGear { diff --git a/libraries/AP_Logger/AP_Logger.cpp b/libraries/AP_Logger/AP_Logger.cpp index f223ab5251f..71469faac30 100644 --- a/libraries/AP_Logger/AP_Logger.cpp +++ b/libraries/AP_Logger/AP_Logger.cpp @@ -1,14 +1,18 @@ #include "AP_Logger.h" +#if HAL_LOGGING_ENABLED + #include "AP_Logger_Backend.h" #include "AP_Logger_File.h" #include "AP_Logger_DataFlash.h" +#include "AP_Logger_W25N01GV.h" #include "AP_Logger_MAVLink.h" #include #include #include +#include AP_Logger *AP_Logger::_singleton; @@ -26,8 +30,12 @@ extern const AP_HAL::HAL& hal; #endif #endif +#ifndef HAL_LOGGING_DATAFLASH_DRIVER +#define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_DataFlash +#endif + #ifndef HAL_LOGGING_STACK_SIZE -#define HAL_LOGGING_STACK_SIZE 1324 +#define HAL_LOGGING_STACK_SIZE 1580 #endif #ifndef HAL_LOGGING_MAV_BUFSIZE @@ -57,6 +65,14 @@ extern const AP_HAL::HAL& hal; # endif #endif +// when adding new msgs we start at a different index in replay +#if APM_BUILD_TYPE(APM_BUILD_Replay) +#define LOGGING_FIRST_DYNAMIC_MSGID REPLAY_LOG_NEW_MSG_MAX +#else +#define LOGGING_FIRST_DYNAMIC_MSGID 254 +#endif + + const AP_Param::GroupInfo AP_Logger::var_info[] = { // @Param: _BACKEND_TYPE // @DisplayName: AP_Logger Backend Storage type @@ -121,6 +137,7 @@ const AP_Param::GroupInfo AP_Logger::var_info[] = { // @Description: This sets the maximum rate that streaming log messages will be logged to the file backend. A value of zero means that rate limiting is disabled. // @Units: Hz // @Range: 0 1000 + // @Increment: 0.1 // @User: Standard AP_GROUPINFO("_FILE_RATEMAX", 8, AP_Logger, _params.file_ratemax, 0), @@ -130,6 +147,7 @@ const AP_Param::GroupInfo AP_Logger::var_info[] = { // @Description: This sets the maximum rate that streaming log messages will be logged to the mavlink backend. A value of zero means that rate limiting is disabled. // @Units: Hz // @Range: 0 1000 + // @Increment: 0.1 // @User: Standard AP_GROUPINFO("_MAV_RATEMAX", 9, AP_Logger, _params.mav_ratemax, 0), #endif @@ -140,6 +158,7 @@ const AP_Param::GroupInfo AP_Logger::var_info[] = { // @Description: This sets the maximum rate that streaming log messages will be logged to the mavlink backend. A value of zero means that rate limiting is disabled. // @Units: Hz // @Range: 0 1000 + // @Increment: 0.1 // @User: Standard AP_GROUPINFO("_BLK_RATEMAX", 10, AP_Logger, _params.blk_ratemax, 0), #endif @@ -186,7 +205,7 @@ void AP_Logger::Init(const struct LogStructure *structures, uint8_t num_types) { Backend_Type::FILESYSTEM, AP_Logger_File::probe }, #endif #if HAL_LOGGING_DATAFLASH_ENABLED - { Backend_Type::BLOCK, AP_Logger_DataFlash::probe }, + { Backend_Type::BLOCK, HAL_LOGGING_DATAFLASH_DRIVER::probe }, #endif #if HAL_LOGGING_MAVLINK_ENABLED { Backend_Type::MAVLINK, AP_Logger_MAVLink::probe }, @@ -204,7 +223,7 @@ void AP_Logger::Init(const struct LogStructure *structures, uint8_t num_types) LoggerMessageWriter_DFLogStart *message_writer = new LoggerMessageWriter_DFLogStart(); if (message_writer == nullptr) { - AP_BoardConfig::allocation_error("mesage writer"); + AP_BoardConfig::allocation_error("message writer"); } backends[_next_backend] = backend_config.probe_fn(*this, message_writer); if (backends[_next_backend] == nullptr) { @@ -849,7 +868,7 @@ void AP_Logger::Write_Mode(uint8_t mode, const ModeReason reason) void AP_Logger::Write_Parameter(const char *name, float value) { - FOR_EACH_BACKEND(Write_Parameter(name, value)); + FOR_EACH_BACKEND(Write_Parameter(name, value, quiet_nanf())); } void AP_Logger::Write_Mission_Cmd(const AP_Mission &mission, @@ -872,6 +891,13 @@ void AP_Logger::Write_Rally() } #endif +#if HAL_LOGGER_FENCE_ENABLED +void AP_Logger::Write_Fence() +{ + FOR_EACH_BACKEND(Write_Fence()); +} +#endif + // output a FMT message for each backend if not already done so void AP_Logger::Safe_Write_Emit_FMT(log_write_fmt *f) { @@ -1078,12 +1104,6 @@ AP_Logger::log_write_fmt *AP_Logger::msg_fmt_for_name(const char *name, const ch } } -#if APM_BUILD_TYPE(APM_BUILD_Replay) - // don't allow for new msg types during replay. We will be able to - // support these eventually, but for now they cause corruption - return nullptr; -#endif - f = (struct log_write_fmt *)calloc(1, sizeof(*f)); if (f == nullptr) { // out of memory @@ -1198,8 +1218,9 @@ bool AP_Logger::msg_type_in_use(const uint8_t msg_type) const // find a free message type int16_t AP_Logger::find_free_msg_type() const { + const uint8_t start = LOGGING_FIRST_DYNAMIC_MSGID; // avoid using 255 here; perhaps we want to use it to extend things later - for (uint16_t msg_type=254; msg_type>0; msg_type--) { // more likely to be free at end + for (uint16_t msg_type=start; msg_type>0; msg_type--) { // more likely to be free at end if (! msg_type_in_use(msg_type)) { return msg_type; } @@ -1290,6 +1311,36 @@ int16_t AP_Logger::Write_calc_msg_len(const char *fmt) const return len; } +/* + see if we need to save a crash dump. Returns true if either no crash + dump available or we have saved it to sdcard. This is called + continuously until success to account for late mount of the microSD + */ +bool AP_Logger::check_crash_dump_save(void) +{ + int fd = AP::FS().open("@SYS/crash_dump.bin", O_RDONLY); + if (fd == -1) { + // we don't have a crash dump file. The @SYS filesystem + // returns -1 for open on empty files + return true; + } + int fd2 = AP::FS().open("APM/crash_dump.bin", O_WRONLY|O_CREAT|O_TRUNC); + if (fd2 == -1) { + // sdcard not available yet, try again later + AP::FS().close(fd); + return false; + } + uint8_t buf[128]; + int32_t n; + while ((n = AP::FS().read(fd, buf, sizeof(buf))) > 0) { + AP::FS().write(fd2, buf, n); + } + AP::FS().close(fd2); + AP::FS().close(fd); + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Saved crash_dump.bin"); + return true; +} + // thread for processing IO - in general IO involves a long blocking DMA write to an SPI device // and the thread will sleep while this completes preventing other tasks from running, it therefore // is necessary to run the IO in it's own thread @@ -1297,6 +1348,8 @@ void AP_Logger::io_thread(void) { uint32_t last_run_us = AP_HAL::micros(); uint32_t last_stack_us = last_run_us; + uint32_t last_crash_check_us = last_run_us; + bool done_crash_dump_save = false; while (true) { uint32_t now = AP_HAL::micros(); @@ -1315,6 +1368,13 @@ void AP_Logger::io_thread(void) last_stack_us = now; hal.util->log_stack_info(); } + + // check for saving a crash dump file every 5s + if (!done_crash_dump_save && + now - last_crash_check_us > 5000000U) { + last_crash_check_us = now; + done_crash_dump_save = check_crash_dump_save(); + } #if HAL_LOGGER_FILE_CONTENTS_ENABLED file_content_update(); #endif @@ -1532,14 +1592,15 @@ void AP_Logger::file_content_update(FileContent &file_content) return; } - /* this function is called at max 1kHz. We don't want to saturate - the logging with file data, so we reduce the frequency of 64 - byte file writes by a factor of 100. For the file - crash_dump.bin we dump 10x faster so we get it in a reasonable - time (full dump of 450k in about 1 minute) + /* this function is called at around 100Hz on average (tested on + 400Hz copter). We don't want to saturate the logging with file + data, so we reduce the frequency of 64 byte file writes by a + factor of 10. For the file crash_dump.bin we dump 10x faster so + we get it in a reasonable time (full dump of 450k in about 1 + minute) */ file_content.counter++; - const uint8_t frequency = file_content.fast?10:100; + const uint8_t frequency = file_content.fast?1:10; if (file_content.counter % frequency != 0) { return; } @@ -1565,6 +1626,7 @@ void AP_Logger::file_content_update(FileContent &file_content) const auto length = AP::FS().read(file_content.fd, pkt.data, sizeof(pkt.data)); if (length <= 0) { AP::FS().close(file_content.fd); + file_content.fd = -1; file_content.remove_and_free(file); return; } @@ -1587,3 +1649,5 @@ AP_Logger &logger() } }; + +#endif // HAL_LOGGING_ENABLED diff --git a/libraries/AP_Logger/AP_Logger.h b/libraries/AP_Logger/AP_Logger.h index 4a509347a73..386b922503c 100644 --- a/libraries/AP_Logger/AP_Logger.h +++ b/libraries/AP_Logger/AP_Logger.h @@ -48,27 +48,31 @@ #define HAL_LOGGER_FILE_CONTENTS_ENABLED HAL_LOGGING_FILESYSTEM_ENABLED #endif +// range of IDs to allow for new messages during replay. It is very +// useful to be able to add new messages during a replay, but we need +// to avoid colliding with existing messages +#define REPLAY_LOG_NEW_MSG_MAX 230 +#define REPLAY_LOG_NEW_MSG_MIN 220 + #include -#include -#include #include #include #include -#include #include -#include -#include -#include -#include #include +#include +#define HAL_LOGGER_FENCE_ENABLED (AP_FENCE_ENABLED && !defined(HAL_BUILD_AP_PERIPH)) + +#if HAL_LOGGER_FENCE_ENABLED + #include +#endif + #include #include "LoggerMessageWriter.h" class AP_Logger_Backend; -class AP_AHRS; -class AP_AHRS_View; // do not do anything here apart from add stuff; maintaining older // entries means log analysis is easier @@ -138,6 +142,8 @@ enum class LogEvent : uint8_t { EK3_SOURCES_SET_TO_SECONDARY = 86, EK3_SOURCES_SET_TO_TERTIARY = 87, + AIRSPEED_PRIMARY_CHANGED = 90, + SURFACED = 163, NOT_SURFACED = 164, BOTTOMED = 165, @@ -181,6 +187,7 @@ enum class LogErrorSubsystem : uint8_t { PILOT_INPUT = 28, FAILSAFE_VIBE = 29, INTERNAL_ERROR = 30, + FAILSAFE_DEADRECKON = 31 }; // bizarrely this enumeration has lots of duplicate values, offering @@ -250,6 +257,12 @@ class AP_Logger void set_num_types(uint8_t num_types) { _num_types = num_types; } bool CardInserted(void); + bool _log_pause; + + // pause logging if aux switch is active and log rate limit enabled + void log_pause(bool value) { + _log_pause = value; + } // erase handling void EraseAll(); @@ -288,6 +301,9 @@ class AP_Logger void Write_RCOUT(void); void Write_RSSI(); void Write_Rally(); +#if HAL_LOGGER_FENCE_ENABLED + void Write_Fence(); +#endif void Write_Power(void); void Write_Radio(const mavlink_radio_t &packet); void Write_Message(const char *message); @@ -304,14 +320,9 @@ class AP_Logger bool was_command_long=false); void Write_Mission_Cmd(const AP_Mission &mission, const AP_Mission::Mission_Command &cmd); - void Write_RPM(const AP_RPM &rpm_sensor); void Write_RallyPoint(uint8_t total, uint8_t sequence, - const RallyLocation &rally_point); - void Write_Beacon(AP_Beacon &beacon); -#if HAL_PROXIMITY_ENABLED - void Write_Proximity(AP_Proximity &proximity); -#endif + const class RallyLocation &rally_point); void Write_SRTL(bool active, uint16_t num_points, uint16_t max_points, uint8_t action, const Vector3f& point); void Write_Winch(bool healthy, bool thread_end, bool moving, bool clutch, uint8_t mode, float desired_length, float length, float desired_rate, uint16_t tension, float voltage, int8_t temp); void Write_PSCN(float pos_target, float pos, float vel_desired, float vel_target, float vel, float accel_desired, float accel_target, float accel); @@ -326,21 +337,7 @@ class AP_Logger void WriteCritical(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, ...); void WriteV(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, va_list arg_list, bool is_critical=false, bool is_streaming=false); - // This structure provides information on the internal member data of a PID for logging purposes - struct PID_Info { - float target; - float actual; - float error; - float P; - float I; - float D; - float FF; - float Dmod; - float slew_rate; - bool limit; - }; - - void Write_PID(uint8_t msg_type, const PID_Info &info); + void Write_PID(uint8_t msg_type, const class AP_PIDInfo &info); // returns true if logging of a message should be attempted bool should_log(uint32_t mask) const; @@ -363,7 +360,7 @@ class AP_Logger // number of blocks that have been dropped uint32_t num_dropped(void) const; - // accesss to public parameters + // access to public parameters void set_force_log_disarmed(bool force_logging) { _force_log_disarmed = force_logging; } void set_long_log_persist(bool b) { _force_long_log_persist = b; } bool log_while_disarmed(void) const; @@ -499,7 +496,7 @@ class AP_Logger bool _armed; - // state to help us not log unneccesary RCIN values: + // state to help us not log unnecessary RCIN values: bool should_log_rcin2; void Write_Compass_instance(uint64_t time_us, uint8_t mag_instance); @@ -537,6 +534,7 @@ class AP_Logger void start_io_thread(void); void io_thread(); + bool check_crash_dump_save(void); #if HAL_LOGGER_FILE_CONTENTS_ENABLED // support for logging file content @@ -549,7 +547,7 @@ class AP_Logger void reset(); void remove_and_free(file_list *victim); struct file_list *head, *tail; - int fd; + int fd{-1}; uint32_t offset; bool fast; uint8_t counter; diff --git a/libraries/AP_Logger/AP_Logger_Backend.cpp b/libraries/AP_Logger/AP_Logger_Backend.cpp index b1a993164d6..dea7412a15d 100644 --- a/libraries/AP_Logger/AP_Logger_Backend.cpp +++ b/libraries/AP_Logger/AP_Logger_Backend.cpp @@ -5,6 +5,7 @@ #include "AP_Common/AP_FWVersion.h" #include #include +#include extern const AP_HAL::HAL& hal; @@ -172,8 +173,10 @@ void AP_Logger_Backend::WriteMoreStartupMessages() bool AP_Logger_Backend::Write_Emit_FMT(uint8_t msg_type) { #if APM_BUILD_TYPE(APM_BUILD_Replay) - // sure, sure we did.... - return true; + if (msg_type < REPLAY_LOG_NEW_MSG_MIN || msg_type > REPLAY_LOG_NEW_MSG_MAX) { + // don't re-emit FMU msgs unless they are in the replay range + return true; + } #endif // get log structure from front end: @@ -444,7 +447,7 @@ bool AP_Logger_Backend::ShouldLog(bool is_critical) _front._last_mavlink_log_transfer_message_handled_ms != 0) { if (AP_HAL::millis() - _front._last_mavlink_log_transfer_message_handled_ms < 10000) { if (!_front.vehicle_is_armed()) { - // user is transfering files via mavlink + // user is transferring files via mavlink return false; } } else { @@ -520,6 +523,32 @@ bool AP_Logger_Backend::Write_Rally() } #endif +#if HAL_LOGGER_FENCE_ENABLED +// Write a fence point +bool AP_Logger_Backend::Write_FencePoint(uint8_t total, uint8_t sequence, const AC_PolyFenceItem &fence_point) +{ + const struct log_Fence pkt_fence{ + LOG_PACKET_HEADER_INIT(LOG_FENCE_MSG), + time_us : AP_HAL::micros64(), + total : total, + sequence : sequence, + type : uint8_t(fence_point.type), + latitude : fence_point.loc.x, + longitude : fence_point.loc.y, + vertex_count : fence_point.vertex_count, + radius : fence_point.radius + }; + return WriteBlock(&pkt_fence, sizeof(pkt_fence)); +} + +// Write all fence points +bool AP_Logger_Backend::Write_Fence() +{ + // kick off asynchronous write: + return _startup_messagewriter->writeallfence(); +} +#endif // HAL_LOGGER_FENCE_ENABLED + bool AP_Logger_Backend::Write_VER() { @@ -655,9 +684,8 @@ AP_Logger_RateLimiter::AP_Logger_RateLimiter(const AP_Logger &_front, const AP_F */ bool AP_Logger_RateLimiter::should_log_streaming(uint8_t msgid) { - if (rate_limit_hz <= 0) { - // no limiting (user changed the parameter) - return true; + if (front._log_pause) { + return false; } const uint16_t now = AP_HAL::millis16(); uint16_t delta_ms = now - last_send_ms[msgid]; @@ -675,8 +703,8 @@ bool AP_Logger_RateLimiter::should_log_streaming(uint8_t msgid) */ bool AP_Logger_RateLimiter::should_log(uint8_t msgid, bool writev_streaming) { - if (rate_limit_hz <= 0) { - // no limiting (user changed the parameter) + if (rate_limit_hz <= 0 && !front._log_pause) { + // no rate limiting if not paused and rate is zero(user changed the parameter) return true; } if (last_send_ms[msgid] == 0 && !writev_streaming) { diff --git a/libraries/AP_Logger/AP_Logger_Backend.h b/libraries/AP_Logger/AP_Logger_Backend.h index 58d77c46c49..650ffe4efc5 100644 --- a/libraries/AP_Logger/AP_Logger_Backend.h +++ b/libraries/AP_Logger/AP_Logger_Backend.h @@ -2,6 +2,8 @@ #include "AP_Logger.h" +#include + class LoggerMessageWriter_DFLogStart; #define MAX_LOG_FILES 500 @@ -118,18 +120,23 @@ class AP_Logger_Backend bool Write_EntireMission(); bool Write_RallyPoint(uint8_t total, uint8_t sequence, - const RallyLocation &rally_point); + const class RallyLocation &rally_point); bool Write_Rally(); +#if HAL_LOGGER_FENCE_ENABLED + bool Write_FencePoint(uint8_t total, uint8_t sequence, const AC_PolyFenceItem &fence_point); + bool Write_Fence(); +#endif bool Write_Format(const struct LogStructure *structure); bool Write_Message(const char *message); bool Write_MessageF(const char *fmt, ...); bool Write_Mission_Cmd(const AP_Mission &mission, const AP_Mission::Mission_Command &cmd); bool Write_Mode(uint8_t mode, const ModeReason reason); - bool Write_Parameter(const char *name, float value); + bool Write_Parameter(const char *name, float value, float default_val); bool Write_Parameter(const AP_Param *ap, const AP_Param::ParamToken &token, - enum ap_var_type type); + enum ap_var_type type, + float default_val); bool Write_VER(); uint32_t num_dropped(void) const { diff --git a/libraries/AP_Logger/AP_Logger_Block.cpp b/libraries/AP_Logger/AP_Logger_Block.cpp index 4ead7fa5547..e261fe6df5e 100644 --- a/libraries/AP_Logger/AP_Logger_Block.cpp +++ b/libraries/AP_Logger/AP_Logger_Block.cpp @@ -21,17 +21,21 @@ AP_Logger_Block::AP_Logger_Block(AP_Logger &front, LoggerMessageWriter_DFLogStar AP_Logger_Backend(front, writer), writebuf(0) { - // buffer is used for both reads and writes so access must always be within the semaphore - buffer = (uint8_t *)hal.util->malloc_type(page_size_max, AP_HAL::Util::MEM_DMA_SAFE); - if (buffer == nullptr) { - AP_HAL::panic("Out of DMA memory for logging"); - } df_stats_clear(); } -// init is called after backend init +// Init() is called after driver Init(), it is the responsibility of the driver to make sure the +// device is ready to accept commands before Init() is called void AP_Logger_Block::Init(void) { + // buffer is used for both reads and writes so access must always be within the semaphore + buffer = (uint8_t *)hal.util->malloc_type(df_PageSize, AP_HAL::Util::MEM_DMA_SAFE); + if (buffer == nullptr) { + AP_HAL::panic("Out of DMA memory for logging"); + } + + //flash_test(); + if (CardInserted()) { // reserve space for version in last sector df_NumPages -= df_PagePerBlock; @@ -45,16 +49,16 @@ void AP_Logger_Block::Init(void) // If we can't allocate the full size, try to reduce it until we can allocate it while (!writebuf.set_size(bufsize) && bufsize >= df_PageSize * df_PagePerBlock) { - hal.console->printf("AP_Logger_Block: Couldn't set buffer size to=%u\n", (unsigned)bufsize); + DEV_PRINTF("AP_Logger_Block: Couldn't set buffer size to=%u\n", (unsigned)bufsize); bufsize >>= 1; } if (!writebuf.get_size()) { - hal.console->printf("Out of memory for logging\n"); + DEV_PRINTF("Out of memory for logging\n"); return; } - hal.console->printf("AP_Logger_Block: buffer size=%u\n", (unsigned)bufsize); + DEV_PRINTF("AP_Logger_Block: buffer size=%u\n", (unsigned)bufsize); _initialised = true; } @@ -105,7 +109,7 @@ void AP_Logger_Block::FinishWrite(void) chip_full = true; return; } - SectorErase(df_PageAdr / df_PagePerBlock); + SectorErase(get_block(df_PageAdr)); } } @@ -179,13 +183,12 @@ bool AP_Logger_Block::_WritePrioritisedBlock(const void *pBuffer, uint16_t size, // read from the page address and return the file number at that location uint16_t AP_Logger_Block::StartRead(uint32_t PageAdr) { - df_Read_PageAdr = PageAdr; - // copy flash page to buffer if (erase_started) { + df_Read_PageAdr = PageAdr; memset(buffer, 0xff, df_PageSize); } else { - PageToBuffer(df_Read_PageAdr); + PageToBuffer(PageAdr); } return ReadHeaders(); } @@ -235,14 +238,15 @@ bool AP_Logger_Block::ReadBlock(void *pBuffer, uint16_t size) df_Read_BufferIdx += n; if (df_Read_BufferIdx == df_PageSize) { - df_Read_PageAdr++; - if (df_Read_PageAdr > df_NumPages) { - df_Read_PageAdr = 1; + uint32_t new_page_addr = df_Read_PageAdr + 1; + if (new_page_addr > df_NumPages) { + new_page_addr = 1; } if (erase_started) { memset(buffer, 0xff, df_PageSize); + df_Read_PageAdr = new_page_addr; } else { - PageToBuffer(df_Read_PageAdr); + PageToBuffer(new_page_addr); } // We are starting a new page - read FileNumber and FilePage @@ -303,8 +307,8 @@ void AP_Logger_Block::periodic_1Hz() { AP_Logger_Backend::periodic_1Hz(); - if (rate_limiter == nullptr && _front._params.blk_ratemax > 0) { - // setup rate limiting + if (rate_limiter == nullptr && (_front._params.blk_ratemax > 0 || _front._log_pause)) { + // setup rate limiting if log rate max > 0Hz or log pause of streaming entries is requested rate_limiter = new AP_Logger_RateLimiter(_front, _front._params.blk_ratemax); } @@ -408,15 +412,15 @@ void AP_Logger_Block::validate_log_structure() last_file = file; } if (file == next_file) { - hal.console->printf("Found complete log %d at %X-%X\n", int(file), unsigned(page), unsigned(find_last_page_of_log(file))); + DEV_PRINTF("Found complete log %d at %X-%X\n", int(file), unsigned(page), unsigned(find_last_page_of_log(file))); } } if (file != 0xFFFF && file != next_file && page <= df_NumPages && page > 0) { - hal.console->printf("Found corrupt log %d at 0x%04X, erasing", int(file), unsigned(page)); + DEV_PRINTF("Found corrupt log %d at 0x%04X, erasing", int(file), unsigned(page)); df_EraseFrom = page; } else if (next_file != 0xFFFF && page > 0 && next_file > 1) { // chip is empty - hal.console->printf("Found %d complete logs at 0x%04X-0x%04X", int(next_file - first_file), unsigned(page_start), unsigned(page - 1)); + DEV_PRINTF("Found %d complete logs at 0x%04X-0x%04X", int(next_file - first_file), unsigned(page_start), unsigned(page - 1)); } } @@ -827,7 +831,7 @@ bool AP_Logger_Block::io_thread_alive() const /* IO timer running on IO thread - The IO timer runs every 1ms or at 1Khz. The standard flash chip can write rougly 130Kb/s + The IO timer runs every 1ms or at 1Khz. The standard flash chip can write roughly 130Kb/s so there is little point in trying to write more than 130 bytes - or 1 page (256 bytes). The W25Q128FV datasheet gives tpp as typically 0.7ms yielding an absolute maximum rate of 365Kb/s or just over a page per cycle. @@ -864,9 +868,10 @@ void AP_Logger_Block::io_timer(void) WITH_SEMAPHORE(sem); const uint32_t sectors = df_NumPages / df_PagePerSector; - const uint32_t sectors_in_64k = 0x10000 / (df_PagePerSector * df_PageSize); + const uint32_t block_size = df_PagePerBlock * df_PageSize; + const uint32_t sectors_in_block = block_size / (df_PagePerSector * df_PageSize); uint32_t next_sector = get_sector(df_EraseFrom); - const uint32_t aligned_sector = sectors - (((df_NumPages - df_EraseFrom + 1) / df_PagePerSector) / sectors_in_64k) * sectors_in_64k; + const uint32_t aligned_sector = sectors - (((df_NumPages - df_EraseFrom + 1) / df_PagePerSector) / sectors_in_block) * sectors_in_block; while (next_sector < aligned_sector) { Sector4kErase(next_sector); io_timer_heartbeat = AP_HAL::millis(); @@ -875,9 +880,9 @@ void AP_Logger_Block::io_timer(void) uint16_t blocks_erased = 0; while (next_sector < sectors) { blocks_erased++; - SectorErase(next_sector / sectors_in_64k); + SectorErase(next_sector / sectors_in_block); io_timer_heartbeat = AP_HAL::millis(); - next_sector += sectors_in_64k; + next_sector += sectors_in_block; } status_msg = StatusMessage::RECOVERY_COMPLETE; df_EraseFrom = 0; @@ -928,4 +933,44 @@ void AP_Logger_Block::write_log_page() df_Write_FilePage++; } +void AP_Logger_Block::flash_test() +{ + const uint32_t pages_to_check = 128; + for (uint32_t i=1; i<=pages_to_check; i++) { + if ((i-1) % df_PagePerBlock == 0) { + printf("Block erase %u\n", get_block(i)); + SectorErase(get_block(i)); + } + memset(buffer, uint8_t(i), df_PageSize); + if (i<5) { + printf("Flash fill 0x%x\n", uint8_t(i)); + } else if (i==5) { + printf("Flash fill pages 5-%u\n", pages_to_check); + } + BufferToPage(i); + } + for (uint32_t i=1; i<=pages_to_check; i++) { + if (i<5) { + printf("Flash check 0x%x\n", uint8_t(i)); + } else if (i==5) { + printf("Flash check pages 5-%u\n", pages_to_check); + } + PageToBuffer(i); + uint32_t bad_bytes = 0; + uint32_t first_bad_byte = 0; + for (uint32_t j=0; j 0) { + printf("Test failed: page %u, %u of %u bad bytes, first=0x%x\n", + i, bad_bytes, df_PageSize, buffer[first_bad_byte]); + } + } +} + #endif // HAL_LOGGING_BLOCK_ENABLED diff --git a/libraries/AP_Logger/AP_Logger_Block.h b/libraries/AP_Logger/AP_Logger_Block.h index 0eb723629c2..8061137a579 100644 --- a/libraries/AP_Logger/AP_Logger_Block.h +++ b/libraries/AP_Logger/AP_Logger_Block.h @@ -60,9 +60,9 @@ class AP_Logger_Block : public AP_Logger_Backend { uint32_t df_NumPages; volatile bool log_write_started; - static const uint16_t page_size_max = 256; uint8_t *buffer; uint32_t last_messagewrite_message_sent; + uint32_t df_Read_PageAdr; private: /* @@ -74,6 +74,7 @@ class AP_Logger_Block : public AP_Logger_Backend { virtual void Sector4kErase(uint32_t SectorAdr) = 0; virtual void StartErase() = 0; virtual bool InErase() = 0; + void flash_test(void); struct PACKED PageHeader { uint32_t FilePage; @@ -95,8 +96,7 @@ class AP_Logger_Block : public AP_Logger_Backend { // state variables uint16_t df_Read_BufferIdx; - uint32_t df_PageAdr; - uint32_t df_Read_PageAdr; + uint32_t df_PageAdr; // current page address for writes // file numbers uint16_t df_FileNumber; uint16_t df_Write_FileNumber; diff --git a/libraries/AP_Logger/AP_Logger_DataFlash.cpp b/libraries/AP_Logger/AP_Logger_DataFlash.cpp index 65e12f87390..b846f63cd97 100644 --- a/libraries/AP_Logger/AP_Logger_DataFlash.cpp +++ b/libraries/AP_Logger/AP_Logger_DataFlash.cpp @@ -53,6 +53,7 @@ extern const AP_HAL::HAL& hal; #define JEDEC_ID_WINBOND_W25Q64 0xEF4017 #define JEDEC_ID_WINBOND_W25Q128 0xEF4018 #define JEDEC_ID_WINBOND_W25Q256 0xEF4019 +#define JEDEC_ID_WINBOND_W25Q128_2 0xEF7018 #define JEDEC_ID_CYPRESS_S25FL128L 0x016018 void AP_Logger_DataFlash::Init() @@ -109,9 +110,10 @@ bool AP_Logger_DataFlash::getSectorCount(void) // Read manufacturer ID uint8_t cmd = JEDEC_DEVICE_ID; - dev->transfer(&cmd, 1, buffer, 4); + uint8_t buf[4]; // buffer not yet allocated + dev->transfer(&cmd, 1, buf, 4); - uint32_t id = buffer[0] << 16 | buffer[1] << 8 | buffer[2]; + uint32_t id = buf[0] << 16 | buf[1] << 8 | buf[2]; uint32_t blocks = 0; @@ -138,6 +140,7 @@ bool AP_Logger_DataFlash::getSectorCount(void) break; case JEDEC_ID_MICRON_N25Q128: case JEDEC_ID_WINBOND_W25Q128: + case JEDEC_ID_WINBOND_W25Q128_2: case JEDEC_ID_CYPRESS_S25FL128L: blocks = 256; df_PagePerBlock = 256; @@ -216,8 +219,17 @@ void AP_Logger_DataFlash::PageToBuffer(uint32_t pageNum) if (pageNum == 0 || pageNum > df_NumPages+1) { printf("Invalid page read %u\n", pageNum); memset(buffer, 0xFF, df_PageSize); + df_Read_PageAdr = pageNum; return; } + + // we already just read this page + if (pageNum == df_Read_PageAdr && read_cache_valid) { + return; + } + + df_Read_PageAdr = pageNum; + WaitReady(); uint32_t PageAdr = (pageNum-1) * df_PageSize; @@ -227,6 +239,8 @@ void AP_Logger_DataFlash::PageToBuffer(uint32_t pageNum) send_command_addr(JEDEC_READ_DATA, PageAdr); dev->transfer(nullptr, 0, buffer, df_PageSize); dev->set_chip_select(false); + + read_cache_valid = true; } void AP_Logger_DataFlash::BufferToPage(uint32_t pageNum) @@ -235,6 +249,12 @@ void AP_Logger_DataFlash::BufferToPage(uint32_t pageNum) printf("Invalid page write %u\n", pageNum); return; } + + // about to write the cached page + if (pageNum != df_Read_PageAdr) { + read_cache_valid = false; + } + WriteEnable(); WITH_SEMAPHORE(dev_sem); @@ -302,29 +322,4 @@ void AP_Logger_DataFlash::WriteEnable(void) dev->transfer(&b, 1, nullptr, 0); } -void AP_Logger_DataFlash::flash_test() -{ - // wait for the chip to be ready, this has been moved from Init() - hal.scheduler->delay(2000); - - for (uint8_t i=1; i<=20; i++) { - printf("Flash fill %u\n", i); - if (i % df_PagePerBlock == 0) { - SectorErase(i / df_PagePerBlock); - } - memset(buffer, i, df_PageSize); - BufferToPage(i); - } - for (uint8_t i=1; i<=20; i++) { - printf("Flash check %u\n", i); - PageToBuffer(i); - for (uint32_t j=0; j dev; AP_HAL::Semaphore *dev_sem; @@ -44,6 +43,7 @@ class AP_Logger_DataFlash : public AP_Logger_Block { uint32_t erase_start_ms; uint8_t erase_cmd; bool use_32bit_address; + bool read_cache_valid; }; #endif // HAL_LOGGING_DATAFLASH_ENABLED diff --git a/libraries/AP_Logger/AP_Logger_File.cpp b/libraries/AP_Logger/AP_Logger_File.cpp index 3249cd1373f..eb608cbde55 100644 --- a/libraries/AP_Logger/AP_Logger_File.cpp +++ b/libraries/AP_Logger/AP_Logger_File.cpp @@ -76,15 +76,15 @@ void AP_Logger_File::Init() bufsize *= 0.9; } if (bufsize >= _writebuf_chunk && bufsize != desired_bufsize) { - hal.console->printf("AP_Logger: reduced buffer %u/%u\n", (unsigned)bufsize, (unsigned)desired_bufsize); + DEV_PRINTF("AP_Logger: reduced buffer %u/%u\n", (unsigned)bufsize, (unsigned)desired_bufsize); } if (!_writebuf.get_size()) { - hal.console->printf("Out of memory for logging\n"); + DEV_PRINTF("Out of memory for logging\n"); return; } - hal.console->printf("AP_Logger_File: buffer size=%u\n", (unsigned)bufsize); + DEV_PRINTF("AP_Logger_File: buffer size=%u\n", (unsigned)bufsize); _initialised = true; @@ -153,8 +153,8 @@ void AP_Logger_File::periodic_1Hz() } } - if (rate_limiter == nullptr && _front._params.file_ratemax > 0) { - // setup rate limiting + if (rate_limiter == nullptr && (_front._params.file_ratemax > 0 || _front._log_pause)) { + // setup rate limiting if log rate max > 0Hz or log pause of streaming entries is requested rate_limiter = new AP_Logger_RateLimiter(_front, _front._params.file_ratemax); } } @@ -201,6 +201,29 @@ int64_t AP_Logger_File::disk_space() return AP::FS().disk_space(_log_directory); } +/* + convert a dirent to a log number + */ +bool AP_Logger_File::dirent_to_log_num(const dirent *de, uint16_t &log_num) const +{ + uint8_t length = strlen(de->d_name); + if (length < 5) { + return false; + } + if (strncmp(&de->d_name[length-4], ".BIN", 4) != 0) { + // doesn't end in .BIN + return false; + } + + uint16_t thisnum = strtoul(de->d_name, nullptr, 10); + if (thisnum > MAX_LOG_FILES) { + return false; + } + log_num = thisnum; + return true; +} + + // find_oldest_log - find oldest log in _log_directory // returns 0 if no log was found uint16_t AP_Logger_File::find_oldest_log() @@ -230,19 +253,9 @@ uint16_t AP_Logger_File::find_oldest_log() EXPECT_DELAY_MS(3000); for (struct dirent *de=AP::FS().readdir(d); de; de=AP::FS().readdir(d)) { EXPECT_DELAY_MS(3000); - uint8_t length = strlen(de->d_name); - if (length < 5) { - // not long enough for \d+[.]BIN - continue; - } - if (strncmp(&de->d_name[length-4], ".BIN", 4) != 0) { - // doesn't end in .BIN - continue; - } - - uint16_t thisnum = strtoul(de->d_name, nullptr, 10); - if (thisnum > MAX_LOG_FILES) { - // ignore files above our official maximum... + uint16_t thisnum; + if (!dirent_to_log_num(de, thisnum)) { + // not a log filename continue; } if (current_oldest_log == 0) { @@ -310,12 +323,12 @@ void AP_Logger_File::Prep_MinSpace() break; } if (file_exists(filename_to_remove)) { - hal.console->printf("Removing (%s) for minimum-space requirements (%.0fMB < %.0fMB)\n", + DEV_PRINTF("Removing (%s) for minimum-space requirements (%.0fMB < %.0fMB)\n", filename_to_remove, (double)avail*B_to_MB, (double)target_free*B_to_MB); EXPECT_DELAY_MS(2000); if (AP::FS().unlink(filename_to_remove) == -1) { _cached_oldest_log = 0; - hal.console->printf("Failed to remove %s: %s\n", filename_to_remove, strerror(errno)); + DEV_PRINTF("Failed to remove %s: %s\n", filename_to_remove, strerror(errno)); free(filename_to_remove); if (errno == ENOENT) { // corruption - should always have a continuous @@ -529,9 +542,6 @@ uint32_t AP_Logger_File::_get_log_size(const uint16_t log_num) struct stat st; EXPECT_DELAY_MS(3000); if (AP::FS().stat(fname, &st) != 0) { - if (_open_error_ms == 0) { - printf("Unable to fetch Log File Size (%s): %s\n", fname, strerror(errno)); - } free(fname); return 0; } @@ -617,7 +627,7 @@ int16_t AP_Logger_File::get_log_data(const uint16_t list_entry, const uint16_t p int saved_errno = errno; ::printf("Log read open fail for %s - %s\n", fname, strerror(saved_errno)); - hal.console->printf("Log read open fail for %s - %s\n", + DEV_PRINTF("Log read open fail for %s - %s\n", fname, strerror(saved_errno)); free(fname); return -1; @@ -661,29 +671,37 @@ void AP_Logger_File::get_log_info(const uint16_t list_entry, uint32_t &size, uin } - /* get the number of logs - note that the log numbers must be consecutive */ uint16_t AP_Logger_File::get_num_logs() { - uint16_t ret = 0; + auto *d = AP::FS().opendir(_log_directory); + if (d == nullptr) { + return 0; + } uint16_t high = find_last_log(); - uint16_t i; - for (i=high; i>0; i--) { - if (! log_exists(i)) { - break; + uint16_t ret = high; + uint16_t smallest_above_last = 0; + + EXPECT_DELAY_MS(2000); + for (struct dirent *de=AP::FS().readdir(d); de; de=AP::FS().readdir(d)) { + EXPECT_DELAY_MS(100); + uint16_t thisnum; + if (!dirent_to_log_num(de, thisnum)) { + // not a log filename + continue; } - ret++; - } - if (i == 0) { - for (i=MAX_LOG_FILES; i>high; i--) { - if (! log_exists(i)) { - break; - } - ret++; + if (thisnum > high && (smallest_above_last == 0 || thisnum < smallest_above_last)) { + smallest_above_last = thisnum; } } + AP::FS().closedir(d); + if (smallest_above_last != 0) { + // we have wrapped, add in the logs with high numbers + ret += (MAX_LOG_FILES - smallest_above_last) + 1; + } + return ret; } @@ -772,7 +790,7 @@ void AP_Logger_File::start_new_log(void) } if (disk_space_avail() < _free_space_min_avail && disk_space() > 0) { - hal.console->printf("Out of space for logging\n"); + DEV_PRINTF("Out of space for logging\n"); return; } @@ -816,7 +834,7 @@ void AP_Logger_File::start_new_log(void) if (open_error_ms_was_zero) { ::printf("Log open fail for %s - %s\n", _write_filename, strerror(saved_errno)); - hal.console->printf("Log open fail for %s - %s\n", + DEV_PRINTF("Log open fail for %s - %s\n", _write_filename, strerror(saved_errno)); } return; @@ -916,7 +934,7 @@ void AP_Logger_File::io_timer(void) _free_space_last_check_time = tnow; last_io_operation = "disk_space_avail"; if (disk_space_avail() < _free_space_min_avail && disk_space() > 0) { - hal.console->printf("Out of space for logging\n"); + DEV_PRINTF("Out of space for logging\n"); stop_logging(); _open_error_ms = AP_HAL::millis(); // prevent logging starting again for 5s last_io_operation = ""; diff --git a/libraries/AP_Logger/AP_Logger_File.h b/libraries/AP_Logger/AP_Logger_File.h index 5f76f4fb925..7d1f6496c23 100644 --- a/libraries/AP_Logger/AP_Logger_File.h +++ b/libraries/AP_Logger/AP_Logger_File.h @@ -100,6 +100,8 @@ class AP_Logger_File : public AP_Logger_Backend bool file_exists(const char *filename) const; bool log_exists(const uint16_t lognum) const; + bool dirent_to_log_num(const dirent *de, uint16_t &log_num) const; + // write buffer ByteBuffer _writebuf{0}; const uint16_t _writebuf_chunk = HAL_LOGGER_WRITE_CHUNK_SIZE; diff --git a/libraries/AP_Logger/AP_Logger_MAVLink.cpp b/libraries/AP_Logger/AP_Logger_MAVLink.cpp index b9c7a81c5bf..69eb068c522 100644 --- a/libraries/AP_Logger/AP_Logger_MAVLink.cpp +++ b/libraries/AP_Logger/AP_Logger_MAVLink.cpp @@ -274,10 +274,16 @@ void AP_Logger_MAVLink::remote_log_block_status_msg(const GCS_MAVLINK &link, if (!semaphore.take_nonblocking()) { return; } - if(packet.status == MAV_REMOTE_LOG_DATA_BLOCK_NACK) { - handle_retry(packet.seqno); - } else { - handle_ack(link, msg, packet.seqno); + switch ((MAV_REMOTE_LOG_DATA_BLOCK_STATUSES)packet.status) { + case MAV_REMOTE_LOG_DATA_BLOCK_NACK: + handle_retry(packet.seqno); + break; + case MAV_REMOTE_LOG_DATA_BLOCK_ACK: + handle_ack(link, msg, packet.seqno); + break; + // we apparently have to handle an END enum entry, just drop it so we catch future additions + case MAV_REMOTE_LOG_DATA_BLOCK_STATUSES_ENUM_END: + break; } semaphore.give(); } @@ -524,8 +530,8 @@ void AP_Logger_MAVLink::periodic_10Hz(const uint32_t now) } void AP_Logger_MAVLink::periodic_1Hz() { - if (rate_limiter == nullptr && _front._params.mav_ratemax > 0) { - // setup rate limiting + if (rate_limiter == nullptr && (_front._params.mav_ratemax > 0 || _front._log_pause)) { + // setup rate limiting if log rate max > 0Hz or log pause of streaming entries is requested rate_limiter = new AP_Logger_RateLimiter(_front, _front._params.mav_ratemax); } diff --git a/libraries/AP_Logger/AP_Logger_MAVLink.h b/libraries/AP_Logger/AP_Logger_MAVLink.h index f379f121f27..3011dcd718d 100644 --- a/libraries/AP_Logger/AP_Logger_MAVLink.h +++ b/libraries/AP_Logger/AP_Logger_MAVLink.h @@ -5,13 +5,11 @@ */ #pragma once -#include - #include "AP_Logger_Backend.h" #if HAL_LOGGING_MAVLINK_ENABLED -extern const AP_HAL::HAL& hal; +#include #define DF_MAVLINK_DISABLE_INTERRUPTS 0 diff --git a/libraries/AP_Logger/AP_Logger_W25N01GV.cpp b/libraries/AP_Logger/AP_Logger_W25N01GV.cpp new file mode 100644 index 00000000000..86ce642c991 --- /dev/null +++ b/libraries/AP_Logger/AP_Logger_W25N01GV.cpp @@ -0,0 +1,334 @@ +/* + logging to a DataFlash block based storage device on SPI +*/ + + +#include + +#include "AP_Logger_W25N01GV.h" + +#if HAL_LOGGING_DATAFLASH_ENABLED + +#include + +extern const AP_HAL::HAL& hal; + +#define JEDEC_WRITE_ENABLE 0x06 +#define JEDEC_WRITE_DISABLE 0x04 +#define JEDEC_READ_STATUS 0x05 +#define JEDEC_WRITE_STATUS 0x01 +#define JEDEC_READ_DATA 0x03 +#define JEDEC_PAGE_DATA_READ 0x13 +#define JEDEC_FAST_READ 0x0b +#define JEDEC_DEVICE_ID 0x9F +#define JEDEC_PAGE_WRITE 0x02 +#define JEDEC_PROGRAM_EXECUTE 0x10 + +#define JEDEC_DEVICE_RESET 0xFF +#define JEDEC_BLOCK_ERASE 0xD8 // 128K erase + +#define JEDEC_STATUS_BUSY 0x01 +#define JEDEC_STATUS_WRITEPROTECT 0x02 + +#define W25N01G_STATUS_REG 0xC0 +#define W25N01G_PROT_REG 0xA0 +#define W25N01G_CONF_REG 0xB0 +#define W25N01G_STATUS_EFAIL 0x04 +#define W25N01G_STATUS_PFAIL 0x08 + +#define W25N01G_PROT_SRP1_ENABLE (1 << 0) +#define W25N01G_PROT_WP_E_ENABLE (1 << 1) +#define W25N01G_PROT_TB_ENABLE (1 << 2) +#define W25N01G_PROT_PB0_ENABLE (1 << 3) +#define W25N01G_PROT_PB1_ENABLE (1 << 4) +#define W25N01G_PROT_PB2_ENABLE (1 << 5) +#define W25N01G_PROT_PB3_ENABLE (1 << 6) +#define W25N01G_PROT_SRP2_ENABLE (1 << 7) + +#define W25N01G_CONFIG_ECC_ENABLE (1 << 4) +#define W25N01G_CONFIG_BUFFER_READ_MODE (1 << 3) + +#define W25N01G_TIMEOUT_PAGE_READ_US 60 // tREmax = 60us (ECC enabled) +#define W25N01G_TIMEOUT_PAGE_PROGRAM_US 700 // tPPmax = 700us +#define W25N01G_TIMEOUT_BLOCK_ERASE_MS 10 // tBEmax = 10ms +#define W25N01G_TIMEOUT_RESET_MS 500 // tRSTmax = 500ms +#define W25N01G_NUM_BLOCKS 1024 + +#define JEDEC_ID_WINBOND_W25N01GV 0xEFAA21 + +void AP_Logger_W25N01GV::Init() +{ + dev = hal.spi->get_device("dataflash"); + if (!dev) { + AP_HAL::panic("PANIC: AP_Logger W25N01GV device not found"); + return; + } + + dev_sem = dev->get_semaphore(); + + if (!getSectorCount()) { + flash_died = true; + return; + } + + flash_died = false; + + // reset the device + WaitReady(); + { + WITH_SEMAPHORE(dev_sem); + uint8_t b = JEDEC_DEVICE_RESET; + dev->transfer(&b, 1, nullptr, 0); + } + hal.scheduler->delay(W25N01G_TIMEOUT_RESET_MS); + + // disable write protection + WriteStatusReg(W25N01G_PROT_REG, 0); + // enable ECC and buffer mode + WriteStatusReg(W25N01G_CONF_REG, W25N01G_CONFIG_ECC_ENABLE|W25N01G_CONFIG_BUFFER_READ_MODE); + + printf("W25N01GV status: SR-1=0x%x, SR-2=0x%x, SR-3=0x%x\n", + ReadStatusRegBits(W25N01G_PROT_REG), + ReadStatusRegBits(W25N01G_CONF_REG), + ReadStatusRegBits(W25N01G_STATUS_REG)); + + AP_Logger_Block::Init(); +} + +/* + wait for busy flag to be cleared + */ +void AP_Logger_W25N01GV::WaitReady() +{ + if (flash_died) { + return; + } + + uint32_t t = AP_HAL::millis(); + while (Busy()) { + hal.scheduler->delay_microseconds(100); + if (AP_HAL::millis() - t > 5000) { + printf("DataFlash: flash_died\n"); + flash_died = true; + break; + } + } +} + +bool AP_Logger_W25N01GV::getSectorCount(void) +{ + WaitReady(); + + WITH_SEMAPHORE(dev_sem); + + // Read manufacturer ID + uint8_t cmd = JEDEC_DEVICE_ID; + uint8_t buf[4]; // buffer not yet allocated + dev->transfer(&cmd, 1, buf, 4); + + uint32_t id = buf[1] << 16 | buf[2] << 8 | buf[3]; + + switch (id) { + case JEDEC_ID_WINBOND_W25N01GV: + df_PageSize = 2048; + df_PagePerBlock = 64; + df_PagePerSector = 64; // make sectors equivalent to block + break; + + default: + hal.scheduler->delay(2000); + printf("Unknown SPI Flash 0x%08x\n", id); + return false; + } + + df_NumPages = W25N01G_NUM_BLOCKS * df_PagePerBlock; + + printf("SPI Flash 0x%08x found pages=%u\n", id, df_NumPages); + return true; +} + +// Read the status register bits +uint8_t AP_Logger_W25N01GV::ReadStatusRegBits(uint8_t bits) +{ + WITH_SEMAPHORE(dev_sem); + uint8_t cmd[2] { JEDEC_READ_STATUS, bits }; + uint8_t status; + dev->transfer(cmd, 2, &status, 1); + return status; +} + +void AP_Logger_W25N01GV::WriteStatusReg(uint8_t reg, uint8_t bits) +{ + WaitReady(); + WITH_SEMAPHORE(dev_sem); + uint8_t cmd[3] = {JEDEC_WRITE_STATUS, reg, bits}; + dev->transfer(cmd, 3, nullptr, 0); +} + +bool AP_Logger_W25N01GV::Busy() +{ + uint8_t status = ReadStatusRegBits(W25N01G_STATUS_REG); + + if ((status & W25N01G_STATUS_PFAIL) != 0) { + printf("Program failure!\n"); + } + if ((status & W25N01G_STATUS_EFAIL) != 0) { + printf("Erase failure!\n"); + } + + return (status & JEDEC_STATUS_BUSY) != 0; +} + +/* + send a command with an address +*/ +void AP_Logger_W25N01GV::send_command_addr(uint8_t command, uint32_t PageAdr) +{ + uint8_t cmd[4]; + cmd[0] = command; + cmd[1] = 0; // dummy + cmd[2] = (PageAdr >> 8) & 0xff; + cmd[3] = (PageAdr >> 0) & 0xff; + + dev->transfer(cmd, 4, nullptr, 0); +} + +void AP_Logger_W25N01GV::PageToBuffer(uint32_t pageNum) +{ + if (pageNum == 0 || pageNum > df_NumPages+1) { + printf("Invalid page read %u\n", pageNum); + memset(buffer, 0xFF, df_PageSize); + df_Read_PageAdr = pageNum; + return; + } + + // we already just read this page + if (pageNum == df_Read_PageAdr && read_cache_valid) { + return; + } + + df_Read_PageAdr = pageNum; + + WaitReady(); + + uint32_t PageAdr = (pageNum-1); + + { + WITH_SEMAPHORE(dev_sem); + // read page into internal buffer + send_command_addr(JEDEC_PAGE_DATA_READ, PageAdr); + } + + // read from internal buffer into our buffer + WaitReady(); + { + WITH_SEMAPHORE(dev_sem); + dev->set_chip_select(true); + uint8_t cmd[4]; + cmd[0] = JEDEC_READ_DATA; + cmd[1] = (0 >> 8) & 0xff; // column address zero + cmd[2] = (0 >> 0) & 0xff; // column address zero + cmd[3] = 0; // dummy + dev->transfer(cmd, 4, nullptr, 0); + dev->transfer(nullptr, 0, buffer, df_PageSize); + dev->set_chip_select(false); + + read_cache_valid = true; + } +} + +void AP_Logger_W25N01GV::BufferToPage(uint32_t pageNum) +{ + if (pageNum == 0 || pageNum > df_NumPages+1) { + printf("Invalid page write %u\n", pageNum); + return; + } + + // just wrote the cached page + if (pageNum != df_Read_PageAdr) { + read_cache_valid = false; + } + + WriteEnable(); + + uint32_t PageAdr = (pageNum-1); + { + WITH_SEMAPHORE(dev_sem); + + // write our buffer into internal buffer + dev->set_chip_select(true); + + uint8_t cmd[3]; + cmd[0] = JEDEC_PAGE_WRITE; + cmd[1] = (0 >> 8) & 0xff; // column address zero + cmd[2] = (0 >> 0) & 0xff; // column address zero + + dev->transfer(cmd, 3, nullptr, 0); + dev->transfer(buffer, df_PageSize, nullptr, 0); + dev->set_chip_select(false); + } + + // write from internal buffer into page + { + WITH_SEMAPHORE(dev_sem); + send_command_addr(JEDEC_PROGRAM_EXECUTE, PageAdr); + } +} + +/* + erase one sector (sizes varies with hw) +*/ +void AP_Logger_W25N01GV::SectorErase(uint32_t blockNum) +{ + WriteEnable(); + WITH_SEMAPHORE(dev_sem); + + uint32_t PageAdr = blockNum * df_PagePerBlock; + send_command_addr(JEDEC_BLOCK_ERASE, PageAdr); +} + +/* + erase one 4k sector +*/ +void AP_Logger_W25N01GV::Sector4kErase(uint32_t sectorNum) +{ + SectorErase(sectorNum); +} + +void AP_Logger_W25N01GV::StartErase() +{ + WriteEnable(); + + WITH_SEMAPHORE(dev_sem); + + // just erase the first block, others will follow in InErase + send_command_addr(JEDEC_BLOCK_ERASE, 0); + + erase_block = 1; + erase_start_ms = AP_HAL::millis(); + printf("Dataflash: erase started\n"); +} + +bool AP_Logger_W25N01GV::InErase() +{ + if (erase_start_ms && !Busy()) { + if (erase_block < W25N01G_NUM_BLOCKS) { + SectorErase(erase_block++); + } else { + printf("Dataflash: erase done (%u ms)\n", AP_HAL::millis() - erase_start_ms); + erase_start_ms = 0; + erase_block = 0; + } + } + return erase_start_ms != 0; +} + +void AP_Logger_W25N01GV::WriteEnable(void) +{ + WaitReady(); + WITH_SEMAPHORE(dev_sem); + uint8_t b = JEDEC_WRITE_ENABLE; + dev->transfer(&b, 1, nullptr, 0); +} + +#endif // HAL_LOGGING_DATAFLASH_ENABLED diff --git a/libraries/AP_Logger/AP_Logger_W25N01GV.h b/libraries/AP_Logger/AP_Logger_W25N01GV.h new file mode 100644 index 00000000000..556603eaffd --- /dev/null +++ b/libraries/AP_Logger/AP_Logger_W25N01GV.h @@ -0,0 +1,48 @@ +/* + logging for block based dataflash devices on SPI + */ +#pragma once + +#include + +#include "AP_Logger_Block.h" + +#if HAL_LOGGING_DATAFLASH_ENABLED + +class AP_Logger_W25N01GV : public AP_Logger_Block { +public: + AP_Logger_W25N01GV(AP_Logger &front, LoggerMessageWriter_DFLogStart *writer) : + AP_Logger_Block(front, writer) {} + static AP_Logger_Backend *probe(AP_Logger &front, + LoggerMessageWriter_DFLogStart *ls) { + return new AP_Logger_W25N01GV(front, ls); + } + void Init(void) override; + bool CardInserted() const override { return !flash_died && df_NumPages > 0; } + +private: + void BufferToPage(uint32_t PageAdr) override; + void PageToBuffer(uint32_t PageAdr) override; + void SectorErase(uint32_t SectorAdr) override; + void Sector4kErase(uint32_t SectorAdr) override; + void StartErase() override; + bool InErase() override; + void send_command_addr(uint8_t cmd, uint32_t address); + void WaitReady(); + bool Busy(); + uint8_t ReadStatusRegBits(uint8_t bits); + void WriteStatusReg(uint8_t reg, uint8_t bits); + + void WriteEnable(); + bool getSectorCount(void); + + AP_HAL::OwnPtr dev; + AP_HAL::Semaphore *dev_sem; + + bool flash_died; + uint32_t erase_start_ms; + uint16_t erase_block; + bool read_cache_valid; +}; + +#endif // HAL_LOGGING_DATAFLASH_ENABLED diff --git a/libraries/AP_Logger/LogFile.cpp b/libraries/AP_Logger/LogFile.cpp index 7c0c5d78cb7..192c93782f6 100644 --- a/libraries/AP_Logger/LogFile.cpp +++ b/libraries/AP_Logger/LogFile.cpp @@ -6,6 +6,9 @@ #include #include #include +#include +#include +#include #include "AP_Logger.h" #include "AP_Logger_File.h" @@ -100,13 +103,14 @@ bool AP_Logger_Backend::Write_Format_Units(const struct LogStructure *s) /* write a parameter to the log */ -bool AP_Logger_Backend::Write_Parameter(const char *name, float value) +bool AP_Logger_Backend::Write_Parameter(const char *name, float value, float default_val) { struct log_Parameter pkt{ LOG_PACKET_HEADER_INIT(LOG_PARAMETER_MSG), time_us : AP_HAL::micros64(), name : {}, - value : value + value : value, + default_value : default_val }; strncpy_noterm(pkt.name, name, sizeof(pkt.name)); return WriteCriticalBlock(&pkt, sizeof(pkt)); @@ -117,11 +121,12 @@ bool AP_Logger_Backend::Write_Parameter(const char *name, float value) */ bool AP_Logger_Backend::Write_Parameter(const AP_Param *ap, const AP_Param::ParamToken &token, - enum ap_var_type type) + enum ap_var_type type, + float default_val) { char name[16]; ap->copy_name_token(token, &name[0], sizeof(name), true); - return Write_Parameter(name, ap->cast_to_float(type)); + return Write_Parameter(name, ap->cast_to_float(type), default_val); } // Write an RCIN packet @@ -178,25 +183,68 @@ void AP_Logger::Write_RCIN(void) // Write an SERVO packet void AP_Logger::Write_RCOUT(void) { - const struct log_RCOUT pkt{ - LOG_PACKET_HEADER_INIT(LOG_RCOUT_MSG), - time_us : AP_HAL::micros64(), - chan1 : hal.rcout->read(0), - chan2 : hal.rcout->read(1), - chan3 : hal.rcout->read(2), - chan4 : hal.rcout->read(3), - chan5 : hal.rcout->read(4), - chan6 : hal.rcout->read(5), - chan7 : hal.rcout->read(6), - chan8 : hal.rcout->read(7), - chan9 : hal.rcout->read(8), - chan10 : hal.rcout->read(9), - chan11 : hal.rcout->read(10), - chan12 : hal.rcout->read(11), - chan13 : hal.rcout->read(12), - chan14 : hal.rcout->read(13) - }; - WriteBlock(&pkt, sizeof(pkt)); + const uint32_t enabled_mask = ~SRV_Channels::get_output_channel_mask(SRV_Channel::k_GPIO); + + if ((enabled_mask & 0x3FFF) != 0) { + const struct log_RCOUT pkt{ + LOG_PACKET_HEADER_INIT(LOG_RCOUT_MSG), + time_us : AP_HAL::micros64(), + chan1 : hal.rcout->read(0), + chan2 : hal.rcout->read(1), + chan3 : hal.rcout->read(2), + chan4 : hal.rcout->read(3), + chan5 : hal.rcout->read(4), + chan6 : hal.rcout->read(5), + chan7 : hal.rcout->read(6), + chan8 : hal.rcout->read(7), + chan9 : hal.rcout->read(8), + chan10 : hal.rcout->read(9), + chan11 : hal.rcout->read(10), + chan12 : hal.rcout->read(11), + chan13 : hal.rcout->read(12), + chan14 : hal.rcout->read(13) + }; + WriteBlock(&pkt, sizeof(pkt)); + } + +#if NUM_SERVO_CHANNELS >= 15 + if ((enabled_mask & 0x3C000) != 0) { + const struct log_RCOUT2 pkt2{ + LOG_PACKET_HEADER_INIT(LOG_RCOUT2_MSG), + time_us : AP_HAL::micros64(), + chan15 : hal.rcout->read(14), + chan16 : hal.rcout->read(15), + chan17 : hal.rcout->read(16), + chan18 : hal.rcout->read(17), + }; + WriteBlock(&pkt2, sizeof(pkt2)); + } +#endif + +#if NUM_SERVO_CHANNELS >= 19 + if ((enabled_mask & 0xFFFC0000) != 0) { + const struct log_RCOUT pkt3{ + LOG_PACKET_HEADER_INIT(LOG_RCOUT3_MSG), + time_us : AP_HAL::micros64(), + chan1 : hal.rcout->read(18), + chan2 : hal.rcout->read(19), + chan3 : hal.rcout->read(20), + chan4 : hal.rcout->read(21), + chan5 : hal.rcout->read(22), + chan6 : hal.rcout->read(23), + chan7 : hal.rcout->read(24), + chan8 : hal.rcout->read(25), + chan9 : hal.rcout->read(26), + chan10 : hal.rcout->read(27), + chan11 : hal.rcout->read(28), + chan12 : hal.rcout->read(29), + chan13 : hal.rcout->read(30), + chan14 : hal.rcout->read(31) + }; + WriteBlock(&pkt3, sizeof(pkt3)); + } +#endif + } // Write an RSSI packet @@ -267,7 +315,7 @@ bool AP_Logger_Backend::Write_Mission_Cmd(const AP_Mission &mission, return WriteBlock(&pkt, sizeof(pkt)); } -#if HAL_MISSION_ENABLED +#if AP_MISSION_ENABLED bool AP_Logger_Backend::Write_EntireMission() { // kick off asynchronous write: @@ -407,7 +455,7 @@ void AP_Logger::Write_ServoStatus(uint64_t time_us, uint8_t id, float position, // Write a Yaw PID packet -void AP_Logger::Write_PID(uint8_t msg_type, const PID_Info &info) +void AP_Logger::Write_PID(uint8_t msg_type, const AP_PIDInfo &info) { const struct log_PID pkt{ LOG_PACKET_HEADER_INIT(msg_type), @@ -426,114 +474,6 @@ void AP_Logger::Write_PID(uint8_t msg_type, const PID_Info &info) WriteBlock(&pkt, sizeof(pkt)); } -void AP_Logger::Write_RPM(const AP_RPM &rpm_sensor) -{ - float rpm1 = -1, rpm2 = -1; - - rpm_sensor.get_rpm(0, rpm1); - rpm_sensor.get_rpm(1, rpm2); - - const struct log_RPM pkt{ - LOG_PACKET_HEADER_INIT(LOG_RPM_MSG), - time_us : AP_HAL::micros64(), - rpm1 : rpm1, - rpm2 : rpm2 - }; - WriteBlock(&pkt, sizeof(pkt)); -} - -// Write beacon sensor (position) data -void AP_Logger::Write_Beacon(AP_Beacon &beacon) -{ - if (!beacon.enabled()) { - return; - } - // position - Vector3f pos; - float accuracy = 0.0f; - beacon.get_vehicle_position_ned(pos, accuracy); - - const struct log_Beacon pkt_beacon{ - LOG_PACKET_HEADER_INIT(LOG_BEACON_MSG), - time_us : AP_HAL::micros64(), - health : (uint8_t)beacon.healthy(), - count : (uint8_t)beacon.count(), - dist0 : beacon.beacon_distance(0), - dist1 : beacon.beacon_distance(1), - dist2 : beacon.beacon_distance(2), - dist3 : beacon.beacon_distance(3), - posx : pos.x, - posy : pos.y, - posz : pos.z - }; - WriteBlock(&pkt_beacon, sizeof(pkt_beacon)); -} - -#if HAL_PROXIMITY_ENABLED -// Write proximity sensor distances -void AP_Logger::Write_Proximity(AP_Proximity &proximity) -{ - // exit immediately if not enabled - if (proximity.get_status() == AP_Proximity::Status::NotConnected) { - return; - } - - AP_Proximity::Proximity_Distance_Array dist_array{}; // raw distances stored here - AP_Proximity::Proximity_Distance_Array filt_dist_array{}; //filtered distances stored here - for (uint8_t i = 0; i < proximity.get_num_layers(); i++) { - const bool active = proximity.get_active_layer_distances(i, dist_array, filt_dist_array); - if (!active) { - // nothing on this layer - continue; - } - float dist_up; - if (!proximity.get_upward_distance(dist_up)) { - dist_up = 0.0f; - } - - float closest_ang = 0.0f; - float closest_dist = 0.0f; - proximity.get_closest_object(closest_ang, closest_dist); - - const struct log_Proximity pkt_proximity{ - LOG_PACKET_HEADER_INIT(LOG_PROXIMITY_MSG), - time_us : AP_HAL::micros64(), - instance : i, - health : (uint8_t)proximity.get_status(), - dist0 : filt_dist_array.distance[0], - dist45 : filt_dist_array.distance[1], - dist90 : filt_dist_array.distance[2], - dist135 : filt_dist_array.distance[3], - dist180 : filt_dist_array.distance[4], - dist225 : filt_dist_array.distance[5], - dist270 : filt_dist_array.distance[6], - dist315 : filt_dist_array.distance[7], - distup : dist_up, - closest_angle : closest_ang, - closest_dist : closest_dist - }; - WriteBlock(&pkt_proximity, sizeof(pkt_proximity)); - - if (proximity.get_raw_log_enable()) { - const struct log_Proximity_raw pkt_proximity_raw{ - LOG_PACKET_HEADER_INIT(LOG_RAW_PROXIMITY_MSG), - time_us : AP_HAL::micros64(), - instance : i, - raw_dist0 : dist_array.distance[0], - raw_dist45 : dist_array.distance[1], - raw_dist90 : dist_array.distance[2], - raw_dist135 : dist_array.distance[3], - raw_dist180 : dist_array.distance[4], - raw_dist225 : dist_array.distance[5], - raw_dist270 : dist_array.distance[6], - raw_dist315 : dist_array.distance[7], - }; - WriteBlock(&pkt_proximity_raw, sizeof(pkt_proximity_raw)); - } - } -} -#endif - void AP_Logger::Write_SRTL(bool active, uint16_t num_points, uint16_t max_points, uint8_t action, const Vector3f& breadcrumb) { const struct log_SRTL pkt_srtl{ diff --git a/libraries/AP_Logger/LogStructure.h b/libraries/AP_Logger/LogStructure.h index aacdb5e8ef8..c17e4fc7fa2 100644 --- a/libraries/AP_Logger/LogStructure.h +++ b/libraries/AP_Logger/LogStructure.h @@ -101,6 +101,7 @@ const struct MultiplierStructure log_Multipliers[] = { { 'E', 1e-5 }, { 'F', 1e-6 }, { 'G', 1e-7 }, + { 'I', 1e-9 }, // { '!', 3.6 }, // (ampere*second => milliampere*hour) and (km/h => m/s) { '/', 3600 }, // (ampere*second => ampere*hour) @@ -119,6 +120,7 @@ const struct MultiplierStructure log_Multipliers[] = { #define HEAD_BYTE1 0xA3 // Decimal 163 #define HEAD_BYTE2 0x95 // Decimal 149 +#include #include #include #include @@ -131,12 +133,23 @@ const struct MultiplierStructure log_Multipliers[] = { #include #include #include +#include #include #include #include +#include +#include +#include // structure used to define logging format +// It is packed on ChibiOS to save flash space; however, this causes problems +// when building the SITL on an Apple M1 CPU (and is also slower) so we do not +// pack it by default +#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS struct PACKED LogStructure { +#else +struct LogStructure { +#endif uint8_t msg_type; uint8_t msg_len; const char *name; @@ -193,6 +206,7 @@ struct PACKED log_Parameter { uint64_t time_us; char name[16]; float value; + float default_value; }; struct PACKED log_DSF { @@ -272,6 +286,15 @@ struct PACKED log_RCOUT { uint16_t chan14; }; +struct PACKED log_RCOUT2 { + LOG_PACKET_HEADER; + uint64_t time_us; + uint16_t chan15; + uint16_t chan16; + uint16_t chan17; + uint16_t chan18; +}; + struct PACKED log_MAV { LOG_PACKET_HEADER; uint64_t time_us; @@ -451,6 +474,7 @@ struct PACKED log_TERRAIN { float current_height; uint16_t pending; uint16_t loaded; + float reference_offset; }; struct PACKED log_CSRV { @@ -475,6 +499,7 @@ struct PACKED log_ARSP { bool use; bool healthy; float health_prob; + float test_ratio; uint8_t primary; }; @@ -499,13 +524,6 @@ struct PACKED log_MAV_Stats { // uint8_t state_retry_max; }; -struct PACKED log_RPM { - LOG_PACKET_HEADER; - uint64_t time_us; - float rpm1; - float rpm2; -}; - struct PACKED log_Rally { LOG_PACKET_HEADER; uint64_t time_us; @@ -516,55 +534,10 @@ struct PACKED log_Rally { int16_t altitude; }; -struct PACKED log_Beacon { - LOG_PACKET_HEADER; - uint64_t time_us; - uint8_t health; - uint8_t count; - float dist0; - float dist1; - float dist2; - float dist3; - float posx; - float posy; - float posz; -}; - -// proximity sensor logging -struct PACKED log_Proximity { - LOG_PACKET_HEADER; - uint64_t time_us; - uint8_t instance; - uint8_t health; - float dist0; - float dist45; - float dist90; - float dist135; - float dist180; - float dist225; - float dist270; - float dist315; - float distup; - float closest_angle; - float closest_dist; -}; -struct PACKED log_Proximity_raw { - LOG_PACKET_HEADER; - uint64_t time_us; - uint8_t instance; - float raw_dist0; - float raw_dist45; - float raw_dist90; - float raw_dist135; - float raw_dist180; - float raw_dist225; - float raw_dist270; - float raw_dist315; -}; - struct PACKED log_Performance { LOG_PACKET_HEADER; uint64_t time_us; + uint16_t loop_rate; uint16_t num_long_running; uint16_t num_loops; uint32_t max_time; @@ -739,7 +712,7 @@ struct PACKED log_VER { #define PID_MULTS "F----------" // @LoggerMessage: ADSB -// @Description: Automatic Dependant Serveillance - Broadcast detected vehicle information +// @Description: Automatic Dependent Serveillance - Broadcast detected vehicle information // @Field: TimeUS: Time since system startup // @Field: ICAO_address: Transponder address // @Field: Lat: Vehicle latitude @@ -769,22 +742,10 @@ struct PACKED log_VER { // @Field: Offset: Offset from parameter // @Field: U: True if sensor is being used // @Field: H: True if sensor is healthy -// @Field: Hfp: Probability sensor has failed +// @Field: Hp: Probability sensor is healthy +// @Field: TR: innovation test ratio // @Field: Pri: True if sensor is the primary sensor -// @LoggerMessage: BCN -// @Description: Beacon information -// @Field: TimeUS: Time since system startup -// @Field: Health: True if beacon sensor is healthy -// @Field: Cnt: Number of beacons being used -// @Field: D0: Distance to first beacon -// @Field: D1: Distance to second beacon -// @Field: D2: Distance to third beacon -// @Field: D3: Distance to fourth beacon -// @Field: PosX: Calculated beacon position, x-axis -// @Field: PosY: Calculated beacon position, y-axis -// @Field: PosZ: Calculated beacon position, z-axis - // @LoggerMessage: CMD // @Description: Executed mission command information // @Field: TimeUS: Time since system startup @@ -939,20 +900,6 @@ struct PACKED log_VER { // @Field: ModeNum: alias for Mode // @Field: Rsn: reason for entering this mode; enumeration value -// @LoggerMessage: MON -// @Description: Main loop stuck data -// @Field: TimeUS: Time since system startup -// @Field: LDelay: Time main loop has been stuck for -// @Field: Task: Current scheduler task number -// @Field: IErr: Internal error mask; which internal errors have been detected -// @Field: IErrCnt: Internal error count; how many internal errors have been detected -// @Field: IErrLn: Line on which internal error ocurred -// @Field: MavMsg: Id of the last mavlink message processed -// @Field: MavCmd: Id of the last mavlink command processed -// @Field: SemLine: Line number of semaphore most recently taken -// @Field: SPICnt: Number of SPI transactions processed -// @Field: I2CCnt: Number of i2c transactions processed - // @LoggerMessage: MSG // @Description: Textual messages // @Field: TimeUS: Time since system startup @@ -978,6 +925,7 @@ struct PACKED log_VER { // @Field: TimeUS: Time since system startup // @Field: Name: parameter name // @Field: Value: parameter value +// @Field: Default: default parameter value for this board and config // @LoggerMessage: PIDR,PIDP,PIDY,PIDA,PIDS,PIDN,PIDE // @Description: Proportional/Integral/Derivative gain values for Roll/Pitch/Yaw/Altitude/Steering @@ -996,8 +944,9 @@ struct PACKED log_VER { // @LoggerMessage: PM // @Description: autopilot system performance and general data dumping ground // @Field: TimeUS: Time since system startup +// @Field: LR: Main loop rate // @Field: NLon: Number of long loops detected -// @Field: NLoop: Number of measurement loops for this message +// @Field: NL: Number of measurement loops for this message // @Field: MaxT: Maximum loop time // @Field: Mem: Free memory available // @Field: Load: System processor load @@ -1022,36 +971,6 @@ struct PACKED log_VER { // @Field: MVmin: MCU Voltage min // @Field: MVmax: MCU Voltage max -// @LoggerMessage: PRX -// @Description: Proximity Filtered sensor data -// @Field: TimeUS: Time since system startup -// @Field: Layer: Pitch(instance) at which the obstacle is at. 0th layer {-75,-45} degrees. 1st layer {-45,-15} degrees. 2nd layer {-15, 15} degrees. 3rd layer {15, 45} degrees. 4th layer {45,75} degrees. Minimum distance in each layer will be logged. -// @Field: He: True if proximity sensor is healthy -// @Field: D0: Nearest object in sector surrounding 0-degrees -// @Field: D45: Nearest object in sector surrounding 45-degrees -// @Field: D90: Nearest object in sector surrounding 90-degrees -// @Field: D135: Nearest object in sector surrounding 135-degrees -// @Field: D180: Nearest object in sector surrounding 180-degrees -// @Field: D225: Nearest object in sector surrounding 225-degrees -// @Field: D270: Nearest object in sector surrounding 270-degrees -// @Field: D315: Nearest object in sector surrounding 315-degrees -// @Field: DUp: Nearest object in upwards direction -// @Field: CAn: Angle to closest object -// @Field: CDis: Distance to closest object - -// @LoggerMessage: PRXR -// @Description: Proximity Raw sensor data -// @Field: TimeUS: Time since system startup -// @Field: Layer: Pitch(instance) at which the obstacle is at. 0th layer {-75,-45} degrees. 1st layer {-45,-15} degrees. 2nd layer {-15, 15} degrees. 3rd layer {15, 45} degrees. 4th layer {45,75} degrees. Minimum distance in each layer will be logged. -// @Field: D0: Nearest object in sector surrounding 0-degrees -// @Field: D45: Nearest object in sector surrounding 45-degrees -// @Field: D90: Nearest object in sector surrounding 90-degrees -// @Field: D135: Nearest object in sector surrounding 135-degrees -// @Field: D180: Nearest object in sector surrounding 180-degrees -// @Field: D225: Nearest object in sector surrounding 225-degrees -// @Field: D270: Nearest object in sector surrounding 270-degrees -// @Field: D315: Nearest object in sector surrounding 315-degrees - // @LoggerMessage: RAD // @Description: Telemetry radio statistics // @Field: TimeUS: Time since system startup @@ -1098,7 +1017,7 @@ struct PACKED log_VER { // @Field: C14: channel 14 input // @LoggerMessage: RCOU -// @Description: Servo channel output values +// @Description: Servo channel output values 1 to 14 // @Field: TimeUS: Time since system startup // @Field: C1: channel 1 output // @Field: C2: channel 2 output @@ -1115,6 +1034,32 @@ struct PACKED log_VER { // @Field: C13: channel 13 output // @Field: C14: channel 14 output +// @LoggerMessage: RCO2 +// @Description: Servo channel output values 15 to 18 +// @Field: TimeUS: Time since system startup +// @Field: C15: channel 15 output +// @Field: C16: channel 16 output +// @Field: C17: channel 17 output +// @Field: C18: channel 18 output + +// @LoggerMessage: RCO3 +// @Description: Servo channel output values 19 to 32 +// @Field: TimeUS: Time since system startup +// @Field: C19: channel 19 output +// @Field: C20: channel 20 output +// @Field: C21: channel 21 output +// @Field: C22: channel 22 output +// @Field: C23: channel 23 output +// @Field: C24: channel 24 output +// @Field: C25: channel 25 output +// @Field: C26: channel 26 output +// @Field: C27: channel 27 output +// @Field: C28: channel 28 output +// @Field: C29: channel 29 output +// @Field: C30: channel 30 output +// @Field: C31: channel 31 output +// @Field: C32: channel 32 output + // @LoggerMessage: RFND // @Description: Rangefinder sensor information // @Field: TimeUS: Time since system startup @@ -1123,12 +1068,6 @@ struct PACKED log_VER { // @Field: Stat: Sensor state // @Field: Orient: Sensor orientation -// @LoggerMessage: RPM -// @Description: Data from RPM sensors -// @Field: TimeUS: Time since system startup -// @Field: rpm1: First sensor's data -// @Field: rpm2: Second sensor's data - // @LoggerMessage: RSSI // @Description: Received Signal Strength Indicator for RC receiver // @Field: TimeUS: Time since system startup @@ -1171,6 +1110,7 @@ struct PACKED log_VER { // @Field: CHeight: Vehicle height above terrain // @Field: Pending: Number of tile requests outstanding // @Field: Loaded: Number of tiles in memory +// @Field: ROfs: terrain reference offset for arming altitude // @LoggerMessage: TSYN // @Description: Time synchronisation response information @@ -1257,16 +1197,16 @@ struct PACKED log_VER { // @Field: TimeUS: Time since system startup // @Field: Name: script name // @Field: Runtime: run time -// @Field: Total_mem: total memory useage +// @Field: Total_mem: total memory usage // @Field: Run_mem: run memory usage // @LoggerMessage: MOTB // @Description: Motor mixer information // @Field: TimeUS: Time since system startup // @Field: LiftMax: Maximum motor compensation gain -// @Field: BatVolt: Ratio betwen detected battery voltage and maximum battery voltage +// @Field: BatVolt: Ratio between detected battery voltage and maximum battery voltage // @Field: ThLimit: Throttle limit set due to battery current limitations -// @Field: ThrAvMx: Maximum average throttle that can be used to maintain attitude controll, derived from throttle mix params +// @Field: ThrAvMx: Maximum average throttle that can be used to maintain attitude control, derived from throttle mix params // @Field: FailFlags: bit 0 motor failed, bit 1 motors balanced, should be 2 in normal flight // messages for all boards @@ -1280,7 +1220,7 @@ struct PACKED log_VER { { LOG_MULT_MSG, sizeof(log_Format_Multiplier), \ "MULT", "Qbd", "TimeUS,Id,Mult", "s--","F--" }, \ { LOG_PARAMETER_MSG, sizeof(log_Parameter), \ - "PARM", "QNf", "TimeUS,Name,Value", "s--", "F--" }, \ + "PARM", "QNff", "TimeUS,Name,Value,Default", "s---", "F---" }, \ LOG_STRUCTURE_FROM_GPS \ { LOG_MESSAGE_MSG, sizeof(log_Message), \ "MSG", "QZ", "TimeUS,Message", "s-", "F-"}, \ @@ -1290,6 +1230,10 @@ LOG_STRUCTURE_FROM_GPS \ "RCI2", "QHHH", "TimeUS,C15,C16,OMask", "sYY-", "F---", true }, \ { LOG_RCOUT_MSG, sizeof(log_RCOUT), \ "RCOU", "QHHHHHHHHHHHHHH", "TimeUS,C1,C2,C3,C4,C5,C6,C7,C8,C9,C10,C11,C12,C13,C14", "sYYYYYYYYYYYYYY", "F--------------", true }, \ + { LOG_RCOUT2_MSG, sizeof(log_RCOUT2), \ + "RCO2", "QHHHH", "TimeUS,C15,C16,C17,C18", "sYYYY", "F----", true }, \ + { LOG_RCOUT3_MSG, sizeof(log_RCOUT), \ + "RCO3", "QHHHHHHHHHHHHHH", "TimeUS,C19,C20,C21,C22,C23,C24,C25,C26,C27,C28,C29,C30,C31,C32", "sYYYYYYYYYYYYYY", "F--------------", true }, \ { LOG_RSSI_MSG, sizeof(log_RSSI), \ "RSSI", "Qff", "TimeUS,RXRSSI,RXLQ", "s--", "F--", true }, \ LOG_STRUCTURE_FROM_BARO \ @@ -1303,7 +1247,7 @@ LOG_STRUCTURE_FROM_PRECLAND \ { LOG_RADIO_MSG, sizeof(log_Radio), \ "RAD", "QBBBBBHH", "TimeUS,RSSI,RemRSSI,TxBuf,Noise,RemNoise,RxErrors,Fixed", "s-------", "F-------", true }, \ LOG_STRUCTURE_FROM_CAMERA \ - { LOG_ARSP_MSG, sizeof(log_ARSP), "ARSP", "QBffcffBBfB", "TimeUS,I,Airspeed,DiffPress,Temp,RawPress,Offset,U,H,Hfp,Pri", "s#nPOPP----", "F-00B00----", true }, \ + { LOG_ARSP_MSG, sizeof(log_ARSP), "ARSP", "QBffcffBBffB", "TimeUS,I,Airspeed,DiffPress,Temp,RawPress,Offset,U,H,Hp,TR,Pri", "s#nPOPP-----", "F-00B00-----", true }, \ LOG_STRUCTURE_FROM_BATTMONITOR \ { LOG_MAG_MSG, sizeof(log_MAG), \ "MAG", "QBhhhhhhhhhBI", "TimeUS,I,MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOX,MOY,MOZ,Health,S", "s#GGGGGGGGG-s", "F-CCCCCCCCC-F", true }, \ @@ -1313,21 +1257,17 @@ LOG_STRUCTURE_FROM_CAMERA \ "RFND", "QBCBB", "TimeUS,Instance,Dist,Stat,Orient", "s#m--", "F-B--", true }, \ { LOG_MAV_STATS, sizeof(log_MAV_Stats), \ "DMS", "QIIIIBBBBBBBBB", "TimeUS,N,Dp,RT,RS,Fa,Fmn,Fmx,Pa,Pmn,Pmx,Sa,Smn,Smx", "s-------------", "F-------------" }, \ - { LOG_BEACON_MSG, sizeof(log_Beacon), \ - "BCN", "QBBfffffff", "TimeUS,Health,Cnt,D0,D1,D2,D3,PosX,PosY,PosZ", "s--mmmmmmm", "F--0000000", true }, \ - { LOG_PROXIMITY_MSG, sizeof(log_Proximity), \ - "PRX", "QBBfffffffffff", "TimeUS,Layer,He,D0,D45,D90,D135,D180,D225,D270,D315,DUp,CAn,CDis", "s#-mmmmmmmmmhm", "F--00000000000", true }, \ - { LOG_RAW_PROXIMITY_MSG, sizeof(log_Proximity_raw), \ - "PRXR", "QBffffffff", "TimeUS,Layer,D0,D45,D90,D135,D180,D225,D270,D315", "s#mmmmmmmm", "F-00000000", true }, \ + LOG_STRUCTURE_FROM_BEACON \ + LOG_STRUCTURE_FROM_PROXIMITY \ { LOG_PERFORMANCE_MSG, sizeof(log_Performance), \ - "PM", "QHHIIHHIIIIII", "TimeUS,NLon,NLoop,MaxT,Mem,Load,ErrL,IntE,ErrC,SPIC,I2CC,I2CI,Ex", "s---b%------s", "F---0A------F" }, \ + "PM", "QHHHIIHHIIIIII", "TimeUS,LR,NLon,NL,MaxT,Mem,Load,ErrL,IntE,ErrC,SPIC,I2CC,I2CI,Ex", "sz---b%------s", "F----0A------F" }, \ { LOG_SRTL_MSG, sizeof(log_SRTL), \ "SRTL", "QBHHBfff", "TimeUS,Active,NumPts,MaxPts,Action,N,E,D", "s----mmm", "F----000" }, \ LOG_STRUCTURE_FROM_AVOIDANCE \ { LOG_SIMSTATE_MSG, sizeof(log_AHRS), \ "SIM","QccCfLLffff","TimeUS,Roll,Pitch,Yaw,Alt,Lat,Lng,Q1,Q2,Q3,Q4", "sddhmDU????", "FBBB0GG????", true }, \ { LOG_TERRAIN_MSG, sizeof(log_TERRAIN), \ - "TERR","QBLLHffHH","TimeUS,Status,Lat,Lng,Spacing,TerrH,CHeight,Pending,Loaded", "s-DU-mm--", "F-GG-00--", true }, \ + "TERR","QBLLHffHHf","TimeUS,Status,Lat,Lng,Spacing,TerrH,CHeight,Pending,Loaded,ROfs", "s-DU-mm--m", "F-GG-00--0", true }, \ LOG_STRUCTURE_FROM_ESC_TELEM \ { LOG_CSRV_MSG, sizeof(log_CSRV), \ "CSRV","QBfffB","TimeUS,Id,Pos,Force,Speed,Pow", "s#---%", "F-0000", true }, \ @@ -1353,10 +1293,11 @@ LOG_STRUCTURE_FROM_NAVEKF2 \ LOG_STRUCTURE_FROM_NAVEKF3 \ LOG_STRUCTURE_FROM_NAVEKF \ LOG_STRUCTURE_FROM_AHRS \ +LOG_STRUCTURE_FROM_HAL_CHIBIOS \ +LOG_STRUCTURE_FROM_RPM \ +LOG_STRUCTURE_FROM_FENCE \ { LOG_DF_FILE_STATS, sizeof(log_DSF), \ "DSF", "QIHIIII", "TimeUS,Dp,Blk,Bytes,FMn,FMx,FAv", "s--b---", "F--0---" }, \ - { LOG_RPM_MSG, sizeof(log_RPM), \ - "RPM", "Qff", "TimeUS,rpm1,rpm2", "sqq", "F00" , true }, \ { LOG_RALLY_MSG, sizeof(log_Rally), \ "RALY", "QBBLLh", "TimeUS,Tot,Seq,Lat,Lng,Alt", "s--DUm", "F--GGB" }, \ { LOG_MAV_MSG, sizeof(log_MAV), \ @@ -1386,7 +1327,7 @@ LOG_STRUCTURE_FROM_VISUALODOM \ "STAK", "QBBHHN", "TimeUS,Id,Pri,Total,Free,Name", "s#----", "F-----", true }, \ { LOG_FILE_MSG, sizeof(log_File), \ "FILE", "NIBZ", "FileName,Offset,Length,Data", "----", "----" }, \ -LOG_STRUCTURE_FROM_AIS, \ +LOG_STRUCTURE_FROM_AIS \ { LOG_SCRIPTING_MSG, sizeof(log_Scripting), \ "SCR", "QNIii", "TimeUS,Name,Runtime,Total_mem,Run_mem", "s-sbb", "F-F--", true }, \ { LOG_VER_MSG, sizeof(log_VER), \ @@ -1419,6 +1360,7 @@ enum LogMessages : uint8_t { LOG_CSRV_MSG, LOG_IDS_FROM_ESC_TELEM, LOG_IDS_FROM_BATTMONITOR, + LOG_IDS_FROM_HAL_CHIBIOS, LOG_IDS_FROM_GPS, @@ -1432,7 +1374,7 @@ enum LogMessages : uint8_t { LOG_DSTL_MSG, LOG_MAG_MSG, LOG_ARSP_MSG, - LOG_RPM_MSG, + LOG_IDS_FROM_RPM, LOG_RFND_MSG, LOG_MAV_STATS, LOG_FORMAT_UNITS_MSG, @@ -1450,8 +1392,8 @@ enum LogMessages : uint8_t { LOG_IDS_FROM_VISUALODOM, LOG_IDS_FROM_AVOIDANCE, - LOG_BEACON_MSG, - LOG_PROXIMITY_MSG, + LOG_IDS_FROM_BEACON, + LOG_IDS_FROM_PROXIMITY, LOG_DF_FILE_STATS, LOG_SRTL_MSG, LOG_PERFORMANCE_MSG, @@ -1466,7 +1408,6 @@ enum LogMessages : uint8_t { LOG_PSCN_MSG, LOG_PSCE_MSG, LOG_PSCD_MSG, - LOG_RAW_PROXIMITY_MSG, LOG_IDS_FROM_PRECLAND, LOG_IDS_FROM_AIS, LOG_STAK_MSG, @@ -1475,6 +1416,9 @@ enum LogMessages : uint8_t { LOG_VIDEO_STABILISATION_MSG, LOG_MOTBATT_MSG, LOG_VER_MSG, + LOG_RCOUT2_MSG, + LOG_RCOUT3_MSG, + LOG_IDS_FROM_FENCE, _LOG_LAST_MSG_ }; diff --git a/libraries/AP_Logger/LoggerMessageWriter.cpp b/libraries/AP_Logger/LoggerMessageWriter.cpp index 6fdb504f920..a2de4a51b47 100644 --- a/libraries/AP_Logger/LoggerMessageWriter.cpp +++ b/libraries/AP_Logger/LoggerMessageWriter.cpp @@ -38,19 +38,23 @@ void LoggerMessageWriter_DFLogStart::reset() _fmt_done = false; _params_done = false; _writesysinfo.reset(); -#if HAL_MISSION_ENABLED +#if AP_MISSION_ENABLED _writeentiremission.reset(); #endif #if HAL_RALLY_ENABLED _writeallrallypoints.reset(); #endif +#if HAL_LOGGER_FENCE_ENABLED + _writeallpolyfence.reset(); +#endif stage = Stage::FORMATS; next_format_to_send = 0; _next_unit_to_send = 0; _next_multiplier_to_send = 0; _next_format_unit_to_send = 0; - ap = AP_Param::first(&token, &type); + param_default = AP::logger().quiet_nanf(); + ap = AP_Param::first(&token, &type, ¶m_default); } bool LoggerMessageWriter_DFLogStart::out_of_time_for_writing_messages() const @@ -66,11 +70,26 @@ bool LoggerMessageWriter_DFLogStart::out_of_time_for_writing_messages() const return LoggerMessageWriter::out_of_time_for_writing_messages(); } +/* + check if we've taken too long in a process() stage + return true if we should stop processing now as we are out of time + */ +bool LoggerMessageWriter_DFLogStart::check_process_limit(uint32_t start_us) +{ + const uint32_t limit_us = 1000U; + if (AP_HAL::micros() - start_us > limit_us) { + return true; + } + return false; +} + void LoggerMessageWriter_DFLogStart::process() { if (out_of_time_for_writing_messages()) { return; } + // allow any stage to run for max 1ms, to prevent a long loop on arming + const uint32_t start_us = AP_HAL::micros(); switch(stage) { case Stage::FORMATS: @@ -80,21 +99,29 @@ void LoggerMessageWriter_DFLogStart::process() return; // call me again! } next_format_to_send++; + if (check_process_limit(start_us)) { + return; // call me again! + } } _fmt_done = true; stage = Stage::PARMS; FALLTHROUGH; - case Stage::PARMS: + case Stage::PARMS: { while (ap) { - if (!_logger_backend->Write_Parameter(ap, token, type)) { + if (!_logger_backend->Write_Parameter(ap, token, type, param_default)) { return; } - ap = AP_Param::next_scalar(&token, &type); + param_default = AP::logger().quiet_nanf(); + ap = AP_Param::next_scalar(&token, &type, ¶m_default); + if (check_process_limit(start_us)) { + return; // call me again! + } } _params_done = true; stage = Stage::UNITS; + } FALLTHROUGH; case Stage::UNITS: @@ -103,6 +130,9 @@ void LoggerMessageWriter_DFLogStart::process() return; // call me again! } _next_unit_to_send++; + if (check_process_limit(start_us)) { + return; // call me again! + } } stage = Stage::MULTIPLIERS; FALLTHROUGH; @@ -113,6 +143,9 @@ void LoggerMessageWriter_DFLogStart::process() return; // call me again! } _next_multiplier_to_send++; + if (check_process_limit(start_us)) { + return; // call me again! + } } stage = Stage::UNITS; FALLTHROUGH; @@ -123,6 +156,9 @@ void LoggerMessageWriter_DFLogStart::process() return; // call me again! } _next_format_unit_to_send++; + if (check_process_limit(start_us)) { + return; // call me again! + } } stage = Stage::RUNNING_SUBWRITERS; FALLTHROUGH; @@ -134,7 +170,7 @@ void LoggerMessageWriter_DFLogStart::process() return; } } -#if HAL_MISSION_ENABLED +#if AP_MISSION_ENABLED if (!_writeentiremission.finished()) { _writeentiremission.process(); if (!_writeentiremission.finished()) { @@ -149,6 +185,14 @@ void LoggerMessageWriter_DFLogStart::process() return; } } +#endif +#if HAL_LOGGER_FENCE_ENABLED + if (!_writeallpolyfence.finished()) { + _writeallpolyfence.process(); + if (!_writeallpolyfence.finished()) { + return; + } + } #endif stage = Stage::VEHICLE_MESSAGES; FALLTHROUGH; @@ -173,7 +217,7 @@ void LoggerMessageWriter_DFLogStart::process() _finished = true; } -#if HAL_MISSION_ENABLED +#if AP_MISSION_ENABLED bool LoggerMessageWriter_DFLogStart::writeentiremission() { if (stage != Stage::DONE) { @@ -199,6 +243,19 @@ bool LoggerMessageWriter_DFLogStart::writeallrallypoints() } #endif +#if HAL_LOGGER_FENCE_ENABLED +bool LoggerMessageWriter_DFLogStart::writeallfence() +{ + if (stage != Stage::DONE) { + return false; + } + stage = Stage::RUNNING_SUBWRITERS; + _finished = false; + _writeallpolyfence.reset(); + return true; +} +#endif + void LoggerMessageWriter_WriteSysInfo::reset() { LoggerMessageWriter::reset(); @@ -253,7 +310,7 @@ void LoggerMessageWriter_WriteSysInfo::process() { FALLTHROUGH; } case Stage::SYSTEM_ID: - char sysid[40]; + char sysid[50]; if (hal.util->get_system_id(sysid)) { if (! _logger_backend->Write_Message(sysid)) { return; // call me again @@ -380,3 +437,61 @@ void LoggerMessageWriter_WriteEntireMission::reset() stage = Stage::WRITE_NEW_MISSION_MESSAGE; _mission_number_to_send = 0; } + +#if HAL_LOGGER_FENCE_ENABLED +#if APM_BUILD_TYPE(APM_BUILD_Replay) +// dummy methods to allow build with Replay +void LoggerMessageWriter_Write_Polyfence::process() { }; +void LoggerMessageWriter_Write_Polyfence::reset() { }; +#else +void LoggerMessageWriter_Write_Polyfence::process() { + + AC_Fence *fence = AP::fence(); + if (fence == nullptr) { + return; + } + + switch(stage) { + + case Stage::WRITE_NEW_FENCE_MESSAGE: + if (!_logger_backend->Write_Message("New fence")) { + return; // call me again + } + stage = Stage::WRITE_FENCE_ITEMS; + FALLTHROUGH; + + case Stage::WRITE_FENCE_ITEMS: { + while (_fence_number_to_send < fence->polyfence().num_stored_items()) { + if (out_of_time_for_writing_messages()) { + return; + } + + // upon failure to write the fence we will re-read from + // storage; this could be improved. + AC_PolyFenceItem fenceitem {}; + if (fence->polyfence().get_item(_fence_number_to_send, fenceitem)) { + if (!_logger_backend->Write_FencePoint(fence->polyfence().num_stored_items(), _fence_number_to_send, fenceitem)) { + return; // call me again + } + } + _fence_number_to_send++; + } + stage = Stage::DONE; + FALLTHROUGH; + } + + case Stage::DONE: + break; + } + + _finished = true; +} + +void LoggerMessageWriter_Write_Polyfence::reset() +{ + LoggerMessageWriter::reset(); + stage = Stage::WRITE_NEW_FENCE_MESSAGE; + _fence_number_to_send = 0; +} +#endif // !APM_BUILD_TYPE(APM_BUILD_Replay) +#endif // AP_FENCE_ENABLED diff --git a/libraries/AP_Logger/LoggerMessageWriter.h b/libraries/AP_Logger/LoggerMessageWriter.h index 977643f6472..f9b42350ce6 100644 --- a/libraries/AP_Logger/LoggerMessageWriter.h +++ b/libraries/AP_Logger/LoggerMessageWriter.h @@ -1,6 +1,7 @@ #pragma once #include "AP_Logger_Backend.h" +#include class LoggerMessageWriter { public: @@ -46,7 +47,7 @@ class LoggerMessageWriter_WriteEntireMission : public LoggerMessageWriter { void process() override; private: - enum Stage { + enum class Stage { WRITE_NEW_MISSION_MESSAGE = 0, WRITE_MISSION_ITEMS, DONE @@ -63,7 +64,7 @@ class LoggerMessageWriter_WriteAllRallyPoints : public LoggerMessageWriter { void process() override; private: - enum Stage { + enum class Stage { WRITE_NEW_RALLY_MESSAGE = 0, WRITE_ALL_RALLY_POINTS, DONE @@ -73,15 +74,37 @@ class LoggerMessageWriter_WriteAllRallyPoints : public LoggerMessageWriter { Stage stage = Stage::WRITE_NEW_RALLY_MESSAGE; }; +#if HAL_LOGGER_FENCE_ENABLED +class LoggerMessageWriter_Write_Polyfence : public LoggerMessageWriter { +public: + + void reset() override; + void process() override; + +private: + enum class Stage { + WRITE_NEW_FENCE_MESSAGE = 0, + WRITE_FENCE_ITEMS, + DONE + }; + + uint16_t _fence_number_to_send; + Stage stage; +}; +#endif // HAL_LOGGER_FENCE_ENABLED + class LoggerMessageWriter_DFLogStart : public LoggerMessageWriter { public: LoggerMessageWriter_DFLogStart() : _writesysinfo() -#if HAL_MISSION_ENABLED +#if AP_MISSION_ENABLED , _writeentiremission() #endif #if HAL_RALLY_ENABLED , _writeallrallypoints() +#endif +#if HAL_LOGGER_FENCE_ENABLED + , _writeallpolyfence() #endif { } @@ -89,11 +112,14 @@ class LoggerMessageWriter_DFLogStart : public LoggerMessageWriter { virtual void set_logger_backend(class AP_Logger_Backend *backend) override { LoggerMessageWriter::set_logger_backend(backend); _writesysinfo.set_logger_backend(backend); -#if HAL_MISSION_ENABLED +#if AP_MISSION_ENABLED _writeentiremission.set_logger_backend(backend); #endif #if HAL_RALLY_ENABLED _writeallrallypoints.set_logger_backend(backend); +#endif +#if HAL_LOGGER_FENCE_ENABLED + _writeallpolyfence.set_logger_backend(backend); #endif } @@ -106,16 +132,22 @@ class LoggerMessageWriter_DFLogStart : public LoggerMessageWriter { // reset some writers so we push stuff out to logs again. Will // only work if we are in state DONE! -#if HAL_MISSION_ENABLED +#if AP_MISSION_ENABLED bool writeentiremission(); #endif #if HAL_RALLY_ENABLED bool writeallrallypoints(); #endif +#if HAL_LOGGER_FENCE_ENABLED + bool writeallfence(); +#endif private: - enum Stage { + // check for using too much time + static bool check_process_limit(uint32_t start_us); + + enum class Stage { FORMATS = 0, UNITS, MULTIPLIERS, @@ -139,14 +171,18 @@ class LoggerMessageWriter_DFLogStart : public LoggerMessageWriter { AP_Param::ParamToken token; AP_Param *ap; + float param_default; enum ap_var_type type; LoggerMessageWriter_WriteSysInfo _writesysinfo; -#if HAL_MISSION_ENABLED +#if AP_MISSION_ENABLED LoggerMessageWriter_WriteEntireMission _writeentiremission; #endif #if HAL_RALLY_ENABLED LoggerMessageWriter_WriteAllRallyPoints _writeallrallypoints; #endif +#if HAL_LOGGER_FENCE_ENABLED + LoggerMessageWriter_Write_Polyfence _writeallpolyfence; +#endif }; diff --git a/libraries/AP_Logger/README.md b/libraries/AP_Logger/README.md index f1afd1ec9b7..dc42f962946 100644 --- a/libraries/AP_Logger/README.md +++ b/libraries/AP_Logger/README.md @@ -100,5 +100,6 @@ tl;dr a GCS shouldn't/mustn't infer any scaling from the unit name | 'E' | 1e-5 || | 'F' | 1e-6 || | 'G' | 1e-7 || +| 'I' | 1e-9 || | '!' | 3.6 | (milliampere \* hour => ampere \* second) and (km/h => m/s)| | '/' | 3600 | (ampere \* hour => ampere \* second)| diff --git a/libraries/AP_Logger/examples/AP_Logger_AllTypes/AP_Logger_AllTypes.cpp b/libraries/AP_Logger/examples/AP_Logger_AllTypes/AP_Logger_AllTypes.cpp index 2eb177a3932..efa9c4253aa 100644 --- a/libraries/AP_Logger/examples/AP_Logger_AllTypes/AP_Logger_AllTypes.cpp +++ b/libraries/AP_Logger/examples/AP_Logger_AllTypes/AP_Logger_AllTypes.cpp @@ -247,7 +247,7 @@ void AP_LoggerTest_AllTypes::setup(void) { hal.console->printf("Logger All Types 1.0\n"); - log_bitmask = (uint32_t)-1; + log_bitmask.set((uint32_t)-1); logger.Init(log_structure, ARRAY_SIZE(log_structure)); logger.set_vehicle_armed(true); logger.Write_Message("AP_Logger Test"); diff --git a/libraries/AP_Logger/examples/AP_Logger_test/AP_Logger_test.cpp b/libraries/AP_Logger/examples/AP_Logger_test/AP_Logger_test.cpp index 62ade3a338c..fcb6aeb95a5 100644 --- a/libraries/AP_Logger/examples/AP_Logger_test/AP_Logger_test.cpp +++ b/libraries/AP_Logger/examples/AP_Logger_test/AP_Logger_test.cpp @@ -52,7 +52,7 @@ void AP_LoggerTest::setup(void) { hal.console->printf("Logger Log Test 1.0\n"); - log_bitmask = (uint32_t)-1; + log_bitmask.set((uint32_t)-1); logger.Init(log_structure, ARRAY_SIZE(log_structure)); logger.set_vehicle_armed(true); logger.Write_Message("AP_Logger Test"); @@ -67,7 +67,7 @@ void AP_LoggerTest::setup(void) // Test hal.scheduler->delay(20); - // We start to write some info (sequentialy) starting from page 1 + // We start to write some info (sequentially) starting from page 1 // This is similar to what we will do... log_num = logger.find_last_log(); hal.console->printf("Using log number %u\n", log_num); diff --git a/libraries/AP_MSP/AP_MSP.cpp b/libraries/AP_MSP/AP_MSP.cpp index c58491b3cf9..971d446860f 100644 --- a/libraries/AP_MSP/AP_MSP.cpp +++ b/libraries/AP_MSP/AP_MSP.cpp @@ -21,6 +21,8 @@ #include "AP_MSP_Telem_DJI.h" #include "AP_MSP_Telem_DisplayPort.h" +#include + #include #include diff --git a/libraries/AP_MSP/AP_MSP_Telem_Backend.cpp b/libraries/AP_MSP/AP_MSP_Telem_Backend.cpp index cda9fc86ecf..943ad6318f0 100644 --- a/libraries/AP_MSP/AP_MSP_Telem_Backend.cpp +++ b/libraries/AP_MSP/AP_MSP_Telem_Backend.cpp @@ -17,10 +17,12 @@ #include #include #include +#include #include #include #include #include +#include #include #include #include @@ -525,7 +527,7 @@ MSPCommandResult AP_MSP_Telem_Backend::msp_process_sensor_command(uint16_t cmd_m void AP_MSP_Telem_Backend::msp_handle_opflow(const MSP::msp_opflow_data_message_t &pkt) { #if HAL_MSP_OPTICALFLOW_ENABLED - OpticalFlow *optflow = AP::opticalflow(); + AP_OpticalFlow *optflow = AP::opticalflow(); if (optflow == nullptr) { return; } @@ -560,14 +562,14 @@ void AP_MSP_Telem_Backend::msp_handle_compass(const MSP::msp_compass_data_messag void AP_MSP_Telem_Backend::msp_handle_baro(const MSP::msp_baro_data_message_t &pkt) { -#if HAL_MSP_BARO_ENABLED +#if AP_BARO_MSP_ENABLED AP::baro().handle_msp(pkt); #endif } void AP_MSP_Telem_Backend::msp_handle_airspeed(const MSP::msp_airspeed_data_message_t &pkt) { -#if HAL_MSP_AIRSPEED_ENABLED && AP_AIRSPEED_ENABLED +#if AP_AIRSPEED_MSP_ENABLED && AP_AIRSPEED_ENABLED auto *airspeed = AP::airspeed(); if (airspeed) { airspeed->handle_msp(pkt); @@ -575,6 +577,16 @@ void AP_MSP_Telem_Backend::msp_handle_airspeed(const MSP::msp_airspeed_data_mess #endif } +uint32_t AP_MSP_Telem_Backend::get_osd_flight_mode_bitmask(void) +{ + // Note: we only set the BOXARM bit (bit 0) which is the same for BF, INAV and DJI VTX + // When armed we simply return 1 (1 == 1 << 0) + if (hal.util->get_soft_armed()) { + return 1U; + } + return 0U; +} + MSPCommandResult AP_MSP_Telem_Backend::msp_process_out_api_version(sbuf_t *dst) { const struct { @@ -826,7 +838,7 @@ MSPCommandResult AP_MSP_Telem_Backend::msp_process_out_osd_config(sbuf_t *dst) if (msp->_osd_item_settings[i] != nullptr) { // ok supported if (msp->_osd_item_settings[i]->enabled) { // ok enabled // let's check if we need to hide this dynamically - if (!BIT_IS_SET(osd_hidden_items_bitmask, i)) { + if (!BIT_IS_SET_64(osd_hidden_items_bitmask, i)) { pos = MSP_OSD_POS(msp->_osd_item_settings[i]); } } @@ -1215,6 +1227,12 @@ void AP_MSP_Telem_Backend::msp_displayport_write_string(uint8_t col, uint8_t row msp_send_packet(MSP_DISPLAYPORT, MSP::MSP_V1, &packet, 4 + len, false); } + +void AP_MSP_Telem_Backend::msp_displayport_set_options(const uint8_t font_index, const uint8_t screen_resolution) +{ + const uint8_t subcmd[] = { msp_displayport_subcmd_e::MSP_DISPLAYPORT_SET_OPTIONS, font_index, screen_resolution }; + msp_send_packet(MSP_DISPLAYPORT, MSP::MSP_V1, subcmd, sizeof(subcmd), false); +} #endif //HAL_WITH_MSP_DISPLAYPORT bool AP_MSP_Telem_Backend::displaying_stats_screen() const { diff --git a/libraries/AP_MSP/AP_MSP_Telem_Backend.h b/libraries/AP_MSP/AP_MSP_Telem_Backend.h index a6e70a25d8e..8136ecdfd2a 100644 --- a/libraries/AP_MSP/AP_MSP_Telem_Backend.h +++ b/libraries/AP_MSP/AP_MSP_Telem_Backend.h @@ -88,6 +88,7 @@ friend AP_MSP; virtual void msp_displayport_clear_screen(); virtual void msp_displayport_draw_screen(); virtual void msp_displayport_write_string(uint8_t col, uint8_t row, bool blink, const char *string); + virtual void msp_displayport_set_options(const uint8_t font_index, const uint8_t screen_resolution); #endif protected: enum msp_packet_type : uint8_t { @@ -183,11 +184,9 @@ friend AP_MSP; void msp_handle_airspeed(const MSP::msp_airspeed_data_message_t &pkt); // implementation specific helpers + // we only set arming status // custom masks are needed for vendor specific settings - virtual uint32_t get_osd_flight_mode_bitmask(void) - { - return 0; - } + virtual uint32_t get_osd_flight_mode_bitmask(void); virtual bool is_scheduler_enabled() const = 0; // only osd backends should allow a push type telemetry virtual bool use_msp_thread() const {return true;}; // is this backend hanlded by the MSP thread? diff --git a/libraries/AP_MSP/AP_MSP_Telem_DJI.cpp b/libraries/AP_MSP/AP_MSP_Telem_DJI.cpp index 4a23553e8ba..fcb3108c716 100644 --- a/libraries/AP_MSP/AP_MSP_Telem_DJI.cpp +++ b/libraries/AP_MSP/AP_MSP_Telem_DJI.cpp @@ -17,6 +17,7 @@ #include #include #include +#include #include "AP_MSP.h" #include "AP_MSP_Telem_DJI.h" @@ -68,14 +69,9 @@ void AP_MSP_Telem_DJI::hide_osd_items(void) uint32_t AP_MSP_Telem_DJI::get_osd_flight_mode_bitmask(void) { - uint32_t mode_mask = 0; + uint32_t mode_mask = AP_MSP_Telem_Backend::get_osd_flight_mode_bitmask(); const AP_Notify& notify = AP::notify(); - // set arming status - if (notify.flags.armed) { - BIT_SET(mode_mask, DJI_FLAG_ARM); - } - // check failsafe if (notify.flags.failsafe_battery || notify.flags.failsafe_gcs || notify.flags.failsafe_radio || notify.flags.ekf_bad ) { BIT_SET(mode_mask, DJI_FLAG_FS); diff --git a/libraries/AP_MSP/Tools/pymsp.py b/libraries/AP_MSP/Tools/pymsp.py index 717ff707c7a..c52c9929bd2 100755 --- a/libraries/AP_MSP/Tools/pymsp.py +++ b/libraries/AP_MSP/Tools/pymsp.py @@ -1,511 +1,511 @@ -#!/usr/bin/env python -# -*- coding: utf-8 -*- - -""" - author: Alex Apostoli - based on https://github.com/hkm95/python-multiwii - which is under GPLv3 -""" - -import struct -import time -import sys -import re - -class MSPItem: - def __init__(self, name, fmt, fields): - self.name = name - self.format = fmt - self.fields = fields - if not isinstance(self.format, list): - self.format = [self.format] - self.fields = [self.fields] - self.values = {} - - def parse(self, msp, dataSize): - '''parse data''' - ofs = msp.p - for i in range(len(self.format)): - fmt = self.format[i] - fields = self.fields[i].split(',') - if fmt[0] == '{': - # we have a repeat count from an earlier variable - right = fmt.find('}') - vname = fmt[1:right] - count = self.values[vname] - fmt = "%u%s" % (count, fmt[right+1:]) - if fmt[0].isdigit(): - repeat = int(re.search(r'\d+', fmt).group()) - else: - repeat = None - fmt = "<" + fmt - fmt_size = struct.calcsize(fmt) - if dataSize < fmt_size: - raise Exception("Format %s needs %u bytes got %u for %s" % (self.name, fmt_size, dataSize, fmt)) - values = list(struct.unpack(fmt, msp.inBuf[ofs:ofs+fmt_size])) - if repeat is not None: - for i in range(len(fields)): - self.values[fields[i]] = [] - for j in range(repeat): - self.values[fields[i]].append(values[j*len(fields)]) - else: - for i in range(len(fields)): - self.values[fields[i]] = values[i] - dataSize -= fmt_size - ofs += fmt_size - msp.by_name[self.name] = self - #print("Got %s" % self.name) - -class PyMSP: - """ Multiwii Serial Protocol """ - OSD_RSSI_VALUE = 0 - OSD_MAIN_BATT_VOLTAGE = 1 - OSD_CROSSHAIRS = 2 - OSD_ARTIFICIAL_HORIZON = 3 - OSD_HORIZON_SIDEBARS = 4 - OSD_ITEM_TIMER_1 = 5 - OSD_ITEM_TIMER_2 = 6 - OSD_FLYMODE = 7 - OSD_CRAFT_NAME = 8 - OSD_THROTTLE_POS = 9 - OSD_VTX_CHANNEL = 10 - OSD_CURRENT_DRAW = 11 - OSD_MAH_DRAWN = 12 - OSD_GPS_SPEED = 13 - OSD_GPS_SATS = 14 - OSD_ALTITUDE = 15 - OSD_ROLL_PIDS = 16 - OSD_PITCH_PIDS = 17 - OSD_YAW_PIDS = 18 - OSD_POWER = 19 - OSD_PIDRATE_PROFILE = 20 - OSD_WARNINGS = 21 - OSD_AVG_CELL_VOLTAGE = 22 - OSD_GPS_LON = 23 - OSD_GPS_LAT = 24 - OSD_DEBUG = 25 - OSD_PITCH_ANGLE = 26 - OSD_ROLL_ANGLE = 27 - OSD_MAIN_BATT_USAGE = 28 - OSD_DISARMED = 29 - OSD_HOME_DIR = 30 - OSD_HOME_DIST = 31 - OSD_NUMERICAL_HEADING = 32 - OSD_NUMERICAL_VARIO = 33 - OSD_COMPASS_BAR = 34 - OSD_ESC_TMP = 35 - OSD_ESC_RPM = 36 - OSD_REMAINING_TIME_ESTIMATE = 37 - OSD_RTC_DATETIME = 38 - OSD_ADJUSTMENT_RANGE = 39 - OSD_CORE_TEMPERATURE = 40 - OSD_ANTI_GRAVITY = 41 - OSD_G_FORCE = 42 - OSD_MOTOR_DIAG = 43 - OSD_LOG_STATUS = 44 - OSD_FLIP_ARROW = 45 - OSD_LINK_QUALITY = 46 - OSD_FLIGHT_DIST = 47 - OSD_STICK_OVERLAY_LEFT = 48 - OSD_STICK_OVERLAY_RIGHT = 49 - OSD_DISPLAY_NAME = 50 - OSD_ESC_RPM_FREQ = 51 - OSD_RATE_PROFILE_NAME = 52 - OSD_PID_PROFILE_NAME = 53 - OSD_PROFILE_NAME = 54 - OSD_RSSI_DBM_VALUE = 55 - OSD_RC_CHANNELS = 56 - OSD_CAMERA_FRAME = 57 - - MSP_NAME =10 - MSP_OSD_CONFIG =84 - MSP_IDENT =100 - MSP_STATUS =101 - MSP_RAW_IMU =102 - MSP_SERVO =103 - MSP_MOTOR =104 - MSP_RC =105 - MSP_RAW_GPS =106 - MSP_COMP_GPS =107 - MSP_ATTITUDE =108 - MSP_ALTITUDE =109 - MSP_ANALOG =110 - MSP_RC_TUNING =111 - MSP_PID =112 - MSP_BOX =113 - MSP_MISC =114 - MSP_MOTOR_PINS =115 - MSP_BOXNAMES =116 - MSP_PIDNAMES =117 - MSP_WP =118 - MSP_BOXIDS =119 - MSP_SERVO_CONF =120 - MSP_NAV_STATUS =121 - MSP_NAV_CONFIG =122 - MSP_MOTOR_3D_CONFIG =124 - MSP_RC_DEADBAND =125 - MSP_SENSOR_ALIGNMENT =126 - MSP_LED_STRIP_MODECOLOR =127 - MSP_VOLTAGE_METERS =128 - MSP_CURRENT_METERS =129 - MSP_BATTERY_STATE =130 - MSP_MOTOR_CONFIG =131 - MSP_GPS_CONFIG =132 - MSP_COMPASS_CONFIG =133 - MSP_ESC_SENSOR_DATA =134 - MSP_GPS_RESCUE =135 - MSP_GPS_RESCUE_PIDS =136 - MSP_VTXTABLE_BAND =137 - MSP_VTXTABLE_POWERLEVEL =138 - MSP_MOTOR_TELEMETRY =139 - - MSP_SET_RAW_RC =200 - MSP_SET_RAW_GPS =201 - MSP_SET_PID =202 - MSP_SET_BOX =203 - MSP_SET_RC_TUNING =204 - MSP_ACC_CALIBRATION =205 - MSP_MAG_CALIBRATION =206 - MSP_SET_MISC =207 - MSP_RESET_CONF =208 - MSP_SET_WP =209 - MSP_SELECT_SETTING =210 - MSP_SET_HEAD =211 - MSP_SET_SERVO_CONF =212 - MSP_SET_MOTOR =214 - MSP_SET_NAV_CONFIG =215 - MSP_SET_MOTOR_3D_CONFIG =217 - MSP_SET_RC_DEADBAND =218 - MSP_SET_RESET_CURR_PID =219 - MSP_SET_SENSOR_ALIGNMENT =220 - MSP_SET_LED_STRIP_MODECOLOR=221 - MSP_SET_MOTOR_CONFIG =222 - MSP_SET_GPS_CONFIG =223 - MSP_SET_COMPASS_CONFIG =224 - MSP_SET_GPS_RESCUE =225 - MSP_SET_GPS_RESCUE_PIDS =226 - MSP_SET_VTXTABLE_BAND =227 - MSP_SET_VTXTABLE_POWERLEVEL=228 - - - MSP_BIND =241 - MSP_RTC =247 - - MSP_EEPROM_WRITE =250 - - MSP_DEBUGMSG =253 - MSP_DEBUG =254 - - IDLE = 0 - HEADER_START = 1 - HEADER_M = 2 - HEADER_ARROW = 3 - HEADER_SIZE = 4 - HEADER_CMD = 5 - HEADER_ERR = 6 - - PIDITEMS = 10 - - MESSAGES = { - MSP_RAW_GPS: MSPItem('RAW_GPS', "BBiihH", "fix,numSat,Lat,Lon,Alt,Speed"), - MSP_IDENT: MSPItem('IDENT', "BBBI", "version,multiType,MSPVersion,multiCapability"), - MSP_STATUS: MSPItem('STATUS', "HHHI", "cycleTime,i2cError,present,mode"), - MSP_RAW_IMU: MSPItem('RAW_IMU', "hhhhhhhhh", "AccX,AccY,AccZ,GyrX,GyrY,GyrZ,MagX,MagY,MagZ"), - MSP_SERVO: MSPItem('SERVO', "8h", "servo"), - MSP_MOTOR: MSPItem('MOTOR', "8h", "motor"), - MSP_RC: MSPItem('RC', "8h", "rc"), - MSP_COMP_GPS: MSPItem('COMP_GPS', "HhB", "distanceToHome,directionToHome,update"), - MSP_ATTITUDE: MSPItem('ATTITUDE', "hhh", "roll,pitch,yaw"), - MSP_ALTITUDE: MSPItem('ALTITUDE', "ih", "alt,vspeed"), - MSP_RC_TUNING: MSPItem('RC_TUNING', "BBBBBBB", "RC_Rate,RC_Expo,RollPitchRate,YawRate,DynThrPID,ThrottleMID,ThrottleExpo"), - MSP_BATTERY_STATE: MSPItem('BATTERY_STATE', "BHBHhBh", "cellCount,capacity,voltage,mah,current,state,voltage_cv"), - MSP_RTC: MSPItem('RTC', "HBBBBBH", "year,mon,mday,hour,min,sec,millis"), - MSP_OSD_CONFIG: MSPItem("OSD_CONFIG", - ["BBBBHBBH", - "{osd_item_count}H", - "B", "{stats_item_count}H", - "B", "{timer_count}H", - "HBIBBB"], - ["feature,video_system,units,rssi_alarm,cap_alarm,unused1,osd_item_count,alt_alarm", - "osd_items", - "stats_item_count", "stats_items", - "timer_count", "timer_items", - "legacy_warnings,warnings_count,enabled_warnings,profiles,selected_profile,osd_overlay"]), - MSP_PID: MSPItem("PID", "8PID", "P,I,D"), - MSP_MISC: MSPItem("MISC", "HHHHHII","intPowerTrigger,conf1,conf2,conf3,conf4,conf5,conf6"), - MSP_MOTOR_PINS: MSPItem("MOTOR_PINS", "8H","MP"), - MSP_ANALOG: MSPItem("ANALOG", "BHHHH", "dV,consumed_mah,rssi,current,volt"), - MSP_STATUS: MSPItem("STATUS", "HHHIBHHBBIB", "task_delta,i2c_err_count,sensor_status,mode_flags,nop_1,system_load,gyro_time,nop_2,nop_3,armed,extra"), - MSP_ESC_SENSOR_DATA: MSPItem('ESC', "BH", "temp1,rpm1"), - } - - def __init__(self): - - self.msp_name = { - 'name':None - } - self.msp_osd_config = {} - - self.inBuf = bytearray([0] * 255) - self.p = 0 - self.c_state = self.IDLE - self.err_rcvd = False - self.checksum = 0 - self.cmd = 0 - self.offset=0 - self.dataSize=0 - self.servo = [] - self.mot = [] - self.RCChan = [] - self.byteP = [] - self.byteI = [] - self.byteD = [] - self.confINF = [] - self.byteMP = [] - - self.confP = [] - self.confI = [] - self.confD = [] - - # parsed messages, indexed by name - self.by_name = {} - - def get(self, fieldname): - '''get a field from a parsed message by Message.Field name''' - a = fieldname.split('.') - msgName = a[0] - fieldName = a[1] - if not msgName in self.by_name: - # default to zero for simplicty of display - return 0 - msg = self.by_name[msgName] - if not fieldName in msg.values: - raise Exception("Unknown field %s" % fieldName) - return msg.values[fieldName] - - def read32(self): - '''signed 32 bit number''' - value, = struct.unpack(" 0: - if (payloadinbytes == False): - for c in struct.pack('<%dh' % ((pl_size) / 2), *payload): - checksum ^= (ord(c) & 0xFF) - else: - for c in struct.pack('<%Bh' % ((pl_size) / 2), *payload): - checksum ^= (ord(c) & 0xFF) - bf = bf + payload - bf.append(checksum) - return bf - - def evaluateCommand(self, cmd, dataSize): - if cmd in self.MESSAGES: - # most messages are parsed from the MESSAGES list - self.MESSAGES[cmd].parse(self, dataSize) - elif cmd == self.MSP_NAME: - s = bytearray() - for i in range(0,dataSize,1): - b = self.read8() - if b == 0: - break - s.append(b) - self.msp_name['name'] = s.decode("utf-8") - - elif cmd == self.MSP_ACC_CALIBRATION: - x = None - elif cmd == self.MSP_MAG_CALIBRATION: - x = None - elif cmd == self.MSP_BOX: - x = None - elif cmd == self.MSP_BOXNAMES: - x = None - elif cmd == self.MSP_PIDNAMES: - x = None - elif cmd == self.MSP_SERVO_CONF: - x = None - elif cmd == self.MSP_DEBUGMSG: - x = None - elif cmd == self.MSP_DEBUG: - x = None - else: - print("Unhandled command ", cmd, dataSize) - - def parseMspData(self, buf): - for c in buf: - self.parseMspByte(c) - - def parseMspByte(self, c): - if sys.version_info.major >= 3: - cc = chr(c) - ci = c - else: - cc = c - ci = ord(c) - if self.c_state == self.IDLE: - if cc == '$': - self.c_state = self.HEADER_START - else: - self.c_state = self.IDLE - elif self.c_state == self.HEADER_START: - if cc == 'M': - self.c_state = self.HEADER_M - else: - self.c_state = self.IDLE - elif self.c_state == self.HEADER_M: - if cc == '>': - self.c_state = self.HEADER_ARROW - elif cc == '!': - self.c_state = self.HEADER_ERR - else: - self.c_state = self.IDLE - - elif self.c_state == self.HEADER_ARROW or self.c_state == self.HEADER_ERR: - self.err_rcvd = (self.c_state == self.HEADER_ERR) - #print (struct.unpack('= self.dataSize: - # compare calculated and transferred checksum - if ((self.checksum&0xFF) == ci): - if self.err_rcvd: - print("Vehicle didn't understand the request type") - else: - self.evaluateCommand(self.cmd, self.dataSize) - else: - print('"invalid checksum for command "+((int)(cmd&0xFF))+": "+(checksum&0xFF)+" expected, got "+(int)(c&0xFF))') - - self.c_state = self.IDLE - - def setPID(self): - self.sendRequestMSP(self.requestMSP(self.MSP_PID)) - self.receiveData(self.MSP_PID) - time.sleep(0.04) - payload = [] - for i in range(0, self.PIDITEMS, 1): - self.byteP[i] = int((round(self.confP[i] * 10))) - self.byteI[i] = int((round(self.confI[i] * 1000))) - self.byteD[i] = int((round(self.confD[i]))) - - - # POS - 4 POSR - 5 NAVR - 6 - - self.byteP[4] = int((round(self.confP[4] * 100.0))) - self.byteI[4] = int((round(self.confI[4] * 100.0))) - self.byteP[5] = int((round(self.confP[5] * 10.0))) - self.byteI[5] = int((round(self.confI[5] * 100.0))) - self.byteD[5] = int((round(self.confD[5] * 10000.0))) / 10 - - self.byteP[6] = int((round(self.confP[6] * 10.0))) - self.byteI[6] = int((round(self.confI[6] * 100.0))) - self.byteD[6] = int((round(self.confD[6] * 10000.0))) / 10 - - for i in range(0, self.PIDITEMS, 1): - payload.append(self.byteP[i]) - payload.append(self.byteI[i]) - payload.append(self.byteD[i]) - self.sendRequestMSP(self.requestMSP(self.MSP_SET_PID, payload, True), True) - - - def arm(self): - timer = 0 - start = time.time() - while timer < 0.5: - data = [1500,1500,2000,1000] - self.sendRequestMSP(self.requestMSP(self.MSP_SET_RAW_RC,data)) - time.sleep(0.05) - timer = timer + (time.time() - start) - start = time.time() - - def disarm(self): - timer = 0 - start = time.time() - while timer < 0.5: - data = [1500,1500,1000,1000] - self.sendRequestMSP(self.requestMSP(self.MSP_SET_RAW_RC,data)) - time.sleep(0.05) - timer = timer + (time.time() - start) - start = time.time() - - - def receiveIMU(self, duration): - timer = 0 - start = time.time() - while timer < duration: - self.sendRequestMSP(self.requestMSP(self.MSP_RAW_IMU)) - self.receiveData(self.MSP_RAW_IMU) - if self.msp_raw_imu['accx'] > 32768: # 2^15 ...to check if negative number is received - self.msp_raw_imu['accx'] -= 65536 # 2^16 ...converting into 2's complement - if self.msp_raw_imu['accy'] > 32768: - self.msp_raw_imu['accy'] -= 65536 - if self.msp_raw_imu['accz'] > 32768: - self.msp_raw_imu['accz'] -= 65536 - if self.msp_raw_imu['gyrx'] > 32768: - self.msp_raw_imu['gyrx'] -= 65536 - if self.msp_raw_imu['gyry'] > 32768: - self.msp_raw_imu['gyry'] -= 65536 - if self.msp_raw_imu['gyrz'] > 32768: - self.msp_raw_imu['gyrz'] -= 65536 - print("size: %d, accx: %f, accy: %f, accz: %f, gyrx: %f, gyry: %f, gyrz: %f " %(self.msp_raw_imu['size'], self.msp_raw_imu['accx'], self.msp_raw_imu['accy'], self.msp_raw_imu['accz'], self.msp_raw_imu['gyrx'], self.msp_raw_imu['gyry'], self.msp_raw_imu['gyrz'])) - time.sleep(0.04) - timer = timer + (time.time() - start) - start = time.time() - - - def calibrateIMU(self): - self.sendRequestMSP(self.requestMSP(self.MSP_ACC_CALIBRATION)) - time.sleep(0.01) +#!/usr/bin/env python +# -*- coding: utf-8 -*- + +""" + author: Alex Apostoli + based on https://github.com/hkm95/python-multiwii + which is under GPLv3 +""" + +import struct +import time +import sys +import re + +class MSPItem: + def __init__(self, name, fmt, fields): + self.name = name + self.format = fmt + self.fields = fields + if not isinstance(self.format, list): + self.format = [self.format] + self.fields = [self.fields] + self.values = {} + + def parse(self, msp, dataSize): + '''parse data''' + ofs = msp.p + for i in range(len(self.format)): + fmt = self.format[i] + fields = self.fields[i].split(',') + if fmt[0] == '{': + # we have a repeat count from an earlier variable + right = fmt.find('}') + vname = fmt[1:right] + count = self.values[vname] + fmt = "%u%s" % (count, fmt[right+1:]) + if fmt[0].isdigit(): + repeat = int(re.search(r'\d+', fmt).group()) + else: + repeat = None + fmt = "<" + fmt + fmt_size = struct.calcsize(fmt) + if dataSize < fmt_size: + raise Exception("Format %s needs %u bytes got %u for %s" % (self.name, fmt_size, dataSize, fmt)) + values = list(struct.unpack(fmt, msp.inBuf[ofs:ofs+fmt_size])) + if repeat is not None: + for i in range(len(fields)): + self.values[fields[i]] = [] + for j in range(repeat): + self.values[fields[i]].append(values[j*len(fields)]) + else: + for i in range(len(fields)): + self.values[fields[i]] = values[i] + dataSize -= fmt_size + ofs += fmt_size + msp.by_name[self.name] = self + #print("Got %s" % self.name) + +class PyMSP: + """ Multiwii Serial Protocol """ + OSD_RSSI_VALUE = 0 + OSD_MAIN_BATT_VOLTAGE = 1 + OSD_CROSSHAIRS = 2 + OSD_ARTIFICIAL_HORIZON = 3 + OSD_HORIZON_SIDEBARS = 4 + OSD_ITEM_TIMER_1 = 5 + OSD_ITEM_TIMER_2 = 6 + OSD_FLYMODE = 7 + OSD_CRAFT_NAME = 8 + OSD_THROTTLE_POS = 9 + OSD_VTX_CHANNEL = 10 + OSD_CURRENT_DRAW = 11 + OSD_MAH_DRAWN = 12 + OSD_GPS_SPEED = 13 + OSD_GPS_SATS = 14 + OSD_ALTITUDE = 15 + OSD_ROLL_PIDS = 16 + OSD_PITCH_PIDS = 17 + OSD_YAW_PIDS = 18 + OSD_POWER = 19 + OSD_PIDRATE_PROFILE = 20 + OSD_WARNINGS = 21 + OSD_AVG_CELL_VOLTAGE = 22 + OSD_GPS_LON = 23 + OSD_GPS_LAT = 24 + OSD_DEBUG = 25 + OSD_PITCH_ANGLE = 26 + OSD_ROLL_ANGLE = 27 + OSD_MAIN_BATT_USAGE = 28 + OSD_DISARMED = 29 + OSD_HOME_DIR = 30 + OSD_HOME_DIST = 31 + OSD_NUMERICAL_HEADING = 32 + OSD_NUMERICAL_VARIO = 33 + OSD_COMPASS_BAR = 34 + OSD_ESC_TMP = 35 + OSD_ESC_RPM = 36 + OSD_REMAINING_TIME_ESTIMATE = 37 + OSD_RTC_DATETIME = 38 + OSD_ADJUSTMENT_RANGE = 39 + OSD_CORE_TEMPERATURE = 40 + OSD_ANTI_GRAVITY = 41 + OSD_G_FORCE = 42 + OSD_MOTOR_DIAG = 43 + OSD_LOG_STATUS = 44 + OSD_FLIP_ARROW = 45 + OSD_LINK_QUALITY = 46 + OSD_FLIGHT_DIST = 47 + OSD_STICK_OVERLAY_LEFT = 48 + OSD_STICK_OVERLAY_RIGHT = 49 + OSD_DISPLAY_NAME = 50 + OSD_ESC_RPM_FREQ = 51 + OSD_RATE_PROFILE_NAME = 52 + OSD_PID_PROFILE_NAME = 53 + OSD_PROFILE_NAME = 54 + OSD_RSSI_DBM_VALUE = 55 + OSD_RC_CHANNELS = 56 + OSD_CAMERA_FRAME = 57 + + MSP_NAME =10 + MSP_OSD_CONFIG =84 + MSP_IDENT =100 + MSP_STATUS =101 + MSP_RAW_IMU =102 + MSP_SERVO =103 + MSP_MOTOR =104 + MSP_RC =105 + MSP_RAW_GPS =106 + MSP_COMP_GPS =107 + MSP_ATTITUDE =108 + MSP_ALTITUDE =109 + MSP_ANALOG =110 + MSP_RC_TUNING =111 + MSP_PID =112 + MSP_BOX =113 + MSP_MISC =114 + MSP_MOTOR_PINS =115 + MSP_BOXNAMES =116 + MSP_PIDNAMES =117 + MSP_WP =118 + MSP_BOXIDS =119 + MSP_SERVO_CONF =120 + MSP_NAV_STATUS =121 + MSP_NAV_CONFIG =122 + MSP_MOTOR_3D_CONFIG =124 + MSP_RC_DEADBAND =125 + MSP_SENSOR_ALIGNMENT =126 + MSP_LED_STRIP_MODECOLOR =127 + MSP_VOLTAGE_METERS =128 + MSP_CURRENT_METERS =129 + MSP_BATTERY_STATE =130 + MSP_MOTOR_CONFIG =131 + MSP_GPS_CONFIG =132 + MSP_COMPASS_CONFIG =133 + MSP_ESC_SENSOR_DATA =134 + MSP_GPS_RESCUE =135 + MSP_GPS_RESCUE_PIDS =136 + MSP_VTXTABLE_BAND =137 + MSP_VTXTABLE_POWERLEVEL =138 + MSP_MOTOR_TELEMETRY =139 + + MSP_SET_RAW_RC =200 + MSP_SET_RAW_GPS =201 + MSP_SET_PID =202 + MSP_SET_BOX =203 + MSP_SET_RC_TUNING =204 + MSP_ACC_CALIBRATION =205 + MSP_MAG_CALIBRATION =206 + MSP_SET_MISC =207 + MSP_RESET_CONF =208 + MSP_SET_WP =209 + MSP_SELECT_SETTING =210 + MSP_SET_HEAD =211 + MSP_SET_SERVO_CONF =212 + MSP_SET_MOTOR =214 + MSP_SET_NAV_CONFIG =215 + MSP_SET_MOTOR_3D_CONFIG =217 + MSP_SET_RC_DEADBAND =218 + MSP_SET_RESET_CURR_PID =219 + MSP_SET_SENSOR_ALIGNMENT =220 + MSP_SET_LED_STRIP_MODECOLOR=221 + MSP_SET_MOTOR_CONFIG =222 + MSP_SET_GPS_CONFIG =223 + MSP_SET_COMPASS_CONFIG =224 + MSP_SET_GPS_RESCUE =225 + MSP_SET_GPS_RESCUE_PIDS =226 + MSP_SET_VTXTABLE_BAND =227 + MSP_SET_VTXTABLE_POWERLEVEL=228 + + + MSP_BIND =241 + MSP_RTC =247 + + MSP_EEPROM_WRITE =250 + + MSP_DEBUGMSG =253 + MSP_DEBUG =254 + + IDLE = 0 + HEADER_START = 1 + HEADER_M = 2 + HEADER_ARROW = 3 + HEADER_SIZE = 4 + HEADER_CMD = 5 + HEADER_ERR = 6 + + PIDITEMS = 10 + + MESSAGES = { + MSP_RAW_GPS: MSPItem('RAW_GPS', "BBiihH", "fix,numSat,Lat,Lon,Alt,Speed"), + MSP_IDENT: MSPItem('IDENT', "BBBI", "version,multiType,MSPVersion,multiCapability"), + MSP_STATUS: MSPItem('STATUS', "HHHI", "cycleTime,i2cError,present,mode"), + MSP_RAW_IMU: MSPItem('RAW_IMU', "hhhhhhhhh", "AccX,AccY,AccZ,GyrX,GyrY,GyrZ,MagX,MagY,MagZ"), + MSP_SERVO: MSPItem('SERVO', "8h", "servo"), + MSP_MOTOR: MSPItem('MOTOR', "8h", "motor"), + MSP_RC: MSPItem('RC', "8h", "rc"), + MSP_COMP_GPS: MSPItem('COMP_GPS', "HhB", "distanceToHome,directionToHome,update"), + MSP_ATTITUDE: MSPItem('ATTITUDE', "hhh", "roll,pitch,yaw"), + MSP_ALTITUDE: MSPItem('ALTITUDE', "ih", "alt,vspeed"), + MSP_RC_TUNING: MSPItem('RC_TUNING', "BBBBBBB", "RC_Rate,RC_Expo,RollPitchRate,YawRate,DynThrPID,ThrottleMID,ThrottleExpo"), + MSP_BATTERY_STATE: MSPItem('BATTERY_STATE', "BHBHhBh", "cellCount,capacity,voltage,mah,current,state,voltage_cv"), + MSP_RTC: MSPItem('RTC', "HBBBBBH", "year,mon,mday,hour,min,sec,millis"), + MSP_OSD_CONFIG: MSPItem("OSD_CONFIG", + ["BBBBHBBH", + "{osd_item_count}H", + "B", "{stats_item_count}H", + "B", "{timer_count}H", + "HBIBBB"], + ["feature,video_system,units,rssi_alarm,cap_alarm,unused1,osd_item_count,alt_alarm", + "osd_items", + "stats_item_count", "stats_items", + "timer_count", "timer_items", + "legacy_warnings,warnings_count,enabled_warnings,profiles,selected_profile,osd_overlay"]), + MSP_PID: MSPItem("PID", "8PID", "P,I,D"), + MSP_MISC: MSPItem("MISC", "HHHHHII","intPowerTrigger,conf1,conf2,conf3,conf4,conf5,conf6"), + MSP_MOTOR_PINS: MSPItem("MOTOR_PINS", "8H","MP"), + MSP_ANALOG: MSPItem("ANALOG", "BHHHH", "dV,consumed_mah,rssi,current,volt"), + MSP_STATUS: MSPItem("STATUS", "HHHIBHHBBIB", "task_delta,i2c_err_count,sensor_status,mode_flags,nop_1,system_load,gyro_time,nop_2,nop_3,armed,extra"), + MSP_ESC_SENSOR_DATA: MSPItem('ESC', "BH", "temp1,rpm1"), + } + + def __init__(self): + + self.msp_name = { + 'name':None + } + self.msp_osd_config = {} + + self.inBuf = bytearray([0] * 255) + self.p = 0 + self.c_state = self.IDLE + self.err_rcvd = False + self.checksum = 0 + self.cmd = 0 + self.offset=0 + self.dataSize=0 + self.servo = [] + self.mot = [] + self.RCChan = [] + self.byteP = [] + self.byteI = [] + self.byteD = [] + self.confINF = [] + self.byteMP = [] + + self.confP = [] + self.confI = [] + self.confD = [] + + # parsed messages, indexed by name + self.by_name = {} + + def get(self, fieldname): + '''get a field from a parsed message by Message.Field name''' + a = fieldname.split('.') + msgName = a[0] + fieldName = a[1] + if not msgName in self.by_name: + # default to zero for simplicty of display + return 0 + msg = self.by_name[msgName] + if not fieldName in msg.values: + raise Exception("Unknown field %s" % fieldName) + return msg.values[fieldName] + + def read32(self): + '''signed 32 bit number''' + value, = struct.unpack(" 0: + if (payloadinbytes == False): + for c in struct.pack('<%dh' % ((pl_size) / 2), *payload): + checksum ^= (ord(c) & 0xFF) + else: + for c in struct.pack('<%Bh' % ((pl_size) / 2), *payload): + checksum ^= (ord(c) & 0xFF) + bf = bf + payload + bf.append(checksum) + return bf + + def evaluateCommand(self, cmd, dataSize): + if cmd in self.MESSAGES: + # most messages are parsed from the MESSAGES list + self.MESSAGES[cmd].parse(self, dataSize) + elif cmd == self.MSP_NAME: + s = bytearray() + for i in range(0,dataSize,1): + b = self.read8() + if b == 0: + break + s.append(b) + self.msp_name['name'] = s.decode("utf-8") + + elif cmd == self.MSP_ACC_CALIBRATION: + x = None + elif cmd == self.MSP_MAG_CALIBRATION: + x = None + elif cmd == self.MSP_BOX: + x = None + elif cmd == self.MSP_BOXNAMES: + x = None + elif cmd == self.MSP_PIDNAMES: + x = None + elif cmd == self.MSP_SERVO_CONF: + x = None + elif cmd == self.MSP_DEBUGMSG: + x = None + elif cmd == self.MSP_DEBUG: + x = None + else: + print("Unhandled command ", cmd, dataSize) + + def parseMspData(self, buf): + for c in buf: + self.parseMspByte(c) + + def parseMspByte(self, c): + if sys.version_info.major >= 3: + cc = chr(c) + ci = c + else: + cc = c + ci = ord(c) + if self.c_state == self.IDLE: + if cc == '$': + self.c_state = self.HEADER_START + else: + self.c_state = self.IDLE + elif self.c_state == self.HEADER_START: + if cc == 'M': + self.c_state = self.HEADER_M + else: + self.c_state = self.IDLE + elif self.c_state == self.HEADER_M: + if cc == '>': + self.c_state = self.HEADER_ARROW + elif cc == '!': + self.c_state = self.HEADER_ERR + else: + self.c_state = self.IDLE + + elif self.c_state == self.HEADER_ARROW or self.c_state == self.HEADER_ERR: + self.err_rcvd = (self.c_state == self.HEADER_ERR) + #print (struct.unpack('= self.dataSize: + # compare calculated and transferred checksum + if ((self.checksum&0xFF) == ci): + if self.err_rcvd: + print("Vehicle didn't understand the request type") + else: + self.evaluateCommand(self.cmd, self.dataSize) + else: + print('"invalid checksum for command "+((int)(cmd&0xFF))+": "+(checksum&0xFF)+" expected, got "+(int)(c&0xFF))') + + self.c_state = self.IDLE + + def setPID(self): + self.sendRequestMSP(self.requestMSP(self.MSP_PID)) + self.receiveData(self.MSP_PID) + time.sleep(0.04) + payload = [] + for i in range(0, self.PIDITEMS, 1): + self.byteP[i] = int((round(self.confP[i] * 10))) + self.byteI[i] = int((round(self.confI[i] * 1000))) + self.byteD[i] = int((round(self.confD[i]))) + + + # POS - 4 POSR - 5 NAVR - 6 + + self.byteP[4] = int((round(self.confP[4] * 100.0))) + self.byteI[4] = int((round(self.confI[4] * 100.0))) + self.byteP[5] = int((round(self.confP[5] * 10.0))) + self.byteI[5] = int((round(self.confI[5] * 100.0))) + self.byteD[5] = int((round(self.confD[5] * 10000.0))) / 10 + + self.byteP[6] = int((round(self.confP[6] * 10.0))) + self.byteI[6] = int((round(self.confI[6] * 100.0))) + self.byteD[6] = int((round(self.confD[6] * 10000.0))) / 10 + + for i in range(0, self.PIDITEMS, 1): + payload.append(self.byteP[i]) + payload.append(self.byteI[i]) + payload.append(self.byteD[i]) + self.sendRequestMSP(self.requestMSP(self.MSP_SET_PID, payload, True), True) + + + def arm(self): + timer = 0 + start = time.time() + while timer < 0.5: + data = [1500,1500,2000,1000] + self.sendRequestMSP(self.requestMSP(self.MSP_SET_RAW_RC,data)) + time.sleep(0.05) + timer = timer + (time.time() - start) + start = time.time() + + def disarm(self): + timer = 0 + start = time.time() + while timer < 0.5: + data = [1500,1500,1000,1000] + self.sendRequestMSP(self.requestMSP(self.MSP_SET_RAW_RC,data)) + time.sleep(0.05) + timer = timer + (time.time() - start) + start = time.time() + + + def receiveIMU(self, duration): + timer = 0 + start = time.time() + while timer < duration: + self.sendRequestMSP(self.requestMSP(self.MSP_RAW_IMU)) + self.receiveData(self.MSP_RAW_IMU) + if self.msp_raw_imu['accx'] > 32768: # 2^15 ...to check if negative number is received + self.msp_raw_imu['accx'] -= 65536 # 2^16 ...converting into 2's complement + if self.msp_raw_imu['accy'] > 32768: + self.msp_raw_imu['accy'] -= 65536 + if self.msp_raw_imu['accz'] > 32768: + self.msp_raw_imu['accz'] -= 65536 + if self.msp_raw_imu['gyrx'] > 32768: + self.msp_raw_imu['gyrx'] -= 65536 + if self.msp_raw_imu['gyry'] > 32768: + self.msp_raw_imu['gyry'] -= 65536 + if self.msp_raw_imu['gyrz'] > 32768: + self.msp_raw_imu['gyrz'] -= 65536 + print("size: %d, accx: %f, accy: %f, accz: %f, gyrx: %f, gyry: %f, gyrz: %f " %(self.msp_raw_imu['size'], self.msp_raw_imu['accx'], self.msp_raw_imu['accy'], self.msp_raw_imu['accz'], self.msp_raw_imu['gyrx'], self.msp_raw_imu['gyry'], self.msp_raw_imu['gyrz'])) + time.sleep(0.04) + timer = timer + (time.time() - start) + start = time.time() + + + def calibrateIMU(self): + self.sendRequestMSP(self.requestMSP(self.MSP_ACC_CALIBRATION)) + time.sleep(0.01) diff --git a/libraries/AP_MSP/msp.h b/libraries/AP_MSP/msp.h index ebe66148f6b..161367d6aea 100644 --- a/libraries/AP_MSP/msp.h +++ b/libraries/AP_MSP/msp.h @@ -104,6 +104,7 @@ typedef enum : uint8_t { MSP_DISPLAYPORT_CLEAR_SCREEN = 2, MSP_DISPLAYPORT_WRITE_STRING = 3, MSP_DISPLAYPORT_DRAW_SCREEN = 4, + MSP_DISPLAYPORT_SET_OPTIONS = 5, } msp_displayport_subcmd_e; typedef struct PACKED { diff --git a/libraries/AP_Math/AP_Math.cpp b/libraries/AP_Math/AP_Math.cpp index 6cb2dc6b3d5..f76b64755ae 100644 --- a/libraries/AP_Math/AP_Math.cpp +++ b/libraries/AP_Math/AP_Math.cpp @@ -313,9 +313,13 @@ T constrain_value(const T amt, const T low, const T high) } template int constrain_value(const int amt, const int low, const int high); +template unsigned int constrain_value(const unsigned int amt, const unsigned int low, const unsigned int high); template long constrain_value(const long amt, const long low, const long high); +template unsigned long constrain_value(const unsigned long amt, const unsigned long low, const unsigned long high); template long long constrain_value(const long long amt, const long long low, const long long high); +template unsigned long long constrain_value(const unsigned long long amt, const unsigned long long low, const unsigned long long high); template short constrain_value(const short amt, const short low, const short high); +template unsigned short constrain_value(const unsigned short amt, const unsigned short low, const unsigned short high); template float constrain_value(const float amt, const float low, const float high); template double constrain_value(const double amt, const double low, const double high); @@ -333,11 +337,15 @@ uint16_t get_random16(void) } -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#if AP_SIM_ENABLED // generate a random float between -1 and 1, for use in SITL float rand_float(void) { +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL return ((((unsigned)random()) % 2000000) - 1.0e6) / 1.0e6; +#else + return get_random16() / 65535.0; +#endif } Vector3f rand_vec3f(void) @@ -392,11 +400,18 @@ Vector3F get_vel_correction_for_sensor_offset(const Vector3F &sensor_offset_bf, */ float calc_lowpass_alpha_dt(float dt, float cutoff_freq) { - if (dt <= 0.0f || cutoff_freq <= 0.0f) { + if (is_negative(dt) || is_negative(cutoff_freq)) { + INTERNAL_ERROR(AP_InternalError::error_t::invalid_arg_or_result); return 1.0; } - float rc = 1.0f/(M_2PI*cutoff_freq); - return constrain_float(dt/(dt+rc), 0.0f, 1.0f); + if (is_zero(cutoff_freq)) { + return 1.0; + } + if (is_zero(dt)) { + return 0.0; + } + float rc = 1.0f / (M_2PI * cutoff_freq); + return dt / (dt + rc); } #ifndef AP_MATH_FILL_NANF_USE_MEMCPY @@ -479,3 +494,36 @@ float degF_to_Kelvin(float temp_f) { return (temp_f + 459.67) * 0.55556; } + +/* + conversion functions to prevent undefined behaviour + */ +int16_t float_to_int16(const float v) +{ + return int16_t(constrain_float(v, INT16_MIN, INT16_MAX)); +} + +int32_t float_to_int32(const float v) +{ + return int32_t(constrain_float(v, INT32_MIN, INT32_MAX)); +} + +uint16_t float_to_uint16(const float v) +{ + return uint16_t(constrain_float(v, 0, UINT16_MAX)); +} + +uint32_t float_to_uint32(const float v) +{ + return uint32_t(constrain_float(v, 0, UINT32_MAX)); +} + +uint32_t double_to_uint32(const double v) +{ + return uint32_t(constrain_double(v, 0, UINT32_MAX)); +} + +int32_t double_to_int32(const double v) +{ + return int32_t(constrain_double(v, INT32_MIN, UINT32_MAX)); +} diff --git a/libraries/AP_Math/AP_Math.h b/libraries/AP_Math/AP_Math.h index 5b71dea1f96..0abeac01577 100644 --- a/libraries/AP_Math/AP_Math.h +++ b/libraries/AP_Math/AP_Math.h @@ -179,16 +179,36 @@ inline int16_t constrain_int16(const int16_t amt, const int16_t low, const int16 return constrain_value(amt, low, high); } +inline uint16_t constrain_uint16(const uint16_t amt, const uint16_t low, const uint16_t high) +{ + return constrain_value(amt, low, high); +} + inline int32_t constrain_int32(const int32_t amt, const int32_t low, const int32_t high) { return constrain_value(amt, low, high); } +inline uint32_t constrain_uint32(const uint32_t amt, const uint32_t low, const uint32_t high) +{ + return constrain_value(amt, low, high); +} + inline int64_t constrain_int64(const int64_t amt, const int64_t low, const int64_t high) { return constrain_value(amt, low, high); } +inline uint64_t constrain_uint64(const uint64_t amt, const uint64_t low, const uint64_t high) +{ + return constrain_value(amt, low, high); +} + +inline double constrain_double(const double amt, const double low, const double high) +{ + return constrain_value(amt, low, high); +} + // degrees -> radians static inline constexpr ftype radians(ftype deg) { @@ -207,6 +227,10 @@ ftype sq(const T val) ftype v = static_cast(val); return v*v; } +static inline constexpr float sq(const float val) +{ + return val*val; +} /* * Variadic template for calculating the square norm of a vector of any @@ -341,3 +365,13 @@ float fixedwing_turn_rate(float bank_angle_deg, float airspeed); // convert degrees farenheight to Kelvin float degF_to_Kelvin(float temp_f); +/* + conversion functions to prevent undefined behaviour + */ +int16_t float_to_int16(const float v); +uint16_t float_to_uint16(const float v); +int32_t float_to_int32(const float v); +uint32_t float_to_uint32(const float v); +uint32_t double_to_uint32(const double v); +int32_t double_to_int32(const double v); + diff --git a/libraries/AP_Math/SCurve.cpp b/libraries/AP_Math/SCurve.cpp index a09a7514287..074b3e06036 100644 --- a/libraries/AP_Math/SCurve.cpp +++ b/libraries/AP_Math/SCurve.cpp @@ -16,6 +16,10 @@ #include #include #include +#include +#if APM_BUILD_COPTER_OR_HELI +#include +#endif #include "SCurve.h" #if CONFIG_HAL_BOARD == HAL_BOARD_SITL @@ -26,9 +30,11 @@ extern const AP_HAL::HAL &hal; #define SEG_INIT 0 #define SEG_ACCEL_MAX 4 +#define SEG_TURN_IN 4 #define SEG_ACCEL_END 7 #define SEG_SPEED_CHANGE_END 14 #define SEG_CONST 15 +#define SEG_TURN_OUT 15 #define SEG_DECEL_END 22 // constructor @@ -40,7 +46,7 @@ SCurve::SCurve() // initialise and clear the path void SCurve::init() { - jerk_time = 0.0f; + snap_max = 0.0f; jerk_max = 0.0f; accel_max = 0.0f; vel_max = 0.0f; @@ -57,7 +63,7 @@ void SCurve::init() void SCurve::calculate_track(const Vector3f &origin, const Vector3f &destination, float speed_xy, float speed_up, float speed_down, float accel_xy, float accel_z, - float jerk_time_sec, float jerk_maximum) + float snap_maximum, float jerk_maximum) { init(); @@ -67,8 +73,8 @@ void SCurve::calculate_track(const Vector3f &origin, const Vector3f &destination return; } - // set jerk time and jerk max - jerk_time = jerk_time_sec; + // set snap_max and jerk max + snap_max = snap_maximum; jerk_max = jerk_maximum; // update speed and acceleration limits along path @@ -77,7 +83,7 @@ void SCurve::calculate_track(const Vector3f &origin, const Vector3f &destination accel_xy, accel_z); // avoid divide-by zeros. Path will be left as a zero length path - if (!is_positive(jerk_time) || !is_positive(jerk_max) || !is_positive(accel_max) || !is_positive(vel_max)) { + if (!is_positive(snap_max) || !is_positive(jerk_max) || !is_positive(accel_max) || !is_positive(vel_max)) { #if CONFIG_HAL_BOARD == HAL_BOARD_SITL ::printf("SCurve::calculate_track created zero length path\n"); #endif @@ -210,13 +216,13 @@ void SCurve::set_speed_max(float speed_xy, float speed_up, float speed_down) // minimum velocity that can be obtained by shortening SEG_ACCEL_MAX const float Vmin = segment[SEG_ACCEL_END].end_vel - segment[SEG_ACCEL_MAX].end_accel * (segment[SEG_ACCEL_MAX].end_time - MAX(time, segment[SEG_ACCEL_MAX-1].end_time)); - float Jm, t2, t4, t6; - calculate_path(jerk_time, jerk_max, Vstart, accel_max, MAX(Vmin, vel_max), Pend * 0.5f, Jm, t2, t4, t6); + float Jm, tj, t2, t4, t6; + calculate_path(snap_max, jerk_max, Vstart, accel_max, MAX(Vmin, vel_max), Pend * 0.5f, Jm, tj, t2, t4, t6); uint8_t seg = SEG_INIT+1; - add_segments_jerk(seg, jerk_time, Jm, t2); + add_segments_jerk(seg, tj, Jm, t2); add_segment_const_jerk(seg, t4, 0.0f); - add_segments_jerk(seg, jerk_time, -Jm, t6); + add_segments_jerk(seg, tj, -Jm, t6); // remove numerical errors segment[SEG_ACCEL_END].end_accel = 0.0f; @@ -231,12 +237,12 @@ void SCurve::set_speed_max(float speed_xy, float speed_up, float speed_down) segment[i].end_pos = segment[SEG_ACCEL_END].end_pos; } - calculate_path(jerk_time, jerk_max, 0.0f, accel_max, MAX(Vmin, vel_max), Pend * 0.5f, Jm, t2, t4, t6); + calculate_path(snap_max, jerk_max, 0.0f, accel_max, MAX(Vmin, vel_max), Pend * 0.5f, Jm, tj, t2, t4, t6); seg = SEG_CONST + 1; - add_segments_jerk(seg, jerk_time, -Jm, t6); + add_segments_jerk(seg, tj, -Jm, t6); add_segment_const_jerk(seg, t4, 0.0f); - add_segments_jerk(seg, jerk_time, Jm, t2); + add_segments_jerk(seg, tj, Jm, t2); // remove numerical errors segment[SEG_DECEL_END].end_accel = 0.0f; @@ -267,24 +273,26 @@ void SCurve::set_speed_max(float speed_xy, float speed_up, float speed_down) // we use the approximation that the time will be distance/max_vel and 8 jerk segments const float L = segment[SEG_CONST].end_pos - segment[SEG_ACCEL_END].end_pos; float Jm = 0; + float tj = 0; float t2 = 0; float t4 = 0; float t6 = 0; + float jerk_time = MIN(powf((fabsf(vel_max - segment[SEG_ACCEL_END].end_vel) * M_PI) / (4 * snap_max), 1/3), jerk_max * M_PI / (2 * snap_max)); if ((vel_max < segment[SEG_ACCEL_END].end_vel) && (jerk_time*12.0f < L/segment[SEG_ACCEL_END].end_vel)) { // we have a problem here with small segments. - calculate_path(jerk_time, jerk_max, vel_max, accel_max, segment[SEG_ACCEL_END].end_vel, L * 0.5f, Jm, t6, t4, t2); + calculate_path(snap_max, jerk_max, vel_max, accel_max, segment[SEG_ACCEL_END].end_vel, L * 0.5f, Jm, tj, t6, t4, t2); Jm = -Jm; } else if ((vel_max > segment[SEG_ACCEL_END].end_vel) && (L/(jerk_time*12.0f) > segment[SEG_ACCEL_END].end_vel)) { float Vm = MIN(vel_max, L/(jerk_time*12.0f)); - calculate_path(jerk_time, jerk_max, segment[SEG_ACCEL_END].end_vel, accel_max, Vm, L * 0.5f, Jm, t2, t4, t6); + calculate_path(snap_max, jerk_max, segment[SEG_ACCEL_END].end_vel, accel_max, Vm, L * 0.5f, Jm, tj, t2, t4, t6); } uint8_t seg = SEG_ACCEL_END + 1; if (!is_zero(Jm) && !is_negative(t2) && !is_negative(t4) && !is_negative(t6)) { - add_segments_jerk(seg, jerk_time, Jm, t2); + add_segments_jerk(seg, tj, Jm, t2); add_segment_const_jerk(seg, t4, 0.0f); - add_segments_jerk(seg, jerk_time, -Jm, t6); + add_segments_jerk(seg, tj, -Jm, t6); // remove numerical errors segment[SEG_SPEED_CHANGE_END].end_accel = 0.0f; @@ -297,11 +305,11 @@ void SCurve::set_speed_max(float speed_xy, float speed_up, float speed_down) Vend = MIN(Vend, segment[SEG_SPEED_CHANGE_END].end_vel); add_segment_const_jerk(seg, 0.0f, 0.0f); if (Vend < segment[SEG_SPEED_CHANGE_END].end_vel) { - float Jm, t2, t4, t6; - calculate_path(jerk_time, jerk_max, Vend, accel_max, segment[SEG_CONST].end_vel, Pend - segment[SEG_CONST].end_pos, Jm, t2, t4, t6); - add_segments_jerk(seg, jerk_time, -Jm, t6); + float Jm, tj, t2, t4, t6; + calculate_path(snap_max, jerk_max, Vend, accel_max, segment[SEG_CONST].end_vel, Pend - segment[SEG_CONST].end_pos, Jm, tj, t2, t4, t6); + add_segments_jerk(seg, tj, -Jm, t6); add_segment_const_jerk(seg, t4, 0.0f); - add_segments_jerk(seg, jerk_time, Jm, t2); + add_segments_jerk(seg, tj, Jm, t2); } else { // No deceleration is required for (uint8_t i = SEG_CONST+1; i <= SEG_DECEL_END; i++) { @@ -355,14 +363,14 @@ float SCurve::set_origin_speed_max(float speed) const float track_length = track.length(); speed = MIN(speed, Vm); - float Jm, t2, t4, t6; - calculate_path(jerk_time, jerk_max, speed, accel_max, Vm, track_length * 0.5f, Jm, t2, t4, t6); + float Jm, tj, t2, t4, t6; + calculate_path(snap_max, jerk_max, speed, accel_max, Vm, track_length * 0.5f, Jm, tj, t2, t4, t6); uint8_t seg = SEG_INIT; add_segment(seg, 0.0f, SegmentType::CONSTANT_JERK, 0.0f, 0.0f, speed, 0.0f); - add_segments_jerk(seg, jerk_time, Jm, t2); + add_segments_jerk(seg, tj, Jm, t2); add_segment_const_jerk(seg, t4, 0.0f); - add_segments_jerk(seg, jerk_time, -Jm, t6); + add_segments_jerk(seg, tj, -Jm, t6); // remove numerical errors segment[SEG_ACCEL_END].end_accel = 0.0f; @@ -388,11 +396,11 @@ float SCurve::set_origin_speed_max(float speed) seg = SEG_CONST; add_segment_const_jerk(seg, 0.0f, 0.0f); - calculate_path(jerk_time, jerk_max, 0.0f, accel_max, segment[SEG_CONST].end_vel, track_length * 0.5f, Jm, t2, t4, t6); + calculate_path(snap_max, jerk_max, 0.0f, accel_max, segment[SEG_CONST].end_vel, track_length * 0.5f, Jm, tj, t2, t4, t6); - add_segments_jerk(seg, jerk_time, -Jm, t6); + add_segments_jerk(seg, tj, -Jm, t6); add_segment_const_jerk(seg, t4, 0.0f); - add_segments_jerk(seg, jerk_time, Jm, t2); + add_segments_jerk(seg, tj, Jm, t2); // remove numerical errors segment[SEG_DECEL_END].end_accel = 0.0f; @@ -437,15 +445,15 @@ void SCurve::set_destination_speed_max(float speed) const float track_length = track.length(); speed = MIN(speed, Vm); - float Jm, t2, t4, t6; - calculate_path(jerk_time, jerk_max, speed, accel_max, Vm, track_length * 0.5f, Jm, t2, t4, t6); + float Jm, tj, t2, t4, t6; + calculate_path(snap_max, jerk_max, speed, accel_max, Vm, track_length * 0.5f, Jm, tj, t2, t4, t6); uint8_t seg = SEG_CONST; add_segment_const_jerk(seg, 0.0f, 0.0f); - add_segments_jerk(seg, jerk_time, -Jm, t6); + add_segments_jerk(seg, tj, -Jm, t6); add_segment_const_jerk(seg, t4, 0.0f); - add_segments_jerk(seg, jerk_time, Jm, t2); + add_segments_jerk(seg, tj, Jm, t2); // remove numerical errors segment[SEG_DECEL_END].end_accel = 0.0f; @@ -478,7 +486,7 @@ void SCurve::set_destination_speed_max(float speed) // target_pos should be set to this segment's origin and it will be updated to the current position target // target_vel and target_accel are updated with new targets // returns true if vehicle has passed the apex of the corner -bool SCurve::advance_target_along_track(SCurve &prev_leg, SCurve &next_leg, float wp_radius, bool fast_waypoint, float dt, Vector3f &target_pos, Vector3f &target_vel, Vector3f &target_accel) +bool SCurve::advance_target_along_track(SCurve &prev_leg, SCurve &next_leg, float wp_radius, float accel_corner, bool fast_waypoint, float dt, Vector3f &target_pos, Vector3f &target_vel, Vector3f &target_accel) { prev_leg.move_to_pos_vel_accel(dt, target_pos, target_vel, target_accel); move_from_pos_vel_accel(dt, target_pos, target_vel, target_accel); @@ -486,16 +494,19 @@ bool SCurve::advance_target_along_track(SCurve &prev_leg, SCurve &next_leg, floa // check for change of leg on fast waypoint const float time_to_destination = get_time_remaining(); - if (fast_waypoint && braking() && is_zero(next_leg.get_time_elapsed()) && (time_to_destination <= next_leg.get_accel_finished_time())) { + if (fast_waypoint + && is_zero(next_leg.get_time_elapsed()) + && (get_time_elapsed() >= time_turn_out() - next_leg.time_turn_in()) + && (position_sq >= 0.25 * track.length_squared())) { + Vector3f turn_pos = -get_track(); Vector3f turn_vel, turn_accel; move_from_time_pos_vel_accel(get_time_elapsed() + time_to_destination * 0.5f, turn_pos, turn_vel, turn_accel); next_leg.move_from_time_pos_vel_accel(time_to_destination * 0.5f, turn_pos, turn_vel, turn_accel); const float speed_min = MIN(get_speed_along_track(), next_leg.get_speed_along_track()); - const float accel_min = MIN(get_accel_along_track(), next_leg.get_accel_along_track()); if ((get_time_remaining() < next_leg.time_end() * 0.5f) && (turn_pos.length() < wp_radius) && (Vector2f{turn_vel.x, turn_vel.y}.length() < speed_min) && - (Vector2f{turn_accel.x, turn_accel.y}.length() < 2.0f*accel_min)) { + (Vector2f{turn_accel.x, turn_accel.y}.length() < accel_corner)) { next_leg.move_from_pos_vel_accel(dt, target_pos, target_vel, target_accel); } } else if (!is_zero(next_leg.get_time_elapsed())) { @@ -556,7 +567,7 @@ void SCurve::move_from_time_pos_vel_accel(float time_now, Vector3f &pos, Vector3 float SCurve::time_end() const { if (num_segs != segments_max) { - return 0.0f; + return 0.0; } return segment[SEG_DECEL_END].end_time; } @@ -565,7 +576,7 @@ float SCurve::time_end() const float SCurve::get_time_remaining() const { if (num_segs != segments_max) { - return 0.0f; + return 0.0; } return segment[SEG_DECEL_END].end_time - time; } @@ -574,7 +585,7 @@ float SCurve::get_time_remaining() const float SCurve::get_accel_finished_time() const { if (num_segs != segments_max) { - return 0.0f; + return 0.0; } return segment[SEG_ACCEL_END].end_time; } @@ -588,6 +599,24 @@ bool SCurve::braking() const return time >= segment[SEG_CONST].end_time; } +// return time offset used to initiate the turn onto leg +float SCurve::time_turn_in() const +{ + if (num_segs != segments_max) { + return 0.0; + } + return segment[SEG_TURN_IN].end_time; +} + +// return time offset used to initiate the turn from leg +float SCurve::time_turn_out() const +{ + if (num_segs != segments_max) { + return 0.0; + } + return segment[SEG_TURN_OUT].end_time; +} + // increment the internal time void SCurve::advance_time(float dt) { @@ -597,17 +626,18 @@ void SCurve::advance_time(float dt) // calculate the jerk, acceleration, velocity and position at the provided time void SCurve::get_jerk_accel_vel_pos_at_time(float time_now, float &Jt_out, float &At_out, float &Vt_out, float &Pt_out) const { - if ((num_segs != segments_max) || !is_positive(jerk_time)) { - Jt_out = 0; - At_out = 0; - Vt_out = 0; - Pt_out = 0; + // start with zeros as function is void and we want to guarantee all outputs are initialised + Jt_out = 0; + At_out = 0; + Vt_out = 0; + Pt_out = 0; + if (num_segs != segments_max) { return; } SegmentType Jtype; uint8_t pnt = num_segs; - float Jm, T0, A0, V0, P0; + float Jm, tj, T0, A0, V0, P0; // find active segment at time_now for (uint8_t i = 0; i < num_segs; i++) { @@ -618,6 +648,7 @@ void SCurve::get_jerk_accel_vel_pos_at_time(float time_now, float &Jt_out, float if (pnt == 0) { Jtype = SegmentType::CONSTANT_JERK; Jm = 0.0f; + tj = 0.0f; T0 = segment[pnt].end_time; A0 = segment[pnt].end_accel; V0 = segment[pnt].end_vel; @@ -625,6 +656,7 @@ void SCurve::get_jerk_accel_vel_pos_at_time(float time_now, float &Jt_out, float } else if (pnt == num_segs) { Jtype = SegmentType::CONSTANT_JERK; Jm = 0.0f; + tj = 0.0f; T0 = segment[pnt - 1].end_time; A0 = segment[pnt - 1].end_accel; V0 = segment[pnt - 1].end_vel; @@ -632,6 +664,7 @@ void SCurve::get_jerk_accel_vel_pos_at_time(float time_now, float &Jt_out, float } else { Jtype = segment[pnt].seg_type; Jm = segment[pnt].jerk_ref; + tj = segment[pnt].end_time - segment[pnt - 1].end_time; T0 = segment[pnt - 1].end_time; A0 = segment[pnt - 1].end_accel; V0 = segment[pnt - 1].end_vel; @@ -643,10 +676,10 @@ void SCurve::get_jerk_accel_vel_pos_at_time(float time_now, float &Jt_out, float calc_javp_for_segment_const_jerk(time_now - T0, Jm, A0, V0, P0, Jt_out, At_out, Vt_out, Pt_out); break; case SegmentType::POSITIVE_JERK: - calc_javp_for_segment_incr_jerk(time_now - T0, jerk_time, Jm, A0, V0, P0, Jt_out, At_out, Vt_out, Pt_out); + calc_javp_for_segment_incr_jerk(time_now - T0, tj, Jm, A0, V0, P0, Jt_out, At_out, Vt_out, Pt_out); break; case SegmentType::NEGATIVE_JERK: - calc_javp_for_segment_decr_jerk(time_now - T0, jerk_time, Jm, A0, V0, P0, Jt_out, At_out, Vt_out, Pt_out); + calc_javp_for_segment_decr_jerk(time_now - T0, tj, Jm, A0, V0, P0, Jt_out, At_out, Vt_out, Pt_out); break; } Pt_out = MAX(0.0f, Pt_out); @@ -664,6 +697,13 @@ void SCurve::calc_javp_for_segment_const_jerk(float time_now, float J0, float A0 // Calculate the jerk, acceleration, velocity and position at time time_now when running the increasing jerk magnitude time segment based on a raised cosine profile void SCurve::calc_javp_for_segment_incr_jerk(float time_now, float tj, float Jm, float A0, float V0, float P0, float &Jt, float &At, float &Vt, float &Pt) const { + if (!is_positive(tj)) { + Jt = 0.0; + At = A0; + Vt = V0; + Pt = P0; + return; + } const float Alpha = Jm * 0.5f; const float Beta = M_PI / tj; Jt = Alpha * (1.0f - cosf(Beta * time_now)); @@ -675,6 +715,13 @@ void SCurve::calc_javp_for_segment_incr_jerk(float time_now, float tj, float Jm, // Calculate the jerk, acceleration, velocity and position at time time_now when running the decreasing jerk magnitude time segment based on a raised cosine profile void SCurve::calc_javp_for_segment_decr_jerk(float time_now, float tj, float Jm, float A0, float V0, float P0, float &Jt, float &At, float &Vt, float &Pt) const { + if (!is_positive(tj)) { + Jt = 0.0; + At = A0; + Vt = V0; + Pt = P0; + return; + } const float Alpha = Jm * 0.5f; const float Beta = M_PI / tj; const float AT = Alpha * tj; @@ -699,12 +746,12 @@ void SCurve::add_segments(float L) return; } - float Jm, t2, t4, t6; - calculate_path(jerk_time, jerk_max, 0.0f, accel_max, vel_max, L * 0.5f, Jm, t2, t4, t6); + float Jm, tj, t2, t4, t6; + calculate_path(snap_max, jerk_max, 0.0f, accel_max, vel_max, L * 0.5f, Jm, tj, t2, t4, t6); - add_segments_jerk(num_segs, jerk_time, Jm, t2); + add_segments_jerk(num_segs, tj, Jm, t2); add_segment_const_jerk(num_segs, t4, 0.0f); - add_segments_jerk(num_segs, jerk_time, -Jm, t6); + add_segments_jerk(num_segs, tj, -Jm, t6); // remove numerical errors segment[SEG_ACCEL_END].end_accel = 0.0f; @@ -721,9 +768,9 @@ void SCurve::add_segments(float L) const float t15 = MAX(0.0f, (L - 2.0f * segment[SEG_SPEED_CHANGE_END].end_pos) / segment[SEG_SPEED_CHANGE_END].end_vel); add_segment_const_jerk(num_segs, t15, 0.0f); - add_segments_jerk(num_segs, jerk_time, -Jm, t6); + add_segments_jerk(num_segs, tj, -Jm, t6); add_segment_const_jerk(num_segs, t4, 0.0f); - add_segments_jerk(num_segs, jerk_time, Jm, t2); + add_segments_jerk(num_segs, tj, Jm, t2); // remove numerical errors segment[SEG_DECEL_END].end_accel = 0.0f; @@ -731,23 +778,24 @@ void SCurve::add_segments(float L) } // calculate the segment times for the trigonometric S-Curve path defined by: -// tj - duration of the raised cosine jerk profile +// Sm - duration of the raised cosine jerk profile // Jm - maximum value of the raised cosine jerk profile // V0 - initial velocity magnitude // Am - maximum constant acceleration // Vm - maximum constant velocity // L - Length of the path -// t2_out, t4_out, t6_out are the segment durations needed to achieve the kinematic path specified by the input variables -void SCurve::calculate_path(float tj, float Jm, float V0, float Am, float Vm, float L, float &Jm_out, float &t2_out, float &t4_out, float &t6_out) +// tj_out, t2_out, t4_out, t6_out are the segment durations needed to achieve the kinematic path specified by the input variables +void SCurve::calculate_path(float Sm, float Jm, float V0, float Am, float Vm, float L,float &Jm_out, float &tj_out, float &t2_out, float &t4_out, float &t6_out) { // init outputs Jm_out = 0.0f; + tj_out = 0.0f; t2_out = 0.0f; t4_out = 0.0f; t6_out = 0.0f; // check for invalid arguments - if (!is_positive(tj) || !is_positive(Jm) || !is_positive(Am) || !is_positive(Vm) || !is_positive(L)) { + if (!is_positive(Sm) || !is_positive(Jm) || !is_positive(Am) || !is_positive(Vm) || !is_positive(L)) { #if CONFIG_HAL_BOARD == HAL_BOARD_SITL ::printf("SCurve::calculate_path invalid inputs\n"); #endif @@ -760,9 +808,24 @@ void SCurve::calculate_path(float tj, float Jm, float V0, float Am, float Vm, fl return; } - Am = MIN(MIN(Am, (Vm - V0) / (2.0f * tj)), (L + 4.0f * V0 * tj) / (4.0f * sq(tj))); - if (fabsf(Am) < Jm * tj) { - Jm = Am / tj; + float tj = Jm * M_PI / (2 * Sm); + float At = MIN(MIN(Am, + (Vm - V0) / (2.0f * tj) ), + (L + 4.0f * V0 * tj) / (4.0f * sq(tj)) ); + if (fabsf(At) < Jm * tj) { + if (is_zero(V0)) { + // we do not have a solution for non-zero initial velocity + tj = MIN( MIN( MIN( tj, + powf((L * M_PI) / (8.0 * Sm), 1.0/4.0) ), + powf((Vm * M_PI) / (4.0 * Sm), 1.0/3.0) ), + safe_sqrt((Am * M_PI) / (2.0 * Sm)) ); + Jm = 2.0 * Sm * tj / M_PI; + Am = Jm * tj; + } else { + // When doing speed change we use fixed tj and adjust Jm for small changes + Am = At; + Jm = Am / tj; + } if ((Vm <= V0 + 2.0f * Am * tj) || (L <= 4.0f * V0 * tj + 4.0f * Am * sq(tj))) { // solution = 0 - t6 t4 t2 = 0 0 0 t2_out = 0.0f; @@ -790,10 +853,12 @@ void SCurve::calculate_path(float tj, float Jm, float V0, float Am, float Vm, fl t6_out = t2_out; } } + tj_out = tj; Jm_out = Jm; // check outputs and reset back to zero if necessary if (!isfinite(Jm_out) || is_negative(Jm_out) || + !isfinite(tj_out) || is_negative(tj_out) || !isfinite(t2_out) || is_negative(t2_out) || !isfinite(t4_out) || is_negative(t4_out) || !isfinite(t6_out) || is_negative(t6_out)) { @@ -801,6 +866,48 @@ void SCurve::calculate_path(float tj, float Jm, float V0, float Am, float Vm, fl ::printf("SCurve::calculate_path invalid outputs\n"); #endif INTERNAL_ERROR(AP_InternalError::error_t::invalid_arg_or_result); + +#if APM_BUILD_COPTER_OR_HELI + // @LoggerMessage: SCVE + // @Description: Debug message for SCurve internal error + // @Field: TimeUS: Time since system startup + // @Field: Sm: duration of the raised cosine jerk profile + // @Field: Jm: maximum value of the raised cosine jerk profile + // @Field: V0: initial velocity magnitude + // @Field: Am: maximum constant acceleration + // @Field: Vm: maximum constant velocity + // @Field: L: Length of the path + // @Field: Jm_out: maximum value of the raised cosine jerk profile + // @Field: tj_out: segment duration + // @Field: t2_out: segment duration + // @Field: t4_out: segment duration + // @Field: t6_out: segment duration + + static bool logged_scve; // only log once + if (!logged_scve) { + logged_scve = true; + AP::logger().Write( + "SCVE", + "TimeUS,Sm,Jm,V0,Am,Vm,L,Jm_out,tj_out,t2_out,t4_out,t6_out", + "s-----------", + "F-----------", + "Qfffffffffff", + AP_HAL::micros64(), + (double)Sm, + (double)Jm, + (double)V0, + (double)Am, + (double)Vm, + (double)L, + (double)Jm_out, + (double)tj_out, + (double)t2_out, + (double)t4_out, + (double)t6_out + ); + } +#endif // APM_BUILD_COPTER_OR_HELI + Jm_out = 0.0f; t2_out = 0.0f; t4_out = 0.0f; @@ -824,7 +931,7 @@ void SCurve::add_segments_jerk(uint8_t &index, float tj, float Jm, float Tcj) void SCurve::add_segment_const_jerk(uint8_t &index, float tj, float J0) { // if no time increase copy previous segment - if (is_zero(tj)) { + if (!is_positive(tj)) { add_segment(index, segment[index - 1].end_time, SegmentType::CONSTANT_JERK, J0, @@ -847,6 +954,16 @@ void SCurve::add_segment_const_jerk(uint8_t &index, float tj, float J0) // the index variable is the position of this segment in the path array and is incremented to reference the next segment in the array void SCurve::add_segment_incr_jerk(uint8_t &index, float tj, float Jm) { + // if no time increase copy previous segment + if (!is_positive(tj)) { + add_segment(index, segment[index - 1].end_time, + SegmentType::CONSTANT_JERK, + 0.0, + segment[index - 1].end_accel, + segment[index - 1].end_vel, + segment[index - 1].end_pos); + return; + } const float Beta = M_PI / tj; const float Alpha = Jm * 0.5f; const float AT = Alpha * tj; @@ -866,6 +983,16 @@ void SCurve::add_segment_incr_jerk(uint8_t &index, float tj, float Jm) // the index variable is the position of this segment in the path and is incremented to reference the next segment in the array void SCurve::add_segment_decr_jerk(uint8_t &index, float tj, float Jm) { + // if no time increase copy previous segment + if (!is_positive(tj)) { + add_segment(index, segment[index - 1].end_time, + SegmentType::CONSTANT_JERK, + 0.0, + segment[index - 1].end_accel, + segment[index - 1].end_vel, + segment[index - 1].end_pos); + return; + } const float Beta = M_PI / tj; const float Alpha = Jm * 0.5f; const float AT = Alpha * tj; @@ -960,8 +1087,8 @@ bool SCurve::valid() const // debugging messages void SCurve::debug() const { - ::printf("num_segs:%u, time:%4.2f, jerk_time:%4.2f, jerk_max:%4.2f, accel_max:%4.2f, vel_max:%4.2f\n", - (unsigned)num_segs, (double)time, (double)jerk_time, (double)jerk_max, (double)accel_max, (double)vel_max); + ::printf("num_segs:%u, time:%4.2f, snap_max:%4.2f, jerk_max:%4.2f, accel_max:%4.2f, vel_max:%4.2f\n", + (unsigned)num_segs, (double)time, (double)snap_max, (double)jerk_max, (double)accel_max, (double)vel_max); ::printf("T, Jt, J, A, V, P \n"); for (uint8_t i = 0; i < num_segs; i++) { ::printf("i:%u, T:%4.2f, Jtype:%4.2f, J:%4.2f, A:%4.2f, V: %4.2f, P: %4.2f\n", diff --git a/libraries/AP_Math/SCurve.h b/libraries/AP_Math/SCurve.h index 7696c334509..c801e1a003e 100644 --- a/libraries/AP_Math/SCurve.h +++ b/libraries/AP_Math/SCurve.h @@ -36,8 +36,8 @@ * velocity: rate of change of position. aka speed * acceleration: rate of change of speed * jerk: rate of change of acceleration + * snap: rate of change of jerk * jerk time: the time (in seconds) for jerk to increase from zero to its maximum value - * jounce: rate of change of jerk * track: 3D path that the vehicle will follow * path: position, velocity, accel and jerk kinematic profile that this library generates */ @@ -53,21 +53,22 @@ class SCurve { void init(); // calculate the segment times for the trigonometric S-Curve path defined by: - // tj - duration of the raised cosine jerk profile (aka jerk time) - // Jm - maximum value of the raised cosine jerk profile (aka jerk max) + // Sm - maximum value of the snap profile + // Jm - maximum value of the raised cosine jerk profile // V0 - initial velocity magnitude // Am - maximum constant acceleration // Vm - maximum constant velocity // L - Length of the path + // tj_out, t2_out, t4_out, t6_out are the segment durations needed to achieve the kinematic path specified by the input variables // this is an internal function, static for test suite - static void calculate_path(float tj, float Jm, float V0, float Am, float Vm, float L, float &Jm_out, float &t2_out, float &t4_out, float &t6_out); + static void calculate_path(float Sm, float Jm, float V0, float Am, float Vm, float L, float &Jm_out, float &tj_out, float &t2_out, float &t4_out, float &t6_out); // generate a trigonometric track in 3D space that moves over a straight line // between two points defined by the origin and destination void calculate_track(const Vector3f &origin, const Vector3f &destination, float speed_xy, float speed_up, float speed_down, float accel_xy, float accel_z, - float jerk_time_sec, float jerk_maximum); + float snap_maximum, float jerk_maximum); // set maximum velocity and re-calculate the path using these limits void set_speed_max(float speed_xy, float speed_up, float speed_down); @@ -80,14 +81,15 @@ class SCurve { void set_destination_speed_max(float speed); // move target location along path from origin to destination - // prev_leg and next_leg are the paths before and after this path - // wp_radius is max distance from the waypoint at the apex of the turn - // fast_waypoint should be true if vehicle will not stop at end of this leg - // dt is the time increment the vehicle will move along the path - // target_pos should be set to this segment's origin and it will be updated to the current position target - // target_vel and target_accel are updated with new targets - // returns true if vehicle has passed the apex of the corner - bool advance_target_along_track(SCurve &prev_leg, SCurve &next_leg, float wp_radius, bool fast_waypoint, float dt, Vector3f &target_pos, Vector3f &target_vel, Vector3f &target_accel) WARN_IF_UNUSED; + // prev_leg and next_leg - the paths before and after this path + // wp_radius - max distance from the waypoint at the apex of the turn + // accel_corner - max acceleration that the aircraft may use during the corner + // fast_waypoint - true if vehicle will not stop at end of this leg + // dt - the time increment the vehicle will move along the path + // target_pos - set to this segment's origin and it will be updated to the current position target + // target_vel and target_accel - updated with new targets + // advance_target_along_track returns true if vehicle has passed the apex of the corner + bool advance_target_along_track(SCurve &prev_leg, SCurve &next_leg, float wp_radius, float accel_corner, bool fast_waypoint, float dt, Vector3f &target_pos, Vector3f &target_vel, Vector3f &target_accel) WARN_IF_UNUSED; // time has reached the end of the sequence bool finished() const WARN_IF_UNUSED; @@ -127,6 +129,12 @@ class SCurve { // return true if the sequence is braking to a stop bool braking() const WARN_IF_UNUSED; + // return time offset used to initiate the turn onto leg + float time_turn_in() const WARN_IF_UNUSED; + + // return time offset used to initiate the turn from leg + float time_turn_out() const WARN_IF_UNUSED; + // increment the internal time void advance_time(float dt); @@ -146,16 +154,16 @@ class SCurve { void add_segments(float L); // generate three time segments forming the jerk profile - void add_segments_jerk(uint8_t &seg_pnt, float tj, float Jm, float Tcj); + void add_segments_jerk(uint8_t &seg_pnt, float Jm, float tj, float Tcj); // generate constant jerk time segment - void add_segment_const_jerk(uint8_t &seg_pnt, float tin, float J0); + void add_segment_const_jerk(uint8_t &seg_pnt, float J0, float tin); // generate increasing jerk magnitude time segment based on a raised cosine profile - void add_segment_incr_jerk(uint8_t &seg_pnt, float tj, float Jm); + void add_segment_incr_jerk(uint8_t &seg_pnt, float Jm, float tj); // generate decreasing jerk magnitude time segment based on a raised cosine profile - void add_segment_decr_jerk(uint8_t &seg_pnt, float tj, float Jm); + void add_segment_decr_jerk(uint8_t &seg_pnt, float Jm, float tj); // set speed and acceleration limits for the path // origin and destination are offsets from EKF origin @@ -183,7 +191,7 @@ class SCurve { void add_segment(uint8_t &seg_pnt, float end_time, SegmentType seg_type, float jerk_ref, float end_accel, float end_vel, float end_pos); // members - float jerk_time; // duration of jerk raised cosine time segment + float snap_max; // maximum snap magnitude float jerk_max; // maximum jerk magnitude float accel_max; // maximum acceleration magnitude float vel_max; // maximum velocity magnitude diff --git a/libraries/AP_Math/benchmarks/benchmark_geodesic_grid.cpp b/libraries/AP_Math/benchmarks/benchmark_geodesic_grid.cpp index 357998eb0b8..71da640b0a7 100644 --- a/libraries/AP_Math/benchmarks/benchmark_geodesic_grid.cpp +++ b/libraries/AP_Math/benchmarks/benchmark_geodesic_grid.cpp @@ -18,6 +18,8 @@ #include +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); + static const Vector3f triangles[20][3] = { {{-M_GOLDEN, 1, 0}, {-1, 0,-M_GOLDEN}, {-M_GOLDEN,-1, 0}}, {{-1, 0,-M_GOLDEN}, {-M_GOLDEN,-1, 0}, { 0,-M_GOLDEN,-1}}, diff --git a/libraries/AP_Math/benchmarks/benchmark_matrix.cpp b/libraries/AP_Math/benchmarks/benchmark_matrix.cpp index 01c04dd783c..d14b3cbbe0a 100644 --- a/libraries/AP_Math/benchmarks/benchmark_matrix.cpp +++ b/libraries/AP_Math/benchmarks/benchmark_matrix.cpp @@ -2,6 +2,8 @@ #include +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); + static void BM_MatrixMultiplication(benchmark::State& state) { Matrix3f m1(Vector3f(1.0f, 2.0f, 3.0f), diff --git a/libraries/AP_Math/chirp.cpp b/libraries/AP_Math/chirp.cpp new file mode 100644 index 00000000000..b01250bca6b --- /dev/null +++ b/libraries/AP_Math/chirp.cpp @@ -0,0 +1,87 @@ +/* + * chirp.cpp + * + * Copyright (C) Leonard Hall 2020 + * + * This file is free software: you can redistribute it and/or modify it + * under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program. If not, see . + */ + +/* +* This object generates a chirp signal based on the input variables. A chirp is +* a sine wave starting from the minimum frequency and ending at the maximum frequency. +* The progression in frequency is not linear but designed to increase exponentially. +* The chirp can be designed to dwell at the minimum frequency for a specified time +* before sweeping through the frequencies and also can fade in the magnitude at the +* beginning and fade out the magnitude at the end. This object can also generate +* constant frequency sine waves by setting the minimum and maximum frequency to the +* same value. +*/ +#include +#include "chirp.h" + +// constructor +Chirp::Chirp() {} + +// initializes the chirp object +void Chirp::init(float time_record, float frequency_start_hz, float frequency_stop_hz, float time_fade_in, float time_fade_out, float time_const_freq) +{ + // pass in variables to class + record = time_record; + wMin = M_2PI * frequency_start_hz; + wMax = M_2PI * frequency_stop_hz; + fade_in = time_fade_in; + fade_out = time_fade_out; + const_freq = time_const_freq; + + B = logf(wMax / wMin); + +} + +// determine chirp signal output at the specified time and amplitude +float Chirp::update(float time, float waveform_magnitude) +{ + magnitude = waveform_magnitude; + if (time <= 0.0f) { + window = 0.0f; + } else if (time <= fade_in) { + window = 0.5 - 0.5 * cosf(M_PI * time / fade_in); + } else if (time <= record - fade_out) { + window = 1.0; + } else if (time <= record) { + window = 0.5 - 0.5 * cosf(M_PI * (time - (record - fade_out)) / fade_out + M_PI); + } else { + window = 0.0; + } + + if (time <= 0.0f) { + waveform_freq_rads = wMin; + output = 0.0f; + } else if (time <= const_freq) { + waveform_freq_rads = wMin; + output = window * magnitude * sinf(wMin * time - wMin * const_freq); + } else if (time <= record) { + // handles constant frequency dwells and chirps + if (is_equal(wMin, wMax)) { + waveform_freq_rads = wMin; + output = window * magnitude * sinf(wMin * time); + } else { + waveform_freq_rads = wMin * expf(B * (time - const_freq) / (record - const_freq)); + output = window * magnitude * sinf((wMin * (record - const_freq) / B) * (expf(B * (time - const_freq) / (record - const_freq)) - 1)); + } + } else { + waveform_freq_rads = wMax; + output = 0.0f; + } + return output; +} diff --git a/libraries/AP_Math/chirp.h b/libraries/AP_Math/chirp.h new file mode 100644 index 00000000000..23487e21e56 --- /dev/null +++ b/libraries/AP_Math/chirp.h @@ -0,0 +1,53 @@ +#pragma once + +class Chirp { + +public: + + // constructor + Chirp(); + + // initializes the chirp object + void init(float time_record, float frequency_start_hz, float frequency_stop_hz, float time_fade_in, float time_fade_out, float time_const_freq); + + // determine chirp signal output at the specified time and amplitude + float update(float time, float waveform_magnitude); + + // accessor for the current waveform frequency + float get_frequency_rads() {return waveform_freq_rads; } + +private: + // Total chirp length in seconds + float record; + + // Chirp oscillation amplitude + float magnitude; + + // Chirp start frequency in rad/s + float wMin; + + // Chirp end frequency in rad/s + float wMax; + + // Amplitude fade in time in seconds + float fade_in; + + // Amplitude fade out time in seconds + float fade_out; + + // Time that chirp will remain at the min frequency before increasing to max frequency + float const_freq; + + // frequency ratio + float B; + + // current waveform frequency in rad/s + float waveform_freq_rads; + + // current amplitude of chirp + float window; + + // output of chirp signal at the requested time + float output; + +}; diff --git a/libraries/AP_Math/control.cpp b/libraries/AP_Math/control.cpp index 54431e5d6cb..c75e4249707 100644 --- a/libraries/AP_Math/control.cpp +++ b/libraries/AP_Math/control.cpp @@ -33,11 +33,17 @@ // vel_error - specifies the direction of the velocity error used in limit handling. void update_vel_accel(float& vel, float accel, float dt, float limit, float vel_error) { - const float delta_vel = accel * dt; + float delta_vel = accel * dt; // do not add delta_vel if it will increase the velocity error in the direction of limit - if (!(is_positive(delta_vel * limit) && is_positive(vel_error * limit))){ - vel += delta_vel; + // unless adding delta_vel will reduce vel towards zero + if (is_positive(delta_vel * limit) && is_positive(vel_error * limit)) { + if (is_negative(vel * limit)) { + delta_vel = constrain_float(delta_vel, -fabsf(vel), fabsf(vel)); + } else { + delta_vel = 0.0; + } } + vel += delta_vel; } // update_pos_vel_accel - single axis projection of position and velocity forward in time based on a time step of dt and acceleration of accel. @@ -49,9 +55,10 @@ void update_pos_vel_accel(postype_t& pos, float& vel, float accel, float dt, flo // move position and velocity forward by dt if it does not increase error when limited. float delta_pos = vel * dt + accel * 0.5f * sq(dt); // do not add delta_pos if it will increase the velocity error in the direction of limit - if (!(is_positive(delta_pos * limit) && is_positive(pos_error * limit))){ - pos += delta_pos; + if (is_positive(delta_pos * limit) && is_positive(pos_error * limit)) { + delta_pos = 0.0; } + pos += delta_pos; update_vel_accel(vel, accel, dt, limit, vel_error); } @@ -63,13 +70,12 @@ void update_pos_vel_accel(postype_t& pos, float& vel, float accel, float dt, flo void update_vel_accel_xy(Vector2f& vel, const Vector2f& accel, float dt, const Vector2f& limit, const Vector2f& vel_error) { // increase velocity by acceleration * dt if it does not increase error when limited. + // unless adding delta_vel will reduce the magnitude of vel Vector2f delta_vel = accel * dt; if (!limit.is_zero() && !delta_vel.is_zero()) { // check if delta_vel will increase the velocity error in the direction of limit - if (is_positive(delta_vel * limit) && is_positive(vel_error * limit)) { - // remove component of delta_vel in direction of limit - Vector2f limit_unit = limit.normalized(); - delta_vel -= limit_unit * (limit_unit * delta_vel); + if (is_positive(delta_vel * limit) && is_positive(vel_error * limit) && !is_negative(vel * limit)) { + delta_vel.zero(); } } vel += delta_vel; @@ -99,34 +105,42 @@ void update_pos_vel_accel_xy(Vector2p& pos, Vector2f& vel, const Vector2f& accel /* shape_accel calculates a jerk limited path from the current acceleration to an input acceleration. The function takes the current acceleration and calculates the required jerk limited adjustment to the acceleration for the next time dt. The kinematic path is constrained by : - acceleration limits - accel_min, accel_max, - time constant - tc. - The time constant defines the acceleration error decay in the kinematic path as the system approaches constant acceleration. - The time constant also defines the time taken to achieve the maximum acceleration. - The time constant must be positive. + maximum jerk - jerk_max (must be positive). The function alters the variable accel to follow a jerk limited kinematic path to accel_input. */ void shape_accel(float accel_input, float& accel, float jerk_max, float dt) { + // sanity check jerk_max + if (!is_positive(jerk_max)) { + INTERNAL_ERROR(AP_InternalError::error_t::invalid_arg_or_result); + return; + } + // jerk limit acceleration change - float accel_delta = accel_input - accel; - if (is_positive(jerk_max)) { + if (is_positive(dt)) { + float accel_delta = accel_input - accel; accel_delta = constrain_float(accel_delta, -jerk_max * dt, jerk_max * dt); + accel += accel_delta; } - accel += accel_delta; } // 2D version void shape_accel_xy(const Vector2f& accel_input, Vector2f& accel, float jerk_max, float dt) { + // sanity check jerk_max + if (!is_positive(jerk_max)) { + INTERNAL_ERROR(AP_InternalError::error_t::invalid_arg_or_result); + return; + } + // jerk limit acceleration change - Vector2f accel_delta = accel_input - accel; - if (is_positive(jerk_max)) { + if (is_positive(dt)) { + Vector2f accel_delta = accel_input - accel; accel_delta.limit_length(jerk_max * dt); + accel = accel + accel_delta; } - accel = accel + accel_delta; } void shape_accel_xy(const Vector3f& accel_input, Vector3f& accel, @@ -143,22 +157,19 @@ void shape_accel_xy(const Vector3f& accel_input, Vector3f& accel, /* shape_vel_accel and shape_vel_xy calculate a jerk limited path from the current position, velocity and acceleration to an input velocity. The function takes the current position, velocity, and acceleration and calculates the required jerk limited adjustment to the acceleration for the next time dt. The kinematic path is constrained by : - maximum velocity - vel_max, - maximum acceleration - accel_max, - time constant - tc. - The time constant defines the acceleration error decay in the kinematic path as the system approaches constant acceleration. - The time constant also defines the time taken to achieve the maximum acceleration. - The time constant must be positive. + minimum acceleration - accel_min (must be negative), + maximum acceleration - accel_max (must be positive), + maximum jerk - jerk_max (must be positive). The function alters the variable accel to follow a jerk limited kinematic path to vel_input and accel_input. - The accel_max limit can be removed by setting it to zero. + The correction acceleration is limited from accel_min to accel_max. If limit_total is true the target acceleration is limited from accel_min to accel_max. */ void shape_vel_accel(float vel_input, float accel_input, float vel, float& accel, float accel_min, float accel_max, float jerk_max, float dt, bool limit_total_accel) { - // sanity check accel_max - if (!(is_negative(accel_min) && is_positive(accel_max))) { + // sanity check accel_min, accel_max and jerk_max. + if (!is_negative(accel_min) || !is_positive(accel_max) || !is_positive(jerk_max)) { INTERNAL_ERROR(AP_InternalError::error_t::invalid_arg_or_result); return; } @@ -199,8 +210,8 @@ void shape_vel_accel_xy(const Vector2f& vel_input, const Vector2f& accel_input, const Vector2f& vel, Vector2f& accel, float accel_max, float jerk_max, float dt, bool limit_total_accel) { - // sanity check accel_max - if (!is_positive(accel_max)) { + // sanity check accel_max and jerk_max. + if (!is_positive(accel_max) || !is_positive(jerk_max)) { INTERNAL_ERROR(AP_InternalError::error_t::invalid_arg_or_result); return; } @@ -223,7 +234,7 @@ void shape_vel_accel_xy(const Vector2f& vel_input, const Vector2f& accel_input, float accel_dir = vel_input_unit * accel_target; Vector2f accel_cross = accel_target - (vel_input_unit * accel_dir); - // ensure 1/sqrt(2) of maximum acceleration is availible to correct cross component + // ensure 1/sqrt(2) of maximum acceleration is available to correct cross component // relative to vel_input if (sq(accel_dir) <= accel_cross.length_squared()) { // accel_target can be simply limited in magnitude @@ -252,28 +263,27 @@ void shape_vel_accel_xy(const Vector2f& vel_input, const Vector2f& accel_input, /* shape_pos_vel_accel calculate a jerk limited path from the current position, velocity and acceleration to an input position and velocity. The function takes the current position, velocity, and acceleration and calculates the required jerk limited adjustment to the acceleration for the next time dt. The kinematic path is constrained by : - maximum velocity - vel_max, - maximum acceleration - accel_max, - time constant - tc. - The time constant defines the acceleration error decay in the kinematic path as the system approaches constant acceleration. - The time constant also defines the time taken to achieve the maximum acceleration. - The time constant must be positive. + minimum velocity - vel_min (must not be positive), + maximum velocity - vel_max (must not be negative), + minimum acceleration - accel_min (must be negative), + maximum acceleration - accel_max (must be positive), + maximum jerk - jerk_max (must be positive). The function alters the variable accel to follow a jerk limited kinematic path to pos_input, vel_input and accel_input. - The vel_max, vel_correction_max, and accel_max limits can be removed by setting the desired limit to zero. + The correction velocity is limited to vel_max to vel_min. If limit_total is true the target velocity is limited to vel_max to vel_min. + The correction acceleration is limited from accel_min to accel_max. If limit_total is true the target acceleration is limited from accel_min to accel_max. */ void shape_pos_vel_accel(postype_t pos_input, float vel_input, float accel_input, postype_t pos, float vel, float& accel, float vel_min, float vel_max, float accel_min, float accel_max, - float jerk_max, float dt, bool limit_total_accel) + float jerk_max, float dt, bool limit_total) { - // sanity check accel_max - if (!(is_negative(accel_min) && is_positive(accel_max))) { + // sanity check vel_min, vel_max, accel_min, accel_max and jerk_max. + if (is_positive(vel_min) || is_negative(vel_max) || !is_negative(accel_min) || !is_positive(accel_max) || !is_positive(jerk_max)) { INTERNAL_ERROR(AP_InternalError::error_t::invalid_arg_or_result); return; } - // position error to be corrected float pos_error = pos_input - pos; @@ -294,25 +304,30 @@ void shape_pos_vel_accel(postype_t pos_input, float vel_input, float accel_input // velocity to correct position float vel_target = sqrt_controller(pos_error, KPv, accel_tc_max, dt); - // limit velocity to vel_max - if (is_negative(vel_min) && is_positive(vel_max)){ + // limit velocity between vel_min and vel_max + if (is_negative(vel_min) || is_positive(vel_max)) { vel_target = constrain_float(vel_target, vel_min, vel_max); } // velocity correction with input velocity vel_target += vel_input; - shape_vel_accel(vel_target, accel_input, vel, accel, accel_min, accel_max, jerk_max, dt, limit_total_accel); + // limit velocity between vel_min and vel_max + if (limit_total) { + vel_target = constrain_float(vel_target, vel_min, vel_max); + } + + shape_vel_accel(vel_target, accel_input, vel, accel, accel_min, accel_max, jerk_max, dt, limit_total); } // 2D version void shape_pos_vel_accel_xy(const Vector2p& pos_input, const Vector2f& vel_input, const Vector2f& accel_input, const Vector2p& pos, const Vector2f& vel, Vector2f& accel, float vel_max, float accel_max, - float jerk_max, float dt, bool limit_total_accel) + float jerk_max, float dt, bool limit_total) { - // sanity check accel_max - if (!is_positive(accel_max)) { + // sanity check vel_max, accel_max and jerk_max. + if (is_negative(vel_max) || !is_positive(accel_max) || !is_positive(jerk_max)) { INTERNAL_ERROR(AP_InternalError::error_t::invalid_arg_or_result); return; } @@ -329,16 +344,19 @@ void shape_pos_vel_accel_xy(const Vector2p& pos_input, const Vector2f& vel_input Vector2f vel_target = sqrt_controller(pos_error, KPv, accel_tc_max, dt); // limit velocity to vel_max - if (is_negative(vel_max)) { - INTERNAL_ERROR(AP_InternalError::error_t::invalid_arg_or_result); - } else if (is_positive(vel_max)) { + if (is_positive(vel_max)) { vel_target.limit_length(vel_max); } // velocity correction with input velocity vel_target = vel_target + vel_input; + + // limit velocity to vel_max + if (limit_total) { + vel_target.limit_length(vel_max); + } - shape_vel_accel_xy(vel_target, accel_input, vel, accel, accel_max, jerk_max, dt, limit_total_accel); + shape_vel_accel_xy(vel_target, accel_input, vel, accel, accel_max, jerk_max, dt, limit_total); } /* limit_accel_xy limits the acceleration to prioritise acceleration perpendicular to the provided velocity vector. @@ -406,7 +424,7 @@ float sqrt_controller(float error, float p, float second_ord_lim, float dt) correction_rate = error * p; } } - if (!is_zero(dt)) { + if (is_positive(dt)) { // this ensures we do not get small oscillations by over shooting the error correction in the last time step. return constrain_float(correction_rate, -fabsf(error) / dt, fabsf(error) / dt); } else { @@ -507,3 +525,46 @@ float input_expo(float input, float expo) } return input; } + +// angle_to_accel converts a maximum lean angle in degrees to an accel limit in m/s/s +float angle_to_accel(float angle_deg) +{ + return GRAVITY_MSS * tanf(radians(angle_deg)); +} + +// accel_to_angle converts a maximum accel in m/s/s to a lean angle in degrees +float accel_to_angle(float accel) +{ + return degrees(atanf((accel/GRAVITY_MSS))); +} + +// rc_input_to_roll_pitch - transform pilot's normalised roll or pitch stick input into a roll and pitch euler angle command +// roll_in_unit and pitch_in_unit - are normalised roll and pitch stick input +// angle_max_deg - maximum lean angle from the z axis +// angle_limit_deg - provides the ability to reduce the maximum output lean angle to less than angle_max_deg +// returns roll and pitch angle in degrees +void rc_input_to_roll_pitch(float roll_in_unit, float pitch_in_unit, float angle_max_deg, float angle_limit_deg, float &roll_out_deg, float &pitch_out_deg) +{ + angle_max_deg = MIN(angle_max_deg, 85.0); + float rc_2_rad = radians(angle_max_deg); + + // fetch roll and pitch stick positions and convert them to normalised horizontal thrust + Vector2f thrust; + thrust.x = - tanf(rc_2_rad * pitch_in_unit); + thrust.y = tanf(rc_2_rad * roll_in_unit); + + // calculate the horizontal thrust limit based on the angle limit + angle_limit_deg = constrain_float(angle_limit_deg, 10.0f, angle_max_deg); + float thrust_limit = tanf(radians(angle_limit_deg)); + + // apply horizontal thrust limit + thrust.limit_length(thrust_limit); + + // Conversion from angular thrust vector to euler angles. + float pitch_rad = - atanf(thrust.x); + float roll_rad = atanf(cosf(pitch_rad) * thrust.y); + + // Convert to degrees + roll_out_deg = degrees(roll_rad); + pitch_out_deg = degrees(pitch_rad); +} diff --git a/libraries/AP_Math/control.h b/libraries/AP_Math/control.h index 3ef5b0321b5..142791c46b9 100644 --- a/libraries/AP_Math/control.h +++ b/libraries/AP_Math/control.h @@ -1,6 +1,5 @@ #pragma once -#include #include #include "vector2.h" #include "vector3.h" @@ -52,11 +51,7 @@ void update_pos_vel_accel_xy(Vector2p& pos, Vector2f& vel, const Vector2f& accel /* shape_accel calculates a jerk limited path from the current acceleration to an input acceleration. The function takes the current acceleration and calculates the required jerk limited adjustment to the acceleration for the next time dt. The kinematic path is constrained by : - acceleration limits - accel_min, accel_max, - time constant - tc. - The time constant defines the acceleration error decay in the kinematic path as the system approaches constant acceleration. - The time constant also defines the time taken to achieve the maximum acceleration. - The time constant must be positive. + maximum jerk - jerk_max (must be positive). The function alters the variable accel to follow a jerk limited kinematic path to accel_input. */ void shape_accel(float accel_input, float& accel, @@ -72,14 +67,11 @@ void shape_accel_xy(const Vector3f& accel_input, Vector3f& accel, /* shape_vel_accel and shape_vel_xy calculate a jerk limited path from the current position, velocity and acceleration to an input velocity. The function takes the current position, velocity, and acceleration and calculates the required jerk limited adjustment to the acceleration for the next time dt. The kinematic path is constrained by : - maximum velocity - vel_max, - maximum acceleration - accel_max, - time constant - tc. - The time constant defines the acceleration error decay in the kinematic path as the system approaches constant acceleration. - The time constant also defines the time taken to achieve the maximum acceleration. - The time constant must be positive. + minimum acceleration - accel_min (must be negative), + maximum acceleration - accel_max (must be positive), + maximum jerk - jerk_max (must be positive). The function alters the variable accel to follow a jerk limited kinematic path to vel_input and accel_input. - The accel_max limit can be removed by setting it to zero. + The correction acceleration is limited from accel_min to accel_max. If limit_total is true the target acceleration is limited from accel_min to accel_max. */ void shape_vel_accel(float vel_input, float accel_input, float vel, float& accel, @@ -94,26 +86,27 @@ void shape_vel_accel_xy(const Vector2f& vel_input1, const Vector2f& accel_input, /* shape_pos_vel_accel calculate a jerk limited path from the current position, velocity and acceleration to an input position and velocity. The function takes the current position, velocity, and acceleration and calculates the required jerk limited adjustment to the acceleration for the next time dt. The kinematic path is constrained by : - maximum velocity - vel_max, - maximum acceleration - accel_max, - time constant - tc. - The time constant defines the acceleration error decay in the kinematic path as the system approaches constant acceleration. - The time constant also defines the time taken to achieve the maximum acceleration. - The time constant must be positive. + minimum velocity - vel_min (must be negative), + maximum velocity - vel_max (must be positive), + minimum acceleration - accel_min (must be negative), + maximum acceleration - accel_max (must be positive), + maximum jerk - jerk_max (must be positive). The function alters the variable accel to follow a jerk limited kinematic path to pos_input, vel_input and accel_input. - The vel_max, vel_correction_max, and accel_max limits can be removed by setting the desired limit to zero. + The correction velocity is limited to vel_max to vel_min. If limit_total is true the target velocity is limited to vel_max to vel_min. + The correction acceleration is limited from accel_min to accel_max. If limit_total is true the target acceleration is limited from accel_min to accel_max. */ void shape_pos_vel_accel(const postype_t pos_input, float vel_input, float accel_input, const postype_t pos, float vel, float& accel, float vel_min, float vel_max, float accel_min, float accel_max, - float jerk_max, float dt, bool limit_total_accel); + float jerk_max, float dt, bool limit_total); // 2D version void shape_pos_vel_accel_xy(const Vector2p& pos_input, const Vector2f& vel_input, const Vector2f& accel_input, const Vector2p& pos, const Vector2f& vel, Vector2f& accel, float vel_max, float accel_max, - float jerk_max, float dt, bool limit_total_accel); + float jerk_max, float dt, bool limit_total); + /* limit_accel_xy limits the acceleration to prioritise acceleration perpendicular to the provided velocity vector. Input parameters are: @@ -145,3 +138,16 @@ float kinematic_limit(Vector3f direction, float max_xy, float max_z_pos, float m // The input must be in the range of -1 to 1. // The expo should be less than 1.0 but limited to be less than 0.95. float input_expo(float input, float expo); + +// angle_to_accel converts a maximum lean angle in degrees to an accel limit in m/s/s +float angle_to_accel(float angle_deg); + +// accel_to_angle converts a maximum accel in m/s/s to a lean angle in degrees +float accel_to_angle(float accel); + +// rc_input_to_roll_pitch - transform pilot's normalised roll or pitch stick input into a roll and pitch euler angle command +// roll_in_unit and pitch_in_unit - are normalised roll and pitch stick inputs +// angle_max_deg - maximum lean angle from the z axis +// angle_limit_deg - provides the ability to reduce the maximum output lean angle to less than angle_max_deg +// returns roll and pitch euler angles in degrees +void rc_input_to_roll_pitch(float roll_in_unit, float pitch_in_unit, float angle_max_deg, float angle_limit_deg, float &roll_out_deg, float &pitch_out_deg); diff --git a/libraries/AP_Math/definitions.h b/libraries/AP_Math/definitions.h index 0f2c5d3b840..446c92fd78b 100644 --- a/libraries/AP_Math/definitions.h +++ b/libraries/AP_Math/definitions.h @@ -2,7 +2,7 @@ #include -#include +#include #ifdef M_PI # undef M_PI @@ -117,3 +117,6 @@ static const double WGS84_E = (sqrt(2 * WGS84_F - WGS84_F * WGS84_F)); // Amps microseconds to milliamp hours #define AUS_TO_MAH 0.0000002778f + +// kg/m^3 to g/cm^3 +#define KG_PER_M3_TO_G_PER_CM3(x) (0.001 * x) diff --git a/libraries/AP_Math/examples/rotations/rotations.cpp b/libraries/AP_Math/examples/rotations/rotations.cpp index fb3095890fc..e181597f04c 100644 --- a/libraries/AP_Math/examples/rotations/rotations.cpp +++ b/libraries/AP_Math/examples/rotations/rotations.cpp @@ -4,6 +4,9 @@ #include #include +#include + +AP_CustomRotations cust_rot; void setup(); void loop(); @@ -165,9 +168,9 @@ static void test_euler(enum Rotation rotation, float roll, float pitch, float ya float q_roll, q_pitch, q_yaw, qe_roll, qe_pitch, qe_yaw; q.to_euler(q_roll, q_pitch, q_yaw); qe.to_euler(qe_roll, qe_pitch, qe_yaw); - const float roll_diff = fabsf(wrap_PI(q_roll - qe_roll)); - const float pitch_diff = fabsf(wrap_PI(q_pitch - qe_pitch)); - const float yaw_diff = fabsf(wrap_PI(q_yaw - qe_yaw)); + float roll_diff = fabsf(wrap_PI(q_roll - qe_roll)); + float pitch_diff = fabsf(wrap_PI(q_pitch - qe_pitch)); + float yaw_diff = fabsf(wrap_PI(q_yaw - qe_yaw)); if ((roll_diff > q_accuracy) || (pitch_diff > q_accuracy) || (yaw_diff > q_accuracy)) { hal.console->printf("quaternion test %u failed : yaw:%f/%f roll:%f/%f pitch:%f/%f\n", (unsigned)rotation, @@ -175,6 +178,36 @@ static void test_euler(enum Rotation rotation, float roll, float pitch, float ya (double)q_roll,(double)qe_roll, (double)q_pitch,(double)qe_pitch); } + + // test custom rotations + AP::custom_rotations().set(ROTATION_CUSTOM_1, roll, pitch, yaw); + v1 = v; + v1.rotate(ROTATION_CUSTOM_1); + + diff = (v2 - v1); + if (diff.length() > accuracy) { + hal.console->printf("euler test %u failed : yaw:%d roll:%d pitch:%d\n", + (unsigned)rotation, + (int)yaw, + (int)roll, + (int)pitch); + hal.console->printf("custom rotated: "); + print_vector(v1); + hal.console->printf("correct rotated: "); + print_vector(v2); + hal.console->printf("\n"); + } + + Quaternion qc; + qc.from_rotation(ROTATION_CUSTOM_1); + float qc_roll, qc_pitch, qc_yaw; + qc.to_euler(qc_roll, qc_pitch, qc_yaw); + roll_diff = fabsf(wrap_PI(qc_roll - qe_roll)); + pitch_diff = fabsf(wrap_PI(qc_pitch - qe_pitch)); + yaw_diff = fabsf(wrap_PI(qc_yaw - qe_yaw)); + if ((roll_diff > q_accuracy) || (pitch_diff > q_accuracy) || (yaw_diff > q_accuracy)) { + hal.console->printf("custom quaternion test %u failed\n", (unsigned)rotation); + } } static void test_rotate_inverse(void) diff --git a/libraries/AP_Math/ftype.h b/libraries/AP_Math/ftype.h index 04cf0b50279..d2095df1047 100644 --- a/libraries/AP_Math/ftype.h +++ b/libraries/AP_Math/ftype.h @@ -5,6 +5,7 @@ */ #include +#include /* capital F is used to denote the chosen float type (float or double) diff --git a/libraries/AP_Math/matrixN.h b/libraries/AP_Math/matrixN.h index 82605fa54b4..5cb604b275d 100644 --- a/libraries/AP_Math/matrixN.h +++ b/libraries/AP_Math/matrixN.h @@ -19,12 +19,12 @@ class MatrixN { public: // constructor from zeros - MatrixN(void) { + MatrixN(void) { memset(v, 0, sizeof(v)); } // constructor from 4 diagonals - MatrixN(const float d[N]) { + MatrixN(const float d[N]) { memset(v, 0, sizeof(v)); for (uint8_t i = 0; i < N; i++) { v[i][i] = d[i]; diff --git a/libraries/AP_Math/quaternion.cpp b/libraries/AP_Math/quaternion.cpp index 93918818b5d..99d9c0824e2 100644 --- a/libraries/AP_Math/quaternion.cpp +++ b/libraries/AP_Math/quaternion.cpp @@ -18,8 +18,11 @@ #pragma GCC optimize("O2") +#include "quaternion.h" #include "AP_Math.h" #include +#include +#include #define HALF_SQRT_2_PlUS_SQRT_2 0.92387953251128673848313610506011 // sqrt(2 + sqrt(2)) / 2 #define HALF_SQRT_2_MINUS_SQTR_2 0.38268343236508972626808144923416 // sqrt(2 - sqrt(2)) / 2 @@ -376,12 +379,16 @@ void QuaternionT::from_rotation(enum Rotation rotation) q3 = q4 = 0.0; return; - case ROTATION_CUSTOM: - // Error; custom rotations not supported - INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + case ROTATION_CUSTOM_1: + case ROTATION_CUSTOM_2: +#if !APM_BUILD_TYPE(APM_BUILD_AP_Periph) + // Do not support custom rotations on Periph + AP::custom_rotations().from_rotation(rotation, *this); return; - +#endif case ROTATION_MAX: + case ROTATION_CUSTOM_OLD: + case ROTATION_CUSTOM_END: break; } // rotation invalid diff --git a/libraries/AP_Math/quaternion.h b/libraries/AP_Math/quaternion.h index e73eeaa2976..3ee535476e2 100644 --- a/libraries/AP_Math/quaternion.h +++ b/libraries/AP_Math/quaternion.h @@ -17,6 +17,8 @@ // Refactored by Jonathan Challinger #pragma once +#include "definitions.h" +#include "matrix3.h" #include #if MATH_CHECK_INDEXES #include @@ -30,20 +32,20 @@ class QuaternionT { // constructor creates a quaternion equivalent // to roll=0, pitch=0, yaw=0 - QuaternionT() + QuaternionT() { q1 = 1; q2 = q3 = q4 = 0; } // setting constructor - QuaternionT(const T _q1, const T _q2, const T _q3, const T _q4) : + QuaternionT(const T _q1, const T _q2, const T _q3, const T _q4) : q1(_q1), q2(_q2), q3(_q3), q4(_q4) { } // setting constructor - QuaternionT(const T _q[4]) : + QuaternionT(const T _q[4]) : q1(_q[0]), q2(_q[1]), q3(_q[2]), q4(_q[3]) { } diff --git a/libraries/AP_Math/rotations.h b/libraries/AP_Math/rotations.h index d7b4dabbbaa..042ac090337 100644 --- a/libraries/AP_Math/rotations.h +++ b/libraries/AP_Math/rotations.h @@ -76,7 +76,10 @@ enum Rotation : uint8_t { // to the MAVLink messages as well. /////////////////////////////////////////////////////////////////////// ROTATION_MAX, - ROTATION_CUSTOM = 100, + ROTATION_CUSTOM_OLD = 100, + ROTATION_CUSTOM_1 = 101, + ROTATION_CUSTOM_2 = 102, + ROTATION_CUSTOM_END, }; @@ -87,5 +90,5 @@ enum Rotation : uint8_t { Here are the same values in a form suitable for a @Values attribute in auto documentation: -@Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Roll180Yaw45,10:Roll180Yaw90,11:Roll180Yaw135,12:Pitch180,13:Roll180Yaw225,14:Roll180Yaw270,15:Roll180Yaw315,16:Roll90,17:Roll90Yaw45,18:Roll90Yaw90,19:Roll90Yaw135,20:Roll270,21:Roll270Yaw45,22:Roll270Yaw90,23:Roll270Yaw135,24:Pitch90,25:Pitch270,26:Pitch180Yaw90,27:Pitch180Yaw270,28:Roll90Pitch90,29:Roll180Pitch90,30:Roll270Pitch90,31:Roll90Pitch180,32:Roll270Pitch180,33:Roll90Pitch270,34:Roll180Pitch270,35:Roll270Pitch270,36:Roll90Pitch180Yaw90,37:Roll90Yaw270,38:Yaw293Pitch68Roll180,39:Pitch315,40:Roll90Pitch315,42:Roll45,43:Roll315,100:Custom +@Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Yaw45Roll180,10:Yaw90Roll180,11:Yaw135Roll180,12:Pitch180,13:Yaw225Roll180,14:Yaw270Roll180,15:Yaw315Roll180,16:Roll90,17:Yaw45Roll90,18:Yaw90Roll90,19:Yaw135Roll90,20:Roll270,21:Yaw45Roll270,22:Yaw90Roll270,23:Yaw135Roll270,24:Pitch90,25:Pitch270,26:Yaw90Pitch180,27:Yaw270Pitch180,28:Pitch90Roll90,29:Pitch90Roll180,30:Pitch90Roll270,31:Pitch180Roll90,32:Pitch180Roll270,33:Pitch270Roll90,34:Pitch270Roll180,35:Pitch270Roll270,36:Yaw90Pitch180Roll90,37:Yaw270Roll90,38:Yaw293Pitch68Roll180,39:Pitch315,40:Pitch315Roll90,42:Roll45,43:Roll315,100:Custom 4.1 and older,101:Custom 1,102:Custom 2 */ diff --git a/libraries/AP_Math/tests/test_3d_lines.cpp b/libraries/AP_Math/tests/test_3d_lines.cpp index da8c1cfbcb5..0d41064f98d 100644 --- a/libraries/AP_Math/tests/test_3d_lines.cpp +++ b/libraries/AP_Math/tests/test_3d_lines.cpp @@ -26,7 +26,7 @@ TEST(Lines3dTests, ClosestDistBetweenLinePoint) // check protection agains null length const Vector3f intersection_null = Vector3f::point_on_line_closest_to_other_point(Vector3f{1.0f, 1.0f, 1.0f}, Vector3f{1.0f, 1.0f, 1.0f}, Vector3f{0.0f, 5.0f, 5.0f}); - EXPECT_VECTOR3F_EQ((Vector3f{0.0f, 0.0f, 0.0f}), intersection_null); + EXPECT_VECTOR3F_EQ((Vector3f{1.0f, 1.0f, 1.0f}), intersection_null); } TEST(Lines3dTests, SegmentToSegmentCloestPoint) diff --git a/libraries/AP_Math/tests/test_control.cpp b/libraries/AP_Math/tests/test_control.cpp new file mode 100644 index 00000000000..217e23f382a --- /dev/null +++ b/libraries/AP_Math/tests/test_control.cpp @@ -0,0 +1,470 @@ +#include + +#include +#include +#include +#include + +TEST(Control, test_control) +{ + postype_t pos_start = 17; + float vel_start = 20; + float accel_start = 1.0; + const float dt = 0.01; + + // test for update_pos_vel_accel includes update_vel_accel. + // test unlimited behaviour + // 1 + float vel = vel_start; + postype_t pos = pos_start; + float accel = accel_start; + update_pos_vel_accel(pos, vel, accel, dt, 0.0, 0.0, 0.0); + EXPECT_FLOAT_EQ(vel, vel_start + accel * dt); + EXPECT_FLOAT_EQ(pos, pos_start + vel_start * dt + 0.5 * accel * sq(dt)); + + // 2 + vel = vel_start; + pos = pos_start; + accel = -accel_start; + update_pos_vel_accel(pos, vel, accel, dt, 0.0, 0.0, 0.0); + EXPECT_FLOAT_EQ(vel, vel_start + accel * dt); + EXPECT_FLOAT_EQ(pos, pos_start + vel_start * dt + 0.5 * accel * sq(dt)); + + // error has no impact when not limited + // 3 + vel = vel_start; + pos = pos_start; + accel = accel_start; + update_pos_vel_accel(pos, vel, accel, dt, 0.0, 1.0, 1.0); + EXPECT_FLOAT_EQ(vel, vel_start + accel * dt); + EXPECT_FLOAT_EQ(pos, pos_start + vel_start * dt + 0.5 * accel * sq(dt)); + + // 4 + vel = vel_start; + pos = pos_start; + accel = accel_start; + update_pos_vel_accel(pos, vel, accel, dt, 0.0, -1.0, -1.0); + EXPECT_FLOAT_EQ(vel, vel_start + accel * dt); + EXPECT_FLOAT_EQ(pos, pos_start + vel_start * dt + 0.5 * accel * sq(dt)); + + // test unlimited behaviour + // zero error should result in normal behaviour + // 5 + vel = vel_start; + pos = pos_start; + accel = accel_start; + update_pos_vel_accel(pos, vel, accel, dt, 1.0, 0.0, 0.0); + EXPECT_FLOAT_EQ(vel, vel_start + accel * dt); + EXPECT_FLOAT_EQ(pos, pos_start + vel_start * dt + 0.5 * accel * sq(dt)); + + // 6 + vel = vel_start; + pos = pos_start; + accel = -accel_start; + update_pos_vel_accel(pos, vel, accel, dt, 1.0, 0.0, 0.0); + EXPECT_FLOAT_EQ(vel, vel_start + accel * dt); + EXPECT_FLOAT_EQ(pos, pos_start + vel_start * dt + 0.5 * accel * sq(dt)); + + // 7 + vel = vel_start; + pos = pos_start; + accel = accel_start; + update_pos_vel_accel(pos, vel, accel, dt, -1.0, 0.0, 0.0); + EXPECT_FLOAT_EQ(vel, vel_start + accel * dt); + EXPECT_FLOAT_EQ(pos, pos_start + vel_start * dt + 0.5 * accel * sq(dt)); + + // 8 + vel = vel_start; + pos = pos_start; + accel = -accel_start; + update_pos_vel_accel(pos, vel, accel, dt, -1.0, 0.0, 0.0); + EXPECT_FLOAT_EQ(vel, vel_start + accel * dt); + EXPECT_FLOAT_EQ(pos, pos_start + vel_start * dt + 0.5 * accel * sq(dt)); + + // error sign opposite to limit sign should result in normal behaviour + // 9 + vel = vel_start; + pos = pos_start; + accel = accel_start; + update_pos_vel_accel(pos, vel, accel, dt, 1.0, -1.0, -1.0); + EXPECT_FLOAT_EQ(vel, vel_start + accel * dt); + EXPECT_FLOAT_EQ(pos, pos_start + vel_start * dt + 0.5 * accel * sq(dt)); + + // 10 + vel = vel_start; + pos = pos_start; + accel = -accel_start; + update_pos_vel_accel(pos, vel, accel, dt, 1.0, -1.0, -1.0); + EXPECT_FLOAT_EQ(vel, vel_start + accel * dt); + EXPECT_FLOAT_EQ(pos, pos_start + vel_start * dt + 0.5 * accel * sq(dt)); + + // 11 + vel = vel_start; + pos = pos_start; + accel = accel_start; + update_pos_vel_accel(pos, vel, accel, dt, -1.0, 1.0, 1.0); + EXPECT_FLOAT_EQ(vel, vel_start + accel * dt); + EXPECT_FLOAT_EQ(pos, pos_start + vel_start * dt + 0.5 * accel * sq(dt)); + + // 12 + vel = vel_start; + pos = pos_start; + accel = -accel_start; + update_pos_vel_accel(pos, vel, accel, dt, -1.0, 1.0, 1.0); + EXPECT_FLOAT_EQ(vel, vel_start + accel * dt); + EXPECT_FLOAT_EQ(pos, pos_start + vel_start * dt + 0.5 * accel * sq(dt)); + + // error sign same as limit sign should result various limited behaviours + // 13 + vel = vel_start; + pos = pos_start; + accel = accel_start; + update_pos_vel_accel(pos, vel, accel, dt, 1.0, 1.0, 1.0); + // vel is not increased + EXPECT_FLOAT_EQ(vel, vel_start); + // pos is not increased + EXPECT_FLOAT_EQ(pos, pos_start); + + // 14 + vel = vel_start; + pos = pos_start; + accel = -accel_start; + update_pos_vel_accel(pos, vel, accel, dt, 1.0, 1.0, 1.0); + // vel is decreased + EXPECT_FLOAT_EQ(vel, vel_start + accel * dt); + // pos is not increased + EXPECT_FLOAT_EQ(pos, pos_start); + + // 15 + vel = vel_start; + pos = pos_start; + accel = accel_start; + update_pos_vel_accel(pos, vel, accel, dt, -1.0, -1.0, -1.0); + // vel is increased + EXPECT_FLOAT_EQ(vel, vel_start + accel * dt); + // pos is increased + EXPECT_FLOAT_EQ(pos, pos_start + vel_start * dt + 0.5 * accel * sq(dt)); + + // 16 + vel = vel_start; + pos = pos_start; + accel = -accel_start; + update_pos_vel_accel(pos, vel, accel, dt, -1.0, -1.0, -1.0); + // velocity is limited but limit is not applied because velocity is reducing + EXPECT_FLOAT_EQ(vel, vel_start + accel * dt); + // pos is increased + EXPECT_FLOAT_EQ(pos, pos_start + vel_start * dt + 0.5 * accel * sq(dt)); + + // 17 + vel = -vel_start; + pos = pos_start; + accel = accel_start; + update_pos_vel_accel(pos, vel, accel, dt, 1.0, 1.0, 1.0); + // velocity is limited but limit is not applied because velocity is reducing + EXPECT_FLOAT_EQ(vel, -vel_start + accel * dt); + // pos is decreased + EXPECT_FLOAT_EQ(pos, pos_start - vel_start * dt + 0.5 * accel * sq(dt)); + + // 18 + vel_start = 0.1 * accel_start * dt; + vel = vel_start; + pos = pos_start; + accel = -accel_start; + update_pos_vel_accel(pos, vel, accel, dt, -1.0, -1.0, -1.0); + // velocity is limited but limit is not applied because velocity is reducing + // final result is zero because velocity would change sign during dt + EXPECT_FLOAT_EQ(vel, 0.0); + // pos is not changed because is_negative(vel_start * dt + 0.5 * accel * sq(t)) + EXPECT_FLOAT_EQ(pos, pos_start); + + // 19 + vel = -vel_start; + pos = pos_start; + accel = accel_start; + update_pos_vel_accel(pos, vel, accel, dt, 1.0, 1.0, 1.0); + // velocity is limited but limit is not applied because velocity is reducing + // final result is zero because velocity would change sign during dt + EXPECT_FLOAT_EQ(vel, 0.0); + // pos is not changed because is_negative(vel_start * dt + 0.5 * accel * sq(t)) + EXPECT_FLOAT_EQ(pos, pos_start); + + + // test for update_pos_vel_accel includes update_vel_accel. + // test unlimited behaviour + + // 1 + pos_start = 17; + vel_start = 20; + accel_start = 1.0; + Vector2p posxy = Vector2p(pos_start, 0.0); + Vector2f velxy = Vector2f(vel_start, 0.0); + Vector2f accelxy = Vector2f(accel_start, 0.0); + Vector2f limit = Vector2f(0.0, 0.0); + Vector2f pos_error = Vector2f(0.0, 0.0); + Vector2f vel_error = Vector2f(0.0, 0.0); + update_pos_vel_accel_xy(posxy, velxy, accelxy, dt, limit, pos_error, vel_error); + EXPECT_FLOAT_EQ(velxy.x, vel_start + accelxy.x * dt); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + EXPECT_FLOAT_EQ(posxy.x, pos_start + vel_start * dt + 0.5 * accelxy.x * sq(dt)); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + + // 2 + posxy = Vector2p(pos_start, 0.0); + velxy = Vector2f(vel_start, 0.0); + accelxy = Vector2f(-accel_start, 0.0); + limit = Vector2f(0.0, 0.0); + pos_error = Vector2f(0.0, 0.0); + vel_error = Vector2f(0.0, 0.0); + update_pos_vel_accel_xy(posxy, velxy, accelxy, dt, limit, pos_error, vel_error); + EXPECT_FLOAT_EQ(velxy.x, vel_start + accelxy.x * dt); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + EXPECT_FLOAT_EQ(posxy.x, pos_start + vel_start * dt + 0.5 * accelxy.x * sq(dt)); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + + // error has no impact when not limited + // 3 + posxy = Vector2p(pos_start, 0.0); + velxy = Vector2f(vel_start, 0.0); + accelxy = Vector2f(accel_start, 0.0); + limit = Vector2f(0.0, 0.0); + pos_error = Vector2f(1.0, 0.0); + vel_error = Vector2f(1.0, 0.0); + update_pos_vel_accel_xy(posxy, velxy, accelxy, dt, limit, pos_error, vel_error); + EXPECT_FLOAT_EQ(velxy.x, vel_start + accelxy.x * dt); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + EXPECT_FLOAT_EQ(posxy.x, pos_start + vel_start * dt + 0.5 * accelxy.x * sq(dt)); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + + // 4 + posxy = Vector2p(pos_start, 0.0); + velxy = Vector2f(vel_start, 0.0); + accelxy = Vector2f(accel_start, 0.0); + limit = Vector2f(0.0, 0.0); + pos_error = Vector2f(0.0, 0.0); + vel_error = Vector2f(0.0, 0.0); + update_pos_vel_accel_xy(posxy, velxy, accelxy, dt, limit, pos_error, vel_error); + EXPECT_FLOAT_EQ(velxy.x, vel_start + accelxy.x * dt); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + EXPECT_FLOAT_EQ(posxy.x, pos_start + vel_start * dt + 0.5 * accelxy.x * sq(dt)); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + + // test unlimited behaviour + // zero error should result in normal behaviour + // 5 + posxy = Vector2p(pos_start, 0.0); + velxy = Vector2f(vel_start, 0.0); + accelxy = Vector2f(accel_start, 0.0); + limit = Vector2f(1.0, 0.0); + pos_error = Vector2f(0.0, 0.0); + vel_error = Vector2f(0.0, 0.0); + update_pos_vel_accel_xy(posxy, velxy, accelxy, dt, limit, pos_error, vel_error); + EXPECT_FLOAT_EQ(velxy.x, vel_start + accelxy.x * dt); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + EXPECT_FLOAT_EQ(posxy.x, pos_start + vel_start * dt + 0.5 * accelxy.x * sq(dt)); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + + // 6 + posxy = Vector2p(pos_start, 0.0); + velxy = Vector2f(vel_start, 0.0); + accelxy = Vector2f(-accel_start, 0.0); + limit = Vector2f(1.0, 0.0); + pos_error = Vector2f(0.0, 0.0); + vel_error = Vector2f(0.0, 0.0); + update_pos_vel_accel_xy(posxy, velxy, accelxy, dt, limit, pos_error, vel_error); + EXPECT_FLOAT_EQ(velxy.x, vel_start + accelxy.x * dt); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + EXPECT_FLOAT_EQ(posxy.x, pos_start + vel_start * dt + 0.5 * accelxy.x * sq(dt)); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + + // 7 + posxy = Vector2p(pos_start, 0.0); + velxy = Vector2f(vel_start, 0.0); + accelxy = Vector2f(accel_start, 0.0); + limit = Vector2f(1.0, 0.0); + pos_error = Vector2f(0.0, 0.0); + vel_error = Vector2f(0.0, 0.0); + update_pos_vel_accel_xy(posxy, velxy, accelxy, dt, limit, pos_error, vel_error); + EXPECT_FLOAT_EQ(velxy.x, vel_start + accelxy.x * dt); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + EXPECT_FLOAT_EQ(posxy.x, pos_start + vel_start * dt + 0.5 * accelxy.x * sq(dt)); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + + // 8 + posxy = Vector2p(pos_start, 0.0); + velxy = Vector2f(vel_start, 0.0); + accelxy = Vector2f(-accel_start, 0.0); + limit = Vector2f(1.0, 0.0); + pos_error = Vector2f(0.0, 0.0); + vel_error = Vector2f(0.0, 0.0); + update_pos_vel_accel_xy(posxy, velxy, accelxy, dt, limit, pos_error, vel_error); + EXPECT_FLOAT_EQ(velxy.x, vel_start + accelxy.x * dt); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + EXPECT_FLOAT_EQ(posxy.x, pos_start + vel_start * dt + 0.5 * accelxy.x * sq(dt)); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + + // error sign opposite to limit sign should result in normal behaviour + // 9 + posxy = Vector2p(pos_start, 0.0); + velxy = Vector2f(vel_start, 0.0); + accelxy = Vector2f(accel_start, 0.0); + limit = Vector2f(1.0, 0.0); + pos_error = Vector2f(-1.0, 0.0); + vel_error = Vector2f(-1.0, 0.0); + update_pos_vel_accel_xy(posxy, velxy, accelxy, dt, limit, pos_error, vel_error); + EXPECT_FLOAT_EQ(velxy.x, vel_start + accelxy.x * dt); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + EXPECT_FLOAT_EQ(posxy.x, pos_start + vel_start * dt + 0.5 * accelxy.x * sq(dt)); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + + // 10 + posxy = Vector2p(pos_start, 0.0); + velxy = Vector2f(vel_start, 0.0); + accelxy = Vector2f(-accel_start, 0.0); + limit = Vector2f(1.0, 0.0); + pos_error = Vector2f(-1.0, 0.0); + vel_error = Vector2f(-1.0, 0.0); + update_pos_vel_accel_xy(posxy, velxy, accelxy, dt, limit, pos_error, vel_error); + EXPECT_FLOAT_EQ(velxy.x, vel_start + accelxy.x * dt); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + EXPECT_FLOAT_EQ(posxy.x, pos_start + vel_start * dt + 0.5 * accelxy.x * sq(dt)); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + + // 11 + posxy = Vector2p(pos_start, 0.0); + velxy = Vector2f(vel_start, 0.0); + accelxy = Vector2f(accel_start, 0.0); + limit = Vector2f(-1.0, 0.0); + pos_error = Vector2f(1.0, 0.0); + vel_error = Vector2f(1.0, 0.0); + update_pos_vel_accel_xy(posxy, velxy, accelxy, dt, limit, pos_error, vel_error); + EXPECT_FLOAT_EQ(velxy.x, vel_start + accelxy.x * dt); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + EXPECT_FLOAT_EQ(posxy.x, pos_start + vel_start * dt + 0.5 * accelxy.x * sq(dt)); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + + // 12 + posxy = Vector2p(pos_start, 0.0); + velxy = Vector2f(vel_start, 0.0); + accelxy = Vector2f(-accel_start, 0.0); + limit = Vector2f(-1.0, 0.0); + pos_error = Vector2f(1.0, 0.0); + vel_error = Vector2f(1.0, 0.0); + update_pos_vel_accel_xy(posxy, velxy, accelxy, dt, limit, pos_error, vel_error); + EXPECT_FLOAT_EQ(velxy.x, vel_start + accelxy.x * dt); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + EXPECT_FLOAT_EQ(posxy.x, pos_start + vel_start * dt + 0.5 * accelxy.x * sq(dt)); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + + // error sign same as limit sign should result various limited behaviours + // 13 + posxy = Vector2p(pos_start, 0.0); + velxy = Vector2f(vel_start, 0.0); + accelxy = Vector2f(accel_start, 0.0); + limit = Vector2f(1.0, 0.0); + pos_error = Vector2f(1.0, 0.0); + vel_error = Vector2f(1.0, 0.0); + update_pos_vel_accel_xy(posxy, velxy, accelxy, dt, limit, pos_error, vel_error); + // vel is not increased + EXPECT_FLOAT_EQ(velxy.x, vel_start); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + // pos is not increased + EXPECT_FLOAT_EQ(posxy.x, pos_start); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + + // 14 + posxy = Vector2p(pos_start, 0.0); + velxy = Vector2f(vel_start, 0.0); + accelxy = Vector2f(-accel_start, 0.0); + limit = Vector2f(1.0, 0.0); + pos_error = Vector2f(1.0, 0.0); + vel_error = Vector2f(1.0, 0.0); + update_pos_vel_accel_xy(posxy, velxy, accelxy, dt, limit, pos_error, vel_error); + // vel is decreased + EXPECT_FLOAT_EQ(velxy.x, vel_start + accelxy.x * dt); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + // pos is not increased + EXPECT_FLOAT_EQ(posxy.x, pos_start); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + + // 15 + posxy = Vector2p(pos_start, 0.0); + velxy = Vector2f(vel_start, 0.0); + accelxy = Vector2f(accel_start, 0.0); + limit = Vector2f(-1.0, 0.0); + pos_error = Vector2f(-1.0, 0.0); + vel_error = Vector2f(-1.0, 0.0); + update_pos_vel_accel_xy(posxy, velxy, accelxy, dt, limit, pos_error, vel_error); + // vel is increased + EXPECT_FLOAT_EQ(velxy.x, vel_start + accelxy.x * dt); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + // pos is increased + EXPECT_FLOAT_EQ(posxy.x, pos_start + vel_start * dt + 0.5 * accelxy.x * sq(dt)); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + + // 16 + posxy = Vector2p(pos_start, 0.0); + velxy = Vector2f(vel_start, 0.0); + accelxy = Vector2f(-accel_start, 0.0); + limit = Vector2f(-1.0, 0.0); + pos_error = Vector2f(-1.0, 0.0); + vel_error = Vector2f(-1.0, 0.0); + update_pos_vel_accel_xy(posxy, velxy, accelxy, dt, limit, pos_error, vel_error); + // velocity is limited but limit is not applied because velocity is reducing + EXPECT_FLOAT_EQ(velxy.x, vel_start + accelxy.x * dt); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + // pos is increased + EXPECT_FLOAT_EQ(posxy.x, pos_start + vel_start * dt + 0.5 * accelxy.x * sq(dt)); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + + // 17 + posxy = Vector2p(pos_start, 0.0); + velxy = Vector2f(-vel_start, 0.0); + accelxy = Vector2f(accel_start, 0.0); + limit = Vector2f(1.0, 0.0); + pos_error = Vector2f(1.0, 0.0); + vel_error = Vector2f(1.0, 0.0); + update_pos_vel_accel_xy(posxy, velxy, accelxy, dt, limit, pos_error, vel_error); + // velocity is limited but limit is not applied because velocity is reducing + EXPECT_FLOAT_EQ(velxy.x, -vel_start + accelxy.x * dt); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + // pos is decreased + EXPECT_FLOAT_EQ(posxy.x, pos_start - vel_start * dt + 0.5 * accelxy.x * sq(dt)); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + + // 18 + vel_start = 0.1 * accel_start * dt; + posxy = Vector2p(pos_start, 0.0); + velxy = Vector2f(vel_start, 0.0); + accelxy = Vector2f(-accel_start, 0.0); + limit = Vector2f(-1.0, 0.0); + pos_error = Vector2f(-1.0, 0.0); + vel_error = Vector2f(-1.0, 0.0); + update_pos_vel_accel_xy(posxy, velxy, accelxy, dt, limit, pos_error, vel_error); + // velocity is limited but limit is not applied because velocity is reducing + // ideally this would be zero but code makes a simplification here + EXPECT_FLOAT_EQ(velxy.x, vel_start + accelxy.x * dt); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + // pos is not changed because is_negative(vel_start * dt + 0.5 * accel * sq(t)) + EXPECT_FLOAT_EQ(posxy.x, pos_start); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + + // 19 + posxy = Vector2p(pos_start, 0.0); + velxy = Vector2f(-vel_start, 0.0); + accelxy = Vector2f(accel_start, 0.0); + limit = Vector2f(1.0, 0.0); + pos_error = Vector2f(1.0, 0.0); + vel_error = Vector2f(1.0, 0.0); + update_pos_vel_accel_xy(posxy, velxy, accelxy, dt, limit, pos_error, vel_error); + // velocity is limited but limit is not applied because velocity is reducing + // ideally this would be zero but code makes a simplification here + EXPECT_FLOAT_EQ(velxy.x, -vel_start + accelxy.x * dt); + EXPECT_FLOAT_EQ(velxy.y, 0.0); + // pos is not changed because is_negative(vel_start * dt + 0.5 * accel * sq(t)) + EXPECT_FLOAT_EQ(posxy.x, pos_start); + EXPECT_FLOAT_EQ(velxy.y, 0.0); +} + + +AP_GTEST_MAIN() +int hal = 0; diff --git a/libraries/AP_Math/tests/test_geodesic_grid.cpp b/libraries/AP_Math/tests/test_geodesic_grid.cpp index 8cf897d1315..e0e8b6e6235 100644 --- a/libraries/AP_Math/tests/test_geodesic_grid.cpp +++ b/libraries/AP_Math/tests/test_geodesic_grid.cpp @@ -20,6 +20,8 @@ #include "math_test.h" #include +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); + class TestParam { public: /** diff --git a/libraries/AP_Math/tests/test_math.cpp b/libraries/AP_Math/tests/test_math.cpp index bdd4e2ec4f6..ccc959d2fe7 100644 --- a/libraries/AP_Math/tests/test_math.cpp +++ b/libraries/AP_Math/tests/test_math.cpp @@ -83,11 +83,11 @@ TEST(VectorTest, Rotations) EXPECT_EQ(ROTATION_MAX, rotation_count) << "All rotations are expect to be tested"; #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX - TEST_ROTATION(ROTATION_CUSTOM, 1, 1, 1); + TEST_ROTATION(ROTATION_CUSTOM_OLD, 1, 1, 1); TEST_ROTATION(ROTATION_MAX, 1, 1, 1); #elif CONFIG_HAL_BOARD == HAL_BOARD_SITL Vector3F v {1, 1, 1}; - EXPECT_EXIT(v.rotate(ROTATION_CUSTOM), testing::KilledBySignal(SIGABRT), "AP_InternalError::error_t::flow_of_ctrl"); + EXPECT_EXIT(v.rotate(ROTATION_CUSTOM_OLD), testing::KilledBySignal(SIGABRT), "AP_InternalError::error_t::bad_rotation"); EXPECT_EXIT(v.rotate(ROTATION_MAX), testing::KilledBySignal(SIGABRT), "AP_InternalError::error_t::bad_rotation"); #endif } @@ -100,9 +100,9 @@ TEST(MathTest, IsZero) EXPECT_TRUE(is_zero(FLT_MIN)); EXPECT_TRUE(is_zero(-FLT_MIN)); AP_Float t_float; - t_float = 0.1f; + t_float.set(0.1f); EXPECT_FALSE(is_zero(t_float)); - t_float = 0.0f; + t_float.set(0.0f); EXPECT_TRUE(is_zero(t_float)); } @@ -113,9 +113,9 @@ TEST(MathTest, IsPositive) EXPECT_FALSE(is_positive(0.0f)); EXPECT_FALSE(is_positive(-1.0f)); AP_Float t_float; - t_float = 0.1f; + t_float.set(0.1f); EXPECT_TRUE(is_positive(t_float)); - t_float = -0.1f; + t_float.set(-0.1f); EXPECT_FALSE(is_positive(t_float)); } @@ -126,9 +126,9 @@ TEST(MathTest, IsNegative) EXPECT_FALSE(is_negative(0.0f)); EXPECT_FALSE(is_negative(1.0f)); AP_Float t_float; - t_float = 0.1f; + t_float.set(0.1f); EXPECT_FALSE(is_negative(t_float)); - t_float = -0.1f; + t_float.set(-0.1f); EXPECT_TRUE(is_negative(t_float)); } @@ -217,18 +217,18 @@ TEST(MathTest, MAX) EXPECT_EQ(2.0f, MAX(testushort, 2.0f)); EXPECT_EQ(2.0f, MAX(testi32, 2.0f)); AP_Float t_float; - t_float = 0.1f; + t_float.set(0.1f); EXPECT_EQ(2.0f, MAX(t_float, 2.0f)); EXPECT_EQ(2.0f, MAX(2.0f, t_float)); AP_Int8 t_int8; - t_int8 = 1; + t_int8.set(1); EXPECT_EQ(2, MAX(t_int8, 2)); EXPECT_EQ(2, MAX(2, t_int8)); AP_Int16 t_int16; - t_int16 = 1; + t_int16.set(1); EXPECT_EQ(2, MAX(t_int16, 2)); AP_Int32 t_int32; - t_int32 = 1; + t_int32.set(1); EXPECT_EQ(2, MAX(t_int32, 2)); EXPECT_EQ(2.0f, MAX(1.0f, 2.0f)); EXPECT_EQ(2.0f, MAX(1.0f, 2)); @@ -275,8 +275,14 @@ TEST(MathTest, Square) EXPECT_EQ(1.f, sq_1); EXPECT_EQ(4.f, sq_2); AP_Float t_sqfloat; - t_sqfloat = sq(2); + t_sqfloat.set(sq(2)); EXPECT_EQ(4.f, t_sqfloat); + + EXPECT_FLOAT_EQ(sq(2.3), 5.289999999999999); // uses template sq + EXPECT_FLOAT_EQ(sq(2.3f), 5.29); // uses sq(float v) + EXPECT_EQ(sq(4294967295), 18446744065119617025U); // uses template sq + EXPECT_FLOAT_EQ(sq(4294967295.0), 1.8446744e+19); // uses template sq + EXPECT_FLOAT_EQ(sq(pow(2,25)), pow(2,50)); } TEST(MathTest, Norm) @@ -288,9 +294,9 @@ TEST(MathTest, Norm) float norm_5 = norm(3,4); float norm_6 = norm(4,3,12); AP_Float t_float1, t_float2, t_float3; - t_float1 = 4.0f; - t_float2 = 3.0f; - t_float3 = 12.f; + t_float1.set(4.0f); + t_float2.set(3.0f); + t_float3.set(12.f); float norm_7 = norm(t_float1, t_float2, t_float3); EXPECT_FLOAT_EQ(norm_1, 4.3174066f); @@ -377,6 +383,10 @@ TEST(MathTest, Constrain) EXPECT_EQ(19.9, constrain_value(19.8, 19.9, 20.1)); EXPECT_EQ(19.9f, constrain_value(19.8f, 19.9f, 20.1f)); + // test that constrain on 32 bit integer works correctly. Note the asymmetry + EXPECT_EQ(10, constrain_int32( 0xFFFFFFFFU, 10U, 1200U)); + EXPECT_EQ(1200U, constrain_uint32(0xFFFFFFFFU, 10U, 1200U)); + #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX EXPECT_EQ(1.0f, constrain_float(nanf("0x4152"), 1.0f, 1.0f)); EXPECT_EQ(1.0f, constrain_value(nanf("0x4152"), 1.0f, 1.0f)); @@ -655,10 +665,8 @@ TEST(MathTest, VELCORRECTION) TEST(MathTest, LOWPASSALPHA) { const float accuracy = 1.0e-5f; - EXPECT_EQ(1.0f, calc_lowpass_alpha_dt(0.0f, 2.0f)); - EXPECT_EQ(1.0f, calc_lowpass_alpha_dt(-1.0f, 2.0f)); + EXPECT_EQ(0.0f, calc_lowpass_alpha_dt(0.0f, 2.0f)); EXPECT_EQ(1.0f, calc_lowpass_alpha_dt(1.0f, 0.0f)); - EXPECT_EQ(1.0f, calc_lowpass_alpha_dt(1.0f, -2.0f)); EXPECT_NEAR(0.926288f, calc_lowpass_alpha_dt(1.0f, 2.0f), accuracy); } diff --git a/libraries/AP_Math/tests/test_math_double.cpp b/libraries/AP_Math/tests/test_math_double.cpp index 2d8d831d74a..e6667650d92 100644 --- a/libraries/AP_Math/tests/test_math_double.cpp +++ b/libraries/AP_Math/tests/test_math_double.cpp @@ -23,7 +23,7 @@ TEST(MathTest, IsZeroDouble) TEST(MathTest, MAXDouble) { AP_Float t_float; - t_float = 0.1f; + t_float.set(0.1f); EXPECT_EQ(2.0, MAX(t_float, 2.0)); } TEST(MathTest, IsEqualDouble) diff --git a/libraries/AP_Math/tests/test_matrix3.cpp b/libraries/AP_Math/tests/test_matrix3.cpp index 3372134f60e..099368e68d1 100644 --- a/libraries/AP_Math/tests/test_matrix3.cpp +++ b/libraries/AP_Math/tests/test_matrix3.cpp @@ -17,6 +17,8 @@ #include "math_test.h" +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); + // given we are in the Math library, you're epected to know what // you're doing when directly comparing floats: #pragma GCC diagnostic push diff --git a/libraries/AP_Math/tests/test_perpendicular.cpp b/libraries/AP_Math/tests/test_perpendicular.cpp index 8e9befc871a..8abfe6e7191 100644 --- a/libraries/AP_Math/tests/test_perpendicular.cpp +++ b/libraries/AP_Math/tests/test_perpendicular.cpp @@ -3,6 +3,8 @@ #include #include +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); + #define EXPECT_VECTOR2F_EQ(v1, v2) \ do { \ EXPECT_FLOAT_EQ(v1[0], v2[0]); \ diff --git a/libraries/AP_Math/tests/test_quaternion.cpp b/libraries/AP_Math/tests/test_quaternion.cpp index 664307d9c70..3e878d3d63b 100644 --- a/libraries/AP_Math/tests/test_quaternion.cpp +++ b/libraries/AP_Math/tests/test_quaternion.cpp @@ -2,6 +2,8 @@ #include +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); + // Tests that quaternion multiplication obeys Hamilton's quaternion multiplication convention // i*i == j*j == k*k == i*j*k == -1 TEST(QuaternionTest, QuaternionMultiplicationOfBases) { diff --git a/libraries/AP_Math/tests/test_rc_in_to_roll_pitch.cpp b/libraries/AP_Math/tests/test_rc_in_to_roll_pitch.cpp new file mode 100644 index 00000000000..5bd0799e1b9 --- /dev/null +++ b/libraries/AP_Math/tests/test_rc_in_to_roll_pitch.cpp @@ -0,0 +1,91 @@ +#include + +#include + +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); + +const float angle_max_deg = 60; +const float angle_limit_deg = 60; +float roll_out_deg, pitch_out_deg; + +// Test the corners of the input range +TEST(RC2RPTest, Corners) { + // (-1,-1), (-1,1), (1,-1), (1,1) + float roll_in[] = {-1, -1, 1, 1}; + float pitch_in[] = {-1, 1, -1, 1}; + float rc = 37.761f; // roll at 60 deg max/limit + float pc = 50.768f; // pitch at 60 deg max/limit + float roll_val_deg[] = {-rc, -rc, rc, rc}; + float pitch_val_deg[] = {-pc, pc, -pc, pc}; + + for (uint i=0; i +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); + #define EXPECT_VECTOR2F_EQ(v1, v2) \ do { \ EXPECT_FLOAT_EQ(v1[0], v2[0]); \ diff --git a/libraries/AP_Math/tests/test_vector2.cpp b/libraries/AP_Math/tests/test_vector2.cpp index e0b460a9cef..2125aabaca1 100644 --- a/libraries/AP_Math/tests/test_vector2.cpp +++ b/libraries/AP_Math/tests/test_vector2.cpp @@ -2,6 +2,8 @@ #include +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); + TEST(Vector2Test, Operator) { Vector2f v_float0{1.0f, 1.0f}; diff --git a/libraries/AP_Math/tests/test_vector3.cpp b/libraries/AP_Math/tests/test_vector3.cpp index 2fffa64ddce..dac9662f4a4 100644 --- a/libraries/AP_Math/tests/test_vector3.cpp +++ b/libraries/AP_Math/tests/test_vector3.cpp @@ -2,6 +2,8 @@ #define ALLOW_DOUBLE_MATH_FUNCTIONS #include +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); + TEST(Vector3Test, Operator) { Vector3f v_float0{1.0f, 1.0f,1.0f}; diff --git a/libraries/AP_Math/vector2.h b/libraries/AP_Math/vector2.h index 35a61d56870..152da159895 100644 --- a/libraries/AP_Math/vector2.h +++ b/libraries/AP_Math/vector2.h @@ -89,6 +89,11 @@ struct Vector2 // dot product T operator *(const Vector2 &v) const; + // dot product (same as above but a more easily understood name) + T dot(const Vector2 &v) const { + return *this * v; + } + // cross product T operator %(const Vector2 &v) const; diff --git a/libraries/AP_Math/vector3.cpp b/libraries/AP_Math/vector3.cpp index 95864cca7fc..669ecb2f287 100644 --- a/libraries/AP_Math/vector3.cpp +++ b/libraries/AP_Math/vector3.cpp @@ -20,6 +20,8 @@ #include "AP_Math.h" #include +#include +#include // rotate a vector by a standard rotation, attempting // to use the minimum number of floating point operations @@ -255,11 +257,16 @@ void Vector3::rotate(enum Rotation rotation) y = tmp; return; } - case ROTATION_CUSTOM: - // Error: caller must perform custom rotations via matrix multiplication - INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + case ROTATION_CUSTOM_1: + case ROTATION_CUSTOM_2: +#if !APM_BUILD_TYPE(APM_BUILD_AP_Periph) + // Do not support custom rotations on Periph + AP::custom_rotations().rotate(rotation, *this); return; +#endif case ROTATION_MAX: + case ROTATION_CUSTOM_OLD: + case ROTATION_CUSTOM_END: break; } // rotation invalid @@ -430,7 +437,7 @@ T Vector3::angle(const Vector3 &v2) const // multiplication of transpose by a vector template -Vector3 Vector3::operator *(const Matrix3 &m) const +Vector3 Vector3::row_times_mat(const Matrix3 &m) const { return Vector3(*this * m.colx(), *this * m.coly(), @@ -502,7 +509,7 @@ Vector3 Vector3::point_on_line_closest_to_other_point(const Vector3 &w1 const T line_vec_len = line_vec.length(); // protection against divide by zero if(::is_zero(line_vec_len)) { - return {0.0f, 0.0f, 0.0f}; + return w1; } const T scale = 1/line_vec_len; diff --git a/libraries/AP_Math/vector3.h b/libraries/AP_Math/vector3.h index 3862a23ef41..08f6337cef4 100644 --- a/libraries/AP_Math/vector3.h +++ b/libraries/AP_Math/vector3.h @@ -158,7 +158,7 @@ class Vector3 } // multiply a row vector by a matrix, to give a row vector - Vector3 operator *(const Matrix3 &m) const; + Vector3 row_times_mat(const Matrix3 &m) const; // multiply a column vector by a row vector, returning a 3x3 matrix Matrix3 mul_rowcol(const Vector3 &v) const; diff --git a/libraries/AP_Mission/AP_Mission.cpp b/libraries/AP_Mission/AP_Mission.cpp index dd9c399193e..672d1feefdc 100644 --- a/libraries/AP_Mission/AP_Mission.cpp +++ b/libraries/AP_Mission/AP_Mission.cpp @@ -54,6 +54,9 @@ void AP_Mission::init() // command list will be cleared if they do not match check_eeprom_version(); + // initialize the jump tracking array + init_jump_tracking(); + // If Mission Clear bit is set then it should clear the mission, otherwise retain the mission. if (AP_MISSION_MASK_MISSION_CLEAR & _options) { gcs().send_text(MAV_SEVERITY_INFO, "Clearing Mission"); @@ -161,11 +164,13 @@ bool AP_Mission::is_takeoff_next(uint16_t cmd_index) } switch (cmd.id) { // any of these are considered a takeoff command: + case MAV_CMD_NAV_VTOL_TAKEOFF: case MAV_CMD_NAV_TAKEOFF: case MAV_CMD_NAV_TAKEOFF_LOCAL: return true; // any of these are considered "skippable" when determining if // we "start with a takeoff command" + case MAV_CMD_DO_AUX_FUNCTION: case MAV_CMD_NAV_DELAY: continue; default: @@ -239,7 +244,7 @@ bool AP_Mission::clear() } // remove all commands - _cmd_total.set_and_save(0); + truncate(0); // clear index to commands _nav_cmd.index = AP_MISSION_CMD_INDEX_NONE; @@ -257,6 +262,7 @@ void AP_Mission::truncate(uint16_t index) { if ((unsigned)_cmd_total > index) { _cmd_total.set_and_save(index); + _last_change_time_ms = AP_HAL::millis(); } } @@ -325,6 +331,7 @@ bool AP_Mission::verify_command(const Mission_Command& cmd) case MAV_CMD_DO_SPRAYER: case MAV_CMD_DO_AUX_FUNCTION: case MAV_CMD_DO_SET_RESUME_REPEAT_DIST: + case MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW: return true; default: return _cmd_verify_fn(cmd); @@ -336,6 +343,8 @@ bool AP_Mission::start_command(const Mission_Command& cmd) // check for landing related commands and set in_landing_sequence flag if (is_landing_type_cmd(cmd.id) || cmd.id == MAV_CMD_DO_LAND_START) { set_in_landing_sequence_flag(true); + } else if (is_takeoff_type_cmd(cmd.id)) { + set_in_landing_sequence_flag(false); } gcs().send_text(MAV_SEVERITY_INFO, "Mission: %u %s", cmd.index, cmd.type()); @@ -362,6 +371,8 @@ bool AP_Mission::start_command(const Mission_Command& cmd) return start_command_do_sprayer(cmd); case MAV_CMD_DO_SET_RESUME_REPEAT_DIST: return command_do_set_repeat_dist(cmd); + case MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW: + return start_command_do_gimbal_manager_pitchyaw(cmd); default: return _cmd_start_fn(cmd); } @@ -409,7 +420,8 @@ bool AP_Mission::is_nav_cmd(const Mission_Command& cmd) // NAV commands all have ids below MAV_CMD_NAV_LAST, plus some exceptions return (cmd.id <= MAV_CMD_NAV_LAST || cmd.id == MAV_CMD_NAV_SET_YAW_SPEED || - cmd.id == MAV_CMD_NAV_SCRIPT_TIME); + cmd.id == MAV_CMD_NAV_SCRIPT_TIME || + cmd.id == MAV_CMD_NAV_ATTITUDE_TIME); } /// get_next_nav_cmd - gets next "navigation" command found at or after start_index @@ -639,6 +651,7 @@ struct PACKED Packed_Location_Option_Flags { uint8_t terrain_alt : 1; // this altitude is above terrain uint8_t origin_alt : 1; // this altitude is above ekf origin uint8_t loiter_xtrack : 1; // 0 to crosstrack from center of waypoint, 1 to crosstrack from tangent exit location + uint8_t type_specific_bit_0 : 1; // each mission item type can use this for storing 1 bit of extra data }; struct PACKED PackedLocation { @@ -724,6 +737,10 @@ bool AP_Mission::read_cmd_from_storage(uint16_t index, Mission_Command& cmd) con cmd.content.location.alt = packed_content.location.alt; cmd.content.location.lat = packed_content.location.lat; cmd.content.location.lng = packed_content.location.lng; + + if (packed_content.location.flags.type_specific_bit_0) { + cmd.type_specific_bits = 1U << 0; + } } else { // all other options in Content are assumed to be packed: static_assert(sizeof(cmd.content) >= 12, @@ -785,6 +802,7 @@ bool AP_Mission::write_cmd_to_storage(uint16_t index, const Mission_Command& cmd packed.location.flags.terrain_alt = cmd.content.location.terrain_alt; packed.location.flags.origin_alt = cmd.content.location.origin_alt; packed.location.flags.loiter_xtrack = cmd.content.location.loiter_xtrack; + packed.location.flags.type_specific_bit_0 = cmd.type_specific_bits & (1U<<0); packed.location.alt = cmd.content.location.alt; packed.location.lat = cmd.content.location.lat; packed.location.lng = cmd.content.location.lng; @@ -920,9 +938,20 @@ MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_ break; case MAV_CMD_NAV_LOITER_TURNS: { // MAV ID: 18 - uint16_t num_turns = packet.param1; // param 1 is number of times to circle is held in low p1 - uint16_t radius_m = fabsf(packet.param3); // param 3 is radius in meters is held in high p1 - cmd.p1 = (radius_m<<8) | (num_turns & 0x00FF); // store radius in high byte of p1, num turns in low byte of p1 + // number of turns is stored in the lowest bits. radii below + // 255m are stored in the top 8 bits as an 8-bit integer. + // Radii above 255m are stored divided by 10 and a bit set in + // storage so that on retrieval they are multiplied by 10 + cmd.p1 = MIN(255, packet.param1); // store number of times to circle in low p1 + uint8_t radius_m; + const float abs_radius = fabsf(packet.param3); + if (abs_radius <= 255) { + radius_m = abs_radius; + } else { + radius_m = MIN(255, abs_radius * 0.1); + cmd.type_specific_bits = 1U << 0; + } + cmd.p1 |= (radius_m<<8); // store radius in high byte of p1 cmd.content.location.loiter_ccw = (packet.param3 < 0); cmd.content.location.loiter_xtrack = (packet.param4 > 0); // 0 to xtrack from center of waypoint, 1 to xtrack from tangent exit location } @@ -1116,6 +1145,7 @@ MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_ break; case MAV_CMD_NAV_VTOL_LAND: + cmd.p1 = (NAV_VTOL_LAND_OPTIONS)packet.param1; break; case MAV_CMD_DO_VTOL_TRANSITION: @@ -1171,10 +1201,27 @@ MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_ cmd.content.nav_script_time.arg2 = packet.param4; break; + case MAV_CMD_NAV_ATTITUDE_TIME: + cmd.content.nav_attitude_time.time_sec = constrain_float(packet.param1, 0, UINT16_MAX); + cmd.content.nav_attitude_time.roll_deg = (fabsf(packet.param2) <= 180) ? packet.param2 : 0; + cmd.content.nav_attitude_time.pitch_deg = (fabsf(packet.param3) <= 90) ? packet.param3 : 0; + cmd.content.nav_attitude_time.yaw_deg = ((packet.param4 >= -180) && (packet.param4 <= 360)) ? packet.param4 : 0; + cmd.content.nav_attitude_time.climb_rate = packet.x; + break; + case MAV_CMD_DO_PAUSE_CONTINUE: cmd.p1 = packet.param1; break; - + + case MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW: + cmd.content.gimbal_manager_pitchyaw.pitch_angle_deg = packet.param1; + cmd.content.gimbal_manager_pitchyaw.yaw_angle_deg = packet.param2; + cmd.content.gimbal_manager_pitchyaw.pitch_rate_degs = packet.param3; + cmd.content.gimbal_manager_pitchyaw.yaw_rate_degs = packet.param4; + cmd.content.gimbal_manager_pitchyaw.flags = packet.x; + cmd.content.gimbal_manager_pitchyaw.gimbal_id = packet.z; + break; + default: // unrecognised command return MAV_MISSION_UNSUPPORTED; @@ -1261,6 +1308,8 @@ MAV_MISSION_RESULT AP_Mission::convert_MISSION_ITEM_to_MISSION_ITEM_INT(const ma switch (packet.command) { case MAV_CMD_DO_DIGICAM_CONTROL: case MAV_CMD_DO_DIGICAM_CONFIGURE: + case MAV_CMD_NAV_ATTITUDE_TIME: + case MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW: mav_cmd.x = packet.x; mav_cmd.y = packet.y; break; @@ -1302,6 +1351,8 @@ MAV_MISSION_RESULT AP_Mission::convert_MISSION_ITEM_INT_to_MISSION_ITEM(const ma switch (item_int.command) { case MAV_CMD_DO_DIGICAM_CONTROL: case MAV_CMD_DO_DIGICAM_CONFIGURE: + case MAV_CMD_NAV_ATTITUDE_TIME: + case MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW: item.x = item_int.x; item.y = item_int.y; break; @@ -1343,6 +1394,7 @@ MAV_MISSION_RESULT AP_Mission::mavlink_cmd_long_to_mission_cmd(const mavlink_com // mission_cmd_to_mavlink_int - converts an AP_Mission::Mission_Command object to a mavlink message which can be sent to the GCS // return true on success, false on failure +// NOTE: callers to this method current fill parts of "packet" in before calling this method, so do NOT attempt to zero the entire packet in here bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& cmd, mavlink_mission_item_int_t& packet) { // command's position in mission list and mavlink id @@ -1355,6 +1407,7 @@ bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& c packet.param2 = 0; packet.param3 = 0; packet.param4 = 0; + packet.frame = 0; packet.autocontinue = 1; // command specific conversions from mission command to mavlink packet @@ -1388,6 +1441,9 @@ bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& c if (cmd.content.location.loiter_ccw) { packet.param3 = -packet.param3; } + if (cmd.type_specific_bits & (1U<<0)) { + packet.param3 *= 10; + } packet.param4 = cmd.content.location.loiter_xtrack; // 0 to xtrack from center of waypoint, 1 to xtrack from tangent exit location break; @@ -1587,6 +1643,7 @@ bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& c break; case MAV_CMD_NAV_VTOL_LAND: + packet.param1 = cmd.p1; break; case MAV_CMD_DO_VTOL_TRANSITION: @@ -1634,10 +1691,27 @@ bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& c packet.param4 = cmd.content.nav_script_time.arg2; break; + case MAV_CMD_NAV_ATTITUDE_TIME: + packet.param1 = cmd.content.nav_attitude_time.time_sec; + packet.param2 = cmd.content.nav_attitude_time.roll_deg; + packet.param3 = cmd.content.nav_attitude_time.pitch_deg; + packet.param4 = cmd.content.nav_attitude_time.yaw_deg; + packet.x = cmd.content.nav_attitude_time.climb_rate; + break; + case MAV_CMD_DO_PAUSE_CONTINUE: packet.param1 = cmd.p1; break; - + + case MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW: + packet.param1 = cmd.content.gimbal_manager_pitchyaw.pitch_angle_deg; + packet.param2 = cmd.content.gimbal_manager_pitchyaw.yaw_angle_deg; + packet.param3 = cmd.content.gimbal_manager_pitchyaw.pitch_rate_degs; + packet.param4 = cmd.content.gimbal_manager_pitchyaw.yaw_rate_degs; + packet.x = cmd.content.gimbal_manager_pitchyaw.flags; + packet.z = cmd.content.gimbal_manager_pitchyaw.gimbal_id; + break; + default: // unrecognised command return false; @@ -1648,7 +1722,7 @@ bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& c packet.x = cmd.content.location.lat; packet.y = cmd.content.location.lng; - packet.z = cmd.content.location.alt / 100.0f; // cmd alt in cm to m + packet.z = cmd.content.location.alt * 0.01f; // cmd alt in cm to m if (cmd.content.location.relative_alt) { packet.frame = MAV_FRAME_GLOBAL_RELATIVE_ALT; } else { @@ -2255,6 +2329,18 @@ bool AP_Mission::is_landing_type_cmd(uint16_t id) const } } +// check if command is a takeoff type command. +bool AP_Mission::is_takeoff_type_cmd(uint16_t id) const +{ + switch (id) { + case MAV_CMD_NAV_TAKEOFF: + case MAV_CMD_NAV_VTOL_TAKEOFF: + return true; + default: + return false; + } +} + const char *AP_Mission::Mission_Command::type() const { switch (id) { @@ -2358,9 +2444,12 @@ const char *AP_Mission::Mission_Command::type() const return "Go Around"; case MAV_CMD_NAV_SCRIPT_TIME: return "NavScriptTime"; + case MAV_CMD_NAV_ATTITUDE_TIME: + return "NavAttitudeTime"; case MAV_CMD_DO_PAUSE_CONTINUE: return "PauseContinue"; - + case MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW: + return "GimbalPitchYaw"; default: #if CONFIG_HAL_BOARD == HAL_BOARD_SITL AP_HAL::panic("Mission command with ID %u has no string", id); @@ -2383,6 +2472,32 @@ bool AP_Mission::contains_item(MAV_CMD command) const return false; } +/* + return true if the mission has a terrain relative item. ~2200us for 530 items on H7 + */ +bool AP_Mission::contains_terrain_alt_items(void) +{ + if (_last_contains_relative_calculated_ms != _last_change_time_ms) { + _contains_terrain_alt_items = calculate_contains_terrain_alt_items(); + _last_contains_relative_calculated_ms = _last_change_time_ms; + } + return _contains_terrain_alt_items; +} + +bool AP_Mission::calculate_contains_terrain_alt_items(void) const +{ + for (int i = 1; i < num_commands(); i++) { + Mission_Command tmp; + if (!read_cmd_from_storage(i, tmp)) { + continue; + } + if (stored_in_location(tmp.id) && tmp.content.location.terrain_alt) { + return true; + } + } + return false; +} + // reset the mission history to prevent recalling previous mission histories after a mission restart. void AP_Mission::reset_wp_history(void) { diff --git a/libraries/AP_Mission/AP_Mission.h b/libraries/AP_Mission/AP_Mission.h index 04f2bf16aaa..7c93a58853f 100644 --- a/libraries/AP_Mission/AP_Mission.h +++ b/libraries/AP_Mission/AP_Mission.h @@ -12,11 +12,8 @@ */ #pragma once -#ifndef HAL_MISSION_ENABLED -#define HAL_MISSION_ENABLED 1 -#endif +#include "AP_Mission_config.h" -#include #include #include #include @@ -228,7 +225,26 @@ class AP_Mission float arg1; float arg2; }; - + + // Scripting NAV command (with verify) + struct PACKED nav_attitude_time_Command { + uint16_t time_sec; + int16_t roll_deg; + int8_t pitch_deg; + int16_t yaw_deg; + float climb_rate; + }; + + // MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW support + struct PACKED gimbal_manager_pitchyaw_Command { + int8_t pitch_angle_deg; + int16_t yaw_angle_deg; + int8_t pitch_rate_degs; + int8_t yaw_rate_degs; + uint8_t flags; + uint8_t gimbal_id; + }; + union Content { // jump structure Jump_Command jump; @@ -301,7 +317,13 @@ class AP_Mission // nav scripting nav_script_time_Command nav_script_time; - + + // nav attitude time + nav_attitude_time_Command nav_attitude_time; + + // MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW + gimbal_manager_pitchyaw_Command gimbal_manager_pitchyaw; + // location Location location{}; // Waypoint location }; @@ -313,6 +335,10 @@ class AP_Mission uint16_t p1; // general purpose parameter 1 Content content; + // for items which store in location, we offer a few more bits + // of storage: + uint8_t type_specific_bits; // bitmask of set/unset bits + // return a human-readable interpretation of the ID stored in this command const char *type() const; @@ -589,6 +615,9 @@ class AP_Mission // returns true if the mission contains the requested items bool contains_item(MAV_CMD command) const; + // returns true if the mission has a terrain relative mission item + bool contains_terrain_alt_items(void); + // reset the mission history to prevent recalling previous mission histories when restarting missions. void reset_wp_history(void); @@ -683,6 +712,9 @@ class AP_Mission // check if command is a landing type command. Asside the obvious, MAV_CMD_DO_PARACHUTE is considered a type of landing bool is_landing_type_cmd(uint16_t id) const; + // check if command is a takeoff type command. + bool is_takeoff_type_cmd(uint16_t id) const; + // approximate the distance travelled to get to a landing. DO_JUMP commands are observed in look forward. bool distance_to_landing(uint16_t index, float &tot_distance,Location current_loc); @@ -728,6 +760,10 @@ class AP_Mission // last time that mission changed uint32_t _last_change_time_ms; + // memoisation of contains-relative: + bool _contains_terrain_alt_items; // true if the mission has terrain-relative items + uint32_t _last_contains_relative_calculated_ms; // will be equal to _last_change_time_ms if _contains_terrain_alt_items is up-to-date + bool calculate_contains_terrain_alt_items(void) const; // multi-thread support. This is static so it can be used from // const functions @@ -743,7 +779,7 @@ class AP_Mission bool start_command_do_sprayer(const AP_Mission::Mission_Command& cmd); bool start_command_do_scripting(const AP_Mission::Mission_Command& cmd); - + bool start_command_do_gimbal_manager_pitchyaw(const AP_Mission::Mission_Command& cmd); }; namespace AP diff --git a/libraries/AP_Mission/AP_Mission_ChangeDetector.cpp b/libraries/AP_Mission/AP_Mission_ChangeDetector.cpp index 5b8d8be1460..6ebf7ba75e0 100644 --- a/libraries/AP_Mission/AP_Mission_ChangeDetector.cpp +++ b/libraries/AP_Mission/AP_Mission_ChangeDetector.cpp @@ -3,7 +3,7 @@ #include "AP_Mission_ChangeDetector.h" -extern const AP_HAL::HAL& hal; +#if AP_MISSION_ENABLED // detect external changes to mission bool AP_Mission_ChangeDetector::check_for_mission_change() @@ -59,3 +59,4 @@ bool AP_Mission_ChangeDetector::check_for_mission_change() return cmds_changed && !curr_cmd_idx_changed; } +#endif // AP_MISSION_ENABLED diff --git a/libraries/AP_Mission/AP_Mission_ChangeDetector.h b/libraries/AP_Mission/AP_Mission_ChangeDetector.h index 52d24ac8c10..580f5c4956b 100644 --- a/libraries/AP_Mission/AP_Mission_ChangeDetector.h +++ b/libraries/AP_Mission/AP_Mission_ChangeDetector.h @@ -14,7 +14,7 @@ #include "AP_Mission.h" -#if HAL_MISSION_ENABLED +#if AP_MISSION_ENABLED /// @class AP_Mission_ChangeDetector /// @brief Mission command change detector @@ -38,4 +38,4 @@ class AP_Mission_ChangeDetector } mis_change_detect; }; -#endif // HAL_MISSION_ENABLED +#endif // AP_MISSION_ENABLED diff --git a/libraries/AP_Mission/AP_Mission_Commands.cpp b/libraries/AP_Mission/AP_Mission_Commands.cpp index 2bc7bc0cb01..e4dcadc8bfd 100644 --- a/libraries/AP_Mission/AP_Mission_Commands.cpp +++ b/libraries/AP_Mission/AP_Mission_Commands.cpp @@ -7,6 +7,8 @@ #include #include #include +#include +#include bool AP_Mission::start_command_do_aux_function(const AP_Mission::Mission_Command& cmd) { @@ -203,3 +205,49 @@ bool AP_Mission::start_command_do_scripting(const AP_Mission::Mission_Command& c return false; #endif // AP_SCRIPTING_ENABLED } + +bool AP_Mission::start_command_do_gimbal_manager_pitchyaw(const AP_Mission::Mission_Command& cmd) +{ +#if HAL_MOUNT_ENABLED + AP_Mount *mount = AP::mount(); + if (mount == nullptr) { + return false; + } + + // check gimbal device id. 0 is primary, 1 is 1st gimbal, 2 is 2nd gimbal, etc + uint8_t gimbal_instance = mount->get_primary(); + if (cmd.content.gimbal_manager_pitchyaw.gimbal_id > 0) { + gimbal_instance = cmd.content.gimbal_manager_pitchyaw.gimbal_id - 1; + } + + // check flags for change to RETRACT + if ((cmd.content.gimbal_manager_pitchyaw.flags & GIMBAL_MANAGER_FLAGS_RETRACT) > 0) { + mount->set_mode(gimbal_instance, MAV_MOUNT_MODE_RETRACT); + return true; + } + // check flags for change to NEUTRAL + if ((cmd.content.gimbal_manager_pitchyaw.flags & GIMBAL_MANAGER_FLAGS_NEUTRAL) > 0) { + mount->set_mode(gimbal_instance, MAV_MOUNT_MODE_NEUTRAL); + return true; + } + + // handle angle target + const bool pitch_angle_valid = !isnan(cmd.content.gimbal_manager_pitchyaw.pitch_angle_deg) && (fabsf(cmd.content.gimbal_manager_pitchyaw.pitch_angle_deg) <= 90); + const bool yaw_angle_valid = !isnan(cmd.content.gimbal_manager_pitchyaw.yaw_angle_deg) && (fabsf(cmd.content.gimbal_manager_pitchyaw.yaw_angle_deg) <= 360); + if (pitch_angle_valid && yaw_angle_valid) { + mount->set_angle_target(gimbal_instance, 0, cmd.content.gimbal_manager_pitchyaw.pitch_angle_deg, cmd.content.gimbal_manager_pitchyaw.yaw_angle_deg, cmd.content.gimbal_manager_pitchyaw.flags & GIMBAL_MANAGER_FLAGS_YAW_LOCK); + return true; + } + + // handle rate target + if (!isnan(cmd.content.gimbal_manager_pitchyaw.pitch_rate_degs) && !isnan(cmd.content.gimbal_manager_pitchyaw.yaw_rate_degs)) { + mount->set_rate_target(gimbal_instance, 0, cmd.content.gimbal_manager_pitchyaw.pitch_rate_degs, cmd.content.gimbal_manager_pitchyaw.yaw_rate_degs, cmd.content.gimbal_manager_pitchyaw.flags & GIMBAL_MANAGER_FLAGS_YAW_LOCK); + return true; + } + + // if we got this far then message is not handled + return false; +#else + return false; +#endif // HAL_MOUNT_ENABLED +} diff --git a/libraries/AP_Mission/AP_Mission_config.h b/libraries/AP_Mission/AP_Mission_config.h new file mode 100644 index 00000000000..94be328bcfa --- /dev/null +++ b/libraries/AP_Mission/AP_Mission_config.h @@ -0,0 +1,5 @@ +#include + +#ifndef AP_MISSION_ENABLED +#define AP_MISSION_ENABLED 1 +#endif diff --git a/libraries/AP_Module/AP_Module.h b/libraries/AP_Module/AP_Module.h index d7dae64e2be..768413f4c56 100644 --- a/libraries/AP_Module/AP_Module.h +++ b/libraries/AP_Module/AP_Module.h @@ -27,8 +27,6 @@ */ #pragma once -#include - #if AP_MODULE_SUPPORTED #include diff --git a/libraries/AP_Module/examples/ModuleTest/ModuleTest.cpp b/libraries/AP_Module/examples/ModuleTest/ModuleTest.cpp index ac8e19b8f05..99ec60be0d1 100644 --- a/libraries/AP_Module/examples/ModuleTest/ModuleTest.cpp +++ b/libraries/AP_Module/examples/ModuleTest/ModuleTest.cpp @@ -8,6 +8,12 @@ #include #include #include +#include + +const struct AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { + AP_GROUPEND +}; +GCS_Dummy _gcs; void setup(); void loop(); diff --git a/libraries/AP_Motors/AP_Motors6DOF.cpp b/libraries/AP_Motors/AP_Motors6DOF.cpp index 003215eb9fd..f64e0a5aae6 100644 --- a/libraries/AP_Motors/AP_Motors6DOF.cpp +++ b/libraries/AP_Motors/AP_Motors6DOF.cpp @@ -367,15 +367,13 @@ void AP_Motors6DOF::output_armed_stabilizing() float _batt_current_delta = _batt_current - _batt_current_last; - float loop_interval = 1.0f/_loop_rate; + float _current_change_rate = _batt_current_delta / _dt; - float _current_change_rate = _batt_current_delta / loop_interval; + float predicted_current = _batt_current + (_current_change_rate * _dt * 5); - float predicted_current = _batt_current + (_current_change_rate * loop_interval * 5); + float batt_current_ratio = _batt_current / _batt_current_max; - float batt_current_ratio = _batt_current/_batt_current_max; - - float predicted_current_ratio = predicted_current/_batt_current_max; + float predicted_current_ratio = predicted_current / _batt_current_max; _batt_current_last = _batt_current; if (predicted_current > _batt_current_max * 1.5f) { @@ -383,7 +381,7 @@ void AP_Motors6DOF::output_armed_stabilizing() } else if (_batt_current < _batt_current_max && predicted_current > _batt_current_max) { batt_current_ratio = predicted_current_ratio; } - _output_limited += (loop_interval/(loop_interval+_batt_current_time_constant)) * (1 - batt_current_ratio); + _output_limited += (_dt / (_dt + _batt_current_time_constant)) * (1 - batt_current_ratio); _output_limited = constrain_float(_output_limited, 0.0f, 1.0f); diff --git a/libraries/AP_Motors/AP_Motors6DOF.h b/libraries/AP_Motors/AP_Motors6DOF.h index 14ed738fa90..90d7c0e00f9 100644 --- a/libraries/AP_Motors/AP_Motors6DOF.h +++ b/libraries/AP_Motors/AP_Motors6DOF.h @@ -12,8 +12,8 @@ class AP_Motors6DOF : public AP_MotorsMatrix { public: - AP_Motors6DOF(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : - AP_MotorsMatrix(loop_rate, speed_hz) { + AP_Motors6DOF(uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : + AP_MotorsMatrix(speed_hz) { AP_Param::setup_object_defaults(this, var_info); }; diff --git a/libraries/AP_Motors/AP_MotorsCoax.cpp b/libraries/AP_Motors/AP_MotorsCoax.cpp index 2141858c3e0..82cc47511d8 100644 --- a/libraries/AP_Motors/AP_MotorsCoax.cpp +++ b/libraries/AP_Motors/AP_MotorsCoax.cpp @@ -100,12 +100,12 @@ void AP_MotorsCoax::output_to_motors() // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used) // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict -uint16_t AP_MotorsCoax::get_motor_mask() +uint32_t AP_MotorsCoax::get_motor_mask() { uint32_t motor_mask = 1U << AP_MOTORS_MOT_5 | 1U << AP_MOTORS_MOT_6; - uint16_t mask = motor_mask_to_srv_channel_mask(motor_mask); + uint32_t mask = motor_mask_to_srv_channel_mask(motor_mask); // add parent's mask mask |= AP_MotorsMulticopter::get_motor_mask(); @@ -153,7 +153,7 @@ void AP_MotorsCoax::output_armed_stabilizing() if (is_zero(rp_thrust_max)) { rp_scale = 1.0f; } else { - rp_scale = constrain_float((1.0f - MIN(fabsf(yaw_thrust), 0.5f * (float)_yaw_headroom / 1000.0f)) / rp_thrust_max, 0.0f, 1.0f); + rp_scale = constrain_float((1.0f - MIN(fabsf(yaw_thrust), 0.5f * (float)_yaw_headroom * 0.001f)) / rp_thrust_max, 0.0f, 1.0f); if (rp_scale < 1.0f) { limit.roll = true; limit.pitch = true; diff --git a/libraries/AP_Motors/AP_MotorsCoax.h b/libraries/AP_Motors/AP_MotorsCoax.h index cd6ab2944fe..cbc07b39cd3 100644 --- a/libraries/AP_Motors/AP_MotorsCoax.h +++ b/libraries/AP_Motors/AP_MotorsCoax.h @@ -23,8 +23,8 @@ class AP_MotorsCoax : public AP_MotorsMulticopter { public: /// Constructor - AP_MotorsCoax(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : - AP_MotorsMulticopter(loop_rate, speed_hz) + AP_MotorsCoax(uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : + AP_MotorsMulticopter(speed_hz) { }; @@ -42,7 +42,10 @@ class AP_MotorsCoax : public AP_MotorsMulticopter { // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used) // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict - uint16_t get_motor_mask() override; + uint32_t get_motor_mask() override; + + // Run arming checks + bool arming_checks(size_t buflen, char *buffer) const override { return AP_Motors::arming_checks(buflen, buffer); } protected: // output - sends commands to the motors diff --git a/libraries/AP_Motors/AP_MotorsHeli.cpp b/libraries/AP_Motors/AP_MotorsHeli.cpp index 68d5dbe4d65..43db815da79 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli.cpp @@ -167,7 +167,7 @@ void AP_MotorsHeli::init(motor_frame_class frame_class, motor_frame_type frame_t _servo_test_cycle_counter = _servo_test; // ensure inputs are not passed through to servos on start-up - _servo_mode = SERVO_CONTROL_MODE_AUTOMATED; + _servo_mode.set(SERVO_CONTROL_MODE_AUTOMATED); // initialise radio passthrough for collective to middle _throttle_radio_passthrough = 0.5f; @@ -190,12 +190,6 @@ void AP_MotorsHeli::init(motor_frame_class frame_class, motor_frame_type frame_t _mav_type = MAV_TYPE_HELICOPTER; } -// set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus) -void AP_MotorsHeli::set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type) -{ - set_initialised_ok(frame_class == MOTOR_FRAME_HELI); -} - // output_min - sets servos to neutral point with motors stopped void AP_MotorsHeli::output_min() { @@ -528,7 +522,7 @@ void AP_MotorsHeli::reset_swash_servo(SRV_Channel::Aux_servo_function_t function // update the throttle input filter void AP_MotorsHeli::update_throttle_filter() { - _throttle_filter.apply(_throttle_in, 1.0f/_loop_rate); + _throttle_filter.apply(_throttle_in, _dt); // constrain filtered throttle if (_throttle_filter.get() < 0.0f) { @@ -542,7 +536,7 @@ void AP_MotorsHeli::update_throttle_filter() // reset_flight_controls - resets all controls and scalars to flight status void AP_MotorsHeli::reset_flight_controls() { - _servo_mode = SERVO_CONTROL_MODE_AUTOMATED; + _servo_mode.set(SERVO_CONTROL_MODE_AUTOMATED); init_outputs(); calculate_scalars(); } @@ -570,7 +564,7 @@ void AP_MotorsHeli::update_throttle_hover(float dt) } // we have chosen to constrain the hover collective to be within the range reachable by the third order expo polynomial. - _collective_hover = constrain_float(_collective_hover + (dt / (dt + AP_MOTORS_HELI_COLLECTIVE_HOVER_TC)) * (curr_collective - _collective_hover), AP_MOTORS_HELI_COLLECTIVE_HOVER_MIN, AP_MOTORS_HELI_COLLECTIVE_HOVER_MAX); + _collective_hover.set(constrain_float(_collective_hover + (dt / (dt + AP_MOTORS_HELI_COLLECTIVE_HOVER_TC)) * (curr_collective - _collective_hover), AP_MOTORS_HELI_COLLECTIVE_HOVER_MIN, AP_MOTORS_HELI_COLLECTIVE_HOVER_MAX)); } } @@ -609,3 +603,17 @@ void AP_MotorsHeli::update_turbine_start() } } +bool AP_MotorsHeli::arming_checks(size_t buflen, char *buffer) const +{ + // run base class checks + if (!AP_Motors::arming_checks(buflen, buffer)) { + return false; + } + + if (_heliflags.servo_test_running) { + hal.util->snprintf(buffer, buflen, "Servo Test is still running"); + return false; + } + + return true; +} diff --git a/libraries/AP_Motors/AP_MotorsHeli.h b/libraries/AP_Motors/AP_MotorsHeli.h index 8dface0caae..53cba9a3a0f 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.h +++ b/libraries/AP_Motors/AP_MotorsHeli.h @@ -40,9 +40,8 @@ class AP_MotorsHeli : public AP_Motors { public: /// Constructor - AP_MotorsHeli( uint16_t loop_rate, - uint16_t speed_hz = AP_MOTORS_HELI_SPEED_DEFAULT) : - AP_Motors(loop_rate, speed_hz), + AP_MotorsHeli( uint16_t speed_hz = AP_MOTORS_HELI_SPEED_DEFAULT) : + AP_Motors(speed_hz), _main_rotor(SRV_Channel::k_heli_rsc, AP_MOTORS_HELI_RSC) { AP_Param::setup_object_defaults(this, var_info); @@ -52,7 +51,10 @@ class AP_MotorsHeli : public AP_Motors { void init(motor_frame_class frame_class, motor_frame_type frame_type) override; // set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus) - void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type) override; + void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type) override { + _frame_class = frame_class; + _frame_type = frame_type; + } // set update rate to motors - a value in hertz virtual void set_update_rate( uint16_t speed_hz ) override = 0; @@ -108,7 +110,7 @@ class AP_MotorsHeli : public AP_Motors { // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used) // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict - virtual uint16_t get_motor_mask() override = 0; + virtual uint32_t get_motor_mask() override = 0; virtual void set_acro_tail(bool set) {} @@ -140,9 +142,6 @@ class AP_MotorsHeli : public AP_Motors { // set_enable_bailout - allows main code to set when RSC can immediately ramp engine instantly void set_enable_bailout(bool bailout) { _heliflags.enable_bailout = bailout; } - // return true if the servo test is still running/pending - bool servo_test_running() const { return _heliflags.servo_test_running; } - // set land complete flag void set_land_complete(bool landed) { _heliflags.land_complete = landed; } @@ -154,6 +153,9 @@ class AP_MotorsHeli : public AP_Motors { // use leaking integrator management scheme bool using_leaky_integrator() const { return heli_option(HeliOption::USE_LEAKY_I); } + // Run arming checks + bool arming_checks(size_t buflen, char *buffer) const override; + // var_info for holding Parameter information static const struct AP_Param::GroupInfo var_info[]; @@ -198,7 +200,8 @@ class AP_MotorsHeli : public AP_Motors { // reset_swash_servo - free up swash servo for maximum movement void reset_swash_servo(SRV_Channel::Aux_servo_function_t function); - // init_outputs - initialise Servo/PWM ranges and endpoints + // init_outputs - initialise Servo/PWM ranges and endpoints. This + // method also updates the initialised flag. virtual bool init_outputs() = 0; // calculate_armed_scalars - must be implemented by child classes diff --git a/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp b/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp index da401c2252f..335b9021cac 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp @@ -215,7 +215,7 @@ void AP_MotorsHeli_Dual::set_update_rate( uint16_t speed_hz ) _speed_hz = speed_hz; // setup fast channels - uint16_t mask = 0; + uint32_t mask = 0; for (uint8_t i=0; i= _collective_max ) { - _collective_min = AP_MOTORS_HELI_COLLECTIVE_MIN; - _collective_max = AP_MOTORS_HELI_COLLECTIVE_MAX; + _collective_min.set(AP_MOTORS_HELI_COLLECTIVE_MIN); + _collective_max.set(AP_MOTORS_HELI_COLLECTIVE_MAX); } // range check collective min, max and mid for rear swashplate if( _collective2_min >= _collective2_max ) { - _collective2_min = AP_MOTORS_HELI_DUAL_COLLECTIVE2_MIN; - _collective2_max = AP_MOTORS_HELI_DUAL_COLLECTIVE2_MAX; + _collective2_min.set(AP_MOTORS_HELI_DUAL_COLLECTIVE2_MIN); + _collective2_max.set(AP_MOTORS_HELI_DUAL_COLLECTIVE2_MAX); } - _collective_zero_thrust_deg = constrain_float(_collective_zero_thrust_deg, _collective_min_deg, _collective_max_deg); + _collective_zero_thrust_deg.set(constrain_float(_collective_zero_thrust_deg, _collective_min_deg, _collective_max_deg)); - _collective_land_min_deg = constrain_float(_collective_land_min_deg, _collective_min_deg, _collective_max_deg); + _collective_land_min_deg.set(constrain_float(_collective_land_min_deg, _collective_min_deg, _collective_max_deg)); if (!is_equal((float)_collective_max_deg, (float)_collective_min_deg)) { // calculate collective zero thrust point as a number from 0 to 1 @@ -473,10 +473,10 @@ float AP_MotorsHeli_Dual::get_swashplate (int8_t swash_num, int8_t swash_axis, f // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used) // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict -uint16_t AP_MotorsHeli_Dual::get_motor_mask() +uint32_t AP_MotorsHeli_Dual::get_motor_mask() { // dual heli uses channels 1,2,3,4,5,6 and 8 - uint16_t mask = 0; + uint32_t mask = 0; for (uint8_t i=0; i= 0.0f && _servo_test_cycle_time < 0.5f)|| // Tilt swash back (_servo_test_cycle_time >= 6.0f && _servo_test_cycle_time < 6.5f)){ - _pitch_test += (1.0f / (_loop_rate/2)); - _oscillate_angle += 8 * M_PI / _loop_rate; + _pitch_test += 2.0 * _dt; + _oscillate_angle += 8 * M_PI * _dt; } else if ((_servo_test_cycle_time >= 0.5f && _servo_test_cycle_time < 4.5f)|| // Roll swash around (_servo_test_cycle_time >= 6.5f && _servo_test_cycle_time < 10.5f)){ - _oscillate_angle += M_PI / (2 * _loop_rate); + _oscillate_angle += 0.5 * M_PI * _dt; _roll_test = sinf(_oscillate_angle); _pitch_test = cosf(_oscillate_angle); } else if ((_servo_test_cycle_time >= 4.5f && _servo_test_cycle_time < 5.0f)|| // Return swash to level (_servo_test_cycle_time >= 10.5f && _servo_test_cycle_time < 11.0f)){ - _pitch_test -= (1.0f / (_loop_rate/2)); - _oscillate_angle += 8 * M_PI / _loop_rate; + _pitch_test -= 2.0 * _dt; + _oscillate_angle += 8 * M_PI * _dt; } else if (_servo_test_cycle_time >= 5.0f && _servo_test_cycle_time < 6.0f){ // Raise swash to top - _collective_test += (1.0f / _loop_rate); - _oscillate_angle += 2 * M_PI / _loop_rate; + _collective_test += _dt; + _oscillate_angle += 2 * M_PI * _dt; } else if (_servo_test_cycle_time >= 11.0f && _servo_test_cycle_time < 12.0f){ // Lower swash to bottom - _collective_test -= (1.0f / _loop_rate); - _oscillate_angle += 2 * M_PI / _loop_rate; + _collective_test -= _dt; + _oscillate_angle += 2 * M_PI * _dt; } else { // reset cycle _servo_test_cycle_time = 0.0f; _oscillate_angle = 0.0f; diff --git a/libraries/AP_Motors/AP_MotorsHeli_Dual.h b/libraries/AP_Motors/AP_MotorsHeli_Dual.h index 9d079f59611..f18a8926725 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Dual.h +++ b/libraries/AP_Motors/AP_MotorsHeli_Dual.h @@ -36,9 +36,8 @@ class AP_MotorsHeli_Dual : public AP_MotorsHeli { public: // constructor - AP_MotorsHeli_Dual(uint16_t loop_rate, - uint16_t speed_hz = AP_MOTORS_HELI_SPEED_DEFAULT) : - AP_MotorsHeli(loop_rate, speed_hz) + AP_MotorsHeli_Dual(uint16_t speed_hz = AP_MOTORS_HELI_SPEED_DEFAULT) : + AP_MotorsHeli(speed_hz) { AP_Param::setup_object_defaults(this, var_info); }; @@ -78,7 +77,7 @@ class AP_MotorsHeli_Dual : public AP_MotorsHeli { void calculate_armed_scalars() override; // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used) - uint16_t get_motor_mask() override; + uint32_t get_motor_mask() override; // has_flybar - returns true if we have a mechical flybar bool has_flybar() const override { return AP_MOTORS_HELI_NOFLYBAR; } diff --git a/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp b/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp index 94a8cec2fcc..7d44022640f 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp @@ -67,7 +67,7 @@ bool AP_MotorsHeli_Quad::init_outputs() _main_rotor.set_ext_gov_arot_bail(0); } - set_initialised_ok(true); + set_initialised_ok(_frame_class == MOTOR_FRAME_HELI_QUAD); return true; } @@ -132,13 +132,13 @@ void AP_MotorsHeli_Quad::calculate_scalars() { // range check collective min, max and mid if( _collective_min >= _collective_max ) { - _collective_min = AP_MOTORS_HELI_COLLECTIVE_MIN; - _collective_max = AP_MOTORS_HELI_COLLECTIVE_MAX; + _collective_min.set(AP_MOTORS_HELI_COLLECTIVE_MIN); + _collective_max.set(AP_MOTORS_HELI_COLLECTIVE_MAX); } - _collective_zero_thrust_deg = constrain_float(_collective_zero_thrust_deg, _collective_min_deg, _collective_max_deg); + _collective_zero_thrust_deg.set(constrain_float(_collective_zero_thrust_deg, _collective_min_deg, _collective_max_deg)); - _collective_land_min_deg = constrain_float(_collective_land_min_deg, _collective_min_deg, _collective_max_deg); + _collective_land_min_deg.set(constrain_float(_collective_land_min_deg, _collective_min_deg, _collective_max_deg)); if (!is_equal((float)_collective_max_deg, (float)_collective_min_deg)) { // calculate collective zero thrust point as a number from 0 to 1 @@ -183,9 +183,9 @@ void AP_MotorsHeli_Quad::calculate_roll_pitch_collective_factors() // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used) // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict -uint16_t AP_MotorsHeli_Quad::get_motor_mask() +uint32_t AP_MotorsHeli_Quad::get_motor_mask() { - uint16_t mask = 0; + uint32_t mask = 0; for (uint8_t i=0; i // ArduPilot Mega Vector/Matrix math Library #include #include -#include // default main rotor speed (ch8 out) as a number from 0 ~ 100 #define AP_MOTORS_HELI_RSC_SETPOINT 70 @@ -73,7 +72,7 @@ class AP_MotorsHeli_RSC { uint8_t get_control_mode() const { return _control_mode; } // set_critical_speed - void set_critical_speed(float critical_speed) { _critical_speed = critical_speed; } + void set_critical_speed(float critical_speed) { _critical_speed.set(critical_speed); } // get_desired_speed float get_desired_speed() const { return _desired_speed; } @@ -89,13 +88,13 @@ class AP_MotorsHeli_RSC { float get_governor_output() const { return _governor_output; } void governor_reset(); float get_control_output() const { return _control_output; } - void set_idle_output(float idle_output) { _idle_output = idle_output; } + void set_idle_output(float idle_output) { _idle_output.set(idle_output); } void autothrottle_run(); void set_throttle_curve(); // functions for ramp and runup timers, runup_complete flag - void set_ramp_time(int8_t ramp_time) { _ramp_time = ramp_time; } - void set_runup_time(int8_t runup_time) { _runup_time = runup_time; } + void set_ramp_time(int8_t ramp_time) { _ramp_time.set(ramp_time); } + void set_runup_time(int8_t runup_time) { _runup_time.set(runup_time); } bool is_runup_complete() const { return _runup_complete; } // is_spooldown_complete diff --git a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp index 65d788827fb..ce33484e14a 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp @@ -215,7 +215,7 @@ bool AP_MotorsHeli_Single::init_outputs() // yaw servo is an angle from -4500 to 4500 SRV_Channels::set_angle(SRV_Channel::k_motor4, YAW_SERVO_MAX_ANGLE); - set_initialised_ok(true); + set_initialised_ok(_frame_class == MOTOR_FRAME_HELI); return true; } @@ -310,13 +310,13 @@ void AP_MotorsHeli_Single::calculate_scalars() { // range check collective min, max and zero if( _collective_min >= _collective_max ) { - _collective_min = AP_MOTORS_HELI_COLLECTIVE_MIN; - _collective_max = AP_MOTORS_HELI_COLLECTIVE_MAX; + _collective_min.set(AP_MOTORS_HELI_COLLECTIVE_MIN); + _collective_max.set(AP_MOTORS_HELI_COLLECTIVE_MAX); } - _collective_zero_thrust_deg = constrain_float(_collective_zero_thrust_deg, _collective_min_deg, _collective_max_deg); + _collective_zero_thrust_deg.set(constrain_float(_collective_zero_thrust_deg, _collective_min_deg, _collective_max_deg)); - _collective_land_min_deg = constrain_float(_collective_land_min_deg, _collective_min_deg, _collective_max_deg); + _collective_land_min_deg.set(constrain_float(_collective_land_min_deg, _collective_min_deg, _collective_max_deg)); if (!is_equal((float)_collective_max_deg, (float)_collective_min_deg)) { // calculate collective zero thrust point as a number from 0 to 1 @@ -355,7 +355,7 @@ void AP_MotorsHeli_Single::calculate_scalars() // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used) // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict -uint16_t AP_MotorsHeli_Single::get_motor_mask() +uint32_t AP_MotorsHeli_Single::get_motor_mask() { // heli uses channels 1,2,3,4 and 8 // setup fast channels @@ -467,7 +467,7 @@ void AP_MotorsHeli_Single::move_actuators(float roll_out, float pitch_out, float // also not required if we are using external gyro if ((_main_rotor.get_control_output() > _main_rotor.get_idle_output()) && _tail_type != AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO_EXTGYRO) { // sanity check collective_yaw_effect - _collective_yaw_effect = constrain_float(_collective_yaw_effect, -AP_MOTORS_HELI_SINGLE_COLYAW_RANGE, AP_MOTORS_HELI_SINGLE_COLYAW_RANGE); + _collective_yaw_effect.set(constrain_float(_collective_yaw_effect, -AP_MOTORS_HELI_SINGLE_COLYAW_RANGE, AP_MOTORS_HELI_SINGLE_COLYAW_RANGE)); // the 4.5 scaling factor is to bring the values in line with previous releases yaw_offset = _collective_yaw_effect * fabsf(collective_out - _collective_zero_thrust_pct) / 4.5f; } @@ -582,31 +582,31 @@ void AP_MotorsHeli_Single::output_to_motors() // servo_test - move servos through full range of movement void AP_MotorsHeli_Single::servo_test() { - _servo_test_cycle_time += 1.0f / _loop_rate; + _servo_test_cycle_time += _dt; if ((_servo_test_cycle_time >= 0.0f && _servo_test_cycle_time < 0.5f)|| // Tilt swash back (_servo_test_cycle_time >= 6.0f && _servo_test_cycle_time < 6.5f)){ - _pitch_test += (1.0f / (_loop_rate / 2.0f)); - _oscillate_angle += 8 * M_PI / _loop_rate; + _pitch_test += 2.0 * _dt; + _oscillate_angle += 8 * M_PI * _dt; _yaw_test = 0.5f * sinf(_oscillate_angle); } else if ((_servo_test_cycle_time >= 0.5f && _servo_test_cycle_time < 4.5f)|| // Roll swash around (_servo_test_cycle_time >= 6.5f && _servo_test_cycle_time < 10.5f)){ - _oscillate_angle += M_PI / (2 * _loop_rate); + _oscillate_angle += 0.5 * M_PI * _dt; _roll_test = sinf(_oscillate_angle); _pitch_test = cosf(_oscillate_angle); _yaw_test = sinf(_oscillate_angle); } else if ((_servo_test_cycle_time >= 4.5f && _servo_test_cycle_time < 5.0f)|| // Return swash to level (_servo_test_cycle_time >= 10.5f && _servo_test_cycle_time < 11.0f)){ - _pitch_test -= (1.0f / (_loop_rate / 2.0f)); - _oscillate_angle += 8 * M_PI / _loop_rate; + _pitch_test -= 2.0 * _dt; + _oscillate_angle += 8 * M_PI * _dt; _yaw_test = 0.5f * sinf(_oscillate_angle); } else if (_servo_test_cycle_time >= 5.0f && _servo_test_cycle_time < 6.0f){ // Raise swash to top - _collective_test += (1.0f / _loop_rate); - _oscillate_angle += 2 * M_PI / _loop_rate; + _collective_test += _dt; + _oscillate_angle += 2 * M_PI * _dt; _yaw_test = sinf(_oscillate_angle); } else if (_servo_test_cycle_time >= 11.0f && _servo_test_cycle_time < 12.0f){ // Lower swash to bottom - _collective_test -= (1.0f / _loop_rate); - _oscillate_angle += 2 * M_PI / _loop_rate; + _collective_test -= _dt; + _oscillate_angle += 2 * M_PI * _dt; _yaw_test = sinf(_oscillate_angle); } else { // reset cycle _servo_test_cycle_time = 0.0f; diff --git a/libraries/AP_Motors/AP_MotorsHeli_Single.h b/libraries/AP_Motors/AP_MotorsHeli_Single.h index 2f2cbb6719b..c2079e7afab 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Single.h +++ b/libraries/AP_Motors/AP_MotorsHeli_Single.h @@ -38,9 +38,8 @@ class AP_MotorsHeli_Single : public AP_MotorsHeli { public: // constructor - AP_MotorsHeli_Single(uint16_t loop_rate, - uint16_t speed_hz = AP_MOTORS_HELI_SPEED_DEFAULT) : - AP_MotorsHeli(loop_rate, speed_hz), + AP_MotorsHeli_Single(uint16_t speed_hz = AP_MOTORS_HELI_SPEED_DEFAULT) : + AP_MotorsHeli(speed_hz), _tail_rotor(SRV_Channel::k_heli_tail_rsc, AP_MOTORS_HELI_SINGLE_TAILRSC), _swashplate() { @@ -79,10 +78,10 @@ class AP_MotorsHeli_Single : public AP_MotorsHeli { // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used) // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict - uint16_t get_motor_mask() override; + uint32_t get_motor_mask() override; // ext_gyro_gain - set external gyro gain in range 0 ~ 1000 - void ext_gyro_gain(float gain) override { if (gain >= 0 && gain <= 1000) { _ext_gyro_gain_std = gain; }} + void ext_gyro_gain(float gain) override { if (gain >= 0 && gain <= 1000) { _ext_gyro_gain_std.set(gain); }} // has_flybar - returns true if we have a mechical flybar bool has_flybar() const override { return _flybar_mode; } diff --git a/libraries/AP_Motors/AP_MotorsHeli_Swash.cpp b/libraries/AP_Motors/AP_MotorsHeli_Swash.cpp index be325bad3df..6b92fcb27ea 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Swash.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Swash.cpp @@ -94,9 +94,9 @@ void AP_MotorsHeli_Swash::configure() _collective_direction = static_cast(_swash_coll_dir.get()); _make_servo_linear = _linear_swash_servo; if (_swash_type == SWASHPLATE_TYPE_H3) { - enable = 1; + enable.set(1); } else { - enable = 0; + enable.set(0); } } diff --git a/libraries/AP_Motors/AP_MotorsMatrix.cpp b/libraries/AP_Motors/AP_MotorsMatrix.cpp index 9016eeef0a9..c8ec9b0afea 100644 --- a/libraries/AP_Motors/AP_MotorsMatrix.cpp +++ b/libraries/AP_Motors/AP_MotorsMatrix.cpp @@ -117,7 +117,7 @@ void AP_MotorsMatrix::set_update_rate(uint16_t speed_hz) // record requested speed _speed_hz = speed_hz; - uint16_t mask = 0; + uint32_t mask = 0; for (uint8_t i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) { if (motor_enabled[i]) { mask |= 1U << i; @@ -184,15 +184,15 @@ void AP_MotorsMatrix::output_to_motors() // get_motor_mask - returns a bitmask of which outputs are being used for motors (1 means being used) // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict -uint16_t AP_MotorsMatrix::get_motor_mask() +uint32_t AP_MotorsMatrix::get_motor_mask() { - uint16_t motor_mask = 0; + uint32_t motor_mask = 0; for (uint8_t i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) { if (motor_enabled[i]) { motor_mask |= 1U << i; } } - uint16_t mask = motor_mask_to_srv_channel_mask(motor_mask); + uint32_t mask = motor_mask_to_srv_channel_mask(motor_mask); // add parent's mask mask |= AP_MotorsMulticopter::get_motor_mask(); @@ -295,7 +295,7 @@ void AP_MotorsMatrix::output_armed_stabilizing() // calculate the maximum yaw control that can be used // todo: make _yaw_headroom 0 to 1 - float yaw_allowed_min = (float)_yaw_headroom / 1000.0f; + float yaw_allowed_min = (float)_yaw_headroom * 0.001f; // increase yaw headroom to 50% if thrust boost enabled yaw_allowed_min = _thrust_boost_ratio * 0.5f + (1.0f - _thrust_boost_ratio) * yaw_allowed_min; @@ -414,7 +414,7 @@ void AP_MotorsMatrix::output_armed_stabilizing() void AP_MotorsMatrix::check_for_failed_motor(float throttle_thrust_best_plus_adj) { // record filtered and scaled thrust output for motor loss monitoring purposes - float alpha = 1.0f / (1.0f + _loop_rate * 0.5f); + float alpha = _dt / (_dt + 0.5f); for (uint8_t i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) { if (motor_enabled[i]) { _thrust_rpyt_out_filt[i] += alpha * (_thrust_rpyt_out[i] - _thrust_rpyt_out_filt[i]); @@ -569,6 +569,680 @@ void AP_MotorsMatrix::add_motors_raw(const struct MotorDefRaw *motors, uint8_t n add_motor_raw(i, m.roll_fac, m.pitch_fac, m.yaw_fac, m.testing_order); } } +#if AP_MOTORS_FRAME_QUAD_ENABLED +bool AP_MotorsMatrix::setup_quad_matrix(motor_frame_type frame_type) +{ + _frame_class_string = "QUAD"; + _mav_type = MAV_TYPE_QUADROTOR; + switch (frame_type) { + case MOTOR_FRAME_TYPE_PLUS: { + _frame_type_string = "PLUS"; + static const AP_MotorsMatrix::MotorDef motors[] { + { 90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 }, + { -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 }, + { 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 }, + { 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 }, + }; + add_motors(motors, ARRAY_SIZE(motors)); + break; + } + case MOTOR_FRAME_TYPE_X: { + _frame_type_string = "X"; + static const AP_MotorsMatrix::MotorDef motors[] { + { 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, + { -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 }, + { -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 }, + { 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, + }; + add_motors(motors, ARRAY_SIZE(motors)); + break; + } +#if APM_BUILD_TYPE(APM_BUILD_ArduPlane) + case MOTOR_FRAME_TYPE_NYT_PLUS: { + _frame_type_string = "NYT_PLUS"; + static const AP_MotorsMatrix::MotorDef motors[] { + { 90, 0, 2 }, + { -90, 0, 4 }, + { 0, 0, 1 }, + { 180, 0, 3 }, + }; + add_motors(motors, ARRAY_SIZE(motors)); + break; + } + case MOTOR_FRAME_TYPE_NYT_X: { + _frame_type_string = "NYT_X"; + static const AP_MotorsMatrix::MotorDef motors[] { + { 45, 0, 1 }, + { -135, 0, 3 }, + { -45, 0, 4 }, + { 135, 0, 2 }, + }; + add_motors(motors, ARRAY_SIZE(motors)); + break; + } +#endif //APM_BUILD_TYPE(APM_BUILD_ArduPlane) + case MOTOR_FRAME_TYPE_BF_X: { + // betaflight quad X order + // see: https://fpvfrenzy.com/betaflight-motor-order/ + _frame_type_string = "BF_X"; + static const AP_MotorsMatrix::MotorDef motors[] { + { 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, + { 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, + { -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 }, + { -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 }, + }; + add_motors(motors, ARRAY_SIZE(motors)); + break; + } + case MOTOR_FRAME_TYPE_BF_X_REV: { + // betaflight quad X order, reversed motors + _frame_type_string = "X_REV"; + static const AP_MotorsMatrix::MotorDef motors[] { + { 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 }, + { 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 }, + { -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 }, + { -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 }, + }; + add_motors(motors, ARRAY_SIZE(motors)); + break; + } + case MOTOR_FRAME_TYPE_DJI_X: { + // DJI quad X order + // see https://forum44.djicdn.com/data/attachment/forum/201711/26/172348bppvtt1ot1nrtp5j.jpg + _frame_type_string = "DJI_X"; + static const AP_MotorsMatrix::MotorDef motors[] { + { 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, + { -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 }, + { -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 }, + { 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, + }; + add_motors(motors, ARRAY_SIZE(motors)); + break; + } + case MOTOR_FRAME_TYPE_CW_X: { + // "clockwise X" motor order. Motors are ordered clockwise from front right + // matching test order + _frame_type_string = "CW_X"; + static const AP_MotorsMatrix::MotorDef motors[] { + { 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, + { 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, + { -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 }, + { -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 }, + }; + add_motors(motors, ARRAY_SIZE(motors)); + break; + } + case MOTOR_FRAME_TYPE_V: { + _frame_type_string = "V"; + static const AP_MotorsMatrix::MotorDef motors[] { + { 45, 0.7981f, 1 }, + { -135, 1.0000f, 3 }, + { -45, -0.7981f, 4 }, + { 135, -1.0000f, 2 }, + }; + add_motors(motors, ARRAY_SIZE(motors)); + break; + } + case MOTOR_FRAME_TYPE_H: { + // H frame set-up - same as X but motors spin in opposite directiSons + _frame_type_string = "H"; + static const AP_MotorsMatrix::MotorDef motors[] { + { 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 }, + { -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 }, + { -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 }, + { 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 }, + }; + add_motors(motors, ARRAY_SIZE(motors)); + break; + } + case MOTOR_FRAME_TYPE_VTAIL: { + /* + Tested with: Lynxmotion Hunter Vtail 400 + - inverted rear outward blowing motors (at a 40 degree angle) + - should also work with non-inverted rear outward blowing motors + - no roll in rear motors + - no yaw in front motors + - should fly like some mix between a tricopter and X Quadcopter + + Roll control comes only from the front motors, Yaw control only from the rear motors. + Roll & Pitch factor is measured by the angle away from the top of the forward axis to each arm. + + Note: if we want the front motors to help with yaw, + motors 1's yaw factor should be changed to sin(radians(40)). Where "40" is the vtail angle + motors 3's yaw factor should be changed to -sin(radians(40)) + */ + _frame_type_string = "VTAIL"; + add_motor(AP_MOTORS_MOT_1, 60, 60, 0, 1); + add_motor(AP_MOTORS_MOT_2, 0, -160, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3); + add_motor(AP_MOTORS_MOT_3, -60, -60, 0, 4); + add_motor(AP_MOTORS_MOT_4, 0, 160, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2); + break; + } + case MOTOR_FRAME_TYPE_ATAIL: + /* + The A-Shaped VTail is the exact same as a V-Shaped VTail, with one difference: + - The Yaw factors are reversed, because the rear motors are facing different directions + + With V-Shaped VTails, the props make a V-Shape when spinning, but with + A-Shaped VTails, the props make an A-Shape when spinning. + - Rear thrust on a V-Shaped V-Tail Quad is outward + - Rear thrust on an A-Shaped V-Tail Quad is inward + + Still functions the same as the V-Shaped VTail mixing below: + - Yaw control is entirely in the rear motors + - Roll is is entirely in the front motors + */ + _frame_type_string = "ATAIL"; + add_motor(AP_MOTORS_MOT_1, 60, 60, 0, 1); + add_motor(AP_MOTORS_MOT_2, 0, -160, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3); + add_motor(AP_MOTORS_MOT_3, -60, -60, 0, 4); + add_motor(AP_MOTORS_MOT_4, 0, 160, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2); + break; + case MOTOR_FRAME_TYPE_PLUSREV: { + // plus with reversed motor directions + _frame_type_string = "PLUSREV"; + static const AP_MotorsMatrix::MotorDef motors[] { + { 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, + { -90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 }, + { 0, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, + { 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 }, + }; + add_motors(motors, ARRAY_SIZE(motors)); + break; + } + case MOTOR_FRAME_TYPE_Y4: + _frame_type_string = "Y4"; + // Y4 motor definition with right front CCW, left front CW + static const AP_MotorsMatrix::MotorDefRaw motors[] { + { -1.0f, 1.000f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, + { 0.0f, -1.000f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, + { 0.0f, -1.000f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 }, + { 1.0f, 1.000f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 }, + }; + add_motors_raw(motors, ARRAY_SIZE(motors)); + break; + default: + // quad frame class does not support this frame type + _frame_type_string = "UNSUPPORTED"; + return false; + } + return true; +} +#endif //AP_MOTORS_FRAME_QUAD_ENABLED +#if AP_MOTORS_FRAME_HEXA_ENABLED +bool AP_MotorsMatrix::setup_hexa_matrix(motor_frame_type frame_type) +{ + _frame_class_string = "HEXA"; + _mav_type = MAV_TYPE_HEXAROTOR; + switch (frame_type) { + case MOTOR_FRAME_TYPE_PLUS: { + _frame_type_string = "PLUS"; + static const AP_MotorsMatrix::MotorDef motors[] { + { 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 }, + { 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 }, + { -120, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 }, + { 60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 }, + { -60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 }, + { 120, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 }, + }; + add_motors(motors, ARRAY_SIZE(motors)); + break; + } + case MOTOR_FRAME_TYPE_X: { + _frame_type_string = "X"; + static const AP_MotorsMatrix::MotorDef motors[] { + { 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, + { -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 }, + { -30, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 }, + { 150, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 }, + { 30, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, + { -150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 }, + }; + add_motors(motors, ARRAY_SIZE(motors)); + break; + } + case MOTOR_FRAME_TYPE_H: { + // H is same as X except middle motors are closer to center + _frame_type_string = "H"; + static const AP_MotorsMatrix::MotorDefRaw motors[] { + { -1.0f, 0.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, + { 1.0f, 0.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 }, + { 1.0f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 }, + { -1.0f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 }, + { -1.0f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, + { 1.0f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 }, + }; + add_motors_raw(motors, ARRAY_SIZE(motors)); + break; + } + case MOTOR_FRAME_TYPE_DJI_X: { + _frame_type_string = "DJI_X"; + static const AP_MotorsMatrix::MotorDef motors[] { + { 30, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, + { -30, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 }, + { -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 }, + { -150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 }, + { 150, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 }, + { 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, + }; + add_motors(motors, ARRAY_SIZE(motors)); + break; + } + case MOTOR_FRAME_TYPE_CW_X: { + _frame_type_string = "CW_X"; + static const AP_MotorsMatrix::MotorDef motors[] { + { 30, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, + { 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, + { 150, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 }, + { -150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 }, + { -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 }, + { -30, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 }, + }; + add_motors(motors, ARRAY_SIZE(motors)); + break; + } + default: + // hexa frame class does not support this frame type + _frame_type_string = "UNSUPPORTED"; + return false; + } //hexa + return true; +} +#endif ////AP_MOTORS_FRAME_HEXA_ENABLED +#if AP_MOTORS_FRAME_OCTA_ENABLED +bool AP_MotorsMatrix::setup_octa_matrix(motor_frame_type frame_type) +{ + _frame_class_string = "OCTA"; + _mav_type = MAV_TYPE_OCTOROTOR; + switch (frame_type) { + case MOTOR_FRAME_TYPE_PLUS: { + _frame_type_string = "PLUS"; + static const AP_MotorsMatrix::MotorDef motors[] { + { 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 }, + { 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 }, + { 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 }, + { 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 }, + { -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 }, + { -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 }, + { -90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 }, + { 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 }, + }; + + add_motors(motors, ARRAY_SIZE(motors)); + break; + } + case MOTOR_FRAME_TYPE_X: { + _frame_type_string = "X"; + static const AP_MotorsMatrix::MotorDef motors[] { + { 22.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 }, + { -157.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 }, + { 67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 }, + { 157.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 }, + { -22.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 }, + { -112.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 }, + { -67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 }, + { 112.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 }, + }; + add_motors(motors, ARRAY_SIZE(motors)); + break; + } + case MOTOR_FRAME_TYPE_V: { + _frame_type_string = "V"; + static const AP_MotorsMatrix::MotorDefRaw motors[] { + { 0.83f, 0.34f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 }, + { -0.67f, -0.32f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 }, + { 0.67f, -0.32f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 }, + { -0.50f, -1.00f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 }, + { 1.00f, 1.00f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 }, + { -0.83f, 0.34f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 }, + { -1.00f, 1.00f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 }, + { 0.50f, -1.00f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 }, + }; + add_motors_raw(motors, ARRAY_SIZE(motors)); + break; + } + case MOTOR_FRAME_TYPE_H: { + _frame_type_string = "H"; + static const AP_MotorsMatrix::MotorDefRaw motors[] { + { -1.0f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 }, + { 1.0f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 }, + { -1.0f, 0.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 }, + { -1.0f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 }, + { 1.0f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 }, + { 1.0f, -0.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 }, + { 1.0f, 0.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 }, + { -1.0f, -0.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 }, + }; + add_motors_raw(motors, ARRAY_SIZE(motors)); + break; + } + case MOTOR_FRAME_TYPE_I: { + _frame_type_string = "I"; + static const AP_MotorsMatrix::MotorDefRaw motors[] { + { 0.333f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 }, + { -0.333f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 }, + { 1.0f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 }, + { 0.333f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 }, + { -0.333f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 }, + { -1.0f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 }, + { -1.0f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 }, + { 1.0f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 }, + }; + add_motors_raw(motors, ARRAY_SIZE(motors)); + break; + } + case MOTOR_FRAME_TYPE_DJI_X: { + _frame_type_string = "DJI_X"; + static const AP_MotorsMatrix::MotorDef motors[] { + { 22.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, + { -22.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 8 }, + { -67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 7 }, + { -112.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 }, + { -157.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 }, + { 157.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 }, + { 112.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 }, + { 67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, + }; + add_motors(motors, ARRAY_SIZE(motors)); + break; + } + case MOTOR_FRAME_TYPE_CW_X: { + _frame_type_string = "CW_X"; + static const AP_MotorsMatrix::MotorDef motors[] { + { 22.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, + { 67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, + { 112.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 }, + { 157.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 }, + { -157.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 }, + { -112.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 }, + { -67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 7 }, + { -22.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 8 }, + }; + add_motors(motors, ARRAY_SIZE(motors)); + break; + } + default: + // octa frame class does not support this frame type + _frame_type_string = "UNSUPPORTED"; + return false; + } // octa frame type + return true; +} +#endif //AP_MOTORS_FRAME_OCTA_ENABLED +#if AP_MOTORS_FRAME_OCTAQUAD_ENABLED +bool AP_MotorsMatrix::setup_octaquad_matrix(motor_frame_type frame_type) +{ + _mav_type = MAV_TYPE_OCTOROTOR; + _frame_class_string = "OCTAQUAD"; + switch (frame_type) { + case MOTOR_FRAME_TYPE_PLUS: { + _frame_type_string = "PLUS"; + static const AP_MotorsMatrix::MotorDef motors[] { + { 0, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, + { -90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 }, + { 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 }, + { 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 }, + { -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 }, + { 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, + { 90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 }, + { 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 }, + }; + add_motors(motors, ARRAY_SIZE(motors)); + break; + } + case MOTOR_FRAME_TYPE_X: { + _frame_type_string = "X"; + static const AP_MotorsMatrix::MotorDef motors[] { + { 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, + { -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 }, + { -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 }, + { 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 }, + { -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 }, + { 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, + { 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 }, + { -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 }, + }; + add_motors(motors, ARRAY_SIZE(motors)); + break; + } + case MOTOR_FRAME_TYPE_V: { + _frame_type_string = "V"; + static const AP_MotorsMatrix::MotorDef motors[] { + { 45, 0.7981f, 1 }, + { -45, -0.7981f, 7 }, + { -135, 1.0000f, 5 }, + { 135, -1.0000f, 3 }, + { -45, 0.7981f, 8 }, + { 45, -0.7981f, 2 }, + { 135, 1.0000f, 4 }, + { -135, -1.0000f, 6 }, + }; + add_motors(motors, ARRAY_SIZE(motors)); + break; + } + case MOTOR_FRAME_TYPE_H: { + // H frame set-up - same as X but motors spin in opposite directions + _frame_type_string = "H"; + static const AP_MotorsMatrix::MotorDef motors[] { + { 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 }, + { -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 7 }, + { -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 }, + { 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 }, + { -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 8 }, + { 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 }, + { 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 }, + { -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 }, + }; + add_motors(motors, ARRAY_SIZE(motors)); + break; + } + case MOTOR_FRAME_TYPE_CW_X: { + _frame_type_string = "CW_X"; + static const AP_MotorsMatrix::MotorDef motors[] { + { 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, + { 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, + { 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 }, + { 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 }, + { -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 }, + { -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 }, + { -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 }, + { -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 }, + }; + add_motors(motors, ARRAY_SIZE(motors)); + break; + } + // BF/X cinelifters using two 4-in-1 ESCs are quite common + // see: https://fpvfrenzy.com/betaflight-motor-order/ + case MOTOR_FRAME_TYPE_BF_X: { + _frame_type_string = "BF_X"; + static const AP_MotorsMatrix::MotorDef motors[] { + { 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 }, + { 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, + { -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 }, + { -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 }, + { 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 }, + { 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, + { -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 }, + { -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 }, + }; + add_motors(motors, ARRAY_SIZE(motors)); + break; + } + case MOTOR_FRAME_TYPE_BF_X_REV: { + // betaflight octa quad X order, reversed motors + _frame_type_string = "X_REV"; + static const AP_MotorsMatrix::MotorDef motors[] { + { 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 }, + { 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 }, + { -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 }, + { -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 7 }, + { 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 }, + { 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 }, + { -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 }, + { -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 8 }, + }; + add_motors(motors, ARRAY_SIZE(motors)); + break; + } + default: + // octaquad frame class does not support this frame type + _frame_type_string = "UNSUPPORTED"; + return false; + } //octaquad + return true; +} +#endif // AP_MOTORS_FRAME_OCTAQUAD_ENABLED +#if AP_MOTORS_FRAME_DODECAHEXA_ENABLED +bool AP_MotorsMatrix::setup_dodecahexa_matrix(motor_frame_type frame_type) +{ + _mav_type = MAV_TYPE_DODECAROTOR; + _frame_class_string = "DODECAHEXA"; + switch (frame_type) { + case MOTOR_FRAME_TYPE_PLUS: { + _frame_type_string = "PLUS"; + static const AP_MotorsMatrix::MotorDef motors[] { + { 0, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, // forward-top + { 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, // forward-bottom + { 60, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 }, // forward-right-top + { 60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 }, // forward-right-bottom + { 120, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 }, // back-right-top + { 120, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 }, // back-right-bottom + { 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 }, // back-top + { 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 }, // back-bottom + { -120, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 9 }, // back-left-top + { -120, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 10 }, // back-left-bottom + { -60, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 11 }, // forward-left-top + { -60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 12 }, // forward-left-bottom + }; + add_motors(motors, ARRAY_SIZE(motors)); + break; + } + case MOTOR_FRAME_TYPE_X: { + _frame_type_string = "X"; + static const AP_MotorsMatrix::MotorDef motors[] { + { 30, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, // forward-right-top + { 30, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, // forward-right-bottom + { 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 }, // right-top + { 90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 }, // right-bottom + { 150, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 }, // back-right-top + { 150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 }, // back-right-bottom + { -150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 }, // back-left-top + { -150, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 }, // back-left-bottom + { -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 9 }, // left-top + { -90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 10 }, // left-bottom + { -30, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 11 }, // forward-left-top + { -30, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 12 }, // forward-left-bottom + }; + add_motors(motors, ARRAY_SIZE(motors)); + break; + } + default: + // dodeca-hexa frame class does not support this frame type + _frame_type_string = "UNSUPPORTED"; + return false; + } //dodecahexa + return true; +} +#endif //AP_MOTORS_FRAME_DODECAHEXA_ENABLED +#if AP_MOTORS_FRAME_Y6_ENABLED +bool AP_MotorsMatrix::setup_y6_matrix(motor_frame_type frame_type) +{ + _mav_type = MAV_TYPE_HEXAROTOR; + _frame_class_string = "Y6"; + switch (frame_type) { + case MOTOR_FRAME_TYPE_Y6B: { + // Y6 motor definition with all top motors spinning clockwise, all bottom motors counter clockwise + _frame_type_string = "Y6B"; + static const AP_MotorsMatrix::MotorDefRaw motors[] { + { -1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 }, + { -1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 }, + { 0.0f, -1.000f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 }, + { 0.0f, -1.000f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 }, + { 1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 }, + { 1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 }, + }; + add_motors_raw(motors, ARRAY_SIZE(motors)); + break; + } + case MOTOR_FRAME_TYPE_Y6F: { + // Y6 motor layout for FireFlyY6 + _frame_type_string = "Y6F"; + static const AP_MotorsMatrix::MotorDefRaw motors[] { + { 0.0f, -1.000f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 }, + { -1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, + { 1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 }, + { 0.0f, -1.000f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 }, + { -1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, + { 1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 }, + }; + add_motors_raw(motors, ARRAY_SIZE(motors)); + break; + } + default: { + _frame_type_string = "default"; + static const AP_MotorsMatrix::MotorDefRaw motors[] { + { -1.0f, 0.666f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 }, + { 1.0f, 0.666f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 }, + { 1.0f, 0.666f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 }, + { 0.0f, -1.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 }, + { -1.0f, 0.666f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 }, + { 0.0f, -1.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 }, + }; + add_motors_raw(motors, ARRAY_SIZE(motors)); + break; + } + } //y6 + return true; +} +#endif // AP_MOTORS_FRAME_Y6_ENABLED +#if AP_MOTORS_FRAME_DECA_ENABLED +bool AP_MotorsMatrix::setup_deca_matrix(motor_frame_type frame_type) +{ + _mav_type = MAV_TYPE_DECAROTOR; + _frame_class_string = "DECA"; + switch (frame_type) { + case MOTOR_FRAME_TYPE_PLUS: { + _frame_type_string = "PLUS"; + static const AP_MotorsMatrix::MotorDef motors[] { + { 0, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, + { 36, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, + { 72, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 }, + { 108, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 }, + { 144, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 }, + { 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 }, + { -144, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 7 }, + { -108, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 8 }, + { -72, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 9 }, + { -36, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 10 }, + }; + add_motors(motors, ARRAY_SIZE(motors)); + break; + } + case MOTOR_FRAME_TYPE_X: + case MOTOR_FRAME_TYPE_CW_X: { + _frame_type_string = "X/CW_X"; + static const AP_MotorsMatrix::MotorDef motors[] { + { 18, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, + { 54, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, + { 90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 }, + { 126, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 }, + { 162, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 }, + { -162, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 }, + { -126, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 7 }, + { -90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 8 }, + { -54, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 9 }, + { -18, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 10 }, + }; + add_motors(motors, ARRAY_SIZE(motors)); + break; + } + default: + // deca frame class does not support this frame type + return false; + } //deca + return true; +} +#endif // AP_MOTORS_FRAME_DECA_ENABLED void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_type frame_type) { @@ -581,645 +1255,46 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty switch (frame_class) { #if AP_MOTORS_FRAME_QUAD_ENABLED - case MOTOR_FRAME_QUAD: - _frame_class_string = "QUAD"; - _mav_type = MAV_TYPE_QUADROTOR; - switch (frame_type) { - case MOTOR_FRAME_TYPE_PLUS: { - _frame_type_string = "PLUS"; - static const AP_MotorsMatrix::MotorDef motors[] { - { 90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 }, - { -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 }, - { 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 }, - { 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 }, - }; - add_motors(motors, ARRAY_SIZE(motors)); - break; - } - case MOTOR_FRAME_TYPE_X: { - _frame_type_string = "X"; - static const AP_MotorsMatrix::MotorDef motors[] { - { 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, - { -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 }, - { -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 }, - { 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, - }; - add_motors(motors, ARRAY_SIZE(motors)); - break; - } -#if APM_BUILD_TYPE(APM_BUILD_ArduPlane) - case MOTOR_FRAME_TYPE_NYT_PLUS: { - _frame_type_string = "NYT_PLUS"; - static const AP_MotorsMatrix::MotorDef motors[] { - { 90, 0, 2 }, - { -90, 0, 4 }, - { 0, 0, 1 }, - { 180, 0, 3 }, - }; - add_motors(motors, ARRAY_SIZE(motors)); - break; - } - case MOTOR_FRAME_TYPE_NYT_X: { - _frame_type_string = "NYT_X"; - static const AP_MotorsMatrix::MotorDef motors[] { - { 45, 0, 1 }, - { -135, 0, 3 }, - { -45, 0, 4 }, - { 135, 0, 2 }, - }; - add_motors(motors, ARRAY_SIZE(motors)); - break; - } -#endif //APM_BUILD_TYPE(APM_BUILD_ArduPlane) - case MOTOR_FRAME_TYPE_BF_X: { - // betaflight quad X order - // see: https://fpvfrenzy.com/betaflight-motor-order/ - _frame_type_string = "BF_X"; - static const AP_MotorsMatrix::MotorDef motors[] { - { 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, - { 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, - { -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 }, - { -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 }, - }; - add_motors(motors, ARRAY_SIZE(motors)); - break; - } - case MOTOR_FRAME_TYPE_BF_X_REV: { - // betaflight quad X order, reversed motors - _frame_type_string = "X_REV"; - static const AP_MotorsMatrix::MotorDef motors[] { - { 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 }, - { 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 }, - { -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 }, - { -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 }, - }; - add_motors(motors, ARRAY_SIZE(motors)); - break; - } - case MOTOR_FRAME_TYPE_DJI_X: { - // DJI quad X order - // see https://forum44.djicdn.com/data/attachment/forum/201711/26/172348bppvtt1ot1nrtp5j.jpg - _frame_type_string = "DJI_X"; - static const AP_MotorsMatrix::MotorDef motors[] { - { 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, - { -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 }, - { -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 }, - { 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, - }; - add_motors(motors, ARRAY_SIZE(motors)); - break; - } - case MOTOR_FRAME_TYPE_CW_X: { - // "clockwise X" motor order. Motors are ordered clockwise from front right - // matching test order - _frame_type_string = "CW_X"; - static const AP_MotorsMatrix::MotorDef motors[] { - { 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, - { 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, - { -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 }, - { -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 }, - }; - add_motors(motors, ARRAY_SIZE(motors)); - break; - } - case MOTOR_FRAME_TYPE_V: { - _frame_type_string = "V"; - static const AP_MotorsMatrix::MotorDef motors[] { - { 45, 0.7981f, 1 }, - { -135, 1.0000f, 3 }, - { -45, -0.7981f, 4 }, - { 135, -1.0000f, 2 }, - }; - add_motors(motors, ARRAY_SIZE(motors)); - break; - } - case MOTOR_FRAME_TYPE_H: { - // H frame set-up - same as X but motors spin in opposite directiSons - _frame_type_string = "H"; - static const AP_MotorsMatrix::MotorDef motors[] { - { 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 }, - { -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 }, - { -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 }, - { 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 }, - }; - add_motors(motors, ARRAY_SIZE(motors)); - break; - } - case MOTOR_FRAME_TYPE_VTAIL: { - /* - Tested with: Lynxmotion Hunter Vtail 400 - - inverted rear outward blowing motors (at a 40 degree angle) - - should also work with non-inverted rear outward blowing motors - - no roll in rear motors - - no yaw in front motors - - should fly like some mix between a tricopter and X Quadcopter - - Roll control comes only from the front motors, Yaw control only from the rear motors. - Roll & Pitch factor is measured by the angle away from the top of the forward axis to each arm. - - Note: if we want the front motors to help with yaw, - motors 1's yaw factor should be changed to sin(radians(40)). Where "40" is the vtail angle - motors 3's yaw factor should be changed to -sin(radians(40)) - */ - _frame_type_string = "VTAIL"; - add_motor(AP_MOTORS_MOT_1, 60, 60, 0, 1); - add_motor(AP_MOTORS_MOT_2, 0, -160, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3); - add_motor(AP_MOTORS_MOT_3, -60, -60, 0, 4); - add_motor(AP_MOTORS_MOT_4, 0, 160, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2); - break; - } - case MOTOR_FRAME_TYPE_ATAIL: - /* - The A-Shaped VTail is the exact same as a V-Shaped VTail, with one difference: - - The Yaw factors are reversed, because the rear motors are facing different directions - - With V-Shaped VTails, the props make a V-Shape when spinning, but with - A-Shaped VTails, the props make an A-Shape when spinning. - - Rear thrust on a V-Shaped V-Tail Quad is outward - - Rear thrust on an A-Shaped V-Tail Quad is inward - - Still functions the same as the V-Shaped VTail mixing below: - - Yaw control is entirely in the rear motors - - Roll is is entirely in the front motors - */ - _frame_type_string = "ATAIL"; - add_motor(AP_MOTORS_MOT_1, 60, 60, 0, 1); - add_motor(AP_MOTORS_MOT_2, 0, -160, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3); - add_motor(AP_MOTORS_MOT_3, -60, -60, 0, 4); - add_motor(AP_MOTORS_MOT_4, 0, 160, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2); - break; - case MOTOR_FRAME_TYPE_PLUSREV:{ - // plus with reversed motor directions - _frame_type_string = "PLUSREV"; - static const AP_MotorsMatrix::MotorDef motors[] { - { 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, - { -90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 }, - { 0, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, - { 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 }, - }; - add_motors(motors, ARRAY_SIZE(motors)); - break; - } - case MOTOR_FRAME_TYPE_Y4: - _frame_type_string = "Y4"; - // Y4 motor definition with right front CCW, left front CW - static const AP_MotorsMatrix::MotorDefRaw motors[] { - { -1.0f, 1.000f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, - { 0.0f, -1.000f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, - { 0.0f, -1.000f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 }, - { 1.0f, 1.000f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 }, - }; - add_motors_raw(motors, ARRAY_SIZE(motors)); - break; - default: - // quad frame class does not support this frame type - _frame_type_string = "UNSUPPORTED"; - success = false; - break; - } - break; // quad + case MOTOR_FRAME_QUAD: + success = setup_quad_matrix(frame_type); + break; // quad #endif //AP_MOTORS_FRAME_QUAD_ENABLED #if AP_MOTORS_FRAME_HEXA_ENABLED - case MOTOR_FRAME_HEXA: - _frame_class_string = "HEXA"; - _mav_type = MAV_TYPE_HEXAROTOR; - switch (frame_type) { - case MOTOR_FRAME_TYPE_PLUS: { - _frame_type_string = "PLUS"; - static const AP_MotorsMatrix::MotorDef motors[] { - { 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 }, - { 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 }, - { -120, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 }, - { 60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 }, - { -60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 }, - { 120, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 }, - }; - add_motors(motors, ARRAY_SIZE(motors)); - break; - } - case MOTOR_FRAME_TYPE_X: { - _frame_type_string = "X"; - static const AP_MotorsMatrix::MotorDef motors[] { - { 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, - { -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 }, - { -30, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 }, - { 150, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 }, - { 30, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, - { -150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 }, - }; - add_motors(motors, ARRAY_SIZE(motors)); - break; - } - case MOTOR_FRAME_TYPE_H: { - // H is same as X except middle motors are closer to center - _frame_type_string = "H"; - static const AP_MotorsMatrix::MotorDefRaw motors[] { - { -1.0f, 0.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, - { 1.0f, 0.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 }, - { 1.0f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 }, - { -1.0f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 }, - { -1.0f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, - { 1.0f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 }, - }; - add_motors_raw(motors, ARRAY_SIZE(motors)); - break; - } - case MOTOR_FRAME_TYPE_DJI_X: { - _frame_type_string = "DJI_X"; - static const AP_MotorsMatrix::MotorDef motors[] { - { 30, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, - { -30, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 }, - { -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 }, - { -150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 }, - { 150, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 }, - { 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, - }; - add_motors(motors, ARRAY_SIZE(motors)); - break; - } - case MOTOR_FRAME_TYPE_CW_X: { - _frame_type_string = "CW_X"; - static const AP_MotorsMatrix::MotorDef motors[] { - { 30, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, - { 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, - { 150, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 }, - { -150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 }, - { -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 }, - { -30, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 }, - }; - add_motors(motors, ARRAY_SIZE(motors)); - break; - } - default: - // hexa frame class does not support this frame type - _frame_type_string = "UNSUPPORTED"; - success = false; - break; - } - break; + case MOTOR_FRAME_HEXA: + success = setup_hexa_matrix(frame_type); + break; #endif //AP_MOTORS_FRAME_HEXA_ENABLED #if AP_MOTORS_FRAME_OCTA_ENABLED - case MOTOR_FRAME_OCTA: - _frame_class_string = "OCTA"; - _mav_type = MAV_TYPE_OCTOROTOR; - switch (frame_type) { - case MOTOR_FRAME_TYPE_PLUS: { - _frame_type_string = "PLUS"; - static const AP_MotorsMatrix::MotorDef motors[] { - { 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 }, - { 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 }, - { 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 }, - { 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 }, - { -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 }, - { -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 }, - { -90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 }, - { 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 }, - }; - - add_motors(motors, ARRAY_SIZE(motors)); - break; - } - case MOTOR_FRAME_TYPE_X: { - _frame_type_string = "X"; - static const AP_MotorsMatrix::MotorDef motors[] { - { 22.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 }, - { -157.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 }, - { 67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 }, - { 157.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 }, - { -22.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 }, - { -112.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 }, - { -67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 }, - { 112.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 }, - }; - add_motors(motors, ARRAY_SIZE(motors)); - break; - } - case MOTOR_FRAME_TYPE_V: { - _frame_type_string = "V"; - static const AP_MotorsMatrix::MotorDefRaw motors[] { - { 0.83f, 0.34f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 }, - { -0.67f, -0.32f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 }, - { 0.67f, -0.32f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 }, - { -0.50f, -1.00f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 }, - { 1.00f, 1.00f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 }, - { -0.83f, 0.34f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 }, - { -1.00f, 1.00f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 }, - { 0.50f, -1.00f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 }, - }; - add_motors_raw(motors, ARRAY_SIZE(motors)); - break; - } - case MOTOR_FRAME_TYPE_H: { - _frame_type_string = "H"; - static const AP_MotorsMatrix::MotorDefRaw motors[] { - { -1.0f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 }, - { 1.0f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 }, - { -1.0f, 0.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 }, - { -1.0f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 }, - { 1.0f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 }, - { 1.0f, -0.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 }, - { 1.0f, 0.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 }, - { -1.0f, -0.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 }, - }; - add_motors_raw(motors, ARRAY_SIZE(motors)); - break; - } - case MOTOR_FRAME_TYPE_I: { - _frame_type_string = "I"; - static const AP_MotorsMatrix::MotorDefRaw motors[] { - { 0.333f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 }, - { -0.333f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 }, - { 1.0f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 }, - { 0.333f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 }, - { -0.333f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 }, - { -1.0f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 }, - { -1.0f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 }, - { 1.0f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 }, - }; - add_motors_raw(motors, ARRAY_SIZE(motors)); - break; - } - case MOTOR_FRAME_TYPE_DJI_X: { - _frame_type_string = "DJI_X"; - static const AP_MotorsMatrix::MotorDef motors[] { - { 22.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, - { -22.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 8 }, - { -67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 7 }, - { -112.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 }, - { -157.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 }, - { 157.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 }, - { 112.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 }, - { 67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, - }; - add_motors(motors, ARRAY_SIZE(motors)); - break; - } - case MOTOR_FRAME_TYPE_CW_X: { - _frame_type_string = "CW_X"; - static const AP_MotorsMatrix::MotorDef motors[] { - { 22.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, - { 67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, - { 112.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 }, - { 157.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 }, - { -157.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 }, - { -112.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 }, - { -67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 7 }, - { -22.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 8 }, - }; - add_motors(motors, ARRAY_SIZE(motors)); - break; - } - default: - // octa frame class does not support this frame type - _frame_type_string = "UNSUPPORTED"; - success = false; - break; - } // octa frame type - break; + case MOTOR_FRAME_OCTA: + success = setup_octa_matrix(frame_type); + break; #endif //AP_MOTORS_FRAME_OCTA_ENABLED #if AP_MOTORS_FRAME_OCTAQUAD_ENABLED - case MOTOR_FRAME_OCTAQUAD: - _mav_type = MAV_TYPE_OCTOROTOR; - _frame_class_string = "OCTAQUAD"; - switch (frame_type) { - case MOTOR_FRAME_TYPE_PLUS: { - _frame_type_string = "PLUS"; - static const AP_MotorsMatrix::MotorDef motors[] { - { 0, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, - { -90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 }, - { 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 }, - { 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 }, - { -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 }, - { 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, - { 90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 }, - { 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 }, - }; - add_motors(motors, ARRAY_SIZE(motors)); - break; - } - case MOTOR_FRAME_TYPE_X: { - _frame_type_string = "X"; - static const AP_MotorsMatrix::MotorDef motors[] { - { 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, - { -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 }, - { -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 }, - { 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 }, - { -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 }, - { 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, - { 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 }, - { -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 }, - }; - add_motors(motors, ARRAY_SIZE(motors)); - break; - } - case MOTOR_FRAME_TYPE_V: { - _frame_type_string = "V"; - static const AP_MotorsMatrix::MotorDef motors[] { - { 45, 0.7981f, 1 }, - { -45, -0.7981f, 7 }, - { -135, 1.0000f, 5 }, - { 135, -1.0000f, 3 }, - { -45, 0.7981f, 8 }, - { 45, -0.7981f, 2 }, - { 135, 1.0000f, 4 }, - { -135, -1.0000f, 6 }, - }; - add_motors(motors, ARRAY_SIZE(motors)); - break; - } - case MOTOR_FRAME_TYPE_H: { - // H frame set-up - same as X but motors spin in opposite directions - _frame_type_string = "H"; - static const AP_MotorsMatrix::MotorDef motors[] { - { 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 }, - { -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 7 }, - { -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 }, - { 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 }, - { -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 8 }, - { 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 }, - { 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 }, - { -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 }, - }; - add_motors(motors, ARRAY_SIZE(motors)); - break; - } - case MOTOR_FRAME_TYPE_CW_X: - _frame_type_string = "CW_X"; - static const AP_MotorsMatrix::MotorDef motors[] { - { 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, - { 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, - { 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 }, - { 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 }, - { -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 }, - { -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 }, - { -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 }, - { -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 }, - }; - add_motors(motors, ARRAY_SIZE(motors)); - break; - default: - // octaquad frame class does not support this frame type - _frame_type_string = "UNSUPPORTED"; - success = false; - break; - } - break; + case MOTOR_FRAME_OCTAQUAD: + success = setup_octaquad_matrix(frame_type); + break; #endif //AP_MOTORS_FRAME_OCTAQUAD_ENABLED #if AP_MOTORS_FRAME_DODECAHEXA_ENABLED - case MOTOR_FRAME_DODECAHEXA: { - _mav_type = MAV_TYPE_DODECAROTOR; - _frame_class_string = "DODECAHEXA"; - switch (frame_type) { - case MOTOR_FRAME_TYPE_PLUS: { - _frame_type_string = "PLUS"; - static const AP_MotorsMatrix::MotorDef motors[] { - { 0, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, // forward-top - { 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, // forward-bottom - { 60, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 }, // forward-right-top - { 60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 }, // forward-right-bottom - { 120, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 }, // back-right-top - { 120, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 }, // back-right-bottom - { 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 }, // back-top - { 180, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 }, // back-bottom - { -120, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 9 }, // back-left-top - { -120, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 10 }, // back-left-bottom - { -60, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 11 }, // forward-left-top - { -60, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 12 }, // forward-left-bottom - }; - add_motors(motors, ARRAY_SIZE(motors)); - break; - } - case MOTOR_FRAME_TYPE_X: { - _frame_type_string = "X"; - static const AP_MotorsMatrix::MotorDef motors[] { - { 30, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, // forward-right-top - { 30, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, // forward-right-bottom - { 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 }, // right-top - { 90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 }, // right-bottom - { 150, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 }, // back-right-top - { 150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 }, // back-right-bottom - { -150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7 }, // back-left-top - { -150, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8 }, // back-left-bottom - { -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 9 }, // left-top - { -90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 10 }, // left-bottom - { -30, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 11 }, // forward-left-top - { -30, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 12 }, // forward-left-bottom - }; - add_motors(motors, ARRAY_SIZE(motors)); - break; - } - default: - // dodeca-hexa frame class does not support this frame type - _frame_type_string = "UNSUPPORTED"; - success = false; - break; - }} - break; + case MOTOR_FRAME_DODECAHEXA: + success = setup_dodecahexa_matrix(frame_type); + break; #endif //AP_MOTORS_FRAME_DODECAHEXA_ENABLED #if AP_MOTORS_FRAME_Y6_ENABLED - case MOTOR_FRAME_Y6: - _mav_type = MAV_TYPE_HEXAROTOR; - _frame_class_string = "Y6"; - switch (frame_type) { - case MOTOR_FRAME_TYPE_Y6B: { - // Y6 motor definition with all top motors spinning clockwise, all bottom motors counter clockwise - _frame_type_string = "Y6B"; - static const AP_MotorsMatrix::MotorDefRaw motors[] { - { -1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 }, - { -1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 }, - { 0.0f, -1.000f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3 }, - { 0.0f, -1.000f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4 }, - { 1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 }, - { 1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 }, - }; - add_motors_raw(motors, ARRAY_SIZE(motors)); - break; - } - case MOTOR_FRAME_TYPE_Y6F: { - // Y6 motor layout for FireFlyY6 - _frame_type_string = "Y6F"; - static const AP_MotorsMatrix::MotorDefRaw motors[] { - { 0.0f, -1.000f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 }, - { -1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, - { 1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 }, - { 0.0f, -1.000f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 }, - { -1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, - { 1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 }, - }; - add_motors_raw(motors, ARRAY_SIZE(motors)); - break; - } - default: { - _frame_type_string = "default"; - static const AP_MotorsMatrix::MotorDefRaw motors[] { - { -1.0f, 0.666f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2 }, - { 1.0f, 0.666f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5 }, - { 1.0f, 0.666f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6 }, - { 0.0f, -1.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 }, - { -1.0f, 0.666f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1 }, - { 0.0f, -1.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 }, - }; - add_motors_raw(motors, ARRAY_SIZE(motors)); - break; - } - } - break; + case MOTOR_FRAME_Y6: + success = setup_y6_matrix(frame_type); + break; #endif //AP_MOTORS_FRAME_Y6_ENABLED #if AP_MOTORS_FRAME_DECA_ENABLED - case MOTOR_FRAME_DECA: - _mav_type = MAV_TYPE_DECAROTOR; - _frame_class_string = "DECA"; - switch (frame_type) { - case MOTOR_FRAME_TYPE_PLUS: { - _frame_type_string = "PLUS"; - static const AP_MotorsMatrix::MotorDef motors[] { - { 0, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, - { 36, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, - { 72, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 }, - { 108, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 }, - { 144, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 }, - { 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 }, - { -144, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 7 }, - { -108, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 8 }, - { -72, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 9 }, - { -36, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 10 }, - }; - add_motors(motors, ARRAY_SIZE(motors)); - break; - } - case MOTOR_FRAME_TYPE_X: - case MOTOR_FRAME_TYPE_CW_X: { - _frame_type_string = "X/CW_X"; - static const AP_MotorsMatrix::MotorDef motors[] { - { 18, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1 }, - { 54, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2 }, - { 90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3 }, - { 126, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4 }, - { 162, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5 }, - { -162, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6 }, - { -126, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 7 }, - { -90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 8 }, - { -54, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 9 }, - { -18, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 10 }, - }; - add_motors(motors, ARRAY_SIZE(motors)); - break; - } - default: - // deca frame class does not support this frame type - success = false; - break; - } - break; + case MOTOR_FRAME_DECA: + success = setup_deca_matrix(frame_type); + break; #endif //AP_MOTORS_FRAME_DECA_ENABLED - default: - // matrix doesn't support the configured class - _frame_class_string = "UNSUPPORTED"; - success = false; - _mav_type = MAV_TYPE_GENERIC; - break; - - + default: + // matrix doesn't support the configured class + _frame_class_string = "UNSUPPORTED"; + success = false; + _mav_type = MAV_TYPE_GENERIC; + break; } // switch frame_class // normalise factors to magnitude 0.5 diff --git a/libraries/AP_Motors/AP_MotorsMatrix.h b/libraries/AP_Motors/AP_MotorsMatrix.h index e21311ff8b5..5b2061546fc 100644 --- a/libraries/AP_Motors/AP_MotorsMatrix.h +++ b/libraries/AP_Motors/AP_MotorsMatrix.h @@ -15,8 +15,8 @@ class AP_MotorsMatrix : public AP_MotorsMulticopter { public: /// Constructor - AP_MotorsMatrix(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : - AP_MotorsMulticopter(loop_rate, speed_hz) + AP_MotorsMatrix(uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : + AP_MotorsMulticopter(speed_hz) { if (_singleton != nullptr) { AP_HAL::panic("AP_MotorsMatrix must be singleton"); @@ -60,7 +60,7 @@ class AP_MotorsMatrix : public AP_MotorsMulticopter { // get_motor_mask - returns a bitmask of which outputs are being used for motors (1 means being used) // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict - uint16_t get_motor_mask() override; + uint32_t get_motor_mask() override; // return number of motor that has failed. Should only be called if get_thrust_boost() returns true uint8_t get_lost_motor() const override { return _motor_lost_index; } @@ -150,6 +150,16 @@ class AP_MotorsMatrix : public AP_MotorsMulticopter { const char* _frame_class_string = ""; // string representation of frame class const char* _frame_type_string = ""; // string representation of frame type + private: + // setup motors matrix + bool setup_quad_matrix(motor_frame_type frame_type); + bool setup_hexa_matrix(motor_frame_type frame_type); + bool setup_octa_matrix(motor_frame_type frame_type); + bool setup_deca_matrix(motor_frame_type frame_type); + bool setup_dodecahexa_matrix(motor_frame_type frame_type); + bool setup_y6_matrix(motor_frame_type frame_type); + bool setup_octaquad_matrix(motor_frame_type frame_type); + static AP_MotorsMatrix *_singleton; }; diff --git a/libraries/AP_Motors/AP_MotorsMatrix_6DoF_Scripting.cpp b/libraries/AP_Motors/AP_MotorsMatrix_6DoF_Scripting.cpp index f1d640fe627..9aeb88003a5 100644 --- a/libraries/AP_Motors/AP_MotorsMatrix_6DoF_Scripting.cpp +++ b/libraries/AP_Motors/AP_MotorsMatrix_6DoF_Scripting.cpp @@ -18,6 +18,7 @@ #include #include "AP_MotorsMatrix_6DoF_Scripting.h" #include +#include extern const AP_HAL::HAL& hal; diff --git a/libraries/AP_Motors/AP_MotorsMatrix_6DoF_Scripting.h b/libraries/AP_Motors/AP_MotorsMatrix_6DoF_Scripting.h index 86b973b0934..3b083b7e686 100644 --- a/libraries/AP_Motors/AP_MotorsMatrix_6DoF_Scripting.h +++ b/libraries/AP_Motors/AP_MotorsMatrix_6DoF_Scripting.h @@ -10,8 +10,8 @@ class AP_MotorsMatrix_6DoF_Scripting : public AP_MotorsMatrix { public: /// Constructor - AP_MotorsMatrix_6DoF_Scripting(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : - AP_MotorsMatrix(loop_rate, speed_hz) + AP_MotorsMatrix_6DoF_Scripting(uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : + AP_MotorsMatrix(speed_hz) { if (_singleton != nullptr) { AP_HAL::panic("AP_MotorsMatrix 6DoF must be singleton"); diff --git a/libraries/AP_Motors/AP_MotorsMatrix_Scripting_Dynamic.h b/libraries/AP_Motors/AP_MotorsMatrix_Scripting_Dynamic.h index 70879d00402..12b86281c57 100644 --- a/libraries/AP_Motors/AP_MotorsMatrix_Scripting_Dynamic.h +++ b/libraries/AP_Motors/AP_MotorsMatrix_Scripting_Dynamic.h @@ -7,8 +7,8 @@ class AP_MotorsMatrix_Scripting_Dynamic : public AP_MotorsMatrix { public: // Constructor - AP_MotorsMatrix_Scripting_Dynamic(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : - AP_MotorsMatrix(loop_rate, speed_hz) + AP_MotorsMatrix_Scripting_Dynamic(uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : + AP_MotorsMatrix(speed_hz) { if (_singleton != nullptr) { AP_HAL::panic("AP_MotorsMatrix_Scripting_Dynamic must be singleton"); diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.cpp b/libraries/AP_Motors/AP_MotorsMulticopter.cpp index b3fcfe27b69..c0aacdddda8 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.cpp +++ b/libraries/AP_Motors/AP_MotorsMulticopter.cpp @@ -16,6 +16,7 @@ #include "AP_MotorsMulticopter.h" #include #include +#include #include extern const AP_HAL::HAL& hal; @@ -103,7 +104,7 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = { // @Param: SPIN_MIN // @DisplayName: Motor Spin minimum // @Description: Point at which the thrust starts expressed as a number from 0 to 1 in the entire output range. Should be higher than MOT_SPIN_ARM. - // @Values: 0.0:Low, 0.15:Default, 0.3:High + // @Values: 0.0:Low, 0.15:Default, 0.25:High // @User: Advanced AP_GROUPINFO("SPIN_MIN", 18, AP_MotorsMulticopter, _spin_min, AP_MOTORS_SPIN_MIN_DEFAULT), @@ -147,7 +148,7 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = { // @Param: YAW_SV_ANGLE // @DisplayName: Yaw Servo Max Lean Angle - // @Description: Yaw servo's maximum lean angle + // @Description: Yaw servo's maximum lean angle (Tricopter only) // @Range: 5 80 // @Units: deg // @Increment: 1 @@ -211,8 +212,8 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = { }; // Constructor -AP_MotorsMulticopter::AP_MotorsMulticopter(uint16_t loop_rate, uint16_t speed_hz) : - AP_Motors(loop_rate, speed_hz), +AP_MotorsMulticopter::AP_MotorsMulticopter(uint16_t speed_hz) : + AP_Motors(speed_hz), _lift_max(1.0f), _throttle_limit(1.0f) { @@ -284,7 +285,7 @@ void AP_MotorsMulticopter::output_min() void AP_MotorsMulticopter::update_throttle_filter() { if (armed()) { - _throttle_filter.apply(_throttle_in, 1.0f / _loop_rate); + _throttle_filter.apply(_throttle_in, _dt); // constrain filtered throttle if (_throttle_filter.get() < 0.0f) { _throttle_filter.reset(0.0f); @@ -323,8 +324,7 @@ float AP_MotorsMulticopter::get_current_limit_max_throttle() float batt_current_ratio = _batt_current / batt_current_max; - float loop_interval = 1.0f / _loop_rate; - _throttle_limit += (loop_interval / (loop_interval + _batt_current_time_constant)) * (1.0f - batt_current_ratio); + _throttle_limit += (_dt / (_dt + _batt_current_time_constant)) * (1.0f - batt_current_ratio); // throttle limit drops to 20% between hover and full throttle _throttle_limit = constrain_float(_throttle_limit, 0.2f, 1.0f); @@ -382,13 +382,13 @@ void AP_MotorsMulticopter::update_lift_max_from_batt_voltage() return; } - _batt_voltage_min = MAX(_batt_voltage_min, _batt_voltage_max * 0.6f); + _batt_voltage_min.set(MAX(_batt_voltage_min, _batt_voltage_max * 0.6f)); // contrain resting voltage estimate (resting voltage is actual voltage with sag removed based on current draw and resistance) _batt_voltage_resting_estimate = constrain_float(_batt_voltage_resting_estimate, _batt_voltage_min, _batt_voltage_max); // filter at 0.5 Hz - float batt_voltage_filt = _batt_voltage_filt.apply(_batt_voltage_resting_estimate / _batt_voltage_max, 1.0f / _loop_rate); + float batt_voltage_filt = _batt_voltage_filt.apply(_batt_voltage_resting_estimate / _batt_voltage_max, _dt); // calculate lift max float thrust_curve_expo = constrain_float(_thrust_curve_expo, -1.0f, 1.0f); @@ -478,13 +478,13 @@ void AP_MotorsMulticopter::set_actuator_with_slew(float& actuator_output, float // If MOT_SLEW_UP_TIME is set, calculate the highest allowed new output value, constrained 0.0~1.0 if (is_positive(_slew_up_time)) { - float output_delta_up_max = 1.0f / (constrain_float(_slew_up_time, 0.0f, 0.5f) * _loop_rate); + float output_delta_up_max = _dt / (constrain_float(_slew_up_time, 0.0f, 0.5f)); output_slew_limit_up = constrain_float(actuator_output + output_delta_up_max, 0.0f, 1.0f); } // If MOT_SLEW_DN_TIME is set, calculate the lowest allowed new output value, constrained 0.0~1.0 if (is_positive(_slew_dn_time)) { - float output_delta_dn_max = 1.0f / (constrain_float(_slew_dn_time, 0.0f, 0.5f) * _loop_rate); + float output_delta_dn_max = _dt / (constrain_float(_slew_dn_time, 0.0f, 0.5f)); output_slew_limit_dn = constrain_float(actuator_output - output_delta_dn_max, 0.0f, 1.0f); } @@ -501,12 +501,10 @@ float AP_MotorsMulticopter::actuator_spin_up_to_ground_idle() const // parameter checks for MOT_PWM_MIN/MAX, returns true if parameters are valid bool AP_MotorsMulticopter::check_mot_pwm_params() const { - // sanity says that minimum should be less than maximum: - if (_pwm_min >= _pwm_max) { - return false; - } - // negative values are out-of-range: - if (_pwm_max <= 0) { + // _pwm_min is a value greater than or equal to 1. + // _pwm_max is greater than _pwm_min. + // The values of _pwm_min and _pwm_max are positive values. + if (_pwm_min < 1 || _pwm_min >= _pwm_max) { return false; } return true; @@ -518,8 +516,8 @@ void AP_MotorsMulticopter::update_throttle_range() // if all outputs are digital adjust the range. We also do this for type PWM_RANGE, as those use the // scaled output, which is then mapped to PWM via the SRV_Channel library if (SRV_Channels::have_digital_outputs(get_motor_mask()) || (_pwm_type == PWM_TYPE_PWM_RANGE)) { - _pwm_min = 1000; - _pwm_max = 2000; + _pwm_min.set_and_default(1000); + _pwm_max.set_and_default(2000); } hal.rcout->set_esc_scaling(get_pwm_output_min(), get_pwm_output_max()); @@ -530,7 +528,7 @@ void AP_MotorsMulticopter::update_throttle_hover(float dt) { if (_throttle_hover_learn != HOVER_LEARN_DISABLED) { // we have chosen to constrain the hover throttle to be within the range reachable by the third order expo polynomial. - _throttle_hover = constrain_float(_throttle_hover + (dt / (dt + AP_MOTORS_THST_HOVER_TC)) * (get_throttle() - _throttle_hover), AP_MOTORS_THST_HOVER_MIN, AP_MOTORS_THST_HOVER_MAX); + _throttle_hover.set(constrain_float(_throttle_hover + (dt / (dt + AP_MOTORS_THST_HOVER_TC)) * (get_throttle() - _throttle_hover), AP_MOTORS_THST_HOVER_MIN, AP_MOTORS_THST_HOVER_MAX)); } } @@ -539,7 +537,7 @@ void AP_MotorsMulticopter::output_logic() { if (armed()) { if (_disarm_disable_pwm && (_disarm_safe_timer < _safe_time)) { - _disarm_safe_timer += 1.0f/_loop_rate; + _disarm_safe_timer += _dt; } else { _disarm_safe_timer = _safe_time; } @@ -558,6 +556,7 @@ void AP_MotorsMulticopter::output_logic() _spool_up_time.set(0.05); } + const float spool_step = _dt / _spool_up_time; switch (_spool_state) { case SpoolState::SHUT_DOWN: // Motors should be stationary. @@ -597,7 +596,6 @@ void AP_MotorsMulticopter::output_logic() limit.throttle_upper = true; // set and increment ramp variables - float spool_step = 1.0f / (_spool_up_time * _loop_rate); switch (_spool_desired) { case DesiredSpoolState::SHUT_DOWN: _spin_up_ratio -= spool_step; @@ -613,7 +611,10 @@ void AP_MotorsMulticopter::output_logic() // constrain ramp value and update mode if (_spin_up_ratio >= 1.0f) { _spin_up_ratio = 1.0f; - _spool_state = SpoolState::SPOOLING_UP; + if (!get_spoolup_block()) { + // Only advance from ground idle if spoolup checks have passed + _spool_state = SpoolState::SPOOLING_UP; + } } break; @@ -651,7 +652,7 @@ void AP_MotorsMulticopter::output_logic() // set and increment ramp variables _spin_up_ratio = 1.0f; - _throttle_thrust_max += 1.0f / (_spool_up_time * _loop_rate); + _throttle_thrust_max += spool_step; // constrain ramp value and update mode if (_throttle_thrust_max >= MIN(get_throttle(), get_current_limit_max_throttle())) { @@ -663,7 +664,7 @@ void AP_MotorsMulticopter::output_logic() // initialise motor failure variables _thrust_boost = false; - _thrust_boost_ratio = MAX(0.0, _thrust_boost_ratio - 1.0 / (_spool_up_time * _loop_rate)); + _thrust_boost_ratio = MAX(0.0, _thrust_boost_ratio - spool_step); break; case SpoolState::THROTTLE_UNLIMITED: @@ -688,9 +689,9 @@ void AP_MotorsMulticopter::output_logic() _throttle_thrust_max = get_current_limit_max_throttle(); if (_thrust_boost && !_thrust_balanced) { - _thrust_boost_ratio = MIN(1.0, _thrust_boost_ratio + 1.0f / (_spool_up_time * _loop_rate)); + _thrust_boost_ratio = MIN(1.0, _thrust_boost_ratio + spool_step); } else { - _thrust_boost_ratio = MAX(0.0, _thrust_boost_ratio - 1.0f / (_spool_up_time * _loop_rate)); + _thrust_boost_ratio = MAX(0.0, _thrust_boost_ratio - spool_step); } break; @@ -713,7 +714,7 @@ void AP_MotorsMulticopter::output_logic() // set and increment ramp variables _spin_up_ratio = 1.0f; - _throttle_thrust_max -= 1.0f / (_spool_up_time * _loop_rate); + _throttle_thrust_max -= spool_step; // constrain ramp value and update mode if (_throttle_thrust_max <= 0.0f) { @@ -725,7 +726,7 @@ void AP_MotorsMulticopter::output_logic() _spool_state = SpoolState::GROUND_IDLE; } - _thrust_boost_ratio = MAX(0.0, _thrust_boost_ratio - 1.0f / (_spool_up_time * _loop_rate)); + _thrust_boost_ratio = MAX(0.0, _thrust_boost_ratio - spool_step); break; } } @@ -777,7 +778,7 @@ void AP_MotorsMulticopter::output_motor_mask(float thrust, uint8_t mask, float r // get_motor_mask - returns a bitmask of which outputs are being used for motors (1 means being used) // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict -uint16_t AP_MotorsMulticopter::get_motor_mask() +uint32_t AP_MotorsMulticopter::get_motor_mask() { return SRV_Channels::get_output_channel_mask(SRV_Channel::k_boost_throttle); } @@ -794,9 +795,41 @@ void AP_MotorsMulticopter::save_params_on_disarm() // convert to PWM min and max in the motor lib void AP_MotorsMulticopter::convert_pwm_min_max_param(int16_t radio_min, int16_t radio_max) { - if (_pwm_min.configured_in_storage() || _pwm_max.configured_in_storage()) { + if (_pwm_min.configured() || _pwm_max.configured()) { return; } _pwm_min.set_and_save(radio_min); _pwm_max.set_and_save(radio_max); } + +bool AP_MotorsMulticopter::arming_checks(size_t buflen, char *buffer) const +{ + // run base class checks + if (!AP_Motors::arming_checks(buflen, buffer)) { + return false; + } + + // Check output function is setup for each motor + for (uint8_t i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) { + if (!motor_enabled[i]) { + continue; + } + uint8_t chan; + SRV_Channel::Aux_servo_function_t function = SRV_Channels::get_motor_function(i); + if (!SRV_Channels::find_channel(function, chan)) { + hal.util->snprintf(buffer, buflen, "no SERVOx_FUNCTION set to Motor%u", i + 1); + return false; + } + } + + if (_spin_min > 0.3) { + hal.util->snprintf(buffer, buflen, "SPIN_MIN too high %.2f, max 0.3", _spin_min.get()); + return false; + } + if (_spin_arm > _spin_min) { + hal.util->snprintf(buffer, buflen, "SPIN_ARM higher than SPIN_MIN"); + return false; + } + + return true; +} diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.h b/libraries/AP_Motors/AP_MotorsMulticopter.h index 7cbc53dcd98..3fc19f55308 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.h +++ b/libraries/AP_Motors/AP_MotorsMulticopter.h @@ -33,7 +33,7 @@ class AP_MotorsMulticopter : public AP_Motors { public: // Constructor - AP_MotorsMulticopter(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT); + AP_MotorsMulticopter(uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT); // output - sends commands to the motors virtual void output() override; @@ -42,7 +42,7 @@ class AP_MotorsMulticopter : public AP_Motors { void output_min() override; // set_yaw_headroom - set yaw headroom (yaw is given at least this amount of pwm) - void set_yaw_headroom(int16_t pwm) { _yaw_headroom = pwm; } + void set_yaw_headroom(int16_t pwm) { _yaw_headroom.set(pwm); } // update_throttle_range - update throttle endpoints void update_throttle_range(); @@ -68,7 +68,7 @@ class AP_MotorsMulticopter : public AP_Motors { // get_motor_mask - returns a bitmask of which outputs are being used for motors (1 means being used) // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict - virtual uint16_t get_motor_mask() override; + virtual uint32_t get_motor_mask() override; // get minimum or maximum pwm value that can be output to motors int16_t get_pwm_output_min() const { return _pwm_min; } @@ -102,6 +102,9 @@ class AP_MotorsMulticopter : public AP_Motors { // 10hz logging of voltage scaling and max trust void Log_Write() override; + // Run arming checks + bool arming_checks(size_t buflen, char *buffer) const override; + // var_info for holding Parameter information static const struct AP_Param::GroupInfo var_info[]; diff --git a/libraries/AP_Motors/AP_MotorsSingle.cpp b/libraries/AP_Motors/AP_MotorsSingle.cpp index 74c000ec6f6..c693e53b052 100644 --- a/libraries/AP_Motors/AP_MotorsSingle.cpp +++ b/libraries/AP_Motors/AP_MotorsSingle.cpp @@ -103,7 +103,7 @@ void AP_MotorsSingle::output_to_motors() // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used) // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict -uint16_t AP_MotorsSingle::get_motor_mask() +uint32_t AP_MotorsSingle::get_motor_mask() { uint32_t motor_mask = 1U << AP_MOTORS_MOT_1 | @@ -113,7 +113,7 @@ uint16_t AP_MotorsSingle::get_motor_mask() 1U << AP_MOTORS_MOT_5 | 1U << AP_MOTORS_MOT_6; - uint16_t mask = motor_mask_to_srv_channel_mask(motor_mask); + uint32_t mask = motor_mask_to_srv_channel_mask(motor_mask); // add parent's mask mask |= AP_MotorsMulticopter::get_motor_mask(); @@ -162,7 +162,7 @@ void AP_MotorsSingle::output_armed_stabilizing() if (is_zero(rp_thrust_max)) { rp_scale = 1.0f; } else { - rp_scale = constrain_float((1.0f - MIN(fabsf(yaw_thrust), (float) _yaw_headroom / 1000.0f)) / rp_thrust_max, 0.0f, 1.0f); + rp_scale = constrain_float((1.0f - MIN(fabsf(yaw_thrust), (float) _yaw_headroom * 0.001f)) / rp_thrust_max, 0.0f, 1.0f); if (rp_scale < 1.0f) { limit.roll = true; limit.pitch = true; diff --git a/libraries/AP_Motors/AP_MotorsSingle.h b/libraries/AP_Motors/AP_MotorsSingle.h index 2de48660118..5f9264dcf5a 100644 --- a/libraries/AP_Motors/AP_MotorsSingle.h +++ b/libraries/AP_Motors/AP_MotorsSingle.h @@ -23,8 +23,8 @@ class AP_MotorsSingle : public AP_MotorsMulticopter { public: /// Constructor - AP_MotorsSingle(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : - AP_MotorsMulticopter(loop_rate, speed_hz) + AP_MotorsSingle(uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : + AP_MotorsMulticopter(speed_hz) { }; @@ -42,7 +42,10 @@ class AP_MotorsSingle : public AP_MotorsMulticopter { // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used) // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict - uint16_t get_motor_mask() override; + uint32_t get_motor_mask() override; + + // Run arming checks + bool arming_checks(size_t buflen, char *buffer) const override { return AP_Motors::arming_checks(buflen, buffer); } protected: // output - sends commands to the motors diff --git a/libraries/AP_Motors/AP_MotorsTailsitter.cpp b/libraries/AP_Motors/AP_MotorsTailsitter.cpp index 7fca4cab2b5..ae1a361d3c9 100644 --- a/libraries/AP_Motors/AP_MotorsTailsitter.cpp +++ b/libraries/AP_Motors/AP_MotorsTailsitter.cpp @@ -55,8 +55,8 @@ void AP_MotorsTailsitter::init(motor_frame_class frame_class, motor_frame_type f /// Constructor -AP_MotorsTailsitter::AP_MotorsTailsitter(uint16_t loop_rate, uint16_t speed_hz) : - AP_MotorsMulticopter(loop_rate, speed_hz) +AP_MotorsTailsitter::AP_MotorsTailsitter(uint16_t speed_hz) : + AP_MotorsMulticopter(speed_hz) { set_update_rate(speed_hz); } @@ -113,7 +113,7 @@ void AP_MotorsTailsitter::output_to_motors() // get_motor_mask - returns a bitmask of which outputs are being used for motors (1 means being used) // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict -uint16_t AP_MotorsTailsitter::get_motor_mask() +uint32_t AP_MotorsTailsitter::get_motor_mask() { uint32_t motor_mask = 0; uint8_t chan; diff --git a/libraries/AP_Motors/AP_MotorsTailsitter.h b/libraries/AP_Motors/AP_MotorsTailsitter.h index 53f1d7a2a2f..e1d6e9fa3e1 100644 --- a/libraries/AP_Motors/AP_MotorsTailsitter.h +++ b/libraries/AP_Motors/AP_MotorsTailsitter.h @@ -12,7 +12,7 @@ class AP_MotorsTailsitter : public AP_MotorsMulticopter { public: /// Constructor - AP_MotorsTailsitter(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT); + AP_MotorsTailsitter(uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT); // init void init(motor_frame_class frame_class, motor_frame_type frame_type) override; @@ -28,7 +28,7 @@ class AP_MotorsTailsitter : public AP_MotorsMulticopter { // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used) // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict - uint16_t get_motor_mask() override; + uint32_t get_motor_mask() override; // Set by tailsitters using diskloading minumum outflow velocity limit void set_min_throttle(float val) {_external_min_throttle = val;} diff --git a/libraries/AP_Motors/AP_MotorsTri.cpp b/libraries/AP_Motors/AP_MotorsTri.cpp index 9641cda727b..ab734a8b15b 100644 --- a/libraries/AP_Motors/AP_MotorsTri.cpp +++ b/libraries/AP_Motors/AP_MotorsTri.cpp @@ -14,8 +14,11 @@ */ #include +#include + #include #include + #include "AP_MotorsTri.h" extern const AP_HAL::HAL& hal; @@ -124,13 +127,13 @@ void AP_MotorsTri::output_to_motors() // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used) // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict -uint16_t AP_MotorsTri::get_motor_mask() +uint32_t AP_MotorsTri::get_motor_mask() { // tri copter uses channels 1,2,4 and 7 - uint16_t motor_mask = (1U << AP_MOTORS_MOT_1) | + uint32_t motor_mask = (1U << AP_MOTORS_MOT_1) | (1U << AP_MOTORS_MOT_2) | (1U << AP_MOTORS_MOT_4); - uint16_t mask = motor_mask_to_srv_channel_mask(motor_mask); + uint32_t mask = motor_mask_to_srv_channel_mask(motor_mask); // add parent's mask mask |= AP_MotorsMulticopter::get_motor_mask(); @@ -156,7 +159,7 @@ void AP_MotorsTri::output_armed_stabilizing() SRV_Channels::set_angle(SRV_Channels::get_motor_function(AP_MOTORS_CH_TRI_YAW), _yaw_servo_angle_max_deg*100); // sanity check YAW_SV_ANGLE parameter value to avoid divide by zero - _yaw_servo_angle_max_deg = constrain_float(_yaw_servo_angle_max_deg, AP_MOTORS_TRI_SERVO_RANGE_DEG_MIN, AP_MOTORS_TRI_SERVO_RANGE_DEG_MAX); + _yaw_servo_angle_max_deg.set(constrain_float(_yaw_servo_angle_max_deg, AP_MOTORS_TRI_SERVO_RANGE_DEG_MIN, AP_MOTORS_TRI_SERVO_RANGE_DEG_MAX)); // apply voltage and air pressure compensation const float compensation_gain = get_compensation_gain(); diff --git a/libraries/AP_Motors/AP_MotorsTri.h b/libraries/AP_Motors/AP_MotorsTri.h index 893fb174b88..3aeb807ddf0 100644 --- a/libraries/AP_Motors/AP_MotorsTri.h +++ b/libraries/AP_Motors/AP_MotorsTri.h @@ -18,8 +18,8 @@ class AP_MotorsTri : public AP_MotorsMulticopter { public: /// Constructor - AP_MotorsTri(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : - AP_MotorsMulticopter(loop_rate, speed_hz) + AP_MotorsTri(uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : + AP_MotorsMulticopter(speed_hz) { }; @@ -37,7 +37,7 @@ class AP_MotorsTri : public AP_MotorsMulticopter { // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used) // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict - uint16_t get_motor_mask() override; + uint32_t get_motor_mask() override; // output a thrust to all motors that match a given motor // mask. This is used to control tiltrotor motors in forward diff --git a/libraries/AP_Motors/AP_Motors_Class.cpp b/libraries/AP_Motors/AP_Motors_Class.cpp index 7f51eea1cc7..3951e17d29d 100644 --- a/libraries/AP_Motors/AP_Motors_Class.cpp +++ b/libraries/AP_Motors/AP_Motors_Class.cpp @@ -17,6 +17,7 @@ #include #include #include +#include extern const AP_HAL::HAL& hal; @@ -24,8 +25,7 @@ extern const AP_HAL::HAL& hal; AP_Motors *AP_Motors::_singleton; // Constructor -AP_Motors::AP_Motors(uint16_t loop_rate, uint16_t speed_hz) : - _loop_rate(loop_rate), +AP_Motors::AP_Motors(uint16_t speed_hz) : _speed_hz(speed_hz), _throttle_filter(), _spool_desired(DesiredSpoolState::SHUT_DOWN), @@ -124,6 +124,7 @@ void AP_Motors::rc_set_freq(uint32_t motor_mask, uint16_t freq_hz) const uint32_t mask = motor_mask_to_srv_channel_mask(motor_mask); hal.rcout->set_freq(mask, freq_hz); + hal.rcout->set_dshot_esc_type(SRV_Channels::get_dshot_esc_type()); switch (pwm_type(_pwm_type.get())) { case PWM_TYPE_ONESHOT: @@ -195,12 +196,8 @@ void AP_Motors::add_motor_num(int8_t motor_num) { // ensure valid motor number is provided if (motor_num >= 0 && motor_num < AP_MOTORS_MAX_NUM_MOTORS) { - uint8_t chan; SRV_Channel::Aux_servo_function_t function = SRV_Channels::get_motor_function(motor_num); SRV_Channels::set_aux_channel_default(function, motor_num); - if (!SRV_Channels::find_channel(function, chan)) { - gcs().send_text(MAV_SEVERITY_ERROR, "Motors: unable to setup motor %u", motor_num); - } } } @@ -266,6 +263,16 @@ void AP_Motors::output_test_seq(uint8_t motor_seq, int16_t pwm) } } +bool AP_Motors::arming_checks(size_t buflen, char *buffer) const +{ + if (!initialised_ok()) { + hal.util->snprintf(buffer, buflen, "Check frame class and type"); + return false; + } + + return true; +} + namespace AP { AP_Motors *motors() { diff --git a/libraries/AP_Motors/AP_Motors_Class.h b/libraries/AP_Motors/AP_Motors_Class.h index e9feb01b66d..83e23b0b154 100644 --- a/libraries/AP_Motors/AP_Motors_Class.h +++ b/libraries/AP_Motors/AP_Motors_Class.h @@ -1,10 +1,9 @@ #pragma once #include -#include // ArduPilot Mega Vector/Matrix math Library -#include // Notify library -#include +#include #include // filter library +#include // offsets for motors in motor_out and _motor_filtered arrays #define AP_MOTORS_MOT_1 0U @@ -104,12 +103,13 @@ class AP_Motors { void get_frame_and_type_string(char *buffer, uint8_t buflen) const; // Constructor - AP_Motors(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT); + AP_Motors(uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT); // singleton support static AP_Motors *get_singleton(void) { return _singleton; } // check initialisation succeeded + virtual bool arming_checks(size_t buflen, char *buffer) const; bool initialised_ok() const { return _initialised_ok; } void set_initialised_ok(bool val) { _initialised_ok = val; } @@ -123,6 +123,10 @@ class AP_Motors { // get motor interlock status. true means motors run, false motors don't run bool get_interlock() const { return _interlock; } + // get/set spoolup block + bool get_spoolup_block() const { return _spoolup_block; } + void set_spoolup_block(bool set) { _spoolup_block = set; } + // set_roll, set_pitch, set_yaw, set_throttle void set_roll(float roll_in) { _roll_in = roll_in; }; // range -1 ~ +1 void set_roll_ff(float roll_in) { _roll_in_ff = roll_in; }; // range -1 ~ +1 @@ -184,6 +188,12 @@ class AP_Motors { // set_density_ratio - sets air density as a proportion of sea level density void set_air_density_ratio(float ratio) { _air_density_ratio = ratio; } + // set_dt / get_dt - dt is the time since the last time the motor mixers were updated + // _dt should be set based on the time of the last IMU read used by these controllers + // the motor mixers should run on each loop to ensure normal operation + void set_dt(float dt) { _dt = dt; } + float get_dt() const { return _dt; } + // structure for holding motor limit flags struct AP_Motors_limit { uint8_t roll : 1; // we have reached roll or pitch limit @@ -222,14 +232,11 @@ class AP_Motors { // get_motor_mask - returns a bitmask of which outputs are being used for motors (1 means being used) // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict - virtual uint16_t get_motor_mask() = 0; + virtual uint32_t get_motor_mask() = 0; // pilot input in the -1 ~ +1 range for roll, pitch and yaw. 0~1 range for throttle void set_radio_passthrough(float roll_input, float pitch_input, float throttle_input, float yaw_input); - // set loop rate. Used to support loop rate as a parameter - void set_loop_rate(uint16_t loop_rate) { _loop_rate = loop_rate; } - // return the roll factor of any motor, this is used for tilt rotors and tail sitters // using copter motors for forward flight virtual float get_roll_factor(uint8_t i) { return 0.0f; } @@ -289,7 +296,7 @@ class AP_Motors { virtual void save_params_on_disarm() {} // internal variables - uint16_t _loop_rate; // rate in Hz at which output() function is called (normally 400hz) + float _dt; // time difference (in seconds) since the last loop time uint16_t _speed_hz; // speed in hz to send updates to motors float _roll_in; // desired roll control from attitude controllers, -1 ~ +1 float _roll_in_ff; // desired roll feed forward control from attitude controllers, -1 ~ +1 @@ -310,10 +317,10 @@ class AP_Motors { float _air_density_ratio; // air density / sea level density - decreases in altitude // mask of what channels need fast output - uint16_t _motor_fast_mask; + uint32_t _motor_fast_mask; // mask of what channels need to use SERVOn_MIN/MAX for output mapping - uint16_t _motor_pwm_range_mask; + uint32_t _motor_pwm_range_mask; // pass through variables float _roll_radio_passthrough; // roll input from pilot in -1 ~ +1 range. used for setup and providing servo feedback while landed @@ -361,6 +368,7 @@ class AP_Motors { bool _armed; // 0 if disarmed, 1 if armed bool _interlock; // 1 if the motor interlock is enabled (i.e. motors run), 0 if disabled (motors don't run) bool _initialised_ok; // 1 if initialisation was successful + bool _spoolup_block; // true if spoolup is blocked static AP_Motors *_singleton; }; diff --git a/libraries/AP_Motors/examples/expo_inverse_test/expo_inverse_test.cpp b/libraries/AP_Motors/examples/expo_inverse_test/expo_inverse_test.cpp index 5a3ad80d622..0398193401a 100644 --- a/libraries/AP_Motors/examples/expo_inverse_test/expo_inverse_test.cpp +++ b/libraries/AP_Motors/examples/expo_inverse_test/expo_inverse_test.cpp @@ -30,8 +30,8 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); class AP_MotorsMulticopter_test : public AP_MotorsMulticopter { public: - AP_MotorsMulticopter_test(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : - AP_MotorsMulticopter(loop_rate, speed_hz) + AP_MotorsMulticopter_test(uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) : + AP_MotorsMulticopter(speed_hz) { }; @@ -48,7 +48,7 @@ class AP_MotorsMulticopter_test : public AP_MotorsMulticopter { }; -AP_MotorsMulticopter_test motors{1}; +AP_MotorsMulticopter_test motors; /* * rotation tests @@ -66,6 +66,7 @@ void setup(void) float max_diff_expo = 0; float expo = -1.0; + motors.set_dt(1); while (expo < 1.0+expo_step*0.5) { hal.console->printf("expo: %0.4f\n",expo); motors.set_expo(expo); diff --git a/libraries/AP_Mount/AP_Mount.cpp b/libraries/AP_Mount/AP_Mount.cpp index 56e2536a606..81699675ad2 100644 --- a/libraries/AP_Mount/AP_Mount.cpp +++ b/libraries/AP_Mount/AP_Mount.cpp @@ -10,392 +10,23 @@ #include "AP_Mount_Alexmos.h" #include "AP_Mount_SToRM32.h" #include "AP_Mount_SToRM32_serial.h" +#include "AP_Mount_Gremsy.h" +#include "AP_Mount_Siyi.h" +#include #include +#include const AP_Param::GroupInfo AP_Mount::var_info[] = { - // @Param: _TYPE - // @DisplayName: Mount Type - // @Description: Mount Type (None, Servo or MAVLink) - // @Values: 0:None, 1:Servo, 2:3DR Solo, 3:Alexmos Serial, 4:SToRM32 MAVLink, 5:SToRM32 Serial - // @RebootRequired: True - // @User: Standard - AP_GROUPINFO_FLAGS("_TYPE", 19, AP_Mount, state[0]._type, 0, AP_PARAM_FLAG_ENABLE), - - // @Param: _DEFLT_MODE - // @DisplayName: Mount default operating mode - // @Description: Mount default operating mode on startup and after control is returned from autopilot - // @Values: 0:Retracted,1:Neutral,2:MavLink Targeting,3:RC Targeting,4:GPS Point - // @User: Standard - AP_GROUPINFO("_DEFLT_MODE", 0, AP_Mount, state[0]._default_mode, MAV_MOUNT_MODE_RC_TARGETING), - - // @Param: _RETRACT_X - // @DisplayName: Mount roll angle when in retracted position - // @Description: Mount roll angle when in retracted position - // @Units: deg - // @Range: -180.00 179.99 - // @Increment: 1 - // @User: Standard - - // @Param: _RETRACT_Y - // @DisplayName: Mount tilt/pitch angle when in retracted position - // @Description: Mount tilt/pitch angle when in retracted position - // @Units: deg - // @Range: -180.00 179.99 - // @Increment: 1 - // @User: Standard - - // @Param: _RETRACT_Z - // @DisplayName: Mount yaw/pan angle when in retracted position - // @Description: Mount yaw/pan angle when in retracted position - // @Units: deg - // @Range: -180.00 179.99 - // @Increment: 1 - // @User: Standard - AP_GROUPINFO("_RETRACT", 1, AP_Mount, state[0]._retract_angles, 0), - - // @Param: _NEUTRAL_X - // @DisplayName: Mount roll angle when in neutral position - // @Description: Mount roll angle when in neutral position - // @Units: deg - // @Range: -180.00 179.99 - // @Increment: 1 - // @User: Standard - - // @Param: _NEUTRAL_Y - // @DisplayName: Mount tilt/pitch angle when in neutral position - // @Description: Mount tilt/pitch angle when in neutral position - // @Units: deg - // @Range: -180.00 179.99 - // @Increment: 1 - // @User: Standard - - // @Param: _NEUTRAL_Z - // @DisplayName: Mount pan/yaw angle when in neutral position - // @Description: Mount pan/yaw angle when in neutral position - // @Units: deg - // @Range: -180.00 179.99 - // @Increment: 1 - // @User: Standard - AP_GROUPINFO("_NEUTRAL", 2, AP_Mount, state[0]._neutral_angles, 0), - - // 3 was used for control_angles - - // @Param: _STAB_ROLL - // @DisplayName: Stabilize mount's roll angle - // @Description: enable roll stabilisation relative to Earth - // @Values: 0:Disabled,1:Enabled - // @User: Standard - AP_GROUPINFO("_STAB_ROLL", 4, AP_Mount, state[0]._stab_roll, 0), - - // @Param: _STAB_TILT - // @DisplayName: Stabilize mount's pitch/tilt angle - // @Description: enable tilt/pitch stabilisation relative to Earth - // @Values: 0:Disabled,1:Enabled - // @User: Standard - AP_GROUPINFO("_STAB_TILT", 5, AP_Mount, state[0]._stab_tilt, 0), - - // @Param: _STAB_PAN - // @DisplayName: Stabilize mount pan/yaw angle - // @Description: enable pan/yaw stabilisation relative to Earth - // @Values: 0:Disabled,1:Enabled - // @User: Standard - AP_GROUPINFO("_STAB_PAN", 6, AP_Mount, state[0]._stab_pan, 0), - - // @Param: _RC_IN_ROLL - // @DisplayName: roll RC input channel - // @Description: 0 for none, any other for the RC channel to be used to control roll movements - // @Values: 0:Disabled,5:RC5,6:RC6,7:RC7,8:RC8,9:RC9,10:RC10,11:RC11,12:RC12 - // @User: Standard - AP_GROUPINFO("_RC_IN_ROLL", 7, AP_Mount, state[0]._roll_rc_in, 0), - - // @Param: _ANGMIN_ROL - // @DisplayName: Minimum roll angle - // @Description: Minimum physical roll angular position of mount. - // @Units: cdeg - // @Range: -18000 17999 - // @Increment: 10 - // @User: Standard - AP_GROUPINFO("_ANGMIN_ROL", 8, AP_Mount, state[0]._roll_angle_min, -4500), - - // @Param: _ANGMAX_ROL - // @DisplayName: Maximum roll angle - // @Description: Maximum physical roll angular position of the mount - // @Units: cdeg - // @Range: -18000 17999 - // @Increment: 10 - // @User: Standard - AP_GROUPINFO("_ANGMAX_ROL", 9, AP_Mount, state[0]._roll_angle_max, 4500), - - // @Param: _RC_IN_TILT - // @DisplayName: tilt (pitch) RC input channel - // @Description: 0 for none, any other for the RC channel to be used to control tilt (pitch) movements - // @Values: 0:Disabled,5:RC5,6:RC6,7:RC7,8:RC8,9:RC9,10:RC10,11:RC11,12:RC12 - // @User: Standard - AP_GROUPINFO("_RC_IN_TILT", 10, AP_Mount, state[0]._tilt_rc_in, 0), - - // @Param: _ANGMIN_TIL - // @DisplayName: Minimum tilt angle - // @Description: Minimum physical tilt (pitch) angular position of mount. - // @Units: cdeg - // @Range: -18000 17999 - // @Increment: 10 - // @User: Standard - AP_GROUPINFO("_ANGMIN_TIL", 11, AP_Mount, state[0]._tilt_angle_min, -4500), - - // @Param: _ANGMAX_TIL - // @DisplayName: Maximum tilt angle - // @Description: Maximum physical tilt (pitch) angular position of the mount - // @Units: cdeg - // @Range: -18000 17999 - // @Increment: 10 - // @User: Standard - AP_GROUPINFO("_ANGMAX_TIL", 12, AP_Mount, state[0]._tilt_angle_max, 4500), - - // @Param: _RC_IN_PAN - // @DisplayName: pan (yaw) RC input channel - // @Description: 0 for none, any other for the RC channel to be used to control pan (yaw) movements - // @Values: 0:Disabled,5:RC5,6:RC6,7:RC7,8:RC8,9:RC9,10:RC10,11:RC11,12:RC12 - // @User: Standard - AP_GROUPINFO("_RC_IN_PAN", 13, AP_Mount, state[0]._pan_rc_in, 0), - - // @Param: _ANGMIN_PAN - // @DisplayName: Minimum pan angle - // @Description: Minimum physical pan (yaw) angular position of mount. - // @Units: cdeg - // @Range: -18000 17999 - // @Increment: 10 - // @User: Standard - AP_GROUPINFO("_ANGMIN_PAN", 14, AP_Mount, state[0]._pan_angle_min, -4500), - - // @Param: _ANGMAX_PAN - // @DisplayName: Maximum pan angle - // @Description: Maximum physical pan (yaw) angular position of the mount - // @Units: cdeg - // @Range: -18000 17999 - // @Increment: 10 - // @User: Standard - AP_GROUPINFO("_ANGMAX_PAN", 15, AP_Mount, state[0]._pan_angle_max, 4500), - - // @Param: _JSTICK_SPD - // @DisplayName: mount joystick speed - // @Description: 0 for position control, small for low speeds, 100 for max speed. A good general value is 10 which gives a movement speed of 3 degrees per second. - // @Range: 0 100 - // @Increment: 1 - // @User: Standard - AP_GROUPINFO("_JSTICK_SPD", 16, AP_Mount, _joystick_speed, 0), - - // @Param: _LEAD_RLL - // @DisplayName: Roll stabilization lead time - // @Description: Causes the servo angle output to lead the current angle of the vehicle by some amount of time based on current angular rate, compensating for servo delay. Increase until the servo is responsive but doesn't overshoot. Does nothing with pan stabilization enabled. - // @Units: s - // @Range: 0.0 0.2 - // @Increment: .005 - // @User: Standard - AP_GROUPINFO("_LEAD_RLL", 17, AP_Mount, state[0]._roll_stb_lead, 0.0f), - - // @Param: _LEAD_PTCH - // @DisplayName: Pitch stabilization lead time - // @Description: Causes the servo angle output to lead the current angle of the vehicle by some amount of time based on current angular rate. Increase until the servo is responsive but doesn't overshoot. Does nothing with pan stabilization enabled. - // @Units: s - // @Range: 0.0 0.2 - // @Increment: .005 - // @User: Standard - AP_GROUPINFO("_LEAD_PTCH", 18, AP_Mount, state[0]._pitch_stb_lead, 0.0f), - - // 19 _TYPE, now at top with enable flag - - // 20 formerly _OFF_JNT - - // 21 formerly _OFF_ACC - - // 22 formerly _OFF_GYRO - - // 23 formerly _K_RATE - - // 24 is AVAILABLE + // @Group: 1 + // @Path: AP_Mount_Params.cpp + AP_SUBGROUPINFO(_params[0], "1", 43, AP_Mount, AP_Mount_Params), #if AP_MOUNT_MAX_INSTANCES > 1 - // @Param: 2_DEFLT_MODE - // @DisplayName: Mount default operating mode - // @Description: Mount default operating mode on startup and after control is returned from autopilot - // @Values: 0:Retracted,1:Neutral,2:MavLink Targeting,3:RC Targeting,4:GPS Point - // @User: Standard - AP_GROUPINFO("2_DEFLT_MODE", 25, AP_Mount, state[1]._default_mode, MAV_MOUNT_MODE_RC_TARGETING), - - // @Param: 2_RETRACT_X - // @DisplayName: Mount2 roll angle when in retracted position - // @Description: Mount2 roll angle when in retracted position - // @Units: deg - // @Range: -180.00 179.99 - // @Increment: 1 - // @User: Standard - - // @Param: 2_RETRACT_Y - // @DisplayName: Mount2 tilt/pitch angle when in retracted position - // @Description: Mount2 tilt/pitch angle when in retracted position - // @Units: deg - // @Range: -180.00 179.99 - // @Increment: 1 - // @User: Standard - - // @Param: 2_RETRACT_Z - // @DisplayName: Mount2 yaw/pan angle when in retracted position - // @Description: Mount2 yaw/pan angle when in retracted position - // @Units: deg - // @Range: -180.00 179.99 - // @Increment: 1 - // @User: Standard - AP_GROUPINFO("2_RETRACT", 26, AP_Mount, state[1]._retract_angles, 0), - - // @Param: 2_NEUTRAL_X - // @DisplayName: Mount2 roll angle when in neutral position - // @Description: Mount2 roll angle when in neutral position - // @Units: deg - // @Range: -180.00 179.99 - // @Increment: 1 - // @User: Standard - - // @Param: 2_NEUTRAL_Y - // @DisplayName: Mount2 tilt/pitch angle when in neutral position - // @Description: Mount2 tilt/pitch angle when in neutral position - // @Units: deg - // @Range: -180.00 179.99 - // @Increment: 1 - // @User: Standard - - // @Param: 2_NEUTRAL_Z - // @DisplayName: Mount2 pan/yaw angle when in neutral position - // @Description: Mount2 pan/yaw angle when in neutral position - // @Units: deg - // @Range: -180.00 179.99 - // @Increment: 1 - // @User: Standard - AP_GROUPINFO("2_NEUTRAL", 27, AP_Mount, state[1]._neutral_angles, 0), - - // 3 was used for control_angles - - // @Param: 2_STAB_ROLL - // @DisplayName: Stabilize Mount2's roll angle - // @Description: enable roll stabilisation relative to Earth - // @Values: 0:Disabled,1:Enabled - // @User: Standard - AP_GROUPINFO("2_STAB_ROLL", 28, AP_Mount, state[1]._stab_roll, 0), - - // @Param: 2_STAB_TILT - // @DisplayName: Stabilize Mount2's pitch/tilt angle - // @Description: enable tilt/pitch stabilisation relative to Earth - // @Values: 0:Disabled,1:Enabled - // @User: Standard - AP_GROUPINFO("2_STAB_TILT", 29, AP_Mount, state[1]._stab_tilt, 0), - - // @Param: 2_STAB_PAN - // @DisplayName: Stabilize mount2 pan/yaw angle - // @Description: enable pan/yaw stabilisation relative to Earth - // @Values: 0:Disabled,1:Enabled - // @User: Standard - AP_GROUPINFO("2_STAB_PAN", 30, AP_Mount, state[1]._stab_pan, 0), - - // @Param: 2_RC_IN_ROLL - // @DisplayName: Mount2's roll RC input channel - // @Description: 0 for none, any other for the RC channel to be used to control roll movements - // @Values: 0:Disabled,5:RC5,6:RC6,7:RC7,8:RC8,9:RC9,10:RC10,11:RC11,12:RC12 - // @User: Standard - AP_GROUPINFO("2_RC_IN_ROLL", 31, AP_Mount, state[1]._roll_rc_in, 0), - - // @Param: 2_ANGMIN_ROL - // @DisplayName: Mount2's minimum roll angle - // @Description: Mount2's minimum physical roll angular position - // @Units: cdeg - // @Range: -18000 17999 - // @Increment: 10 - // @User: Standard - AP_GROUPINFO("2_ANGMIN_ROL", 32, AP_Mount, state[1]._roll_angle_min, -4500), - - // @Param: 2_ANGMAX_ROL - // @DisplayName: Mount2's maximum roll angle - // @Description: Mount2's maximum physical roll angular position - // @Units: cdeg - // @Range: -18000 17999 - // @Increment: 10 - // @User: Standard - AP_GROUPINFO("2_ANGMAX_ROL", 33, AP_Mount, state[1]._roll_angle_max, 4500), - - // @Param: 2_RC_IN_TILT - // @DisplayName: Mount2's tilt (pitch) RC input channel - // @Description: 0 for none, any other for the RC channel to be used to control tilt (pitch) movements - // @Values: 0:Disabled,5:RC5,6:RC6,7:RC7,8:RC8,9:RC9,10:RC10,11:RC11,12:RC12 - // @User: Standard - AP_GROUPINFO("2_RC_IN_TILT", 34, AP_Mount, state[1]._tilt_rc_in, 0), - - // @Param: 2_ANGMIN_TIL - // @DisplayName: Mount2's minimum tilt angle - // @Description: Mount2's minimum physical tilt (pitch) angular position - // @Units: cdeg - // @Range: -18000 17999 - // @Increment: 10 - // @User: Standard - AP_GROUPINFO("2_ANGMIN_TIL", 35, AP_Mount, state[1]._tilt_angle_min, -4500), - - // @Param: 2_ANGMAX_TIL - // @DisplayName: Mount2's maximum tilt angle - // @Description: Mount2's maximum physical tilt (pitch) angular position - // @Units: cdeg - // @Range: -18000 17999 - // @Increment: 10 - // @User: Standard - AP_GROUPINFO("2_ANGMAX_TIL", 36, AP_Mount, state[1]._tilt_angle_max, 4500), - - // @Param: 2_RC_IN_PAN - // @DisplayName: Mount2's pan (yaw) RC input channel - // @Description: 0 for none, any other for the RC channel to be used to control pan (yaw) movements - // @Values: 0:Disabled,5:RC5,6:RC6,7:RC7,8:RC8,9:RC9,10:RC10,11:RC11,12:RC12 - // @User: Standard - AP_GROUPINFO("2_RC_IN_PAN", 37, AP_Mount, state[1]._pan_rc_in, 0), - - // @Param: 2_ANGMIN_PAN - // @DisplayName: Mount2's minimum pan angle - // @Description: Mount2's minimum physical pan (yaw) angular position - // @Units: cdeg - // @Range: -18000 17999 - // @Increment: 10 - // @User: Standard - AP_GROUPINFO("2_ANGMIN_PAN", 38, AP_Mount, state[1]._pan_angle_min, -4500), - - // @Param: 2_ANGMAX_PAN - // @DisplayName: Mount2's maximum pan angle - // @Description: MOunt2's maximum physical pan (yaw) angular position - // @Units: cdeg - // @Range: -18000 17999 - // @Increment: 10 - // @User: Standard - AP_GROUPINFO("2_ANGMAX_PAN", 39, AP_Mount, state[1]._pan_angle_max, 4500), - - // @Param: 2_LEAD_RLL - // @DisplayName: Mount2's Roll stabilization lead time - // @Description: Causes the servo angle output to lead the current angle of the vehicle by some amount of time based on current angular rate, compensating for servo delay. Increase until the servo is responsive but doesn't overshoot. Does nothing with pan stabilization enabled. - // @Units: s - // @Range: 0.0 0.2 - // @Increment: .005 - // @User: Standard - AP_GROUPINFO("2_LEAD_RLL", 40, AP_Mount, state[1]._roll_stb_lead, 0.0f), - - // @Param: 2_LEAD_PTCH - // @DisplayName: Mount2's Pitch stabilization lead time - // @Description: Causes the servo angle output to lead the current angle of the vehicle by some amount of time based on current angular rate. Increase until the servo is responsive but doesn't overshoot. Does nothing with pan stabilization enabled. - // @Units: s - // @Range: 0.0 0.2 - // @Increment: .005 - // @User: Standard - AP_GROUPINFO("2_LEAD_PTCH", 41, AP_Mount, state[1]._pitch_stb_lead, 0.0f), - - // @Param: 2_TYPE - // @DisplayName: Mount2 Type - // @Description: Mount Type (None, Servo or MAVLink) - // @Values: 0:None, 1:Servo, 2:3DR Solo, 3:Alexmos Serial, 4:SToRM32 MAVLink, 5:SToRM32 Serial - // @User: Standard - AP_GROUPINFO("2_TYPE", 42, AP_Mount, state[1]._type, 0), -#endif // AP_MOUNT_MAX_INSTANCES > 1 + // @Group: 2 + // @Path: AP_Mount_Params.cpp + AP_SUBGROUPINFO(_params[1], "2", 44, AP_Mount, AP_Mount_Params), +#endif AP_GROUPEND }; @@ -421,51 +52,72 @@ void AP_Mount::init() return; } - // default mount to servo mount if rc output channels to control roll, tilt or pan have been defined - if (!state[0]._type.configured()) { - if (SRV_Channels::function_assigned(SRV_Channel::Aux_servo_function_t::k_mount_pan) || - SRV_Channels::function_assigned(SRV_Channel::Aux_servo_function_t::k_mount_tilt) || - SRV_Channels::function_assigned(SRV_Channel::Aux_servo_function_t::k_mount_roll)) { - state[0]._type.set_and_save(Mount_Type_Servo); - } - } + // perform any required parameter conversion + convert_params(); // primary is reset to the first instantiated mount bool primary_set = false; // create each instance for (uint8_t instance=0; instanceinit(); + set_mode_to_default(instance); } } } @@ -514,7 +167,7 @@ AP_Mount::MountType AP_Mount::get_mount_type(uint8_t instance) const return Mount_Type_None; } - return (MountType)state[instance]._type.get(); + return (MountType)_params[instance].type.get(); } // has_pan_control - returns true if the mount has yaw control (required for copters) @@ -532,18 +185,19 @@ bool AP_Mount::has_pan_control(uint8_t instance) const MAV_MOUNT_MODE AP_Mount::get_mode(uint8_t instance) const { // sanity check instance - if (instance >= AP_MOUNT_MAX_INSTANCES) { - return MAV_MOUNT_MODE_RETRACT; + if (!check_instance(instance)) { + return MAV_MOUNT_MODE_RETRACT; } - return state[instance]._mode; + // ask backend its mode + return _backends[instance]->get_mode(); } -// set_mode_to_default - restores the mode to it's default mode held in the MNT_MODE parameter +// set_mode_to_default - restores the mode to it's default mode held in the MNTx__DEFLT_MODE parameter // this operation requires 60us on a Pixhawk/PX4 void AP_Mount::set_mode_to_default(uint8_t instance) { - set_mode(instance, (enum MAV_MOUNT_MODE)state[instance]._default_mode.get()); + set_mode(instance, (enum MAV_MOUNT_MODE)_params[instance].default_mode.get()); } // set_mode - sets mount's mode @@ -558,15 +212,41 @@ void AP_Mount::set_mode(uint8_t instance, enum MAV_MOUNT_MODE mode) _backends[instance]->set_mode(mode); } -// set_angle_targets - sets angle targets in degrees -void AP_Mount::set_angle_targets(uint8_t instance, float roll, float tilt, float pan) +// set yaw_lock. If true, the gimbal's yaw target is maintained in earth-frame meaning it will lock onto an earth-frame heading (e.g. North) +// If false (aka "follow") the gimbal's yaw is maintained in body-frame meaning it will rotate with the vehicle +void AP_Mount::set_yaw_lock(uint8_t instance, bool yaw_lock) +{ + // sanity check instance + if (!check_instance(instance)) { + return; + } + + // call backend's set_yaw_lock + _backends[instance]->set_yaw_lock(yaw_lock); +} + +// set angle target in degrees +// yaw_is_earth_frame (aka yaw_lock) should be true if yaw angle is earth-frame, false if body-frame +void AP_Mount::set_angle_target(uint8_t instance, float roll_deg, float pitch_deg, float yaw_deg, bool yaw_is_earth_frame) { if (!check_instance(instance)) { return; } // send command to backend - _backends[instance]->set_angle_targets(roll, tilt, pan); + _backends[instance]->set_angle_target(roll_deg, pitch_deg, yaw_deg, yaw_is_earth_frame); +} + +// sets rate target in deg/s +// yaw_lock should be true if the yaw rate is earth-frame, false if body-frame (e.g. rotates with body of vehicle) +void AP_Mount::set_rate_target(uint8_t instance, float roll_degs, float pitch_degs, float yaw_degs, bool yaw_lock) +{ + if (!check_instance(instance)) { + return; + } + + // send command to backend + _backends[instance]->set_rate_target(roll_degs, pitch_degs, yaw_degs, yaw_lock); } MAV_RESULT AP_Mount::handle_command_do_mount_configure(const mavlink_command_long_t &packet) @@ -575,9 +255,6 @@ MAV_RESULT AP_Mount::handle_command_do_mount_configure(const mavlink_command_lon return MAV_RESULT_FAILED; } _backends[_primary]->set_mode((MAV_MOUNT_MODE)packet.param1); - state[0]._stab_roll = packet.param2; - state[0]._stab_tilt = packet.param3; - state[0]._stab_pan = packet.param4; return MAV_RESULT_ACCEPTED; } @@ -589,12 +266,58 @@ MAV_RESULT AP_Mount::handle_command_do_mount_control(const mavlink_command_long_ return MAV_RESULT_FAILED; } - // send message to backend - _backends[_primary]->control(packet.param1, packet.param2, packet.param3, (MAV_MOUNT_MODE) packet.param7); + return _backends[_primary]->handle_command_do_mount_control(packet); +} - return MAV_RESULT_ACCEPTED; +MAV_RESULT AP_Mount::handle_command_do_gimbal_manager_pitchyaw(const mavlink_command_long_t &packet) +{ + if (!check_primary()) { + return MAV_RESULT_FAILED; + } + + // check flags for change to RETRACT + uint32_t flags = (uint32_t)packet.param5; + if ((flags & GIMBAL_MANAGER_FLAGS_RETRACT) > 0) { + _backends[_primary]->set_mode(MAV_MOUNT_MODE_RETRACT); + return MAV_RESULT_ACCEPTED; + } + // check flags for change to NEUTRAL + if ((flags & GIMBAL_MANAGER_FLAGS_NEUTRAL) > 0) { + _backends[_primary]->set_mode(MAV_MOUNT_MODE_NEUTRAL); + return MAV_RESULT_ACCEPTED; + } + + // check gimbal device id. 0 is primary, 1 is 1st gimbal, 2 is 2nd gimbal, etc + if ((packet.param7 < 0) || (packet.param7 > AP_MOUNT_MAX_INSTANCES)) { + return MAV_RESULT_FAILED; + } + const uint8_t gimbal_instance = (packet.param7 < 1) ? get_primary() : (uint8_t)packet.param7 - 1; + if (!check_instance(gimbal_instance)) { + return MAV_RESULT_FAILED; + } + + // param1 : pitch_angle (in degrees) + // param2 : yaw angle (in degrees) + const float pitch_angle_deg = packet.param1; + const float yaw_angle_deg = packet.param2; + if (!isnan(pitch_angle_deg) && !isnan(yaw_angle_deg)) { + set_angle_target(gimbal_instance, 0, pitch_angle_deg, yaw_angle_deg, flags & GIMBAL_MANAGER_FLAGS_YAW_LOCK); + return MAV_RESULT_ACCEPTED; + } + + // param3 : pitch_rate (in deg/s) + // param4 : yaw rate (in deg/s) + const float pitch_rate_degs = packet.param3; + const float yaw_rate_degs = packet.param4; + if (!isnan(pitch_rate_degs) && !isnan(yaw_rate_degs)) { + set_rate_target(gimbal_instance, 0, pitch_rate_degs, yaw_rate_degs, flags & GIMBAL_MANAGER_FLAGS_YAW_LOCK); + return MAV_RESULT_ACCEPTED; + } + + return MAV_RESULT_FAILED; } + MAV_RESULT AP_Mount::handle_command_long(const mavlink_command_long_t &packet) { switch (packet.command) { @@ -602,6 +325,8 @@ MAV_RESULT AP_Mount::handle_command_long(const mavlink_command_long_t &packet) return handle_command_do_mount_configure(packet); case MAV_CMD_DO_MOUNT_CONTROL: return handle_command_do_mount_control(packet); + case MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW: + return handle_command_do_gimbal_manager_pitchyaw(packet); default: return MAV_RESULT_UNSUPPORTED; } @@ -652,17 +377,45 @@ void AP_Mount::handle_mount_control(const mavlink_message_t &msg) _backends[_primary]->handle_mount_control(packet); } -/// Return mount status information -void AP_Mount::send_mount_status(mavlink_channel_t chan) +// send a GIMBAL_DEVICE_ATTITUDE_STATUS message to GCS +void AP_Mount::send_gimbal_device_attitude_status(mavlink_channel_t chan) { - // call send_mount_status for each instance + // call send_gimbal_device_attitude_status for each instance for (uint8_t instance=0; instancesend_mount_status(chan); + _backends[instance]->send_gimbal_device_attitude_status(chan); } } } +// run pre-arm check. returns false on failure and fills in failure_msg +// any failure_msg returned will not include a prefix +bool AP_Mount::pre_arm_checks(char *failure_msg, uint8_t failure_msg_len) +{ + // check type parameters + for (uint8_t i=0; ihealthy()) { + strncpy(failure_msg, "not healthy", failure_msg_len); + return false; + } + } + + return true; +} + // point at system ID sysid void AP_Mount::set_target_sysid(uint8_t instance, uint8_t sysid) { @@ -673,7 +426,7 @@ void AP_Mount::set_target_sysid(uint8_t instance, uint8_t sysid) } // set_roi_target - sets target location that mount should attempt to point towards -void AP_Mount::set_roi_target(uint8_t instance, const struct Location &target_loc) +void AP_Mount::set_roi_target(uint8_t instance, const Location &target_loc) { // call instance's set_roi_cmd if (check_instance(instance)) { @@ -681,6 +434,64 @@ void AP_Mount::set_roi_target(uint8_t instance, const struct Location &target_lo } } +// +// camera controls for gimbals that include a camera +// + +// take a picture. returns true on success +bool AP_Mount::take_picture(uint8_t instance) +{ + // call instance's take_picture + if (!check_instance(instance)) { + return false; + } + return _backends[instance]->take_picture(); +} + +// start or stop video recording. returns true on success +// set start_recording = true to start record, false to stop recording +bool AP_Mount::record_video(uint8_t instance, bool start_recording) +{ + // call instance's record_video + if (!check_instance(instance)) { + return false; + } + return _backends[instance]->record_video(start_recording); +} + +// set camera zoom step. returns true on success +// zoom out = -1, hold = 0, zoom in = 1 +bool AP_Mount::set_zoom_step(uint8_t instance, int8_t zoom_step) +{ + // call instance's set_zoom_step + if (!check_instance(instance)) { + return false; + } + return _backends[instance]->set_zoom_step(zoom_step); +} + +// set focus in, out or hold. returns true on success +// focus in = -1, focus hold = 0, focus out = 1 +bool AP_Mount::set_manual_focus_step(uint8_t instance, int8_t focus_step) +{ + // call instance's set_manual_focus_step + if (!check_instance(instance)) { + return false; + } + return _backends[instance]->set_manual_focus_step(focus_step); +} + +// auto focus. returns true on success +bool AP_Mount::set_auto_focus(uint8_t instance) +{ + // call instance's set_auto_focus + if (!check_instance(instance)) { + return false; + } + return _backends[instance]->set_auto_focus(); +} + + bool AP_Mount::check_primary() const { return check_instance(_primary); @@ -716,6 +527,12 @@ void AP_Mount::handle_message(mavlink_channel_t chan, const mavlink_message_t &m case MAVLINK_MSG_ID_GLOBAL_POSITION_INT: handle_global_position_int(msg); break; + case MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION: + handle_gimbal_device_information(msg); + break; + case MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS: + handle_gimbal_device_attitude_status(msg); + break; default: #if CONFIG_HAL_BOARD == HAL_BOARD_SITL AP_HAL::panic("Unhandled mount case"); @@ -734,16 +551,115 @@ void AP_Mount::handle_param_value(const mavlink_message_t &msg) } } -// send a GIMBAL_REPORT message to the GCS -void AP_Mount::send_gimbal_report(mavlink_channel_t chan) + +// handle GIMBAL_DEVICE_INFORMATION message +void AP_Mount::handle_gimbal_device_information(const mavlink_message_t &msg) +{ + for (uint8_t instance=0; instancehandle_gimbal_device_information(msg); + } + } +} + +// handle GIMBAL_DEVICE_ATTITUDE_STATUS message +void AP_Mount::handle_gimbal_device_attitude_status(const mavlink_message_t &msg) { for (uint8_t instance=0; instancesend_gimbal_report(chan); + _backends[instance]->handle_gimbal_device_attitude_status(msg); } - } + } } +// perform any required parameter conversion +void AP_Mount::convert_params() +{ + // exit immediately if MNT1_TYPE has already been configured + if (_params[0].type.configured()) { + return; + } + + // below conversions added Sep 2022 ahead of 4.3 release + + // convert MNT_TYPE to MNT1_TYPE + int8_t mnt_type = 0; + IGNORE_RETURN(AP_Param::get_param_by_index(this, 19, AP_PARAM_INT8, &mnt_type)); + if (mnt_type > 0) { + int8_t stab_roll = 0; + int8_t stab_pitch = 0; + IGNORE_RETURN(AP_Param::get_param_by_index(this, 4, AP_PARAM_INT8, &stab_roll)); + IGNORE_RETURN(AP_Param::get_param_by_index(this, 5, AP_PARAM_INT8, &stab_pitch)); + if (mnt_type == 1 && stab_roll == 0 && stab_pitch == 0) { + // Servo type without stabilization is changed to BrushlessPWM + mnt_type = (int8_t)Mount_Type_BrushlessPWM; + } + } + _params[0].type.set_and_save(mnt_type); + + // convert MNT_JSTICK_SPD to MNT1_RC_RATE + int8_t jstick_spd = 0; + if (AP_Param::get_param_by_index(this, 16, AP_PARAM_INT8, &jstick_spd) && (jstick_spd > 0)) { + _params[0].rc_rate_max.set_and_save(jstick_spd * 0.3); + } + + // find Mount's top level key + uint16_t k_param_mount_key; + if (!AP_Param::find_top_level_key_by_pointer(this, k_param_mount_key)) { + return; + } + + // table of mount parameters to be converted without scaling + static const AP_Param::ConversionInfo mnt_param_conversion_info[] { + { k_param_mount_key, 0, AP_PARAM_INT8, "MNT1_DEFLT_MODE" }, + { k_param_mount_key, 1, AP_PARAM_VECTOR3F, "MNT1_RETRACT" }, + { k_param_mount_key, 2, AP_PARAM_VECTOR3F, "MNT1_NEUTRAL" }, + { k_param_mount_key, 17, AP_PARAM_FLOAT, "MNT1_LEAD_RLL" }, + { k_param_mount_key, 18, AP_PARAM_FLOAT, "MNT1_LEAD_PTCH" }, + }; + uint8_t table_size = ARRAY_SIZE(mnt_param_conversion_info); + for (uint8_t i=0; i 0)) { + // get pointers to the appropriate RCx_OPTION parameter + char pname[17]; + enum ap_var_type ptype; + snprintf(pname, sizeof(pname), "RC%u_OPTION", (unsigned)mnt_rcin); + AP_Int16 *rcx_option = (AP_Int16 *)AP_Param::find(pname, &ptype); + if ((rcx_option != nullptr) && !rcx_option->configured()) { + rcx_option->set_and_save(mnt_rc_conversion_table[i].new_rc_option); + } + } + } +} // singleton instance AP_Mount *AP_Mount::_singleton; diff --git a/libraries/AP_Mount/AP_Mount.h b/libraries/AP_Mount/AP_Mount.h index aa617040d3c..0ce255fc582 100644 --- a/libraries/AP_Mount/AP_Mount.h +++ b/libraries/AP_Mount/AP_Mount.h @@ -14,20 +14,19 @@ * Usage: Use in main code to control mounts attached to * * vehicle. * * * -* Comments: All angles in degrees * 100, distances in meters* +* Comments: All angles in degrees, distances in meters * * unless otherwise stated. * ************************************************************/ #pragma once -#include -#include +#include #ifndef HAL_MOUNT_ENABLED #define HAL_MOUNT_ENABLED !HAL_MINIMIZE_FEATURES #endif #ifndef HAL_SOLO_GIMBAL_ENABLED -#define HAL_SOLO_GIMBAL_ENABLED HAL_MOUNT_ENABLED && BOARD_FLASH_SIZE > 1024 +#define HAL_SOLO_GIMBAL_ENABLED 0 #endif #if HAL_MOUNT_ENABLED @@ -36,9 +35,10 @@ #include #include #include +#include "AP_Mount_Params.h" // maximum number of mounts -#define AP_MOUNT_MAX_INSTANCES 1 +#define AP_MOUNT_MAX_INSTANCES 2 // declare backend classes class AP_Mount_Backend; @@ -47,6 +47,8 @@ class AP_Mount_SoloGimbal; class AP_Mount_Alexmos; class AP_Mount_SToRM32; class AP_Mount_SToRM32_serial; +class AP_Mount_Gremsy; +class AP_Mount_Siyi; /* This is a workaround to allow the MAVLink backend access to the @@ -62,6 +64,8 @@ class AP_Mount friend class AP_Mount_Alexmos; friend class AP_Mount_SToRM32; friend class AP_Mount_SToRM32_serial; + friend class AP_Mount_Gremsy; + friend class AP_Mount_Siyi; public: AP_Mount(); @@ -82,7 +86,10 @@ class AP_Mount Mount_Type_SoloGimbal = 2, /// Solo's gimbal Mount_Type_Alexmos = 3, /// Alexmos mount Mount_Type_SToRM32 = 4, /// SToRM32 mount using MAVLink protocol - Mount_Type_SToRM32_serial = 5 /// SToRM32 mount using custom serial protocol + Mount_Type_SToRM32_serial = 5, /// SToRM32 mount using custom serial protocol + Mount_Type_Gremsy = 6, /// Gremsy gimbal using MAVLink v2 Gimbal protocol + Mount_Type_BrushlessPWM = 7, /// Brushless (stabilized) gimbal using PWM protocol + Mount_Type_Siyi = 8, /// Siyi gimbal using custom serial protocol }; // init - detect and initialise all mounts @@ -94,6 +101,9 @@ class AP_Mount // used for gimbals that need to read INS data at full rate void update_fast(); + // return primary instance + uint8_t get_primary() const { return _primary; } + // get_mount_type - returns the type of mount AP_Mount::MountType get_mount_type() const { return get_mount_type(_primary); } AP_Mount::MountType get_mount_type(uint8_t instance) const; @@ -111,33 +121,67 @@ class AP_Mount void set_mode(enum MAV_MOUNT_MODE mode) { return set_mode(_primary, mode); } void set_mode(uint8_t instance, enum MAV_MOUNT_MODE mode); - // set_mode_to_default - restores the mode to it's default mode held in the MNT_DEFLT_MODE parameter + // set_mode_to_default - restores the mode to it's default mode held in the MNTx_DEFLT_MODE parameter // this operation requires 60us on a Pixhawk/PX4 void set_mode_to_default() { set_mode_to_default(_primary); } void set_mode_to_default(uint8_t instance); - // set_angle_targets - sets angle targets in degrees - void set_angle_targets(float roll, float tilt, float pan) { set_angle_targets(_primary, roll, tilt, pan); } - void set_angle_targets(uint8_t instance, float roll, float tilt, float pan); + // set yaw_lock. If true, the gimbal's yaw target is maintained in earth-frame meaning it will lock onto an earth-frame heading (e.g. North) + // If false (aka "follow") the gimbal's yaw is maintained in body-frame meaning it will rotate with the vehicle + void set_yaw_lock(bool yaw_lock) { set_yaw_lock(_primary, yaw_lock); } + void set_yaw_lock(uint8_t instance, bool yaw_lock); + + // set angle target in degrees + // yaw_is_earth_frame (aka yaw_lock) should be true if yaw angle is earth-frame, false if body-frame + void set_angle_target(float roll_deg, float pitch_deg, float yaw_deg, bool yaw_is_earth_frame) { set_angle_target(_primary, roll_deg, pitch_deg, yaw_deg, yaw_is_earth_frame); } + void set_angle_target(uint8_t instance, float roll_deg, float pitch_deg, float yaw_deg, bool yaw_is_earth_frame); + + // sets rate target in deg/s + // yaw_lock should be true if the yaw rate is earth-frame, false if body-frame (e.g. rotates with body of vehicle) + void set_rate_target(float roll_degs, float pitch_degs, float yaw_degs, bool yaw_lock) { set_rate_target(_primary, roll_degs, pitch_degs, yaw_degs, yaw_lock); } + void set_rate_target(uint8_t instance, float roll_degs, float pitch_degs, float yaw_degs, bool yaw_lock); // set_roi_target - sets target location that mount should attempt to point towards - void set_roi_target(const struct Location &target_loc) { set_roi_target(_primary,target_loc); } - void set_roi_target(uint8_t instance, const struct Location &target_loc); + void set_roi_target(const Location &target_loc) { set_roi_target(_primary,target_loc); } + void set_roi_target(uint8_t instance, const Location &target_loc); // point at system ID sysid - void set_target_sysid(uint8_t instance, const uint8_t sysid); - void set_target_sysid(const uint8_t sysid) { set_target_sysid(_primary, sysid); } + void set_target_sysid(uint8_t sysid) { set_target_sysid(_primary, sysid); } + void set_target_sysid(uint8_t instance, uint8_t sysid); // mavlink message handling: MAV_RESULT handle_command_long(const mavlink_command_long_t &packet); void handle_param_value(const mavlink_message_t &msg); void handle_message(mavlink_channel_t chan, const mavlink_message_t &msg); - // send a GIMBAL_REPORT message to GCS - void send_gimbal_report(mavlink_channel_t chan); + // send a GIMBAL_DEVICE_ATTITUDE_STATUS message to GCS + void send_gimbal_device_attitude_status(mavlink_channel_t chan); + + // run pre-arm check. returns false on failure and fills in failure_msg + // any failure_msg returned will not include a prefix + bool pre_arm_checks(char *failure_msg, uint8_t failure_msg_len); + + // + // camera controls for gimbals that include a camera + // + + // take a picture + bool take_picture(uint8_t instance); + + // start or stop video recording + // set start_recording = true to start record, false to stop recording + bool record_video(uint8_t instance, bool start_recording); + + // set camera zoom step + // zoom out = -1, hold = 0, zoom in = 1 + bool set_zoom_step(uint8_t instance, int8_t zoom_step); + + // set focus in, out or hold + // focus in = -1, focus hold = 0, focus out = 1 + bool set_manual_focus_step(uint8_t instance, int8_t focus_step); - // send a MOUNT_STATUS message to GCS: - void send_mount_status(mavlink_channel_t chan); + // auto focus + bool set_auto_focus(uint8_t instance); // parameter var table static const struct AP_Param::GroupInfo var_info[]; @@ -146,52 +190,14 @@ class AP_Mount static AP_Mount *_singleton; - // frontend parameters - AP_Int8 _joystick_speed; // joystick gain + // parameters for backends + AP_Mount_Params _params[AP_MOUNT_MAX_INSTANCES]; // front end members uint8_t _num_instances; // number of mounts instantiated uint8_t _primary; // primary mount AP_Mount_Backend *_backends[AP_MOUNT_MAX_INSTANCES]; // pointers to instantiated mounts - // backend state including parameters - struct mount_state { - // Parameters - AP_Int8 _type; // mount type (None, Servo or MAVLink, see MountType enum) - AP_Int8 _default_mode; // default mode on startup and when control is returned from autopilot - AP_Int8 _stab_roll; // 1 = mount should stabilize earth-frame roll axis, 0 = no stabilization - AP_Int8 _stab_tilt; // 1 = mount should stabilize earth-frame pitch axis - AP_Int8 _stab_pan; // 1 = mount should stabilize earth-frame yaw axis - - // RC input channels from receiver used for direct angular input from pilot - AP_Int8 _roll_rc_in; // pilot provides roll input on this channel - AP_Int8 _tilt_rc_in; // pilot provides tilt input on this channel - AP_Int8 _pan_rc_in; // pilot provides pan input on this channel - - // Mount's physical limits - AP_Int16 _roll_angle_min; // min roll in 0.01 degree units - AP_Int16 _roll_angle_max; // max roll in 0.01 degree units - AP_Int16 _tilt_angle_min; // min tilt in 0.01 degree units - AP_Int16 _tilt_angle_max; // max tilt in 0.01 degree units - AP_Int16 _pan_angle_min; // min pan in 0.01 degree units - AP_Int16 _pan_angle_max; // max pan in 0.01 degree units - - AP_Vector3f _retract_angles; // retracted position for mount, vector.x = roll vector.y = tilt, vector.z=pan - AP_Vector3f _neutral_angles; // neutral position for mount, vector.x = roll vector.y = tilt, vector.z=pan - - AP_Float _roll_stb_lead; // roll lead control gain - AP_Float _pitch_stb_lead; // pitch lead control gain - - MAV_MOUNT_MODE _mode; // current mode (see MAV_MOUNT_MODE enum) - struct Location _roi_target; // roi target location - bool _roi_target_set; - - uint8_t _target_sysid; // sysid to track - Location _target_sysid_location; // sysid target location - bool _target_sysid_location_set; - - } state[AP_MOUNT_MAX_INSTANCES]; - private: // Check if instance backend is ok bool check_primary() const; @@ -203,7 +209,13 @@ class AP_Mount MAV_RESULT handle_command_do_mount_configure(const mavlink_command_long_t &packet); MAV_RESULT handle_command_do_mount_control(const mavlink_command_long_t &packet); + MAV_RESULT handle_command_do_gimbal_manager_pitchyaw(const mavlink_command_long_t &packet); void handle_global_position_int(const mavlink_message_t &msg); + void handle_gimbal_device_information(const mavlink_message_t &msg); + void handle_gimbal_device_attitude_status(const mavlink_message_t &msg); + + // perform any required parameter conversion + void convert_params(); }; namespace AP { diff --git a/libraries/AP_Mount/AP_Mount_Alexmos.cpp b/libraries/AP_Mount/AP_Mount_Alexmos.cpp index 0011b5f9123..8a5213bd5f0 100644 --- a/libraries/AP_Mount/AP_Mount_Alexmos.cpp +++ b/libraries/AP_Mount/AP_Mount_Alexmos.cpp @@ -1,6 +1,8 @@ #include "AP_Mount_Alexmos.h" -#if HAL_MOUNT_ENABLED + +#if HAL_MOUNT_ALEXMOS_ENABLED #include +#include extern const AP_HAL::HAL& hal; @@ -13,6 +15,7 @@ void AP_Mount_Alexmos::init() _initialised = true; get_boardinfo(); read_params(0); //we request parameters for profile 0 and therfore get global and profile parameters + set_mode((enum MAV_MOUNT_MODE)_params.default_mode.get()); } } @@ -26,85 +29,92 @@ void AP_Mount_Alexmos::update() read_incoming(); // read the incoming messages from the gimbal // update based on mount mode - switch(get_mode()) { + switch (get_mode()) { // move mount to a "retracted" position. we do not implement a separate servo based retract mechanism - case MAV_MOUNT_MODE_RETRACT: - control_axis(_state._retract_angles.get(), true); + case MAV_MOUNT_MODE_RETRACT: { + const Vector3f &target = _params.retract_angles.get(); + _angle_rad.roll = radians(target.x); + _angle_rad.pitch = radians(target.y); + _angle_rad.yaw = radians(target.z); + _angle_rad.yaw_is_ef = false; break; + } // move mount to a neutral position, typically pointing forward - case MAV_MOUNT_MODE_NEUTRAL: - control_axis(_state._neutral_angles.get(), true); + case MAV_MOUNT_MODE_NEUTRAL: { + const Vector3f &target = _params.neutral_angles.get(); + _angle_rad.roll = radians(target.x); + _angle_rad.pitch = radians(target.y); + _angle_rad.yaw = radians(target.z); + _angle_rad.yaw_is_ef = false; break; + } // point to the angles given by a mavlink message case MAV_MOUNT_MODE_MAVLINK_TARGETING: - // do nothing because earth-frame angle targets (i.e. _angle_ef_target_rad) should have already been set by a MOUNT_CONTROL message from GCS - control_axis(_angle_ef_target_rad, false); + switch (mavt_target.target_type) { + case MountTargetType::ANGLE: + _angle_rad = mavt_target.angle_rad; + break; + case MountTargetType::RATE: + update_angle_target_from_rate(mavt_target.rate_rads, _angle_rad); + break; + } break; // RC radio manual angle control, but with stabilization from the AHRS - case MAV_MOUNT_MODE_RC_TARGETING: - // update targets using pilot's rc inputs - update_targets_from_rc(); - control_axis(_angle_ef_target_rad, false); + case MAV_MOUNT_MODE_RC_TARGETING: { + // update targets using pilot's RC inputs + MountTarget rc_target {}; + if (get_rc_rate_target(rc_target)) { + update_angle_target_from_rate(rc_target, _angle_rad); + } else if (get_rc_angle_target(rc_target)) { + _angle_rad = rc_target; + } break; + } // point mount to a GPS point given by the mission planner case MAV_MOUNT_MODE_GPS_POINT: - if (calc_angle_to_roi_target(_angle_ef_target_rad, true, false)) { - control_axis(_angle_ef_target_rad, false); - } + IGNORE_RETURN(get_angle_target_to_roi(_angle_rad)); break; case MAV_MOUNT_MODE_HOME_LOCATION: - // constantly update the home location: - if (!AP::ahrs().home_is_set()) { - break; - } - _state._roi_target = AP::ahrs().get_home(); - _state._roi_target_set = true; - if (calc_angle_to_roi_target(_angle_ef_target_rad, true, false)) { - control_axis(_angle_ef_target_rad, false); - } + IGNORE_RETURN(get_angle_target_to_home(_angle_rad)); break; case MAV_MOUNT_MODE_SYSID_TARGET: - if (calc_angle_to_sysid_target(_angle_ef_target_rad, - true, - false)) { - control_axis(_angle_ef_target_rad, false); - } + IGNORE_RETURN(get_angle_target_to_sysid(_angle_rad)); break; default: // we do not know this mode so do nothing break; } -} -// has_pan_control - returns true if this mount can control it's pan (required for multicopters) -bool AP_Mount_Alexmos::has_pan_control() const -{ - return _gimbal_3axis; + // send latest targets to gimbal + control_axis(_angle_rad); } -// set_mode - sets mount's mode -void AP_Mount_Alexmos::set_mode(enum MAV_MOUNT_MODE mode) +// has_pan_control - returns true if this mount can control its pan (required for multicopters) +bool AP_Mount_Alexmos::has_pan_control() const { - // record the mode change and return success - _state._mode = mode; + return _gimbal_3axis && yaw_range_valid(); } -// send_mount_status - called to allow mounts to send their status to GCS using the MOUNT_STATUS message -void AP_Mount_Alexmos::send_mount_status(mavlink_channel_t chan) +// get attitude as a quaternion. returns true on success +bool AP_Mount_Alexmos::get_attitude_quaternion(Quaternion& att_quat) { if (!_initialised) { - return; + return false; } + // request attitude from gimbal get_angles(); - mavlink_msg_mount_status_send(chan, 0, 0, _current_angle.y*100, _current_angle.x*100, _current_angle.z*100, _state._mode); + + // construct quaternion + att_quat.from_euler(radians(_current_angle.x), radians(_current_angle.y), radians(_current_angle.z)); + return true; } /* @@ -143,23 +153,18 @@ void AP_Mount_Alexmos::get_boardinfo() } /* - control_axis : send new angles to the gimbal at a fixed speed of 30 deg/s2 + control_axis : send new angle target to the gimbal at a fixed speed of 30 deg/s */ -void AP_Mount_Alexmos::control_axis(const Vector3f& angle, bool target_in_degrees) +void AP_Mount_Alexmos::control_axis(const MountTarget& angle_target_rad) { - // convert to degrees if necessary - Vector3f target_deg = angle; - if (!target_in_degrees) { - target_deg *= RAD_TO_DEG; - } alexmos_parameters outgoing_buffer; outgoing_buffer.angle_speed.mode = AP_MOUNT_ALEXMOS_MODE_ANGLE; outgoing_buffer.angle_speed.speed_roll = DEGREE_PER_SEC_TO_VALUE(AP_MOUNT_ALEXMOS_SPEED); - outgoing_buffer.angle_speed.angle_roll = DEGREE_TO_VALUE(target_deg.x); + outgoing_buffer.angle_speed.angle_roll = DEGREE_TO_VALUE(degrees(angle_target_rad.roll)); outgoing_buffer.angle_speed.speed_pitch = DEGREE_PER_SEC_TO_VALUE(AP_MOUNT_ALEXMOS_SPEED); - outgoing_buffer.angle_speed.angle_pitch = DEGREE_TO_VALUE(target_deg.y); + outgoing_buffer.angle_speed.angle_pitch = DEGREE_TO_VALUE(degrees(angle_target_rad.pitch)); outgoing_buffer.angle_speed.speed_yaw = DEGREE_PER_SEC_TO_VALUE(AP_MOUNT_ALEXMOS_SPEED); - outgoing_buffer.angle_speed.angle_yaw = DEGREE_TO_VALUE(target_deg.z); + outgoing_buffer.angle_speed.angle_yaw = DEGREE_TO_VALUE(degrees(get_bf_yaw_angle(angle_target_rad))); send_command(CMD_CONTROL, (uint8_t *)&outgoing_buffer.angle_speed, sizeof(alexmos_angles_speed)); } @@ -212,7 +217,7 @@ void AP_Mount_Alexmos::parse_body() switch (_command_id ) { case CMD_BOARD_INFO: _board_version = _buffer.version._board_version/ 10; - _current_firmware_version = _buffer.version._firmware_version / 1000.0f ; + _current_firmware_version = _buffer.version._firmware_version * 0.001f ; _firmware_beta_version = _buffer.version._firmware_version % 10 ; _gimbal_3axis = (_buffer.version._board_features & 0x1); _gimbal_bat_monitoring = (_buffer.version._board_features & 0x2); @@ -305,4 +310,4 @@ void AP_Mount_Alexmos::read_incoming() } } } -#endif // HAL_MOUNT_ENABLED \ No newline at end of file +#endif // HAL_MOUNT_ALEXMOS_ENABLED diff --git a/libraries/AP_Mount/AP_Mount_Alexmos.h b/libraries/AP_Mount/AP_Mount_Alexmos.h index 713319d9b8a..90a5db7978c 100644 --- a/libraries/AP_Mount/AP_Mount_Alexmos.h +++ b/libraries/AP_Mount/AP_Mount_Alexmos.h @@ -3,14 +3,16 @@ */ #pragma once -#include "AP_Mount.h" -#if HAL_MOUNT_ENABLED +#include "AP_Mount_Backend.h" + +#ifndef HAL_MOUNT_ALEXMOS_ENABLED +#define HAL_MOUNT_ALEXMOS_ENABLED HAL_MOUNT_ENABLED +#endif + +#if HAL_MOUNT_ALEXMOS_ENABLED #include #include #include -#include -#include "AP_Mount_Backend.h" - //definition of the commands id for the Alexmos Serial Protocol #define CMD_READ_PARAMS 'R' @@ -56,7 +58,7 @@ #define AP_MOUNT_ALEXMOS_MODE_SPEED_ANGLE 3 #define AP_MOUNT_ALEXMOS_MODE_RC 4 -#define AP_MOUNT_ALEXMOS_SPEED 30 // degree/s2 +#define AP_MOUNT_ALEXMOS_SPEED 30 // deg/s #define VALUE_TO_DEGREE(d) ((float)((d * 720) >> 15)) #define DEGREE_TO_VALUE(d) ((int16_t)((float)(d)*(1.0f/0.02197265625f))) @@ -66,8 +68,8 @@ class AP_Mount_Alexmos : public AP_Mount_Backend { public: //constructor - AP_Mount_Alexmos(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance): - AP_Mount_Backend(frontend, state, instance) + AP_Mount_Alexmos(AP_Mount &frontend, AP_Mount_Params ¶ms, uint8_t instance): + AP_Mount_Backend(frontend, params, instance) {} // init - performs any required initialisation for this instance @@ -76,14 +78,13 @@ class AP_Mount_Alexmos : public AP_Mount_Backend // update mount position - should be called periodically void update() override; - // has_pan_control - returns true if this mount can control it's pan (required for multicopters) + // has_pan_control - returns true if this mount can control its pan (required for multicopters) bool has_pan_control() const override; - // set_mode - sets mount's mode - void set_mode(enum MAV_MOUNT_MODE mode) override; +protected: - // send_mount_status - called to allow mounts to send their status to GCS via MAVLink - void send_mount_status(mavlink_channel_t chan) override; + // get attitude as a quaternion. returns true on success + bool get_attitude_quaternion(Quaternion& att_quat) override; private: @@ -96,8 +97,8 @@ class AP_Mount_Alexmos : public AP_Mount_Backend // get_boardinfo - get board version and firmware version void get_boardinfo(); - // control_axis - send new angles to the gimbal at a fixed speed of 30 deg/s - void control_axis(const Vector3f& angle , bool targets_in_degrees); + // send new angles to the gimbal at a fixed speed of 30 deg/s + void control_axis(const MountTarget& angle_target_rad); // read_params - read current profile profile_id and global parameters from the gimbal settings void read_params(uint8_t profile_id); @@ -105,7 +106,7 @@ class AP_Mount_Alexmos : public AP_Mount_Backend // write_params - write new parameters to the gimbal settings void write_params(); - bool get_realtimedata( Vector3f& angle); + bool get_realtimedata(Vector3f& angle); // Alexmos Serial Protocol reading part implementation // send_command - send a command to the Alemox Serial API @@ -117,6 +118,8 @@ class AP_Mount_Alexmos : public AP_Mount_Backend // read_incoming - detect and read the header of the incoming message from the gimbal void read_incoming(); + MountTarget _angle_rad; // latest angle target + // structure for the Serial Protocol // CMD_BOARD_INFO @@ -300,4 +303,4 @@ class AP_Mount_Alexmos : public AP_Mount_Backend // confirmed that last command was ok bool _last_command_confirmed : 1; }; -#endif // HAL_MOUNT_ENABLED +#endif // HAL_MOUNT_ALEXMOS_ENABLED diff --git a/libraries/AP_Mount/AP_Mount_Backend.cpp b/libraries/AP_Mount/AP_Mount_Backend.cpp index 3ebb8e582e7..7d9ff9fc26f 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.cpp +++ b/libraries/AP_Mount/AP_Mount_Backend.cpp @@ -4,207 +4,303 @@ extern const AP_HAL::HAL& hal; -// set_angle_targets - sets angle targets in degrees -void AP_Mount_Backend::set_angle_targets(float roll, float tilt, float pan) +#define AP_MOUNT_UPDATE_DT 0.02 // update rate in seconds. update() should be called at this rate + +// set angle target in degrees +// yaw_is_earth_frame (aka yaw_lock) should be true if yaw angle is earth-frame, false if body-frame +void AP_Mount_Backend::set_angle_target(float roll_deg, float pitch_deg, float yaw_deg, bool yaw_is_earth_frame) { // set angle targets - _angle_ef_target_rad.x = radians(roll); - _angle_ef_target_rad.y = radians(tilt); - _angle_ef_target_rad.z = radians(pan); + mavt_target.target_type = MountTargetType::ANGLE; + mavt_target.angle_rad.roll = radians(roll_deg); + mavt_target.angle_rad.pitch = radians(pitch_deg); + mavt_target.angle_rad.yaw = radians(yaw_deg); + mavt_target.angle_rad.yaw_is_ef = yaw_is_earth_frame; + + // set the mode to mavlink targeting + set_mode(MAV_MOUNT_MODE_MAVLINK_TARGETING); +} + +// sets rate target in deg/s +// yaw_lock should be true if the yaw rate is earth-frame, false if body-frame (e.g. rotates with body of vehicle) +void AP_Mount_Backend::set_rate_target(float roll_degs, float pitch_degs, float yaw_degs, bool yaw_is_earth_frame) +{ + // set rate targets + mavt_target.target_type = MountTargetType::RATE; + mavt_target.rate_rads.roll = radians(roll_degs); + mavt_target.rate_rads.pitch = radians(pitch_degs); + mavt_target.rate_rads.yaw = radians(yaw_degs); + mavt_target.rate_rads.yaw_is_ef = yaw_is_earth_frame; // set the mode to mavlink targeting - _frontend.set_mode(_instance, MAV_MOUNT_MODE_MAVLINK_TARGETING); + set_mode(MAV_MOUNT_MODE_MAVLINK_TARGETING); } // set_roi_target - sets target location that mount should attempt to point towards -void AP_Mount_Backend::set_roi_target(const struct Location &target_loc) +void AP_Mount_Backend::set_roi_target(const Location &target_loc) { // set the target gps location - _state._roi_target = target_loc; - _state._roi_target_set = true; + _roi_target = target_loc; + _roi_target_set = true; // set the mode to GPS tracking mode - _frontend.set_mode(_instance, MAV_MOUNT_MODE_GPS_POINT); + set_mode(MAV_MOUNT_MODE_GPS_POINT); } // set_sys_target - sets system that mount should attempt to point towards void AP_Mount_Backend::set_target_sysid(uint8_t sysid) { - _state._target_sysid = sysid; + _target_sysid = sysid; // set the mode to sysid tracking mode - _frontend.set_mode(_instance, MAV_MOUNT_MODE_SYSID_TARGET); + set_mode(MAV_MOUNT_MODE_SYSID_TARGET); } // process MOUNT_CONFIGURE messages received from GCS. deprecated. void AP_Mount_Backend::handle_mount_configure(const mavlink_mount_configure_t &packet) { set_mode((MAV_MOUNT_MODE)packet.mount_mode); - _state._stab_roll = packet.stab_roll; - _state._stab_tilt = packet.stab_pitch; - _state._stab_pan = packet.stab_yaw; +} + +// send a GIMBAL_DEVICE_ATTITUDE_STATUS message to GCS +void AP_Mount_Backend::send_gimbal_device_attitude_status(mavlink_channel_t chan) +{ + if (suppress_heartbeat()) { + // block heartbeat from transmitting to the GCS + GCS_MAVLINK::disable_channel_routing(chan); + } + + Quaternion att_quat; + if (!get_attitude_quaternion(att_quat)) { + return; + } + + // construct quaternion array + const float quat_array[4] = {att_quat.q1, att_quat.q2, att_quat.q3, att_quat.q4}; + + mavlink_msg_gimbal_device_attitude_status_send(chan, + 0, // target system + 0, // target component + AP_HAL::millis(), // autopilot system time + get_gimbal_device_flags(), + quat_array, // attitude expressed as quaternion + std::numeric_limits::quiet_NaN(), // roll axis angular velocity (NaN for unknown) + std::numeric_limits::quiet_NaN(), // pitch axis angular velocity (NaN for unknown) + std::numeric_limits::quiet_NaN(), // yaw axis angular velocity (NaN for unknown) + 0); // failure flags (not supported) } // process MOUNT_CONTROL messages received from GCS. deprecated. void AP_Mount_Backend::handle_mount_control(const mavlink_mount_control_t &packet) { - control((int32_t)packet.input_a, (int32_t)packet.input_b, (int32_t)packet.input_c, _state._mode); + switch (get_mode()) { + case MAV_MOUNT_MODE_MAVLINK_TARGETING: + // input_a : Pitch in centi-degrees + // input_b : Roll in centi-degrees + // input_c : Yaw in centi-degrees (interpreted as body-frame) + set_angle_target(packet.input_b * 0.01, packet.input_a * 0.01, packet.input_c * 0.01, false); + break; + + case MAV_MOUNT_MODE_GPS_POINT: { + // input_a : lat in degE7 + // input_b : lon in degE7 + // input_c : alt in cm (interpreted as above home) + const Location target_location { + packet.input_a, + packet.input_b, + packet.input_c, + Location::AltFrame::ABOVE_HOME + }; + set_roi_target(target_location); + break; + } + + case MAV_MOUNT_MODE_RETRACT: + case MAV_MOUNT_MODE_NEUTRAL: + case MAV_MOUNT_MODE_RC_TARGETING: + case MAV_MOUNT_MODE_SYSID_TARGET: + case MAV_MOUNT_MODE_HOME_LOCATION: + default: + // no effect in these modes + break; + } } -void AP_Mount_Backend::control(int32_t pitch_or_lat, int32_t roll_or_lon, int32_t yaw_or_alt, MAV_MOUNT_MODE mount_mode) +// handle do_mount_control command. Returns MAV_RESULT_ACCEPTED on success +MAV_RESULT AP_Mount_Backend::handle_command_do_mount_control(const mavlink_command_long_t &packet) { - _frontend.set_mode(_instance, mount_mode); + const MAV_MOUNT_MODE new_mode = (MAV_MOUNT_MODE)packet.param7; // interpret message fields based on mode - switch (_frontend.get_mode(_instance)) { - case MAV_MOUNT_MODE_RETRACT: - case MAV_MOUNT_MODE_NEUTRAL: - // do nothing with request if mount is retracted or in neutral position - break; - - // set earth frame target angles from mavlink message - case MAV_MOUNT_MODE_MAVLINK_TARGETING: - set_angle_targets(roll_or_lon*0.01f, pitch_or_lat*0.01f, yaw_or_alt*0.01f); - break; - - // Load neutral position and start RC Roll,Pitch,Yaw control with stabilization - case MAV_MOUNT_MODE_RC_TARGETING: - // do nothing if pilot is controlling the roll, pitch and yaw - break; + switch (new_mode) { + case MAV_MOUNT_MODE_RETRACT: + case MAV_MOUNT_MODE_NEUTRAL: + case MAV_MOUNT_MODE_RC_TARGETING: + case MAV_MOUNT_MODE_HOME_LOCATION: + // simply set mode + set_mode(new_mode); + return MAV_RESULT_ACCEPTED; - // set lat, lon, alt position targets from mavlink message + case MAV_MOUNT_MODE_MAVLINK_TARGETING: { + // set body-frame target angles (in degrees) from mavlink message + const float pitch_deg = packet.param1; // param1: pitch (in degrees) + const float roll_deg = packet.param2; // param2: roll in degrees + const float yaw_deg = packet.param3; // param3: yaw in degrees - case MAV_MOUNT_MODE_GPS_POINT: { - const Location target_location{ - pitch_or_lat, - roll_or_lon, - yaw_or_alt, - Location::AltFrame::ABOVE_HOME - }; - set_roi_target(target_location); - break; + // warn if angles are invalid to catch angles sent in centi-degrees + if ((fabsf(pitch_deg) > 90) || (fabsf(roll_deg) > 180) || (fabsf(yaw_deg) > 360)) { + send_warning_to_GCS("invalid angle targets"); + return MAV_RESULT_FAILED; } - case MAV_MOUNT_MODE_HOME_LOCATION: { - // set the target gps location - _state._roi_target = AP::ahrs().get_home(); - _state._roi_target_set = true; - break; + set_angle_target(packet.param2, packet.param1, packet.param3, false); + return MAV_RESULT_ACCEPTED; + } + + case MAV_MOUNT_MODE_GPS_POINT: { + // set lat, lon, alt position targets from mavlink message + + // warn if lat, lon appear to be in param1,2 instead of param5,6 as this indicates + // sender is relying on a bug in AP-4.2's (and earlier) handling of MAV_CMD_DO_MOUNT_CONTROL + if (!is_zero(packet.param1) && !is_zero(packet.param2) && is_zero(packet.param5) && is_zero(packet.param6)) { + send_warning_to_GCS("GPS_POINT target invalid"); + return MAV_RESULT_FAILED; } - default: - // do nothing - break; + // param4: altitude in meters + // param5: latitude in degrees * 1E7 + // param6: longitude in degrees * 1E7 + const Location target_location { + (int32_t)packet.param5, // latitude in degrees * 1E7 + (int32_t)packet.param6, // longitude in degrees * 1E7 + (int32_t)packet.param4 * 100, // alt converted from meters to cm + Location::AltFrame::ABOVE_HOME + }; + set_roi_target(target_location); + return MAV_RESULT_ACCEPTED; + } + + default: + // invalid mode + return MAV_RESULT_FAILED; } } // handle a GLOBAL_POSITION_INT message bool AP_Mount_Backend::handle_global_position_int(uint8_t msg_sysid, const mavlink_global_position_int_t &packet) { - if (_state._target_sysid != msg_sysid) { + if (_target_sysid != msg_sysid) { return false; } - _state._target_sysid_location.lat = packet.lat; - _state._target_sysid_location.lng = packet.lon; + _target_sysid_location.lat = packet.lat; + _target_sysid_location.lng = packet.lon; // global_position_int.alt is *UP*, so is location. - _state._target_sysid_location.set_alt_cm(packet.alt*0.1, Location::AltFrame::ABSOLUTE); - _state._target_sysid_location_set = true; + _target_sysid_location.set_alt_cm(packet.alt*0.1, Location::AltFrame::ABSOLUTE); + _target_sysid_location_set = true; return true; } -void AP_Mount_Backend::rate_input_rad(float &out, const RC_Channel *chan, float min, float max) const +// get pilot input (in the range -1 to +1) received through RC +void AP_Mount_Backend::get_rc_input(float& roll_in, float& pitch_in, float& yaw_in) const { - if ((chan == nullptr) || (chan->get_radio_in() == 0)) { - return; + const RC_Channel *roll_ch = rc().find_channel_for_option(_instance == 0 ? RC_Channel::AUX_FUNC::MOUNT1_ROLL : RC_Channel::AUX_FUNC::MOUNT2_ROLL); + const RC_Channel *pitch_ch = rc().find_channel_for_option(_instance == 0 ? RC_Channel::AUX_FUNC::MOUNT1_PITCH : RC_Channel::AUX_FUNC::MOUNT2_PITCH); + const RC_Channel *yaw_ch = rc().find_channel_for_option(_instance == 0 ? RC_Channel::AUX_FUNC::MOUNT1_YAW : RC_Channel::AUX_FUNC::MOUNT2_YAW); + + roll_in = 0; + if ((roll_ch != nullptr) && (roll_ch->get_radio_in() > 0)) { + roll_in = roll_ch->norm_input_dz(); } - out += chan->norm_input_dz() * 0.0001f * _frontend._joystick_speed; - out = constrain_float(out, radians(min*0.01f), radians(max*0.01f)); -} - -// update_targets_from_rc - updates angle targets using input from receiver -void AP_Mount_Backend::update_targets_from_rc() -{ - const RC_Channel *roll_ch = rc().channel(_state._roll_rc_in - 1); - const RC_Channel *tilt_ch = rc().channel(_state._tilt_rc_in - 1); - const RC_Channel *pan_ch = rc().channel(_state._pan_rc_in - 1); - - // if joystick_speed is defined then pilot input defines a rate of change of the angle - if (_frontend._joystick_speed) { - // allow pilot position input to come directly from an RC_Channel - rate_input_rad(_angle_ef_target_rad.x, - roll_ch, - _state._roll_angle_min, - _state._roll_angle_max); - rate_input_rad(_angle_ef_target_rad.y, - tilt_ch, - _state._tilt_angle_min, - _state._tilt_angle_max); - rate_input_rad(_angle_ef_target_rad.z, - pan_ch, - _state._pan_angle_min, - _state._pan_angle_max); - } else { - // allow pilot rate input to come directly from an RC_Channel - if ((roll_ch != nullptr) && (roll_ch->get_radio_in() != 0)) { - _angle_ef_target_rad.x = angle_input_rad(roll_ch, _state._roll_angle_min, _state._roll_angle_max); - } - if ((tilt_ch != nullptr) && (tilt_ch->get_radio_in() != 0)) { - _angle_ef_target_rad.y = angle_input_rad(tilt_ch, _state._tilt_angle_min, _state._tilt_angle_max); - } - if ((pan_ch != nullptr) && (pan_ch->get_radio_in() != 0)) { - _angle_ef_target_rad.z = angle_input_rad(pan_ch, _state._pan_angle_min, _state._pan_angle_max); - } + + pitch_in = 0; + if ((pitch_ch != nullptr) && (pitch_ch->get_radio_in() > 0)) { + pitch_in = pitch_ch->norm_input_dz(); } -} -// returns the angle (radians) that the RC_Channel input is receiving -float AP_Mount_Backend::angle_input_rad(const RC_Channel* rc, int16_t angle_min, int16_t angle_max) -{ - return radians(((rc->norm_input_ignore_trim() + 1.0f) * 0.5f * (angle_max - angle_min) + angle_min)*0.01f); + yaw_in = 0; + if ((yaw_ch != nullptr) && (yaw_ch->get_radio_in() > 0)) { + yaw_in = yaw_ch->norm_input_dz(); + } } -bool AP_Mount_Backend::calc_angle_to_roi_target(Vector3f& angles_to_target_rad, - bool calc_tilt, - bool calc_pan, - bool relative_pan) const +// get rate targets (in rad/s) from pilot RC +// returns true on success (RC is providing rate targets), false on failure (RC is providing angle targets) +bool AP_Mount_Backend::get_rc_rate_target(MountTarget& rate_rads) const { - if (!_state._roi_target_set) { + // exit immediately if RC is not providing rate targets + if (_params.rc_rate_max <= 0) { return false; } - return calc_angle_to_location(_state._roi_target, angles_to_target_rad, calc_tilt, calc_pan, relative_pan); + + // get RC input from pilot + float roll_in, pitch_in, yaw_in; + get_rc_input(roll_in, pitch_in, yaw_in); + + // calculate rates + const float rc_rate_max_rads = radians(_params.rc_rate_max.get()); + rate_rads.roll = roll_in * rc_rate_max_rads; + rate_rads.pitch = pitch_in * rc_rate_max_rads; + rate_rads.yaw = yaw_in * rc_rate_max_rads; + + // yaw frame + rate_rads.yaw_is_ef = _yaw_lock; + + return true; } -bool AP_Mount_Backend::calc_angle_to_sysid_target(Vector3f& angles_to_target_rad, - bool calc_tilt, - bool calc_pan, - bool relative_pan) const +// get angle targets (in radians) from pilot RC +// returns true on success (RC is providing angle targets), false on failure (RC is providing rate targets) +bool AP_Mount_Backend::get_rc_angle_target(MountTarget& angle_rad) const { - if (!_state._target_sysid_location_set) { + // exit immediately if RC is not providing angle targets + if (_params.rc_rate_max > 0) { return false; } - if (!_state._target_sysid) { - return false; + + // get RC input from pilot + float roll_in, pitch_in, yaw_in; + get_rc_input(roll_in, pitch_in, yaw_in); + + // roll angle + angle_rad.roll = radians(((roll_in + 1.0f) * 0.5f * (_params.roll_angle_max - _params.roll_angle_min) + _params.roll_angle_min)); + + // pitch angle + angle_rad.pitch = radians(((pitch_in + 1.0f) * 0.5f * (_params.pitch_angle_max - _params.pitch_angle_min) + _params.pitch_angle_min)); + + // yaw angle + angle_rad.yaw_is_ef = _yaw_lock; + if (angle_rad.yaw_is_ef) { + // if yaw is earth-frame pilot yaw input control angle from -180 to +180 deg + angle_rad.yaw = yaw_in * M_PI; + } else { + // yaw target in body frame so apply body frame limits + angle_rad.yaw = radians(((yaw_in + 1.0f) * 0.5f * (_params.yaw_angle_max - _params.yaw_angle_min) + _params.yaw_angle_min)); } - return calc_angle_to_location(_state._target_sysid_location, - angles_to_target_rad, - calc_tilt, - calc_pan, - relative_pan); + + return true; } -// calc_angle_to_location - calculates the earth-frame roll, tilt and pan angles (and radians) to point at the given target -bool AP_Mount_Backend::calc_angle_to_location(const struct Location &target, Vector3f& angles_to_target_rad, bool calc_tilt, bool calc_pan, bool relative_pan) const +// get angle targets (in radians) to a Location +// returns true on success, false on failure +bool AP_Mount_Backend::get_angle_target_to_location(const Location &loc, MountTarget& angle_rad) const { + // exit immediately if vehicle's location is unavailable Location current_loc; if (!AP::ahrs().get_location(current_loc)) { return false; } - const float GPS_vector_x = Location::diff_longitude(target.lng,current_loc.lng)*cosf(ToRad((current_loc.lat+target.lat)*0.00000005f))*0.01113195f; - const float GPS_vector_y = (target.lat-current_loc.lat)*0.01113195f; + + // exit immediate if location is invalid + if (!loc.initialised()) { + return false; + } + + const float GPS_vector_x = Location::diff_longitude(loc.lng, current_loc.lng)*cosf(ToRad((current_loc.lat + loc.lat) * 0.00000005f)) * 0.01113195f; + const float GPS_vector_y = (loc.lat - current_loc.lat) * 0.01113195f; int32_t target_alt_cm = 0; - if (!target.get_alt_cm(Location::AltFrame::ABOVE_HOME, target_alt_cm)) { + if (!loc.get_alt_cm(Location::AltFrame::ABOVE_HOME, target_alt_cm)) { return false; } int32_t current_alt_cm = 0; @@ -214,23 +310,124 @@ bool AP_Mount_Backend::calc_angle_to_location(const struct Location &target, Vec float GPS_vector_z = target_alt_cm - current_alt_cm; float target_distance = 100.0f*norm(GPS_vector_x, GPS_vector_y); // Careful , centimeters here locally. Baro/alt is in cm, lat/lon is in meters. - // initialise all angles to zero - angles_to_target_rad.zero(); + // calculate roll, pitch, yaw angles + angle_rad.roll = 0; + angle_rad.pitch = atan2f(GPS_vector_z, target_distance); + angle_rad.yaw = atan2f(GPS_vector_x, GPS_vector_y); + angle_rad.yaw_is_ef = true; + + return true; +} + +// get angle targets (in radians) to ROI location +// returns true on success, false on failure +bool AP_Mount_Backend::get_angle_target_to_roi(MountTarget& angle_rad) const +{ + if (!_roi_target_set) { + return false; + } + return get_angle_target_to_location(_roi_target, angle_rad); +} + +// return body-frame yaw angle from a mount target +float AP_Mount_Backend::get_bf_yaw_angle(const MountTarget& angle_rad) const +{ + if (angle_rad.yaw_is_ef) { + // convert to body-frame + return wrap_PI(angle_rad.yaw - AP::ahrs().yaw); + } + + // target is already body-frame + return angle_rad.yaw; +} - // tilt calcs - if (calc_tilt) { - angles_to_target_rad.y = atan2f(GPS_vector_z, target_distance); +// return earth-frame yaw angle from a mount target +float AP_Mount_Backend::get_ef_yaw_angle(const MountTarget& angle_rad) const +{ + if (angle_rad.yaw_is_ef) { + // target is already earth-frame + return angle_rad.yaw; } - // pan calcs - if (calc_pan) { - // calc absolute heading and then onvert to vehicle relative yaw - angles_to_target_rad.z = atan2f(GPS_vector_x, GPS_vector_y); - if (relative_pan) { - angles_to_target_rad.z = wrap_PI(angles_to_target_rad.z - AP::ahrs().yaw); + // convert to earth-frame + return wrap_PI(angle_rad.yaw + AP::ahrs().yaw); +} + +// update angle targets using a given rate target +// the resulting angle_rad yaw frame will match the rate_rad yaw frame +// assumes a 50hz update rate +void AP_Mount_Backend::update_angle_target_from_rate(const MountTarget& rate_rad, MountTarget& angle_rad) const +{ + // update roll and pitch angles and apply limits + angle_rad.roll = constrain_float(angle_rad.roll + rate_rad.roll * AP_MOUNT_UPDATE_DT, radians(_params.roll_angle_min), radians(_params.roll_angle_max)); + angle_rad.pitch = constrain_float(angle_rad.pitch + rate_rad.pitch * AP_MOUNT_UPDATE_DT, radians(_params.pitch_angle_min), radians(_params.pitch_angle_max)); + + // ensure angle yaw frames matches rate yaw frame + if (angle_rad.yaw_is_ef != rate_rad.yaw_is_ef) { + if (rate_rad.yaw_is_ef) { + angle_rad.yaw = get_ef_yaw_angle(angle_rad); + } else { + angle_rad.yaw = get_bf_yaw_angle(angle_rad); } + angle_rad.yaw_is_ef = rate_rad.yaw_is_ef; } - return true; + + // update yaw angle target + angle_rad.yaw = angle_rad.yaw + rate_rad.yaw * AP_MOUNT_UPDATE_DT; + if (angle_rad.yaw_is_ef) { + // if earth-frame yaw wraps between += 180 degrees + angle_rad.yaw = wrap_PI(angle_rad.yaw); + } else { + // if body-frame constrain yaw to body-frame limits + angle_rad.yaw = constrain_float(angle_rad.yaw, radians(_params.yaw_angle_min), radians(_params.yaw_angle_max)); + } +} + +// helper function to provide GIMBAL_DEVICE_FLAGS for use in GIMBAL_DEVICE_ATTITUDE_STATUS message +uint16_t AP_Mount_Backend::get_gimbal_device_flags() const +{ + const uint16_t flags = (get_mode() == MAV_MOUNT_MODE_RETRACT ? GIMBAL_DEVICE_FLAGS_RETRACT : 0) | + (get_mode() == MAV_MOUNT_MODE_NEUTRAL ? GIMBAL_DEVICE_FLAGS_NEUTRAL : 0) | + GIMBAL_DEVICE_FLAGS_ROLL_LOCK | // roll angle is always earth-frame + GIMBAL_DEVICE_FLAGS_PITCH_LOCK; // pitch angle is always earth-frame, yaw_angle is always body-frame + return flags; +} + +// get angle targets (in radians) to home location +// returns true on success, false on failure +bool AP_Mount_Backend::get_angle_target_to_home(MountTarget& angle_rad) const +{ + // exit immediately if home is not set + if (!AP::ahrs().home_is_set()) { + return false; + } + return get_angle_target_to_location(AP::ahrs().get_home(), angle_rad); +} + +// get angle targets (in radians) to a vehicle with sysid of _target_sysid +// returns true on success, false on failure +bool AP_Mount_Backend::get_angle_target_to_sysid(MountTarget& angle_rad) const +{ + // exit immediately if sysid is not set or no location available + if (!_target_sysid_location_set) { + return false; + } + if (!_target_sysid) { + return false; + } + return get_angle_target_to_location(_target_sysid_location, angle_rad); +} + +// sent warning to GCS. Warnings are throttled to at most once every 30 seconds +void AP_Mount_Backend::send_warning_to_GCS(const char* warning_str) +{ + uint32_t now_ms = AP_HAL::millis(); + if (now_ms - _last_warning_ms < 30000) { + return; + } + + gcs().send_text(MAV_SEVERITY_WARNING, "Mount: %s", warning_str); + _last_warning_ms = now_ms; } #endif // HAL_MOUNT_ENABLED diff --git a/libraries/AP_Mount/AP_Mount_Backend.h b/libraries/AP_Mount/AP_Mount_Backend.h index 7ccdcca64fb..119e30bde4b 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.h +++ b/libraries/AP_Mount/AP_Mount_Backend.h @@ -19,24 +19,21 @@ */ #pragma once -#include #include "AP_Mount.h" #if HAL_MOUNT_ENABLED +#include #include class AP_Mount_Backend { public: // Constructor - AP_Mount_Backend(AP_Mount &frontend, AP_Mount::mount_state& state, uint8_t instance) : + AP_Mount_Backend(AP_Mount &frontend, AP_Mount_Params ¶ms, uint8_t instance) : _frontend(frontend), - _state(state), + _params(params), _instance(instance) {} - // Virtual destructor - virtual ~AP_Mount_Backend(void) {} - // init - performs any required initialisation for this instance virtual void init() = 0; @@ -46,23 +43,38 @@ class AP_Mount_Backend // used for gimbals that need to read INS data at full rate virtual void update_fast() {} - // has_pan_control - returns true if this mount can control it's pan (required for multicopters) + // return true if healthy + virtual bool healthy() const { return true; } + + // returns true if this mount can control its pan (required for multicopters) virtual bool has_pan_control() const = 0; - // set_mode - sets mount's mode - virtual void set_mode(enum MAV_MOUNT_MODE mode) = 0; + // get mount's mode + enum MAV_MOUNT_MODE get_mode() const { return _mode; } + + // set mount's mode + void set_mode(enum MAV_MOUNT_MODE mode) { _mode = mode; } - // set_angle_targets - sets angle targets in degrees - void set_angle_targets(float roll, float tilt, float pan); + // set yaw_lock. If true, the gimbal's yaw target is maintained in earth-frame meaning it will lock onto an earth-frame heading (e.g. North) + // If false (aka "follow") the gimbal's yaw is maintained in body-frame meaning it will rotate with the vehicle + void set_yaw_lock(bool yaw_lock) { _yaw_lock = yaw_lock; } + + // set angle target in degrees + // yaw_is_earth_frame (aka yaw_lock) should be true if yaw angle is earth-frame, false if body-frame + void set_angle_target(float roll_deg, float pitch_deg, float yaw_deg, bool yaw_is_earth_frame); + + // sets rate target in deg/s + // yaw_lock should be true if the yaw rate is earth-frame, false if body-frame (e.g. rotates with body of vehicle) + void set_rate_target(float roll_degs, float pitch_degs, float yaw_degs, bool yaw_is_earth_frame); // set_roi_target - sets target location that mount should attempt to point towards - void set_roi_target(const struct Location &target_loc); + void set_roi_target(const Location &target_loc); // set_sys_target - sets system that mount should attempt to point towards void set_target_sysid(uint8_t sysid); - // control - control the mount - virtual void control(int32_t pitch_or_lat, int32_t roll_or_lon, int32_t yaw_or_alt, MAV_MOUNT_MODE mount_mode); + // handle do_mount_control command. Returns MAV_RESULT_ACCEPTED on success + MAV_RESULT handle_command_do_mount_control(const mavlink_command_long_t &packet); // process MOUNT_CONFIGURE messages received from GCS. deprecated. void handle_mount_configure(const mavlink_mount_configure_t &msg); @@ -70,8 +82,8 @@ class AP_Mount_Backend // process MOUNT_CONTROL messages received from GCS. deprecated. void handle_mount_control(const mavlink_mount_control_t &packet); - // send_mount_status - called to allow mounts to send their status to GCS via MAVLink - virtual void send_mount_status(mavlink_channel_t chan) = 0; + // send a GIMBAL_DEVICE_ATTITUDE_STATUS message to GCS + void send_gimbal_device_attitude_status(mavlink_channel_t chan); // handle a GIMBAL_REPORT message virtual void handle_gimbal_report(mavlink_channel_t chan, const mavlink_message_t &msg) {} @@ -79,55 +91,128 @@ class AP_Mount_Backend // handle a PARAM_VALUE message virtual void handle_param_value(const mavlink_message_t &msg) {} - // send a GIMBAL_REPORT message to the GCS - virtual void send_gimbal_report(const mavlink_channel_t chan) {} - // handle a GLOBAL_POSITION_INT message bool handle_global_position_int(uint8_t msg_sysid, const mavlink_global_position_int_t &packet); + // handle GIMBAL_DEVICE_INFORMATION message + virtual void handle_gimbal_device_information(const mavlink_message_t &msg) {} + + // handle GIMBAL_DEVICE_ATTITUDE_STATUS message + virtual void handle_gimbal_device_attitude_status(const mavlink_message_t &msg) {} + + // + // camera controls for gimbals that include a camera + // + + // take a picture. returns true on success + virtual bool take_picture() { return false; } + + // start or stop video recording. returns true on success + // set start_recording = true to start record, false to stop recording + virtual bool record_video(bool start_recording) { return false; } + + // set camera zoom step. returns true on success + // zoom out = -1, hold = 0, zoom in = 1 + virtual bool set_zoom_step(int8_t zoom_step) { return false; } + + // set focus in, out or hold. returns true on success + // focus in = -1, focus hold = 0, focus out = 1 + virtual bool set_manual_focus_step(int8_t focus_step) { return false; } + + // auto focus. returns true on success + virtual bool set_auto_focus() { return false; } + protected: - // update_targets_from_rc - updates angle targets (i.e. _angle_ef_target_rad) using input from receiver - void update_targets_from_rc(); - - // angle_input_rad - convert RC input into an earth-frame target angle - float angle_input_rad(const RC_Channel* rc, int16_t angle_min, int16_t angle_max); - - // calc_angle_to_location - calculates the earth-frame roll, tilt - // and pan angles (and radians) to point at the given target - bool calc_angle_to_location(const struct Location &target, - Vector3f& angles_to_target_rad, - bool calc_tilt, - bool calc_pan, - bool relative_pan = true) const WARN_IF_UNUSED; - - // calc_angle_to_roi_target - calculates the earth-frame roll, tilt - // and pan angles (and radians) to point at the ROI-target (as set - // by various mavlink messages) - bool calc_angle_to_roi_target(Vector3f& angles_to_target_rad, - bool calc_tilt, - bool calc_pan, - bool relative_pan = true) const WARN_IF_UNUSED; - - // calc_angle_to_sysid_target - calculates the earth-frame roll, tilt - // and pan angles (and radians) to point at the sysid-target (as set - // by various mavlink messages) - bool calc_angle_to_sysid_target(Vector3f& angles_to_target_rad, - bool calc_tilt, - bool calc_pan, - bool relative_pan = true) const WARN_IF_UNUSED; - - // get the mount mode from frontend - MAV_MOUNT_MODE get_mode(void) const { return _frontend.get_mode(_instance); } + enum class MountTargetType { + ANGLE, + RATE, + }; + + // structure for a single angle or rate target + struct MountTarget { + float roll; + float pitch; + float yaw; + bool yaw_is_ef; + }; + + // returns true if user has configured a valid yaw angle range + // allows user to disable yaw even on 3-axis gimbal + bool yaw_range_valid() const { return (_params.yaw_angle_min < _params.yaw_angle_max); } + + // returns true if mavlink heartbeat should be suppressed for this gimbal (only used by Solo gimbal) + virtual bool suppress_heartbeat() const { return false; } + + // get attitude as a quaternion. returns true on success + virtual bool get_attitude_quaternion(Quaternion& att_quat) = 0; + + // get pilot input (in the range -1 to +1) received through RC + void get_rc_input(float& roll_in, float& pitch_in, float& yaw_in) const; + + // get rate targets (in rad/s) from pilot RC + // returns true on success (RC is providing rate targets), false on failure (RC is providing angle targets) + bool get_rc_rate_target(MountTarget& rate_rads) const WARN_IF_UNUSED; + + // get angle targets (in radians) from pilot RC + // returns true on success (RC is providing angle targets), false on failure (RC is providing rate targets) + bool get_rc_angle_target(MountTarget& angle_rad) const WARN_IF_UNUSED; + + // get angle targets (in radians) to a Location + // returns true on success, false on failure + bool get_angle_target_to_location(const Location &loc, MountTarget& angle_rad) const WARN_IF_UNUSED; + + // get angle targets (in radians) to ROI location + // returns true on success, false on failure + bool get_angle_target_to_roi(MountTarget& angle_rad) const WARN_IF_UNUSED; + + // get angle targets (in radians) to home location + // returns true on success, false on failure + bool get_angle_target_to_home(MountTarget& angle_rad) const WARN_IF_UNUSED; + + // get angle targets (in radians) to a vehicle with sysid of _target_sysid + // returns true on success, false on failure + bool get_angle_target_to_sysid(MountTarget& angle_rad) const WARN_IF_UNUSED; + + // return body-frame yaw angle from a mount target + float get_bf_yaw_angle(const MountTarget& angle_rad) const; + + // return earth-frame yaw angle from a mount target + float get_ef_yaw_angle(const MountTarget& angle_rad) const; + + // update angle targets using a given rate target + // the resulting angle_rad yaw frame will match the rate_rad yaw frame + // assumes a 50hz update rate + void update_angle_target_from_rate(const MountTarget& rate_rad, MountTarget& angle_rad) const; + + // helper function to provide GIMBAL_DEVICE_FLAGS for use in GIMBAL_DEVICE_ATTITUDE_STATUS message + uint16_t get_gimbal_device_flags() const; + + // sent warning to GCS + void send_warning_to_GCS(const char* warning_str); AP_Mount &_frontend; // reference to the front end which holds parameters - AP_Mount::mount_state &_state; // references to the parameters and state for this backend + AP_Mount_Params &_params; // parameters for this backend uint8_t _instance; // this instance's number - Vector3f _angle_ef_target_rad; // desired earth-frame roll, tilt and vehicle-relative pan angles in radians -private: + MAV_MOUNT_MODE _mode; // current mode (see MAV_MOUNT_MODE enum) + bool _yaw_lock; // True if the gimbal's yaw target is maintained in earth-frame, if false (aka "follow") it is maintained in body-frame + + // structure for MAVLink Targeting angle and rate targets + struct { + MountTargetType target_type;// MAVLink targeting mode's current target type (e.g. angle or rate) + MountTarget angle_rad; // angle target in radians + MountTarget rate_rads; // rate target in rad/s + } mavt_target; + + Location _roi_target; // roi target location + bool _roi_target_set; // true if the roi target has been set + + uint8_t _target_sysid; // sysid to track + Location _target_sysid_location;// sysid target location + bool _target_sysid_location_set;// true if _target_sysid has been set - void rate_input_rad(float &out, const RC_Channel *ch, float min, float max) const; + uint32_t _last_warning_ms; // system time of last warning sent to GCS }; #endif // HAL_MOUNT_ENABLED diff --git a/libraries/AP_Mount/AP_Mount_Gremsy.cpp b/libraries/AP_Mount/AP_Mount_Gremsy.cpp new file mode 100644 index 00000000000..f668fbad4d3 --- /dev/null +++ b/libraries/AP_Mount/AP_Mount_Gremsy.cpp @@ -0,0 +1,349 @@ +#include "AP_Mount_Gremsy.h" + +#if HAL_MOUNT_GREMSY_ENABLED + +extern const AP_HAL::HAL& hal; + +#define AP_MOUNT_GREMSY_RESEND_MS 1000 // resend angle targets to gimbal at least once per second +#define AP_MOUNT_GREMSY_SEARCH_MS 60000 // search for gimbal for 1 minute after startup +#define AP_MOUNT_GREMSY_ATTITUDE_INTERVAL_US 20000 // send ATTITUDE and AUTOPILOT_STATE_FOR_GIMBAL_DEVICE at 50hz + +AP_Mount_Gremsy::AP_Mount_Gremsy(AP_Mount &frontend, AP_Mount_Params ¶ms, uint8_t instance) : + AP_Mount_Backend(frontend, params, instance) +{} + +// update mount position +void AP_Mount_Gremsy::update() +{ + // exit immediately if not initialised + if (!_initialised) { + find_gimbal(); + return; + } + + // update based on mount mode + switch (get_mode()) { + + // move mount to a "retracted" position. We disable motors + case MAV_MOUNT_MODE_RETRACT: + // handled below + send_gimbal_device_retract(); + break; + + // move mount to a neutral position, typically pointing forward + case MAV_MOUNT_MODE_NEUTRAL: { + const Vector3f &angle_bf_target = _params.neutral_angles.get(); + send_gimbal_device_set_attitude(ToRad(angle_bf_target.x), ToRad(angle_bf_target.y), ToRad(angle_bf_target.z), false); + } + break; + + // use angle or rate targets provided by a mavlink message or mission command + case MAV_MOUNT_MODE_MAVLINK_TARGETING: + switch (mavt_target.target_type) { + case MountTargetType::ANGLE: + send_gimbal_device_set_attitude(mavt_target.angle_rad.roll, mavt_target.angle_rad.pitch, mavt_target.angle_rad.yaw, mavt_target.angle_rad.yaw_is_ef); + break; + case MountTargetType::RATE: + send_gimbal_device_set_rate(mavt_target.rate_rads.roll, mavt_target.rate_rads.pitch, mavt_target.rate_rads.yaw, mavt_target.rate_rads.yaw_is_ef); + break; + } + break; + + // RC radio manual angle control, but with stabilization from the AHRS + case MAV_MOUNT_MODE_RC_TARGETING: { + // update targets using pilot's rc inputs + MountTarget rc_target {}; + if (get_rc_rate_target(rc_target)) { + send_gimbal_device_set_rate(rc_target.roll, rc_target.pitch, rc_target.yaw, rc_target.yaw_is_ef); + } else if (get_rc_angle_target(rc_target)) { + send_gimbal_device_set_attitude(rc_target.roll, rc_target.pitch, rc_target.yaw, rc_target.yaw_is_ef); + } + break; + } + + // point mount to a GPS point given by the mission planner + case MAV_MOUNT_MODE_GPS_POINT: { + MountTarget angle_target_rad {}; + if (get_angle_target_to_roi(angle_target_rad)) { + send_gimbal_device_set_attitude(angle_target_rad.roll, angle_target_rad.pitch, angle_target_rad.yaw, angle_target_rad.yaw_is_ef); + } + break; + } + + // point mount to home + case MAV_MOUNT_MODE_HOME_LOCATION: { + MountTarget angle_target_rad {}; + if (get_angle_target_to_home(angle_target_rad)) { + send_gimbal_device_set_attitude(angle_target_rad.roll, angle_target_rad.pitch, angle_target_rad.yaw, angle_target_rad.yaw_is_ef); + } + break; + } + + case MAV_MOUNT_MODE_SYSID_TARGET: { + MountTarget angle_target_rad {}; + if (get_angle_target_to_sysid(angle_target_rad)) { + send_gimbal_device_set_attitude(angle_target_rad.roll, angle_target_rad.pitch, angle_target_rad.yaw, angle_target_rad.yaw_is_ef); + } + break; + } + + default: + // unknown mode so do nothing + break; + } +} + +// return true if healthy +bool AP_Mount_Gremsy::healthy() const +{ + // unhealthy until gimbal has been found and replied with device info + if (_link == nullptr || !_got_device_info) { + return false; + } + + // unhealthy if attitude information NOT received within the last second + if (AP_HAL::millis() - _last_attitude_status_ms > 1000) { + return false; + } + + // check failure flags + uint32_t critical_failure_flags = GIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERROR | + GIMBAL_DEVICE_ERROR_FLAGS_POWER_ERROR | + GIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR | + GIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR | + GIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR; + + if ((_gimbal_device_attitude_status.failure_flags & critical_failure_flags) > 0) { + return false; + } + + // if we get this far return mount is healthy + return true; +} + +// get attitude as a quaternion. returns true on success +bool AP_Mount_Gremsy::get_attitude_quaternion(Quaternion& att_quat) +{ + // check we have received an updated message + if (_gimbal_device_attitude_status.time_boot_ms == _sent_gimbal_device_attitude_status_ms) { + return false; + } + _sent_gimbal_device_attitude_status_ms = _gimbal_device_attitude_status.time_boot_ms; + + att_quat = _gimbal_device_attitude_status.q; + return true; +} + +// search for gimbal in GCS_MAVLink routing table +void AP_Mount_Gremsy::find_gimbal() +{ + // do not look for gimbal for first 10 seconds so user may see banner + uint32_t now_ms = AP_HAL::millis(); + if (now_ms < 10000) { + return; + } + + // search for gimbal for 60 seconds or until armed + if ((now_ms > AP_MOUNT_GREMSY_SEARCH_MS) && hal.util->get_soft_armed()) { + return; + } + + // search for a mavlink enabled gimbal + if (_link == nullptr) { + // we expect that instance 0 has compid = MAV_COMP_ID_GIMBAL, instance 1 has compid = MAV_COMP_ID_GIMBAL2, etc + uint8_t compid = (_instance == 0) ? MAV_COMP_ID_GIMBAL : MAV_COMP_ID_GIMBAL2 + (_instance - 1); + _link = GCS_MAVLINK::find_by_mavtype_and_compid(MAV_TYPE_GIMBAL, compid, _sysid); + if (_link == nullptr) { + // have not yet found a gimbal so return + return; + } + + _compid = compid; + } + + // request GIMBAL_DEVICE_INFORMATION + if (!_got_device_info) { + if (now_ms - _last_devinfo_req_ms > 1000) { + _last_devinfo_req_ms = now_ms; + request_gimbal_device_information(); + } + return; + } + + // start sending autopilot attitude to gimbal + if (start_sending_attitude_to_gimbal()) { + _initialised = true; + } +} + +// handle GIMBAL_DEVICE_INFORMATION message +void AP_Mount_Gremsy::handle_gimbal_device_information(const mavlink_message_t &msg) +{ + // exit immediately if this is not our message + if (msg.sysid != _sysid || msg.compid != _compid) { + return; + } + + mavlink_gimbal_device_information_t info; + mavlink_msg_gimbal_device_information_decode(&msg, &info); + + // set parameter defaults from gimbal information + _params.roll_angle_min.set_default(degrees(info.roll_min)); + _params.roll_angle_max.set_default(degrees(info.roll_max)); + _params.pitch_angle_min.set_default(degrees(info.pitch_min)); + _params.pitch_angle_max.set_default(degrees(info.pitch_max)); + _params.yaw_angle_min.set_default(degrees(info.yaw_min)); + _params.yaw_angle_max.set_default(degrees(info.yaw_max)); + + const uint8_t fw_ver_major = info.firmware_version & 0x000000FF; + const uint8_t fw_ver_minor = (info.firmware_version & 0x0000FF00) >> 8; + const uint8_t fw_ver_revision = (info.firmware_version & 0x00FF0000) >> 16; + const uint8_t fw_ver_build = (info.firmware_version & 0xFF000000) >> 24; + + // display gimbal info to user + gcs().send_text(MAV_SEVERITY_INFO, "Mount: %s %s fw:%u.%u.%u.%u", + info.vendor_name, + info.model_name, + (unsigned)fw_ver_major, + (unsigned)fw_ver_minor, + (unsigned)fw_ver_revision, + (unsigned)fw_ver_build); + + _got_device_info = true; +} + +// handle GIMBAL_DEVICE_ATTITUDE_STATUS message +void AP_Mount_Gremsy::handle_gimbal_device_attitude_status(const mavlink_message_t &msg) +{ + // exit immediately if this is not our message + if (msg.sysid != _sysid || msg.compid != _compid) { + return; + } + + // take copy of message so it can be forwarded onto GCS later + mavlink_msg_gimbal_device_attitude_status_decode(&msg, &_gimbal_device_attitude_status); + _last_attitude_status_ms = AP_HAL::millis(); +} + +// request GIMBAL_DEVICE_INFORMATION message +void AP_Mount_Gremsy::request_gimbal_device_information() const +{ + if (_link == nullptr) { + return; + } + const mavlink_channel_t chan = _link->get_chan(); + + // check we have space for the message + if (!HAVE_PAYLOAD_SPACE(chan, COMMAND_LONG)) { + return; + } + + mavlink_msg_command_long_send( + chan, + _sysid, + _compid, + MAV_CMD_REQUEST_MESSAGE, + 0, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION, 0, 0, 0, 0, 0, 0); +} + +// start sending ATTITUDE and AUTOPILOT_STATE_FOR_GIMBAL_DEVICE to gimbal +bool AP_Mount_Gremsy::start_sending_attitude_to_gimbal() +{ + // better safe than sorry: + if (_link == nullptr) { + return false; + } + // send AUTOPILOT_STATE_FOR_GIMBAL_DEVICE + const MAV_RESULT res = _link->set_message_interval(MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE, AP_MOUNT_GREMSY_ATTITUDE_INTERVAL_US); + + // return true on success + return (res == MAV_RESULT_ACCEPTED); +} + +// send GIMBAL_DEVICE_SET_ATTITUDE to gimbal to command gimbal to retract (aka relax) +void AP_Mount_Gremsy::send_gimbal_device_retract() const +{ + if (_link == nullptr) { + return; + } + const mavlink_channel_t chan = _link->get_chan(); + + // check we have space for the message + if (!HAVE_PAYLOAD_SPACE(chan, GIMBAL_DEVICE_SET_ATTITUDE)) { + return; + } + + // send command_long command containing a do_mount_control command + const float quat_array[4] = {NAN, NAN, NAN, NAN}; + mavlink_msg_gimbal_device_set_attitude_send(chan, + _sysid, // target system + _compid, // target component + GIMBAL_DEVICE_FLAGS_RETRACT, // gimbal device flags + quat_array, // attitude as a quaternion + 0, 0, 0); // angular velocities +} + +// send GIMBAL_DEVICE_SET_ATTITUDE to gimbal to control rate +// earth_frame should be true if yaw_rads target is an earth frame rate, false if body_frame +void AP_Mount_Gremsy::send_gimbal_device_set_rate(float roll_rads, float pitch_rads, float yaw_rads, bool earth_frame) const +{ + if (_link == nullptr) { + return; + } + const mavlink_channel_t chan = _link->get_chan(); + + // check we have space for the message + if (!HAVE_PAYLOAD_SPACE(chan, GIMBAL_DEVICE_SET_ATTITUDE)) { + return; + } + + // prepare flags + const uint16_t flags = earth_frame ? (GIMBAL_DEVICE_FLAGS_ROLL_LOCK | GIMBAL_DEVICE_FLAGS_PITCH_LOCK | GIMBAL_DEVICE_FLAGS_YAW_LOCK) : 0; + const float quat_array[4] = {NAN, NAN, NAN, NAN}; + + // send command_long command containing a do_mount_control command + mavlink_msg_gimbal_device_set_attitude_send(chan, + _sysid, // target system + _compid, // target component + flags, // gimbal device flags + quat_array, // attitude as a quaternion + roll_rads, pitch_rads, yaw_rads); // angular velocities +} + +// send GIMBAL_DEVICE_SET_ATTITUDE to gimbal to control attitude +// earth_frame should be true if yaw_rad target is in earth frame angle, false if body_frame +void AP_Mount_Gremsy::send_gimbal_device_set_attitude(float roll_rad, float pitch_rad, float yaw_rad, bool earth_frame) const +{ + // exit immediately if not initialised + if (!_initialised) { + return; + } + + if (_link == nullptr) { + return; + } + const mavlink_channel_t chan = _link->get_chan(); + + // check we have space for the message + if (!HAVE_PAYLOAD_SPACE(chan, GIMBAL_DEVICE_SET_ATTITUDE)) { + return; + } + + // prepare flags + const uint16_t flags = earth_frame ? (GIMBAL_DEVICE_FLAGS_ROLL_LOCK | GIMBAL_DEVICE_FLAGS_PITCH_LOCK | GIMBAL_DEVICE_FLAGS_YAW_LOCK) : 0; + + // convert euler angles to quaternion + Quaternion q; + q.from_euler(roll_rad, pitch_rad, yaw_rad); + const float quat_array[4] = {q.q1, q.q2, q.q3, q.q4}; + + // send command_long command containing a do_mount_control command + mavlink_msg_gimbal_device_set_attitude_send(chan, + _sysid, // target system + _compid, // target component + flags, // gimbal device flags + quat_array, // attitude as a quaternion + NAN, NAN, NAN); // angular velocities +} + +#endif // HAL_MOUNT_GREMSY_ENABLED diff --git a/libraries/AP_Mount/AP_Mount_Gremsy.h b/libraries/AP_Mount/AP_Mount_Gremsy.h new file mode 100644 index 00000000000..4895fcd5003 --- /dev/null +++ b/libraries/AP_Mount/AP_Mount_Gremsy.h @@ -0,0 +1,84 @@ +/* + Gremsy mount backend class + */ +#pragma once + +#include "AP_Mount_Backend.h" + +#ifndef HAL_MOUNT_GREMSY_ENABLED +#define HAL_MOUNT_GREMSY_ENABLED (HAL_MOUNT_ENABLED && !HAL_MINIMIZE_FEATURES && BOARD_FLASH_SIZE > 1024) +#endif + +#if HAL_MOUNT_GREMSY_ENABLED + +#include +#include +#include +#include +#include + +class AP_Mount_Gremsy : public AP_Mount_Backend +{ + +public: + // Constructor + AP_Mount_Gremsy(AP_Mount &frontend, AP_Mount_Params ¶ms, uint8_t instance); + + // init + void init() override {} + + // update mount position + void update() override; + + // return true if healthy + bool healthy() const override; + + // has_pan_control + bool has_pan_control() const override { return yaw_range_valid(); } + + // handle GIMBAL_DEVICE_INFORMATION message + void handle_gimbal_device_information(const mavlink_message_t &msg) override; + + // handle GIMBAL_DEVICE_ATTITUDE_STATUS message + void handle_gimbal_device_attitude_status(const mavlink_message_t &msg) override; + +protected: + + // get attitude as a quaternion. returns true on success + bool get_attitude_quaternion(Quaternion& att_quat) override; + +private: + + // search for gimbal in GCS_MAVLink routing table + void find_gimbal(); + + // request GIMBAL_DEVICE_INFORMATION from gimbal (holds vendor and model name, max lean angles) + void request_gimbal_device_information() const; + + // start sending ATTITUDE and AUTOPILOT_STATE_FOR_GIMBAL_DEVICE to gimbal + // returns true on success, false on failure to start sending + bool start_sending_attitude_to_gimbal(); + + // send GIMBAL_DEVICE_SET_ATTITUDE to gimbal to command gimbal to retract (aka relax) + void send_gimbal_device_retract() const; + + // send GIMBAL_DEVICE_SET_ATTITUDE to gimbal to control rate + // earth_frame should be true if yaw_rads target is an earth frame rate, false if body_frame + void send_gimbal_device_set_rate(float roll_rads, float pitch_rads, float yaw_rads, bool earth_frame) const; + + // send GIMBAL_DEVICE_SET_ATTITUDE to gimbal to control attitude + // earth_frame should be true if yaw_rad target is an earth frame angle, false if body_frame + void send_gimbal_device_set_attitude(float roll_rad, float pitch_rad, float yaw_rad, bool earth_frame) const; + + // internal variables + bool _got_device_info; // true once gimbal has provided device info + bool _initialised; // true once the gimbal has provided a GIMBAL_DEVICE_INFORMATION + uint32_t _last_devinfo_req_ms; // system time that GIMBAL_DEVICE_INFORMATION was last requested (used to throttle requests) + class GCS_MAVLINK *_link; // link we have found gimbal on; nullptr if not seen yet + uint8_t _sysid; // sysid of gimbal + uint8_t _compid; // component id of gimbal + mavlink_gimbal_device_attitude_status_t _gimbal_device_attitude_status; // copy of most recently received gimbal status + uint32_t _last_attitude_status_ms; // system time last attitude status was received (used for health reporting) + uint32_t _sent_gimbal_device_attitude_status_ms; // time_boot_ms field of gimbal_device_status message last forwarded to the GCS (used to prevent sending duplicates) +}; +#endif // HAL_MOUNT_GREMSY_ENABLED diff --git a/libraries/AP_Mount/AP_Mount_Params.cpp b/libraries/AP_Mount/AP_Mount_Params.cpp new file mode 100644 index 00000000000..d8655bb8a80 --- /dev/null +++ b/libraries/AP_Mount/AP_Mount_Params.cpp @@ -0,0 +1,160 @@ +#include "AP_Mount_Params.h" +#include + +// table of user settable parameters +const AP_Param::GroupInfo AP_Mount_Params::var_info[] = { + + // 0 should not be used + + // @Param: _TYPE + // @DisplayName: Mount Type + // @Description: Mount Type + // @Values: 0:None, 1:Servo, 2:3DR Solo, 3:Alexmos Serial, 4:SToRM32 MAVLink, 5:SToRM32 Serial, 6:Gremsy, 7:BrushlessPWM, 8:Siyi + // @RebootRequired: True + // @User: Standard + AP_GROUPINFO_FLAGS("_TYPE", 1, AP_Mount_Params, type, 0, AP_PARAM_FLAG_ENABLE), + + // @Param: _DEFLT_MODE + // @DisplayName: Mount default operating mode + // @Description: Mount default operating mode on startup and after control is returned from autopilot + // @Values: 0:Retracted,1:Neutral,2:MavLink Targeting,3:RC Targeting,4:GPS Point,6:Home Location + // @User: Standard + AP_GROUPINFO("_DEFLT_MODE", 2, AP_Mount_Params, default_mode, MAV_MOUNT_MODE_RC_TARGETING), + + // @Param: _RC_RATE + // @DisplayName: Mount RC Rate + // @Description: Pilot rate control's maximum rate. Set to zero to use angle control + // @Units: deg/s + // @Range: 0 90 + // @Increment: 1 + // @User: Standard + AP_GROUPINFO("_RC_RATE", 3, AP_Mount_Params, rc_rate_max, 0), + + // @Param: _ROLL_MIN + // @DisplayName: Mount Roll angle minimum + // @Description: Mount Roll angle minimum + // @Units: deg + // @Range: -180 180 + // @Increment: 1 + // @User: Standard + AP_GROUPINFO("_ROLL_MIN", 4, AP_Mount_Params, roll_angle_min, -30), + + // @Param: _ROLL_MAX + // @DisplayName: Mount Roll angle maximum + // @Description: Mount Roll angle maximum + // @Units: deg + // @Range: -180 180 + // @Increment: 1 + // @User: Standard + AP_GROUPINFO("_ROLL_MAX", 5, AP_Mount_Params, roll_angle_max, 30), + + // @Param: _PITCH_MIN + // @DisplayName: Mount Pitch angle minimum + // @Description: Mount Pitch angle minimum + // @Units: deg + // @Range: -90 90 + // @Increment: 1 + // @User: Standard + AP_GROUPINFO("_PITCH_MIN", 6, AP_Mount_Params, pitch_angle_min, -90), + + // @Param: _PITCH_MAX + // @DisplayName: Mount Pitch angle maximum + // @Description: Mount Pitch angle maximum + // @Units: deg + // @Range: -90 90 + // @Increment: 1 + // @User: Standard + AP_GROUPINFO("_PITCH_MAX", 7, AP_Mount_Params, pitch_angle_max, 20), + + // @Param: _YAW_MIN + // @DisplayName: Mount Yaw angle minimum + // @Description: Mount Yaw angle minimum + // @Units: deg + // @Range: -180 180 + // @Increment: 1 + // @User: Standard + AP_GROUPINFO("_YAW_MIN", 8, AP_Mount_Params, yaw_angle_min, -180), + + // @Param: _YAW_MAX + // @DisplayName: Mount Yaw angle maximum + // @Description: Mount Yaw angle maximum + // @Units: deg + // @Range: -180 180 + // @Increment: 1 + // @User: Standard + AP_GROUPINFO("_YAW_MAX", 9, AP_Mount_Params, yaw_angle_max, 180), + + // @Param: _RETRACT_X + // @DisplayName: Mount roll angle when in retracted position + // @Description: Mount roll angle when in retracted position + // @Units: deg + // @Range: -180.0 180.0 + // @Increment: 1 + // @User: Standard + + // @Param: _RETRACT_Y + // @DisplayName: Mount pitch angle when in retracted position + // @Description: Mount pitch angle when in retracted position + // @Units: deg + // @Range: -180.0 180.0 + // @Increment: 1 + // @User: Standard + + // @Param: _RETRACT_Z + // @DisplayName: Mount yaw angle when in retracted position + // @Description: Mount yaw angle when in retracted position + // @Units: deg + // @Range: -180.0 180.0 + // @Increment: 1 + // @User: Standard + AP_GROUPINFO("_RETRACT", 10, AP_Mount_Params, retract_angles, 0), + + // @Param: _NEUTRAL_X + // @DisplayName: Mount roll angle when in neutral position + // @Description: Mount roll angle when in neutral position + // @Units: deg + // @Range: -180.0 180.0 + // @Increment: 1 + // @User: Standard + + // @Param: _NEUTRAL_Y + // @DisplayName: Mount pitch angle when in neutral position + // @Description: Mount pitch angle when in neutral position + // @Units: deg + // @Range: -180.0 180.0 + // @Increment: 1 + // @User: Standard + + // @Param: _NEUTRAL_Z + // @DisplayName: Mount yaw angle when in neutral position + // @Description: Mount yaw angle when in neutral position + // @Units: deg + // @Range: -180.0 180.0 + // @Increment: 1 + // @User: Standard + AP_GROUPINFO("_NEUTRAL", 11, AP_Mount_Params, neutral_angles, 0), + + // @Param: _LEAD_RLL + // @DisplayName: Mount Roll stabilization lead time + // @Description: Servo mount roll angle output leads the vehicle angle by this amount of time based on current roll rate. Increase until the servo is responsive but does not overshoot + // @Units: s + // @Range: 0.0 0.2 + // @Increment: .005 + // @User: Standard + AP_GROUPINFO("_LEAD_RLL", 12, AP_Mount_Params, roll_stb_lead, 0.0f), + + // @Param: _LEAD_PTCH + // @DisplayName: Mount Pitch stabilization lead time + // @Description: Servo mount pitch angle output leads the vehicle angle by this amount of time based on current pitch rate. Increase until the servo is responsive but does not overshoot + // @Units: s + // @Range: 0.0 0.2 + // @Increment: .005 + // @User: Standard + AP_GROUPINFO("_LEAD_PTCH", 13, AP_Mount_Params, pitch_stb_lead, 0.0f), + + AP_GROUPEND +}; + +AP_Mount_Params::AP_Mount_Params(void) { + AP_Param::setup_object_defaults(this, var_info); +} diff --git a/libraries/AP_Mount/AP_Mount_Params.h b/libraries/AP_Mount/AP_Mount_Params.h new file mode 100644 index 00000000000..4a2322cf9ba --- /dev/null +++ b/libraries/AP_Mount/AP_Mount_Params.h @@ -0,0 +1,33 @@ +#pragma once + +#include +#include + +class AP_Mount_Params { + +public: + + static const struct AP_Param::GroupInfo var_info[]; + + AP_Mount_Params(void); + + /* Do not allow copies */ + AP_Mount_Params(const AP_Mount_Params &other) = delete; + AP_Mount_Params &operator=(const AP_Mount_Params&) = delete; + + AP_Int8 type; // mount type (see MountType enum) + AP_Int8 default_mode; // default mode on startup and when control is returned from autopilot + AP_Int16 rc_rate_max; // Pilot rate control's maximum rate. Set to zero to use angle control + AP_Int16 roll_angle_min; // roll angle min in degrees + AP_Int16 roll_angle_max; // roll angle max in degrees + AP_Int16 pitch_angle_min; // pitch angle min in degrees + AP_Int16 pitch_angle_max; // pitch angle max in degrees + AP_Int16 yaw_angle_min; // yaw angle min in degrees + AP_Int16 yaw_angle_max; // yaw angle max in degrees + + AP_Vector3f retract_angles; // retracted position in degrees. vector.x = roll vector.y = pitch, vector.z=yaw + AP_Vector3f neutral_angles; // neutral position in degrees. vector.x = roll vector.y = pitch, vector.z=yaw + + AP_Float roll_stb_lead; // roll lead control gain (only used by servo backend) + AP_Float pitch_stb_lead; // pitch lead control gain (only used by servo backend) +}; diff --git a/libraries/AP_Mount/AP_Mount_SToRM32.cpp b/libraries/AP_Mount/AP_Mount_SToRM32.cpp index 06a77f5e48a..52aa45616b4 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32.cpp +++ b/libraries/AP_Mount/AP_Mount_SToRM32.cpp @@ -1,12 +1,16 @@ #include "AP_Mount_SToRM32.h" -#if HAL_MOUNT_ENABLED + +#if HAL_MOUNT_STORM32MAVLINK_ENABLED #include #include extern const AP_HAL::HAL& hal; -AP_Mount_SToRM32::AP_Mount_SToRM32(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance) : - AP_Mount_Backend(frontend, state, instance), +#define AP_MOUNT_STORM32_RESEND_MS 1000 // resend angle targets to gimbal once per second +#define AP_MOUNT_STORM32_SEARCH_MS 60000 // search for gimbal for 1 minute after startup + +AP_Mount_SToRM32::AP_Mount_SToRM32(AP_Mount &frontend, AP_Mount_Params ¶ms, uint8_t instance) : + AP_Mount_Backend(frontend, params, instance), _chan(MAVLINK_COMM_0) {} @@ -25,59 +29,66 @@ void AP_Mount_SToRM32::update() // update based on mount mode switch(get_mode()) { // move mount to a "retracted" position. To-Do: remove support and replace with a relaxed mode? - case MAV_MOUNT_MODE_RETRACT: - { - const Vector3f &target = _state._retract_angles.get(); - _angle_ef_target_rad.x = ToRad(target.x); - _angle_ef_target_rad.y = ToRad(target.y); - _angle_ef_target_rad.z = ToRad(target.z); - } + case MAV_MOUNT_MODE_RETRACT: { + const Vector3f &target = _params.retract_angles.get(); + _angle_rad.roll = radians(target.x); + _angle_rad.pitch = radians(target.y); + _angle_rad.yaw = radians(target.z); + _angle_rad.yaw_is_ef = false; break; + } // move mount to a neutral position, typically pointing forward - case MAV_MOUNT_MODE_NEUTRAL: - { - const Vector3f &target = _state._neutral_angles.get(); - _angle_ef_target_rad.x = ToRad(target.x); - _angle_ef_target_rad.y = ToRad(target.y); - _angle_ef_target_rad.z = ToRad(target.z); - } + case MAV_MOUNT_MODE_NEUTRAL: { + const Vector3f &target = _params.neutral_angles.get(); + _angle_rad.roll = radians(target.x); + _angle_rad.pitch = radians(target.y); + _angle_rad.yaw = radians(target.z); + _angle_rad.yaw_is_ef = false; break; + } // point to the angles given by a mavlink message case MAV_MOUNT_MODE_MAVLINK_TARGETING: - // do nothing because earth-frame angle targets (i.e. _angle_ef_target_rad) should have already been set by a MOUNT_CONTROL message from GCS + switch (mavt_target.target_type) { + case MountTargetType::ANGLE: + _angle_rad = mavt_target.angle_rad; + break; + case MountTargetType::RATE: + update_angle_target_from_rate(mavt_target.rate_rads, _angle_rad); + break; + } resend_now = true; break; // RC radio manual angle control, but with stabilization from the AHRS - case MAV_MOUNT_MODE_RC_TARGETING: - // update targets using pilot's rc inputs - update_targets_from_rc(); + case MAV_MOUNT_MODE_RC_TARGETING: { + // update targets using pilot's RC inputs + MountTarget rc_target {}; + if (get_rc_rate_target(rc_target)) { + update_angle_target_from_rate(rc_target, _angle_rad); + } else if (get_rc_angle_target(rc_target)) { + _angle_rad = rc_target; + } resend_now = true; break; + } - // point mount to a GPS point given by the mission planner + // point mount to a GPS location case MAV_MOUNT_MODE_GPS_POINT: - if (calc_angle_to_roi_target(_angle_ef_target_rad, true, true)) { + if (get_angle_target_to_roi(_angle_rad)) { resend_now = true; } break; case MAV_MOUNT_MODE_HOME_LOCATION: - // constantly update the home location: - if (!AP::ahrs().home_is_set()) { - break; - } - _state._roi_target = AP::ahrs().get_home(); - _state._roi_target_set = true; - if (calc_angle_to_roi_target(_angle_ef_target_rad, true, true)) { + if (get_angle_target_to_home(_angle_rad)) { resend_now = true; } break; case MAV_MOUNT_MODE_SYSID_TARGET: - if (calc_angle_to_sysid_target(_angle_ef_target_rad, true, true)) { + if (get_angle_target_to_sysid(_angle_rad)) { resend_now = true; } break; @@ -89,34 +100,15 @@ void AP_Mount_SToRM32::update() // resend target angles at least once per second if (resend_now || ((AP_HAL::millis() - _last_send) > AP_MOUNT_STORM32_RESEND_MS)) { - send_do_mount_control(ToDeg(_angle_ef_target_rad.y), ToDeg(_angle_ef_target_rad.x), ToDeg(_angle_ef_target_rad.z), MAV_MOUNT_MODE_MAVLINK_TARGETING); - } -} - -// has_pan_control - returns true if this mount can control it's pan (required for multicopters) -bool AP_Mount_SToRM32::has_pan_control() const -{ - // we do not have yaw control - return false; -} - -// set_mode - sets mount's mode -void AP_Mount_SToRM32::set_mode(enum MAV_MOUNT_MODE mode) -{ - // exit immediately if not initialised - if (!_initialised) { - return; + send_do_mount_control(_angle_rad); } - - // record the mode change - _state._mode = mode; } -// send_mount_status - called to allow mounts to send their status to GCS using the MOUNT_STATUS message -void AP_Mount_SToRM32::send_mount_status(mavlink_channel_t chan) +// get attitude as a quaternion. returns true on success +bool AP_Mount_SToRM32::get_attitude_quaternion(Quaternion& att_quat) { - // return target angles as gimbal's actual attitude. To-Do: retrieve actual gimbal attitude and send these instead - mavlink_msg_mount_status_send(chan, 0, 0, ToDeg(_angle_ef_target_rad.y)*100, ToDeg(_angle_ef_target_rad.x)*100, ToDeg(_angle_ef_target_rad.z)*100, _state._mode); + att_quat.from_euler(_angle_rad.roll, _angle_rad.pitch, get_bf_yaw_angle(_angle_rad)); + return true; } // search for gimbal in GCS_MAVLink routing table @@ -132,13 +124,16 @@ void AP_Mount_SToRM32::find_gimbal() return; } - if (GCS_MAVLINK::find_by_mavtype(MAV_TYPE_GIMBAL, _sysid, _compid, _chan)) { + // we expect that instance 0 has compid = MAV_COMP_ID_GIMBAL, instance 1 has compid = MAV_COMP_ID_GIMBAL2, etc + uint8_t compid = (_instance == 0) ? MAV_COMP_ID_GIMBAL : MAV_COMP_ID_GIMBAL2 + (_instance - 1); + if (GCS_MAVLINK::find_by_mavtype_and_compid(MAV_TYPE_GIMBAL, compid, _sysid, _chan)) { + _compid = compid; _initialised = true; } } // send_do_mount_control - send a COMMAND_LONG containing a do_mount_control message -void AP_Mount_SToRM32::send_do_mount_control(float pitch_deg, float roll_deg, float yaw_deg, enum MAV_MOUNT_MODE mount_mode) +void AP_Mount_SToRM32::send_do_mount_control(const MountTarget& angle_target_rad) { // exit immediately if not initialised if (!_initialised) { @@ -150,23 +145,20 @@ void AP_Mount_SToRM32::send_do_mount_control(float pitch_deg, float roll_deg, fl return; } - // reverse pitch and yaw control - pitch_deg = -pitch_deg; - yaw_deg = -yaw_deg; - // send command_long command containing a do_mount_control command + // Note: pitch and yaw are reversed mavlink_msg_command_long_send(_chan, _sysid, _compid, MAV_CMD_DO_MOUNT_CONTROL, 0, // confirmation of zero means this is the first time this message has been sent - pitch_deg, - roll_deg, - yaw_deg, + -degrees(angle_target_rad.pitch), + degrees(angle_target_rad.roll), + -degrees(get_bf_yaw_angle(angle_target_rad)), 0, 0, 0, // param4 ~ param6 unused - mount_mode); + MAV_MOUNT_MODE_MAVLINK_TARGETING); // store time of send _last_send = AP_HAL::millis(); } -#endif // HAL_MOUNT_ENABLED +#endif // HAL_MOUNT_STORM32MAVLINK_ENABLED diff --git a/libraries/AP_Mount/AP_Mount_SToRM32.h b/libraries/AP_Mount/AP_Mount_SToRM32.h index 75b639b078f..2f195b910b3 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32.h +++ b/libraries/AP_Mount/AP_Mount_SToRM32.h @@ -3,24 +3,25 @@ */ #pragma once -#include -#include +#include "AP_Mount_Backend.h" + +#ifndef HAL_MOUNT_STORM32MAVLINK_ENABLED +#define HAL_MOUNT_STORM32MAVLINK_ENABLED HAL_MOUNT_ENABLED +#endif + +#if HAL_MOUNT_STORM32MAVLINK_ENABLED #include #include #include -#include "AP_Mount_Backend.h" -#if HAL_MOUNT_ENABLED - -#define AP_MOUNT_STORM32_RESEND_MS 1000 // resend angle targets to gimbal once per second -#define AP_MOUNT_STORM32_SEARCH_MS 60000 // search for gimbal for 1 minute after startup +#include class AP_Mount_SToRM32 : public AP_Mount_Backend { public: // Constructor - AP_Mount_SToRM32(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance); + AP_Mount_SToRM32(AP_Mount &frontend, AP_Mount_Params ¶ms, uint8_t instance); // init - performs any required initialisation for this instance void init() override {} @@ -28,28 +29,28 @@ class AP_Mount_SToRM32 : public AP_Mount_Backend // update mount position - should be called periodically void update() override; - // has_pan_control - returns true if this mount can control it's pan (required for multicopters) - bool has_pan_control() const override; + // has_pan_control - returns true if this mount can control its pan (required for multicopters) + bool has_pan_control() const override { return yaw_range_valid(); } - // set_mode - sets mount's mode - void set_mode(enum MAV_MOUNT_MODE mode) override; +protected: - // send_mount_status - called to allow mounts to send their status to GCS using the MOUNT_STATUS message - void send_mount_status(mavlink_channel_t chan) override; + // get attitude as a quaternion. returns true on success + bool get_attitude_quaternion(Quaternion& att_quat) override; private: // search for gimbal in GCS_MAVLink routing table void find_gimbal(); - // send_do_mount_control - send a COMMAND_LONG containing a do_mount_control message - void send_do_mount_control(float pitch_deg, float roll_deg, float yaw_deg, enum MAV_MOUNT_MODE mount_mode); + // send_do_mount_control with latest angle targets + void send_do_mount_control(const MountTarget& angle_target_rad); // internal variables bool _initialised; // true once the driver has been initialised uint8_t _sysid; // sysid of gimbal uint8_t _compid; // component id of gimbal - mavlink_channel_t _chan; // mavlink channel used to communicate with gimbal. Currently hard-coded to Telem2 + mavlink_channel_t _chan; // mavlink channel used to communicate with gimbal uint32_t _last_send; // system time of last do_mount_control sent to gimbal + MountTarget _angle_rad; // latest angle target }; -#endif // HAL_MOUNT_ENABLED +#endif // HAL_MOUNT_STORM32MAVLINK_ENABLED diff --git a/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp b/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp index 85ab28c3db2..98cdc269213 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp +++ b/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp @@ -1,5 +1,6 @@ #include "AP_Mount_SToRM32_serial.h" -#if HAL_MOUNT_ENABLED + +#if HAL_MOUNT_STORM32SERIAL_ENABLED #include #include #include @@ -7,8 +8,8 @@ extern const AP_HAL::HAL& hal; -AP_Mount_SToRM32_serial::AP_Mount_SToRM32_serial(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance) : - AP_Mount_Backend(frontend, state, instance), +AP_Mount_SToRM32_serial::AP_Mount_SToRM32_serial(AP_Mount &frontend, AP_Mount_Params ¶ms, uint8_t instance) : + AP_Mount_Backend(frontend, params, instance), _reply_type(ReplyType_UNKNOWN) {} @@ -20,7 +21,7 @@ void AP_Mount_SToRM32_serial::init() _port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_SToRM32, 0); if (_port) { _initialised = true; - set_mode((enum MAV_MOUNT_MODE)_state._default_mode.get()); + set_mode((enum MAV_MOUNT_MODE)_params.default_mode.get()); } } @@ -41,61 +42,66 @@ void AP_Mount_SToRM32_serial::update() // update based on mount mode switch(get_mode()) { // move mount to a "retracted" position. To-Do: remove support and replace with a relaxed mode? - case MAV_MOUNT_MODE_RETRACT: - { - const Vector3f &target = _state._retract_angles.get(); - _angle_ef_target_rad.x = ToRad(target.x); - _angle_ef_target_rad.y = ToRad(target.y); - _angle_ef_target_rad.z = ToRad(target.z); - } + case MAV_MOUNT_MODE_RETRACT: { + const Vector3f &target = _params.retract_angles.get(); + _angle_rad.roll = ToRad(target.x); + _angle_rad.pitch = ToRad(target.y); + _angle_rad.yaw = ToRad(target.z); + _angle_rad.yaw_is_ef = false; break; + } // move mount to a neutral position, typically pointing forward - case MAV_MOUNT_MODE_NEUTRAL: - { - const Vector3f &target = _state._neutral_angles.get(); - _angle_ef_target_rad.x = ToRad(target.x); - _angle_ef_target_rad.y = ToRad(target.y); - _angle_ef_target_rad.z = ToRad(target.z); - } + case MAV_MOUNT_MODE_NEUTRAL: { + const Vector3f &target = _params.neutral_angles.get(); + _angle_rad.roll = ToRad(target.x); + _angle_rad.pitch = ToRad(target.y); + _angle_rad.yaw = ToRad(target.z); + _angle_rad.yaw_is_ef = false; break; + } // point to the angles given by a mavlink message case MAV_MOUNT_MODE_MAVLINK_TARGETING: - // do nothing because earth-frame angle targets (i.e. _angle_ef_target_rad) should have already been set by a MOUNT_CONTROL message from GCS + switch (mavt_target.target_type) { + case MountTargetType::ANGLE: + _angle_rad = mavt_target.angle_rad; + break; + case MountTargetType::RATE: + update_angle_target_from_rate(mavt_target.rate_rads, _angle_rad); + break; + } resend_now = true; break; // RC radio manual angle control, but with stabilization from the AHRS - case MAV_MOUNT_MODE_RC_TARGETING: - // update targets using pilot's rc inputs - update_targets_from_rc(); + case MAV_MOUNT_MODE_RC_TARGETING: { + // update targets using pilot's RC inputs + MountTarget rc_target {}; + if (get_rc_rate_target(rc_target)) { + update_angle_target_from_rate(rc_target, _angle_rad); + } else if (get_rc_angle_target(rc_target)) { + _angle_rad = rc_target; + } resend_now = true; break; + } // point mount to a GPS point given by the mission planner case MAV_MOUNT_MODE_GPS_POINT: - if (calc_angle_to_roi_target(_angle_ef_target_rad, true, true)) { + if (get_angle_target_to_roi(_angle_rad)) { resend_now = true; } break; case MAV_MOUNT_MODE_HOME_LOCATION: - // constantly update the home location: - if (!AP::ahrs().home_is_set()) { - break; - } - _state._roi_target = AP::ahrs().get_home(); - _state._roi_target_set = true; - if (calc_angle_to_roi_target(_angle_ef_target_rad, true, true)) { + if (get_angle_target_to_home(_angle_rad)) { resend_now = true; } break; case MAV_MOUNT_MODE_SYSID_TARGET: - if (calc_angle_to_sysid_target(_angle_ef_target_rad, - true, - true)) { + if (get_angle_target_to_sysid(_angle_rad)) { resend_now = true; } break; @@ -113,7 +119,7 @@ void AP_Mount_SToRM32_serial::update() } if (can_send(resend_now)) { if (resend_now) { - send_target_angles(ToDeg(_angle_ef_target_rad.y), ToDeg(_angle_ef_target_rad.x), ToDeg(_angle_ef_target_rad.z)); + send_target_angles(_angle_rad); get_angles(); _reply_type = ReplyType_ACK; _reply_counter = 0; @@ -127,30 +133,11 @@ void AP_Mount_SToRM32_serial::update() } } -// has_pan_control - returns true if this mount can control it's pan (required for multicopters) -bool AP_Mount_SToRM32_serial::has_pan_control() const +// get attitude as a quaternion. returns true on success +bool AP_Mount_SToRM32_serial::get_attitude_quaternion(Quaternion& att_quat) { - // we do not have yaw control - return false; -} - -// set_mode - sets mount's mode -void AP_Mount_SToRM32_serial::set_mode(enum MAV_MOUNT_MODE mode) -{ - // exit immediately if not initialised - if (!_initialised) { - return; - } - - // record the mode change - _state._mode = mode; -} - -// send_mount_status - called to allow mounts to send their status to GCS using the MOUNT_STATUS message -void AP_Mount_SToRM32_serial::send_mount_status(mavlink_channel_t chan) -{ - // return target angles as gimbal's actual attitude. - mavlink_msg_mount_status_send(chan, 0, 0, _current_angle.y, _current_angle.x, _current_angle.z, _state._mode); + att_quat.from_euler(radians(_current_angle.x * 0.01f), radians(_current_angle.y * 0.01f), radians(_current_angle.z * 0.01f)); + return true; } bool AP_Mount_SToRM32_serial::can_send(bool with_control) { @@ -163,7 +150,7 @@ bool AP_Mount_SToRM32_serial::can_send(bool with_control) { // send_target_angles -void AP_Mount_SToRM32_serial::send_target_angles(float pitch_deg, float roll_deg, float yaw_deg) +void AP_Mount_SToRM32_serial::send_target_angles(const MountTarget& angle_target_rad) { static cmd_set_angles_struct cmd_set_angles_data = { @@ -187,14 +174,10 @@ void AP_Mount_SToRM32_serial::send_target_angles(float pitch_deg, float roll_deg return; } - // reverse pitch and yaw control - pitch_deg = -pitch_deg; - yaw_deg = -yaw_deg; - - // send CMD_SETANGLE - cmd_set_angles_data.pitch = pitch_deg; - cmd_set_angles_data.roll = roll_deg; - cmd_set_angles_data.yaw = yaw_deg; + // send CMD_SETANGLE (Note: reversed pitch and yaw) + cmd_set_angles_data.pitch = -degrees(angle_target_rad.pitch); + cmd_set_angles_data.roll = degrees(angle_target_rad.roll); + cmd_set_angles_data.yaw = -degrees(get_bf_yaw_angle(angle_target_rad)); uint8_t* buf = (uint8_t*)&cmd_set_angles_data; @@ -288,12 +271,13 @@ void AP_Mount_SToRM32_serial::parse_reply() { break; } + // Parse angles (Note: reversed pitch and yaw) to match ardupilot coordinate system _current_angle.x = _buffer.data.imu1_roll; - _current_angle.y = _buffer.data.imu1_pitch; - _current_angle.z = _buffer.data.imu1_yaw; + _current_angle.y = -_buffer.data.imu1_pitch; + _current_angle.z = -_buffer.data.imu1_yaw; break; default: break; } } -#endif // HAL_MOUNT_ENABLED +#endif // HAL_MOUNT_STORM32SERIAL_ENABLED diff --git a/libraries/AP_Mount/AP_Mount_SToRM32_serial.h b/libraries/AP_Mount/AP_Mount_SToRM32_serial.h index 8d5b39c2f2c..5156f7d90ad 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32_serial.h +++ b/libraries/AP_Mount/AP_Mount_SToRM32_serial.h @@ -3,14 +3,19 @@ */ #pragma once +#include "AP_Mount_Backend.h" + +#ifndef HAL_MOUNT_STORM32SERIAL_ENABLED +#define HAL_MOUNT_STORM32SERIAL_ENABLED HAL_MOUNT_ENABLED +#endif + +#if HAL_MOUNT_STORM32SERIAL_ENABLED + #include #include - #include #include #include -#include "AP_Mount_Backend.h" -#if HAL_MOUNT_ENABLED #define AP_MOUNT_STORM32_SERIAL_RESEND_MS 1000 // resend angle targets to gimbal once per second @@ -19,7 +24,7 @@ class AP_Mount_SToRM32_serial : public AP_Mount_Backend public: // Constructor - AP_Mount_SToRM32_serial(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance); + AP_Mount_SToRM32_serial(AP_Mount &frontend, AP_Mount_Params ¶ms, uint8_t instance); // init - performs any required initialisation for this instance void init() override; @@ -27,19 +32,18 @@ class AP_Mount_SToRM32_serial : public AP_Mount_Backend // update mount position - should be called periodically void update() override; - // has_pan_control - returns true if this mount can control it's pan (required for multicopters) - bool has_pan_control() const override; + // has_pan_control - returns true if this mount can control its pan (required for multicopters) + bool has_pan_control() const override { return yaw_range_valid(); }; - // set_mode - sets mount's mode - void set_mode(enum MAV_MOUNT_MODE mode) override; +protected: - // send_mount_status - called to allow mounts to send their status to GCS using the MOUNT_STATUS message - void send_mount_status(mavlink_channel_t chan) override; + // get attitude as a quaternion. returns true on success + bool get_attitude_quaternion(Quaternion& att_quat) override; private: // send_target_angles - void send_target_angles(float pitch_deg, float roll_deg, float yaw_deg); + void send_target_angles(const MountTarget& angle_target_rad); // send read data request void get_angles(); @@ -132,6 +136,7 @@ class AP_Mount_SToRM32_serial : public AP_Mount_Backend AP_HAL::UARTDriver *_port; bool _initialised; // true once the driver has been initialised + MountTarget _angle_rad; // latest angle target uint32_t _last_send; // system time of last do_mount_control sent to gimbal uint8_t _reply_length; @@ -148,4 +153,4 @@ class AP_Mount_SToRM32_serial : public AP_Mount_Backend // keep the last _current_angle values Vector3l _current_angle; }; -#endif // HAL_MOUNT_ENABLED +#endif // HAL_MOUNT_STORM32SERIAL_ENABLED diff --git a/libraries/AP_Mount/AP_Mount_Servo.cpp b/libraries/AP_Mount/AP_Mount_Servo.cpp index a5314daa820..b022d722c15 100644 --- a/libraries/AP_Mount/AP_Mount_Servo.cpp +++ b/libraries/AP_Mount/AP_Mount_Servo.cpp @@ -1,5 +1,5 @@ #include "AP_Mount_Servo.h" -#if HAL_MOUNT_ENABLED +#if HAL_MOUNT_SERVO_ENABLED extern const AP_HAL::HAL& hal; @@ -18,84 +18,86 @@ void AP_Mount_Servo::init() _pan_idx = SRV_Channel::k_mount2_pan; _open_idx = SRV_Channel::k_mount2_open; } - - // check which servos have been assigned - check_servo_map(); } // update mount position - should be called periodically void AP_Mount_Servo::update() { - static bool mount_open = 0; // 0 is closed - - // check servo map every three seconds to allow users to modify parameters - uint32_t now = AP_HAL::millis(); - if (now - _last_check_servo_map_ms > 3000) { - check_servo_map(); - _last_check_servo_map_ms = now; - } - - switch(get_mode()) { + switch (get_mode()) { // move mount to a "retracted position" or to a position where a fourth servo can retract the entire mount into the fuselage - case MAV_MOUNT_MODE_RETRACT: - { - _angle_bf_output_deg = _state._retract_angles.get(); + case MAV_MOUNT_MODE_RETRACT: { + _angle_bf_output_deg = _params.retract_angles.get(); + + // initialise _angle_rad to smooth transition if user changes to RC_TARGETTING + _angle_rad.roll = radians(_angle_bf_output_deg.x); + _angle_rad.pitch = radians(_angle_bf_output_deg.y); + _angle_rad.yaw = radians(_angle_bf_output_deg.z); + _angle_rad.yaw_is_ef = false; break; } // move mount to a neutral position, typically pointing forward - case MAV_MOUNT_MODE_NEUTRAL: - { - _angle_bf_output_deg = _state._neutral_angles.get(); + case MAV_MOUNT_MODE_NEUTRAL: { + _angle_bf_output_deg = _params.neutral_angles.get(); + + // initialise _angle_rad to smooth transition if user changes to RC_TARGETTING + _angle_rad.roll = radians(_angle_bf_output_deg.x); + _angle_rad.pitch = radians(_angle_bf_output_deg.y); + _angle_rad.yaw = radians(_angle_bf_output_deg.z); + _angle_rad.yaw_is_ef = false; break; } // point to the angles given by a mavlink message - case MAV_MOUNT_MODE_MAVLINK_TARGETING: - { - // earth-frame angle targets (i.e. _angle_ef_target_rad) should have already been set by a MOUNT_CONTROL message from GCS - stabilize(); + case MAV_MOUNT_MODE_MAVLINK_TARGETING: { + switch (mavt_target.target_type) { + case MountTargetType::ANGLE: + _angle_rad = mavt_target.angle_rad; + break; + case MountTargetType::RATE: + update_angle_target_from_rate(mavt_target.rate_rads, _angle_rad); + break; + } + // update _angle_bf_output_deg based on angle target + update_angle_outputs(_angle_rad); break; } // RC radio manual angle control, but with stabilization from the AHRS - case MAV_MOUNT_MODE_RC_TARGETING: - { - // update targets using pilot's rc inputs - update_targets_from_rc(); - stabilize(); + case MAV_MOUNT_MODE_RC_TARGETING: { + // update targets using pilot's RC inputs + MountTarget rc_target {}; + if (get_rc_rate_target(rc_target)) { + update_angle_target_from_rate(rc_target, _angle_rad); + } else if (get_rc_angle_target(rc_target)) { + _angle_rad = rc_target; + } + // update _angle_bf_output_deg based on angle target + update_angle_outputs(_angle_rad); break; } - // point mount to a GPS point given by the mission planner - case MAV_MOUNT_MODE_GPS_POINT: - { - if (calc_angle_to_roi_target(_angle_ef_target_rad, _flags.tilt_control, _flags.pan_control, true)) { - stabilize(); + // point mount to a GPS location + case MAV_MOUNT_MODE_GPS_POINT: { + if (get_angle_target_to_roi(_angle_rad)) { + update_angle_outputs(_angle_rad); } break; } - case MAV_MOUNT_MODE_HOME_LOCATION: - // constantly update the home location: - if (!AP::ahrs().home_is_set()) { - break; - } - _state._roi_target = AP::ahrs().get_home(); - _state._roi_target_set = true; - if (calc_angle_to_roi_target(_angle_ef_target_rad, _flags.tilt_control, _flags.pan_control, true)) { - stabilize(); + case MAV_MOUNT_MODE_HOME_LOCATION: { + if (get_angle_target_to_home(_angle_rad)) { + update_angle_outputs(_angle_rad); } break; + } - case MAV_MOUNT_MODE_SYSID_TARGET: - if (calc_angle_to_sysid_target(_angle_ef_target_rad, - _flags.tilt_control, - _flags.pan_control, - true)) { - stabilize(); + case MAV_MOUNT_MODE_SYSID_TARGET: { + if (get_angle_target_to_sysid(_angle_rad)) { + update_angle_outputs(_angle_rad); } break; + } default: //do nothing @@ -103,122 +105,79 @@ void AP_Mount_Servo::update() } // move mount to a "retracted position" into the fuselage with a fourth servo - bool mount_open_new = (get_mode() == MAV_MOUNT_MODE_RETRACT) ? 0 : 1; - if (mount_open != mount_open_new) { - mount_open = mount_open_new; - move_servo(_open_idx, mount_open_new, 0, 1); - } + const bool mount_open = (get_mode() == MAV_MOUNT_MODE_RETRACT) ? 0 : 1; + move_servo(_open_idx, mount_open, 0, 1); // write the results to the servos - move_servo(_roll_idx, _angle_bf_output_deg.x*10, _state._roll_angle_min*0.1f, _state._roll_angle_max*0.1f); - move_servo(_tilt_idx, _angle_bf_output_deg.y*10, _state._tilt_angle_min*0.1f, _state._tilt_angle_max*0.1f); - move_servo(_pan_idx, _angle_bf_output_deg.z*10, _state._pan_angle_min*0.1f, _state._pan_angle_max*0.1f); + move_servo(_roll_idx, _angle_bf_output_deg.x*10, _params.roll_angle_min*10, _params.roll_angle_max*10); + move_servo(_tilt_idx, _angle_bf_output_deg.y*10, _params.pitch_angle_min*10, _params.pitch_angle_max*10); + move_servo(_pan_idx, _angle_bf_output_deg.z*10, _params.yaw_angle_min*10, _params.yaw_angle_max*10); } -// set_mode - sets mount's mode -void AP_Mount_Servo::set_mode(enum MAV_MOUNT_MODE mode) +// returns true if this mount can control its pan (required for multicopters) +bool AP_Mount_Servo::has_pan_control() const { - // record the mode change and return success - _state._mode = mode; + return SRV_Channels::function_assigned(_pan_idx) && yaw_range_valid(); } -// private methods - -// check_servo_map - detects which axis we control using the functions assigned to the servos in the RC_Channel_aux -// should be called periodically (i.e. 1hz or less) -void AP_Mount_Servo::check_servo_map() +// get attitude as a quaternion. returns true on success +bool AP_Mount_Servo::get_attitude_quaternion(Quaternion& att_quat) { - _flags.roll_control = SRV_Channels::function_assigned(_roll_idx); - _flags.tilt_control = SRV_Channels::function_assigned(_tilt_idx); - _flags.pan_control = SRV_Channels::function_assigned(_pan_idx); + att_quat.from_euler(radians(_angle_bf_output_deg.x), radians(_angle_bf_output_deg.y), radians(_angle_bf_output_deg.z)); + return true; } -// send_mount_status - called to allow mounts to send their status to GCS using the MOUNT_STATUS message -void AP_Mount_Servo::send_mount_status(mavlink_channel_t chan) -{ - mavlink_msg_mount_status_send(chan, 0, 0, _angle_bf_output_deg.y*100, _angle_bf_output_deg.x*100, _angle_bf_output_deg.z*100, _state._mode); -} +// private methods -// stabilize - stabilizes the mount relative to the Earth's frame -// input: _angle_ef_target_rad (earth frame targets in radians) -// output: _angle_bf_output_deg (body frame angles in degrees) -void AP_Mount_Servo::stabilize() +// update body-frame angle outputs from earth-frame angle targets +void AP_Mount_Servo::update_angle_outputs(const MountTarget& angle_rad) { - AP_AHRS &ahrs = AP::ahrs(); - // only do the full 3D frame transform if we are doing pan control - if (_state._stab_pan) { - Matrix3f m; ///< holds 3 x 3 matrix, var is used as temp in calcs - Matrix3f cam; ///< Rotation matrix earth to camera. Desired camera from input. - Matrix3f gimbal_target; ///< Rotation matrix from plane to camera. Then Euler angles to the servos. - m = ahrs.get_rotation_body_to_ned(); - m.transpose(); - cam.from_euler(_angle_ef_target_rad.x, _angle_ef_target_rad.y, _angle_ef_target_rad.z); - gimbal_target = m * cam; - gimbal_target.to_euler(&_angle_bf_output_deg.x, &_angle_bf_output_deg.y, &_angle_bf_output_deg.z); - _angle_bf_output_deg.x = _state._stab_roll ? degrees(_angle_bf_output_deg.x) : degrees(_angle_ef_target_rad.x); - _angle_bf_output_deg.y = _state._stab_tilt ? degrees(_angle_bf_output_deg.y) : degrees(_angle_ef_target_rad.y); - _angle_bf_output_deg.z = degrees(_angle_bf_output_deg.z); - } else { - // otherwise base mount roll and tilt on the ahrs - // roll/tilt attitude, plus any requested angle - _angle_bf_output_deg.x = degrees(_angle_ef_target_rad.x); - _angle_bf_output_deg.y = degrees(_angle_ef_target_rad.y); - _angle_bf_output_deg.z = degrees(_angle_ef_target_rad.z); - if (_state._stab_roll) { - _angle_bf_output_deg.x -= degrees(ahrs.roll); - } - if (_state._stab_tilt) { - _angle_bf_output_deg.y -= degrees(ahrs.pitch); - } + const AP_AHRS &ahrs = AP::ahrs(); - // lead filter - const Vector3f &gyro = ahrs.get_gyro(); + // get target yaw in body-frame with limits applied + const float yaw_bf_rad = constrain_float(get_bf_yaw_angle(angle_rad), radians(_params.yaw_angle_min), radians(_params.yaw_angle_max)); - if (_state._stab_roll && !is_zero(_state._roll_stb_lead) && fabsf(ahrs.pitch) < M_PI/3.0f) { - // Compute rate of change of euler roll angle - float roll_rate = gyro.x + (ahrs.sin_pitch() / ahrs.cos_pitch()) * (gyro.y * ahrs.sin_roll() + gyro.z * ahrs.cos_roll()); - _angle_bf_output_deg.x -= degrees(roll_rate) * _state._roll_stb_lead; - } + // default output to target earth-frame roll and pitch angles, body-frame yaw + _angle_bf_output_deg.x = degrees(angle_rad.roll); + _angle_bf_output_deg.y = degrees(angle_rad.pitch); + _angle_bf_output_deg.z = degrees(yaw_bf_rad); - if (_state._stab_tilt && !is_zero(_state._pitch_stb_lead)) { - // Compute rate of change of euler pitch angle - float pitch_rate = ahrs.cos_pitch() * gyro.y - ahrs.sin_roll() * gyro.z; - _angle_bf_output_deg.y -= degrees(pitch_rate) * _state._pitch_stb_lead; - } + // this is sufficient for self-stabilising brushless gimbals + if (!requires_stabilization) { + return; } -} -// closest_limit - returns closest angle to 'angle' taking into account limits. all angles are in degrees * 10 -int16_t AP_Mount_Servo::closest_limit(int16_t angle, int16_t angle_min, int16_t angle_max) -{ - // Make sure the angle lies in the interval [-180 .. 180[ degrees - while (angle < -1800) angle += 3600; - while (angle >= 1800) angle -= 3600; - - // Make sure the angle limits lie in the interval [-180 .. 180[ degrees - while (angle_min < -1800) angle_min += 3600; - while (angle_min >= 1800) angle_min -= 3600; - while (angle_max < -1800) angle_max += 3600; - while (angle_max >= 1800) angle_max -= 3600; - - // If the angle is outside servo limits, saturate the angle to the closest limit - // On a circle the closest angular position must be carefully calculated to account for wrap-around - if ((angle < angle_min) && (angle > angle_max)) { - // angle error if min limit is used - int16_t err_min = angle_min - angle + (angleangle_max ? 0 : 3600); // add 360 degrees if on the "wrong side" - angle = err_min #include #include #include #include -#include "AP_Mount_Backend.h" -#if HAL_MOUNT_ENABLED class AP_Mount_Servo : public AP_Mount_Backend { public: // Constructor - AP_Mount_Servo(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance): - AP_Mount_Backend(frontend, state, instance), + AP_Mount_Servo(AP_Mount &frontend, AP_Mount_Params ¶ms, bool requires_stab, uint8_t instance): + AP_Mount_Backend(frontend, params, instance), + requires_stabilization(requires_stab), _roll_idx(SRV_Channel::k_none), _tilt_idx(SRV_Channel::k_none), _pan_idx(SRV_Channel::k_none), @@ -30,45 +37,32 @@ class AP_Mount_Servo : public AP_Mount_Backend // update mount position - should be called periodically void update() override; - // has_pan_control - returns true if this mount can control it's pan (required for multicopters) - bool has_pan_control() const override { return _flags.pan_control; } + // returns true if this mount can control its pan (required for multicopters) + bool has_pan_control() const override; - // set_mode - sets mount's mode - void set_mode(enum MAV_MOUNT_MODE mode) override; +protected: - // send_mount_status - called to allow mounts to send their status to GCS using the MOUNT_STATUS message - void send_mount_status(mavlink_channel_t chan) override; + // get attitude as a quaternion. returns true on success + bool get_attitude_quaternion(Quaternion& att_quat) override; private: - // flags structure - struct { - bool roll_control :1; // true if mount has roll control - bool tilt_control :1; // true if mount has tilt control - bool pan_control :1; // true if mount has pan control - } _flags; + // update body-frame angle outputs from earth-frame targets + void update_angle_outputs(const MountTarget& angle_rad); - // check_servo_map - detects which axis we control (i.e. _flags) using the functions assigned to the servos in the SRV_Channel - // should be called periodically (i.e. 1hz or less) - void check_servo_map(); - - // stabilize - stabilizes the mount relative to the Earth's frame - void stabilize(); - - // closest_limit - returns closest angle to 'angle' taking into account limits. all angles are in degrees * 10 - int16_t closest_limit(int16_t angle, int16_t angle_min, int16_t angle_max); - - /// move_servo - moves servo with the given id to the specified angle. all angles are in degrees * 10 + /// moves servo with the given function id to the specified angle. all angles are in body-frame and degrees * 10 void move_servo(uint8_t rc, int16_t angle, int16_t angle_min, int16_t angle_max); + /// Servo gimbals require stabilization, BrushlessPWM gimbals self-stabilize + const bool requires_stabilization; + // SRV_Channel - different id numbers are used depending upon the instance number SRV_Channel::Aux_servo_function_t _roll_idx; // SRV_Channel mount roll function index SRV_Channel::Aux_servo_function_t _tilt_idx; // SRV_Channel mount tilt function index SRV_Channel::Aux_servo_function_t _pan_idx; // SRV_Channel mount pan function index SRV_Channel::Aux_servo_function_t _open_idx; // SRV_Channel mount open function index + MountTarget _angle_rad; // angle target Vector3f _angle_bf_output_deg; // final body frame output angle in degrees - - uint32_t _last_check_servo_map_ms; // system time of latest call to check_servo_map function }; -#endif // HAL_MOUNT_ENABLED +#endif // HAL_MOUNT_SERVO_ENABLED diff --git a/libraries/AP_Mount/AP_Mount_Siyi.cpp b/libraries/AP_Mount/AP_Mount_Siyi.cpp new file mode 100644 index 00000000000..1fa648a4e71 --- /dev/null +++ b/libraries/AP_Mount/AP_Mount_Siyi.cpp @@ -0,0 +1,634 @@ +#include "AP_Mount_Siyi.h" + +#if HAL_MOUNT_SIYI_ENABLED +#include +#include +#include +#include +#include + +extern const AP_HAL::HAL& hal; + +#define AP_MOUNT_SIYI_HEADER1 0x55 // first header byte +#define AP_MOUNT_SIYI_HEADER2 0x66 // second header byte +#define AP_MOUNT_SIYI_PACKETLEN_MIN 10 // minimum number of bytes in a packet. this is a packet with no data bytes +#define AP_MOUNT_SIYI_DATALEN_MAX (AP_MOUNT_SIYI_PACKETLEN_MAX-AP_MOUNT_SIYI_PACKETLEN_MIN) // max bytes for data portion of packet +#define AP_MOUNT_SIYI_SERIAL_RESEND_MS 1000 // resend angle targets to gimbal once per second +#define AP_MOUNT_SIYI_MSG_BUF_DATA_START 8 // data starts at this byte in _msg_buf +#define AP_MOUNT_SIYI_RATE_MAX_RADS radians(90) // maximum physical rotation rate of gimbal in radans/sec +#define AP_MOUNT_SIYI_PITCH_P 1.50 // pitch controller P gain (converts pitch angle error to target rate) +#define AP_MOUNT_SIYI_YAW_P 1.50 // yaw controller P gain (converts yaw angle error to target rate) +#define AP_MOUNT_SIYI_LOCK_RESEND_COUNT 5 // lock value is resent to gimbal every 5 iterations + +#define AP_MOUNT_SIYI_DEBUG 0 +#define debug(fmt, args ...) do { if (AP_MOUNT_SIYI_DEBUG) { GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Siyi: " fmt, ## args); } } while (0) + +// init - performs any required initialisation for this instance +void AP_Mount_Siyi::init() +{ + const AP_SerialManager& serial_manager = AP::serialmanager(); + + _uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_SToRM32, 0); + if (_uart != nullptr) { + _initialised = true; + set_mode((enum MAV_MOUNT_MODE)_params.default_mode.get()); + } + +} + +// update mount position - should be called periodically +void AP_Mount_Siyi::update() +{ + // exit immediately if not initialised + if (!_initialised) { + return; + } + + // reading incoming packets from gimbal + read_incoming_packets(); + + // request firmware version during startup at 1hz + // during regular operation request configuration at 1hz + uint32_t now_ms = AP_HAL::millis(); + if ((now_ms - _last_send_ms) >= 1000) { + _last_send_ms = now_ms; + if (!_got_firmware_version) { + request_firmware_version(); + return; + } else { + request_configuration(); + } + } + + // request attitude at regular intervals + if ((now_ms - _last_req_current_angle_rad_ms) >= 50) { + request_gimbal_attitude(); + _last_req_current_angle_rad_ms = now_ms; + } + + // update based on mount mode + switch (get_mode()) { + // move mount to a "retracted" position. To-Do: remove support and replace with a relaxed mode? + case MAV_MOUNT_MODE_RETRACT: { + const Vector3f &angle_bf_target = _params.retract_angles.get(); + send_target_angles(ToRad(angle_bf_target.y), ToRad(angle_bf_target.z), false); + break; + } + + // move mount to a neutral position, typically pointing forward + case MAV_MOUNT_MODE_NEUTRAL: { + const Vector3f &angle_bf_target = _params.neutral_angles.get(); + send_target_angles(ToRad(angle_bf_target.y), ToRad(angle_bf_target.z), false); + break; + } + + // point to the angles given by a mavlink message + case MAV_MOUNT_MODE_MAVLINK_TARGETING: + switch (mavt_target.target_type) { + case MountTargetType::ANGLE: + send_target_angles(mavt_target.angle_rad.pitch, mavt_target.angle_rad.yaw, mavt_target.angle_rad.yaw_is_ef); + break; + case MountTargetType::RATE: + send_target_rates(mavt_target.rate_rads.pitch, mavt_target.rate_rads.yaw, mavt_target.rate_rads.yaw_is_ef); + break; + } + break; + + // RC radio manual angle control, but with stabilization from the AHRS + case MAV_MOUNT_MODE_RC_TARGETING: { + // update targets using pilot's rc inputs + MountTarget rc_target {}; + if (get_rc_rate_target(rc_target)) { + send_target_rates(rc_target.pitch, rc_target.yaw, rc_target.yaw_is_ef); + } else if (get_rc_angle_target(rc_target)) { + send_target_angles(rc_target.pitch, rc_target.yaw, rc_target.yaw_is_ef); + } + break; + } + + // point mount to a GPS point given by the mission planner + case MAV_MOUNT_MODE_GPS_POINT: { + MountTarget angle_target_rad {}; + if (get_angle_target_to_roi(angle_target_rad)) { + send_target_angles(angle_target_rad.pitch, angle_target_rad.yaw, angle_target_rad.yaw_is_ef); + } + break; + } + + case MAV_MOUNT_MODE_HOME_LOCATION: { + MountTarget angle_target_rad {}; + if (get_angle_target_to_home(angle_target_rad)) { + send_target_angles(angle_target_rad.pitch, angle_target_rad.yaw, angle_target_rad.yaw_is_ef); + } + break; + } + + case MAV_MOUNT_MODE_SYSID_TARGET:{ + MountTarget angle_target_rad {}; + if (get_angle_target_to_sysid(angle_target_rad)) { + send_target_angles(angle_target_rad.pitch, angle_target_rad.yaw, angle_target_rad.yaw_is_ef); + } + break; + } + + default: + // we do not know this mode so raise internal error + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + break; + } +} + +// return true if healthy +bool AP_Mount_Siyi::healthy() const +{ + // unhealthy until gimbal has been found and replied with firmware version info + if (!_initialised || !_got_firmware_version) { + return false; + } + + // unhealthy if attitude information NOT received recently + if (AP_HAL::millis() - _last_current_angle_rad_ms > 1000) { + return false; + } + + // if we get this far return healthy + return true; +} + +// get attitude as a quaternion. returns true on success +bool AP_Mount_Siyi::get_attitude_quaternion(Quaternion& att_quat) +{ + att_quat.from_euler(_current_angle_rad.x, _current_angle_rad.y, _current_angle_rad.z); + return true; +} + +// reading incoming packets from gimbal and confirm they are of the correct format +// results are held in the _parsed_msg structure +void AP_Mount_Siyi::read_incoming_packets() +{ + // check for bytes on the serial port + int16_t nbytes = MIN(_uart->available(), 1024U); + if (nbytes <= 0 ) { + return; + } + + // flag to allow cases below to reset parser state + bool reset_parser = false; + + // process bytes received + for (int16_t i = 0; i < nbytes; i++) { + const int16_t b = _uart->read(); + + // sanity check byte + if ((b < 0) || (b > 0xFF)) { + continue; + } + + _msg_buff[_msg_buff_len++] = b; + + // protect against overly long messages + if (_msg_buff_len >= AP_MOUNT_SIYI_PACKETLEN_MAX) { + reset_parser = true; + } + + // process byte depending upon current state + switch (_parsed_msg.state) { + + case ParseState::WAITING_FOR_HEADER_LOW: + if (b == AP_MOUNT_SIYI_HEADER1) { + _parsed_msg.state = ParseState::WAITING_FOR_HEADER_HIGH; + } else { + reset_parser = true; + } + break; + + case ParseState::WAITING_FOR_HEADER_HIGH: + if (b == AP_MOUNT_SIYI_HEADER2) { + _parsed_msg.state = ParseState::WAITING_FOR_CTRL; + } else { + reset_parser = true; + } + break; + + case ParseState::WAITING_FOR_CTRL: + _parsed_msg.state = ParseState::WAITING_FOR_DATALEN_LOW; + break; + + case ParseState::WAITING_FOR_DATALEN_LOW: + _parsed_msg.data_len = b; + _parsed_msg.state = ParseState::WAITING_FOR_DATALEN_HIGH; + break; + + case ParseState::WAITING_FOR_DATALEN_HIGH: + _parsed_msg.data_len |= ((uint16_t)b << 8); + // sanity check data length + if (_parsed_msg.data_len <= AP_MOUNT_SIYI_DATALEN_MAX) { + _parsed_msg.state = ParseState::WAITING_FOR_SEQ_LOW; + } else { + reset_parser = true; + debug("data len too large:%u (>%u)", (unsigned)_parsed_msg.data_len, (unsigned)AP_MOUNT_SIYI_DATALEN_MAX); + } + break; + + case ParseState::WAITING_FOR_SEQ_LOW: + _parsed_msg.state = ParseState::WAITING_FOR_SEQ_HIGH; + break; + + case ParseState::WAITING_FOR_SEQ_HIGH: + _parsed_msg.state = ParseState::WAITING_FOR_CMDID; + break; + + case ParseState::WAITING_FOR_CMDID: + _parsed_msg.command_id = b; + _parsed_msg.data_bytes_received = 0; + if (_parsed_msg.data_len > 0) { + _parsed_msg.state = ParseState::WAITING_FOR_DATA; + } else { + _parsed_msg.state = ParseState::WAITING_FOR_CRC_LOW; + } + break; + + case ParseState::WAITING_FOR_DATA: + _parsed_msg.data_bytes_received++; + if (_parsed_msg.data_bytes_received >= _parsed_msg.data_len) { + _parsed_msg.state = ParseState::WAITING_FOR_CRC_LOW; + } + break; + + case ParseState::WAITING_FOR_CRC_LOW: + _parsed_msg.crc16 = b; + _parsed_msg.state = ParseState::WAITING_FOR_CRC_HIGH; + break; + + case ParseState::WAITING_FOR_CRC_HIGH: + _parsed_msg.crc16 |= ((uint16_t)b << 8); + + // check crc + const uint16_t expected_crc = crc16_ccitt(_msg_buff, _msg_buff_len-2, 0); + if (expected_crc == _parsed_msg.crc16) { + // successfully received a message, do something with it + process_packet(); + } else { + debug("crc expected:%x got:%x", (unsigned)expected_crc, (unsigned)_parsed_msg.crc16); + } + reset_parser = true; + break; + } + + // handle reset of parser + if (reset_parser) { + _parsed_msg.state = ParseState::WAITING_FOR_HEADER_LOW; + _msg_buff_len = 0; + } + } +} + +// process successfully decoded packets held in the _parsed_msg structure +void AP_Mount_Siyi::process_packet() +{ + // flag to warn of unexpected data buffer length + bool unexpected_len = false; + + // process packet depending upon command id + switch ((SiyiCommandId)_parsed_msg.command_id) { + + case SiyiCommandId::ACQUIRE_FIRMWARE_VERSION: { + if (_parsed_msg.data_bytes_received != 12 && // ZR10 firmware version reply is 12bytes + _parsed_msg.data_bytes_received != 8) { // A8 firmware version reply is 8 bytes + unexpected_len = true; + break; + } + _got_firmware_version = true; + + // display camera firmware version + debug("Mount: SiyiCam fw:%u.%u.%u", + (unsigned)_msg_buff[_msg_buff_data_start+2], // firmware major version + (unsigned)_msg_buff[_msg_buff_data_start+1], // firmware minor version + (unsigned)_msg_buff[_msg_buff_data_start+0]); // firmware revision + + // display gimbal info to user + gcs().send_text(MAV_SEVERITY_INFO, "Mount: Siyi fw:%u.%u.%u", + (unsigned)_msg_buff[_msg_buff_data_start+6], // firmware major version + (unsigned)_msg_buff[_msg_buff_data_start+5], // firmware minor version + (unsigned)_msg_buff[_msg_buff_data_start+4]); // firmware revision + + // display zoom firmware version +#if AP_MOUNT_SIYI_DEBUG + if (_parsed_msg.data_bytes_received >= 12) { + debug("Mount: SiyiZoom fw:%u.%u.%u", + (unsigned)_msg_buff[_msg_buff_data_start+10], // firmware major version + (unsigned)_msg_buff[_msg_buff_data_start+9], // firmware minor version + (unsigned)_msg_buff[_msg_buff_data_start+8]); // firmware revision + } +#endif + break; + } + + case SiyiCommandId::HARDWARE_ID: + // unsupported + break; + + case SiyiCommandId::AUTO_FOCUS: +#if AP_MOUNT_SIYI_DEBUG + if (_parsed_msg.data_bytes_received != 1) { + unexpected_len = true; + break; + } + debug("AutoFocus:%u", (unsigned)_msg_buff[_msg_buff_data_start]); +#endif + break; + + case SiyiCommandId::MANUAL_ZOOM_AND_AUTO_FOCUS: { + if (_parsed_msg.data_bytes_received != 2) { + unexpected_len = true; + break; + } + const float zoom_mult = UINT16_VALUE(_msg_buff[_msg_buff_data_start+1], _msg_buff[_msg_buff_data_start]) * 0.1; + debug("ZoomMult:%4.1f", (double)zoom_mult); + break; + } + + case SiyiCommandId::MANUAL_FOCUS: +#if AP_MOUNT_SIYI_DEBUG + if (_parsed_msg.data_bytes_received != 1) { + unexpected_len = true; + break; + } + debug("ManualFocus:%u", (unsigned)_msg_buff[_msg_buff_data_start]); +#endif + break; + + case SiyiCommandId::GIMBAL_ROTATION: +#if AP_MOUNT_SIYI_DEBUG + if (_parsed_msg.data_bytes_received != 1) { + unexpected_len = true; + break; + } + debug("GimbRot:%u", (unsigned)_msg_buff[_msg_buff_data_start]); +#endif + break; + + case SiyiCommandId::CENTER: +#if AP_MOUNT_SIYI_DEBUG + if (_parsed_msg.data_bytes_received != 1) { + unexpected_len = true; + break; + } + debug("Center:%u", (unsigned)_msg_buff[_msg_buff_data_start]); +#endif + break; + + case SiyiCommandId::ACQUIRE_GIMBAL_CONFIG_INFO: { + if (_parsed_msg.data_bytes_received != 5 && // ZR10 firmware version reply is 5 bytes + _parsed_msg.data_bytes_received != 7) { // A8 firmware version reply is 7 bytes + unexpected_len = true; + break; + } + // update recording state and warn user of mismatch + const bool recording = _msg_buff[_msg_buff_data_start+3] > 0; + if (recording != _last_record_video) { + gcs().send_text(MAV_SEVERITY_INFO, "Siyi: recording %s", recording ? "ON" : "OFF"); + } + _last_record_video = recording; + debug("GimConf hdr:%u rec:%u foll:%u", (unsigned)_msg_buff[_msg_buff_data_start+1], + (unsigned)_msg_buff[_msg_buff_data_start+3], + (unsigned)_msg_buff[_msg_buff_data_start+4]); + break; + } + + case SiyiCommandId::FUNCTION_FEEDBACK_INFO: { + if (_parsed_msg.data_bytes_received != 1) { + unexpected_len = true; + break; + } + const uint8_t func_feedback_info = _msg_buff[_msg_buff_data_start]; + const char* err_prefix = "Mount: Siyi"; + switch ((FunctionFeedbackInfo)func_feedback_info) { + case FunctionFeedbackInfo::SUCCESS: + debug("FnFeedB success"); + break; + case FunctionFeedbackInfo::FAILED_TO_TAKE_PHOTO: + gcs().send_text(MAV_SEVERITY_ERROR, "%s failed to take picture", err_prefix); + break; + case FunctionFeedbackInfo::HDR_ON: + debug("HDR on"); + break; + case FunctionFeedbackInfo::HDR_OFF: + debug("HDR off"); + break; + case FunctionFeedbackInfo::FAILED_TO_RECORD_VIDEO: + gcs().send_text(MAV_SEVERITY_ERROR, "%s failed to record video", err_prefix); + break; + default: + debug("FnFeedB unexpected val:%u", (unsigned)func_feedback_info); + } + break; + } + + case SiyiCommandId::PHOTO: + // no ack should ever be sent by the gimbal + break; + + case SiyiCommandId::ACQUIRE_GIMBAL_ATTITUDE: { + if (_parsed_msg.data_bytes_received != 12) { + unexpected_len = true; + break; + } + _last_current_angle_rad_ms = AP_HAL::millis(); + _current_angle_rad.z = -radians((int16_t)UINT16_VALUE(_msg_buff[_msg_buff_data_start+1], _msg_buff[_msg_buff_data_start]) * 0.1); // yaw angle + _current_angle_rad.y = radians((int16_t)UINT16_VALUE(_msg_buff[_msg_buff_data_start+3], _msg_buff[_msg_buff_data_start+2]) * 0.1); // pitch angle + _current_angle_rad.x = radians((int16_t)UINT16_VALUE(_msg_buff[_msg_buff_data_start+5], _msg_buff[_msg_buff_data_start+4]) * 0.1); // roll angle + //const float yaw_rate_degs = -(int16_t)UINT16_VALUE(_msg_buff[_msg_buff_data_start+7], _msg_buff[_msg_buff_data_start+6]) * 0.1; // yaw rate + //const float pitch_rate_deg = (int16_t)UINT16_VALUE(_msg_buff[_msg_buff_data_start+9], _msg_buff[_msg_buff_data_start+8]) * 0.1; // pitch rate + //const float roll_rate_deg = (int16_t)UINT16_VALUE(_msg_buff[_msg_buff_data_start+11], _msg_buff[_msg_buff_data_start+10]) * 0.1; // roll rate + break; + } + + default: + debug("Unhandled CmdId:%u", (unsigned)_parsed_msg.command_id); + break; + } + + // handle unexpected data buffer lenth + if (unexpected_len) { + debug("CmdId:%u unexpected len:%u", (unsigned)_parsed_msg.command_id, (unsigned)_parsed_msg.data_bytes_received); + } +} + +// methods to send commands to gimbal +// returns true on success, false if outgoing serial buffer is full +bool AP_Mount_Siyi::send_packet(SiyiCommandId cmd_id, const uint8_t* databuff, uint8_t databuff_len) +{ + // calculate and sanity check packet size + const uint16_t packet_size = AP_MOUNT_SIYI_PACKETLEN_MIN + databuff_len; + if (packet_size > AP_MOUNT_SIYI_PACKETLEN_MAX) { + debug("send_packet data buff too large"); + return false; + } + + // check for sufficient space in outgoing buffer + if (_uart->txspace() < packet_size) { + return false; + } + + // buffer for holding outgoing packet + uint8_t send_buff[packet_size]; + uint8_t send_buff_ofs = 0; + + // packet header + send_buff[send_buff_ofs++] = AP_MOUNT_SIYI_HEADER1; + send_buff[send_buff_ofs++] = AP_MOUNT_SIYI_HEADER2; + + // CTRL. Always request ACK + send_buff[send_buff_ofs++] = 1; + + // Data_len. protocol supports uint16_t but messages are never longer than 22 bytes + send_buff[send_buff_ofs++] = databuff_len; + send_buff[send_buff_ofs++] = 0; + + // SEQ (sequence) + send_buff[send_buff_ofs++] = LOWBYTE(_last_seq); + send_buff[send_buff_ofs++] = HIGHBYTE(_last_seq++); + + // CMD_ID + send_buff[send_buff_ofs++] = (uint8_t)cmd_id; + + // DATA + if (databuff_len != 0) { + memcpy(&send_buff[send_buff_ofs], databuff, databuff_len); + send_buff_ofs += databuff_len; + } + + // CRC16 + const uint16_t crc = crc16_ccitt(send_buff, send_buff_ofs, 0); + send_buff[send_buff_ofs++] = LOWBYTE(crc); + send_buff[send_buff_ofs++] = HIGHBYTE(crc); + + // send packet + _uart->write(send_buff, send_buff_ofs); + + return true; +} + +// send a packet with a single data byte to gimbal +// returns true on success, false if outgoing serial buffer is full +bool AP_Mount_Siyi::send_1byte_packet(SiyiCommandId cmd_id, uint8_t data_byte) +{ + return send_packet(cmd_id, &data_byte, 1); +} + +// rotate gimbal. pitch_rate and yaw_rate are scalars in the range -100 ~ +100 +// yaw_is_ef should be true if gimbal should maintain an earth-frame target (aka lock) +void AP_Mount_Siyi::rotate_gimbal(int8_t pitch_scalar, int8_t yaw_scalar, bool yaw_is_ef) +{ + // send lock/follow value if it has changed + if ((yaw_is_ef != _last_lock) || (_lock_send_counter >= AP_MOUNT_SIYI_LOCK_RESEND_COUNT)) { + set_lock(yaw_is_ef); + _lock_send_counter = 0; + _last_lock = yaw_is_ef; + } else { + _lock_send_counter++; + } + + const uint8_t yaw_and_pitch_rates[] {(uint8_t)yaw_scalar, (uint8_t)pitch_scalar}; + send_packet(SiyiCommandId::GIMBAL_ROTATION, yaw_and_pitch_rates, ARRAY_SIZE(yaw_and_pitch_rates)); +} + +// center gimbal +void AP_Mount_Siyi::center_gimbal() +{ + send_1byte_packet(SiyiCommandId::CENTER, 1); +} + +// set gimbal's lock vs follow mode +// lock should be true if gimbal should maintain an earth-frame target +// lock is false to follow / maintain a body-frame target +void AP_Mount_Siyi::set_lock(bool lock) +{ + send_1byte_packet(SiyiCommandId::PHOTO, lock ? (uint8_t)PhotoFunction::LOCK_MODE : (uint8_t)PhotoFunction::FOLLOW_MODE); +} + +// send target pitch and yaw rates to gimbal +// yaw_is_ef should be true if yaw_rads target is an earth frame rate, false if body_frame +void AP_Mount_Siyi::send_target_rates(float pitch_rads, float yaw_rads, bool yaw_is_ef) +{ + const float pitch_rate_scalar = constrain_float(100.0 * pitch_rads / AP_MOUNT_SIYI_RATE_MAX_RADS, -100, 100); + const float yaw_rate_scalar = constrain_float(100.0 * yaw_rads / AP_MOUNT_SIYI_RATE_MAX_RADS, -100, 100); + rotate_gimbal(pitch_rate_scalar, yaw_rate_scalar, yaw_is_ef); +} + +// send target pitch and yaw angles to gimbal +// yaw_is_ef should be true if yaw_rad target is an earth frame angle, false if body_frame +void AP_Mount_Siyi::send_target_angles(float pitch_rad, float yaw_rad, bool yaw_is_ef) +{ + // stop gimbal if no recent actual angles + uint32_t now_ms = AP_HAL::millis(); + if (now_ms - _last_current_angle_rad_ms >= 200) { + rotate_gimbal(0, 0, false); + return; + } + + // use simple P controller to convert pitch angle error (in radians) to a target rate scalar (-100 to +100) + const float pitch_err_rad = (pitch_rad - _current_angle_rad.y); + const float pitch_rate_scalar = constrain_float(100.0 * pitch_err_rad * AP_MOUNT_SIYI_PITCH_P / AP_MOUNT_SIYI_RATE_MAX_RADS, -100, 100); + + // convert yaw angle to body-frame the use simple P controller to convert yaw angle error to a target rate scalar (-100 to +100) + const float yaw_bf_rad = yaw_is_ef ? wrap_PI(yaw_rad - AP::ahrs().yaw) : yaw_rad; + const float yaw_err_rad = (yaw_bf_rad - _current_angle_rad.z); + const float yaw_rate_scalar = constrain_float(100.0 * yaw_err_rad * AP_MOUNT_SIYI_YAW_P / AP_MOUNT_SIYI_RATE_MAX_RADS, -100, 100); + + // rotate gimbal. pitch_rate and yaw_rate are scalars in the range -100 ~ +100 + rotate_gimbal(pitch_rate_scalar, yaw_rate_scalar, yaw_is_ef); +} + +// take a picture. returns true on success +bool AP_Mount_Siyi::take_picture() +{ + return send_1byte_packet(SiyiCommandId::PHOTO, (uint8_t)PhotoFunction::TAKE_PICTURE); +} + +// start or stop video recording. returns true on success +// set start_recording = true to start record, false to stop recording +bool AP_Mount_Siyi::record_video(bool start_recording) +{ + // exit immediately if not initialised to reduce mismatch + // between internal and actual state of recording + if (!_initialised) { + return false; + } + + // check desired recording state has changed + bool ret = true; + if (_last_record_video != start_recording) { + // request recording start or stop (sadly the same message is used) + const uint8_t func_type = (uint8_t)PhotoFunction::RECORD_VIDEO_TOGGLE; + ret = send_packet(SiyiCommandId::PHOTO, &func_type, 1); + } + + // request recording state update from gimbal + request_configuration(); + + return ret; +} + +// set camera zoom step. returns true on success +// zoom out = -1, hold = 0, zoom in = 1 +bool AP_Mount_Siyi::set_zoom_step(int8_t zoom_step) +{ + return send_1byte_packet(SiyiCommandId::MANUAL_ZOOM_AND_AUTO_FOCUS, (uint8_t)zoom_step); +} + +// set focus in, out or hold. returns true on success +// focus in = -1, focus hold = 0, focus out = 1 +bool AP_Mount_Siyi::set_manual_focus_step(int8_t focus_step) +{ + return send_1byte_packet(SiyiCommandId::MANUAL_FOCUS, (uint8_t)focus_step); +} + +// auto focus. returns true on success +bool AP_Mount_Siyi::set_auto_focus() +{ + return send_1byte_packet(SiyiCommandId::AUTO_FOCUS, 1); +} + +#endif // HAL_MOUNT_SIYI_ENABLED diff --git a/libraries/AP_Mount/AP_Mount_Siyi.h b/libraries/AP_Mount/AP_Mount_Siyi.h new file mode 100644 index 00000000000..1677a0bc1b0 --- /dev/null +++ b/libraries/AP_Mount/AP_Mount_Siyi.h @@ -0,0 +1,209 @@ +/* + Siyi gimbal driver using custom serial protocol + + Packet format (courtesy of Siyi's SDK document) + + ------------------------------------------------------------------------------------------- + Field Index Bytes Description + ------------------------------------------------------------------------------------------- + STX 0 2 0x5566: starting mark + CTRL 2 1 bit 0: need_ack. set if the current data packet needs ack + bit 1: ack_pack. set if the current data packate IS an ack + bit 2-7: reserved + Data_len 3 2 Data field byte length. Low byte in the front + SEQ 5 2 Frame sequence (0 ~ 65535). Low byte in the front. May be used to detect packet loss + CMD_ID 7 1 Command ID + DATA 8 Data_len Data + CRC16 2 CRC16 check the complete data package. Low byte in the front + */ + +#pragma once + +#include "AP_Mount_Backend.h" + +#ifndef HAL_MOUNT_SIYI_ENABLED +#define HAL_MOUNT_SIYI_ENABLED HAL_MOUNT_ENABLED && BOARD_FLASH_SIZE > 1024 +#endif + +#if HAL_MOUNT_SIYI_ENABLED + +#include +#include +#include + +#define AP_MOUNT_SIYI_PACKETLEN_MAX 22 // maximum number of bytes in a packet sent to or received from the gimbal + +class AP_Mount_Siyi : public AP_Mount_Backend +{ + +public: + // Constructor + using AP_Mount_Backend::AP_Mount_Backend; + + /* Do not allow copies */ + CLASS_NO_COPY(AP_Mount_Siyi); + + // init - performs any required initialisation for this instance + void init() override; + + // update mount position - should be called periodically + void update() override; + + // return true if healthy + bool healthy() const override; + + // has_pan_control - returns true if this mount can control its pan (required for multicopters) + bool has_pan_control() const override { return yaw_range_valid(); }; + + // + // camera controls + // + + // take a picture. returns true on success + bool take_picture() override; + + // start or stop video recording + // set start_recording = true to start record, false to stop recording + bool record_video(bool start_recording) override; + + // set camera zoom step. returns true on success + // zoom out = -1, hold = 0, zoom in = 1 + bool set_zoom_step(int8_t zoom_step) override; + + // set focus in, out or hold. returns true on success + // focus in = -1, focus hold = 0, focus out = 1 + bool set_manual_focus_step(int8_t focus_step) override; + + // auto focus. returns true on success + bool set_auto_focus() override; + +protected: + + // get attitude as a quaternion. returns true on success + bool get_attitude_quaternion(Quaternion& att_quat) override; + +private: + + // serial protocol command ids + enum class SiyiCommandId { + ACQUIRE_FIRMWARE_VERSION = 0x01, + HARDWARE_ID = 0x02, + AUTO_FOCUS = 0x04, + MANUAL_ZOOM_AND_AUTO_FOCUS = 0x05, + MANUAL_FOCUS = 0x06, + GIMBAL_ROTATION = 0x07, + CENTER = 0x08, + ACQUIRE_GIMBAL_CONFIG_INFO = 0x0A, + FUNCTION_FEEDBACK_INFO = 0x0B, + PHOTO = 0x0C, + ACQUIRE_GIMBAL_ATTITUDE = 0x0D + }; + + // Function Feedback Info packet info_type values + enum class FunctionFeedbackInfo : uint8_t { + SUCCESS = 0, + FAILED_TO_TAKE_PHOTO = 1, + HDR_ON = 2, + HDR_OFF = 3, + FAILED_TO_RECORD_VIDEO = 4 + }; + + // Photo Function packet func_type values + enum class PhotoFunction : uint8_t { + TAKE_PICTURE = 0, + HDR_TOGGLE = 1, + RECORD_VIDEO_TOGGLE = 2, + LOCK_MODE = 3, + FOLLOW_MODE = 4, + FPV_MODE = 5 + }; + + // parsing state + enum class ParseState : uint8_t { + WAITING_FOR_HEADER_LOW, + WAITING_FOR_HEADER_HIGH, + WAITING_FOR_CTRL, + WAITING_FOR_DATALEN_LOW, + WAITING_FOR_DATALEN_HIGH, + WAITING_FOR_SEQ_LOW, + WAITING_FOR_SEQ_HIGH, + WAITING_FOR_CMDID, + WAITING_FOR_DATA, + WAITING_FOR_CRC_LOW, + WAITING_FOR_CRC_HIGH, + }; + + // reading incoming packets from gimbal and confirm they are of the correct format + // results are held in the _parsed_msg structure + void read_incoming_packets(); + + // process successfully decoded packets held in the _parsed_msg structure + void process_packet(); + + // send packet to gimbal + // returns true on success, false if outgoing serial buffer is full + bool send_packet(SiyiCommandId cmd_id, const uint8_t* databuff, uint8_t databuff_len); + bool send_1byte_packet(SiyiCommandId cmd_id, uint8_t data_byte); + + // request info from gimbal + void request_firmware_version() { send_packet(SiyiCommandId::ACQUIRE_FIRMWARE_VERSION, nullptr, 0); } + void request_hardware_id() { send_packet(SiyiCommandId::HARDWARE_ID, nullptr, 0); } + void request_configuration() { send_packet(SiyiCommandId::ACQUIRE_GIMBAL_CONFIG_INFO, nullptr, 0); } + void request_function_feedback_info() { send_packet(SiyiCommandId::FUNCTION_FEEDBACK_INFO, nullptr, 0); } + void request_gimbal_attitude() { send_packet(SiyiCommandId::ACQUIRE_GIMBAL_ATTITUDE, nullptr, 0); } + + // rotate gimbal. pitch_rate and yaw_rate are scalars in the range -100 ~ +100 + // yaw_is_ef should be true if gimbal should maintain an earth-frame target (aka lock) + void rotate_gimbal(int8_t pitch_scalar, int8_t yaw_scalar, bool yaw_is_ef); + + // center gimbal + void center_gimbal(); + + // set gimbal's lock vs follow mode + // lock should be true if gimbal should maintain an earth-frame target + // lock is false to follow / maintain a body-frame target + void set_lock(bool lock); + + // send target pitch and yaw rates to gimbal + // yaw_is_ef should be true if yaw_rads target is an earth frame rate, false if body_frame + void send_target_rates(float pitch_rads, float yaw_rads, bool yaw_is_ef); + + // send target pitch and yaw angles to gimbal + // yaw_is_ef should be true if yaw_rad target is an earth frame angle, false if body_frame + void send_target_angles(float pitch_rad, float yaw_rad, bool yaw_is_ef); + + // internal variables + AP_HAL::UARTDriver *_uart; // uart connected to gimbal + bool _initialised; // true once the driver has been initialised + bool _got_firmware_version; // true once gimbal firmware version has been received + + // buffer holding bytes from latest packet. This is only used to calculate the crc + uint8_t _msg_buff[AP_MOUNT_SIYI_PACKETLEN_MAX]; + uint8_t _msg_buff_len; + const uint8_t _msg_buff_data_start = 8; // data starts at this byte of _msg_buff + + // parser state and unpacked fields + struct PACKED { + uint16_t data_len; // expected number of data bytes + uint8_t command_id; // command id + uint16_t data_bytes_received; // number of data bytes received so far + uint16_t crc16; // latest message's crc + ParseState state; // state of incoming message processing + } _parsed_msg; + + // variables for sending packets to gimbal + uint32_t _last_send_ms; // system time (in milliseconds) of last packet sent to gimbal + uint16_t _last_seq; // last sequence number used (should be increment for each send) + bool _last_lock; // last lock value sent to gimbal + uint8_t _lock_send_counter; // counter used to resend lock status to gimbal at regular intervals + + // actual attitude received from gimbal + Vector3f _current_angle_rad; // current angles in radians received from gimbal (x=roll, y=pitch, z=yaw) + uint32_t _last_current_angle_rad_ms; // system time _current_angle_rad was updated + uint32_t _last_req_current_angle_rad_ms; // system time that this driver last requested current angle + + // variables for camera state + bool _last_record_video; // last record_video state sent to gimbal +}; + +#endif // HAL_MOUNT_SIYISERIAL_ENABLED diff --git a/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp b/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp index 5b636f0e228..df48ddf7ccc 100644 --- a/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp +++ b/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp @@ -10,8 +10,8 @@ extern const AP_HAL::HAL& hal; -AP_Mount_SoloGimbal::AP_Mount_SoloGimbal(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance) : - AP_Mount_Backend(frontend, state, instance), +AP_Mount_SoloGimbal::AP_Mount_SoloGimbal(AP_Mount &frontend, AP_Mount_Params ¶ms, uint8_t instance) : + AP_Mount_Backend(frontend, params, instance), _gimbal() {} @@ -19,7 +19,7 @@ AP_Mount_SoloGimbal::AP_Mount_SoloGimbal(AP_Mount &frontend, AP_Mount::mount_sta void AP_Mount_SoloGimbal::init() { _initialised = true; - set_mode((enum MAV_MOUNT_MODE)_state._default_mode.get()); + set_mode((enum MAV_MOUNT_MODE)_params.default_mode.get()); } void AP_Mount_SoloGimbal::update_fast() @@ -40,51 +40,61 @@ void AP_Mount_SoloGimbal::update() // move mount to a "retracted" position. we do not implement a separate servo based retract mechanism case MAV_MOUNT_MODE_RETRACT: _gimbal.set_lockedToBody(true); + // initialise _angle_rad to smooth transition if user changes to RC_TARGETTINg + _angle_rad = {0, 0, 0, false}; break; // move mount to a neutral position, typically pointing forward - case MAV_MOUNT_MODE_NEUTRAL: - { + case MAV_MOUNT_MODE_NEUTRAL: { _gimbal.set_lockedToBody(false); - const Vector3f &target = _state._neutral_angles.get(); - _angle_ef_target_rad.x = ToRad(target.x); - _angle_ef_target_rad.y = ToRad(target.y); - _angle_ef_target_rad.z = ToRad(target.z); - } + const Vector3f &target = _params.neutral_angles.get(); + _angle_rad.roll = radians(target.x); + _angle_rad.pitch = radians(target.y); + _angle_rad.yaw = radians(target.z); + _angle_rad.yaw_is_ef = false; break; + } // point to the angles given by a mavlink message case MAV_MOUNT_MODE_MAVLINK_TARGETING: _gimbal.set_lockedToBody(false); - // do nothing because earth-frame angle targets (i.e. _angle_ef_target_rad) should have already been set by a MOUNT_CONTROL message from GCS + switch (mavt_target.target_type) { + case MountTargetType::ANGLE: + _angle_rad = mavt_target.angle_rad; + break; + case MountTargetType::RATE: + update_angle_target_from_rate(mavt_target.rate_rads, _angle_rad); + break; + } break; // RC radio manual angle control, but with stabilization from the AHRS - case MAV_MOUNT_MODE_RC_TARGETING: + case MAV_MOUNT_MODE_RC_TARGETING: { _gimbal.set_lockedToBody(false); - // update targets using pilot's rc inputs - update_targets_from_rc(); + // update targets using pilot's RC inputs + MountTarget rc_target {}; + if (get_rc_rate_target(rc_target)) { + update_angle_target_from_rate(rc_target, _angle_rad); + } else if (get_rc_angle_target(rc_target)) { + _angle_rad = rc_target; + } break; + } // point mount to a GPS point given by the mission planner case MAV_MOUNT_MODE_GPS_POINT: _gimbal.set_lockedToBody(false); - UNUSED_RESULT(calc_angle_to_roi_target(_angle_ef_target_rad, true, true)); + IGNORE_RETURN(get_angle_target_to_roi(_angle_rad)); break; case MAV_MOUNT_MODE_HOME_LOCATION: - // constantly update the home location: - if (!AP::ahrs().home_is_set()) { - break; - } - _state._roi_target = AP::ahrs().get_home(); - _state._roi_target_set = true; _gimbal.set_lockedToBody(false); - UNUSED_RESULT(calc_angle_to_roi_target(_angle_ef_target_rad, true, true)); + IGNORE_RETURN(get_angle_target_to_home(_angle_rad)); break; case MAV_MOUNT_MODE_SYSID_TARGET: - UNUSED_RESULT(calc_angle_to_sysid_target(_angle_ef_target_rad, true, true)); + _gimbal.set_lockedToBody(false); + IGNORE_RETURN(get_angle_target_to_sysid(_angle_rad)); break; default: @@ -93,34 +103,14 @@ void AP_Mount_SoloGimbal::update() } } -// has_pan_control - returns true if this mount can control it's pan (required for multicopters) -bool AP_Mount_SoloGimbal::has_pan_control() const -{ - // we do not have yaw control - return false; -} - -// set_mode - sets mount's mode -void AP_Mount_SoloGimbal::set_mode(enum MAV_MOUNT_MODE mode) -{ - // exit immediately if not initialised - if (!_initialised) { - return; - } - - // record the mode change - _state._mode = mode; -} - -// send_mount_status - called to allow mounts to send their status to GCS using the MOUNT_STATUS message -void AP_Mount_SoloGimbal::send_mount_status(mavlink_channel_t chan) +// get attitude as a quaternion. returns true on success +bool AP_Mount_SoloGimbal::get_attitude_quaternion(Quaternion& att_quat) { - if (_gimbal.aligned()) { - mavlink_msg_mount_status_send(chan, 0, 0, degrees(_angle_ef_target_rad.y)*100, degrees(_angle_ef_target_rad.x)*100, degrees(_angle_ef_target_rad.z)*100, _state._mode); + if (!_gimbal.aligned()) { + return false; } - - // block heartbeat from transmitting to the GCS - GCS_MAVLINK::disable_channel_routing(chan); + att_quat.from_euler(_angle_rad.roll, _angle_rad.pitch, get_bf_yaw_angle(_angle_rad)); + return true; } /* @@ -128,7 +118,7 @@ void AP_Mount_SoloGimbal::send_mount_status(mavlink_channel_t chan) */ void AP_Mount_SoloGimbal::handle_gimbal_report(mavlink_channel_t chan, const mavlink_message_t &msg) { - _gimbal.update_target(_angle_ef_target_rad); + _gimbal.update_target(Vector3f{_angle_rad.roll, _angle_rad.pitch, get_bf_yaw_angle(_angle_rad)}); _gimbal.receive_feedback(chan,msg); AP_Logger *logger = AP_Logger::get_singleton(); @@ -159,11 +149,4 @@ void AP_Mount_SoloGimbal::handle_gimbal_torque_report(mavlink_channel_t chan, co _gimbal.disable_torque_report(); } -/* - send a GIMBAL_REPORT message to the GCS - */ -void AP_Mount_SoloGimbal::send_gimbal_report(mavlink_channel_t chan) -{ -} - #endif // HAL_SOLO_GIMBAL_ENABLED diff --git a/libraries/AP_Mount/AP_Mount_SoloGimbal.h b/libraries/AP_Mount/AP_Mount_SoloGimbal.h index d8238f0fa04..8b845a27cf0 100644 --- a/libraries/AP_Mount/AP_Mount_SoloGimbal.h +++ b/libraries/AP_Mount/AP_Mount_SoloGimbal.h @@ -21,7 +21,7 @@ class AP_Mount_SoloGimbal : public AP_Mount_Backend public: // Constructor - AP_Mount_SoloGimbal(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance); + AP_Mount_SoloGimbal(AP_Mount &frontend, AP_Mount_Params ¶ms, uint8_t instance); // init - performs any required initialisation for this instance void init() override; @@ -29,25 +29,24 @@ class AP_Mount_SoloGimbal : public AP_Mount_Backend // update mount position - should be called periodically void update() override; - // has_pan_control - returns true if this mount can control it's pan (required for multicopters) - bool has_pan_control() const override; - - // set_mode - sets mount's mode - void set_mode(enum MAV_MOUNT_MODE mode) override; - - // send_mount_status - called to allow mounts to send their status to GCS using the MOUNT_STATUS message - void send_mount_status(mavlink_channel_t chan) override; + // has_pan_control - returns true if this mount can control its pan (required for multicopters) + bool has_pan_control() const override { return false; } // handle a GIMBAL_REPORT message void handle_gimbal_report(mavlink_channel_t chan, const mavlink_message_t &msg) override; void handle_gimbal_torque_report(mavlink_channel_t chan, const mavlink_message_t &msg); void handle_param_value(const mavlink_message_t &msg) override; - // send a GIMBAL_REPORT message to the GCS - void send_gimbal_report(mavlink_channel_t chan) override; - void update_fast() override; +protected: + + // returns true if heart beat should be suppressed for this gimbal + bool suppress_heartbeat() const override { return true; } + + // get attitude as a quaternion. returns true on success + bool get_attitude_quaternion(Quaternion& att_quat) override; + private: // internal variables bool _initialised; // true once the driver has been initialised @@ -56,7 +55,7 @@ class AP_Mount_SoloGimbal : public AP_Mount_Backend void Log_Write_Gimbal(SoloGimbal &gimbal); bool _params_saved; - + MountTarget _angle_rad; // angle target SoloGimbal _gimbal; }; diff --git a/libraries/AP_Mount/SoloGimbal.h b/libraries/AP_Mount/SoloGimbal.h index 9041f793c76..236fe2a33ab 100644 --- a/libraries/AP_Mount/SoloGimbal.h +++ b/libraries/AP_Mount/SoloGimbal.h @@ -6,8 +6,7 @@ ************************************************************/ #pragma once -#include -#include +#include #include "AP_Mount.h" #if HAL_SOLO_GIMBAL_ENABLED #include "SoloGimbalEKF.h" @@ -51,7 +50,9 @@ class SoloGimbal : AP_AccelCal_Client _log_del_ang(), _log_del_vel() { +#if HAL_INS_ACCELCAL_ENABLED AP_AccelCal::register_client(this); +#endif } void update_target(const Vector3f &newTarget); diff --git a/libraries/AP_Mount/SoloGimbalEKF.cpp b/libraries/AP_Mount/SoloGimbalEKF.cpp index 37d0c1dadaf..0003d343609 100644 --- a/libraries/AP_Mount/SoloGimbalEKF.cpp +++ b/libraries/AP_Mount/SoloGimbalEKF.cpp @@ -107,7 +107,7 @@ void SoloGimbalEKF::RunEKF(float delta_time, const Vector3f &delta_angles, const for (uint8_t i=3; i <= 5; i++) Cov[i][i] = sq(Sigma_velNED); for (uint8_t i=6; i <= 8; i++) Cov[i][i] = sq(Sigma_dAngBias); FiltInit = true; - hal.console->printf("\nSoloGimbalEKF Alignment Started\n"); + DEV_PRINTF("\nSoloGimbalEKF Alignment Started\n"); // Don't run the filter in this timestep because we have already used the delta velocity data to set an initial orientation return; @@ -142,7 +142,7 @@ void SoloGimbalEKF::RunEKF(float delta_time, const Vector3f &delta_angles, const //calculate the initial heading using magnetometer, estimated tilt and declination alignHeading(); YawAligned = true; - hal.console->printf("\nSoloGimbalEKF Alignment Completed\n"); + DEV_PRINTF("\nSoloGimbalEKF Alignment Completed\n"); } // Fuse magnetometer data if we have new measurements and an aligned heading diff --git a/libraries/AP_Mount/SoloGimbal_Parameters.cpp b/libraries/AP_Mount/SoloGimbal_Parameters.cpp index 4864a59acd0..8245086ba32 100644 --- a/libraries/AP_Mount/SoloGimbal_Parameters.cpp +++ b/libraries/AP_Mount/SoloGimbal_Parameters.cpp @@ -162,7 +162,7 @@ void SoloGimbal_Parameters::update() for(uint8_t i=0; i _max_fetch_attempts) { _params[i].state = GMB_PARAMSTATE_NONEXISTANT; - hal.console->printf("Gimbal parameter %s timed out\n", get_param_name((gmb_param_t)i)); + DEV_PRINTF("Gimbal parameter %s timed out\n", get_param_name((gmb_param_t)i)); } } diff --git a/libraries/AP_NMEA_Output/AP_NMEA_Output.cpp b/libraries/AP_NMEA_Output/AP_NMEA_Output.cpp index ba155416e83..269a6161206 100644 --- a/libraries/AP_NMEA_Output/AP_NMEA_Output.cpp +++ b/libraries/AP_NMEA_Output/AP_NMEA_Output.cpp @@ -16,6 +16,7 @@ Author: Francisco Ferreira (some code is copied from sitl_gps.cpp) */ +#define ALLOW_DOUBLE_MATH_FUNCTIONS #include "AP_NMEA_Output.h" @@ -101,22 +102,25 @@ void AP_NMEA_Output::update() // format latitude char lat_string[13]; - float deg = fabsf(loc.lat * 1.0e-7f); + double deg = fabs(loc.lat * 1.0e-7f); + double min_dec = ((fabs(loc.lat) - (unsigned)deg * 1.0e7)) * 60 * 1.e-7f; snprintf(lat_string, sizeof(lat_string), "%02u%08.5f,%c", (unsigned) deg, - double((deg - int(deg)) * 60), + min_dec, loc.lat < 0 ? 'S' : 'N'); + // format longitude char lng_string[14]; - deg = fabsf(loc.lng * 1.0e-7f); + deg = fabs(loc.lng * 1.0e-7f); + min_dec = ((fabs(loc.lng) - (unsigned)deg * 1.0e7)) * 60 * 1.e-7f; snprintf(lng_string, sizeof(lng_string), "%03u%08.5f,%c", (unsigned) deg, - double((deg - int(deg)) * 60), + min_dec, loc.lng < 0 ? 'W' : 'E'); // format GGA message diff --git a/libraries/AP_NavEKF/AP_NavEKF_Source.cpp b/libraries/AP_NavEKF/AP_NavEKF_Source.cpp index bf851ac1e65..3684c9b9e3c 100644 --- a/libraries/AP_NavEKF/AP_NavEKF_Source.cpp +++ b/libraries/AP_NavEKF/AP_NavEKF_Source.cpp @@ -286,20 +286,20 @@ bool AP_NavEKF_Source::usingGPS() const } // true if some parameters have been configured (used during parameter conversion) -bool AP_NavEKF_Source::configured_in_storage() +bool AP_NavEKF_Source::configured() { - if (config_in_storage) { + if (_configured) { return true; } // first source parameter is used to determine if configured or not - config_in_storage = _source_set[0].posxy.configured_in_storage(); + _configured = _source_set[0].posxy.configured(); - return config_in_storage; + return _configured; } -// mark parameters as configured in storage (used to ensure parameter conversion is only done once) -void AP_NavEKF_Source::mark_configured_in_storage() +// mark parameters as configured (used to ensure parameter conversion is only done once) +void AP_NavEKF_Source::mark_configured() { // save first parameter's current value to mark as configured return _source_set[0].posxy.save(true); @@ -524,6 +524,12 @@ bool AP_NavEKF_Source::wheel_encoder_enabled(void) const return false; } +// returns active source set +uint8_t AP_NavEKF_Source::get_active_source_set() const +{ + return active_source_set; +} + // return true if GPS yaw is enabled on any source bool AP_NavEKF_Source::gps_yaw_enabled(void) const { diff --git a/libraries/AP_NavEKF/AP_NavEKF_Source.h b/libraries/AP_NavEKF/AP_NavEKF_Source.h index 1ab40a42f4f..ca9969d63a5 100644 --- a/libraries/AP_NavEKF/AP_NavEKF_Source.h +++ b/libraries/AP_NavEKF/AP_NavEKF_Source.h @@ -85,10 +85,10 @@ class AP_NavEKF_Source bool usingGPS() const; // true if source parameters have been configured (used for parameter conversion) - bool configured_in_storage(); + bool configured(); - // mark parameters as configured in storage (used to ensure parameter conversion is only done once) - void mark_configured_in_storage(); + // mark parameters as configured (used to ensure parameter conversion is only done once) + void mark_configured(); // returns false if we fail arming checks, in which case the buffer will be populated with a failure message // requires_position should be true if horizontal position configuration should be checked @@ -103,6 +103,9 @@ class AP_NavEKF_Source // return true if wheel encoder is enabled on any source bool wheel_encoder_enabled(void) const; + // returns active source set + uint8_t get_active_source_set() const; + static const struct AP_Param::GroupInfo var_info[]; private: @@ -119,5 +122,5 @@ class AP_NavEKF_Source AP_Int16 _options; // source options bitmask uint8_t active_source_set; // index of active source set - bool config_in_storage; // true once configured in storage has returned true + bool _configured; // true once configured has returned true }; diff --git a/libraries/AP_NavEKF/AP_Nav_Common.h b/libraries/AP_NavEKF/AP_Nav_Common.h index 1aff03ce960..10037c4e157 100644 --- a/libraries/AP_NavEKF/AP_Nav_Common.h +++ b/libraries/AP_NavEKF/AP_Nav_Common.h @@ -39,6 +39,7 @@ union nav_filter_status { bool gps_quality_good : 1; // 15 - true if we can use GPS for navigation bool initalized : 1; // 16 - true if the EKF has ever been healthy bool rejecting_airspeed : 1; // 17 - true if we are rejecting airspeed data + bool dead_reckoning : 1; // 18 - true if we are dead reckoning (e.g. no position or velocity source) } flags; uint32_t value; }; diff --git a/libraries/AP_NavEKF/EKFGSF_Logging.cpp b/libraries/AP_NavEKF/EKFGSF_Logging.cpp index 31cc095d929..64673085ce9 100644 --- a/libraries/AP_NavEKF/EKFGSF_Logging.cpp +++ b/libraries/AP_NavEKF/EKFGSF_Logging.cpp @@ -16,13 +16,13 @@ void EKFGSF_yaw::Log_Write(uint64_t time_us, LogMessages id0, LogMessages id1, u LOG_PACKET_HEADER_INIT(id0), time_us : time_us, core : core_index, - yaw_composite : GSF.yaw, - yaw_composite_variance : sqrtF(MAX(GSF.yaw_variance, 0.0f)), - yaw0 : EKF[0].X[2], - yaw1 : EKF[1].X[2], - yaw2 : EKF[2].X[2], - yaw3 : EKF[3].X[2], - yaw4 : EKF[4].X[2], + yaw_composite : wrap_360(degrees(GSF.yaw)), + yaw_composite_variance : sqrtF(MAX(degrees(GSF.yaw_variance), 0.0f)), + yaw0 : wrap_360(degrees(EKF[0].X[2])), + yaw1 : wrap_360(degrees(EKF[1].X[2])), + yaw2 : wrap_360(degrees(EKF[2].X[2])), + yaw3 : wrap_360(degrees(EKF[3].X[2])), + yaw4 : wrap_360(degrees(EKF[4].X[2])), wgt0 : GSF.weights[0], wgt1 : GSF.weights[1], wgt2 : GSF.weights[2], diff --git a/libraries/AP_NavEKF/EKFGSF_yaw.cpp b/libraries/AP_NavEKF/EKFGSF_yaw.cpp index 290e65eaf4c..2bba0d49d16 100644 --- a/libraries/AP_NavEKF/EKFGSF_yaw.cpp +++ b/libraries/AP_NavEKF/EKFGSF_yaw.cpp @@ -93,7 +93,7 @@ void EKFGSF_yaw::update(const Vector3F &delAng, } // Always run the AHRS prediction cycle for each model - for (uint8_t mdl_idx = 0; mdl_idx < N_MODELS_EKFGSF; mdl_idx ++) { + for (uint8_t mdl_idx = 0; mdl_idx < N_MODELS_EKFGSF; mdl_idx++) { predict(mdl_idx); } @@ -105,7 +105,7 @@ void EKFGSF_yaw::update(const Vector3F &delAng, // To avoid issues with angle wrapping, the yaw state is converted to a vector with legnth // equal to the weighting value before it is summed. Vector2F yaw_vector = {}; - for (uint8_t mdl_idx = 0; mdl_idx < N_MODELS_EKFGSF; mdl_idx ++) { + for (uint8_t mdl_idx = 0; mdl_idx < N_MODELS_EKFGSF; mdl_idx++) { yaw_vector[0] += GSF.weights[mdl_idx] * cosF(EKF[mdl_idx].X[2]); yaw_vector[1] += GSF.weights[mdl_idx] * sinF(EKF[mdl_idx].X[2]); } @@ -114,7 +114,7 @@ void EKFGSF_yaw::update(const Vector3F &delAng, // Example for future reference showing how a full GSF covariance matrix could be calculated if required /* memset(&GSF.P, 0, sizeof(GSF.P)); - for (uint8_t mdl_idx = 0; mdl_idx < N_MODELS_EKFGSF; mdl_idx ++) { + for (uint8_t mdl_idx = 0; mdl_idx < N_MODELS_EKFGSF; mdl_idx++) { ftype delta[3]; for (uint8_t row = 0; row < 3; row++) { delta[row] = EKF[mdl_idx].X[row] - GSF.X[row]; @@ -128,7 +128,7 @@ void EKFGSF_yaw::update(const Vector3F &delAng, */ GSF.yaw_variance = 0.0f; - for (uint8_t mdl_idx = 0; mdl_idx < N_MODELS_EKFGSF; mdl_idx ++) { + for (uint8_t mdl_idx = 0; mdl_idx < N_MODELS_EKFGSF; mdl_idx++) { ftype yawDelta = wrap_PI(EKF[mdl_idx].X[2] - GSF.yaw); GSF.yaw_variance += GSF.weights[mdl_idx] * (EKF[mdl_idx].P[2][2] + sq(yawDelta)); } @@ -144,7 +144,7 @@ void EKFGSF_yaw::fuseVelData(const Vector2F &vel, const ftype velAcc) if (!vel_fuse_running) { // Perform in-flight alignment resetEKFGSF(); - for (uint8_t mdl_idx = 0; mdl_idx < N_MODELS_EKFGSF; mdl_idx ++) { + for (uint8_t mdl_idx = 0; mdl_idx < N_MODELS_EKFGSF; mdl_idx++) { // Use the firstGPS measurement to set the velocities and corresponding variances EKF[mdl_idx].X[0] = vel[0]; EKF[mdl_idx].X[1] = vel[1]; @@ -157,7 +157,7 @@ void EKFGSF_yaw::fuseVelData(const Vector2F &vel, const ftype velAcc) ftype total_w = 0.0f; ftype newWeight[(uint8_t)N_MODELS_EKFGSF]; bool state_update_failed = false; - for (uint8_t mdl_idx = 0; mdl_idx < N_MODELS_EKFGSF; mdl_idx ++) { + for (uint8_t mdl_idx = 0; mdl_idx < N_MODELS_EKFGSF; mdl_idx++) { // Update states and covariances using GPS NE velocity measurements fused as direct state observations if (!correct(mdl_idx, vel, velObsVar)) { state_update_failed = true; @@ -167,8 +167,8 @@ void EKFGSF_yaw::fuseVelData(const Vector2F &vel, const ftype velAcc) if (!state_update_failed) { // Calculate weighting for each model assuming a normal error distribution const ftype min_weight = 1e-5f; - uint8_t n_clips = 0; - for (uint8_t mdl_idx = 0; mdl_idx < N_MODELS_EKFGSF; mdl_idx ++) { + n_clips = 0; + for (uint8_t mdl_idx = 0; mdl_idx < N_MODELS_EKFGSF; mdl_idx++) { newWeight[mdl_idx] = gaussianDensity(mdl_idx) * GSF.weights[mdl_idx]; if (newWeight[mdl_idx] < min_weight) { n_clips++; @@ -181,7 +181,7 @@ void EKFGSF_yaw::fuseVelData(const Vector2F &vel, const ftype velAcc) // Reset the filters if all weights have underflowed due to excessive innovation variances if (vel_fuse_running && n_clips < N_MODELS_EKFGSF) { ftype total_w_inv = 1.0f / total_w; - for (uint8_t mdl_idx = 0; mdl_idx < N_MODELS_EKFGSF; mdl_idx ++) { + for (uint8_t mdl_idx = 0; mdl_idx < N_MODELS_EKFGSF; mdl_idx++) { GSF.weights[mdl_idx] = newWeight[mdl_idx] * total_w_inv; } } else { @@ -226,10 +226,15 @@ void EKFGSF_yaw::predictAHRS(const uint8_t mdl_idx) // Gyro bias estimation const ftype gyro_bias_limit = radians(5.0f); - const ftype spinRate = ang_rate_delayed_raw.length(); - if (spinRate < 0.175f) { + const ftype spinRate_squared = ang_rate_delayed_raw.length_squared(); + if (spinRate_squared < sq(0.175f)) { AHRS[mdl_idx].gyro_bias -= tilt_error_gyro_correction * (EKFGSF_gyroBiasGain * angle_dt); + // sanity check + if (AHRS[mdl_idx].gyro_bias.is_nan()) { + AHRS[mdl_idx].gyro_bias.zero(); + } + for (uint8_t i = 0; i < 3; i++) { AHRS[mdl_idx].gyro_bias[i] = constrain_ftype(AHRS[mdl_idx].gyro_bias[i], -gyro_bias_limit, gyro_bias_limit); } @@ -625,13 +630,19 @@ Matrix3F EKFGSF_yaw::updateRotMat(const Matrix3F &R, const Vector3F &g) const return ret; } -bool EKFGSF_yaw::getYawData(ftype &yaw, ftype &yawVariance) const +// returns true if a yaw estimate is available. yaw and its variance +// is returned, as well as the number of models which are *not* being +// used to snthesise the yaw. +bool EKFGSF_yaw::getYawData(ftype &yaw, ftype &yawVariance, uint8_t *_n_clips) const { if (!vel_fuse_running) { return false; } yaw = GSF.yaw; yawVariance = GSF.yaw_variance; + if (_n_clips != nullptr) { + *_n_clips = n_clips; + } return true; } @@ -641,7 +652,7 @@ bool EKFGSF_yaw::getVelInnovLength(ftype &velInnovLength) const return false; } velInnovLength = 0.0f; - for (uint8_t mdl_idx = 0; mdl_idx < N_MODELS_EKFGSF; mdl_idx ++) { + for (uint8_t mdl_idx = 0; mdl_idx < N_MODELS_EKFGSF; mdl_idx++) { velInnovLength += GSF.weights[mdl_idx] * sqrtF((sq(EKF[mdl_idx].innov[0]) + sq(EKF[mdl_idx].innov[1]))); } return true; diff --git a/libraries/AP_NavEKF/EKFGSF_yaw.h b/libraries/AP_NavEKF/EKFGSF_yaw.h index 4a333ef2eb0..2487aea1a3e 100644 --- a/libraries/AP_NavEKF/EKFGSF_yaw.h +++ b/libraries/AP_NavEKF/EKFGSF_yaw.h @@ -16,8 +16,8 @@ class EKFGSF_yaw EKFGSF_yaw(); // Update Filter States - this should be called whenever new IMU data is available - void update(const Vector3F &delAng,// IMU delta angle rotation vector meassured in body frame (rad) - const Vector3F &delVel,// IMU delta velocity vector meassured in body frame (m/s) + void update(const Vector3F &delAng,// IMU delta angle rotation vector measured in body frame (rad) + const Vector3F &delVel,// IMU delta velocity vector measured in body frame (m/s) const ftype delAngDT, // time interval that delAng was integrated over (sec) - must be no less than IMU_DT_MIN_SEC const ftype delVelDT, // time interval that delVel was integrated over (sec) - must be no less than IMU_DT_MIN_SEC bool runEKF, // set to true when flying or movement suitable for yaw estimation @@ -31,9 +31,11 @@ class EKFGSF_yaw // set the gyro bias in rad/sec void setGyroBias(Vector3f &gyroBias); - // get yaw estimated and corresponding variance - // return false if yaw estimation is inactive - bool getYawData(ftype &yaw, ftype &yawVariance) const; + // get yaw estimated and corresponding variance return false if + // yaw estimation is inactive. n_clips will contain the number of + // models which were *not* used to create the yaw and yawVariance + // return values. + bool getYawData(ftype &yaw, ftype &yawVariance, uint8_t *n_clips=nullptr) const; // get the length of the weighted average velocity innovation vector // return false if not available @@ -136,4 +138,8 @@ class EKFGSF_yaw // Returns the probability for a selected model assuming a Gaussian error distribution // Used by the Guassian Sum Filter to calculate the weightings when combining the outputs from the bank of EKF's ftype gaussianDensity(const uint8_t mdl_idx) const; + + // number of models whose weights underflowed due to excessive + // innovation variances: + uint8_t n_clips; }; diff --git a/libraries/AP_NavEKF/EKF_Buffer.cpp b/libraries/AP_NavEKF/EKF_Buffer.cpp index fcaf3361af0..928a8d655ae 100644 --- a/libraries/AP_NavEKF/EKF_Buffer.cpp +++ b/libraries/AP_NavEKF/EKF_Buffer.cpp @@ -10,22 +10,21 @@ // constructor ekf_ring_buffer::ekf_ring_buffer(uint8_t _elsize) : - elsize(_elsize) + elsize(_elsize), + buffer(nullptr) {} -bool ekf_ring_buffer::init(uint8_t size) +bool ekf_ring_buffer::init(uint8_t _size) { if (buffer) { free(buffer); } - buffer = calloc(size, elsize); + buffer = calloc(_size, elsize); if (buffer == nullptr) { return false; } - _size = size; - _head = 0; - _tail = 0; - _new_data = false; + size = _size; + reset(); return true; } @@ -40,7 +39,7 @@ void *ekf_ring_buffer::get_offset(uint8_t idx) const /* get a reference to the timestamp for an index */ -uint32_t &ekf_ring_buffer::time_ms(uint8_t idx) +uint32_t ekf_ring_buffer::time_ms(uint8_t idx) const { EKF_obs_element_t *el = (EKF_obs_element_t *)get_offset(idx); return el->time_ms; @@ -48,53 +47,30 @@ uint32_t &ekf_ring_buffer::time_ms(uint8_t idx) /* Search through a ring buffer and return the newest data that is - older than the time specified by sample_time_ms Zeros old data - so it cannot not be used again Returns false if no data can be - found that is less than 100msec old + older than the time specified by sample_time_ms + Returns false if no data can be found that is less than 100msec old */ -bool ekf_ring_buffer::recall(void *element,uint32_t sample_time) +bool ekf_ring_buffer::recall(void *element, const uint32_t sample_time_ms) { - if (!_new_data) { - return false; - } - bool success = false; - uint8_t tail = _tail, bestIndex; - - if (_head == tail) { - if (time_ms(tail) != 0 && time_ms(tail) <= sample_time) { - // if head is equal to tail just check if the data is unused and within time horizon window - if (((sample_time - time_ms(tail)) < 100)) { - bestIndex = tail; - success = true; - _new_data = false; - } + bool ret = false; + while (count > 0) { + const uint32_t toldest = time_ms(oldest); + const int32_t dt = sample_time_ms - toldest; + const bool matches = dt >= 0 && dt < 100; + if (matches) { + memcpy(element, get_offset(oldest), elsize); + ret = true; } - } else { - while(_head != tail) { - // find a measurement older than the fusion time horizon that we haven't checked before - if (time_ms(tail) != 0 && time_ms(tail) <= sample_time) { - // Find the most recent non-stale measurement that meets the time horizon criteria - if (((sample_time - time_ms(tail)) < 100)) { - bestIndex = tail; - success = true; - } - } else if (time_ms(tail) > sample_time){ - break; - } - tail = (tail+1) % _size; + if (dt < 0) { + // the oldest element is younger than we want, stop + // searching and don't consume this element + break; } + // discard the sample + count--; + oldest = (oldest+1) % size; } - - if (!success) { - return false; - } - - memcpy(element, get_offset(bestIndex), elsize); - _tail = (bestIndex+1) % _size; - // make time zero to stop using it again, - // resolves corner case of reusing the element when head == tail - time_ms(bestIndex) = 0; - return true; + return ret; } /* @@ -106,21 +82,26 @@ void ekf_ring_buffer::push(const void *element) if (buffer == nullptr) { return; } + // Advance head to next available index - _head = (_head+1) % _size; + const uint8_t head = (oldest+count) % size; + // New data is written at the head - memcpy(get_offset(_head), element, elsize); - _new_data = true; + memcpy(get_offset(head), element, elsize); + + if (count < size) { + count++; + } else { + oldest = (oldest+1) % size; + } } // zeroes all data in the ring buffer void ekf_ring_buffer::reset() { - _head = 0; - _tail = 0; - _new_data = false; - memset((void *)buffer,0,_size*uint32_t(elsize)); + count = 0; + oldest = 0; } //////////////////////////////////////////////////// diff --git a/libraries/AP_NavEKF/EKF_Buffer.h b/libraries/AP_NavEKF/EKF_Buffer.h index e7c0086abcb..0991735aaa5 100644 --- a/libraries/AP_NavEKF/EKF_Buffer.h +++ b/libraries/AP_NavEKF/EKF_Buffer.h @@ -28,7 +28,7 @@ class ekf_ring_buffer * Zeros old data so it cannot not be used again * Returns false if no data can be found that is less than 100msec old */ - bool recall(void *element, uint32_t sample_time); + bool recall(void *element, const uint32_t sample_time_ms); /* * Writes data and timestamp to a Ring buffer and advances indices that @@ -42,9 +42,17 @@ class ekf_ring_buffer private: const uint8_t elsize; void *buffer; - uint8_t _size, _head, _tail, _new_data; - uint32_t &time_ms(uint8_t idx); + // size of allocated buffer in elsize units + uint8_t size; + + // index of the oldest element in the buffer + uint8_t oldest; + + // total number of elements in the buffer + uint8_t count; + + uint32_t time_ms(uint8_t idx) const; void *get_offset(uint8_t idx) const; }; @@ -63,15 +71,15 @@ class EKF_obs_buffer_t : ekf_ring_buffer ekf_ring_buffer(sizeof(element_type)) {} - bool init(uint8_t size) { - return ekf_ring_buffer::init(size); + bool init(uint8_t _size) { + return ekf_ring_buffer::init(_size); } bool recall(element_type &element,uint32_t sample_time) { return ekf_ring_buffer::recall(&element, sample_time); } - void push(element_type element) { + void push(const element_type &element) { return ekf_ring_buffer::push(&element); } diff --git a/libraries/AP_NavEKF/LogStructure.h b/libraries/AP_NavEKF/LogStructure.h index 85beb5e9791..119ea0f9ead 100644 --- a/libraries/AP_NavEKF/LogStructure.h +++ b/libraries/AP_NavEKF/LogStructure.h @@ -6,13 +6,13 @@ // @Description: EKF Yaw Estimator States // @Field: TimeUS: Time since system startup // @Field: C: EKF core this data is for -// @Field: YC: GSF yaw estimate (rad) -// @Field: YCS: GSF yaw estimate 1-Sigma uncertainty (rad) -// @Field: Y0: Yaw estimate from individual EKF filter 0 (rad) -// @Field: Y1: Yaw estimate from individual EKF filter 1 (rad) -// @Field: Y2: Yaw estimate from individual EKF filter 2 (rad) -// @Field: Y3: Yaw estimate from individual EKF filter 3 (rad) -// @Field: Y4: Yaw estimate from individual EKF filter 4 (rad) +// @Field: YC: GSF yaw estimate (deg) +// @Field: YCS: GSF yaw estimate 1-Sigma uncertainty (deg) +// @Field: Y0: Yaw estimate from individual EKF filter 0 (deg) +// @Field: Y1: Yaw estimate from individual EKF filter 1 (deg) +// @Field: Y2: Yaw estimate from individual EKF filter 2 (deg) +// @Field: Y3: Yaw estimate from individual EKF filter 3 (deg) +// @Field: Y4: Yaw estimate from individual EKF filter 4 (deg) // @Field: W0: Weighting applied to yaw estimate from individual EKF filter 0 // @Field: W1: Weighting applied to yaw estimate from individual EKF filter 1 // @Field: W2: Weighting applied to yaw estimate from individual EKF filter 2 @@ -69,7 +69,7 @@ struct PACKED log_KY1 { #define KY0_FMT "QBffffffffffff" #define KY0_LABELS "TimeUS,C,YC,YCS,Y0,Y1,Y2,Y3,Y4,W0,W1,W2,W3,W4" -#define KY0_UNITS "s#rrrrrrr-----" +#define KY0_UNITS "s#hdhhhhh-----" #define KY0_MULTS "F-000000000000" #define KY1_FMT "QBffffffffff" diff --git a/libraries/AP_NavEKF/Models/GimbalEstimatorExample/calcTms.c b/libraries/AP_NavEKF/Models/GimbalEstimatorExample/calcTms.c index 16c1e5a17ce..fc38672e187 100644 --- a/libraries/AP_NavEKF/Models/GimbalEstimatorExample/calcTms.c +++ b/libraries/AP_NavEKF/Models/GimbalEstimatorExample/calcTms.c @@ -1 +1 @@ - t0 = _symans_32_297; + t0 = _symans_32_297; diff --git a/libraries/AP_NavEKF/tests/test_ring_buffer.cpp b/libraries/AP_NavEKF/tests/test_ring_buffer.cpp new file mode 100644 index 00000000000..a808c4b48dc --- /dev/null +++ b/libraries/AP_NavEKF/tests/test_ring_buffer.cpp @@ -0,0 +1,124 @@ +#include + +/* + tests for AP_NavEKF/EKF_Buffer.cpp + */ + +#include +#include + +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX + +TEST(EKF_Buffer, EKF_Buffer) +{ + struct test_data : EKF_obs_element_t { + uint32_t data; + }; + EKF_obs_buffer_t buf; + buf.init(8); + struct test_data d, d2; + uint32_t now = 100; + d.data = 17; + d.time_ms = now++; + buf.push(d); + + EXPECT_TRUE(buf.recall(d2, now)); + EXPECT_EQ(d2.data, d.data); + EXPECT_EQ(d2.time_ms, uint32_t(100)); + + d.time_ms = 101; + buf.push(d); + d.time_ms = 102; + buf.push(d); + + // recall first element + EXPECT_TRUE(buf.recall(d2, 101)); + EXPECT_EQ(d2.data, d.data); + EXPECT_EQ(d2.time_ms, uint32_t(101)); + + EXPECT_TRUE(buf.recall(d2, 102)); + EXPECT_EQ(d2.data, d.data); + EXPECT_EQ(d2.time_ms, uint32_t(102)); + + EXPECT_FALSE(buf.recall(d2, 103)); + + d.time_ms = 101; + buf.push(d); + d.time_ms = 102; + buf.push(d); + + // recall 2nd element, note that first element is discarded + EXPECT_TRUE(buf.recall(d2, 103)); + EXPECT_EQ(d2.data, d.data); + EXPECT_EQ(d2.time_ms, uint32_t(102)); + + EXPECT_FALSE(buf.recall(d2, 103)); + EXPECT_FALSE(buf.recall(d2, 103)); + + // test overflow of buffer + for (uint8_t i=0; i<16; i++) { + d.time_ms = 100+i; + d.data = 1000+i; + buf.push(d); + } + for (uint8_t i=0; i<16; i++) { + if (i < 8) { + EXPECT_TRUE(buf.recall(d2, 108+i)); + } else { + EXPECT_FALSE(buf.recall(d2, 1100)); + } + } + + // test with an element that is too old + d.time_ms = 101; + d.data = 200; + buf.push(d); + d.time_ms = 1002; + d.data = 2000; + buf.push(d); + + // recall element, first one is too old so will be discarded + EXPECT_TRUE(buf.recall(d2, 1003)); + EXPECT_EQ(d2.data, 2000U); + EXPECT_EQ(d2.time_ms, uint32_t(1002)); + + EXPECT_FALSE(buf.recall(d2, 103)); + + + // test 32 bit time wrap + d.time_ms = 0xFFFFFFF0U; + d.data = 200; + buf.push(d); + d.time_ms = 0xFFFFFFFAU; + d.data = 2000; + buf.push(d); + d.time_ms = 0xFFFFFFFBU; + d.data = 2001; + buf.push(d); + + // recall element, first one is too old so will be discarded + EXPECT_TRUE(buf.recall(d2, 10)); + EXPECT_EQ(d2.data, 2001U); + EXPECT_EQ(d2.time_ms, uint32_t(0xFFFFFFFBU)); + + EXPECT_FALSE(buf.recall(d2, 103)); + + // test 32 bit time wrap with a too old element + d.time_ms = 0xFFFFFFFFU - 1000U; + d.data = 200; + buf.push(d); + d.time_ms = 0xFFFFFFFBU; + d.data = 2001; + buf.push(d); + + // recall element, first one is too old so will be discarded + EXPECT_TRUE(buf.recall(d2, 10)); + EXPECT_EQ(d2.data, 2001U); + EXPECT_EQ(d2.time_ms, uint32_t(0xFFFFFFFBU)); + + EXPECT_FALSE(buf.recall(d2, 103)); +} + +AP_GTEST_MAIN() + +#endif // HAL_SITL or HAL_LINUX diff --git a/libraries/AP_NavEKF/tests/wscript b/libraries/AP_NavEKF/tests/wscript new file mode 100644 index 00000000000..cd3e5e3ce7c --- /dev/null +++ b/libraries/AP_NavEKF/tests/wscript @@ -0,0 +1,7 @@ +#!/usr/bin/env python +# encoding: utf-8 + +def build(bld): + bld.ap_find_tests( + use='ap', + ) diff --git a/libraries/AP_NavEKF2/AP_NavEKF2.cpp b/libraries/AP_NavEKF2/AP_NavEKF2.cpp index 490ee7b1bb6..b9a3b17126d 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2.cpp @@ -913,74 +913,59 @@ int8_t NavEKF2::getPrimaryCoreIMUIndex(void) const // Write the last calculated NE position relative to the reference point (m). // If a calculated solution is not available, use the best available data and return false // If false returned, do not use for flight control -bool NavEKF2::getPosNE(int8_t instance, Vector2f &posNE) const +bool NavEKF2::getPosNE(Vector2f &posNE) const { - if (instance < 0 || instance >= num_cores) instance = primary; if (!core) { return false; } - return core[instance].getPosNE(posNE); + return core[primary].getPosNE(posNE); } // Write the last calculated D position relative to the reference point (m). // If a calculated solution is not available, use the best available data and return false // If false returned, do not use for flight control -bool NavEKF2::getPosD(int8_t instance, float &posD) const +bool NavEKF2::getPosD(float &posD) const { - if (instance < 0 || instance >= num_cores) instance = primary; if (!core) { return false; } - return core[instance].getPosD(posD); + return core[primary].getPosD(posD); } // return NED velocity in m/s -void NavEKF2::getVelNED(int8_t instance, Vector3f &vel) const +void NavEKF2::getVelNED(Vector3f &vel) const { - if (instance < 0 || instance >= num_cores) instance = primary; if (core) { - core[instance].getVelNED(vel); + core[primary].getVelNED(vel); } } // return estimate of true airspeed vector in body frame in m/s for the specified instance // An out of range instance (eg -1) returns data for the primary instance // returns false if estimate is unavailable -bool NavEKF2::getAirSpdVec(int8_t instance, Vector3f &vel) const +bool NavEKF2::getAirSpdVec(Vector3f &vel) const { - if (instance < 0 || instance >= num_cores) instance = primary; if (core) { - return core[instance].getAirSpdVec(vel); + return core[primary].getAirSpdVec(vel); } return false; } // Return the rate of change of vertical position in the down direction (dPosD/dt) in m/s -float NavEKF2::getPosDownDerivative(int8_t instance) const +float NavEKF2::getPosDownDerivative() const { - if (instance < 0 || instance >= num_cores) instance = primary; // return the value calculated from a complementary filter applied to the EKF height and vertical acceleration if (core) { - return core[instance].getPosDownDerivative(); + return core[primary].getPosDownDerivative(); } return 0.0f; } // return body axis gyro bias estimates in rad/sec -void NavEKF2::getGyroBias(int8_t instance, Vector3f &gyroBias) const +void NavEKF2::getGyroBias(Vector3f &gyroBias) const { - if (instance < 0 || instance >= num_cores) instance = primary; if (core) { - core[instance].getGyroBias(gyroBias); - } -} - -// return body axis gyro scale factor error as a percentage -void NavEKF2::getGyroScaleErrorPercentage(int8_t instance, Vector3f &gyroScale) const -{ - if (instance < 0 || instance >= num_cores) instance = primary; - if (core) { - core[instance].getGyroScaleErrorPercentage(gyroScale); + core[primary].getGyroBias(gyroBias); } } @@ -1031,38 +1016,34 @@ void NavEKF2::getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainSca } // return the individual Z-accel bias estimates in m/s^2 -void NavEKF2::getAccelZBias(int8_t instance, float &zbias) const +void NavEKF2::getAccelZBias(float &zbias) const { - if (instance < 0 || instance >= num_cores) instance = primary; if (core) { - core[instance].getAccelZBias(zbias); + core[primary].getAccelZBias(zbias); } } // return the NED wind speed estimates in m/s (positive is air moving in the direction of the axis) -void NavEKF2::getWind(int8_t instance, Vector3f &wind) const +void NavEKF2::getWind(Vector3f &wind) const { - if (instance < 0 || instance >= num_cores) instance = primary; if (core) { - core[instance].getWind(wind); + core[primary].getWind(wind); } } // return earth magnetic field estimates in measurement units / 1000 -void NavEKF2::getMagNED(int8_t instance, Vector3f &magNED) const +void NavEKF2::getMagNED(Vector3f &magNED) const { - if (instance < 0 || instance >= num_cores) instance = primary; if (core) { - core[instance].getMagNED(magNED); + core[primary].getMagNED(magNED); } } // return body magnetic field estimates in measurement units / 1000 -void NavEKF2::getMagXYZ(int8_t instance, Vector3f &magXYZ) const +void NavEKF2::getMagXYZ(Vector3f &magXYZ) const { - if (instance < 0 || instance >= num_cores) instance = primary; if (core) { - core[instance].getMagXYZ(magXYZ); + core[primary].getMagXYZ(magXYZ); } } @@ -1101,13 +1082,12 @@ bool NavEKF2::getLLH(struct Location &loc) const // An out of range instance (eg -1) returns data for the primary instance // All NED positions calculated by the filter are relative to this location // Returns false if the origin has not been set -bool NavEKF2::getOriginLLH(int8_t instance, struct Location &loc) const +bool NavEKF2::getOriginLLH(struct Location &loc) const { - if (instance < 0 || instance >= num_cores) instance = primary; if (!core) { return false; } - return core[instance].getOriginLLH(loc); + return core[primary].getOriginLLH(loc); } // set the latitude and longitude and height used to set the NED origin @@ -1148,11 +1128,10 @@ bool NavEKF2::getHAGL(float &HAGL) const } // return the Euler roll, pitch and yaw angle in radians for the specified instance -void NavEKF2::getEulerAngles(int8_t instance, Vector3f &eulers) const +void NavEKF2::getEulerAngles(Vector3f &eulers) const { - if (instance < 0 || instance >= num_cores) instance = primary; if (core) { - core[instance].getEulerAngles(eulers); + core[primary].getEulerAngles(eulers); } } @@ -1176,35 +1155,31 @@ void NavEKF2::getQuaternionBodyToNED(int8_t instance, Quaternion &quat) const } // return the quaternions defining the rotation from NED to XYZ (autopilot) axes -void NavEKF2::getQuaternion(int8_t instance, Quaternion &quat) const +void NavEKF2::getQuaternion(Quaternion &quat) const { - if (instance < 0 || instance >= num_cores) instance = primary; if (core) { - core[instance].getQuaternion(quat); + core[primary].getQuaternion(quat); } } // return the innovations for the specified instance -bool NavEKF2::getInnovations(int8_t instance, Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const +bool NavEKF2::getInnovations(Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const { if (core == nullptr) { return false; } - if (instance < 0 || instance >= num_cores) instance = primary; - - return core[instance].getInnovations(velInnov, posInnov, magInnov, tasInnov, yawInnov); + return core[primary].getInnovations(velInnov, posInnov, magInnov, tasInnov, yawInnov); } // return the innovation consistency test ratios for the velocity, position, magnetometer and true airspeed measurements -bool NavEKF2::getVariances(int8_t instance, float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const +bool NavEKF2::getVariances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const { if (core == nullptr) { return false; } - if (instance < 0 || instance >= num_cores) instance = primary; - return core[instance].getVariances(velVar, posVar, hgtVar, magVar, tasVar, offset); + return core[primary].getVariances(velVar, posVar, hgtVar, magVar, tasVar, offset); } // should we use the compass? This is public so it can be used for @@ -1265,11 +1240,10 @@ void NavEKF2::setTerrainHgtStable(bool val) 6 = badly conditioned synthetic sideslip fusion 7 = filter is not initialised */ -void NavEKF2::getFilterFaults(int8_t instance, uint16_t &faults) const +void NavEKF2::getFilterFaults(uint16_t &faults) const { - if (instance < 0 || instance >= num_cores) instance = primary; if (core) { - core[instance].getFilterFaults(faults); + core[primary].getFilterFaults(faults); } else { faults = 0; } @@ -1278,11 +1252,10 @@ void NavEKF2::getFilterFaults(int8_t instance, uint16_t &faults) const /* return filter status flags */ -void NavEKF2::getFilterStatus(int8_t instance, nav_filter_status &status) const +void NavEKF2::getFilterStatus(nav_filter_status &status) const { - if (instance < 0 || instance >= num_cores) instance = primary; if (core) { - core[instance].getFilterStatus(status); + core[primary].getFilterStatus(status); } else { memset(&status, 0, sizeof(status)); } @@ -1291,21 +1264,20 @@ void NavEKF2::getFilterStatus(int8_t instance, nav_filter_status &status) const /* return filter gps quality check status */ -void NavEKF2::getFilterGpsStatus(int8_t instance, nav_gps_status &status) const +void NavEKF2::getFilterGpsStatus(nav_gps_status &status) const { - if (instance < 0 || instance >= num_cores) instance = primary; if (core) { - core[instance].getFilterGpsStatus(status); + core[primary].getFilterGpsStatus(status); } else { memset(&status, 0, sizeof(status)); } } // send an EKF_STATUS_REPORT message to GCS -void NavEKF2::send_status_report(mavlink_channel_t chan) const +void NavEKF2::send_status_report(GCS_MAVLINK &link) const { if (core) { - core[primary].send_status_report(chan); + core[primary].send_status_report(link); } } @@ -1601,7 +1573,7 @@ void NavEKF2::writeExtNavVelData(const Vector3f &vel, float err, uint32_t timeSt } } -// get a yaw estimator instance +// get yaw estimator instance const EKFGSF_yaw *NavEKF2::get_yawEstimator(void) const { if (core) { diff --git a/libraries/AP_NavEKF2/AP_NavEKF2.h b/libraries/AP_NavEKF2/AP_NavEKF2.h index a1f5b1a123d..8f475a06b11 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2.h +++ b/libraries/AP_NavEKF2/AP_NavEKF2.h @@ -25,7 +25,6 @@ #include #include #include -#include #include class NavEKF2_core; @@ -68,40 +67,30 @@ class NavEKF2 { // return -1 if no primary core selected int8_t getPrimaryCoreIMUIndex(void) const; - // Write the last calculated NE position relative to the reference point (m) for the specified instance. - // An out of range instance (eg -1) returns data for the primary instance + // Write the last calculated NE position relative to the reference point (m) // If a calculated solution is not available, use the best available data and return false // If false returned, do not use for flight control - bool getPosNE(int8_t instance, Vector2f &posNE) const; + bool getPosNE(Vector2f &posNE) const; - // Write the last calculated D position relative to the reference point (m) for the specified instance. - // An out of range instance (eg -1) returns data for the primary instance + // Write the last calculated D position relative to the reference point (m) // If a calculated solution is not available, use the best available data and return false // If false returned, do not use for flight control - bool getPosD(int8_t instance, float &posD) const; + bool getPosD(float &posD) const; - // return NED velocity in m/s for the specified instance - // An out of range instance (eg -1) returns data for the primary instance - void getVelNED(int8_t instance, Vector3f &vel) const; + // return NED velocity in m/s + void getVelNED(Vector3f &vel) const; - // return estimate of true airspeed vector in body frame in m/s for the specified instance - // An out of range instance (eg -1) returns data for the primary instance + // return estimate of true airspeed vector in body frame in m/s // returns false if estimate is unavailable - bool getAirSpdVec(int8_t instance, Vector3f &vel) const; + bool getAirSpdVec(Vector3f &vel) const; - // Return the rate of change of vertical position in the down direction (dPosD/dt) in m/s for the specified instance - // An out of range instance (eg -1) returns data for the primary instance + // Return the rate of change of vertical position in the down direction (dPosD/dt) in m/s // This can be different to the z component of the EKF velocity state because it will fluctuate with height errors and corrections in the EKF // but will always be kinematically consistent with the z component of the EKF position state - float getPosDownDerivative(int8_t instance) const; - - // return body axis gyro bias estimates in rad/sec for the specified instance - // An out of range instance (eg -1) returns data for the primary instance - void getGyroBias(int8_t instance, Vector3f &gyroBias) const; + float getPosDownDerivative() const; - // return body axis gyro scale factor error as a percentage for the specified instance - // An out of range instance (eg -1) returns data for the primary instance - void getGyroScaleErrorPercentage(int8_t instance, Vector3f &gyroScale) const; + // return body axis gyro bias estimates in rad/sec + void getGyroBias(Vector3f &gyroBias) const; // reset body axis gyro bias estimates void resetGyroBias(void); @@ -119,19 +108,19 @@ class NavEKF2 { // return the Z-accel bias estimate in m/s^2 for the specified instance // An out of range instance (eg -1) returns data for the primary instance - void getAccelZBias(int8_t instance, float &zbias) const; + void getAccelZBias(float &zbias) const; // return the NED wind speed estimates in m/s (positive is air moving in the direction of the axis) // An out of range instance (eg -1) returns data for the primary instance - void getWind(int8_t instance, Vector3f &wind) const; + void getWind(Vector3f &wind) const; // return earth magnetic field estimates in measurement units / 1000 for the specified instance // An out of range instance (eg -1) returns data for the primary instance - void getMagNED(int8_t instance, Vector3f &magNED) const; + void getMagNED(Vector3f &magNED) const; // return body magnetic field estimates in measurement units / 1000 for the specified instance // An out of range instance (eg -1) returns data for the primary instance - void getMagXYZ(int8_t instance, Vector3f &magXYZ) const; + void getMagXYZ(Vector3f &magXYZ) const; // Return estimated magnetometer offsets // Return true if magnetometer offsets are valid @@ -147,7 +136,7 @@ class NavEKF2 { // An out of range instance (eg -1) returns data for the primary instance // All NED positions calculated by the filter are relative to this location // Returns false if the origin has not been set - bool getOriginLLH(int8_t instance, struct Location &loc) const; + bool getOriginLLH(struct Location &loc) const; // set the latitude and longitude and height used to set the NED origin // All NED positions calculated by the filter will be relative to this location @@ -161,7 +150,7 @@ class NavEKF2 { // return the Euler roll, pitch and yaw angle in radians for the specified instance // An out of range instance (eg -1) returns data for the primary instance - void getEulerAngles(int8_t instance, Vector3f &eulers) const; + void getEulerAngles(Vector3f &eulers) const; // return the transformation matrix from XYZ (body) to NED axes void getRotationBodyToNED(Matrix3f &mat) const; @@ -170,15 +159,15 @@ class NavEKF2 { void getQuaternionBodyToNED(int8_t instance, Quaternion &quat) const; // return the quaternions defining the rotation from NED to autopilot axes - void getQuaternion(int8_t instance, Quaternion &quat) const; + void getQuaternion(Quaternion &quat) const; // return the innovations for the specified instance // An out of range instance (eg -1) returns data for the primary instance - bool getInnovations(int8_t index, Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const; + bool getInnovations(Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const; // return the innovation consistency test ratios for the specified instance // An out of range instance (eg -1) returns data for the primary instance - bool getVariances(int8_t instance, float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const; + bool getVariances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const; // should we use the compass? This is public so it can be used for // reporting via ahrs.use_compass() @@ -211,22 +200,22 @@ class NavEKF2 { 6 = badly conditioned synthetic sideslip fusion 7 = filter is not initialised */ - void getFilterFaults(int8_t instance, uint16_t &faults) const; + void getFilterFaults(uint16_t &faults) const; /* return filter gps quality check status for the specified instance An out of range instance (eg -1) returns data for the primary instance */ - void getFilterGpsStatus(int8_t instance, nav_gps_status &faults) const; + void getFilterGpsStatus(nav_gps_status &faults) const; /* return filter status flags for the specified instance An out of range instance (eg -1) returns data for the primary instance */ - void getFilterStatus(int8_t instance, nav_filter_status &status) const; + void getFilterStatus(nav_filter_status &status) const; // send an EKF_STATUS_REPORT message to GCS - void send_status_report(mavlink_channel_t chan) const; + void send_status_report(class GCS_MAVLINK &link) const; // provides the height limit to be observed by the control loops // returns false if no height limiting is required diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_Logging.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_Logging.cpp index 72a5187113e..9f92a2eb01f 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_Logging.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_Logging.cpp @@ -170,7 +170,7 @@ void NavEKF2_core::Log_Write_NKF5(uint64_t time_us) const FIX : (int16_t)(1000*innovOptFlow[0]), // optical flow LOS rate vector innovations from the main nav filter FIY : (int16_t)(1000*innovOptFlow[1]), // optical flow LOS rate vector innovations from the main nav filter AFI : (int16_t)(1000 * auxFlowObsInnov.length()), // optical flow LOS rate innovation from terrain offset estimator - HAGL : (int16_t)(100*(terrainState - stateStruct.position.z)), // height above ground level + HAGL : float_to_int16(100*(terrainState - stateStruct.position.z)), // height above ground level offset : (int16_t)(100*terrainState), // // estimated vertical position of the terrain relative to the nav filter zero datum RI : (int16_t)(100*innovRng), // range finder innovations meaRng : (uint16_t)(100*rangeDataDelayed.rng), // measured range diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp index 0dd728669ed..a7847b9b075 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp @@ -4,6 +4,7 @@ #include #include #include +#include extern const AP_HAL::HAL& hal; diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp index aedf27f06db..aadafd00d9d 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp @@ -3,6 +3,7 @@ #include "AP_NavEKF2_core.h" #include #include +#include extern const AP_HAL::HAL& hal; @@ -285,9 +286,7 @@ bool NavEKF2_core::getLLH(struct Location &loc) const if(getPosD(posD) && getOriginLLH(origin)) { // Altitude returned is an absolute altitude relative to the WGS-84 spherioid - loc.alt = origin.alt - posD*100; - loc.relative_alt = 0; - loc.terrain_alt = 0; + loc.set_alt_cm(origin.alt - posD*100, Location::AltFrame::ABSOLUTE); // there are three modes of operation, absolute position (GPS fusion), relative position (optical flow fusion) and constant position (no aiding) if (filterStatus.flags.horiz_pos_abs || filterStatus.flags.horiz_pos_rel) { @@ -322,10 +321,7 @@ bool NavEKF2_core::getLLH(struct Location &loc) const // If no origin has been defined for the EKF, then we cannot use its position states so return a raw // GPS reading if available and return false if ((gps.status() >= AP_DAL_GPS::GPS_OK_FIX_3D)) { - const struct Location &gpsloc = gps.location(); - loc = gpsloc; - loc.relative_alt = 0; - loc.terrain_alt = 0; + loc = gps.location(); } return false; } @@ -497,8 +493,9 @@ void NavEKF2_core::getFilterGpsStatus(nav_gps_status &faults) const faults.flags.bad_horiz_vel = gpsCheckStatus.bad_horiz_vel; // The GPS horizontal speed is excessive (check assumes the vehicle is static) } +#if HAL_GCS_ENABLED // send an EKF_STATUS message to GCS -void NavEKF2_core::send_status_report(mavlink_channel_t chan) const +void NavEKF2_core::send_status_report(GCS_MAVLINK &link) const { // prepare flags uint16_t flags = 0; @@ -555,8 +552,9 @@ void NavEKF2_core::send_status_report(mavlink_channel_t chan) const } // send message - mavlink_msg_ekf_status_report_send(chan, flags, velVar, posVar, hgtVar, mag_max, temp, tasVar); + mavlink_msg_ekf_status_report_send(link.get_chan(), flags, velVar, posVar, hgtVar, mag_max, temp, tasVar); } +#endif // HAL_GCS_ENABLED // report the reason for why the backend is refusing to initialise const char *NavEKF2_core::prearm_failure_reason(void) const diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_core.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_core.cpp index 9be77903f7e..45bcc369a33 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_core.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_core.cpp @@ -598,7 +598,7 @@ void NavEKF2_core::UpdateFilter(bool predict) static uint32_t timing_counter; total_us += dal.micros() - timing_start_us; if (timing_counter++ == 4000) { - hal.console->printf("ekf2 avg %.2f us\n", total_us / float(timing_counter)); + DEV_PRINTF("ekf2 avg %.2f us\n", total_us / float(timing_counter)); total_us = 0; timing_counter = 0; } diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_core.h b/libraries/AP_NavEKF2/AP_NavEKF2_core.h index e8987499e7a..1a2dc6e8400 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_core.h +++ b/libraries/AP_NavEKF2/AP_NavEKF2_core.h @@ -29,7 +29,6 @@ #include #include #include -#include #include #include "AP_NavEKF/EKFGSF_yaw.h" @@ -247,7 +246,7 @@ class NavEKF2_core : public NavEKF_core_common void getFilterStatus(nav_filter_status &status) const; // send an EKF_STATUS_REPORT message to GCS - void send_status_report(mavlink_channel_t chan) const; + void send_status_report(class GCS_MAVLINK &link) const; // provides the height limit to be observed by the control loops // returns false if no height limiting is required diff --git a/libraries/AP_NavEKF3/AP_NavEKF3.cpp b/libraries/AP_NavEKF3/AP_NavEKF3.cpp index 815c113b1c8..54c59b5bd48 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3.cpp @@ -25,7 +25,7 @@ #define GYRO_P_NSE_DEFAULT 1.5E-02f #define ACC_P_NSE_DEFAULT 3.5E-01f #define GBIAS_P_NSE_DEFAULT 1.0E-03f -#define ABIAS_P_NSE_DEFAULT 3.0E-03f +#define ABIAS_P_NSE_DEFAULT 2.0E-02f #define MAGB_P_NSE_DEFAULT 1.0E-04f #define MAGE_P_NSE_DEFAULT 1.0E-03f #define VEL_I_GATE_DEFAULT 500 @@ -51,7 +51,7 @@ #define GYRO_P_NSE_DEFAULT 1.5E-02f #define ACC_P_NSE_DEFAULT 3.5E-01f #define GBIAS_P_NSE_DEFAULT 1.0E-03f -#define ABIAS_P_NSE_DEFAULT 3.0E-03f +#define ABIAS_P_NSE_DEFAULT 2.0E-02f #define MAGB_P_NSE_DEFAULT 1.0E-04f #define MAGE_P_NSE_DEFAULT 1.0E-03f #define VEL_I_GATE_DEFAULT 500 @@ -77,7 +77,7 @@ #define GYRO_P_NSE_DEFAULT 1.5E-02f #define ACC_P_NSE_DEFAULT 3.5E-01f #define GBIAS_P_NSE_DEFAULT 1.0E-03f -#define ABIAS_P_NSE_DEFAULT 3.0E-03f +#define ABIAS_P_NSE_DEFAULT 2.0E-02f #define MAGB_P_NSE_DEFAULT 1.0E-04f #define MAGE_P_NSE_DEFAULT 1.0E-03f #define VEL_I_GATE_DEFAULT 500 @@ -103,7 +103,7 @@ #define GYRO_P_NSE_DEFAULT 1.5E-02f #define ACC_P_NSE_DEFAULT 3.5E-01f #define GBIAS_P_NSE_DEFAULT 1.0E-03f -#define ABIAS_P_NSE_DEFAULT 3.0E-03f +#define ABIAS_P_NSE_DEFAULT 2.0E-02f #define MAGB_P_NSE_DEFAULT 1.0E-04f #define MAGE_P_NSE_DEFAULT 1.0E-03f #define VEL_I_GATE_DEFAULT 500 @@ -664,7 +664,7 @@ const AP_Param::GroupInfo NavEKF3::var_info2[] = { // @Param: DRAG_BCOEF_X // @DisplayName: Ballistic coefficient for X axis drag - // @Description: Ratio of mass to drag coefficient measured along the X body axis. This parameter enables estimation of wind drift for vehicles with bluff bodies and without propulsion forces in the X and Y direction (eg multicopters). The drag produced by this effect scales with speed squared. Set to a postive value > 1.0 to enable. A starting value is the mass in Kg divided by the frontal area. The predicted drag from the rotors is specified separately by the EK3_MCOEF parameter. + // @Description: Ratio of mass to drag coefficient measured along the X body axis. This parameter enables estimation of wind drift for vehicles with bluff bodies and without propulsion forces in the X and Y direction (eg multicopters). The drag produced by this effect scales with speed squared. Set to a postive value > 1.0 to enable. A starting value is the mass in Kg divided by the frontal area. The predicted drag from the rotors is specified separately by the EK3_DRAG_MCOEF parameter. // @Range: 0.0 1000.0 // @Units: kg/m/m // @User: Advanced @@ -672,7 +672,7 @@ const AP_Param::GroupInfo NavEKF3::var_info2[] = { // @Param: DRAG_BCOEF_Y // @DisplayName: Ballistic coefficient for Y axis drag - // @Description: Ratio of mass to drag coefficient measured along the Y body axis. This parameter enables estimation of wind drift for vehicles with bluff bodies and without propulsion forces in the X and Y direction (eg multicopters). The drag produced by this effect scales with speed squared. Set to a postive value > 1.0 to enable. A starting value is the mass in Kg divided by the side area. The predicted drag from the rotors is specified separately by the EK3_MCOEF parameter. + // @Description: Ratio of mass to drag coefficient measured along the Y body axis. This parameter enables estimation of wind drift for vehicles with bluff bodies and without propulsion forces in the X and Y direction (eg multicopters). The drag produced by this effect scales with speed squared. Set to a postive value > 1.0 to enable. A starting value is the mass in Kg divided by the side area. The predicted drag from the rotors is specified separately by the EK3_DRAG_MCOEF parameter. // @Range: 50.0 1000.0 // @Units: kg/m/m // @User: Advanced @@ -680,7 +680,7 @@ const AP_Param::GroupInfo NavEKF3::var_info2[] = { // @Param: DRAG_M_NSE // @DisplayName: Observation noise for drag acceleration - // @Description: This sets the amount of noise used when fusing X and Y acceleration as an observation that enables esitmation of wind velocity for multi-rotor vehicles. This feature is enabled by the EK3_BCOEF_X and EK3_BCOEF_Y parameters + // @Description: This sets the amount of noise used when fusing X and Y acceleration as an observation that enables esitmation of wind velocity for multi-rotor vehicles. This feature is enabled by the EK3_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters // @Range: 0.1 2.0 // @Increment: 0.1 // @User: Advanced @@ -689,7 +689,7 @@ const AP_Param::GroupInfo NavEKF3::var_info2[] = { // @Param: DRAG_MCOEF // @DisplayName: Momentum coefficient for propeller drag - // @Description: This parameter is used to predict the drag produced by the rotors when flying a multi-copter, enabling estimation of wind drift. The drag produced by this effect scales with speed not speed squared and is produced because some of the air velocity normal to the rotors axis of rotation is lost when passing through the rotor disc which changes the momentum of the airflow causing drag. For unducted rotors the effect is roughly proportional to the area of the propeller blades when viewed side on and changes with different propellers. It is higher for ducted rotors. For example if flying at 15 m/s at sea level conditions produces a rotor induced drag acceleration of 1.5 m/s/s, then EK3_MCOEF would be set to 0.1 = (1.5/15.0). Set EK3_MCOEF to a postive value to enable wind estimation using this drag effect. To account for the drag produced by the body which scales with speed squared, see documentation for the EK3_BCOEF_X and EK3_BCOEF_Y parameters. + // @Description: This parameter is used to predict the drag produced by the rotors when flying a multi-copter, enabling estimation of wind drift. The drag produced by this effect scales with speed not speed squared and is produced because some of the air velocity normal to the rotors axis of rotation is lost when passing through the rotor disc which changes the momentum of the airflow causing drag. For unducted rotors the effect is roughly proportional to the area of the propeller blades when viewed side on and changes with different propellers. It is higher for ducted rotors. For example if flying at 15 m/s at sea level conditions produces a rotor induced drag acceleration of 1.5 m/s/s, then EK3_DRAG_MCOEF would be set to 0.1 = (1.5/15.0). Set EK3_MCOEF to a postive value to enable wind estimation using this drag effect. To account for the drag produced by the body which scales with speed squared, see documentation for the EK3_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters. // @Range: 0.0 1.0 // @Increment: 0.01 // @Units: 1/s @@ -706,7 +706,7 @@ const AP_Param::GroupInfo NavEKF3::var_info2[] = { // @Param: GND_EFF_DZ // @DisplayName: Baro height ground effect dead zone - // @Description: This parameter sets the size of the dead zone that is applied to negative baro height spikes that can occur when takeing off or landing when a vehicle with lift rotors is operating in ground effect ground effect. Set to about 0.5m less than the amount of negative offset in baro height that occurs just prior to takeoff when lift motors are spooling up. Set to 0 if no ground effect is present. + // @Description: This parameter sets the size of the dead zone that is applied to negative baro height spikes that can occur when taking off or landing when a vehicle with lift rotors is operating in ground effect ground effect. Set to about 0.5m less than the amount of negative offset in baro height that occurs just prior to takeoff when lift motors are spooling up. Set to 0 if no ground effect is present. // @Range: 0.0 10.0 // @Increment: 0.5 // @User: Advanced @@ -719,7 +719,24 @@ const AP_Param::GroupInfo NavEKF3::var_info2[] = { // @Increment: 1 // @User: Advanced AP_GROUPINFO("PRIMARY", 8, NavEKF3, _primary_core, EK3_PRIMARY_DEFAULT), + + // @Param: LOG_LEVEL + // @DisplayName: Logging Level + // @Description: Determines how verbose the EKF3 streaming logging is. A value of 0 provides full logging(default), a value of 1 only XKF4 scaled innovations are logged, a value of 2 both XKF4 and GSF are logged, and a value of 3 disables all streaming logging of EKF3. + // @Range: 0 3 + // @Increment: 1 + // @User: Advanced + AP_GROUPINFO("LOG_LEVEL", 9, NavEKF3, _log_level, 0), + // @Param: GPS_VACC_MAX + // @DisplayName: GPS vertical accuracy threshold + // @Description: Vertical accuracy threshold for GPS as the altitude source. The GPS will not be used as an altitude source if the reported vertical accuracy of the GPS is larger than this threshold, falling back to baro instead. Set to zero to deactivate the threshold check. + // @Range: 0.0 10.0 + // @Increment: 0.1 + // @User: Advanced + // @Units: m + AP_GROUPINFO("GPS_VACC_MAX", 10, NavEKF3, _gpsVAccThreshold, 0.0f), + AP_GROUPEND }; @@ -1083,6 +1100,9 @@ void NavEKF3::resetCoreErrors(void) // set position, velocity and yaw sources to either 0=primary, 1=secondary, 2=tertiary void NavEKF3::setPosVelYawSourceSet(uint8_t source_set_idx) { + if (source_set_idx < AP_NAKEKF_SOURCE_SET_MAX) { + AP::dal().log_event3(AP_DAL::Event(uint8_t(AP_DAL::Event::setSourceSet0)+source_set_idx)); + } sources.setPosVelYawSourceSet(source_set_idx); } @@ -1154,55 +1174,58 @@ int8_t NavEKF3::getPrimaryCoreIMUIndex(void) const // Write the last calculated NE position relative to the reference point (m). // If a calculated solution is not available, use the best available data and return false // If false returned, do not use for flight control -bool NavEKF3::getPosNE(int8_t instance, Vector2f &posNE) const +bool NavEKF3::getPosNE(Vector2f &posNE) const { - if (instance < 0 || instance >= num_cores) instance = primary; if (!core) { return false; } - return core[instance].getPosNE(posNE); + return core[primary].getPosNE(posNE); } // Write the last calculated D position relative to the reference point (m). // If a calculated solution is not available, use the best available data and return false // If false returned, do not use for flight control -bool NavEKF3::getPosD(int8_t instance, float &posD) const +bool NavEKF3::getPosD(float &posD) const { - if (instance < 0 || instance >= num_cores) instance = primary; if (!core) { return false; } - return core[instance].getPosD(posD); + return core[primary].getPosD(posD); } // return NED velocity in m/s -void NavEKF3::getVelNED(int8_t instance, Vector3f &vel) const +void NavEKF3::getVelNED(Vector3f &vel) const { - if (instance < 0 || instance >= num_cores) instance = primary; if (core) { - core[instance].getVelNED(vel); + core[primary].getVelNED(vel); } } -// return estimate of true airspeed vector in body frame in m/s for the specified instance -// An out of range instance (eg -1) returns data for the primary instance +// return estimate of true airspeed vector in body frame in m/s // returns false if estimate is unavailable -bool NavEKF3::getAirSpdVec(int8_t instance, Vector3f &vel) const +bool NavEKF3::getAirSpdVec(Vector3f &vel) const { - if (instance < 0 || instance >= num_cores) instance = primary; if (core) { - return core[instance].getAirSpdVec(vel); + return core[primary].getAirSpdVec(vel); + } + return false; +} + +// return the innovation in m/s, innovation variance in (m/s)^2 and age in msec of the last TAS measurement processed +bool NavEKF3::getAirSpdHealthData(float &innovation, float &innovationVariance, uint32_t &age_ms) const +{ + if (core) { + return core[primary].getAirSpdHealthData(innovation, innovationVariance, age_ms); } return false; } // Return the rate of change of vertical position in the down direction (dPosD/dt) in m/s -float NavEKF3::getPosDownDerivative(int8_t instance) const +float NavEKF3::getPosDownDerivative() const { - if (instance < 0 || instance >= num_cores) instance = primary; // return the value calculated from a complementary filter applied to the EKF height and vertical acceleration if (core) { - return core[instance].getPosDownDerivative(); + return core[primary].getPosDownDerivative(); } return 0.0f; } @@ -1225,6 +1248,12 @@ void NavEKF3::getAccelBias(int8_t instance, Vector3f &accelBias) const } } +// returns active source set used by EKF3 +uint8_t NavEKF3::get_active_source_set() const +{ + return sources.get_active_source_set(); +} + // reset body axis gyro bias estimates void NavEKF3::resetGyroBias(void) { @@ -1273,40 +1302,35 @@ void NavEKF3::getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainSca // return the NED wind speed estimates in m/s (positive is air moving in the direction of the axis) // returns true if wind state estimation is active -bool NavEKF3::getWind(int8_t instance, Vector3f &wind) const +bool NavEKF3::getWind(Vector3f &wind) const { - bool ret = false; - if (instance < 0 || instance >= num_cores) instance = primary; - if (core) { - ret = core[instance].getWind(wind); + if (core == nullptr) { + return false; } - return ret; + return core[primary].getWind(wind); } // return earth magnetic field estimates in measurement units / 1000 -void NavEKF3::getMagNED(int8_t instance, Vector3f &magNED) const +void NavEKF3::getMagNED(Vector3f &magNED) const { - if (instance < 0 || instance >= num_cores) instance = primary; if (core) { - core[instance].getMagNED(magNED); + core[primary].getMagNED(magNED); } } // return body magnetic field estimates in measurement units / 1000 -void NavEKF3::getMagXYZ(int8_t instance, Vector3f &magXYZ) const +void NavEKF3::getMagXYZ(Vector3f &magXYZ) const { - if (instance < 0 || instance >= num_cores) instance = primary; if (core) { - core[instance].getMagXYZ(magXYZ); + core[primary].getMagXYZ(magXYZ); } } -// return the airspeed sensor in use for the specified instance -uint8_t NavEKF3::getActiveAirspeed(int8_t instance) const +// return the airspeed sensor in use +uint8_t NavEKF3::getActiveAirspeed() const { - if (instance < 0 || instance >= num_cores) instance = primary; if (core) { - return core[instance].getActiveAirspeed(); + return core[primary].getActiveAirspeed(); } else { return 255; } @@ -1343,17 +1367,19 @@ bool NavEKF3::getLLH(struct Location &loc) const return core[primary].getLLH(loc); } -// Return the latitude and longitude and height used to set the NED origin for the specified instance -// An out of range instance (eg -1) returns data for the primary instance +// Return the latitude and longitude and height used to set the NED origin // All NED positions calculated by the filter are relative to this location // Returns false if the origin has not been set -bool NavEKF3::getOriginLLH(int8_t instance, struct Location &loc) const +bool NavEKF3::getOriginLLH(struct Location &loc) const { - if (instance < 0 || instance >= num_cores) instance = primary; if (!core) { return false; } - return core[instance].getOriginLLH(loc); + if (common_origin_valid) { + loc = common_EKF_origin; + return true; + } + return core[primary].getOriginLLH(loc); } // set the latitude and longitude and height used to set the NED origin @@ -1393,12 +1419,11 @@ bool NavEKF3::getHAGL(float &HAGL) const return core[primary].getHAGL(HAGL); } -// return the Euler roll, pitch and yaw angle in radians for the specified instance -void NavEKF3::getEulerAngles(int8_t instance, Vector3f &eulers) const +// return the Euler roll, pitch and yaw angle in radians +void NavEKF3::getEulerAngles(Vector3f &eulers) const { - if (instance < 0 || instance >= num_cores) instance = primary; if (core) { - core[instance].getEulerAngles(eulers); + core[primary].getEulerAngles(eulers); } } @@ -1422,45 +1447,39 @@ void NavEKF3::getQuaternionBodyToNED(int8_t instance, Quaternion &quat) const } // return the quaternions defining the rotation from NED to XYZ (autopilot) axes -void NavEKF3::getQuaternion(int8_t instance, Quaternion &quat) const +void NavEKF3::getQuaternion(Quaternion &quat) const { - if (instance < 0 || instance >= num_cores) instance = primary; if (core) { - core[instance].getQuaternion(quat); + core[primary].getQuaternion(quat); } } -// return the innovations for the specified instance -bool NavEKF3::getInnovations(int8_t instance, Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const +// return the innovations +bool NavEKF3::getInnovations(Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const { if (core == nullptr) { return false; } - if (instance < 0 || instance >= num_cores) instance = primary; - return core[instance].getInnovations(velInnov, posInnov, magInnov, tasInnov, yawInnov); + return core[primary].getInnovations(velInnov, posInnov, magInnov, tasInnov, yawInnov); } // return the innovation consistency test ratios for the velocity, position, magnetometer and true airspeed measurements -bool NavEKF3::getVariances(int8_t instance, float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const +bool NavEKF3::getVariances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const { if (core == nullptr) { return false; } - if (instance < 0 || instance >= num_cores) instance = primary; - return core[instance].getVariances(velVar, posVar, hgtVar, magVar, tasVar, offset); + return core[primary].getVariances(velVar, posVar, hgtVar, magVar, tasVar, offset); } -// get a source's velocity innovations for the specified instance. Set instance to -1 for the primary instance +// get a source's velocity innovations // returns true on success and results are placed in innovations and variances arguments -bool NavEKF3::getVelInnovationsAndVariancesForSource(int8_t instance, AP_NavEKF_Source::SourceXY source, Vector3f &innovations, Vector3f &variances) const +bool NavEKF3::getVelInnovationsAndVariancesForSource(AP_NavEKF_Source::SourceXY source, Vector3f &innovations, Vector3f &variances) const { - if (instance < 0 || instance >= num_cores) { - instance = primary; - } if (core) { - return core[instance].getVelInnovationsAndVariancesForSource(source, innovations, variances); + return core[primary].getVelInnovationsAndVariancesForSource(source, innovations, variances); } return false; } @@ -1544,7 +1563,7 @@ void NavEKF3::writeEulerYawAngle(float yawAngle, float yawAngleErr, uint32_t tim * Write position and quaternion data from an external navigation system * * pos : XYZ position (m) in a RH navigation frame with the Z axis pointing down and XY axes horizontal. Frame must be aligned with NED if the magnetomer is being used for yaw. - * quat : quaternion describing the the rotation from navigation frame to body frame + * quat : quaternion describing the rotation from navigation frame to body frame * posErr : 1-sigma spherical position error (m) * angErr : 1-sigma spherical angle error (rad) * timeStamp_ms : system time the measurement was taken, not the time it was received (mSec) @@ -1626,7 +1645,7 @@ void NavEKF3::writeWheelOdom(float delAng, float delTime, uint32_t timeStamp_ms, void NavEKF3::convert_parameters() { // exit immediately if param conversion has been done before - if (sources.configured_in_storage()) { + if (sources.configured()) { return; } @@ -1663,12 +1682,12 @@ void NavEKF3::convert_parameters() case 3: default: // EK3_GPS_TYPE == 3 (No GPS) we don't know what to do, could be optical flow, beacon or external nav - sources.mark_configured_in_storage(); + sources.mark_configured(); break; } } else { // mark configured in storage so conversion is only run once - sources.mark_configured_in_storage(); + sources.mark_configured(); } // use EK3_ALT_SOURCE to set EK3_SRC1_POSZ @@ -1754,11 +1773,10 @@ void NavEKF3::setTerrainHgtStable(bool val) 6 = badly conditioned synthetic sideslip fusion 7 = filter is not initialised */ -void NavEKF3::getFilterFaults(int8_t instance, uint16_t &faults) const +void NavEKF3::getFilterFaults(uint16_t &faults) const { - if (instance < 0 || instance >= num_cores) instance = primary; if (core) { - core[instance].getFilterFaults(faults); + core[primary].getFilterFaults(faults); } else { faults = 0; } @@ -1767,21 +1785,20 @@ void NavEKF3::getFilterFaults(int8_t instance, uint16_t &faults) const /* return filter status flags */ -void NavEKF3::getFilterStatus(int8_t instance, nav_filter_status &status) const +void NavEKF3::getFilterStatus(nav_filter_status &status) const { - if (instance < 0 || instance >= num_cores) instance = primary; if (core) { - core[instance].getFilterStatus(status); + core[primary].getFilterStatus(status); } else { memset(&status, 0, sizeof(status)); } } // send an EKF_STATUS_REPORT message to GCS -void NavEKF3::send_status_report(mavlink_channel_t chan) const +void NavEKF3::send_status_report(GCS_MAVLINK &link) const { if (core) { - core[primary].send_status_report(chan); + core[primary].send_status_report(link); } } @@ -1990,8 +2007,8 @@ void NavEKF3::updateLaneSwitchPosDownResetData(uint8_t new_primary, uint8_t old_ // Record the position delta between current core and new primary core and the timestamp of the core change // Add current delta in case it hasn't been consumed yet - core[old_primary].getPosD(posDownOldPrimary); - core[new_primary].getPosD(posDownNewPrimary); + core[old_primary].getPosD_local(posDownOldPrimary); + core[new_primary].getPosD_local(posDownNewPrimary); pos_down_reset_data.core_delta = posDownNewPrimary - posDownOldPrimary + pos_down_reset_data.core_delta; pos_down_reset_data.last_primary_change = imuSampleTime_us / 1000; pos_down_reset_data.core_changed = true; @@ -2019,14 +2036,11 @@ bool NavEKF3::yawAlignmentComplete(void) const return core[primary].have_aligned_yaw(); } -// returns true when the state estimates for the selected core are significantly degraded by vibration -bool NavEKF3::isVibrationAffected(int8_t instance) const +// returns true when the state estimates are significantly degraded by vibration +bool NavEKF3::isVibrationAffected() const { - if (instance < 0 || instance >= num_cores) { - instance = primary; - } if (core) { - return core[instance].isVibrationAffected(); + return core[primary].isVibrationAffected(); } return false; } diff --git a/libraries/AP_NavEKF3/AP_NavEKF3.h b/libraries/AP_NavEKF3/AP_NavEKF3.h index 68f12a04b88..2d14a44975a 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3.h +++ b/libraries/AP_NavEKF3/AP_NavEKF3.h @@ -22,7 +22,6 @@ #include #include #include -#include #include #include @@ -68,32 +67,31 @@ class NavEKF3 { // return -1 if no primary core selected int8_t getPrimaryCoreIMUIndex(void) const; - // Write the last calculated NE position relative to the reference point (m) for the specified instance. - // An out of range instance (eg -1) returns data for the primary instance + // Write the last calculated NE position relative to the reference point (m) // If a calculated solution is not available, use the best available data and return false // If false returned, do not use for flight control - bool getPosNE(int8_t instance, Vector2f &posNE) const; + bool getPosNE(Vector2f &posNE) const; - // Write the last calculated D position relative to the reference point (m) for the specified instance. - // An out of range instance (eg -1) returns data for the primary instance + // Write the last calculated D position relative to the reference point (m) // If a calculated solution is not available, use the best available data and return false // If false returned, do not use for flight control - bool getPosD(int8_t instance, float &posD) const; + bool getPosD(float &posD) const; - // return NED velocity in m/s for the specified instance - // An out of range instance (eg -1) returns data for the primary instance - void getVelNED(int8_t instance, Vector3f &vel) const; + // return NED velocity in m/s + void getVelNED(Vector3f &vel) const; - // return estimate of true airspeed vector in body frame in m/s for the specified instance - // An out of range instance (eg -1) returns data for the primary instance + // return estimate of true airspeed vector in body frame in m/s // returns false if estimate is unavailable - bool getAirSpdVec(int8_t instance, Vector3f &vel) const; + bool getAirSpdVec(Vector3f &vel) const; - // Return the rate of change of vertical position in the down direction (dPosD/dt) in m/s for the specified instance - // An out of range instance (eg -1) returns data for the primary instance + // return the innovation in m/s, innovation variance in (m/s)^2 and age in msec of the last TAS measurement processed + // returns false if the data is unavilable + bool getAirSpdHealthData(float &innovation, float &innovationVariance, uint32_t &age_ms) const; + + // Return the rate of change of vertical position in the down direction (dPosD/dt) in m/s // This can be different to the z component of the EKF velocity state because it will fluctuate with height errors and corrections in the EKF // but will always be kinematically consistent with the z component of the EKF position state - float getPosDownDerivative(int8_t instance) const; + float getPosDownDerivative() const; // return body axis gyro bias estimates in rad/sec for the specified instance // An out of range instance (eg -1) returns data for the primary instance @@ -103,6 +101,9 @@ class NavEKF3 { // An out of range instance (eg -1) returns data for the primary instance void getAccelBias(int8_t instance, Vector3f &accelBias) const; + //returns index of the active source set used + uint8_t get_active_source_set() const; + // reset body axis gyro bias estimates void resetGyroBias(void); @@ -117,22 +118,19 @@ class NavEKF3 { // return the scale factor to be applied to navigation velocity gains to compensate for increase in velocity noise with height when using optical flow void getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const; - // return the NED wind speed estimates in m/s (positive is air moving in the direction of the axis) - // An out of range instance (eg -1) returns data for the the primary instance - // returns true if wind state estimation is active - bool getWind(int8_t instance, Vector3f &wind) const; + // return the NED wind speed estimates in m/s (positive is air + // moving in the direction of the axis) returns true if wind state + // estimation is active + bool getWind(Vector3f &wind) const; - // return earth magnetic field estimates in measurement units / 1000 for the specified instance - // An out of range instance (eg -1) returns data for the primary instance - void getMagNED(int8_t instance, Vector3f &magNED) const; + // return earth magnetic field estimates in measurement units / 1000 + void getMagNED(Vector3f &magNED) const; - // return body magnetic field estimates in measurement units / 1000 for the specified instance - // An out of range instance (eg -1) returns data for the primary instance - void getMagXYZ(int8_t instance, Vector3f &magXYZ) const; + // return body magnetic field estimates in measurement units / 1000 + void getMagXYZ(Vector3f &magXYZ) const; - // return the sensor in use for the specified instance - // An out of range instance (eg -1) returns data for the primary instance - uint8_t getActiveAirspeed(int8_t instance) const; + // return the airspeed sensor in use + uint8_t getActiveAirspeed() const; // Return estimated magnetometer offsets // Return true if magnetometer offsets are valid @@ -144,11 +142,10 @@ class NavEKF3 { // The getFilterStatus() function provides a more detailed description of data health and must be checked if data is to be used for flight control bool getLLH(struct Location &loc) const; - // Return the latitude and longitude and height used to set the NED origin for the specified instance - // An out of range instance (eg -1) returns data for the primary instance + // Return the latitude and longitude and height used to set the NED origin // All NED positions calculated by the filter are relative to this location // Returns false if the origin has not been set - bool getOriginLLH(int8_t instance, struct Location &loc) const; + bool getOriginLLH(struct Location &loc) const; // set the latitude and longitude and height used to set the NED origin // All NED positions calculated by the filter will be relative to this location @@ -160,9 +157,8 @@ class NavEKF3 { // return false if ground height is not being estimated. bool getHAGL(float &HAGL) const; - // return the Euler roll, pitch and yaw angle in radians for the specified instance - // An out of range instance (eg -1) returns data for the primary instance - void getEulerAngles(int8_t instance, Vector3f &eulers) const; + // return the Euler roll, pitch and yaw angle in radians + void getEulerAngles(Vector3f &eulers) const; // return the transformation matrix from XYZ (body) to NED axes void getRotationBodyToNED(Matrix3f &mat) const; @@ -171,19 +167,17 @@ class NavEKF3 { void getQuaternionBodyToNED(int8_t instance, Quaternion &quat) const; // return the quaternions defining the rotation from NED to XYZ (autopilot) axes - void getQuaternion(int8_t instance, Quaternion &quat) const; + void getQuaternion(Quaternion &quat) const; - // return the innovations for the specified instance - // An out of range instance (eg -1) returns data for the primary instance - bool getInnovations(int8_t index, Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const; + // return the innovations + bool getInnovations(Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const; - // return the innovation consistency test ratios for the specified instance - // An out of range instance (eg -1) returns data for the primary instance - bool getVariances(int8_t instance, float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const; + // return the innovation consistency test ratios + bool getVariances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const; - // get a source's velocity innovations for the specified instance. Set instance to -1 for the primary instance + // get a source's velocity innovations // returns true on success and results are placed in innovations and variances arguments - bool getVelInnovationsAndVariancesForSource(int8_t instance, AP_NavEKF_Source::SourceXY source, Vector3f &innovations, Vector3f &variances) const WARN_IF_UNUSED; + bool getVelInnovationsAndVariancesForSource(AP_NavEKF_Source::SourceXY source, Vector3f &innovations, Vector3f &variances) const WARN_IF_UNUSED; // should we use the compass? This is public so it can be used for // reporting via ahrs.use_compass() @@ -244,7 +238,7 @@ class NavEKF3 { * Write position and quaternion data from an external navigation system * * pos : position in the RH navigation frame. Frame is assumed to be NED if frameIsNED is true. (m) - * quat : quaternion desribing the the rotation from navigation frame to body frame + * quat : quaternion desribing the rotation from navigation frame to body frame * posErr : 1-sigma spherical position error (m) * angErr : 1-sigma spherical angle error (rad) * timeStamp_ms : system time the measurement was taken, not the time it was received (mSec) @@ -271,8 +265,7 @@ class NavEKF3 { void setTerrainHgtStable(bool val); /* - return the filter fault status as a bitmasked integer for the specified instance - An out of range instance (eg -1) returns data for the primary instance + return the filter fault status as a bitmasked integer 0 = quaternions are NaN 1 = velocities are NaN 2 = badly conditioned X magnetometer fusion @@ -282,16 +275,15 @@ class NavEKF3 { 6 = badly conditioned synthetic sideslip fusion 7 = filter is not initialised */ - void getFilterFaults(int8_t instance, uint16_t &faults) const; + void getFilterFaults(uint16_t &faults) const; /* - return filter status flags for the specified instance - An out of range instance (eg -1) returns data for the primary instance + return filter status flags */ - void getFilterStatus(int8_t instance, nav_filter_status &status) const; + void getFilterStatus(nav_filter_status &status) const; // send an EKF_STATUS_REPORT message to GCS - void send_status_report(mavlink_channel_t chan) const; + void send_status_report(class GCS_MAVLINK &link) const; // provides the height limit to be observed by the control loops // returns false if no height limiting is required @@ -358,9 +350,9 @@ class NavEKF3 { // returns true when the yaw angle has been aligned bool yawAlignmentComplete(void) const; - // returns true when the state estimates for the selected core are significantly degraded by vibration - // if instance < 0, the primary instance will be used - bool isVibrationAffected(int8_t instance) const; + // returns true when the state estimates are significantly + // degraded by vibration + bool isVibrationAffected() const; // get a yaw estimator instance const EKFGSF_yaw *get_yawEstimator(void) const; @@ -372,7 +364,15 @@ class NavEKF3 { uint32_t _frameTimeUsec; // time per IMU frame uint8_t _framesPerPrediction; // expected number of IMU frames per prediction - + + // values for EK3_LOG_LEVEL + enum class LogLevel { + ALL = 0, + XKF4 = 1, + XKF4_GSF = 2, + NONE = 3 + }; + // EKF Mavlink Tuneable Parameters AP_Int8 _enable; // zero to disable EKF3 AP_Float _gpsHorizVelNoise; // GPS horizontal velocity measurement noise : m/s @@ -438,6 +438,8 @@ class NavEKF3 { AP_Float _ognmTestScaleFactor; // Scale factor applied to the thresholds used by the on ground not moving test AP_Float _baroGndEffectDeadZone;// Dead zone applied to positive baro height innovations when in ground effect (m) AP_Int8 _primary_core; // initial core number + AP_Enum _log_level; // log verbosity level + AP_Float _gpsVAccThreshold; // vertical accuracy threshold to use GPS as an altitude source // Possible values for _flowUse #define FLOW_USE_NONE 0 @@ -457,6 +459,7 @@ class NavEKF3 { const uint16_t hgtRetryTimeMode0_ms = 10000; // Height retry time with vertical velocity measurement (msec) const uint16_t hgtRetryTimeMode12_ms = 5000; // Height retry time without vertical velocity measurement (msec) const uint16_t tasRetryTime_ms = 5000; // True airspeed timeout and retry interval (msec) + const uint16_t dragFailTimeLimit_ms = 5000; // Drag timeout (msec) const uint32_t magFailTimeLimit_ms = 10000; // number of msec before a magnetometer failing innovation consistency checks is declared failed (msec) const float magVarRateScale = 0.005f; // scale factor applied to magnetometer variance due to angular rate const float gyroBiasNoiseScaler = 2.0f; // scale factor applied to gyro bias state process noise when on ground @@ -475,7 +478,7 @@ class NavEKF3 { const uint8_t flowIntervalMin_ms = 20; // The minimum allowed time between measurements from optical flow sensors (msec) const uint8_t extNavIntervalMin_ms = 20; // The minimum allowed time between measurements from external navigation sensors (msec) const float maxYawEstVelInnov = 2.0f; // Maximum acceptable length of the velocity innovation returned by the EKF-GSF yaw estimator (m/s) - const uint16_t deadReckonDeclare_ms = 1000; // Time without equivalent position or velocity observation to constrain drift beore dead reckoning is declared (msec) + const uint16_t deadReckonDeclare_ms = 1000; // Time without equivalent position or velocity observation to constrain drift before dead reckoning is declared (msec) // time at start of current filter update uint64_t imuSampleTime_us; diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_AirDataFusion.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_AirDataFusion.cpp index 0f1cae9a1c0..38508e44a9a 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_AirDataFusion.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_AirDataFusion.cpp @@ -68,7 +68,7 @@ void NavEKF3_core::FuseAirspeed() } SK_TAS[1] = SH_TAS[1]; - if (!airDataFusionWindOnly) { + if (tasDataDelayed.allowFusion && !airDataFusionWindOnly) { Kfusion[0] = SK_TAS[0]*(P[0][4]*SH_TAS[2] - P[0][22]*SH_TAS[2] + P[0][5]*SK_TAS[1] - P[0][23]*SK_TAS[1] + P[0][6]*vd*SH_TAS[0]); Kfusion[1] = SK_TAS[0]*(P[1][4]*SH_TAS[2] - P[1][22]*SH_TAS[2] + P[1][5]*SK_TAS[1] - P[1][23]*SK_TAS[1] + P[1][6]*vd*SH_TAS[0]); Kfusion[2] = SK_TAS[0]*(P[2][4]*SH_TAS[2] - P[2][22]*SH_TAS[2] + P[2][5]*SK_TAS[1] - P[2][23]*SK_TAS[1] + P[2][6]*vd*SH_TAS[0]); @@ -84,7 +84,7 @@ void NavEKF3_core::FuseAirspeed() zero_range(&Kfusion[0], 0, 9); } - if (!inhibitDelAngBiasStates && !airDataFusionWindOnly) { + if (tasDataDelayed.allowFusion && !inhibitDelAngBiasStates && !airDataFusionWindOnly) { Kfusion[10] = SK_TAS[0]*(P[10][4]*SH_TAS[2] - P[10][22]*SH_TAS[2] + P[10][5]*SK_TAS[1] - P[10][23]*SK_TAS[1] + P[10][6]*vd*SH_TAS[0]); Kfusion[11] = SK_TAS[0]*(P[11][4]*SH_TAS[2] - P[11][22]*SH_TAS[2] + P[11][5]*SK_TAS[1] - P[11][23]*SK_TAS[1] + P[11][6]*vd*SH_TAS[0]); Kfusion[12] = SK_TAS[0]*(P[12][4]*SH_TAS[2] - P[12][22]*SH_TAS[2] + P[12][5]*SK_TAS[1] - P[12][23]*SK_TAS[1] + P[12][6]*vd*SH_TAS[0]); @@ -93,7 +93,7 @@ void NavEKF3_core::FuseAirspeed() zero_range(&Kfusion[0], 10, 12); } - if (!inhibitDelVelBiasStates && !airDataFusionWindOnly) { + if (tasDataDelayed.allowFusion && !inhibitDelVelBiasStates && !airDataFusionWindOnly) { for (uint8_t index = 0; index < 3; index++) { const uint8_t stateIndex = index + 13; if (!dvelBiasAxisInhibit[index]) { @@ -108,7 +108,7 @@ void NavEKF3_core::FuseAirspeed() } // zero Kalman gains to inhibit magnetic field state estimation - if (!inhibitMagStates && !airDataFusionWindOnly) { + if (tasDataDelayed.allowFusion && !inhibitMagStates && !airDataFusionWindOnly) { Kfusion[16] = SK_TAS[0]*(P[16][4]*SH_TAS[2] - P[16][22]*SH_TAS[2] + P[16][5]*SK_TAS[1] - P[16][23]*SK_TAS[1] + P[16][6]*vd*SH_TAS[0]); Kfusion[17] = SK_TAS[0]*(P[17][4]*SH_TAS[2] - P[17][22]*SH_TAS[2] + P[17][5]*SK_TAS[1] - P[17][23]*SK_TAS[1] + P[17][6]*vd*SH_TAS[0]); Kfusion[18] = SK_TAS[0]*(P[18][4]*SH_TAS[2] - P[18][22]*SH_TAS[2] + P[18][5]*SK_TAS[1] - P[18][23]*SK_TAS[1] + P[18][6]*vd*SH_TAS[0]); @@ -120,7 +120,7 @@ void NavEKF3_core::FuseAirspeed() zero_range(&Kfusion[0], 16, 21); } - if (!inhibitWindStates) { + if (tasDataDelayed.allowFusion && !inhibitWindStates) { Kfusion[22] = SK_TAS[0]*(P[22][4]*SH_TAS[2] - P[22][22]*SH_TAS[2] + P[22][5]*SK_TAS[1] - P[22][23]*SK_TAS[1] + P[22][6]*vd*SH_TAS[0]); Kfusion[23] = SK_TAS[0]*(P[23][4]*SH_TAS[2] - P[23][22]*SH_TAS[2] + P[23][5]*SK_TAS[1] - P[23][23]*SK_TAS[1] + P[23][6]*vd*SH_TAS[0]); } else { @@ -135,16 +135,16 @@ void NavEKF3_core::FuseAirspeed() tasTestRatio = sq(innovVtas) / (sq(MAX(0.01f * (ftype)frontend->_tasInnovGate, 1.0f)) * varInnovVtas); // fail if the ratio is > 1, but don't fail if bad IMU data - bool tasHealth = ((tasTestRatio < 1.0f) || badIMUdata); + const bool isConsistent = (tasTestRatio < 1.0f) || badIMUdata; tasTimeout = (imuSampleTime_ms - lastTasPassTime_ms) > frontend->tasRetryTime_ms; - if (!tasHealth) { + if (!isConsistent) { lastTasFailTime_ms = imuSampleTime_ms; } else { lastTasFailTime_ms = 0; } // test the ratio before fusing data, forcing fusion if airspeed and position are timed out as we have no choice but to try and use airspeed to constrain error growth - if (tasHealth || (tasTimeout && posTimeout)) { + if (tasDataDelayed.allowFusion && (isConsistent || (tasTimeout && posTimeout))) { // restart the counter lastTasPassTime_ms = imuSampleTime_ms; @@ -189,11 +189,10 @@ void NavEKF3_core::FuseAirspeed() } } } + // force the covariance matrix to be symmetrical and limit the variances to prevent ill-conditioning. + ForceSymmetry(); + ConstrainVariances(); } - - // force the covariance matrix to be symmetrical and limit the variances to prevent ill-conditioning. - ForceSymmetry(); - ConstrainVariances(); } // select fusion of true airspeed measurements @@ -254,7 +253,7 @@ void NavEKF3_core::SelectBetaDragFusion() // we are required to correct all states airDataFusionWindOnly = false; } else { - // we are required to corrrect only wind states + // we are required to correct only wind states airDataFusionWindOnly = true; } // Fuse estimated airspeed to aid wind estimation @@ -270,6 +269,7 @@ void NavEKF3_core::SelectBetaDragFusion() if (!inhibitWindStates && storedDrag.recall(dragSampleDelayed,imuDataDelayed.time_ms)) { FuseDragForces(); } + dragTimeout = (imuSampleTime_ms - lastDragPassTime_ms) > frontend->dragFailTimeLimit_ms; #endif } @@ -529,7 +529,7 @@ void NavEKF3_core::FuseDragForces() // correct accel data for bias const ftype mea_acc = dragSampleDelayed.accelXY[axis_index] - stateStruct.accel_bias[axis_index] / dtEkfAvg; - // Acceleration in m/s/s predicfed using vehicle and wind velocity estimates + // Acceleration in m/s/s predicted using vehicle and wind velocity estimates // Initialised to measured value and updated later using available drag model ftype predAccel = mea_acc; @@ -620,7 +620,7 @@ void NavEKF3_core::FuseDragForces() } else if (axis_index == 1) { - // drag can be modelled as an arbitrary combination of bluff body drag that proportional to + // drag can be modelled as an arbitrary combination of bluff body drag that proportional to // speed squared, and rotor momentum drag that is proportional to speed. ftype Kacc; // Derivative of specific force wrt airspeed if (using_mcoef && using_bcoef_y) { @@ -751,6 +751,9 @@ void NavEKF3_core::FuseDragForces() } } } + + // record time of successful fusion + lastDragPassTime_ms = imuSampleTime_ms; } #endif // EK3_FEATURE_DRAG_FUSION diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_Control.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_Control.cpp index 3ba49286cc3..beca7ae17b4 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_Control.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_Control.cpp @@ -77,7 +77,7 @@ void NavEKF3_core::setWindMagStateLearningMode() Vector3F tempEuler; stateStruct.quat.to_euler(tempEuler.x, tempEuler.y, tempEuler.z); ftype trueAirspeedVariance; - const bool haveAirspeedMeasurement = usingDefaultAirspeed || (imuDataDelayed.time_ms - tasDataDelayed.time_ms < 500 && useAirspeed()); + const bool haveAirspeedMeasurement = usingDefaultAirspeed || (tasDataDelayed.allowFusion && (imuDataDelayed.time_ms - tasDataDelayed.time_ms < 500) && useAirspeed()); if (haveAirspeedMeasurement) { trueAirspeedVariance = constrain_ftype(tasDataDelayed.tasVariance, WIND_VEL_VARIANCE_MIN, WIND_VEL_VARIANCE_MAX); const ftype windSpeed = sqrtF(sq(stateStruct.velocity.x) + sq(stateStruct.velocity.y)) - tasDataDelayed.tas; @@ -299,6 +299,9 @@ void NavEKF3_core::setAidingMode() // Check if airspeed data is being used bool airSpdUsed = (imuSampleTime_ms - lastTasPassTime_ms <= minTestTime_ms); + // check if drag data is being used + bool dragUsed = (imuSampleTime_ms - lastDragPassTime_ms <= minTestTime_ms); + // Check if range beacon data is being used bool rngBcnUsed = (imuSampleTime_ms - lastRngBcnPassTime_ms <= minTestTime_ms); @@ -307,10 +310,10 @@ void NavEKF3_core::setAidingMode() bool gpsVelUsed = (imuSampleTime_ms - lastVelPassTime_ms <= minTestTime_ms); // Check if attitude drift has been constrained by a measurement source - bool attAiding = posUsed || gpsVelUsed || optFlowUsed || airSpdUsed || rngBcnUsed || bodyOdmUsed; + bool attAiding = posUsed || gpsVelUsed || optFlowUsed || airSpdUsed || dragUsed || rngBcnUsed || bodyOdmUsed; // check if velocity drift has been constrained by a measurement source - bool velAiding = gpsVelUsed || airSpdUsed || optFlowUsed || bodyOdmUsed; + bool velAiding = gpsVelUsed || airSpdUsed || dragUsed || optFlowUsed || bodyOdmUsed; // check if position drift has been constrained by a measurement source bool posAiding = posUsed || rngBcnUsed; @@ -344,6 +347,7 @@ void NavEKF3_core::setAidingMode() posTimeout = true; velTimeout = true; tasTimeout = true; + dragTimeout = true; gpsIsInUse = false; } else if (posAidLossCritical) { // if the loss of position is critical, declare all sources of position aiding as being timed out @@ -377,6 +381,9 @@ void NavEKF3_core::setAidingMode() meaHgtAtTakeOff = baroDataDelayed.hgt; // reset the vertical position state to faster recover from baro errors experienced during touchdown stateStruct.position.z = -meaHgtAtTakeOff; + // store the current height to be used to keep reporting + // the last known position + lastKnownPositionD = stateStruct.position.z; // reset relative aiding sensor fusion activity status flowFusionActive = false; bodyVelFusionActive = false; @@ -680,40 +687,44 @@ void NavEKF3_core::checkGyroCalStatus(void) void NavEKF3_core::updateFilterStatus(void) { // init return value - filterStatus.value = 0; + nav_filter_status status; + status.value = 0; bool doingBodyVelNav = (PV_AidingMode != AID_NONE) && (imuSampleTime_ms - prevBodyVelFuseTime_ms < 5000); bool doingFlowNav = (PV_AidingMode != AID_NONE) && flowDataValid; - bool doingWindRelNav = !tasTimeout && assume_zero_sideslip(); + bool doingWindRelNav = (!tasTimeout && assume_zero_sideslip()) || !dragTimeout; bool doingNormalGpsNav = !posTimeout && (PV_AidingMode == AID_ABSOLUTE); bool someVertRefData = (!velTimeout && (useGpsVertVel || useExtNavVel)) || !hgtTimeout; - bool someHorizRefData = !(velTimeout && posTimeout && tasTimeout) || doingFlowNav || doingBodyVelNav; + bool someHorizRefData = !(velTimeout && posTimeout && tasTimeout && dragTimeout) || doingFlowNav || doingBodyVelNav; bool filterHealthy = healthy() && tiltAlignComplete && (yawAlignComplete || (!use_compass() && (PV_AidingMode != AID_ABSOLUTE))); // If GPS height usage is specified, height is considered to be inaccurate until the GPS passes all checks bool hgtNotAccurate = (frontend->sources.getPosZSource() == AP_NavEKF_Source::SourceZ::GPS) && !validOrigin; // set individual flags - filterStatus.flags.attitude = !stateStruct.quat.is_nan() && filterHealthy; // attitude valid (we need a better check) - filterStatus.flags.horiz_vel = someHorizRefData && filterHealthy; // horizontal velocity estimate valid - filterStatus.flags.vert_vel = someVertRefData && filterHealthy; // vertical velocity estimate valid - filterStatus.flags.horiz_pos_rel = ((doingFlowNav && gndOffsetValid) || doingWindRelNav || doingNormalGpsNav || doingBodyVelNav) && filterHealthy; // relative horizontal position estimate valid - filterStatus.flags.horiz_pos_abs = doingNormalGpsNav && filterHealthy; // absolute horizontal position estimate valid - filterStatus.flags.vert_pos = !hgtTimeout && filterHealthy && !hgtNotAccurate; // vertical position estimate valid - filterStatus.flags.terrain_alt = gndOffsetValid && filterHealthy; // terrain height estimate valid - filterStatus.flags.const_pos_mode = (PV_AidingMode == AID_NONE) && filterHealthy; // constant position mode - filterStatus.flags.pred_horiz_pos_rel = filterStatus.flags.horiz_pos_rel; // EKF3 enters the required mode before flight - filterStatus.flags.pred_horiz_pos_abs = filterStatus.flags.horiz_pos_abs; // EKF3 enters the required mode before flight - filterStatus.flags.takeoff_detected = takeOffDetected; // takeoff for optical flow navigation has been detected - filterStatus.flags.takeoff = dal.get_takeoff_expected(); // The EKF has been told to expect takeoff is in a ground effect mitigation mode and has started the EKF-GSF yaw estimator - filterStatus.flags.touchdown = dal.get_touchdown_expected(); // The EKF has been told to detect touchdown and is in a ground effect mitigation mode - filterStatus.flags.using_gps = ((imuSampleTime_ms - lastPosPassTime_ms) < 4000) && (PV_AidingMode == AID_ABSOLUTE); - filterStatus.flags.gps_glitching = !gpsAccuracyGood && (PV_AidingMode == AID_ABSOLUTE) && (frontend->sources.getPosXYSource() == AP_NavEKF_Source::SourceXY::GPS); // GPS glitching is affecting navigation accuracy - filterStatus.flags.gps_quality_good = gpsGoodToAlign; + status.flags.attitude = !stateStruct.quat.is_nan() && filterHealthy; // attitude valid (we need a better check) + status.flags.horiz_vel = someHorizRefData && filterHealthy; // horizontal velocity estimate valid + status.flags.vert_vel = someVertRefData && filterHealthy; // vertical velocity estimate valid + status.flags.horiz_pos_rel = ((doingFlowNav && gndOffsetValid) || doingWindRelNav || doingNormalGpsNav || doingBodyVelNav) && filterHealthy; // relative horizontal position estimate valid + status.flags.horiz_pos_abs = doingNormalGpsNav && filterHealthy; // absolute horizontal position estimate valid + status.flags.vert_pos = !hgtTimeout && filterHealthy && !hgtNotAccurate; // vertical position estimate valid + status.flags.terrain_alt = gndOffsetValid && filterHealthy; // terrain height estimate valid + status.flags.const_pos_mode = (PV_AidingMode == AID_NONE) && filterHealthy; // constant position mode + status.flags.pred_horiz_pos_rel = status.flags.horiz_pos_rel; // EKF3 enters the required mode before flight + status.flags.pred_horiz_pos_abs = status.flags.horiz_pos_abs; // EKF3 enters the required mode before flight + status.flags.takeoff_detected = takeOffDetected; // takeoff for optical flow navigation has been detected + status.flags.takeoff = dal.get_takeoff_expected(); // The EKF has been told to expect takeoff is in a ground effect mitigation mode and has started the EKF-GSF yaw estimator + status.flags.touchdown = dal.get_touchdown_expected(); // The EKF has been told to detect touchdown and is in a ground effect mitigation mode + status.flags.using_gps = ((imuSampleTime_ms - lastPosPassTime_ms) < 4000) && (PV_AidingMode == AID_ABSOLUTE); + status.flags.gps_glitching = !gpsAccuracyGood && (PV_AidingMode == AID_ABSOLUTE) && (frontend->sources.getPosXYSource() == AP_NavEKF_Source::SourceXY::GPS); // GPS glitching is affecting navigation accuracy + status.flags.gps_quality_good = gpsGoodToAlign; // for reporting purposes we report rejecting airspeed after 3s of not fusing when we want to fuse the data - filterStatus.flags.rejecting_airspeed = lastTasFailTime_ms != 0 && + status.flags.rejecting_airspeed = lastTasFailTime_ms != 0 && (imuSampleTime_ms - lastTasFailTime_ms) < 1000 && (imuSampleTime_ms - lastTasPassTime_ms) > 3000; - filterStatus.flags.initalized = filterStatus.flags.initalized || healthy(); + status.flags.initalized = status.flags.initalized || healthy(); + status.flags.dead_reckoning = (PV_AidingMode != AID_NONE) && doingWindRelNav && !((doingFlowNav && gndOffsetValid) || doingNormalGpsNav || doingBodyVelNav); + + filterStatus.value = status.value; } void NavEKF3_core::runYawEstimatorPrediction() @@ -730,7 +741,7 @@ void NavEKF3_core::runYawEstimatorPrediction() } ftype trueAirspeed; - if (assume_zero_sideslip()) { + if (tasDataDelayed.allowFusion && assume_zero_sideslip()) { trueAirspeed = MAX(tasDataDelayed.tas, 0.0f); } else { trueAirspeed = 0.0f; diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_Logging.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_Logging.cpp index b5e77945f54..6c85670fa63 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_Logging.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_Logging.cpp @@ -146,7 +146,8 @@ void NavEKF3_core::Log_Write_XKF4(uint64_t time_us) const velTimeout<<1 | hgtTimeout<<2 | magTimeout<<3 | - tasTimeout<<4; + tasTimeout<<4 | + dragTimeout<<5; nav_filter_status solutionStatus {}; getVariances(velVar, posVar, hgtVar, magVar, tasVar, offset); @@ -190,7 +191,7 @@ void NavEKF3_core::Log_Write_XKF5(uint64_t time_us) const FIX : (int16_t)(1000*flowInnov[0]), // optical flow LOS rate vector innovations from the main nav filter FIY : (int16_t)(1000*flowInnov[1]), // optical flow LOS rate vector innovations from the main nav filter AFI : (int16_t)(1000 * auxFlowObsInnov.length()), // optical flow LOS rate innovation from terrain offset estimator - HAGL : (int16_t)(100*(terrainState - stateStruct.position.z)), // height above ground level + HAGL : float_to_int16(100*(terrainState - stateStruct.position.z)), // height above ground level offset : (int16_t)(100*terrainState), // filter ground offset state error RI : (int16_t)(100*innovRng), // range finder innovations meaRng : (uint16_t)(100*rangeDataDelayed.rng), // measured range @@ -364,17 +365,28 @@ void NavEKF3::Log_Write() void NavEKF3_core::Log_Write(uint64_t time_us) { + const auto level = frontend->_log_level; + if (level == NavEKF3::LogLevel::NONE) { // no logging from EK3_LOG_LEVEL param + return; + } + Log_Write_XKF4(time_us); + if (level == NavEKF3::LogLevel::XKF4) { // only log XKF4 scaled innovations + return; + } + Log_Write_GSF(time_us); + if (level == NavEKF3::LogLevel::XKF4_GSF) { // only log XKF4 scaled innovations and GSF, otherwise log everything + return; + } // note that several of these functions exit-early if they're not // attempting to log the primary core. Log_Write_XKF1(time_us); Log_Write_XKF2(time_us); Log_Write_XKF3(time_us); - Log_Write_XKF4(time_us); Log_Write_XKF5(time_us); Log_Write_XKFS(time_us); Log_Write_Quaternion(time_us); - Log_Write_GSF(time_us); + // write range beacon fusion debug packet if the range value is non-zero Log_Write_Beacon(time_us); diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp index 50bc3497444..d2559438cc5 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp @@ -4,6 +4,7 @@ #include #include #include +#include /******************************************************** * OPT FLOW AND RANGE FINDER * @@ -89,7 +90,7 @@ void NavEKF3_core::readRangeFinder(void) // indicate we have updated the measurement rngValidMeaTime_ms = imuSampleTime_ms; - } else if (!takeOffDetected && ((imuSampleTime_ms - rngValidMeaTime_ms) > 200)) { + } else if (onGround && ((imuSampleTime_ms - rngValidMeaTime_ms) > 200)) { // before takeoff we assume on-ground range value if there is no data rangeDataNew.time_ms = imuSampleTime_ms; rangeDataNew.rng = rngOnGnd; @@ -830,13 +831,12 @@ void NavEKF3_core::readAirSpdData() const auto *airspeed = dal.airspeed(); if (airspeed && - airspeed->use(selected_airspeed) && - airspeed->healthy(selected_airspeed) && (airspeed->last_update_ms(selected_airspeed) - timeTasReceived_ms) > frontend->sensorIntervalMin_ms) { tasDataNew.tas = airspeed->get_airspeed(selected_airspeed) * EAS2TAS; timeTasReceived_ms = airspeed->last_update_ms(selected_airspeed); tasDataNew.time_ms = timeTasReceived_ms - frontend->tasDelay_ms; tasDataNew.tasVariance = sq(MAX(frontend->_easNoise * EAS2TAS, 0.5f)); + tasDataNew.allowFusion = airspeed->healthy(selected_airspeed) && airspeed->use(selected_airspeed); // Correct for the average intersampling delay due to the filter update rate tasDataNew.time_ms -= localFilterTimeStep_ms/2; @@ -855,6 +855,7 @@ void NavEKF3_core::readAirSpdData() is_positive(defaultAirSpeed)) { tasDataDelayed.tas = defaultAirSpeed * EAS2TAS; tasDataDelayed.tasVariance = sq(MAX(defaultAirSpeedVariance, easErrVar)); + tasDataDelayed.allowFusion = true; tasDataDelayed.time_ms = 0; usingDefaultAirspeed = true; } else { diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_OptFlowFusion.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_OptFlowFusion.cpp index 01154fb6c30..28545ef5aa7 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_OptFlowFusion.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_OptFlowFusion.cpp @@ -612,7 +612,7 @@ void NavEKF3_core::FuseOptFlow(const of_elements &ofDataDelayed, bool really_fus // calculate innovation for Y observation flowInnov[1] = losPred[1] - ofDataDelayed.flowRadXYcomp.y; - flowInnovTime_ms = AP_HAL::millis(); + flowInnovTime_ms = dal.millis(); // calculate Kalman gains for the Y-axis observation Kfusion[0] = -t78*(t12+P[0][5]*t2*t8-P[0][6]*t2*t10+P[0][1]*t2*t16-P[0][2]*t2*t19+P[0][3]*t2*t22+P[0][4]*t2*t27); diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp index a7ef0ff101b..143d3ce92f6 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp @@ -3,6 +3,7 @@ #include "AP_NavEKF3.h" #include "AP_NavEKF3_core.h" #include +#include // Check basic filter health metrics and return a consolidated health status bool NavEKF3_core::healthy(void) const @@ -190,6 +191,19 @@ bool NavEKF3_core::getAirSpdVec(Vector3f &vel) const return true; } +// return the innovation in m/s, innovation variance in (m/s)^2 and age in msec of the last TAS measurement processed +// returns false if the data is unavailable +bool NavEKF3_core::getAirSpdHealthData(float &innovation, float &innovationVariance, uint32_t &age_ms) const +{ + if (tasDataDelayed.time_ms == 0) { + // no data has been processed since startup + return false; + } + innovation = (float)innovVtas; + innovationVariance = (float)varInnovVtas; + age_ms = imuSampleTime_ms - tasDataDelayed.time_ms; + return true; +} // Return the rate of change of vertical position in the down direction (dPosD/dt) of the body frame origin in m/s float NavEKF3_core::getPosDownDerivative(void) const @@ -238,9 +252,9 @@ bool NavEKF3_core::getPosNE(Vector2f &posNE) const return false; } -// Write the last calculated D position of the body frame origin relative to the EKF origin (m). +// Write the last calculated D position of the body frame origin relative to the EKF local origin // Return true if the estimate is valid -bool NavEKF3_core::getPosD(float &posD) const +bool NavEKF3_core::getPosD_local(float &posD) const { // The EKF always has a height estimate regardless of mode of operation // Correct for the IMU offset (EKF calculations are at the IMU) @@ -259,6 +273,21 @@ bool NavEKF3_core::getPosD(float &posD) const } +// Write the last calculated D position of the body frame origin relative to the public origin +// Return true if the estimate is valid +bool NavEKF3_core::getPosD(float &posD) const +{ + bool ret = getPosD_local(posD); + + // adjust posD for difference between our origin and the public_origin + Location local_origin; + if (getOriginLLH(local_origin)) { + posD += (public_origin.alt - local_origin.alt) * 0.01; + } + + return ret; +} + // return the estimated height of body frame origin above ground level bool NavEKF3_core::getHAGL(float &HAGL) const { @@ -276,11 +305,9 @@ bool NavEKF3_core::getLLH(struct Location &loc) const Location origin; if (getOriginLLH(origin)) { float posD; - if(getPosD(posD) && PV_AidingMode != AID_NONE) { + if (getPosD_local(posD) && PV_AidingMode != AID_NONE) { // Altitude returned is an absolute altitude relative to the WGS-84 spherioid - loc.alt = origin.alt - posD*100; - loc.relative_alt = 0; - loc.terrain_alt = 0; + loc.set_alt_cm(origin.alt - posD*100.0, Location::AltFrame::ABSOLUTE); if (filterStatus.flags.horiz_pos_abs || filterStatus.flags.horiz_pos_rel) { // The EKF is able to provide a position estimate loc.lat = EKF_origin.lat; @@ -310,6 +337,7 @@ bool NavEKF3_core::getLLH(struct Location &loc) const loc.lng = EKF_origin.lng; loc.offset(lastKnownPositionNE.x + posOffsetNED.x, lastKnownPositionNE.y + posOffsetNED.y); + loc.alt = EKF_origin.alt - lastKnownPositionD*100.0; return false; } } @@ -461,7 +489,7 @@ bool NavEKF3_core::getVelInnovationsAndVariancesForSource(AP_NavEKF_Source::Sour switch (source) { case AP_NavEKF_Source::SourceXY::GPS: // check for timeouts - if (AP_HAL::millis() - gpsVelInnovTime_ms > 500) { + if (dal.millis() - gpsVelInnovTime_ms > 500) { return false; } innovations = gpsVelInnov.tofloat(); @@ -470,7 +498,7 @@ bool NavEKF3_core::getVelInnovationsAndVariancesForSource(AP_NavEKF_Source::Sour #if EK3_FEATURE_EXTERNAL_NAV case AP_NavEKF_Source::SourceXY::EXTNAV: // check for timeouts - if (AP_HAL::millis() - extNavVelInnovTime_ms > 500) { + if (dal.millis() - extNavVelInnovTime_ms > 500) { return false; } innovations = extNavVelInnov.tofloat(); @@ -479,7 +507,7 @@ bool NavEKF3_core::getVelInnovationsAndVariancesForSource(AP_NavEKF_Source::Sour #endif // EK3_FEATURE_EXTERNAL_NAV case AP_NavEKF_Source::SourceXY::OPTFLOW: // check for timeouts - if (AP_HAL::millis() - flowInnovTime_ms > 500) { + if (dal.millis() - flowInnovTime_ms > 500) { return false; } innovations.x = flowInnov[0]; @@ -527,8 +555,9 @@ void NavEKF3_core::getFilterStatus(nav_filter_status &status) const status = filterStatus; } +#if HAL_GCS_ENABLED // send an EKF_STATUS message to GCS -void NavEKF3_core::send_status_report(mavlink_channel_t chan) const +void NavEKF3_core::send_status_report(GCS_MAVLINK &link) const { // prepare flags uint16_t flags = 0; @@ -575,20 +604,29 @@ void NavEKF3_core::send_status_report(mavlink_channel_t chan) const Vector2f offset; getVariances(velVar, posVar, hgtVar, magVar, tasVar, offset); + // Only report range finder normalised innovation levels if the EKF needs the data for primary // height estimation or optical flow operation. This prevents false alarms at the GCS if a // range finder is fitted for other applications - float temp; + float temp = 0; if (((frontend->_useRngSwHgt > 0) && activeHgtSource == AP_NavEKF_Source::SourceZ::RANGEFINDER) || (PV_AidingMode == AID_RELATIVE && flowDataValid)) { temp = sqrtF(auxRngTestRatio); - } else { - temp = 0.0f; } - const float mag_max = fmaxF(fmaxF(magVar.x,magVar.y),magVar.z); + + const mavlink_ekf_status_report_t packet{ + velVar, + posVar, + hgtVar, + fmaxF(fmaxF(magVar.x,magVar.y),magVar.z), + temp, + flags, + tasVar + }; // send message - mavlink_msg_ekf_status_report_send(chan, flags, velVar, posVar, hgtVar, mag_max, temp, tasVar); + mavlink_msg_ekf_status_report_send_struct(link.get_chan(), &packet); } +#endif // HAL_GCS_ENABLED // report the reason for why the backend is refusing to initialise const char *NavEKF3_core::prearm_failure_reason(void) const diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp index fd1b737889d..a14de0bfa83 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp @@ -442,7 +442,7 @@ void NavEKF3_core::SelectVelPosFusion() CalculateVelInnovationsAndVariances(extNavVelDelayed.vel, extNavVelDelayed.err, frontend->extNavVelVarAccScale, extNavVelInnov, extNavVelVarInnov); // record time innovations were calculated (for timeout checks) - extNavVelInnovTime_ms = AP_HAL::millis(); + extNavVelInnovTime_ms = dal.millis(); } #endif // EK3_FEATURE_EXTERNAL_NAV @@ -457,7 +457,7 @@ void NavEKF3_core::SelectVelPosFusion() // calculate innovations and variances for reporting purposes only CalculateVelInnovationsAndVariances(gpsDataDelayed.vel, frontend->_gpsHorizVelNoise, frontend->gpsNEVelVarAccScale, gpsVelInnov, gpsVelVarInnov); // record time innovations were calculated (for timeout checks) - gpsVelInnovTime_ms = AP_HAL::millis(); + gpsVelInnovTime_ms = dal.millis(); } // detect position source changes. Trigger position reset if position source is valid @@ -1087,7 +1087,7 @@ void NavEKF3_core::selectHeightForFusion() // determine if we are above or below the height switch region ftype rangeMaxUse = 1e-4 * (ftype)_rng->max_distance_cm_orient(ROTATION_PITCH_270) * (ftype)frontend->_useRngSwHgt; bool aboveUpperSwHgt = (terrainState - stateStruct.position.z) > rangeMaxUse; - bool belowLowerSwHgt = (terrainState - stateStruct.position.z) < 0.7f * rangeMaxUse; + bool belowLowerSwHgt = ((terrainState - stateStruct.position.z) < 0.7f * rangeMaxUse) && (imuSampleTime_ms - gndHgtValidTime_ms < 1000); // If the terrain height is consistent and we are moving slowly, then it can be // used as a height reference in combination with a range finder @@ -1135,7 +1135,7 @@ void NavEKF3_core::selectHeightForFusion() // Use Baro alt as a fallback if we lose range finder, GPS, external nav or Beacon bool lostRngHgt = ((activeHgtSource == AP_NavEKF_Source::SourceZ::RANGEFINDER) && !rangeFinderDataIsFresh); - bool lostGpsHgt = ((activeHgtSource == AP_NavEKF_Source::SourceZ::GPS) && ((imuSampleTime_ms - lastTimeGpsReceived_ms) > 2000)); + bool lostGpsHgt = ((activeHgtSource == AP_NavEKF_Source::SourceZ::GPS) && ((imuSampleTime_ms - lastTimeGpsReceived_ms) > 2000 || !gpsAccuracyGoodForAltitude)); bool lostRngBcnHgt = ((activeHgtSource == AP_NavEKF_Source::SourceZ::BEACON) && ((imuSampleTime_ms - rngBcnDataDelayed.time_ms) > 2000)); bool fallback_to_baro = lostRngHgt || lostGpsHgt || lostRngBcnHgt; #if EK3_FEATURE_EXTERNAL_NAV diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_VehicleStatus.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_VehicleStatus.cpp index f00f558f566..e2386001db9 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_VehicleStatus.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_VehicleStatus.cpp @@ -237,9 +237,11 @@ void NavEKF3_core::calcGpsGoodToAlign(void) // update inflight calculaton that determines if GPS data is good enough for reliable navigation void NavEKF3_core::calcGpsGoodForFlight(void) { - // use a simple criteria based on the GPS receivers claimed speed accuracy and the EKF innovation consistency checks + // use simple criteria based on the GPS receiver's claimed vertical + // position accuracy and speed accuracy and the EKF innovation consistency + // checks - // set up varaibles and constants used by filter that is applied to GPS speed accuracy + // set up variables and constants used by filter that is applied to GPS speed accuracy const ftype alpha1 = 0.2f; // coefficient for first stage LPF applied to raw speed accuracy data const ftype tau = 10.0f; // time constant (sec) of peak hold decay if (lastGpsCheckTime_ms == 0) { @@ -268,25 +270,51 @@ void NavEKF3_core::calcGpsGoodForFlight(void) gpsSpdAccPass = true; } + // Apply a threshold test with hysteresis to the GPS vertical position accuracy data + // Require a fail for one second and a pass for 3 seconds to transition + float gpsVAccRaw; + ftype gpsVAccThreshold = (ftype)frontend->_gpsVAccThreshold; + if (lastGpsVertAccFailTime_ms == 0) { + lastGpsVertAccFailTime_ms = imuSampleTime_ms; + lastGpsVertAccPassTime_ms = imuSampleTime_ms; + } + if (!dal.gps().vertical_accuracy(preferred_gps, gpsVAccRaw)) { + // No vertical accuracy data yet, let's treat it as a value above the threshold + gpsVAccRaw = gpsVAccThreshold + 1.0f; + } + if (gpsVAccThreshold <= 0 || gpsVAccRaw < gpsVAccThreshold) { + lastGpsVertAccPassTime_ms = imuSampleTime_ms; + } else { + lastGpsVertAccFailTime_ms = imuSampleTime_ms; + } + if ((imuSampleTime_ms - lastGpsVertAccPassTime_ms) > 1000) { + gpsVertAccPass = false; + } else if ((imuSampleTime_ms - lastGpsVertAccFailTime_ms) > 3000) { + gpsVertAccPass = true; + } + // Apply a threshold test with hysteresis to the normalised position and velocity innovations // Require a fail for one second and a pass for 10 seconds to transition - if (lastInnovFailTime_ms == 0) { - lastInnovFailTime_ms = imuSampleTime_ms; - lastInnovPassTime_ms = imuSampleTime_ms; + if (lastGpsInnovFailTime_ms == 0) { + lastGpsInnovFailTime_ms = imuSampleTime_ms; + lastGpsInnovPassTime_ms = imuSampleTime_ms; } if (velTestRatio < 1.0f && posTestRatio < 1.0f) { - lastInnovPassTime_ms = imuSampleTime_ms; + lastGpsInnovPassTime_ms = imuSampleTime_ms; } else if (velTestRatio > 0.7f || posTestRatio > 0.7f) { - lastInnovFailTime_ms = imuSampleTime_ms; + lastGpsInnovFailTime_ms = imuSampleTime_ms; } - if ((imuSampleTime_ms - lastInnovPassTime_ms) > 1000) { + if ((imuSampleTime_ms - lastGpsInnovPassTime_ms) > 1000) { ekfInnovationsPass = false; - } else if ((imuSampleTime_ms - lastInnovFailTime_ms) > 10000) { + } else if ((imuSampleTime_ms - lastGpsInnovFailTime_ms) > 10000) { ekfInnovationsPass = true; } // both GPS speed accuracy and EKF innovations must pass gpsAccuracyGood = gpsSpdAccPass && ekfInnovationsPass; + + // also update whether the GPS fix is good enough for altitude + gpsAccuracyGoodForAltitude = gpsAccuracyGood && gpsVertAccPass; } // Detect if we are in flight or on ground diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_core.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_core.cpp index a4650192170..1cf98973616 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_core.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_core.cpp @@ -226,6 +226,7 @@ void NavEKF3_core::InitialiseVariables() gpsNoiseScaler = 1.0f; hgtTimeout = true; tasTimeout = true; + dragTimeout = true; badIMUdata = false; badIMUdata_ms = 0; goodIMUdata_ms = 0; @@ -236,6 +237,7 @@ void NavEKF3_core::InitialiseVariables() dt = 0; velDotNEDfilt.zero(); lastKnownPositionNE.zero(); + lastKnownPositionD = 0; prevTnb.zero(); memset(&P[0][0], 0, sizeof(P)); memset(&KH[0][0], 0, sizeof(KH)); @@ -293,9 +295,12 @@ void NavEKF3_core::InitialiseVariables() sAccFilterState1 = 0.0f; sAccFilterState2 = 0.0f; lastGpsCheckTime_ms = 0; - lastInnovPassTime_ms = 0; - lastInnovFailTime_ms = 0; + lastGpsInnovPassTime_ms = 0; + lastGpsInnovFailTime_ms = 0; + lastGpsVertAccPassTime_ms = 0; + lastGpsVertAccFailTime_ms = 0; gpsAccuracyGood = false; + gpsAccuracyGoodForAltitude = false; gpsloc_prev = {}; gpsDriftNE = 0.0f; gpsVertVelFilt = 0.0f; @@ -1104,6 +1109,10 @@ void NavEKF3_core::CovariancePrediction(Vector3F *rotVarVecPtr) if (!inhibitWindStates) { ftype windVelVar = sq(dt * constrain_ftype(frontend->_windVelProcessNoise, 0.0f, 1.0f) * (1.0f + constrain_ftype(frontend->_wndVarHgtRateScale, 0.0f, 1.0f) * fabsF(hgtRate))); + if (!tasDataDelayed.allowFusion) { + // Allow wind states to recover faster when using sideslip fusion with a failed airspeed sesnor + windVelVar *= 10.0f; + } for (uint8_t i=12; i<=13; i++) processNoiseVariance[i] = windVelVar; } @@ -1903,12 +1912,11 @@ void NavEKF3_core::ConstrainVariances() zeroRows(P,10,12); } - const ftype minStateVarTarget = 1E-11; + const ftype minSafeStateVar = 5E-9; if (!inhibitDelVelBiasStates) { // Find the maximum delta velocity bias state variance and request a covariance reset if any variance is below the safe minimum - const ftype minSafeStateVar = minStateVarTarget * 0.1f; - ftype maxStateVar = minSafeStateVar; + ftype maxStateVar = 0.0F; bool resetRequired = false; for (uint8_t stateIndex=13; stateIndex<=15; stateIndex++) { if (P[stateIndex][stateIndex] > maxStateVar) { @@ -1920,33 +1928,30 @@ void NavEKF3_core::ConstrainVariances() // To ensure stability of the covariance matrix operations, the ratio of a max and min variance must // not exceed 100 and the minimum variance must not fall below the target minimum - ftype minAllowedStateVar = fmaxF(0.01f * maxStateVar, minStateVarTarget); + ftype minAllowedStateVar = fmaxF(0.01f * maxStateVar, minSafeStateVar); for (uint8_t stateIndex=13; stateIndex<=15; stateIndex++) { P[stateIndex][stateIndex] = constrain_ftype(P[stateIndex][stateIndex], minAllowedStateVar, sq(10.0f * dtEkfAvg)); } // If any one axis has fallen below the safe minimum, all delta velocity covariance terms must be reset to zero if (resetRequired) { - ftype delVelBiasVar[3]; - // store all delta velocity bias variances - for (uint8_t i=0; i<=2; i++) { - delVelBiasVar[i] = P[i+13][i+13]; - } // reset all delta velocity bias covariances zeroCols(P,13,15); zeroRows(P,13,15); - // restore all delta velocity bias variances - for (uint8_t i=0; i<=2; i++) { - P[i+13][i+13] = delVelBiasVar[i]; - } + // set all delta velocity bias variances to initial values and zero bias states + P[13][13] = sq(ACCEL_BIAS_LIM_SCALER * frontend->_accBiasLim * dtEkfAvg); + P[14][14] = P[13][13]; + P[15][15] = P[13][13]; + stateStruct.accel_bias.zero(); } } else { zeroCols(P,13,15); zeroRows(P,13,15); + // set all delta velocity bias variances to a margin above the minimum safe value for (uint8_t i=0; i<=2; i++) { - const uint8_t stateIndex = 1 + 13; - P[stateIndex][stateIndex] = fmaxF(P[stateIndex][stateIndex], minStateVarTarget); + const uint8_t stateIndex = i + 13; + P[stateIndex][stateIndex] = fmaxF(P[stateIndex][stateIndex], minSafeStateVar * 10.0F); } } diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_core.h b/libraries/AP_NavEKF3/AP_NavEKF3_core.h index aff10f88304..d329b6da5f3 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_core.h +++ b/libraries/AP_NavEKF3/AP_NavEKF3_core.h @@ -32,7 +32,6 @@ #include #include #include -#include #include #include "AP_NavEKF/EKFGSF_yaw.h" @@ -139,7 +138,10 @@ class NavEKF3_core : public NavEKF_core_common // If false returned, do not use for flight control bool getPosNE(Vector2f &posNE) const; - // Write the last calculated D position relative to the reference point (m). + // get position D from local origin + bool getPosD_local(float &posD) const; + + // Write the last calculated D position relative to the public origin // If a calculated solution is not available, use the best available data and return false // If false returned, do not use for flight control bool getPosD(float &posD) const; @@ -151,6 +153,10 @@ class NavEKF3_core : public NavEKF_core_common // returns false if estimate is unavailable bool getAirSpdVec(Vector3f &vel) const; + // return the innovation in m/s, innovation variance in (m/s)^2 and age in msec of the last TAS measurement processed + // returns false if the data is unavailable + bool getAirSpdHealthData(float &innovation, float &innovationVariance, uint32_t &age_ms) const; + // Return the rate of change of vertical position in the down direction (dPosD/dt) in m/s // This can be different to the z component of the EKF velocity state because it will fluctuate with height errors and corrections in the EKF // but will always be kinematically consistent with the z component of the EKF position state @@ -303,7 +309,7 @@ class NavEKF3_core : public NavEKF_core_common * Write position and quaternion data from an external navigation system * * pos : position in the RH navigation frame. Frame is assumed to be NED if frameIsNED is true. (m) - * quat : quaternion desribing the the rotation from navigation frame to body frame + * quat : quaternion desribing the rotation from navigation frame to body frame * posErr : 1-sigma spherical position error (m) * angErr : 1-sigma spherical angle error (rad) * timeStamp_ms : system time the measurement was taken, not the time it was received (mSec) @@ -352,7 +358,7 @@ class NavEKF3_core : public NavEKF_core_common void getFilterStatus(nav_filter_status &status) const; // send an EKF_STATUS_REPORT message to GCS - void send_status_report(mavlink_channel_t chan) const; + void send_status_report(class GCS_MAVLINK &link) const; // provides the height limit to be observed by the control loops // returns false if no height limiting is required @@ -556,6 +562,7 @@ class NavEKF3_core : public NavEKF_core_common struct tas_elements : EKF_obs_element_t { ftype tas; // true airspeed measurement (m/sec) ftype tasVariance; // variance of true airspeed measurement (m/sec)^2 + bool allowFusion; // true if measurement can be allowed to modify EKF states. }; struct of_elements : EKF_obs_element_t { @@ -983,6 +990,7 @@ class NavEKF3_core : public NavEKF_core_common bool hgtTimeout; // boolean true if height measurements have failed innovation consistency check and timed out bool magTimeout; // boolean true if magnetometer measurements have failed for too long and have timed out bool tasTimeout; // boolean true if true airspeed measurements have failed for too long and have timed out + bool dragTimeout; // boolean true if drag measurements have failed for too long and have timed out bool badIMUdata; // boolean true if the bad IMU data is detected uint32_t badIMUdata_ms; // time stamp bad IMU data was last detected uint32_t goodIMUdata_ms; // time stamp good IMU data was last detected @@ -1047,6 +1055,7 @@ class NavEKF3_core : public NavEKF_core_common uint32_t lastSynthYawTime_ms; // time stamp when yaw observation was last fused (msec) uint32_t ekfStartTime_ms; // time the EKF was started (msec) Vector2F lastKnownPositionNE; // last known position + float lastKnownPositionD; // last known height uint32_t lastLaunchAccelTime_ms; ftype velTestRatio; // sum of squares of GPS velocity innovation divided by fail threshold ftype posTestRatio; // sum of squares of GPS position innovation divided by fail threshold @@ -1162,13 +1171,17 @@ class NavEKF3_core : public NavEKF_core_common // variable used by the in-flight GPS quality check bool gpsSpdAccPass; // true when reported GPS speed accuracy passes in-flight checks + bool gpsVertAccPass; // true when reported GPS vertical accuracy passes in-flight checks bool ekfInnovationsPass; // true when GPS innovations pass in-flight checks ftype sAccFilterState1; // state variable for LPF applied to reported GPS speed accuracy ftype sAccFilterState2; // state variable for peak hold filter applied to reported GPS speed uint32_t lastGpsCheckTime_ms; // last time in msec the GPS quality was checked - uint32_t lastInnovPassTime_ms; // last time in msec the GPS innovations passed - uint32_t lastInnovFailTime_ms; // last time in msec the GPS innovations failed + uint32_t lastGpsInnovPassTime_ms; // last time in msec the GPS innovations passed + uint32_t lastGpsInnovFailTime_ms; // last time in msec the GPS innovations failed + uint32_t lastGpsVertAccPassTime_ms; // last time in msec the GPS vertical accuracy test passed + uint32_t lastGpsVertAccFailTime_ms; // last time in msec the GPS vertical accuracy test failed bool gpsAccuracyGood; // true when the GPS accuracy is considered to be good enough for safe flight. + bool gpsAccuracyGoodForAltitude; // true when the GPS accuracy is considered to be good enough to use it as an altitude source. Vector3F gpsVelInnov; // gps velocity innovations Vector3F gpsVelVarInnov; // gps velocity innovation variances uint32_t gpsVelInnovTime_ms; // system time that gps velocity innovations were recorded (to detect timeouts) @@ -1319,6 +1332,7 @@ class NavEKF3_core : public NavEKF_core_common Vector2F innovDragVar; // multirotor drag measurement innovation variance ((m/sec**2)**2) Vector2F dragTestRatio; // drag innovation consistency check ratio #endif + uint32_t lastDragPassTime_ms; // system time that drag samples were last successfully fused bool dragFusionEnabled; // height source selection logic diff --git a/libraries/AP_NavEKF3/LogStructure.h b/libraries/AP_NavEKF3/LogStructure.h index 702c0666826..f3ef63d1bfb 100644 --- a/libraries/AP_NavEKF3/LogStructure.h +++ b/libraries/AP_NavEKF3/LogStructure.h @@ -185,7 +185,7 @@ struct PACKED log_XKF3 { // @Field: OFN: Most recent position reset (North component) // @Field: OFE: Most recent position reset (East component) // @Field: FS: Filter fault status -// @Field: TS: Filter timeout status bitmask (0:position measurement, 1:velocity measurement, 2:height measurement, 3:magnetometer measurement, 4:airspeed measurement) +// @Field: TS: Filter timeout status bitmask (0:position measurement, 1:velocity measurement, 2:height measurement, 3:magnetometer measurement, 4:airspeed measurement, 5:drag measurement) // @Field: SS: Filter solution status // @Field: GPS: Filter GPS status // @Field: PI: Primary core index @@ -420,6 +420,7 @@ struct PACKED log_XKV { float v11; }; +#if HAL_NAVEKF3_AVAILABLE #define LOG_STRUCTURE_FROM_NAVEKF3 \ { LOG_XKF0_MSG, sizeof(log_XKF0), \ "XKF0","QBBccCCcccccccc","TimeUS,C,ID,rng,innov,SIV,TR,BPN,BPE,BPD,OFH,OFL,OFN,OFE,OFD", "s#-m---mmmmmmmm", "F--B---BBBBBBBB" , true }, \ @@ -448,3 +449,6 @@ struct PACKED log_XKV { "XKV1","QBffffffffffff","TimeUS,C,V00,V01,V02,V03,V04,V05,V06,V07,V08,V09,V10,V11", "s#------------", "F-------------" , true }, \ { LOG_XKV2_MSG, sizeof(log_XKV), \ "XKV2","QBffffffffffff","TimeUS,C,V12,V13,V14,V15,V16,V17,V18,V19,V20,V21,V22,V23", "s#------------", "F-------------" , true }, +#else + #define LOG_STRUCTURE_FROM_NAVEKF3 +#endif diff --git a/libraries/AP_NavEKF3/derivation/code_gen.py b/libraries/AP_NavEKF3/derivation/code_gen.py index 9e193b65eee..8aa14500b07 100644 --- a/libraries/AP_NavEKF3/derivation/code_gen.py +++ b/libraries/AP_NavEKF3/derivation/code_gen.py @@ -1,4 +1,3 @@ -#!/usr/bin/env python3 # -*- coding: utf-8 -*- # Taken from https://github.com/PX4/ecl/commit/264c8c4e8681704e4719d0a03b848df8617c0863 # and modified for ArduPilot diff --git a/libraries/AP_NavEKF3/derivation/main.py b/libraries/AP_NavEKF3/derivation/main.py old mode 100644 new mode 100755 index 72f50e91daa..4d541056042 --- a/libraries/AP_NavEKF3/derivation/main.py +++ b/libraries/AP_NavEKF3/derivation/main.py @@ -1,3 +1,4 @@ +#!/usr/bin/env python3 # Copied from https://github.com/PX4/ecl/commit/264c8c4e8681704e4719d0a03b848df8617c0863 # and modified for ArduPilot from sympy import * @@ -267,7 +268,7 @@ def body_frame_accel_observation(P,state,R_to_body,vx,vy,vz,wx,wy): # accYpred = -0.5*rho*vrel[1]*vrel[1]*BCYinv # predicted acceleration measured along Y body axis # Use a simple viscous drag model for the linear estimator equations - # Use the the derivative from speed to acceleration averaged across the + # Use the derivative from speed to acceleration averaged across the # speed range. This avoids the generation of a dirac function in the derivation # The nonlinear equation will be used to calculate the predicted measurement in implementation observation = Matrix([-Kaccx*vrel[0],-Kaccy*vrel[1]]) diff --git a/libraries/AP_Notify/AP_BoardLED.h b/libraries/AP_Notify/AP_BoardLED.h index c812b6316b9..810cacbde88 100644 --- a/libraries/AP_Notify/AP_BoardLED.h +++ b/libraries/AP_Notify/AP_BoardLED.h @@ -15,7 +15,7 @@ #pragma once #include -#include +#include #include "NotifyDevice.h" diff --git a/libraries/AP_Notify/AP_BoardLED2.h b/libraries/AP_Notify/AP_BoardLED2.h index e440aa4a050..2d6b5e19a01 100644 --- a/libraries/AP_Notify/AP_BoardLED2.h +++ b/libraries/AP_Notify/AP_BoardLED2.h @@ -17,7 +17,7 @@ #include -#include +#include #include "NotifyDevice.h" diff --git a/libraries/AP_Notify/AP_Notify.cpp b/libraries/AP_Notify/AP_Notify.cpp index 07a4b1253e0..1d4a80c9847 100644 --- a/libraries/AP_Notify/AP_Notify.cpp +++ b/libraries/AP_Notify/AP_Notify.cpp @@ -176,7 +176,7 @@ const AP_Param::GroupInfo AP_Notify::var_info[] = { // @Param: BUZZ_PIN // @DisplayName: Buzzer pin - // @Description: Enables to connect active buzzer to arbitrary pin. Requires 3-pin buzzer or additional MOSFET! + // @Description: Enables to connect active buzzer to arbitrary pin. Requires 3-pin buzzer or additional MOSFET! Some the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot. // @Values: 0:Disabled // @User: Advanced AP_GROUPINFO("BUZZ_PIN", 5, AP_Notify, _buzzer_pin, HAL_BUZZER_PIN), diff --git a/libraries/AP_Notify/Buzzer.h b/libraries/AP_Notify/Buzzer.h index 80567b5e58d..4098148e76d 100644 --- a/libraries/AP_Notify/Buzzer.h +++ b/libraries/AP_Notify/Buzzer.h @@ -17,8 +17,6 @@ */ #pragma once -#include - #include "NotifyDevice.h" class Buzzer: public NotifyDevice diff --git a/libraries/AP_Notify/DiscoLED.h b/libraries/AP_Notify/DiscoLED.h index ee5ca962591..3c7585327ed 100644 --- a/libraries/AP_Notify/DiscoLED.h +++ b/libraries/AP_Notify/DiscoLED.h @@ -16,7 +16,7 @@ */ #pragma once -#include +#include #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX #include diff --git a/libraries/AP_Notify/DiscreteRGBLed.cpp b/libraries/AP_Notify/DiscreteRGBLed.cpp index a3e5229f1f8..d47773e01ea 100644 --- a/libraries/AP_Notify/DiscreteRGBLed.cpp +++ b/libraries/AP_Notify/DiscreteRGBLed.cpp @@ -13,6 +13,8 @@ #include "DiscreteRGBLed.h" +#include + extern const AP_HAL::HAL& hal; DiscreteRGBLed::DiscreteRGBLed(uint16_t red, uint16_t green, uint16_t blue, bool normal_polarity) diff --git a/libraries/AP_Notify/ExternalLED.h b/libraries/AP_Notify/ExternalLED.h index 6c1b145d1d4..404d300636f 100644 --- a/libraries/AP_Notify/ExternalLED.h +++ b/libraries/AP_Notify/ExternalLED.h @@ -15,10 +15,6 @@ #pragma once -#include -#include -#include - #include "NotifyDevice.h" class ExternalLED: public NotifyDevice diff --git a/libraries/AP_Notify/Led_Sysfs.h b/libraries/AP_Notify/Led_Sysfs.h index 7deb049e043..be8fab15e80 100644 --- a/libraries/AP_Notify/Led_Sysfs.h +++ b/libraries/AP_Notify/Led_Sysfs.h @@ -16,7 +16,7 @@ */ #pragma once -#include +#include #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX #include diff --git a/libraries/AP_Notify/PixRacerLED.cpp b/libraries/AP_Notify/PixRacerLED.cpp index dda60f97ad8..3e543a0cf38 100644 --- a/libraries/AP_Notify/PixRacerLED.cpp +++ b/libraries/AP_Notify/PixRacerLED.cpp @@ -15,6 +15,8 @@ #include "PixRacerLED.h" +#include + #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS #ifndef HAL_GPIO_A_LED_PIN diff --git a/libraries/AP_Notify/PixRacerLED.h b/libraries/AP_Notify/PixRacerLED.h index 09083d11a79..43dc34ac033 100644 --- a/libraries/AP_Notify/PixRacerLED.h +++ b/libraries/AP_Notify/PixRacerLED.h @@ -14,9 +14,6 @@ */ #pragma once -#include -#include - #include "RGBLed.h" class PixRacerLED: public RGBLed diff --git a/libraries/AP_Notify/RGBLed.h b/libraries/AP_Notify/RGBLed.h index 9c2e7fa3758..46dad5726fb 100644 --- a/libraries/AP_Notify/RGBLed.h +++ b/libraries/AP_Notify/RGBLed.h @@ -19,7 +19,6 @@ */ #pragma once -#include #include "NotifyDevice.h" class RGBLed: public NotifyDevice { diff --git a/libraries/AP_Notify/SITL_SFML_LED.h b/libraries/AP_Notify/SITL_SFML_LED.h index 5750ab6ee8e..52dc039c94d 100644 --- a/libraries/AP_Notify/SITL_SFML_LED.h +++ b/libraries/AP_Notify/SITL_SFML_LED.h @@ -16,7 +16,7 @@ */ #pragma once -#include +#include #include #ifdef WITH_SITL_RGBLED diff --git a/libraries/AP_OLC/AP_OLC.h b/libraries/AP_OLC/AP_OLC.h index 377b3a360f7..4df3ddfad4e 100644 --- a/libraries/AP_OLC/AP_OLC.h +++ b/libraries/AP_OLC/AP_OLC.h @@ -17,7 +17,6 @@ #pragma once #include -#include #include #ifndef HAL_PLUSCODE_ENABLE diff --git a/libraries/AP_ONVIF/AP_ONVIF.h b/libraries/AP_ONVIF/AP_ONVIF.h index 470f85e4629..bbc72ffb195 100644 --- a/libraries/AP_ONVIF/AP_ONVIF.h +++ b/libraries/AP_ONVIF/AP_ONVIF.h @@ -16,7 +16,7 @@ */ #pragma once -#include +#include #if ENABLE_ONVIF #pragma GCC diagnostic push diff --git a/libraries/AP_ONVIF/soap/update_onvif_wsdl2h.sh b/libraries/AP_ONVIF/soap/update_onvif_wsdl2h.sh index 494ed5441c4..f68c4a4824f 100755 --- a/libraries/AP_ONVIF/soap/update_onvif_wsdl2h.sh +++ b/libraries/AP_ONVIF/soap/update_onvif_wsdl2h.sh @@ -1,3 +1,5 @@ +#!/bin/sh + cp ../../../modules/gsoap/gsoap/typemap.dat . wsdl2h -O4 -P -s -x -o onvif.h \ http://www.onvif.org/onvif/ver10/device/wsdl/devicemgmt.wsdl \ diff --git a/libraries/AP_OSD/AP_OSD.cpp b/libraries/AP_OSD/AP_OSD.cpp index 435d6c74d29..9101d2b847d 100644 --- a/libraries/AP_OSD/AP_OSD.cpp +++ b/libraries/AP_OSD/AP_OSD.cpp @@ -240,7 +240,7 @@ AP_OSD::AP_OSD() AP_Param::setup_object_defaults(this, var_info); #if OSD_ENABLED // default first screen enabled - screen[0].enabled = 1; + screen[0].enabled.set(1); previous_pwm_screen = -1; #endif #ifdef WITH_SITL_OSD @@ -267,11 +267,13 @@ void AP_OSD::init() if (!spi_dev) { break; } +#if HAL_WITH_OSD_BITMAP backend = AP_OSD_MAX7456::probe(*this, std::move(spi_dev)); +#endif if (backend == nullptr) { break; } - hal.console->printf("Started MAX7456 OSD\n"); + DEV_PRINTF("Started MAX7456 OSD\n"); #endif break; } @@ -282,7 +284,7 @@ void AP_OSD::init() if (backend == nullptr) { break; } - hal.console->printf("Started SITL OSD\n"); + DEV_PRINTF("Started SITL OSD\n"); break; } #endif @@ -291,7 +293,7 @@ void AP_OSD::init() if (backend == nullptr) { break; } - hal.console->printf("Started MSP OSD\n"); + DEV_PRINTF("Started MSP OSD\n"); break; } #if HAL_WITH_MSP_DISPLAYPORT @@ -300,7 +302,7 @@ void AP_OSD::init() if (backend == nullptr) { break; } - hal.console->printf("Started MSP DisplayPort OSD\n"); + DEV_PRINTF("Started MSP DisplayPort OSD\n"); break; } #endif @@ -318,6 +320,9 @@ void AP_OSD::init() #if OSD_ENABLED void AP_OSD::osd_thread() { + // initialize thread specific code once + backend->osd_thread_run_once(); + while (true) { hal.scheduler->delay(100); update_osd(); diff --git a/libraries/AP_OSD/AP_OSD.h b/libraries/AP_OSD/AP_OSD.h index 1f7884f2d90..022869b75d1 100644 --- a/libraries/AP_OSD/AP_OSD.h +++ b/libraries/AP_OSD/AP_OSD.h @@ -16,7 +16,8 @@ #pragma once -#include +#include +#include #include #include #include @@ -25,6 +26,8 @@ #include #include #include +#include +#include #ifndef OSD_ENABLED #define OSD_ENABLED !HAL_MINIMIZE_FEATURES @@ -91,7 +94,14 @@ class AP_OSD_AbstractScreen protected: bool check_option(uint32_t option); - +#ifdef HAL_WITH_MSP_DISPLAYPORT + virtual uint8_t get_txt_resolution() const { + return 0; + } + virtual uint8_t get_font_index() const { + return 0; + } +#endif enum unit_type { ALTITUDE=0, SPEED=1, @@ -131,6 +141,14 @@ class AP_OSD_Screen : public AP_OSD_AbstractScreen static const struct AP_Param::GroupInfo var_info[]; static const struct AP_Param::GroupInfo var_info2[]; +#ifdef HAL_WITH_MSP_DISPLAYPORT + uint8_t get_txt_resolution() const override { + return txt_resolution; + } + uint8_t get_font_index() const override { + return font_index; + } +#endif private: friend class AP_MSP; friend class AP_MSP_Telem_Backend; @@ -211,6 +229,12 @@ class AP_OSD_Screen : public AP_OSD_AbstractScreen AP_OSD_Setting batt_bar{true, 1, 1}; AP_OSD_Setting arming{true, 1, 1}; +#ifdef HAL_WITH_MSP_DISPLAYPORT + // Per screen HD resolution options (currently supported only by DisplayPort) + AP_Int8 txt_resolution; + AP_Int8 font_index; +#endif + void draw_altitude(uint8_t x, uint8_t y); void draw_bat_volt(uint8_t x, uint8_t y); void draw_avgcellvolt(uint8_t x, uint8_t y); @@ -273,10 +297,11 @@ class AP_OSD_Screen : public AP_OSD_AbstractScreen void draw_current2(uint8_t x, uint8_t y); void draw_vtx_power(uint8_t x, uint8_t y); void draw_hgt_abvterr(uint8_t x, uint8_t y); +#if AP_FENCE_ENABLED void draw_fence(uint8_t x, uint8_t y); +#endif void draw_rngf(uint8_t x, uint8_t y); - struct { bool load_attempted; const char *str; diff --git a/libraries/AP_OSD/AP_OSD_Backend.h b/libraries/AP_OSD/AP_OSD_Backend.h index 6a865f4c011..b52cf9b701a 100644 --- a/libraries/AP_OSD/AP_OSD_Backend.h +++ b/libraries/AP_OSD/AP_OSD_Backend.h @@ -56,6 +56,9 @@ class AP_OSD_Backend // copy the backend specific symbol set to the OSD lookup table virtual void init_symbol_set(uint8_t *symbols, const uint8_t size); + // called by the OSD thread once + virtual void osd_thread_run_once() { return; } + AP_OSD * get_osd() { return &_osd; diff --git a/libraries/AP_OSD/AP_OSD_MSP_DisplayPort.cpp b/libraries/AP_OSD/AP_OSD_MSP_DisplayPort.cpp index 6060eb309ec..2336e832779 100644 --- a/libraries/AP_OSD/AP_OSD_MSP_DisplayPort.cpp +++ b/libraries/AP_OSD/AP_OSD_MSP_DisplayPort.cpp @@ -50,8 +50,24 @@ bool AP_OSD_MSP_DisplayPort::init(void) return true; } +// called by the OSD thread once +void AP_OSD_MSP_DisplayPort::osd_thread_run_once() +{ + if (_displayport != nullptr) { + _displayport->init_uart(); + } +} + void AP_OSD_MSP_DisplayPort::clear(void) { + // check if we need to enable some options + // but only for actual OSD screens + if (_osd.get_current_screen() < AP_OSD_NUM_DISPLAY_SCREENS) { + const uint8_t txt_resolution = _osd.screen[_osd.get_current_screen()].get_txt_resolution(); + const uint8_t font_index = _osd.screen[_osd.get_current_screen()].get_font_index(); + _displayport->msp_displayport_set_options(font_index, txt_resolution); + } + // clear remote MSP screen _displayport->msp_displayport_clear_screen(); diff --git a/libraries/AP_OSD/AP_OSD_MSP_DisplayPort.h b/libraries/AP_OSD/AP_OSD_MSP_DisplayPort.h index 98c70d69a1f..a273edd5db6 100644 --- a/libraries/AP_OSD/AP_OSD_MSP_DisplayPort.h +++ b/libraries/AP_OSD/AP_OSD_MSP_DisplayPort.h @@ -24,6 +24,10 @@ class AP_OSD_MSP_DisplayPort : public AP_OSD_Backend // copy the backend specific symbol set to the OSD lookup table void init_symbol_set(uint8_t *lookup_table, const uint8_t size) override; + // called by the OSD thread once + // used to initialize the uart in the correct thread + void osd_thread_run_once() override; + protected: uint8_t format_string_for_osd(char* dst, uint8_t size, bool decimal_packed, const char *fmt, va_list ap) override; diff --git a/libraries/AP_OSD/AP_OSD_ParamScreen.cpp b/libraries/AP_OSD/AP_OSD_ParamScreen.cpp index 4e25178439f..b626296d0d8 100644 --- a/libraries/AP_OSD/AP_OSD_ParamScreen.cpp +++ b/libraries/AP_OSD/AP_OSD_ParamScreen.cpp @@ -26,9 +26,10 @@ #include #include #include -#include #include +#include #include +#include extern const AP_HAL::HAL& hal; @@ -375,11 +376,11 @@ void AP_OSD_ParamScreen::modify_configured_parameter(uint8_t number, Event ev) if (param != nullptr) { // update the stored index - setting._param_group = setting._current_token.group_element; - setting._param_key = AP_Param::get_persistent_key(setting._current_token.key); - setting._param_idx = setting._current_token.idx; + setting._param_group.set(setting._current_token.group_element); + setting._param_key.set(AP_Param::get_persistent_key(setting._current_token.key)); + setting._param_idx.set(setting._current_token.idx); setting._param = param; - setting._type = OSD_PARAM_NONE; + setting._type.set(OSD_PARAM_NONE); // force update() to refresh the token setting._current_token.key = 0; setting._current_token.idx = 0; @@ -629,7 +630,7 @@ void AP_OSD_ParamScreen::save_parameters() // handle OSD configuration messages #if HAL_GCS_ENABLED -void AP_OSD_ParamScreen::handle_write_msg(const mavlink_osd_param_config_t& packet, const GCS_MAVLINK& link) +void AP_OSD_ParamScreen::handle_write_msg(const mavlink_osd_param_config_t& packet, const class GCS_MAVLINK& link) { // request out of range - return an error if (packet.osd_index < 1 || packet.osd_index > AP_OSD_ParamScreen::NUM_PARAMS) { @@ -642,7 +643,7 @@ void AP_OSD_ParamScreen::handle_write_msg(const mavlink_osd_param_config_t& pack } // handle OSD show configuration messages -void AP_OSD_ParamScreen::handle_read_msg(const mavlink_osd_param_show_config_t& packet, const GCS_MAVLINK& link) +void AP_OSD_ParamScreen::handle_read_msg(const mavlink_osd_param_show_config_t& packet, const class GCS_MAVLINK& link) { // request out of range - return an error if (packet.osd_index < 1 || packet.osd_index > AP_OSD_ParamScreen::NUM_PARAMS) { diff --git a/libraries/AP_OSD/AP_OSD_ParamSetting.cpp b/libraries/AP_OSD/AP_OSD_ParamSetting.cpp index ff952ed88aa..a57aca80878 100644 --- a/libraries/AP_OSD/AP_OSD_ParamSetting.cpp +++ b/libraries/AP_OSD/AP_OSD_ParamSetting.cpp @@ -156,7 +156,7 @@ static const char* AUX_OPTIONS[] = { static const char* FLTMODES[] = { "MAN", "CIRC", "STAB", "TRAIN", "ACRO", "FBWA", "FBWB", "CRUISE", "ATUNE", "", "AUTO", "RTL", "LOIT", "TKOF", "ADSB", "GUID", "", "QSTAB", "QHOV", "QLOIT", "QLAND", - "QRTL", "QTUNE", "QACRO" + "QRTL", "QTUNE", "QACRO", "THRML", "L2QLND" }; static const char* FS_ACT[] = { @@ -176,7 +176,7 @@ const AP_OSD_ParamSetting::ParamMetadata AP_OSD_ParamSetting::_param_metadata[OS { -1, AP_SerialManager::SerialProtocol_NumProtocols - 1, 1, ARRAY_SIZE(SERIAL_PROTOCOL_VALUES), SERIAL_PROTOCOL_VALUES }, // OSD_PARAM_SERIAL_PROTOCOL { 0, SRV_Channel::k_nr_aux_servo_functions - 1, 1, ARRAY_SIZE(SERVO_FUNCTIONS), SERVO_FUNCTIONS }, // OSD_PARAM_SERVO_FUNCTION { 0, 105, 1, ARRAY_SIZE(AUX_OPTIONS), AUX_OPTIONS }, // OSD_PARAM_AUX_FUNCTION - { 0, 23, 1, ARRAY_SIZE(FLTMODES), FLTMODES }, // OSD_PARAM_FLIGHT_MODE + { 0, 25, 1, ARRAY_SIZE(FLTMODES), FLTMODES }, // OSD_PARAM_FLIGHT_MODE { 0, 5, 1, ARRAY_SIZE(FS_ACT), FS_ACT }, // OSD_PARAM_FAILSAFE_ACTION { 0, 3, 1, ARRAY_SIZE(FS_SHRT_ACTNS), FS_SHRT_ACTNS }, // OSD_PARAM_FAILSAFE_ACTION_1 { 0, 3, 1, ARRAY_SIZE(FS_LNG_ACTNS), FS_LNG_ACTNS }, // OSD_PARAM_FAILSAFE_ACTION_2 @@ -201,7 +201,8 @@ static const char* AUX_OPTIONS[] = { static const char* FLTMODES[] = { "STAB", "ACRO", "ALTHOLD", "AUTO", "GUIDED", "LOIT", "RTL", "CIRC", "", "LAND", "", "DRFT", "", "SPORT", "FLIP", "ATUN", "POSHLD", "BRAKE", "THROW", "AVD_ADSB", - "GUID_NOGPS", "SMRTRTL", "FLOHOLD", "FOLLOW", "ZIGZAG", "SYSID", "HELI_ARO" + "GUID_NOGPS", "SMRTRTL", "FLOHOLD", "FOLLOW", "ZIGZAG", "SYSID", "HELI_ARO", "AUTORTL", + "TRTLE" }; static const char* FS_OPTIONS[] = { @@ -222,7 +223,7 @@ const AP_OSD_ParamSetting::ParamMetadata AP_OSD_ParamSetting::_param_metadata[OS { -1, AP_SerialManager::SerialProtocol_NumProtocols - 1, 1, ARRAY_SIZE(SERIAL_PROTOCOL_VALUES), SERIAL_PROTOCOL_VALUES }, // OSD_PARAM_SERIAL_PROTOCOL { 0, SRV_Channel::k_nr_aux_servo_functions - 1, 1, ARRAY_SIZE(SERVO_FUNCTIONS), SERVO_FUNCTIONS }, // OSD_PARAM_SERVO_FUNCTION { 0, 105, 1, ARRAY_SIZE(AUX_OPTIONS), AUX_OPTIONS }, // OSD_PARAM_AUX_FUNCTION - { 0, 23, 1, ARRAY_SIZE(FLTMODES), FLTMODES }, // OSD_PARAM_FLIGHT_MODE + { 0, 28, 1, ARRAY_SIZE(FLTMODES), FLTMODES }, // OSD_PARAM_FLIGHT_MODE { 0, 3, 1, ARRAY_SIZE(FS_OPTIONS), FS_OPTIONS }, // OSD_PARAM_FAILSAFE_ACTION { 0, 5, 1, ARRAY_SIZE(FS_ACT), FS_ACT }, // OSD_PARAM_FAILSAFE_ACTION_1 { 0, 5, 1, ARRAY_SIZE(THR_FS_ACT), THR_FS_ACT }, // OSD_PARAM_FAILSAFE_ACTION_2 @@ -238,34 +239,34 @@ extern const AP_HAL::HAL& hal; AP_OSD_ParamSetting::AP_OSD_ParamSetting(uint8_t param_number, bool _enabled, uint8_t x, uint8_t y, int16_t key, int8_t idx, int32_t group, int8_t type, float min, float max, float incr) : AP_OSD_Setting(_enabled, x, y), _param_number(param_number) { - _param_group = group; - _param_idx = idx; - _param_key = key; - _param_min = min; - _param_max = max; - _param_incr = incr; - _type = type; + _param_group.set(group); + _param_idx.set(idx); + _param_key.set(key); + _param_min.set(min); + _param_max.set(max); + _param_incr.set(incr); + _type.set(type); } // default constructor that just sets some sensible defaults that exist on all platforms AP_OSD_ParamSetting::AP_OSD_ParamSetting(uint8_t param_number) : AP_OSD_Setting(false, 2, param_number + 1), _param_number(param_number) { - _param_min = 0.0f; - _param_max = 1.0f; - _param_incr = 0.001f; - _type = OSD_PARAM_NONE; + _param_min.set(0.0f); + _param_max.set(1.0f); + _param_incr.set(0.001f); + _type.set(OSD_PARAM_NONE); } // construct a setting from a compact static initializer structure AP_OSD_ParamSetting::AP_OSD_ParamSetting(const Initializer& initializer) : AP_OSD_ParamSetting(initializer.index) { - _param_group = initializer.token.group_element; - _param_idx = initializer.token.idx; - _param_key = initializer.token.key; - _type = initializer.type; - enabled = true; + _param_group.set(initializer.token.group_element); + _param_idx.set(initializer.token.idx); + _param_key.set(initializer.token.key); + _type.set(initializer.type); + enabled.set(true); } // update the contained parameter @@ -286,7 +287,7 @@ void AP_OSD_ParamSetting::update() } if (_param == nullptr) { - enabled = false; + enabled.set(false); } else { guess_ranges(); } @@ -380,7 +381,7 @@ void AP_OSD_ParamSetting::guess_ranges(bool force) float floatp = p->get(); if (digits < 1) { if (!is_zero(floatp)) { - incr = floatp / 100.0f; // move in 1% increments + incr = floatp * 0.01f; // move in 1% increments } else { incr = 0.01f; // move in absolute 1% increments } @@ -388,7 +389,7 @@ void AP_OSD_ParamSetting::guess_ranges(bool force) min = 0.0f; } else { if (!is_zero(floatp)) { - incr = floatp / 100.0f; // move in 1% increments + incr = floatp * 0.01f; // move in 1% increments } else { incr = MAX(1, powf(10, digits - 2)); } @@ -405,13 +406,13 @@ void AP_OSD_ParamSetting::guess_ranges(bool force) } if (force || !_param_min.configured()) { - _param_min = min; + _param_min.set(min); } if (force || !_param_max.configured()) { - _param_max = max; + _param_max.set(max); } if (force || !_param_incr.configured()) { - _param_incr = incr; + _param_incr.set(incr); } } } @@ -437,9 +438,9 @@ bool AP_OSD_ParamSetting::set_from_metadata() { // check for statically configured setting metadata if (_type > 0 && _type < OSD_PARAM_NUM_TYPES && _param_metadata[_type - 1].values_max > 0) { - _param_incr = _param_metadata[_type - 1].increment; - _param_min = _param_metadata[_type - 1].min_value; - _param_max = _param_metadata[_type - 1].max_value; + _param_incr.set(_param_metadata[_type - 1].increment); + _param_min.set(_param_metadata[_type - 1].min_value); + _param_max.set(_param_metadata[_type - 1].max_value); return true; } return false; diff --git a/libraries/AP_OSD/AP_OSD_Screen.cpp b/libraries/AP_OSD/AP_OSD_Screen.cpp index 3e8079ceded..adaf2b5521a 100644 --- a/libraries/AP_OSD/AP_OSD_Screen.cpp +++ b/libraries/AP_OSD/AP_OSD_Screen.cpp @@ -1022,6 +1022,21 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info2[] = { // @Range: 0 15 AP_SUBGROUPINFO(link_quality, "LINK_Q", 1, AP_OSD_Screen, AP_OSD_Setting), +#if HAL_WITH_MSP_DISPLAYPORT + // @Param: TXT_RES + // @DisplayName: Sets the overlay text resolution (MSP DisplayPort only) + // @Description: Sets the overlay text resolution for this screen to either LD 30x16 or HD 50x18 (MSP DisplayPort only) + // @Values: 0:30x16,1:50x18 + // @User: Standard + AP_GROUPINFO("TXT_RES", 3, AP_OSD_Screen, txt_resolution, 0), + + // @Param: FONT + // @DisplayName: Sets the font index for this screen (MSP DisplayPort only) + // @Description: Sets the font index for this screen (MSP DisplayPort only) + // @Range: 0 15 + // @User: Standard + AP_GROUPINFO("FONT", 4, AP_OSD_Screen, font_index, 0), +#endif AP_GROUPEND }; @@ -1290,7 +1305,7 @@ void AP_OSD_Screen::draw_avgcellvolt(uint8_t x, uint8_t y) uint8_t p = (100 - pct) / 16.6; float v = battery.voltage(); // calculate cell count - WARNING this can be inaccurate if the LIPO/LIION battery is far from fully charged when attached and is used in this panel - osd->max_battery_voltage = MAX(osd->max_battery_voltage,v); + osd->max_battery_voltage.set(MAX(osd->max_battery_voltage,v)); if (osd->cell_count > 0) { v = v / osd->cell_count; backend->write(x,y, v < osd->warn_avgcellvolt, "%c%1.2f%c", SYMBOL(SYM_BATT_FULL) + p, v, SYMBOL(SYM_VOLT)); @@ -1318,7 +1333,7 @@ void AP_OSD_Screen::draw_rssi(uint8_t x, uint8_t y) { AP_RSSI *ap_rssi = AP_RSSI::get_singleton(); if (ap_rssi) { - const uint8_t rssiv = ap_rssi->read_receiver_rssi() * 99; + const uint8_t rssiv = ap_rssi->read_receiver_rssi() * 100; backend->write(x, y, rssiv < osd->warn_rssi, "%c%2d", SYMBOL(SYM_RSSI), rssiv); } } @@ -1862,7 +1877,7 @@ void AP_OSD_Screen::draw_temp(uint8_t x, uint8_t y) void AP_OSD_Screen::draw_hdop(uint8_t x, uint8_t y) { AP_GPS & gps = AP::gps(); - float hdp = gps.get_hdop() / 100.0f; + float hdp = gps.get_hdop() * 0.01f; backend->write(x, y, false, "%c%c%3.2f", SYMBOL(SYM_HDOP_L), SYMBOL(SYM_HDOP_R), (double)hdp); } @@ -1891,7 +1906,7 @@ void AP_OSD_Screen::draw_stat(uint8_t x, uint8_t y) backend->write(x+2, y, false, "%c%c%c", 0x4d,0x41,0x58); backend->write(x, y+1, false, "%c",SYMBOL(SYM_GSPD)); backend->write(x+1, y+1, false, "%4d%c", (int)u_scale(SPEED, osd->_stats.max_speed_mps), u_icon(SPEED)); - backend->write(x, y+2, false, "%5.1f%c", (double)osd->_stats.max_current_a, SYM_AMP); + backend->write(x, y+2, false, "%5.1f%c", (double)osd->_stats.max_current_a, SYMBOL(SYM_AMP)); backend->write(x, y+3, false, "%5d%c", (int)u_scale(ALTITUDE, osd->_stats.max_alt_m), u_icon(ALTITUDE)); backend->write(x, y+4, false, "%c", SYMBOL(SYM_HOME)); draw_distance(x+1, y+4, osd->_stats.max_dist_m); @@ -2124,7 +2139,7 @@ void AP_OSD_Screen::draw_hgt_abvterr(uint8_t x, uint8_t y) } #endif - +#if AP_FENCE_ENABLED void AP_OSD_Screen::draw_fence(uint8_t x, uint8_t y) { AC_Fence *fenceptr = AP::fence(); @@ -2137,6 +2152,7 @@ void AP_OSD_Screen::draw_fence(uint8_t x, uint8_t y) backend->write(x, y, false, "%c", SYMBOL(SYM_FENCE_DISABLED)); } } +#endif void AP_OSD_Screen::draw_rngf(uint8_t x, uint8_t y) { @@ -2200,7 +2216,9 @@ void AP_OSD_Screen::draw(void) DRAW_SETTING(heading); DRAW_SETTING(wind); DRAW_SETTING(home); +#if AP_FENCE_ENABLED DRAW_SETTING(fence); +#endif DRAW_SETTING(roll_angle); DRAW_SETTING(pitch_angle); DRAW_SETTING(temp); diff --git a/libraries/AP_OSD/AP_OSD_Setting.cpp b/libraries/AP_OSD/AP_OSD_Setting.cpp index fd21befac04..c60f86aa183 100644 --- a/libraries/AP_OSD/AP_OSD_Setting.cpp +++ b/libraries/AP_OSD/AP_OSD_Setting.cpp @@ -51,7 +51,7 @@ const AP_Param::GroupInfo AP_OSD_Setting::var_info[] = { // constructor AP_OSD_Setting::AP_OSD_Setting(bool _enabled, uint8_t x, uint8_t y) { - enabled = _enabled; - xpos = x; - ypos = y; + enabled.set(_enabled); + xpos.set(x); + ypos.set(y); } diff --git a/libraries/AP_OpenDroneID/AP_OpenDroneID.cpp b/libraries/AP_OpenDroneID/AP_OpenDroneID.cpp new file mode 100644 index 00000000000..f3fbc99e42a --- /dev/null +++ b/libraries/AP_OpenDroneID/AP_OpenDroneID.cpp @@ -0,0 +1,715 @@ +/* + * This file is free software: you can redistribute it and/or modify it + * under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program. If not, see . + */ +/* + * + * original code by: + * BlueMark Innovations BV, Roel Schiphorst + * Contributors: Tom Pittenger, Josh Henderson, Andrew Tridgell + * Parts of this code are based on/copied from the Open Drone ID project https://github.com/opendroneid/opendroneid-core-c + * + * The code has been tested with the BlueMark DroneBeacon MAVLink transponder running this command in the ArduPlane folder: + * sim_vehicle.py --console --map -A --serial1=uart:/dev/ttyUSB1:9600 + * (and a DroneBeacon MAVLink transponder connected to ttyUSB1) + * + * See https://github.com/ArduPilot/ArduRemoteID for an open implementation of a transmitter module on serial + * and DroneCAN + */ + +#include "AP_OpenDroneID.h" + +#if AP_OPENDRONEID_ENABLED + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +extern const AP_HAL::HAL &hal; + +const AP_Param::GroupInfo AP_OpenDroneID::var_info[] = { + + // @Param: ENABLE + // @DisplayName: Enable ODID subsystem + // @Description: Enable ODID subsystem + // @Values: 0:Disabled,1:Enabled + AP_GROUPINFO_FLAGS("ENABLE", 1, AP_OpenDroneID, _enable, 0, AP_PARAM_FLAG_ENABLE), + + // @Param: MAVPORT + // @DisplayName: MAVLink serial port + // @Description: Serial port number to send OpenDroneID MAVLink messages to. Can be -1 if using DroneCAN. + // @Values: -1:Disabled,0:Serial0,1:Serial1,2:Serial2,3:Serial3,4:Serial4,5:Serial5,6:Serial6 + AP_GROUPINFO("MAVPORT", 2, AP_OpenDroneID, _mav_port, -1), + + // @Param: CANDRIVER + // @DisplayName: DroneCAN driver number + // @Description: DroneCAN driver index, 0 to disable DroneCAN + // @Values: 0:Disabled,1:Driver1,2:Driver2 + AP_GROUPINFO("CANDRIVER", 3, AP_OpenDroneID, _can_driver, 0), + + // @Param: OPTIONS + // @DisplayName: OpenDroneID options + // @Description: Options for OpenDroneID subsystem + // @Bitmask: 0:EnforceArming, 1:AllowNonGPSPosition + AP_GROUPINFO("OPTIONS", 4, AP_OpenDroneID, _options, 0), + + // @Param: BARO_ACC + // @DisplayName: Barometer vertical accuraacy + // @Description: Barometer Vertical Accuracy when installed in the vehicle. Note this is dependent upon installation conditions and thus disabled by default + // @Units: m + // @User: Advanced + AP_GROUPINFO("BARO_ACC", 5, AP_OpenDroneID, _baro_accuracy, -1.0), + + AP_GROUPEND +}; + +// constructor +AP_OpenDroneID::AP_OpenDroneID() +{ +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL + if (_singleton != nullptr) { + AP_HAL::panic("OpenDroneID must be singleton"); + } +#endif + _singleton = this; + AP_Param::setup_object_defaults(this, var_info); +} + +void AP_OpenDroneID::init() +{ + if (_enable == 0) { + return; + } + + _chan = mavlink_channel_t(gcs().get_channel_from_port_number(_mav_port)); +} + +// Perform the pre-arm checks and prevent arming if they are not satisifed +// Except in the case of an in-flight reboot +bool AP_OpenDroneID::pre_arm_check(char* failmsg, uint8_t failmsg_len) +{ + WITH_SEMAPHORE(_sem); + + if (!option_enabled(Options::EnforceArming)) { + return true; + } + + if (pkt_basic_id.id_type == MAV_ODID_ID_TYPE_NONE) { + strncpy(failmsg, "UA_TYPE required in BasicID", failmsg_len); + return false; + } + + if (pkt_system.operator_latitude == 0 && pkt_system.operator_longitude == 0) { + strncpy(failmsg, "operator location must be set", failmsg_len); + return false; + } + + const uint32_t max_age_ms = 3000; + const uint32_t now_ms = AP_HAL::millis(); + + if (last_arm_status_ms == 0 || now_ms - last_arm_status_ms > max_age_ms) { + strncpy(failmsg, "ARM_STATUS not available", failmsg_len); + return false; + } + + if (last_system_ms == 0 || + (now_ms - last_system_ms > max_age_ms && + (now_ms - last_system_update_ms > max_age_ms))) { + strncpy(failmsg, "SYSTEM not available", failmsg_len); + return false; + } + + if (arm_status.status != MAV_ODID_GOOD_TO_ARM) { + strncpy(failmsg, arm_status.error, failmsg_len); + return false; + } + + return true; +} + +void AP_OpenDroneID::update() +{ + if (_enable == 0) { + return; + } + + const bool armed = hal.util->get_soft_armed(); + if (armed && !_was_armed) { + // use arm location as takeoff location + AP::ahrs().get_location(_takeoff_location); + } + _was_armed = armed; + + send_dynamic_out(); + send_static_out(); +} + +// local payload space check which treats invalid channel as having space +// needed to populate the message structures for the DroneCAN backend +#define ODID_HAVE_PAYLOAD_SPACE(id) (_chan == MAV_CHAN_INVALID || HAVE_PAYLOAD_SPACE(_chan, id)) + +void AP_OpenDroneID::send_dynamic_out() +{ + const uint32_t now = AP_HAL::millis(); + if (now - _last_send_location_ms >= _mavlink_dynamic_period_ms && + ODID_HAVE_PAYLOAD_SPACE(OPEN_DRONE_ID_LOCATION)) { + _last_send_location_ms = now; + send_location_message(); + } + + // operator location needs to be sent at the same rate as location for FAA compliance + if (now - _last_send_system_update_ms >= _mavlink_dynamic_period_ms && + ODID_HAVE_PAYLOAD_SPACE(OPEN_DRONE_ID_SYSTEM_UPDATE)) { + _last_send_system_update_ms = now; + send_system_update_message(); + } +} + +void AP_OpenDroneID::send_static_out() +{ + const uint32_t now_ms = AP_HAL::millis(); + + // we need to notify user if we lost the transmitter + if (now_ms - last_arm_status_ms > 5000) { + if (now_ms - last_lost_tx_ms > 5000) { + last_lost_tx_ms = now_ms; + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "ODID: lost transmitter"); + } + } else if (last_lost_tx_ms != 0) { + // we're OK again + last_lost_tx_ms = 0; + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ODID: transmitter OK"); + } + + // we need to notify user if we lost system msg with operator location + if (now_ms - last_system_ms > 5000 && now_ms - last_lost_operator_msg_ms > 5000) { + last_lost_operator_msg_ms = now_ms; + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "ODID: lost operator location"); + } + + const uint32_t msg_spacing_ms = _mavlink_static_period_ms / 4; + if (now_ms - last_msg_send_ms >= msg_spacing_ms) { + // allow update of channel during setup, this makes it easy to debug with a GCS + _chan = mavlink_channel_t(gcs().get_channel_from_port_number(_mav_port)); + bool sent_ok = false; + switch (next_msg_to_send) { + case NEXT_MSG_BASIC_ID: + if (ODID_HAVE_PAYLOAD_SPACE(OPEN_DRONE_ID_BASIC_ID)) { + send_basic_id_message(); + sent_ok = true; + } + break; + case NEXT_MSG_SYSTEM: + if (ODID_HAVE_PAYLOAD_SPACE(OPEN_DRONE_ID_SYSTEM)) { + send_system_message(); + sent_ok = true; + } + break; + case NEXT_MSG_SELF_ID: + if (ODID_HAVE_PAYLOAD_SPACE(OPEN_DRONE_ID_SELF_ID)) { + send_self_id_message(); + sent_ok = true; + } + break; + case NEXT_MSG_OPERATOR_ID: + if (ODID_HAVE_PAYLOAD_SPACE(OPEN_DRONE_ID_OPERATOR_ID)) { + send_operator_id_message(); + sent_ok = true; + } + break; + case NEXT_MSG_ENUM_END: + break; + } + if (sent_ok) { + last_msg_send_ms = now_ms; + next_msg_to_send = next_msg((uint8_t(next_msg_to_send) + 1) % uint8_t(NEXT_MSG_ENUM_END)); + } + } +} + +// The send_location_message +// all open_drone_id send functions use data stored in the open drone id class. +// This location send function is an exception. It uses live location data from the ArduPilot system. +void AP_OpenDroneID::send_location_message() +{ + auto &ahrs = AP::ahrs(); + const auto &barometer = AP::baro(); + const auto &gps = AP::gps(); + + const AP_GPS::GPS_Status gps_status = gps.status(); + const bool got_bad_gps_fix = (gps_status < AP_GPS::GPS_Status::GPS_OK_FIX_3D); + const bool armed = hal.util->get_soft_armed(); + + Location current_location; + if (!ahrs.get_location(current_location)) { + return; + } + uint8_t uav_status = hal.util->get_soft_armed()? MAV_ODID_STATUS_AIRBORNE : MAV_ODID_STATUS_GROUND; +#if HAL_PARACHUTE_ENABLED + // set emergency status if chute is released + const auto *parachute = AP::parachute(); + if (parachute != nullptr && parachute->released()) { + uav_status = MAV_ODID_STATUS_EMERGENCY; + } +#endif + if (AP::vehicle()->is_crashed()) { + // if in crashed state also declare an emergency + uav_status = MAV_ODID_STATUS_EMERGENCY; + } + + // if we are armed with no GPS fix and we haven't specifically + // allowed for non-GPS operation then declare an emergency + if (got_bad_gps_fix && armed && !option_enabled(Options::AllowNonGPSPosition)) { + uav_status = MAV_ODID_STATUS_EMERGENCY; + } + + // if we are disarmed and falling at over 3m/s then declare an + // emergency. This covers cases such as deliberate crash with + // advanced failsafe and an unintended reboot or in-flight disarm + if (!got_bad_gps_fix && !armed && gps.velocity().z > 3.0) { + uav_status = MAV_ODID_STATUS_EMERGENCY; + } + + // if we have watchdogged while armed then declare an emergency + if (hal.util->was_watchdog_armed()) { + uav_status = MAV_ODID_STATUS_EMERGENCY; + } + + float direction = ODID_INV_DIR; + if (!got_bad_gps_fix) { + direction = wrap_360(degrees(ahrs.groundspeed_vector().angle())); // heading (degrees) + } + + const float speed_horizontal = create_speed_horizontal(ahrs.groundspeed()); + + Vector3f velNED; + UNUSED_RESULT(ahrs.get_velocity_NED(velNED)); + const float climb_rate = create_speed_vertical(-velNED.z); //make sure climb_rate is within Remote ID limit + + int32_t latitude = 0; + int32_t longitude = 0; + if (current_location.check_latlng()) { //set location if they are valid + latitude = current_location.lat; + longitude = current_location.lng; + } + + // altitude referenced against 1013.2mb + const float base_press_mbar = 1013.2; + const float altitude_barometric = create_altitude(barometer.get_altitude_difference(base_press_mbar*100, barometer.get_pressure())); + + float altitude_geodetic = -1000; + int32_t alt_amsl_cm; + float undulation; + if (current_location.get_alt_cm(Location::AltFrame::ABSOLUTE, alt_amsl_cm)) { + altitude_geodetic = alt_amsl_cm * 0.01; + } + if (gps.get_undulation(undulation)) { + altitude_geodetic -= undulation; + } + + // Compute the current height above the takeoff location + float height_above_takeoff = 0; // height above takeoff (meters) + if (hal.util->get_soft_armed()) { + int32_t curr_alt_asml_cm; + int32_t takeoff_alt_asml_cm; + if (current_location.get_alt_cm(Location::AltFrame::ABSOLUTE, curr_alt_asml_cm) && + _takeoff_location.get_alt_cm(Location::AltFrame::ABSOLUTE, takeoff_alt_asml_cm)) { + height_above_takeoff = (curr_alt_asml_cm - takeoff_alt_asml_cm) * 0.01; + } + } + + // Accuracy + + // If we have GPS 3D lock we presume that the accuracies of the system will track the GPS's reported accuracy + MAV_ODID_HOR_ACC horizontal_accuracy_mav = MAV_ODID_HOR_ACC_UNKNOWN; + MAV_ODID_VER_ACC vertical_accuracy_mav = MAV_ODID_VER_ACC_UNKNOWN; + MAV_ODID_SPEED_ACC speed_accuracy_mav = MAV_ODID_SPEED_ACC_UNKNOWN; + MAV_ODID_TIME_ACC timestamp_accuracy_mav = MAV_ODID_TIME_ACC_UNKNOWN; + + float horizontal_accuracy; + if (gps.horizontal_accuracy(horizontal_accuracy)) { + horizontal_accuracy_mav = create_enum_horizontal_accuracy(horizontal_accuracy); + } + + float vertical_accuracy; + if (gps.vertical_accuracy(vertical_accuracy)) { + vertical_accuracy_mav = create_enum_vertical_accuracy(vertical_accuracy); + } + + float speed_accuracy; + if (gps.speed_accuracy(speed_accuracy)) { + speed_accuracy_mav = create_enum_speed_accuracy(speed_accuracy); + } + + // if we have ever had GPS lock then we will have better than 1s + // accuracy, as we use system timer to propogate time + timestamp_accuracy_mav = create_enum_timestamp_accuracy(1.0); + + // Barometer altitude accuraacy will be highly dependent on the airframe and installation of the barometer in use + // thus ArduPilot cannot reasonably fill this in. + // Instead allow a manufacturer to use a parameter to fill this in + uint8_t barometer_accuracy = MAV_ODID_VER_ACC_UNKNOWN; //ahrs class does not provide accuracy readings + if (!is_equal(_baro_accuracy.get(), -1.0f)) { + barometer_accuracy = create_enum_vertical_accuracy(_baro_accuracy); + } + + // Timestamp here is the number of seconds after into the current hour referenced to UTC time (up to one hour) + + // FIX we need to only set this if w have a GPS lock is 2D good enough for that? + float timestamp = ODID_INV_TIMESTAMP; + if (!got_bad_gps_fix) { + uint32_t time_week_ms = gps.time_week_ms(); + timestamp = float(time_week_ms % (3600 * 1000)) * 0.001; + timestamp = create_location_timestamp(timestamp); //make sure timestamp is within Remote ID limit + } + + + { + WITH_SEMAPHORE(_sem); + // take semaphore so CAN gets a consistent packet + pkt_location = mavlink_open_drone_id_location_t{ + latitude : latitude, + longitude : longitude, + altitude_barometric : altitude_barometric, + altitude_geodetic : altitude_geodetic, + height : height_above_takeoff, + timestamp : timestamp, + direction : uint16_t(direction * 100.0), // Heading (centi-degrees) + speed_horizontal : uint16_t(speed_horizontal * 100.0), // Ground speed (cm/s) + speed_vertical : int16_t(climb_rate * 100.0), // Climb rate (cm/s) + target_system : 0, + target_component : 0, + id_or_mac : {}, + status : uint8_t(uav_status), + height_reference : MAV_ODID_HEIGHT_REF_OVER_TAKEOFF, // height reference enum: Above takeoff location or above ground + horizontal_accuracy : uint8_t(horizontal_accuracy_mav), + vertical_accuracy : uint8_t(vertical_accuracy_mav), + barometer_accuracy : barometer_accuracy, + speed_accuracy : uint8_t(speed_accuracy_mav), + timestamp_accuracy : uint8_t(timestamp_accuracy_mav) + }; + need_send_location = dronecan_send_all; + } + + if (_chan != MAV_CHAN_INVALID) { + mavlink_msg_open_drone_id_location_send_struct(_chan, &pkt_location); + } +} + +void AP_OpenDroneID::send_basic_id_message() +{ + // note that packet is filled in by the GCS + need_send_basic_id |= dronecan_send_all; + if (_chan != MAV_CHAN_INVALID) { + mavlink_msg_open_drone_id_basic_id_send_struct(_chan, &pkt_basic_id); + } +} + +void AP_OpenDroneID::send_system_message() +{ + // note that packet is filled in by the GCS + need_send_system |= dronecan_send_all; + if (_chan != MAV_CHAN_INVALID) { + mavlink_msg_open_drone_id_system_send_struct(_chan, &pkt_system); + } +} + +void AP_OpenDroneID::send_self_id_message() +{ + need_send_self_id |= dronecan_send_all; + if (_chan != MAV_CHAN_INVALID) { + mavlink_msg_open_drone_id_self_id_send_struct(_chan, &pkt_self_id); + } +} + +void AP_OpenDroneID::send_system_update_message() +{ + need_send_system |= dronecan_send_all; + // note that packet is filled in by the GCS + if (_chan != MAV_CHAN_INVALID) { + const auto pkt_system_update = mavlink_open_drone_id_system_update_t { + operator_latitude : pkt_system.operator_latitude, + operator_longitude : pkt_system.operator_longitude, + operator_altitude_geo : pkt_system.operator_altitude_geo, + timestamp : pkt_system.timestamp, + target_system : pkt_system.target_system, + target_component : pkt_system.target_component, + }; + mavlink_msg_open_drone_id_system_update_send_struct(_chan, &pkt_system_update); + } +} + +void AP_OpenDroneID::send_operator_id_message() +{ + need_send_operator_id |= dronecan_send_all; + // note that packet is filled in by the GCS + if (_chan != MAV_CHAN_INVALID) { + mavlink_msg_open_drone_id_operator_id_send_struct(_chan, &pkt_operator_id); + } +} + +/* +* This converts a horizontal accuracy float value to the corresponding enum +* +* @param Accuracy The horizontal accuracy in meters +* @return Enum value representing the accuracy +*/ +MAV_ODID_HOR_ACC AP_OpenDroneID::create_enum_horizontal_accuracy(float accuracy) const +{ + // Out of bounds return UKNOWN flag + if (accuracy < 0.0 || accuracy >= 18520.0) { + return MAV_ODID_HOR_ACC_UNKNOWN; + } + + static const struct { + float accuracy; // Accuracy bound in meters + MAV_ODID_HOR_ACC mavoutput; // mavlink enum output + } horiz_accuracy_table[] = { + { 1.0, MAV_ODID_HOR_ACC_1_METER}, + { 3.0, MAV_ODID_HOR_ACC_3_METER}, + {10.0, MAV_ODID_HOR_ACC_10_METER}, + {30.0, MAV_ODID_HOR_ACC_30_METER}, + {92.6, MAV_ODID_HOR_ACC_0_05NM}, + {185.2, MAV_ODID_HOR_ACC_0_1NM}, + {555.6, MAV_ODID_HOR_ACC_0_3NM}, + {926.0, MAV_ODID_HOR_ACC_0_5NM}, + {1852.0, MAV_ODID_HOR_ACC_1NM}, + {3704.0, MAV_ODID_HOR_ACC_2NM}, + {7408.0, MAV_ODID_HOR_ACC_4NM}, + {18520.0, MAV_ODID_HOR_ACC_10NM}, + }; + + for (auto elem : horiz_accuracy_table) { + if (accuracy < elem.accuracy) { + return elem.mavoutput; + } + } + + // Should not reach this + return MAV_ODID_HOR_ACC_UNKNOWN; +} + +/** +* This converts a vertical accuracy float value to the corresponding enum +* +* @param Accuracy The vertical accuracy in meters +* @return Enum value representing the accuracy +*/ +MAV_ODID_VER_ACC AP_OpenDroneID::create_enum_vertical_accuracy(float accuracy) const +{ + // Out of bounds return UKNOWN flag + if (accuracy < 0.0 || accuracy >= 150.0) { + return MAV_ODID_VER_ACC_UNKNOWN; + } + + static const struct { + float accuracy; // Accuracy bound in meters + MAV_ODID_VER_ACC mavoutput; // mavlink enum output + } vertical_accuracy_table[] = { + { 1.0, MAV_ODID_VER_ACC_1_METER}, + { 3.0, MAV_ODID_VER_ACC_3_METER}, + {10.0, MAV_ODID_VER_ACC_10_METER}, + {25.0, MAV_ODID_VER_ACC_25_METER}, + {45.0, MAV_ODID_VER_ACC_45_METER}, + {150.0, MAV_ODID_VER_ACC_150_METER}, + }; + + for (auto elem : vertical_accuracy_table) { + if (accuracy < elem.accuracy) { + return elem.mavoutput; + } + } + + // Should not reach this + return MAV_ODID_VER_ACC_UNKNOWN; +} + +/** +* This converts a speed accuracy float value to the corresponding enum +* +* @param Accuracy The speed accuracy in m/s +* @return Enum value representing the accuracy +*/ +MAV_ODID_SPEED_ACC AP_OpenDroneID::create_enum_speed_accuracy(float accuracy) const +{ + // Out of bounds return UKNOWN flag + if (accuracy < 0.0 || accuracy >= 10.0) { + return MAV_ODID_SPEED_ACC_UNKNOWN; + } + + if (accuracy < 0.3) { + return MAV_ODID_SPEED_ACC_0_3_METERS_PER_SECOND; + } else if (accuracy < 1.0) { + return MAV_ODID_SPEED_ACC_1_METERS_PER_SECOND; + } else if (accuracy < 3.0) { + return MAV_ODID_SPEED_ACC_3_METERS_PER_SECOND; + } else if (accuracy < 10.0) { + return MAV_ODID_SPEED_ACC_10_METERS_PER_SECOND; + } + + // Should not reach this + return MAV_ODID_SPEED_ACC_UNKNOWN; +} + +/** +* This converts a timestamp accuracy float value to the corresponding enum +* +* @param Accuracy The timestamp accuracy in seconds +* @return Enum value representing the accuracy +*/ +MAV_ODID_TIME_ACC AP_OpenDroneID::create_enum_timestamp_accuracy(float accuracy) const +{ + // Out of bounds return UKNOWN flag + if (accuracy < 0.0 || accuracy >= 1.5) { + return MAV_ODID_TIME_ACC_UNKNOWN; + } + + static const MAV_ODID_TIME_ACC mavoutput [15] = { + MAV_ODID_TIME_ACC_0_1_SECOND, + MAV_ODID_TIME_ACC_0_2_SECOND, + MAV_ODID_TIME_ACC_0_3_SECOND, + MAV_ODID_TIME_ACC_0_4_SECOND, + MAV_ODID_TIME_ACC_0_5_SECOND, + MAV_ODID_TIME_ACC_0_6_SECOND, + MAV_ODID_TIME_ACC_0_7_SECOND, + MAV_ODID_TIME_ACC_0_8_SECOND, + MAV_ODID_TIME_ACC_0_9_SECOND, + MAV_ODID_TIME_ACC_1_0_SECOND, + MAV_ODID_TIME_ACC_1_1_SECOND, + MAV_ODID_TIME_ACC_1_2_SECOND, + MAV_ODID_TIME_ACC_1_3_SECOND, + MAV_ODID_TIME_ACC_1_4_SECOND, + MAV_ODID_TIME_ACC_1_5_SECOND, + }; + + for (int8_t i = 1; i <= 15; i++) { + if (accuracy <= 0.1 * i) { + return mavoutput[i-1]; + } + } + + // Should not reach this + return MAV_ODID_TIME_ACC_UNKNOWN; +} + +// make sure value is within limits of remote ID standard +uint16_t AP_OpenDroneID::create_speed_horizontal(uint16_t speed) const +{ + if (speed > ODID_MAX_SPEED_H) { // constraint function can't be used, because out of range value is invalid + speed = ODID_INV_SPEED_H; + } + + return speed; +} + +// make sure value is within limits of remote ID standard +int16_t AP_OpenDroneID::create_speed_vertical(int16_t speed) const +{ + if (speed > ODID_MAX_SPEED_V) { // constraint function can't be used, because out of range value is invalid + speed = ODID_INV_SPEED_V; + } else if (speed < ODID_MIN_SPEED_V) { + speed = ODID_INV_SPEED_V; + } + + return speed; +} + +// make sure value is within limits of remote ID standard +float AP_OpenDroneID::create_altitude(float altitude) const +{ + if (altitude > ODID_MAX_ALT) { // constraint function can't be used, because out of range value is invalid + altitude = ODID_INV_ALT; + } else if (altitude < ODID_MIN_ALT) { + altitude = ODID_INV_ALT; + } + + return altitude; +} + +// make sure value is within limits of remote ID standard +float AP_OpenDroneID::create_location_timestamp(float timestamp) const +{ + if (timestamp > ODID_MAX_TIMESTAMP) { // constraint function can't be used, because out of range value is invalid + timestamp = ODID_INV_TIMESTAMP; + } else if (timestamp < 0) { + timestamp = ODID_INV_TIMESTAMP; + } + + return timestamp; +} + +// handle a message from the GCS +void AP_OpenDroneID::handle_msg(mavlink_channel_t chan, const mavlink_message_t &msg) +{ + WITH_SEMAPHORE(_sem); + + switch (msg.msgid) { + // only accept ARM_STATUS from the transmitter + case MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS: { + if (chan == _chan) { + mavlink_msg_open_drone_id_arm_status_decode(&msg, &arm_status); + last_arm_status_ms = AP_HAL::millis(); + } + break; + } + // accept other messages from the GCS + case MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID: + mavlink_msg_open_drone_id_operator_id_decode(&msg, &pkt_operator_id); + break; + case MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID: + mavlink_msg_open_drone_id_self_id_decode(&msg, &pkt_self_id); + break; + case MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID: + mavlink_msg_open_drone_id_basic_id_decode(&msg, &pkt_basic_id); + break; + case MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM: + mavlink_msg_open_drone_id_system_decode(&msg, &pkt_system); + last_system_ms = AP_HAL::millis(); + break; + case MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE: { + mavlink_open_drone_id_system_update_t pkt_system_update; + mavlink_msg_open_drone_id_system_update_decode(&msg, &pkt_system_update); + pkt_system.operator_latitude = pkt_system_update.operator_latitude; + pkt_system.operator_longitude = pkt_system_update.operator_longitude; + pkt_system.operator_altitude_geo = pkt_system_update.operator_altitude_geo; + pkt_system.timestamp = pkt_system_update.timestamp; + last_system_update_ms = AP_HAL::millis(); + if (last_system_ms != 0) { + // we can only mark system as updated if we have the other + // information already + last_system_ms = last_system_update_ms; + } + break; + } + } +} + +// singleton instance +AP_OpenDroneID *AP_OpenDroneID::_singleton; + +namespace AP +{ + +AP_OpenDroneID &opendroneid() +{ + return *AP_OpenDroneID::get_singleton(); +} + +} +#endif //AP_OPENDRONEID_ENABLED diff --git a/libraries/AP_OpenDroneID/AP_OpenDroneID.h b/libraries/AP_OpenDroneID/AP_OpenDroneID.h new file mode 100644 index 00000000000..37d8c427c8e --- /dev/null +++ b/libraries/AP_OpenDroneID/AP_OpenDroneID.h @@ -0,0 +1,209 @@ +/* + * This file is free software: you can redistribute it and/or modify it + * under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program. If not, see . + * + * Code by: + * BlueMark Innovations BV, Roel Schiphorst + * Contributors: Tom Pittenger, Josh Henderson + * Parts of this code are based on/copied from the Open Drone ID project https://github.com/opendroneid/opendroneid-core-c + * + * The code has been tested with the BlueMark DroneBeacon MAVLink transponder running this command in the ArduPlane folder: + * sim_vehicle.py --wipe-eeprom --console --map -A --serial1=uart:/dev/ttyUSB1:9600 + * (and a DroneBeacon MAVLink transponder connected to ttyUSB1) + * + * The Remote ID implementation expects a transponder that caches the received MAVLink messages from ArduPilot + * and transmits them at the required intervals. So static messages are only sent once to the transponder. + */ + +#pragma once + +#include +#include "AP_OpenDroneID_config.h" + +#ifndef AP_OPENDRONEID_ENABLED +// default to off. Enabled in hwdef.dat +#define AP_OPENDRONEID_ENABLED 0 +#endif + +#if AP_OPENDRONEID_ENABLED + +#include +#include +#include +#include + +#define ODID_ID_SIZE 20 +#define ODID_STR_SIZE 23 + +#define ODID_MIN_DIR 0 // Minimum direction +#define ODID_MAX_DIR 360 // Maximum direction +#define ODID_INV_DIR 361 // Invalid direction +#define ODID_MIN_SPEED_H 0 // Minimum speed horizontal +#define ODID_MAX_SPEED_H 254.25f // Maximum speed horizontal +#define ODID_INV_SPEED_H 255 // Invalid speed horizontal +#define ODID_MIN_SPEED_V (-62) // Minimum speed vertical +#define ODID_MAX_SPEED_V 62 // Maximum speed vertical +#define ODID_INV_SPEED_V 63 // Invalid speed vertical +#define ODID_MIN_ALT (-1000) // Minimum altitude +#define ODID_MAX_ALT 31767.5f// Maximum altitude +#define ODID_INV_ALT ODID_MIN_ALT // Invalid altitude +#define ODID_MAX_TIMESTAMP (60 * 60) +#define ODID_INV_TIMESTAMP 0xFFFF // Invalid, No Value or Unknown Timestamp +#define ODID_MAX_AREA_RADIUS 2550 +#define ODID_AREA_COUNT_MIN 1 +#define ODID_AREA_COUNT_MAX 65000 + +class AP_UAVCAN; + +class AP_OpenDroneID +{ +public: + AP_OpenDroneID(); + + /* Do not allow copies */ + CLASS_NO_COPY(AP_OpenDroneID); + + // parameter block + static const struct AP_Param::GroupInfo var_info[]; + + void init(); + bool pre_arm_check(char* failmsg, uint8_t failmsg_len); + void update(); + + // send pending dronecan messages + void dronecan_send(AP_UAVCAN *); + + // handle a message from the GCS + void handle_msg(mavlink_channel_t chan, const mavlink_message_t &msg); + + bool enabled(void) const { + return _enable != 0; + } + + void set_arm_status(mavlink_open_drone_id_arm_status_t &status); + + // get singleton instance + static AP_OpenDroneID *get_singleton() + { + return _singleton; + } +private: + static AP_OpenDroneID *_singleton; + + // parameters + AP_Int8 _enable; + AP_Float _baro_accuracy; // Vertical accuracy of the barometer when installed + AP_Int16 _options; + AP_Int8 _mav_port; + AP_Int8 _can_driver; + + enum Options : int16_t { + EnforceArming = (1U << 0U), + AllowNonGPSPosition = (1U << 1U), + }; + + // check if an option is set + bool option_enabled(const Options option) const + { + return (uint8_t(_options.get()) & uint8_t(option)) != 0; + } + + mavlink_channel_t _chan; // MAVLink channel that communicates with the Remote ID Transceiver + const mavlink_channel_t MAV_CHAN_INVALID = mavlink_channel_t(255U); + uint32_t _last_send_location_ms; + uint32_t _last_send_system_update_ms; + uint32_t _last_send_static_messages_ms; + const uint32_t _mavlink_dynamic_period_ms = 1000; //how often are mavlink dynamic messages sent in ms. E.g. 1000 = 1 Hz + const uint32_t _mavlink_static_period_ms = 5000; //how often are mavlink static messages sent in ms + + bool _have_height_above_takeoff; + Location _takeoff_location; + bool _was_armed; + + // packets ready to be sent, updated with semaphore held + HAL_Semaphore _sem; + mavlink_open_drone_id_location_t pkt_location; + mavlink_open_drone_id_basic_id_t pkt_basic_id; + mavlink_open_drone_id_system_t pkt_system; + mavlink_open_drone_id_self_id_t pkt_self_id; + mavlink_open_drone_id_operator_id_t pkt_operator_id; + + // last time we got a SYSTEM message + uint32_t last_system_ms; + + // last time we got a SYSTEM_UPDATE message + uint32_t last_system_update_ms; + + // arm status from the transmitter + mavlink_open_drone_id_arm_status_t arm_status; + uint32_t last_arm_status_ms; + + // last time we sent a lost transmitter message + uint32_t last_lost_tx_ms; + + // last time we sent a lost operator location notice + uint32_t last_lost_operator_msg_ms; + + // transmit functions to manually send a static MAVLink message + void send_dynamic_out(); + void send_static_out(); + void send_basic_id_message(); + void send_system_message(); + void send_system_update_message(); + void send_self_id_message(); + void send_operator_id_message(); + void send_location_message(); + enum next_msg : uint8_t { + NEXT_MSG_BASIC_ID = 0, + NEXT_MSG_SYSTEM, + NEXT_MSG_SELF_ID, + NEXT_MSG_OPERATOR_ID, + NEXT_MSG_ENUM_END + } next_msg_to_send; + uint32_t last_msg_send_ms; + + // helper functions + MAV_ODID_HOR_ACC create_enum_horizontal_accuracy(float Accuracy) const; + MAV_ODID_VER_ACC create_enum_vertical_accuracy(float Accuracy) const; + MAV_ODID_SPEED_ACC create_enum_speed_accuracy(float Accuracy) const; + MAV_ODID_TIME_ACC create_enum_timestamp_accuracy(float Accuracy) const; + uint16_t create_direction(uint16_t direction) const; + uint16_t create_speed_horizontal(uint16_t speed) const; + int16_t create_speed_vertical(int16_t speed) const; + float create_altitude(float altitude) const; + float create_location_timestamp(float timestamp) const; + + // mask of what UAVCAN drivers need to send each packet + const uint8_t dronecan_send_all = (1U<. + */ +/* + DroneCAN support for OpenDroneID + */ + +#include "AP_OpenDroneID.h" + +#if AP_OPENDRONEID_ENABLED + +#include + +#if HAL_ENABLE_LIBUAVCAN_DRIVERS +#include +#include +#include +#include +#include +#include + +#include + +static uavcan::Publisher* dc_location[HAL_MAX_CAN_PROTOCOL_DRIVERS]; +static uavcan::Publisher* dc_basic_id[HAL_MAX_CAN_PROTOCOL_DRIVERS]; +static uavcan::Publisher* dc_self_id[HAL_MAX_CAN_PROTOCOL_DRIVERS]; +static uavcan::Publisher* dc_system[HAL_MAX_CAN_PROTOCOL_DRIVERS]; +static uavcan::Publisher* dc_operator_id[HAL_MAX_CAN_PROTOCOL_DRIVERS]; + +// handle ArmStatus +UC_REGISTRY_BINDER(ArmStatusCb, dronecan::remoteid::ArmStatus); +static uavcan::Subscriber *arm_status_listener[HAL_MAX_CAN_PROTOCOL_DRIVERS]; + +static void handle_arm_status(AP_UAVCAN* ap_uavcan, uint8_t node_id, const ArmStatusCb &cb); + +void AP_OpenDroneID::dronecan_init(AP_UAVCAN *uavcan) +{ + const uint8_t driver_index = uavcan->get_driver_index(); + const uint8_t driver_mask = 1U<(*uavcan->get_node()); + if (dc_location[driver_index] == nullptr) { + goto alloc_failed; + } + dc_location[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(20)); + dc_location[driver_index]->setPriority(uavcan::TransferPriority::OneHigherThanLowest); + + dc_basic_id[driver_index] = new uavcan::Publisher(*uavcan->get_node()); + if (dc_basic_id[driver_index] == nullptr) { + goto alloc_failed; + } + dc_basic_id[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(20)); + dc_basic_id[driver_index]->setPriority(uavcan::TransferPriority::OneHigherThanLowest); + + dc_self_id[driver_index] = new uavcan::Publisher(*uavcan->get_node()); + if (dc_self_id[driver_index] == nullptr) { + goto alloc_failed; + } + dc_self_id[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(20)); + dc_self_id[driver_index]->setPriority(uavcan::TransferPriority::OneHigherThanLowest); + + dc_system[driver_index] = new uavcan::Publisher(*uavcan->get_node()); + if (dc_system[driver_index] == nullptr) { + goto alloc_failed; + } + dc_system[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(20)); + dc_system[driver_index]->setPriority(uavcan::TransferPriority::OneHigherThanLowest); + + dc_operator_id[driver_index] = new uavcan::Publisher(*uavcan->get_node()); + if (dc_operator_id[driver_index] == nullptr) { + goto alloc_failed; + } + dc_operator_id[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(20)); + dc_operator_id[driver_index]->setPriority(uavcan::TransferPriority::OneHigherThanLowest); + + arm_status_listener[driver_index] = new uavcan::Subscriber(*uavcan->get_node()); + if (arm_status_listener[driver_index] == nullptr) { + goto alloc_failed; + } + arm_status_listener[driver_index]->start(ArmStatusCb(uavcan, &handle_arm_status)); + + dronecan_done_init |= driver_mask; + return; + +alloc_failed: + dronecan_init_failed |= driver_mask; + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "OpenDroneID DroneCAN alloc failed"); +} + +/* + send pending DroneCAN OpenDroneID packets + */ +void AP_OpenDroneID::dronecan_send(AP_UAVCAN *uavcan) +{ + const uint8_t driver_index = uavcan->get_driver_index(); + const uint8_t driver_mask = 1U<get_driver_index()]->broadcast(msg); +} + +void AP_OpenDroneID::dronecan_send_basic_id(AP_UAVCAN *uavcan) +{ + dronecan::remoteid::BasicID msg {}; + const auto &pkt = pkt_basic_id; + ODID_COPY_STR(id_or_mac); + ODID_COPY(id_type); + ODID_COPY(ua_type); + ODID_COPY_STR(uas_id); + dc_basic_id[uavcan->get_driver_index()]->broadcast(msg); +} + +void AP_OpenDroneID::dronecan_send_system(AP_UAVCAN *uavcan) +{ + dronecan::remoteid::System msg {}; + const auto &pkt = pkt_system; + ODID_COPY_STR(id_or_mac); + ODID_COPY(operator_location_type); + ODID_COPY(classification_type); + ODID_COPY(operator_latitude); + ODID_COPY(operator_longitude); + ODID_COPY(area_count); + ODID_COPY(area_radius); + ODID_COPY(area_ceiling); + ODID_COPY(area_floor); + ODID_COPY(category_eu); + ODID_COPY(class_eu); + ODID_COPY(operator_altitude_geo); + ODID_COPY(timestamp); + dc_system[uavcan->get_driver_index()]->broadcast(msg); +} + +void AP_OpenDroneID::dronecan_send_self_id(AP_UAVCAN *uavcan) +{ + dronecan::remoteid::SelfID msg {}; + const auto &pkt = pkt_self_id; + ODID_COPY_STR(id_or_mac); + ODID_COPY(description_type); + ODID_COPY_STR(description); + dc_self_id[uavcan->get_driver_index()]->broadcast(msg); +} + +void AP_OpenDroneID::dronecan_send_operator_id(AP_UAVCAN *uavcan) +{ + dronecan::remoteid::OperatorID msg {}; + const auto &pkt = pkt_operator_id; + ODID_COPY_STR(id_or_mac); + ODID_COPY(operator_id_type); + ODID_COPY_STR(operator_id); + dc_operator_id[uavcan->get_driver_index()]->broadcast(msg); +} + +/* + handle ArmStatus message from DroneCAN + */ +static void handle_arm_status(AP_UAVCAN* ap_uavcan, uint8_t node_id, const ArmStatusCb &cb) +{ + const auto &msg = *cb.msg; + mavlink_open_drone_id_arm_status_t status {}; + + status.status = msg.status; + strncpy_noterm(status.error, msg.error.c_str(), sizeof(status.error)); + + AP::opendroneid().set_arm_status(status); + + // Push DroneCAN Arm Message to GCS + gcs().send_to_active_channels(MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS,(const char*)&status); +} + +// copy arm status for DroneCAN +void AP_OpenDroneID::set_arm_status(mavlink_open_drone_id_arm_status_t &status) +{ + WITH_SEMAPHORE(_sem); + arm_status = status; + last_arm_status_ms = AP_HAL::millis(); +} + +#endif // HAL_ENABLE_LIBUAVCAN_DRIVERS +#endif // AP_OPENDRONEID_ENABLED diff --git a/libraries/AP_OpenDroneID/AP_OpenDroneID_config.h b/libraries/AP_OpenDroneID/AP_OpenDroneID_config.h new file mode 100644 index 00000000000..d1bf00b6cbd --- /dev/null +++ b/libraries/AP_OpenDroneID/AP_OpenDroneID_config.h @@ -0,0 +1,8 @@ +#pragma once + +#include + +#ifndef AP_OPENDRONEID_ENABLED +// default to off. Enabled in hwdef.dat +#define AP_OPENDRONEID_ENABLED 0 +#endif diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp index ca84f7c3523..b9aa1914b89 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp @@ -19,22 +19,22 @@ extern const AP_HAL::HAL& hal; #ifndef OPTICAL_FLOW_TYPE_DEFAULT #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_SKYVIPER_F412 || defined(HAL_HAVE_PIXARTFLOW_SPI) - #define OPTICAL_FLOW_TYPE_DEFAULT OpticalFlowType::PIXART + #define OPTICAL_FLOW_TYPE_DEFAULT Type::PIXART #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP - #define OPTICAL_FLOW_TYPE_DEFAULT OpticalFlowType::BEBOP + #define OPTICAL_FLOW_TYPE_DEFAULT Type::BEBOP #else - #define OPTICAL_FLOW_TYPE_DEFAULT OpticalFlowType::NONE + #define OPTICAL_FLOW_TYPE_DEFAULT Type::NONE #endif #endif -const AP_Param::GroupInfo OpticalFlow::var_info[] = { +const AP_Param::GroupInfo AP_OpticalFlow::var_info[] = { // @Param: _TYPE // @DisplayName: Optical flow sensor type // @Description: Optical flow sensor type // @Values: 0:None, 1:PX4Flow, 2:Pixart, 3:Bebop, 4:CXOF, 5:MAVLink, 6:DroneCAN, 7:MSP, 8:UPFLOW // @User: Standard // @RebootRequired: True - AP_GROUPINFO_FLAGS("_TYPE", 0, OpticalFlow, _type, (int8_t)OPTICAL_FLOW_TYPE_DEFAULT, AP_PARAM_FLAG_ENABLE), + AP_GROUPINFO_FLAGS("_TYPE", 0, AP_OpticalFlow, _type, (float)OPTICAL_FLOW_TYPE_DEFAULT, AP_PARAM_FLAG_ENABLE), // @Param: _FXSCALER // @DisplayName: X axis optical flow scale factor correction @@ -42,7 +42,7 @@ const AP_Param::GroupInfo OpticalFlow::var_info[] = { // @Range: -200 +200 // @Increment: 1 // @User: Standard - AP_GROUPINFO("_FXSCALER", 1, OpticalFlow, _flowScalerX, 0), + AP_GROUPINFO("_FXSCALER", 1, AP_OpticalFlow, _flowScalerX, 0), // @Param: _FYSCALER // @DisplayName: Y axis optical flow scale factor correction @@ -50,7 +50,7 @@ const AP_Param::GroupInfo OpticalFlow::var_info[] = { // @Range: -200 +200 // @Increment: 1 // @User: Standard - AP_GROUPINFO("_FYSCALER", 2, OpticalFlow, _flowScalerY, 0), + AP_GROUPINFO("_FYSCALER", 2, AP_OpticalFlow, _flowScalerY, 0), // @Param: _ORIENT_YAW // @DisplayName: Flow sensor yaw alignment @@ -59,7 +59,7 @@ const AP_Param::GroupInfo OpticalFlow::var_info[] = { // @Range: -17999 +18000 // @Increment: 10 // @User: Standard - AP_GROUPINFO("_ORIENT_YAW", 3, OpticalFlow, _yawAngle_cd, 0), + AP_GROUPINFO("_ORIENT_YAW", 3, AP_OpticalFlow, _yawAngle_cd, 0), // @Param: _POS_X // @DisplayName: X position offset @@ -84,44 +84,44 @@ const AP_Param::GroupInfo OpticalFlow::var_info[] = { // @Range: -5 5 // @Increment: 0.01 // @User: Advanced - AP_GROUPINFO("_POS", 4, OpticalFlow, _pos_offset, 0.0f), + AP_GROUPINFO("_POS", 4, AP_OpticalFlow, _pos_offset, 0.0f), // @Param: _ADDR // @DisplayName: Address on the bus // @Description: This is used to select between multiple possible I2C addresses for some sensor types. For PX4Flow you can choose 0 to 7 for the 8 possible addresses on the I2C bus. // @Range: 0 127 // @User: Advanced - AP_GROUPINFO("_ADDR", 5, OpticalFlow, _address, 0), + AP_GROUPINFO("_ADDR", 5, AP_OpticalFlow, _address, 0), AP_GROUPEND }; // default constructor -OpticalFlow::OpticalFlow() +AP_OpticalFlow::AP_OpticalFlow() { _singleton = this; AP_Param::setup_object_defaults(this, var_info); } -void OpticalFlow::init(uint32_t log_bit) +void AP_OpticalFlow::init(uint32_t log_bit) { _log_bit = log_bit; // return immediately if not enabled or backend already created - if ((_type == (int8_t)OpticalFlowType::NONE) || (backend != nullptr)) { + if ((_type == Type::NONE) || (backend != nullptr)) { return; } - switch ((OpticalFlowType)_type.get()) { - case OpticalFlowType::NONE: + switch ((Type)_type) { + case Type::NONE: break; - case OpticalFlowType::PX4FLOW: + case Type::PX4FLOW: #if AP_OPTICALFLOW_PX4FLOW_ENABLED backend = AP_OpticalFlow_PX4Flow::detect(*this); #endif break; - case OpticalFlowType::PIXART: + case Type::PIXART: #if AP_OPTICALFLOW_PIXART_ENABLED backend = AP_OpticalFlow_Pixart::detect("pixartflow", *this); if (backend == nullptr) { @@ -129,38 +129,38 @@ void OpticalFlow::init(uint32_t log_bit) } #endif break; - case OpticalFlowType::BEBOP: + case Type::BEBOP: #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP backend = new AP_OpticalFlow_Onboard(*this); #endif break; - case OpticalFlowType::CXOF: + case Type::CXOF: #if AP_OPTICALFLOW_CXOF_ENABLED backend = AP_OpticalFlow_CXOF::detect(*this); #endif break; - case OpticalFlowType::MAVLINK: + case Type::MAVLINK: #if AP_OPTICALFLOW_MAV_ENABLED backend = AP_OpticalFlow_MAV::detect(*this); #endif break; - case OpticalFlowType::UAVCAN: + case Type::UAVCAN: #if AP_OPTICALFLOW_HEREFLOW_ENABLED backend = new AP_OpticalFlow_HereFlow(*this); #endif break; - case OpticalFlowType::MSP: + case Type::MSP: #if HAL_MSP_OPTICALFLOW_ENABLED backend = AP_OpticalFlow_MSP::detect(*this); #endif break; - case OpticalFlowType::UPFLOW: + case Type::UPFLOW: #if AP_OPTICALFLOW_UPFLOW_ENABLED backend = AP_OpticalFlow_UPFLOW::detect(*this); #endif break; - case OpticalFlowType::SITL: -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL + case Type::SITL: +#if AP_OPTICALFLOW_SITL_ENABLED backend = new AP_OpticalFlow_SITL(*this); #endif break; @@ -171,7 +171,7 @@ void OpticalFlow::init(uint32_t log_bit) } } -void OpticalFlow::update(void) +void AP_OpticalFlow::update(void) { // exit immediately if not enabled if (!enabled()) { @@ -200,7 +200,7 @@ void OpticalFlow::update(void) } } -void OpticalFlow::handle_msg(const mavlink_message_t &msg) +void AP_OpticalFlow::handle_msg(const mavlink_message_t &msg) { // exit immediately if not enabled if (!enabled()) { @@ -213,7 +213,7 @@ void OpticalFlow::handle_msg(const mavlink_message_t &msg) } #if HAL_MSP_OPTICALFLOW_ENABLED -void OpticalFlow::handle_msp(const MSP::msp_opflow_data_message_t &pkt) +void AP_OpticalFlow::handle_msp(const MSP::msp_opflow_data_message_t &pkt) { // exit immediately if not enabled if (!enabled()) { @@ -227,7 +227,7 @@ void OpticalFlow::handle_msp(const MSP::msp_opflow_data_message_t &pkt) #endif //HAL_MSP_OPTICALFLOW_ENABLED // start calibration -void OpticalFlow::start_calibration() +void AP_OpticalFlow::start_calibration() { if (_calibrator == nullptr) { _calibrator = new AP_OpticalFlow_Calibrator(); @@ -242,14 +242,14 @@ void OpticalFlow::start_calibration() } // stop calibration -void OpticalFlow::stop_calibration() +void AP_OpticalFlow::stop_calibration() { if (_calibrator != nullptr) { _calibrator->stop(); } } -void OpticalFlow::update_state(const OpticalFlow_state &state) +void AP_OpticalFlow::update_state(const OpticalFlow_state &state) { _state = state; _last_update_ms = AP_HAL::millis(); @@ -263,7 +263,7 @@ void OpticalFlow::update_state(const OpticalFlow_state &state) Log_Write_Optflow(); } -void OpticalFlow::Log_Write_Optflow() +void AP_OpticalFlow::Log_Write_Optflow() { AP_Logger *logger = AP_Logger::get_singleton(); if (logger == nullptr) { @@ -289,13 +289,13 @@ void OpticalFlow::Log_Write_Optflow() // singleton instance -OpticalFlow *OpticalFlow::_singleton; +AP_OpticalFlow *AP_OpticalFlow::_singleton; namespace AP { -OpticalFlow *opticalflow() +AP_OpticalFlow *opticalflow() { - return OpticalFlow::get_singleton(); + return AP_OpticalFlow::get_singleton(); } } diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow.h b/libraries/AP_OpticalFlow/AP_OpticalFlow.h index 0f83e304caf..67de7287c88 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow.h +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow.h @@ -24,6 +24,10 @@ #define HAL_MSP_OPTICALFLOW_ENABLED (AP_OPTICALFLOW_ENABLED && (HAL_MSP_ENABLED && !HAL_MINIMIZE_FEATURES)) #endif +#ifndef AP_OPTICALFLOW_SITL_ENABLED +#define AP_OPTICALFLOW_SITL_ENABLED AP_SIM_ENABLED +#endif + #if AP_OPTICALFLOW_ENABLED /* @@ -31,30 +35,27 @@ */ #include -#include #include #include #include "AP_OpticalFlow_Calibrator.h" class OpticalFlow_backend; -class OpticalFlow +class AP_OpticalFlow { friend class OpticalFlow_backend; public: - OpticalFlow(); + AP_OpticalFlow(); - /* Do not allow copies */ - OpticalFlow(const OpticalFlow &other) = delete; - OpticalFlow &operator=(const OpticalFlow&) = delete; + CLASS_NO_COPY(AP_OpticalFlow); // get singleton instance - static OpticalFlow *get_singleton() { + static AP_OpticalFlow *get_singleton() { return _singleton; } - enum class OpticalFlowType { + enum class Type { NONE = 0, PX4FLOW = 1, PIXART = 2, @@ -71,7 +72,7 @@ class OpticalFlow void init(uint32_t log_bit); // enabled - returns true if optical flow is enabled - bool enabled() const { return _type != (int8_t)OpticalFlowType::NONE; } + bool enabled() const { return _type != Type::NONE; } // healthy - return true if the sensor is healthy bool healthy() const { return backend != nullptr && _flags.healthy; } @@ -119,7 +120,7 @@ class OpticalFlow private: - static OpticalFlow *_singleton; + static AP_OpticalFlow *_singleton; OpticalFlow_backend *backend; @@ -128,7 +129,7 @@ class OpticalFlow } _flags; // parameters - AP_Int8 _type; // user configurable sensor type + AP_Enum _type; // user configurable sensor type AP_Int16 _flowScalerX; // X axis flow scale factor correction - parts per thousand AP_Int16 _flowScalerY; // Y axis flow scale factor correction - parts per thousand AP_Int16 _yawAngle_cd; // yaw angle of sensor X axis with respect to vehicle X axis - centi degrees @@ -152,7 +153,7 @@ class OpticalFlow }; namespace AP { - OpticalFlow *opticalflow(); + AP_OpticalFlow *opticalflow(); } #include "AP_OpticalFlow_Backend.h" diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_Backend.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_Backend.cpp index 20eb879895f..8a38dfe4fd4 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_Backend.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_Backend.cpp @@ -19,7 +19,7 @@ extern const AP_HAL::HAL& hal; -OpticalFlow_backend::OpticalFlow_backend(OpticalFlow &_frontend) : +OpticalFlow_backend::OpticalFlow_backend(AP_OpticalFlow &_frontend) : frontend(_frontend) { } @@ -29,7 +29,7 @@ OpticalFlow_backend::~OpticalFlow_backend(void) } // update the frontend -void OpticalFlow_backend::_update_frontend(const struct OpticalFlow::OpticalFlow_state &state) +void OpticalFlow_backend::_update_frontend(const struct AP_OpticalFlow::OpticalFlow_state &state) { frontend.update_state(state); } diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_Backend.h b/libraries/AP_OpticalFlow/AP_OpticalFlow_Backend.h index d06d7b0442f..059e5b92d11 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_Backend.h +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_Backend.h @@ -15,22 +15,24 @@ #pragma once /* - OpticalFlow backend class for ArduPilot + AP_OpticalFlow backend class for ArduPilot */ #include "AP_OpticalFlow.h" class OpticalFlow_backend { - friend class OpticalFlow; + friend class AP_OpticalFlow; public: // constructor - OpticalFlow_backend(OpticalFlow &_frontend); + OpticalFlow_backend(AP_OpticalFlow &_frontend); virtual ~OpticalFlow_backend(void); - + + CLASS_NO_COPY(OpticalFlow_backend); + // init - initialise sensor - virtual void init() = 0; + virtual void init() {} // read latest values from sensor and fill in x,y and totals. virtual void update() = 0; @@ -45,10 +47,10 @@ class OpticalFlow_backend protected: // access to frontend - OpticalFlow &frontend; + AP_OpticalFlow &frontend; // update the frontend - void _update_frontend(const struct OpticalFlow::OpticalFlow_state &state); + void _update_frontend(const struct AP_OpticalFlow::OpticalFlow_state &state); // get the flow scaling parameters Vector2f _flowScaler(void) const { return Vector2f(frontend._flowScalerX, frontend._flowScalerY); } diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_CXOF.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_CXOF.cpp index 0e120df34ee..ed2a099f46e 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_CXOF.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_CXOF.cpp @@ -51,14 +51,14 @@ extern const AP_HAL::HAL& hal; // constructor -AP_OpticalFlow_CXOF::AP_OpticalFlow_CXOF(OpticalFlow &_frontend, AP_HAL::UARTDriver *_uart) : +AP_OpticalFlow_CXOF::AP_OpticalFlow_CXOF(AP_OpticalFlow &_frontend, AP_HAL::UARTDriver *_uart) : OpticalFlow_backend(_frontend), uart(_uart) { } // detect the device -AP_OpticalFlow_CXOF *AP_OpticalFlow_CXOF::detect(OpticalFlow &_frontend) +AP_OpticalFlow_CXOF *AP_OpticalFlow_CXOF::detect(AP_OpticalFlow &_frontend) { AP_SerialManager *serial_manager = AP::serialmanager().get_singleton(); if (serial_manager == nullptr) { @@ -159,7 +159,7 @@ void AP_OpticalFlow_CXOF::update(void) return; } - struct OpticalFlow::OpticalFlow_state state {}; + struct AP_OpticalFlow::OpticalFlow_state state {}; // average surface quality scaled to be between 0 and 255 state.surface_quality = (constrain_int16(qual_sum / count, 64, 78) - 64) * 255 / 14; diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_CXOF.h b/libraries/AP_OpticalFlow/AP_OpticalFlow_CXOF.h index 32b61af2c59..2cb8716bf80 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_CXOF.h +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_CXOF.h @@ -14,7 +14,7 @@ class AP_OpticalFlow_CXOF : public OpticalFlow_backend { public: /// constructor - AP_OpticalFlow_CXOF(OpticalFlow &_frontend, AP_HAL::UARTDriver *uart); + AP_OpticalFlow_CXOF(AP_OpticalFlow &_frontend, AP_HAL::UARTDriver *uart); // initialise the sensor void init() override; @@ -23,7 +23,7 @@ class AP_OpticalFlow_CXOF : public OpticalFlow_backend void update(void) override; // detect if the sensor is available - static AP_OpticalFlow_CXOF *detect(OpticalFlow &_frontend); + static AP_OpticalFlow_CXOF *detect(AP_OpticalFlow &_frontend); private: diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_Calibrator.h b/libraries/AP_OpticalFlow/AP_OpticalFlow_Calibrator.h index 5a169f2ab67..13b9c5c0dc8 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_Calibrator.h +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_Calibrator.h @@ -1,6 +1,5 @@ #pragma once -#include #include #define AP_OPTICALFLOW_CAL_MAX_SAMPLES 50 // number of samples required before calibration begins diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.cpp index 944c1fd3686..bbf37c87ade 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.cpp @@ -20,7 +20,7 @@ AP_UAVCAN* AP_OpticalFlow_HereFlow::_ap_uavcan = nullptr; /* constructor - registers instance at top Flow driver */ -AP_OpticalFlow_HereFlow::AP_OpticalFlow_HereFlow(OpticalFlow &flow) : +AP_OpticalFlow_HereFlow::AP_OpticalFlow_HereFlow(AP_OpticalFlow &flow) : OpticalFlow_backend(flow) { if (_driver) { @@ -83,7 +83,7 @@ void AP_OpticalFlow_HereFlow::_push_state(void) if (!new_data) { return; } - struct OpticalFlow::OpticalFlow_state state; + struct AP_OpticalFlow::OpticalFlow_state state; const Vector2f flowScaler = _flowScaler(); //setup scaling based on parameters float flowScaleFactorX = 1.0f + 0.001f * flowScaler.x; diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.h b/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.h index 77d86ff73e4..e279a118ebf 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.h +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.h @@ -14,7 +14,7 @@ class MeasurementCb; class AP_OpticalFlow_HereFlow : public OpticalFlow_backend { public: - AP_OpticalFlow_HereFlow(OpticalFlow &flow); + AP_OpticalFlow_HereFlow(AP_OpticalFlow &flow); void init() override {} diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_MAV.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_MAV.cpp index 9b90bb42b3c..7a84b17623e 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_MAV.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_MAV.cpp @@ -23,7 +23,7 @@ #define OPTFLOW_MAV_TIMEOUT_SEC 0.5f // detect the device -AP_OpticalFlow_MAV *AP_OpticalFlow_MAV::detect(OpticalFlow &_frontend) +AP_OpticalFlow_MAV *AP_OpticalFlow_MAV::detect(AP_OpticalFlow &_frontend) { // we assume mavlink messages will be sent into this driver AP_OpticalFlow_MAV *sensor = new AP_OpticalFlow_MAV(_frontend); @@ -47,7 +47,7 @@ void AP_OpticalFlow_MAV::update(void) return; } - struct OpticalFlow::OpticalFlow_state state {}; + struct AP_OpticalFlow::OpticalFlow_state state {}; state.surface_quality = quality_sum / count; diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_MAV.h b/libraries/AP_OpticalFlow/AP_OpticalFlow_MAV.h index ba1a7872aff..3784e4dc769 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_MAV.h +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_MAV.h @@ -26,7 +26,7 @@ class AP_OpticalFlow_MAV : public OpticalFlow_backend void handle_msg(const mavlink_message_t &msg) override; // detect if the sensor is available - static AP_OpticalFlow_MAV *detect(OpticalFlow &_frontend); + static AP_OpticalFlow_MAV *detect(AP_OpticalFlow &_frontend); private: diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_MSP.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_MSP.cpp index c41e39446cd..eaff53fde2a 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_MSP.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_MSP.cpp @@ -26,7 +26,7 @@ extern const AP_HAL::HAL& hal; using namespace MSP; // detect the device -AP_OpticalFlow_MSP *AP_OpticalFlow_MSP::detect(OpticalFlow &_frontend) +AP_OpticalFlow_MSP *AP_OpticalFlow_MSP::detect(AP_OpticalFlow &_frontend) { // we assume msp messages will be sent into this driver return new AP_OpticalFlow_MSP(_frontend); @@ -49,7 +49,7 @@ void AP_OpticalFlow_MSP::update(void) return; } - struct OpticalFlow::OpticalFlow_state state {}; + struct AP_OpticalFlow::OpticalFlow_state state {}; state.surface_quality = quality_sum / count; diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_MSP.h b/libraries/AP_OpticalFlow/AP_OpticalFlow_MSP.h index 13aff4b7c55..b3ff611c4af 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_MSP.h +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_MSP.h @@ -21,7 +21,7 @@ class AP_OpticalFlow_MSP : public OpticalFlow_backend void handle_msp(const MSP::msp_opflow_data_message_t &pkt) override; // detect if the sensor is available - static AP_OpticalFlow_MSP *detect(OpticalFlow &_frontend); + static AP_OpticalFlow_MSP *detect(AP_OpticalFlow &_frontend); private: diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_Onboard.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_Onboard.cpp index 8b5896a9ddc..a6e46b928ef 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_Onboard.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_Onboard.cpp @@ -30,10 +30,6 @@ #define OPTICALFLOW_ONBOARD_ID 1 extern const AP_HAL::HAL& hal; -AP_OpticalFlow_Onboard::AP_OpticalFlow_Onboard(OpticalFlow &_frontend) : - OpticalFlow_backend(_frontend) -{} - void AP_OpticalFlow_Onboard::init(void) { /* register callback to get gyro data */ @@ -54,7 +50,7 @@ void AP_OpticalFlow_Onboard::update() return; } - struct OpticalFlow::OpticalFlow_state state; + struct AP_OpticalFlow::OpticalFlow_state state; state.surface_quality = data_frame.quality; if (data_frame.delta_time > 0) { const Vector2f flowScaler = _flowScaler(); diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_Onboard.h b/libraries/AP_OpticalFlow/AP_OpticalFlow_Onboard.h index 46dc74094f4..3d21d82ed26 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_Onboard.h +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_Onboard.h @@ -32,7 +32,9 @@ class AP_OpticalFlow_Onboard : public OpticalFlow_backend { public: - AP_OpticalFlow_Onboard(OpticalFlow &_frontend); + + using OpticalFlow_backend::OpticalFlow_backend; + void init(void) override; void update(void) override; private: diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_PX4Flow.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_PX4Flow.cpp index 1e3f6345209..4b051250af9 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_PX4Flow.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_PX4Flow.cpp @@ -34,15 +34,9 @@ extern const AP_HAL::HAL& hal; #define PX4FLOW_BASE_I2C_ADDR 0x42 #define PX4FLOW_INIT_RETRIES 10 // attempt to initialise the sensor up to 10 times at startup -// constructor -AP_OpticalFlow_PX4Flow::AP_OpticalFlow_PX4Flow(OpticalFlow &_frontend) : - OpticalFlow_backend(_frontend) -{ -} - // detect the device -AP_OpticalFlow_PX4Flow *AP_OpticalFlow_PX4Flow::detect(OpticalFlow &_frontend) +AP_OpticalFlow_PX4Flow *AP_OpticalFlow_PX4Flow::detect(AP_OpticalFlow &_frontend) { AP_OpticalFlow_PX4Flow *sensor = new AP_OpticalFlow_PX4Flow(_frontend); if (!sensor) { @@ -119,7 +113,7 @@ void AP_OpticalFlow_PX4Flow::timer(void) if (!dev->read_registers(REG_INTEGRAL_FRAME, (uint8_t *)&frame, sizeof(frame))) { return; } - struct OpticalFlow::OpticalFlow_state state {}; + struct AP_OpticalFlow::OpticalFlow_state state {}; if (frame.integration_timespan > 0) { const Vector2f flowScaler = _flowScaler(); diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_PX4Flow.h b/libraries/AP_OpticalFlow/AP_OpticalFlow_PX4Flow.h index ebda790c20b..c5c22b6de2d 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_PX4Flow.h +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_PX4Flow.h @@ -14,7 +14,9 @@ class AP_OpticalFlow_PX4Flow : public OpticalFlow_backend { public: /// constructor - AP_OpticalFlow_PX4Flow(OpticalFlow &_frontend); + using OpticalFlow_backend::OpticalFlow_backend; + + CLASS_NO_COPY(AP_OpticalFlow_PX4Flow); // init - initialise the sensor void init() override {} @@ -23,7 +25,7 @@ class AP_OpticalFlow_PX4Flow : public OpticalFlow_backend void update(void) override; // detect if the sensor is available - static AP_OpticalFlow_PX4Flow *detect(OpticalFlow &_frontend); + static AP_OpticalFlow_PX4Flow *detect(AP_OpticalFlow &_frontend); private: AP_HAL::OwnPtr dev; diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_Pixart.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_Pixart.cpp index 511dfdad6ad..96ca4f94255 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_Pixart.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_Pixart.cpp @@ -83,14 +83,14 @@ extern const AP_HAL::HAL& hal; #define PIXART_SROM_CRC_RESULT 0xBEEF // constructor -AP_OpticalFlow_Pixart::AP_OpticalFlow_Pixart(const char *devname, OpticalFlow &_frontend) : +AP_OpticalFlow_Pixart::AP_OpticalFlow_Pixart(const char *devname, AP_OpticalFlow &_frontend) : OpticalFlow_backend(_frontend) { _dev = std::move(hal.spi->get_device(devname)); } // detect the device -AP_OpticalFlow_Pixart *AP_OpticalFlow_Pixart::detect(const char *devname, OpticalFlow &_frontend) +AP_OpticalFlow_Pixart *AP_OpticalFlow_Pixart::detect(const char *devname, AP_OpticalFlow &_frontend) { AP_OpticalFlow_Pixart *sensor = new AP_OpticalFlow_Pixart(devname, _frontend); if (!sensor) { @@ -329,7 +329,7 @@ void AP_OpticalFlow_Pixart::update(void) } last_update_ms = now; - struct OpticalFlow::OpticalFlow_state state; + struct AP_OpticalFlow::OpticalFlow_state state; state.surface_quality = burst.squal; if (integral.sum_us > 0) { diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_Pixart.h b/libraries/AP_OpticalFlow/AP_OpticalFlow_Pixart.h index b2e8a4d1793..d1720eea728 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_Pixart.h +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_Pixart.h @@ -14,7 +14,7 @@ class AP_OpticalFlow_Pixart : public OpticalFlow_backend { public: /// constructor - AP_OpticalFlow_Pixart(const char *devname, OpticalFlow &_frontend); + AP_OpticalFlow_Pixart(const char *devname, AP_OpticalFlow &_frontend); // init - initialise the sensor void init() override {} @@ -23,7 +23,7 @@ class AP_OpticalFlow_Pixart : public OpticalFlow_backend void update(void) override; // detect if the sensor is available - static AP_OpticalFlow_Pixart *detect(const char *devname, OpticalFlow &_frontend); + static AP_OpticalFlow_Pixart *detect(const char *devname, AP_OpticalFlow &_frontend); private: AP_HAL::OwnPtr _dev; diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_SITL.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_SITL.cpp index d6208a6aae9..5ac842daba2 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_SITL.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_SITL.cpp @@ -17,26 +17,17 @@ * AP_OpticalFlow_SITL.cpp - SITL emulation of optical flow sensor. */ -#include - -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL - #include "AP_OpticalFlow_SITL.h" -extern const AP_HAL::HAL& hal; - -AP_OpticalFlow_SITL::AP_OpticalFlow_SITL(OpticalFlow &_frontend) : - OpticalFlow_backend(_frontend), - _sitl(AP::sitl()) -{ -} +#if AP_OPTICALFLOW_SITL_ENABLED -void AP_OpticalFlow_SITL::init(void) -{ -} +#include +#include void AP_OpticalFlow_SITL::update(void) { + auto *_sitl = AP::sitl(); + if (!_sitl->flow_enable) { return; } @@ -52,7 +43,7 @@ void AP_OpticalFlow_SITL::update(void) radians(_sitl->state.pitchRate), radians(_sitl->state.yawRate)); - OpticalFlow::OpticalFlow_state state; + AP_OpticalFlow::OpticalFlow_state state; // NED velocity vector in m/s Vector3f velocity(_sitl->state.speedN, @@ -114,7 +105,7 @@ void AP_OpticalFlow_SITL::update(void) // cope with updates to the delay control if (_sitl->flow_delay > 0 && (uint8_t)(_sitl->flow_delay) > ARRAY_SIZE(optflow_data)) { - _sitl->flow_delay = ARRAY_SIZE(optflow_data); + _sitl->flow_delay.set(ARRAY_SIZE(optflow_data)); } optflow_delay = _sitl->flow_delay; for (uint8_t i=0; i + +#if AP_OPTICALFLOW_SITL_ENABLED class AP_OpticalFlow_SITL : public OpticalFlow_backend { public: /// constructor - AP_OpticalFlow_SITL(OpticalFlow &_frontend); - - // init - initialise the sensor - void init() override; + using OpticalFlow_backend::OpticalFlow_backend; // update - read latest values from sensor and fill in x,y and totals. void update(void) override; private: - SITL::SIM *_sitl; + uint32_t last_flow_ms; uint8_t next_optflow_index; uint8_t optflow_delay; - OpticalFlow::OpticalFlow_state optflow_data[20]; + AP_OpticalFlow::OpticalFlow_state optflow_data[20]; }; -#endif // CONFIG_HAL_BOARD + +#endif // AP_OPTICALFLOW_SITL_ENABLED diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_UPFLOW.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_UPFLOW.cpp index 3e7253071f5..a4af1d4c86c 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_UPFLOW.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_UPFLOW.cpp @@ -53,14 +53,14 @@ extern const AP_HAL::HAL& hal; // constructor -AP_OpticalFlow_UPFLOW::AP_OpticalFlow_UPFLOW(OpticalFlow &_frontend, AP_HAL::UARTDriver *_uart) : +AP_OpticalFlow_UPFLOW::AP_OpticalFlow_UPFLOW(AP_OpticalFlow &_frontend, AP_HAL::UARTDriver *_uart) : OpticalFlow_backend(_frontend), uart(_uart) { } // detect the device -AP_OpticalFlow_UPFLOW *AP_OpticalFlow_UPFLOW::detect(OpticalFlow &_frontend) +AP_OpticalFlow_UPFLOW *AP_OpticalFlow_UPFLOW::detect(AP_OpticalFlow &_frontend) { AP_SerialManager *serial_manager = AP::serialmanager().get_singleton(); if (serial_manager == nullptr) { @@ -156,7 +156,7 @@ void AP_OpticalFlow_UPFLOW::update(void) return; } - struct OpticalFlow::OpticalFlow_state state {}; + struct AP_OpticalFlow::OpticalFlow_state state {}; state.surface_quality = updata.quality; diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_UPFLOW.h b/libraries/AP_OpticalFlow/AP_OpticalFlow_UPFLOW.h index 5cf16f182cc..64bec165eef 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_UPFLOW.h +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_UPFLOW.h @@ -14,7 +14,7 @@ class AP_OpticalFlow_UPFLOW : public OpticalFlow_backend { public: /// constructor - AP_OpticalFlow_UPFLOW(OpticalFlow &_frontend, AP_HAL::UARTDriver *uart); + AP_OpticalFlow_UPFLOW(AP_OpticalFlow &_frontend, AP_HAL::UARTDriver *uart); // initialise the sensor void init() override; @@ -23,7 +23,7 @@ class AP_OpticalFlow_UPFLOW : public OpticalFlow_backend void update(void) override; // detect if the sensor is available - static AP_OpticalFlow_UPFLOW *detect(OpticalFlow &_frontend); + static AP_OpticalFlow_UPFLOW *detect(AP_OpticalFlow &_frontend); private: struct PACKED UpixelsOpticalFlow { diff --git a/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.cpp b/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.cpp index 957c100bd8c..61fa5c8446f 100644 --- a/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.cpp +++ b/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.cpp @@ -32,7 +32,7 @@ class DummyVehicle { static DummyVehicle vehicle; #if AP_OPTICALFLOW_ENABLED -static OpticalFlow optflow; +static AP_OpticalFlow optflow; #endif void setup() diff --git a/libraries/AP_Parachute/AP_Parachute.cpp b/libraries/AP_Parachute/AP_Parachute.cpp index 83ff765296b..1d6f33f4343 100644 --- a/libraries/AP_Parachute/AP_Parachute.cpp +++ b/libraries/AP_Parachute/AP_Parachute.cpp @@ -87,7 +87,7 @@ const AP_Param::GroupInfo AP_Parachute::var_info[] = { /// enabled - enable or disable parachute release void AP_Parachute::enabled(bool on_off) { - _enabled = on_off; + _enabled.set(on_off); // clear release_time _release_time = 0; diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index 1bbba058aa8..d2fd2e3b712 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -33,6 +33,7 @@ #include #include #include +#include #include #if CONFIG_HAL_BOARD == HAL_BOARD_SITL #include @@ -98,6 +99,11 @@ uint16_t AP_Param::num_read_only = 0; ObjectBuffer_TS AP_Param::save_queue{30}; bool AP_Param::registered_save_handler; +AP_Param::defaults_list *AP_Param::default_list; +#if AP_PARAM_MAX_EMBEDDED_PARAM > 0 + AP_Param::defaults_list *AP_Param::embedded_default_list; +#endif + // we need a dummy object for the parameter save callback static AP_Param save_dummy; @@ -1207,7 +1213,7 @@ void AP_Param::save_sync(bool force_save, bool send_to_gcs) if (ofs+type_size((enum ap_var_type)phdr.type)+2*sizeof(phdr) >= _storage.size()) { // we are out of room for saving variables - hal.console->printf("EEPROM full\n"); + DEV_PRINTF("EEPROM full\n"); return; } @@ -1455,6 +1461,11 @@ void AP_Param::setup_object_defaults(const void *object_pointer, const struct Gr void *ptr = (void *)(base + group_info[i].offset); set_value((enum ap_var_type)type, ptr, get_default_value((const AP_Param *)ptr, &group_info[i].def_value)); + } else if (type == AP_PARAM_VECTOR3F) { + // Single default for all components + void *ptr = (void *)(base + group_info[i].offset); + const float default_val = get_default_value((const AP_Param *)ptr, &group_info[i].def_value); + ((AP_Vector3f *)ptr)->set(Vector3f{default_val, default_val, default_val}); } } } @@ -1583,7 +1594,7 @@ void AP_Param::load_object_from_eeprom(const void *object_pointer, const struct uint16_t key; if (!find_key_by_pointer(object_pointer, key)) { - hal.console->printf("ERROR: Unable to find param pointer\n"); + DEV_PRINTF("ERROR: Unable to find param pointer\n"); return; } @@ -1630,7 +1641,7 @@ void AP_Param::load_object_from_eeprom(const void *object_pointer, const struct // return the first variable in _var_info -AP_Param *AP_Param::first(ParamToken *token, enum ap_var_type *ptype) +AP_Param *AP_Param::first(ParamToken *token, enum ap_var_type *ptype, float *default_val) { token->key = 0; token->group_element = 0; @@ -1638,14 +1649,20 @@ AP_Param *AP_Param::first(ParamToken *token, enum ap_var_type *ptype) if (_num_vars == 0) { return nullptr; } - if (ptype != nullptr) { - *ptype = (enum ap_var_type)var_info(0).type; - } ptrdiff_t base; if (!get_base(var_info(0), base)) { // should be impossible, first var needs to be non-pointer return nullptr; } + if (ptype != nullptr) { + *ptype = (enum ap_var_type)var_info(0).type; + } +#if AP_PARAM_DEFAULTS_ENABLED + if (default_val != nullptr) { + *default_val = var_info(0).def_value; + } + check_default((AP_Param *)base, default_val); +#endif return (AP_Param *)base; } @@ -1658,7 +1675,8 @@ AP_Param *AP_Param::next_group(const uint16_t vindex, const struct GroupInfo *gr const ptrdiff_t group_offset, ParamToken *token, enum ap_var_type *ptype, - bool skip_disabled) + bool skip_disabled, + float *default_val) { enum ap_var_type type; for (uint8_t i=0; @@ -1681,7 +1699,7 @@ AP_Param *AP_Param::next_group(const uint16_t vindex, const struct GroupInfo *gr } ap = next_group(vindex, ginfo, found_current, group_id(group_info, group_base, i, group_shift), - group_shift + _group_level_shift, new_offset, token, ptype, skip_disabled); + group_shift + _group_level_shift, new_offset, token, ptype, skip_disabled, default_val); if (ap != nullptr) { return ap; } @@ -1708,6 +1726,11 @@ AP_Param *AP_Param::next_group(const uint16_t vindex, const struct GroupInfo *gr ((AP_Int8 *)ret)->get() == 0) { token->last_disabled = 1; } +#if AP_PARAM_DEFAULTS_ENABLED + if (default_val != nullptr) { + *default_val = group_info[i].def_value; + } +#endif return ret; } if (group_id(group_info, group_base, i, group_shift) == token->group_element) { @@ -1727,6 +1750,11 @@ AP_Param *AP_Param::next_group(const uint16_t vindex, const struct GroupInfo *gr if (!get_base(var_info(vindex), base)) { continue; } +#if AP_PARAM_DEFAULTS_ENABLED + if (default_val != nullptr) { + *default_val = group_info[i].def_value; + } +#endif ptrdiff_t ofs = base + group_info[i].offset + group_offset; ofs += sizeof(float)*(token->idx - 1u); return (AP_Param *)ofs; @@ -1739,7 +1767,7 @@ AP_Param *AP_Param::next_group(const uint16_t vindex, const struct GroupInfo *gr /// Returns the next variable in _var_info, recursing into groups /// as needed -AP_Param *AP_Param::next(ParamToken *token, enum ap_var_type *ptype, bool skip_disabled) +AP_Param *AP_Param::next(ParamToken *token, enum ap_var_type *ptype, bool skip_disabled, float *default_val) { uint16_t i = token->key; bool found_current = false; @@ -1756,6 +1784,11 @@ AP_Param *AP_Param::next(ParamToken *token, enum ap_var_type *ptype, bool skip_d if (ptype != nullptr) { *ptype = AP_PARAM_FLOAT; } +#if AP_PARAM_DEFAULTS_ENABLED + if (default_val != nullptr) { + *default_val = var_info(i).def_value; + } +#endif return (AP_Param *)(((token->idx - 1u)*sizeof(float))+(ptrdiff_t)var_info(i).ptr); } @@ -1774,7 +1807,7 @@ AP_Param *AP_Param::next(ParamToken *token, enum ap_var_type *ptype, bool skip_d if (group_info == nullptr) { continue; } - AP_Param *ap = next_group(i, group_info, &found_current, 0, 0, 0, token, ptype, skip_disabled); + AP_Param *ap = next_group(i, group_info, &found_current, 0, 0, 0, token, ptype, skip_disabled, default_val); if (ap != nullptr) { return ap; } @@ -1786,6 +1819,11 @@ AP_Param *AP_Param::next(ParamToken *token, enum ap_var_type *ptype, bool skip_d if (ptype != nullptr) { *ptype = type; } +#if AP_PARAM_DEFAULTS_ENABLED + if (default_val != nullptr) { + *default_val = info.def_value; + } +#endif return (AP_Param *)(info.ptr); } } @@ -1794,17 +1832,20 @@ AP_Param *AP_Param::next(ParamToken *token, enum ap_var_type *ptype, bool skip_d /// Returns the next scalar in _var_info, recursing into groups /// as needed -AP_Param *AP_Param::next_scalar(ParamToken *token, enum ap_var_type *ptype) +AP_Param *AP_Param::next_scalar(ParamToken *token, enum ap_var_type *ptype, float *default_val) { AP_Param *ap; enum ap_var_type type; - while ((ap = next(token, &type, true)) != nullptr && type > AP_PARAM_FLOAT) ; + while ((ap = next(token, &type, true, default_val)) != nullptr && type > AP_PARAM_FLOAT) ; if (ap != nullptr) { if (ptype != nullptr) { *ptype = type; } } +#if AP_PARAM_DEFAULTS_ENABLED + check_default(ap, default_val); +#endif return ap; } @@ -1868,7 +1909,7 @@ void AP_Param::convert_old_parameter(const struct ConversionInfo *info, float sc AP_Param *ap2; ap2 = find(&info->new_name[0], &ptype); if (ap2 == nullptr) { - hal.console->printf("Unknown conversion '%s'\n", info->new_name); + DEV_PRINTF("Unknown conversion '%s'\n", info->new_name); return; } @@ -1902,7 +1943,7 @@ void AP_Param::convert_old_parameter(const struct ConversionInfo *info, float sc } } else { // can't do vector<->scalar conversion, or different vector types - hal.console->printf("Bad conversion type '%s'\n", info->new_name); + DEV_PRINTF("Bad conversion type '%s'\n", info->new_name); } } #pragma GCC diagnostic pop @@ -1950,6 +1991,10 @@ void AP_Param::convert_class(uint16_t param_key, void *object_pointer, } AP_Param *ap2 = (AP_Param *)(group_info[i].offset + (uint8_t *)object_pointer); + if (ap2->configured_in_storage()) { + // user has already set a value, or previous conversion was done + continue; + } memcpy(ap2, ap, sizeof(old_value)); // and save ap2->save(); @@ -2104,13 +2149,14 @@ bool AP_Param::parse_param_line(char *line, char **vname, float &value, bool &re } -#if HAL_OS_POSIX_IO == 1 +#if HAVE_FILESYSTEM_SUPPORT // increments num_defaults for each default found in filename bool AP_Param::count_defaults_in_file(const char *filename, uint16_t &num_defaults) { - FILE *f = fopen(filename, "r"); - if (f == nullptr) { + // try opening the file both in the posix filesystem and using AP::FS + int file_apfs = AP::FS().open(filename, O_RDONLY, true); + if (file_apfs == -1) { return false; } char line[100]; @@ -2118,7 +2164,7 @@ bool AP_Param::count_defaults_in_file(const char *filename, uint16_t &num_defaul /* work out how many parameter default structures to allocate */ - while (fgets(line, sizeof(line)-1, f)) { + while (AP::FS().fgets(line, sizeof(line)-1, file_apfs)) { char *pname; float value; bool read_only; @@ -2131,23 +2177,23 @@ bool AP_Param::count_defaults_in_file(const char *filename, uint16_t &num_defaul } num_defaults++; } - - fclose(f); + AP::FS().close(file_apfs); return true; } bool AP_Param::read_param_defaults_file(const char *filename, bool last_pass) { - FILE *f = fopen(filename, "r"); - if (f == nullptr) { + // try opening the file both in the posix filesystem and using AP::FS + int file_apfs = AP::FS().open(filename, O_RDONLY, true); + if (file_apfs == -1) { AP_HAL::panic("AP_Param: Failed to re-open defaults file"); return false; } uint16_t idx = 0; char line[100]; - while (fgets(line, sizeof(line)-1, f)) { + while (AP::FS().fgets(line, sizeof(line)-1, file_apfs)) { char *pname; float value; bool read_only; @@ -2179,7 +2225,8 @@ bool AP_Param::read_param_defaults_file(const char *filename, bool last_pass) vp->set_float(value, var_type); } } - fclose(f); + AP::FS().close(file_apfs); + return true; } @@ -2243,7 +2290,7 @@ bool AP_Param::load_defaults_file(const char *filename, bool last_pass) return true; } -#endif // HAL_OS_POSIX_IO +#endif // HAVE_FILESYSTEM_SUPPORT #if AP_PARAM_MAX_EMBEDDED_PARAM > 0 /* @@ -2252,28 +2299,25 @@ bool AP_Param::load_defaults_file(const char *filename, bool last_pass) bool AP_Param::count_embedded_param_defaults(uint16_t &count) { const volatile char *ptr = param_defaults_data.data; - uint16_t length = param_defaults_data.length; + int32_t length = param_defaults_data.length; count = 0; - while (length) { + while (length>0) { char line[100]; char *pname; float value; bool read_only; uint16_t i; - uint16_t n = MIN(length, sizeof(line)-1); + uint16_t n = length; for (i=0;i 0) { char line[100]; char *pname; float value; bool read_only; uint16_t i; - uint16_t n = MIN(length, sizeof(line)-1); + uint16_t n = length; for (i=0;iconfigured_in_storage()) { vp->set_float(value, var_type); } @@ -2644,6 +2689,59 @@ bool AP_Param::set_and_save_by_name_ifchanged(const char *name, float value) return false; } +#if AP_PARAM_DEFAULTS_ENABLED +void AP_Param::check_default(AP_Param *ap, float *default_value) +{ + if (default_value == nullptr || ap == nullptr) { + return; + } +#if AP_PARAM_MAX_EMBEDDED_PARAM > 0 + // Check embedded list first + if (embedded_default_list != nullptr) { + for (defaults_list *item = embedded_default_list; item; item = item->next) { + if (item->ap == ap) { + *default_value = item->val; + return; + } + } + } +#endif + if (default_list != nullptr) { + for (defaults_list *item = default_list; item; item = item->next) { + if (item->ap == ap) { + *default_value = item->val; + return; + } + } + } +} + +void AP_Param::add_default(AP_Param *ap, float v, defaults_list*& list) +{ + if (list != nullptr) { + // check is param is already in list + for (defaults_list *item = list; item; item = item->next) { + // update existing entry + if (item->ap == ap) { + item->val = v; + return; + } + } + } + + // add to list + defaults_list *new_item = new defaults_list; + if (new_item == nullptr) { + return; + } + new_item->ap = ap; + new_item->val = v; + new_item->next = list; + list = new_item; +} +#endif // AP_PARAM_DEFAULTS_ENABLED + + #if AP_PARAM_KEY_DUMP /* do not remove this show_all() code, it is essential for debugging @@ -2688,12 +2786,14 @@ void AP_Param::show_all(AP_HAL::BetterStream *port, bool showKeyValues) ParamToken token; AP_Param *ap; enum ap_var_type type; + float default_value = nanf("0x4152"); // from logger quiet_nanf - for (ap=AP_Param::first(&token, &type); + for (ap=AP_Param::first(&token, &type, &default_value); ap; - ap=AP_Param::next_scalar(&token, &type)) { + ap=AP_Param::next_scalar(&token, &type, &default_value)) { if (showKeyValues) { - ::printf("Key %u: Index %u: GroupElement %u : ", (unsigned)var_info(token.key).key, (unsigned)token.idx, (unsigned)token.group_element); + ::printf("Key %u: Index %u: GroupElement %u : Default %f :", (unsigned)var_info(token.key).key, (unsigned)token.idx, (unsigned)token.group_element, default_value); + default_value = nanf("0x4152"); } show(ap, token, type, port); hal.scheduler->delay(1); diff --git a/libraries/AP_Param/AP_Param.h b/libraries/AP_Param/AP_Param.h index f40f4c26547..b46fc941189 100644 --- a/libraries/AP_Param/AP_Param.h +++ b/libraries/AP_Param/AP_Param.h @@ -35,6 +35,12 @@ // optionally enable debug code for dumping keys #define AP_PARAM_KEY_DUMP 0 +#if defined(HAL_GCS_ENABLED) + #define AP_PARAM_DEFAULTS_ENABLED HAL_GCS_ENABLED +#else + #define AP_PARAM_DEFAULTS_ENABLED 1 +#endif + /* maximum size of embedded parameter file */ @@ -469,15 +475,16 @@ class AP_Param /// @return The first variable in _var_info, or nullptr if /// there are none. /// - static AP_Param * first(ParamToken *token, enum ap_var_type *ptype); + static AP_Param * first(ParamToken *token, enum ap_var_type *ptype, float *default_val = nullptr); /// Returns the next variable in _var_info, recursing into groups /// as needed - static AP_Param * next(ParamToken *token, enum ap_var_type *ptype, bool skip_disabled=false); + static AP_Param * next(ParamToken *token, enum ap_var_type *ptype) { return next(token, ptype, false); } + static AP_Param * next(ParamToken *token, enum ap_var_type *ptype, bool skip_disabled, float *default_val = nullptr); /// Returns the next scalar variable in _var_info, recursing into groups /// as needed - static AP_Param * next_scalar(ParamToken *token, enum ap_var_type *ptype); + static AP_Param * next_scalar(ParamToken *token, enum ap_var_type *ptype, float *default_val = nullptr); /// get the size of a type in bytes static uint8_t type_size(enum ap_var_type type); @@ -488,12 +495,6 @@ class AP_Param // check var table for consistency static bool check_var_info(void); - // return true if the parameter is configured in the defaults file - bool configured_in_defaults_file(bool &read_only) const; - - // return true if the parameter is configured in EEPROM/FRAM - bool configured_in_storage(void) const; - // return true if the parameter is configured bool configured(void) const; @@ -545,7 +546,14 @@ class AP_Param static bool add_param(uint8_t key, uint8_t param_num, const char *pname, float default_value); static bool load_int32(uint16_t key, uint32_t group_element, int32_t &value); #endif - + + static bool load_defaults_file(const char *filename, bool last_pass); + +protected: + + // store default value in linked list + static void add_default(AP_Param *ap, float v) { add_default(ap, v, default_list); } + private: static AP_Param *_singleton; @@ -682,21 +690,19 @@ class AP_Param const ptrdiff_t group_offset, ParamToken *token, enum ap_var_type *ptype, - bool skip_disabled); + bool skip_disabled, + float *default_val); // find a default value given a pointer to a default value in flash static float get_default_value(const AP_Param *object_ptr, const float *def_value_ptr); static bool parse_param_line(char *line, char **vname, float &value, bool &read_only); -#if HAL_OS_POSIX_IO == 1 /* load a parameter defaults file. This happens as part of load_all() */ static bool count_defaults_in_file(const char *filename, uint16_t &num_defaults); static bool read_param_defaults_file(const char *filename, bool last_pass); - static bool load_defaults_file(const char *filename, bool last_pass); -#endif /* load defaults from embedded parameters @@ -704,6 +710,12 @@ class AP_Param static bool count_embedded_param_defaults(uint16_t &count); static void load_embedded_param_defaults(bool last_pass); + // return true if the parameter is configured in the defaults file + bool configured_in_defaults_file(bool &read_only) const; + + // return true if the parameter is configured in EEPROM/FRAM + bool configured_in_storage(void) const; + // send a parameter to all GCS instances void send_parameter(const char *name, enum ap_var_type param_header_type, uint8_t idx) const; @@ -761,6 +773,19 @@ class AP_Param // background function for saving parameters void save_io_handler(void); + + // Store default values from add_default() calls in linked list + struct defaults_list { + AP_Param *ap; + float val; + defaults_list *next; + }; +#if AP_PARAM_MAX_EMBEDDED_PARAM > 0 + static defaults_list *embedded_default_list; +#endif + static defaults_list *default_list; + static void add_default(AP_Param *ap, float v, defaults_list *&list); + static void check_default(AP_Param *ap, float *default_value); }; namespace AP { @@ -804,11 +829,23 @@ class AP_ParamT : public AP_Param /// Sets if the parameter is unconfigured /// void set_default(const T &v) { +#if AP_PARAM_DEFAULTS_ENABLED + add_default(this, (float)v); +#endif if (!configured()) { set(v); } } + /// Sets parameter and default + /// + void set_and_default(const T &v) { +#if AP_PARAM_DEFAULTS_ENABLED + add_default(this, (float)v); +#endif + set(v); + } + /// Value setter - set value, tell GCS /// void set_and_notify(const T &v) { @@ -855,35 +892,6 @@ class AP_ParamT : public AP_Param return _value; } - /// Copy assignment from T is equivalent to ::set. - /// - AP_ParamT& operator= (const T &v) { - _value = v; - return *this; - } - - /// bit ops on parameters - /// - AP_ParamT& operator |=(const T &v) { - _value |= v; - return *this; - } - - AP_ParamT& operator &=(const T &v) { - _value &= v; - return *this; - } - - AP_ParamT& operator +=(const T &v) { - _value += v; - return *this; - } - - AP_ParamT& operator -=(const T &v) { - _value -= v; - return *this; - } - /// AP_ParamT types can implement AP_Param::cast_to_float /// float cast_to_float(void) const { @@ -964,13 +972,6 @@ class AP_ParamV : public AP_Param return _value; } - /// Copy assignment from T is equivalent to ::set. - /// - AP_ParamV& operator=(const T &v) { - _value = v; - return *this; - } - protected: T _value; }; diff --git a/libraries/AP_Param/tools/eedump_apparam.c b/libraries/AP_Param/tools/eedump_apparam.c index 709a37296b1..88a88968f77 100644 --- a/libraries/AP_Param/tools/eedump_apparam.c +++ b/libraries/AP_Param/tools/eedump_apparam.c @@ -119,8 +119,8 @@ main(int argc, char *argv[]) index = sizeof(*header); for (;; ) { uint8_t size; - const uint16_t key = ((uint16_t)var->key_high)<<8 | var->key_low; var = (struct Param_header *)&eeprom[index]; + const uint16_t key = ((uint16_t)var->key_high)<<8 | var->key_low; if (key == _sentinal_key || var->type == _sentinal_type) { printf("end sentinel at %u\n", index); diff --git a/libraries/AP_PiccoloCAN/AP_PiccoloCAN.cpp b/libraries/AP_PiccoloCAN/AP_PiccoloCAN.cpp index d7124d54df9..c73d93ae188 100644 --- a/libraries/AP_PiccoloCAN/AP_PiccoloCAN.cpp +++ b/libraries/AP_PiccoloCAN/AP_PiccoloCAN.cpp @@ -33,6 +33,8 @@ #include #include +#include + #include // Protocol files for the Velocity ESC @@ -43,6 +45,10 @@ #include #include +// Protocol files for the ECU +#include +#include + extern const AP_HAL::HAL& hal; #if HAL_CANMANAGER_ENABLED @@ -57,7 +63,7 @@ const AP_Param::GroupInfo AP_PiccoloCAN::var_info[] = { // @Param: ESC_BM // @DisplayName: ESC channels // @Description: Bitmask defining which ESC (motor) channels are to be transmitted over Piccolo CAN - // @Bitmask: 0: ESC 1, 1: ESC 2, 2: ESC 3, 3: ESC 4, 4: ESC 5, 5: ESC 6, 6: ESC 7, 7: ESC 8, 8: ESC 9, 9: ESC 10, 10: ESC 11, 11: ESC 12, 12: ESC 13, 13: ESC 14, 14: ESC 15, 15: ESC 16 + // @Bitmask: 0: ESC 1, 1: ESC 2, 2: ESC 3, 3: ESC 4, 4: ESC 5, 5: ESC 6, 6: ESC 7, 7: ESC 8, 8: ESC 9, 9: ESC 10, 10: ESC 11, 11: ESC 12, 12: ESC 13, 13: ESC 14, 14: ESC 15, 15: ESC 16, 16: ESC 17, 17: ESC 18, 18: ESC 19, 19: ESC 20, 20: ESC 21, 21: ESC 22, 22: ESC 23, 23: ESC 24, 24: ESC 25, 25: ESC 26, 26: ESC 27, 27: ESC 28, 28: ESC 29, 29: ESC 30, 30: ESC 31, 31: ESC 32 // @User: Advanced AP_GROUPINFO("ESC_BM", 1, AP_PiccoloCAN, _esc_bm, 0xFFFF), @@ -83,7 +89,22 @@ const AP_Param::GroupInfo AP_PiccoloCAN::var_info[] = { // @User: Advanced // @Range: 1 500 AP_GROUPINFO("SRV_RT", 4, AP_PiccoloCAN, _srv_hz, PICCOLO_MSG_RATE_HZ_DEFAULT), +#if HAL_EFI_CURRAWONG_ECU_ENABLED + // @Param: ECU_ID + // @DisplayName: ECU Node ID + // @Description: Node ID to send ECU throttle messages to. Set to zero to disable ECU throttle messages. Set to 255 to broadcast to all ECUs. + // @Range: 0 255 + // @User: Advanced + AP_GROUPINFO("ECU_ID", 5, AP_PiccoloCAN, _ecu_id, PICCOLO_CAN_ECU_ID_DEFAULT), + // @Param: ECU_RT + // @DisplayName: ECU command output rate + // @Description: Output rate of ECU command messages + // @Units: Hz + // @User: Advanced + // @Range: 1 500 + AP_GROUPINFO("ECU_RT", 6, AP_PiccoloCAN, _ecu_hz, PICCOLO_MSG_RATE_HZ_DEFAULT), +#endif AP_GROUPEND }; @@ -161,6 +182,9 @@ void AP_PiccoloCAN::loop() uint16_t esc_tx_counter = 0; uint16_t servo_tx_counter = 0; +#if HAL_EFI_CURRAWONG_ECU_ENABLED + uint16_t ecu_tx_counter = 0; +#endif // CAN Frame ID components uint8_t frame_id_group; // Piccolo message group @@ -175,15 +199,19 @@ void AP_PiccoloCAN::loop() } // Calculate the output rate for ESC commands - _esc_hz = constrain_int16(_esc_hz, PICCOLO_MSG_RATE_HZ_MIN, PICCOLO_MSG_RATE_HZ_MAX); + _esc_hz.set(constrain_int16(_esc_hz, PICCOLO_MSG_RATE_HZ_MIN, PICCOLO_MSG_RATE_HZ_MAX)); uint16_t escCmdRateMs = 1000 / _esc_hz; // Calculate the output rate for servo commands - _srv_hz = constrain_int16(_srv_hz, PICCOLO_MSG_RATE_HZ_MIN, PICCOLO_MSG_RATE_HZ_MAX); + _srv_hz.set(constrain_int16(_srv_hz, PICCOLO_MSG_RATE_HZ_MIN, PICCOLO_MSG_RATE_HZ_MAX)); uint16_t servoCmdRateMs = 1000 / _srv_hz; +#if HAL_EFI_CURRAWONG_ECU_ENABLED + _ecu_hz.set(constrain_int16(_ecu_hz, PICCOLO_MSG_RATE_HZ_MIN, PICCOLO_MSG_RATE_HZ_MAX)); + uint16_t ecuCmdRateMs = 1000 / _ecu_hz; +#endif uint64_t timeout = AP_HAL::micros64() + 250ULL; // 1ms loop delay @@ -201,6 +229,14 @@ void AP_PiccoloCAN::loop() send_servo_messages(); } +#if HAL_EFI_CURRAWONG_ECU_ENABLED + // Transmit ecu throttle commands at regular intervals + if (ecu_tx_counter++ > ecuCmdRateMs) { + ecu_tx_counter = 0; + send_ecu_messages(); + } +#endif + // Look for any message responses on the CAN bus while (read_frame(rxFrame, timeout)) { @@ -233,6 +269,13 @@ void AP_PiccoloCAN::loop() break; } + break; + case MessageGroup::ECU_OUT: + #if HAL_EFI_CURRAWONG_ECU_ENABLED + if (handle_ecu_message(rxFrame)) { + // Returns true if the message was successfully decoded + } + #endif break; default: break; @@ -321,6 +364,13 @@ void AP_PiccoloCAN::update() } } +#if HAL_EFI_CURRAWONG_ECU_ENABLED + if (_ecu_id != 0) { + _ecu_info.command = SRV_Channels::get_output_scaled(SRV_Channel::k_throttle); + _ecu_info.newCommand = true; + } +#endif // HAL_EFI_CURRAWONG_ECU_ENABLED + AP_Logger *logger = AP_Logger::get_singleton(); // Push received telemetry data into the logging system @@ -337,7 +387,7 @@ void AP_PiccoloCAN::update() timestamp, ii, (float) servo.statusA.position, // Servo position (represented in microsecond units) - (float) servo.statusB.current / 100.0f, // Servo force (actually servo current, 0.01A per bit) + (float) servo.statusB.current * 0.01f, // Servo force (actually servo current, 0.01A per bit) (float) servo.statusB.speed, // Servo speed (degrees per second) (uint8_t) abs(servo.statusB.dutyCycle) // Servo duty cycle (absolute value as it can be +/- 100%) ); @@ -693,8 +743,8 @@ bool AP_PiccoloCAN::handle_esc_message(AP_HAL::CANFrame &frame) AP_ESC_Telem_Backend::TelemetryData telem {}; - telem.voltage = float(esc.voltage) * 0.01f; - telem.current = float(esc.current) * 0.01f; + telem.voltage = float(esc.voltage) * 0.1f; + telem.current = float(esc.current) * 0.1f; telem.motor_temp_cdeg = int16_t(esc.motorTemperature * 100); update_telem_data(addr, telem, @@ -736,6 +786,39 @@ bool AP_PiccoloCAN::handle_esc_message(AP_HAL::CANFrame &frame) return result; } +#if HAL_EFI_CURRAWONG_ECU_ENABLED +void AP_PiccoloCAN::send_ecu_messages(void) +{ + AP_HAL::CANFrame txFrame {}; + + const uint64_t timeout = AP_HAL::micros64() + 1000ULL; + + // No ECU node id set, don't send anything + if (_ecu_id == 0) { + return; + } + + if (_ecu_info.newCommand) { + encodeECU_ThrottleCommandPacket(&txFrame, _ecu_info.command); + txFrame.id |= (uint8_t) _ecu_id; + + _ecu_info.newCommand = false; + + write_frame(txFrame, timeout); + } +} + +bool AP_PiccoloCAN::handle_ecu_message(AP_HAL::CANFrame &frame) +{ + // Get the ecu instance + AP_EFI_Currawong_ECU* ecu = AP_EFI_Currawong_ECU::get_instance(); + if (ecu != nullptr) { + return ecu->handle_message(frame); + } + return false; +} +#endif // HAL_EFI_CURRAWONG_ECU_ENABLED + /** * Check if a given servo channel is "active" (has been configured for Piccolo control output) */ @@ -749,7 +832,7 @@ bool AP_PiccoloCAN::is_servo_channel_active(uint8_t chan) SRV_Channel::Aux_servo_function_t function = SRV_Channels::channel_function(chan); // Ignore if the servo channel does not have a function assigned - if (function == SRV_Channel::k_none) { + if (function <= SRV_Channel::k_none) { return false; } @@ -1059,4 +1142,71 @@ uint32_t getServoPacketID(const void* pkt) return (uint32_t) ((frame->id >> 16) & 0xFF); } +/* Piccolo Glue Logic + * The following functions are required by the auto-generated protogen code. + */ + + +//! \return the packet data pointer from the packet +uint8_t* getECUPacketData(void* pkt) +{ + AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt; + + return (uint8_t*) frame->data; +} + +//! \return the packet data pointer from the packet, const +const uint8_t* getECUPacketDataConst(const void* pkt) +{ + AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt; + + return (const uint8_t*) frame->data; +} + +//! Complete a packet after the data have been encoded +void finishECUPacket(void* pkt, int size, uint32_t packetID) +{ + AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt; + + if (size > AP_HAL::CANFrame::MaxDataLen) { + size = AP_HAL::CANFrame::MaxDataLen; + } + + frame->dlc = size; + + /* Encode the CAN ID + * 0x09mmdddd + * - 07 = ECU_IN (to and ECU) group ID + * - mm = Message ID + * - dd = Device ID + * + * Note: The Device ID (lower 16 bits of the frame ID) will have to be inserted later + */ + + uint32_t id = (((uint8_t) AP_PiccoloCAN::MessageGroup::ECU_IN) << 24) | // CAN Group ID + ((packetID & 0xFF) << 16); // Message ID + + // Extended frame format + id |= AP_HAL::CANFrame::FlagEFF; + + frame->id = id; +} + +//! \return the size of a packet from the packet header +int getECUPacketSize(const void* pkt) +{ + AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt; + + return (int) frame->dlc; +} + +//! \return the ID of a packet from the packet header +uint32_t getECUPacketID(const void* pkt) +{ + AP_HAL::CANFrame* frame = (AP_HAL::CANFrame*) pkt; + + // Extract the message ID field from the 29-bit ID + return (uint32_t) ((frame->id >> 16) & 0xFF); +} + #endif // HAL_PICCOLO_CAN_ENABLE diff --git a/libraries/AP_PiccoloCAN/AP_PiccoloCAN.h b/libraries/AP_PiccoloCAN/AP_PiccoloCAN.h index d8c1e830387..d18c7a1e502 100644 --- a/libraries/AP_PiccoloCAN/AP_PiccoloCAN.h +++ b/libraries/AP_PiccoloCAN/AP_PiccoloCAN.h @@ -12,7 +12,7 @@ * You should have received a copy of the GNU General Public License along * with this program. If not, see . * - * Author: Oliver Walters + * Author: Oliver Walters / Currawong Engineering Pty Ltd */ #pragma once @@ -28,6 +28,8 @@ #include "piccolo_protocol/ServoPackets.h" +#include + // maximum number of ESC allowed on CAN bus simultaneously #define PICCOLO_CAN_MAX_NUM_ESC 16 #define PICCOLO_CAN_MAX_GROUP_ESC (PICCOLO_CAN_MAX_NUM_ESC / 4) @@ -45,6 +47,8 @@ #define PICCOLO_MSG_RATE_HZ_MAX 500 #define PICCOLO_MSG_RATE_HZ_DEFAULT 50 +#define PICCOLO_CAN_ECU_ID_DEFAULT 0 + class AP_PiccoloCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { public: @@ -130,6 +134,13 @@ class AP_PiccoloCAN : public AP_CANDriver, public AP_ESC_Telem_Backend // interpret a servo message received over CAN bool handle_servo_message(AP_HAL::CANFrame &frame); + +#if HAL_EFI_CURRAWONG_ECU_ENABLED + void send_ecu_messages(void); + + // interpret an ECU message received over CAN + bool handle_ecu_message(AP_HAL::CANFrame &frame); +#endif bool _initialized; char _thread_name[16]; @@ -200,6 +211,11 @@ class AP_PiccoloCAN : public AP_CANDriver, public AP_ESC_Telem_Backend } _esc_info[PICCOLO_CAN_MAX_NUM_ESC]; + struct CurrawongECU_Info_t { + float command; + bool newCommand; + } _ecu_info; + // Piccolo CAN parameters AP_Int32 _esc_bm; //! ESC selection bitmask AP_Int16 _esc_hz; //! ESC update rate (Hz) @@ -207,6 +223,9 @@ class AP_PiccoloCAN : public AP_CANDriver, public AP_ESC_Telem_Backend AP_Int32 _srv_bm; //! Servo selection bitmask AP_Int16 _srv_hz; //! Servo update rate (Hz) + AP_Int16 _ecu_id; //! ECU Node ID + AP_Int16 _ecu_hz; //! ECU update rate (Hz) + HAL_Semaphore _telem_sem; }; diff --git a/libraries/AP_PiccoloCAN/piccolo_protocol/ECUDefines.c b/libraries/AP_PiccoloCAN/piccolo_protocol/ECUDefines.c new file mode 100644 index 00000000000..1af342789b5 --- /dev/null +++ b/libraries/AP_PiccoloCAN/piccolo_protocol/ECUDefines.c @@ -0,0 +1,663 @@ +// ECUDefines.c was generated by ProtoGen version 3.2.a + +/* + * This file is free software: you can redistribute it and/or modify it + * under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program. If not, see . + * + * Author: Oliver Walters / Currawong Engineering Pty Ltd + */ + + +#include "ECUDefines.h" +#include "fielddecode.h" +#include "fieldencode.h" +#include "scaleddecode.h" +#include "scaledencode.h" + +/*! + * \brief Encode a ECU_AuxiliaryErrorBits_t into a byte array + * + + * \param _pg_data points to the byte array to add encoded data to + * \param _pg_bytecount points to the starting location in the byte array, and will be incremented by the number of encoded bytes. + * \param _pg_user is the data to encode in the byte array + */ +void encodeECU_AuxiliaryErrorBits_t(uint8_t* _pg_data, int* _pg_bytecount, const ECU_AuxiliaryErrorBits_t* _pg_user) +{ + int _pg_byteindex = *_pg_bytecount; + + // 1 if CAN servo is not connected + _pg_data[_pg_byteindex] = (uint8_t)((_pg_user->servoLink == true) ? 1 : 0) << 7; + + // 1 if CAN servo is reporting a position error + _pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->servoPosition == true) ? 1 : 0) << 6; + + // Reserved for future use + // Range of reserved_A is 0 to 63. + _pg_data[_pg_byteindex] |= (uint8_t)_pg_user->reserved_A; + + // Reserved for future use + // Range of reserved_B is 0 to 255. + _pg_data[_pg_byteindex + 1] = (uint8_t)_pg_user->reserved_B; + + // Reserved for future use + // Range of reserved_C is 0 to 255. + _pg_data[_pg_byteindex + 2] = (uint8_t)_pg_user->reserved_C; + + // Reserved for future use + // Range of reserved_D is 0 to 255. + _pg_data[_pg_byteindex + 3] = (uint8_t)_pg_user->reserved_D; + _pg_byteindex += 4; // close bit field + + *_pg_bytecount = _pg_byteindex; + +}// encodeECU_AuxiliaryErrorBits_t + +/*! + * \brief Decode a ECU_AuxiliaryErrorBits_t from a byte array + * + + * \param _pg_data points to the byte array to decoded data from + * \param _pg_bytecount points to the starting location in the byte array, and will be incremented by the number of bytes decoded + * \param _pg_user is the data to decode from the byte array + * \return 1 if the data are decoded, else 0. + */ +int decodeECU_AuxiliaryErrorBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ECU_AuxiliaryErrorBits_t* _pg_user) +{ + int _pg_byteindex = *_pg_bytecount; + + // 1 if CAN servo is not connected + _pg_user->servoLink = ((_pg_data[_pg_byteindex] >> 7)) ? true : false; + + // 1 if CAN servo is reporting a position error + _pg_user->servoPosition = (((_pg_data[_pg_byteindex] >> 6) & 0x1)) ? true : false; + + // Reserved for future use + // Range of reserved_A is 0 to 63. + _pg_user->reserved_A = ((_pg_data[_pg_byteindex]) & 0x3F); + + // Reserved for future use + // Range of reserved_B is 0 to 255. + _pg_user->reserved_B = _pg_data[_pg_byteindex + 1]; + + // Reserved for future use + // Range of reserved_C is 0 to 255. + _pg_user->reserved_C = _pg_data[_pg_byteindex + 2]; + + // Reserved for future use + // Range of reserved_D is 0 to 255. + _pg_user->reserved_D = _pg_data[_pg_byteindex + 3]; + _pg_byteindex += 4; // close bit field + + *_pg_bytecount = _pg_byteindex; + + return 1; + +}// decodeECU_AuxiliaryErrorBits_t + +/*! + * \brief Encode a ECU_AutronicErrorBits_t into a byte array + * + + * \param _pg_data points to the byte array to add encoded data to + * \param _pg_bytecount points to the starting location in the byte array, and will be incremented by the number of encoded bytes. + * \param _pg_user is the data to encode in the byte array + */ +void encodeECU_AutronicErrorBits_t(uint8_t* _pg_data, int* _pg_bytecount, const ECU_AutronicErrorBits_t* _pg_user) +{ + int _pg_byteindex = *_pg_bytecount; + + // Reserved + _pg_data[_pg_byteindex] = 0; + + // Knock control error + _pg_data[_pg_byteindex + 1] = (uint8_t)_pg_user->knockControl << 7; + + // AF closed loop error + _pg_data[_pg_byteindex + 1] |= (uint8_t)_pg_user->afCloseLoop << 6; + + // EEPROM error + _pg_data[_pg_byteindex + 1] |= (uint8_t)_pg_user->eepromError << 5; + + // CMOS RAM error + _pg_data[_pg_byteindex + 1] |= (uint8_t)_pg_user->cmosRam << 4; + + // Over voltage error + _pg_data[_pg_byteindex + 1] |= (uint8_t)_pg_user->overVoltage << 3; + + // Power down error + _pg_data[_pg_byteindex + 1] |= (uint8_t)_pg_user->powerDown << 2; + + // Knock sensor error + _pg_data[_pg_byteindex + 1] |= (uint8_t)_pg_user->knockSensor << 1; + + // Over boost error + _pg_data[_pg_byteindex + 1] |= (uint8_t)_pg_user->overBoost; + + // CAM2 position error + _pg_data[_pg_byteindex + 2] = (uint8_t)_pg_user->cam2Pos << 7; + + // CAM1 position error + _pg_data[_pg_byteindex + 2] |= (uint8_t)_pg_user->cam1Pos << 6; + + // High speed input 1 error + _pg_data[_pg_byteindex + 2] |= (uint8_t)_pg_user->highSpeedInput2 << 5; + + // High speed input 2 error + _pg_data[_pg_byteindex + 2] |= (uint8_t)_pg_user->highSpeedInput1 << 4; + + // Set if too many cylinder pulses + _pg_data[_pg_byteindex + 2] |= (uint8_t)_pg_user->tooManyCylPulse << 3; + + // Set if too few cylinder pulses + _pg_data[_pg_byteindex + 2] |= (uint8_t)_pg_user->tooFewCylPulse << 2; + + // Set if sync input pulse missing + _pg_data[_pg_byteindex + 2] |= (uint8_t)_pg_user->syncInputPulseMissing << 1; + + // Set if cylinder input pulse missing + _pg_data[_pg_byteindex + 2] |= (uint8_t)_pg_user->cylinderInputPulseMissing; + + // Air fuel sensor 2 error + _pg_data[_pg_byteindex + 3] = (uint8_t)_pg_user->af2Sensor << 7; + + // Air fuel sensor 1 error + _pg_data[_pg_byteindex + 3] |= (uint8_t)_pg_user->af1Sensor << 6; + + // Barometric pressure sensor error + _pg_data[_pg_byteindex + 3] |= (uint8_t)_pg_user->baroSensor << 5; + + // Exhaust back pressure sensor error + _pg_data[_pg_byteindex + 3] |= (uint8_t)_pg_user->ebpSensor << 4; + + // Manifold pressure sensor error + _pg_data[_pg_byteindex + 3] |= (uint8_t)_pg_user->mapSensor << 3; + + // Throttle position sensor error + _pg_data[_pg_byteindex + 3] |= (uint8_t)_pg_user->tpsSensor << 2; + + // Cylinder head temperature sensor error + _pg_data[_pg_byteindex + 3] |= (uint8_t)_pg_user->chtSensor << 1; + + // Manifold pressure sensor error + _pg_data[_pg_byteindex + 3] |= (uint8_t)_pg_user->matSensor; + _pg_byteindex += 4; // close bit field + + *_pg_bytecount = _pg_byteindex; + +}// encodeECU_AutronicErrorBits_t + +/*! + * \brief Decode a ECU_AutronicErrorBits_t from a byte array + * + + * \param _pg_data points to the byte array to decoded data from + * \param _pg_bytecount points to the starting location in the byte array, and will be incremented by the number of bytes decoded + * \param _pg_user is the data to decode from the byte array + * \return 1 if the data are decoded, else 0. + */ +int decodeECU_AutronicErrorBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ECU_AutronicErrorBits_t* _pg_user) +{ + int _pg_byteindex = *_pg_bytecount; + + // Reserved + + // Knock control error + _pg_user->knockControl = (_pg_data[_pg_byteindex + 1] >> 7); + + // AF closed loop error + _pg_user->afCloseLoop = ((_pg_data[_pg_byteindex + 1] >> 6) & 0x1); + + // EEPROM error + _pg_user->eepromError = ((_pg_data[_pg_byteindex + 1] >> 5) & 0x1); + + // CMOS RAM error + _pg_user->cmosRam = ((_pg_data[_pg_byteindex + 1] >> 4) & 0x1); + + // Over voltage error + _pg_user->overVoltage = ((_pg_data[_pg_byteindex + 1] >> 3) & 0x1); + + // Power down error + _pg_user->powerDown = ((_pg_data[_pg_byteindex + 1] >> 2) & 0x1); + + // Knock sensor error + _pg_user->knockSensor = ((_pg_data[_pg_byteindex + 1] >> 1) & 0x1); + + // Over boost error + _pg_user->overBoost = ((_pg_data[_pg_byteindex + 1]) & 0x1); + + // CAM2 position error + _pg_user->cam2Pos = (_pg_data[_pg_byteindex + 2] >> 7); + + // CAM1 position error + _pg_user->cam1Pos = ((_pg_data[_pg_byteindex + 2] >> 6) & 0x1); + + // High speed input 1 error + _pg_user->highSpeedInput2 = ((_pg_data[_pg_byteindex + 2] >> 5) & 0x1); + + // High speed input 2 error + _pg_user->highSpeedInput1 = ((_pg_data[_pg_byteindex + 2] >> 4) & 0x1); + + // Set if too many cylinder pulses + _pg_user->tooManyCylPulse = ((_pg_data[_pg_byteindex + 2] >> 3) & 0x1); + + // Set if too few cylinder pulses + _pg_user->tooFewCylPulse = ((_pg_data[_pg_byteindex + 2] >> 2) & 0x1); + + // Set if sync input pulse missing + _pg_user->syncInputPulseMissing = ((_pg_data[_pg_byteindex + 2] >> 1) & 0x1); + + // Set if cylinder input pulse missing + _pg_user->cylinderInputPulseMissing = ((_pg_data[_pg_byteindex + 2]) & 0x1); + + // Air fuel sensor 2 error + _pg_user->af2Sensor = (_pg_data[_pg_byteindex + 3] >> 7); + + // Air fuel sensor 1 error + _pg_user->af1Sensor = ((_pg_data[_pg_byteindex + 3] >> 6) & 0x1); + + // Barometric pressure sensor error + _pg_user->baroSensor = ((_pg_data[_pg_byteindex + 3] >> 5) & 0x1); + + // Exhaust back pressure sensor error + _pg_user->ebpSensor = ((_pg_data[_pg_byteindex + 3] >> 4) & 0x1); + + // Manifold pressure sensor error + _pg_user->mapSensor = ((_pg_data[_pg_byteindex + 3] >> 3) & 0x1); + + // Throttle position sensor error + _pg_user->tpsSensor = ((_pg_data[_pg_byteindex + 3] >> 2) & 0x1); + + // Cylinder head temperature sensor error + _pg_user->chtSensor = ((_pg_data[_pg_byteindex + 3] >> 1) & 0x1); + + // Manifold pressure sensor error + _pg_user->matSensor = ((_pg_data[_pg_byteindex + 3]) & 0x1); + _pg_byteindex += 4; // close bit field + + *_pg_bytecount = _pg_byteindex; + + return 1; + +}// decodeECU_AutronicErrorBits_t + +/*! + * \brief Encode a ECU_ErrorBits_t into a byte array + * + + * \param _pg_data points to the byte array to add encoded data to + * \param _pg_bytecount points to the starting location in the byte array, and will be incremented by the number of encoded bytes. + * \param _pg_user is the data to encode in the byte array + */ +void encodeECU_ErrorBits_t(uint8_t* _pg_data, int* _pg_bytecount, const ECU_ErrorBits_t* _pg_user) +{ + int _pg_byteindex = *_pg_bytecount; + + // Error information for autronic processor + encodeECU_AutronicErrorBits_t(_pg_data, &_pg_byteindex, &_pg_user->autronic); + + // Error information for auxiliary processor + encodeECU_AuxiliaryErrorBits_t(_pg_data, &_pg_byteindex, &_pg_user->auxiliary); + + *_pg_bytecount = _pg_byteindex; + +}// encodeECU_ErrorBits_t + +/*! + * \brief Decode a ECU_ErrorBits_t from a byte array + * + + * \param _pg_data points to the byte array to decoded data from + * \param _pg_bytecount points to the starting location in the byte array, and will be incremented by the number of bytes decoded + * \param _pg_user is the data to decode from the byte array + * \return 1 if the data are decoded, else 0. + */ +int decodeECU_ErrorBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ECU_ErrorBits_t* _pg_user) +{ + int _pg_byteindex = *_pg_bytecount; + + // Error information for autronic processor + if(decodeECU_AutronicErrorBits_t(_pg_data, &_pg_byteindex, &_pg_user->autronic) == 0) + return 0; + + // Error information for auxiliary processor + if(decodeECU_AuxiliaryErrorBits_t(_pg_data, &_pg_byteindex, &_pg_user->auxiliary) == 0) + return 0; + + *_pg_bytecount = _pg_byteindex; + + return 1; + +}// decodeECU_ErrorBits_t + +/*! + * \brief Encode a ECU_ThrottleDelayConfigBits_t into a byte array + * + + * \param _pg_data points to the byte array to add encoded data to + * \param _pg_bytecount points to the starting location in the byte array, and will be incremented by the number of encoded bytes. + * \param _pg_user is the data to encode in the byte array + */ +void encodeECU_ThrottleDelayConfigBits_t(uint8_t* _pg_data, int* _pg_bytecount, const ECU_ThrottleDelayConfigBits_t* _pg_user) +{ + int _pg_byteindex = *_pg_bytecount; + + // reserved for future use + // Range of reserved is 0 to 127. + _pg_data[_pg_byteindex] = (uint8_t)_pg_user->reserved << 1; + + // Set to base the delay on temperature, else the delay is manually set + _pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->delayOnTemp == true) ? 1 : 0); + _pg_byteindex += 1; // close bit field + + *_pg_bytecount = _pg_byteindex; + +}// encodeECU_ThrottleDelayConfigBits_t + +/*! + * \brief Decode a ECU_ThrottleDelayConfigBits_t from a byte array + * + + * \param _pg_data points to the byte array to decoded data from + * \param _pg_bytecount points to the starting location in the byte array, and will be incremented by the number of bytes decoded + * \param _pg_user is the data to decode from the byte array + * \return 1 if the data are decoded, else 0. + */ +int decodeECU_ThrottleDelayConfigBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ECU_ThrottleDelayConfigBits_t* _pg_user) +{ + int _pg_byteindex = *_pg_bytecount; + + // reserved for future use + // Range of reserved is 0 to 127. + _pg_user->reserved = (_pg_data[_pg_byteindex] >> 1); + + // Set to base the delay on temperature, else the delay is manually set + _pg_user->delayOnTemp = (((_pg_data[_pg_byteindex]) & 0x1)) ? true : false; + _pg_byteindex += 1; // close bit field + + *_pg_bytecount = _pg_byteindex; + + return 1; + +}// decodeECU_ThrottleDelayConfigBits_t + +/*! + * \brief Encode a ECU_ThrottleConfigBits_t into a byte array + * + + * \param _pg_data points to the byte array to add encoded data to + * \param _pg_bytecount points to the starting location in the byte array, and will be incremented by the number of encoded bytes. + * \param _pg_user is the data to encode in the byte array + */ +void encodeECU_ThrottleConfigBits_t(uint8_t* _pg_data, int* _pg_bytecount, const ECU_ThrottleConfigBits_t* _pg_user) +{ + int _pg_byteindex = *_pg_bytecount; + + // Enable pass-through of CAN servo data over serial link + _pg_data[_pg_byteindex] = (uint8_t)((_pg_user->servoPassthrough == true) ? 1 : 0) << 7; + + // Reserved for future use + + // Set if the CAN throttle is detected + _pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->canThrottleDetected == true) ? 1 : 0) << 1; + + // Set if CAN throttle is enabled. This bit is ignored when this packet is sent to the ECU. To enable CAN throttle you must use system commands + _pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->canThrottle == true) ? 1 : 0); + _pg_byteindex += 1; // close bit field + + *_pg_bytecount = _pg_byteindex; + +}// encodeECU_ThrottleConfigBits_t + +/*! + * \brief Decode a ECU_ThrottleConfigBits_t from a byte array + * + + * \param _pg_data points to the byte array to decoded data from + * \param _pg_bytecount points to the starting location in the byte array, and will be incremented by the number of bytes decoded + * \param _pg_user is the data to decode from the byte array + * \return 1 if the data are decoded, else 0. + */ +int decodeECU_ThrottleConfigBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ECU_ThrottleConfigBits_t* _pg_user) +{ + int _pg_byteindex = *_pg_bytecount; + + // Enable pass-through of CAN servo data over serial link + _pg_user->servoPassthrough = ((_pg_data[_pg_byteindex] >> 7)) ? true : false; + + // Reserved for future use + + // Set if the CAN throttle is detected + _pg_user->canThrottleDetected = (((_pg_data[_pg_byteindex] >> 1) & 0x1)) ? true : false; + + // Set if CAN throttle is enabled. This bit is ignored when this packet is sent to the ECU. To enable CAN throttle you must use system commands + _pg_user->canThrottle = (((_pg_data[_pg_byteindex]) & 0x1)) ? true : false; + _pg_byteindex += 1; // close bit field + + *_pg_bytecount = _pg_byteindex; + + return 1; + +}// decodeECU_ThrottleConfigBits_t + +/*! + * \brief Encode a ECU_ThrottleCurveConfigBits_t into a byte array + * + + * \param _pg_data points to the byte array to add encoded data to + * \param _pg_bytecount points to the starting location in the byte array, and will be incremented by the number of encoded bytes. + * \param _pg_user is the data to encode in the byte array + */ +void encodeECU_ThrottleCurveConfigBits_t(uint8_t* _pg_data, int* _pg_bytecount, const ECU_ThrottleCurveConfigBits_t* _pg_user) +{ + int _pg_byteindex = *_pg_bytecount; + + // Reserved for future use + _pg_data[_pg_byteindex] = 0; + + // Throttle curve is active + _pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->curveActive == true) ? 1 : 0); + _pg_byteindex += 1; // close bit field + + *_pg_bytecount = _pg_byteindex; + +}// encodeECU_ThrottleCurveConfigBits_t + +/*! + * \brief Decode a ECU_ThrottleCurveConfigBits_t from a byte array + * + + * \param _pg_data points to the byte array to decoded data from + * \param _pg_bytecount points to the starting location in the byte array, and will be incremented by the number of bytes decoded + * \param _pg_user is the data to decode from the byte array + * \return 1 if the data are decoded, else 0. + */ +int decodeECU_ThrottleCurveConfigBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ECU_ThrottleCurveConfigBits_t* _pg_user) +{ + int _pg_byteindex = *_pg_bytecount; + + // Reserved for future use + + // Throttle curve is active + _pg_user->curveActive = (((_pg_data[_pg_byteindex]) & 0x1)) ? true : false; + _pg_byteindex += 1; // close bit field + + *_pg_bytecount = _pg_byteindex; + + return 1; + +}// decodeECU_ThrottleCurveConfigBits_t + +/*! + * \brief Encode a ECU_ECUSettings_t into a byte array + * + + * \param _pg_data points to the byte array to add encoded data to + * \param _pg_bytecount points to the starting location in the byte array, and will be incremented by the number of encoded bytes. + * \param _pg_user is the data to encode in the byte array + */ +void encodeECU_ECUSettings_t(uint8_t* _pg_data, int* _pg_bytecount, const ECU_ECUSettings_t* _pg_user) +{ + int _pg_byteindex = *_pg_bytecount; + + // Range of powerCycles is 0 to 65535. + uint16ToBeBytes(_pg_user->powerCycles, _pg_data, &_pg_byteindex); + + // Deprecated - DO NOT USE + // Range of customerID_deprecated is 0 to 65535. + uint16ToBeBytes(_pg_user->customerID_deprecated, _pg_data, &_pg_byteindex); + + // Range of versionHardware is 0 to 255. + uint8ToBytes(_pg_user->versionHardware, _pg_data, &_pg_byteindex); + + // reserved for future use + // Range of reservedA is 0 to 255. + uint8ToBytes(_pg_user->reservedA, _pg_data, &_pg_byteindex); + + // reserved for future use + // Range of reservedB is 0 to 255. + uint8ToBytes(_pg_user->reservedB, _pg_data, &_pg_byteindex); + + *_pg_bytecount = _pg_byteindex; + +}// encodeECU_ECUSettings_t + +/*! + * \brief Decode a ECU_ECUSettings_t from a byte array + * + + * \param _pg_data points to the byte array to decoded data from + * \param _pg_bytecount points to the starting location in the byte array, and will be incremented by the number of bytes decoded + * \param _pg_user is the data to decode from the byte array + * \return 1 if the data are decoded, else 0. + */ +int decodeECU_ECUSettings_t(const uint8_t* _pg_data, int* _pg_bytecount, ECU_ECUSettings_t* _pg_user) +{ + int _pg_byteindex = *_pg_bytecount; + + // Range of powerCycles is 0 to 65535. + _pg_user->powerCycles = uint16FromBeBytes(_pg_data, &_pg_byteindex); + + // Deprecated - DO NOT USE + // Range of customerID_deprecated is 0 to 65535. + _pg_user->customerID_deprecated = uint16FromBeBytes(_pg_data, &_pg_byteindex); + + // Range of versionHardware is 0 to 255. + _pg_user->versionHardware = uint8FromBytes(_pg_data, &_pg_byteindex); + + // reserved for future use + // Range of reservedA is 0 to 255. + _pg_user->reservedA = uint8FromBytes(_pg_data, &_pg_byteindex); + + // reserved for future use + // Range of reservedB is 0 to 255. + _pg_user->reservedB = uint8FromBytes(_pg_data, &_pg_byteindex); + + *_pg_bytecount = _pg_byteindex; + + return 1; + +}// decodeECU_ECUSettings_t + +/*! + * \brief Encode a ECU_CompileOptions_t into a byte array + * + + * \param _pg_data points to the byte array to add encoded data to + * \param _pg_bytecount points to the starting location in the byte array, and will be incremented by the number of encoded bytes. + * \param _pg_user is the data to encode in the byte array + */ +void encodeECU_CompileOptions_t(uint8_t* _pg_data, int* _pg_bytecount, const ECU_CompileOptions_t* _pg_user) +{ + int _pg_byteindex = *_pg_bytecount; + + // If set, the ECU will pass servo CAN packet data over the serial link + _pg_data[_pg_byteindex] = (uint8_t)((_pg_user->servoPassthrough == true) ? 1 : 0) << 7; + + // If set, the ECU will decode CAN messages in the PICCOLO_DATA_UP group + _pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->piccoloUplink == true) ? 1 : 0) << 6; + + // If set, the ECU supports Autronic message passthrough + _pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->autronicRelay == true) ? 1 : 0) << 5; + + // If set, the ECU supports redundant fuel pump control + _pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->dualPump == true) ? 1 : 0) << 4; + + // If set, the ECU runs a PI controller for fuel pressure. If not set, it uses bang-bang control + _pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->piPump == true) ? 1 : 0) << 3; + + // If set, the ECU will automatically compensate for degredation of the MAP sensor over time + _pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->mapCorrection == true) ? 1 : 0) << 2; + + // If set, the ECU watchdog timer is enabled + _pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->watchdog == true) ? 1 : 0) << 1; + + // If set, the ECU is compiled with extra debug functionality enabled + _pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->debug == true) ? 1 : 0); + _pg_byteindex += 1; // close bit field + + // Reserved for future use + uint8ToBytes((uint8_t)(0), _pg_data, &_pg_byteindex); + + *_pg_bytecount = _pg_byteindex; + +}// encodeECU_CompileOptions_t + +/*! + * \brief Decode a ECU_CompileOptions_t from a byte array + * + + * \param _pg_data points to the byte array to decoded data from + * \param _pg_bytecount points to the starting location in the byte array, and will be incremented by the number of bytes decoded + * \param _pg_user is the data to decode from the byte array + * \return 1 if the data are decoded, else 0. + */ +int decodeECU_CompileOptions_t(const uint8_t* _pg_data, int* _pg_bytecount, ECU_CompileOptions_t* _pg_user) +{ + int _pg_byteindex = *_pg_bytecount; + + // If set, the ECU will pass servo CAN packet data over the serial link + _pg_user->servoPassthrough = ((_pg_data[_pg_byteindex] >> 7)) ? true : false; + + // If set, the ECU will decode CAN messages in the PICCOLO_DATA_UP group + _pg_user->piccoloUplink = (((_pg_data[_pg_byteindex] >> 6) & 0x1)) ? true : false; + + // If set, the ECU supports Autronic message passthrough + _pg_user->autronicRelay = (((_pg_data[_pg_byteindex] >> 5) & 0x1)) ? true : false; + + // If set, the ECU supports redundant fuel pump control + _pg_user->dualPump = (((_pg_data[_pg_byteindex] >> 4) & 0x1)) ? true : false; + + // If set, the ECU runs a PI controller for fuel pressure. If not set, it uses bang-bang control + _pg_user->piPump = (((_pg_data[_pg_byteindex] >> 3) & 0x1)) ? true : false; + + // If set, the ECU will automatically compensate for degredation of the MAP sensor over time + _pg_user->mapCorrection = (((_pg_data[_pg_byteindex] >> 2) & 0x1)) ? true : false; + + // If set, the ECU watchdog timer is enabled + _pg_user->watchdog = (((_pg_data[_pg_byteindex] >> 1) & 0x1)) ? true : false; + + // If set, the ECU is compiled with extra debug functionality enabled + _pg_user->debug = (((_pg_data[_pg_byteindex]) & 0x1)) ? true : false; + _pg_byteindex += 1; // close bit field + + // Reserved for future use + _pg_byteindex += 1; + + *_pg_bytecount = _pg_byteindex; + + return 1; + +}// decodeECU_CompileOptions_t + +// end of ECUDefines.c diff --git a/libraries/AP_PiccoloCAN/piccolo_protocol/ECUDefines.h b/libraries/AP_PiccoloCAN/piccolo_protocol/ECUDefines.h new file mode 100644 index 00000000000..f8d59f1b4e9 --- /dev/null +++ b/libraries/AP_PiccoloCAN/piccolo_protocol/ECUDefines.h @@ -0,0 +1,218 @@ +// ECUDefines.h was generated by ProtoGen version 3.2.a + +/* + * This file is free software: you can redistribute it and/or modify it + * under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program. If not, see . + * + * Author: Oliver Walters / Currawong Engineering Pty Ltd + */ + + +#ifndef _ECUDEFINES_H +#define _ECUDEFINES_H + +// Language target is C, C++ compilers: don't mangle us +#ifdef __cplusplus +extern "C" { +#endif + +/*! + * \file + */ + +#include +#include "ECUProtocol.h" + +typedef struct +{ + bool servoLink; //!< 1 if CAN servo is not connected + bool servoPosition; //!< 1 if CAN servo is reporting a position error + unsigned reserved_A : 6; //!< Reserved for future use + unsigned reserved_B : 8; //!< Reserved for future use + unsigned reserved_C : 8; //!< Reserved for future use + unsigned reserved_D : 8; //!< Reserved for future use +}ECU_AuxiliaryErrorBits_t; + +//! return the minimum encoded length for the ECU_AuxiliaryErrorBits_t structure +#define getMinLengthOfECU_AuxiliaryErrorBits_t() (4) + +//! return the maximum encoded length for the ECU_AuxiliaryErrorBits_t structure +#define getMaxLengthOfECU_AuxiliaryErrorBits_t() (4) + +//! Encode a ECU_AuxiliaryErrorBits_t into a byte array +void encodeECU_AuxiliaryErrorBits_t(uint8_t* data, int* bytecount, const ECU_AuxiliaryErrorBits_t* user); + +//! Decode a ECU_AuxiliaryErrorBits_t from a byte array +int decodeECU_AuxiliaryErrorBits_t(const uint8_t* data, int* bytecount, ECU_AuxiliaryErrorBits_t* user); + +typedef struct +{ + unsigned knockControl : 1; //!< Knock control error + unsigned afCloseLoop : 1; //!< AF closed loop error + unsigned eepromError : 1; //!< EEPROM error + unsigned cmosRam : 1; //!< CMOS RAM error + unsigned overVoltage : 1; //!< Over voltage error + unsigned powerDown : 1; //!< Power down error + unsigned knockSensor : 1; //!< Knock sensor error + unsigned overBoost : 1; //!< Over boost error + unsigned cam2Pos : 1; //!< CAM2 position error + unsigned cam1Pos : 1; //!< CAM1 position error + unsigned highSpeedInput2 : 1; //!< High speed input 1 error + unsigned highSpeedInput1 : 1; //!< High speed input 2 error + unsigned tooManyCylPulse : 1; //!< Set if too many cylinder pulses + unsigned tooFewCylPulse : 1; //!< Set if too few cylinder pulses + unsigned syncInputPulseMissing : 1; //!< Set if sync input pulse missing + unsigned cylinderInputPulseMissing : 1; //!< Set if cylinder input pulse missing + unsigned af2Sensor : 1; //!< Air fuel sensor 2 error + unsigned af1Sensor : 1; //!< Air fuel sensor 1 error + unsigned baroSensor : 1; //!< Barometric pressure sensor error + unsigned ebpSensor : 1; //!< Exhaust back pressure sensor error + unsigned mapSensor : 1; //!< Manifold pressure sensor error + unsigned tpsSensor : 1; //!< Throttle position sensor error + unsigned chtSensor : 1; //!< Cylinder head temperature sensor error + unsigned matSensor : 1; //!< Manifold pressure sensor error +}ECU_AutronicErrorBits_t; + +//! return the minimum encoded length for the ECU_AutronicErrorBits_t structure +#define getMinLengthOfECU_AutronicErrorBits_t() (4) + +//! return the maximum encoded length for the ECU_AutronicErrorBits_t structure +#define getMaxLengthOfECU_AutronicErrorBits_t() (4) + +//! Encode a ECU_AutronicErrorBits_t into a byte array +void encodeECU_AutronicErrorBits_t(uint8_t* data, int* bytecount, const ECU_AutronicErrorBits_t* user); + +//! Decode a ECU_AutronicErrorBits_t from a byte array +int decodeECU_AutronicErrorBits_t(const uint8_t* data, int* bytecount, ECU_AutronicErrorBits_t* user); + +typedef struct +{ + ECU_AutronicErrorBits_t autronic; //!< Error information for autronic processor + ECU_AuxiliaryErrorBits_t auxiliary; //!< Error information for auxiliary processor +}ECU_ErrorBits_t; + +//! return the minimum encoded length for the ECU_ErrorBits_t structure +#define getMinLengthOfECU_ErrorBits_t() (8) + +//! return the maximum encoded length for the ECU_ErrorBits_t structure +#define getMaxLengthOfECU_ErrorBits_t() (8) + +//! Encode a ECU_ErrorBits_t into a byte array +void encodeECU_ErrorBits_t(uint8_t* data, int* bytecount, const ECU_ErrorBits_t* user); + +//! Decode a ECU_ErrorBits_t from a byte array +int decodeECU_ErrorBits_t(const uint8_t* data, int* bytecount, ECU_ErrorBits_t* user); + +typedef struct +{ + unsigned reserved : 7; //!< reserved for future use + bool delayOnTemp; //!< Set to base the delay on temperature, else the delay is manually set +}ECU_ThrottleDelayConfigBits_t; + +//! return the minimum encoded length for the ECU_ThrottleDelayConfigBits_t structure +#define getMinLengthOfECU_ThrottleDelayConfigBits_t() (1) + +//! return the maximum encoded length for the ECU_ThrottleDelayConfigBits_t structure +#define getMaxLengthOfECU_ThrottleDelayConfigBits_t() (1) + +//! Encode a ECU_ThrottleDelayConfigBits_t into a byte array +void encodeECU_ThrottleDelayConfigBits_t(uint8_t* data, int* bytecount, const ECU_ThrottleDelayConfigBits_t* user); + +//! Decode a ECU_ThrottleDelayConfigBits_t from a byte array +int decodeECU_ThrottleDelayConfigBits_t(const uint8_t* data, int* bytecount, ECU_ThrottleDelayConfigBits_t* user); + +typedef struct +{ + bool servoPassthrough; //!< Enable pass-through of CAN servo data over serial link + bool canThrottleDetected; //!< Set if the CAN throttle is detected + bool canThrottle; //!< Set if CAN throttle is enabled. This bit is ignored when this packet is sent to the ECU. To enable CAN throttle you must use system commands +}ECU_ThrottleConfigBits_t; + +//! return the minimum encoded length for the ECU_ThrottleConfigBits_t structure +#define getMinLengthOfECU_ThrottleConfigBits_t() (1) + +//! return the maximum encoded length for the ECU_ThrottleConfigBits_t structure +#define getMaxLengthOfECU_ThrottleConfigBits_t() (1) + +//! Encode a ECU_ThrottleConfigBits_t into a byte array +void encodeECU_ThrottleConfigBits_t(uint8_t* data, int* bytecount, const ECU_ThrottleConfigBits_t* user); + +//! Decode a ECU_ThrottleConfigBits_t from a byte array +int decodeECU_ThrottleConfigBits_t(const uint8_t* data, int* bytecount, ECU_ThrottleConfigBits_t* user); + +typedef struct +{ + bool curveActive; //!< Throttle curve is active +}ECU_ThrottleCurveConfigBits_t; + +//! return the minimum encoded length for the ECU_ThrottleCurveConfigBits_t structure +#define getMinLengthOfECU_ThrottleCurveConfigBits_t() (1) + +//! return the maximum encoded length for the ECU_ThrottleCurveConfigBits_t structure +#define getMaxLengthOfECU_ThrottleCurveConfigBits_t() (1) + +//! Encode a ECU_ThrottleCurveConfigBits_t into a byte array +void encodeECU_ThrottleCurveConfigBits_t(uint8_t* data, int* bytecount, const ECU_ThrottleCurveConfigBits_t* user); + +//! Decode a ECU_ThrottleCurveConfigBits_t from a byte array +int decodeECU_ThrottleCurveConfigBits_t(const uint8_t* data, int* bytecount, ECU_ThrottleCurveConfigBits_t* user); + +typedef struct +{ + uint16_t powerCycles; + uint16_t customerID_deprecated; //!< Deprecated - DO NOT USE + uint8_t versionHardware; + uint8_t reservedA; //!< reserved for future use + uint8_t reservedB; //!< reserved for future use +}ECU_ECUSettings_t; + +//! return the minimum encoded length for the ECU_ECUSettings_t structure +#define getMinLengthOfECU_ECUSettings_t() (7) + +//! return the maximum encoded length for the ECU_ECUSettings_t structure +#define getMaxLengthOfECU_ECUSettings_t() (7) + +//! Encode a ECU_ECUSettings_t into a byte array +void encodeECU_ECUSettings_t(uint8_t* data, int* bytecount, const ECU_ECUSettings_t* user); + +//! Decode a ECU_ECUSettings_t from a byte array +int decodeECU_ECUSettings_t(const uint8_t* data, int* bytecount, ECU_ECUSettings_t* user); + +typedef struct +{ + bool servoPassthrough; //!< If set, the ECU will pass servo CAN packet data over the serial link + bool piccoloUplink; //!< If set, the ECU will decode CAN messages in the PICCOLO_DATA_UP group + bool autronicRelay; //!< If set, the ECU supports Autronic message passthrough + bool dualPump; //!< If set, the ECU supports redundant fuel pump control + bool piPump; //!< If set, the ECU runs a PI controller for fuel pressure. If not set, it uses bang-bang control + bool mapCorrection; //!< If set, the ECU will automatically compensate for degredation of the MAP sensor over time + bool watchdog; //!< If set, the ECU watchdog timer is enabled + bool debug; //!< If set, the ECU is compiled with extra debug functionality enabled +}ECU_CompileOptions_t; + +//! return the minimum encoded length for the ECU_CompileOptions_t structure +#define getMinLengthOfECU_CompileOptions_t() (2) + +//! return the maximum encoded length for the ECU_CompileOptions_t structure +#define getMaxLengthOfECU_CompileOptions_t() (2) + +//! Encode a ECU_CompileOptions_t into a byte array +void encodeECU_CompileOptions_t(uint8_t* data, int* bytecount, const ECU_CompileOptions_t* user); + +//! Decode a ECU_CompileOptions_t from a byte array +int decodeECU_CompileOptions_t(const uint8_t* data, int* bytecount, ECU_CompileOptions_t* user); + +#ifdef __cplusplus +} +#endif +#endif // _ECUDEFINES_H diff --git a/libraries/AP_PiccoloCAN/piccolo_protocol/ECUPackets.c b/libraries/AP_PiccoloCAN/piccolo_protocol/ECUPackets.c new file mode 100644 index 00000000000..d3c72dc4e9f --- /dev/null +++ b/libraries/AP_PiccoloCAN/piccolo_protocol/ECUPackets.c @@ -0,0 +1,4023 @@ +// ECUPackets.c was generated by ProtoGen version 3.2.a + +/* + * Copyright Currawong Engineering Pty Ltd + * www.currawongeng.com + * all rights reserved + */ + + +#include "ECUPackets.h" +#include "fielddecode.h" +#include "fieldencode.h" +#include "scaleddecode.h" +#include "scaledencode.h" + +/*! + * \brief Create the ECU_ThrottleCommand packet + * + * The throttle command packet sets the throttle position setpoint. The ECU + * will adjust the throttle position based on this command. + * \param _pg_pkt points to the packet which will be created by this function + * \param throttleCommand is Commanded throttle position in percent + */ +void encodeECU_ThrottleCommandPacket(void* _pg_pkt, float throttleCommand) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // Commanded throttle position in percent + // Range of throttleCommand is 0.0f to 100.0f. + float32ScaledTo2UnsignedBeBytes(throttleCommand, _pg_data, &_pg_byteindex, 0.0f, 655.35f); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_ThrottleCommandPacketID()); + +}// encodeECU_ThrottleCommandPacket + +/*! + * \brief Decode the ECU_ThrottleCommand packet + * + * The throttle command packet sets the throttle position setpoint. The ECU + * will adjust the throttle position based on this command. + * \param _pg_pkt points to the packet being decoded by this function + * \param throttleCommand receives Commanded throttle position in percent + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_ThrottleCommandPacket(const void* _pg_pkt, float* throttleCommand) +{ + int _pg_byteindex = 0; + const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt); + int _pg_numbytes = getECUPacketSize(_pg_pkt); + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_ThrottleCommandPacketID()) + return 0; + + if(_pg_numbytes < getECU_ThrottleCommandMinDataLength()) + return 0; + + // Commanded throttle position in percent + // Range of throttleCommand is 0.0f to 100.0f. + (*throttleCommand) = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/655.35f); + + return 1; + +}// decodeECU_ThrottleCommandPacket + +/*! + * \brief Create the ECU_RPMCommand packet + * + * The RPM command is used to send a target to the RPM governor on the ECU. + * Based on this command, the ECU will use a feedback loop to maintain the + * commanded engine speed by adjusting the throttle servo accordingly. If a + * valid RPM command is received by the ECU, it will automatically enter RPM + * control mode, and adjust the throttle position to match the desired RPM. + * Sending a throttle command will cause the ECU to stop the RPM loop and enter + * open-loop throttle control mode. + * \param _pg_pkt points to the packet which will be created by this function + * \param _pg_user points to the user data that will be encoded in _pg_pkt + */ +void encodeECU_RPMCommandPacketStructure(void* _pg_pkt, const ECU_RPMCommand_t* _pg_user) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + + // RPM command in units of 50 RPM + // Range of rpmCmdHigh is 0 to 255. + uint8ToBytes(_pg_user->rpmCmdHigh, _pg_data, &_pg_byteindex); + + // Low part of RPM command from 0 to 49 + // Range of rpmCmdLow is 0 to 255. + uint8ToBytes(_pg_user->rpmCmdLow, _pg_data, &_pg_byteindex); + + // Reconstruct the RPM command + _pg_data[0] = (uint8_t)((_pg_user->rpmCmd)/50); _pg_data[1] = (uint8_t)((_pg_user->rpmCmd) - _pg_data[0]*50); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_RPMCommandPacketID()); + +}// encodeECU_RPMCommandPacketStructure + +/*! + * \brief Decode the ECU_RPMCommand packet + * + * The RPM command is used to send a target to the RPM governor on the ECU. + * Based on this command, the ECU will use a feedback loop to maintain the + * commanded engine speed by adjusting the throttle servo accordingly. If a + * valid RPM command is received by the ECU, it will automatically enter RPM + * control mode, and adjust the throttle position to match the desired RPM. + * Sending a throttle command will cause the ECU to stop the RPM loop and enter + * open-loop throttle control mode. + * \param _pg_pkt points to the packet being decoded by this function + * \param _pg_user receives the data decoded from the packet + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_RPMCommandPacketStructure(const void* _pg_pkt, ECU_RPMCommand_t* _pg_user) +{ + int _pg_numbytes; + int _pg_byteindex = 0; + const uint8_t* _pg_data; + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_RPMCommandPacketID()) + return 0; + + // Verify the packet size + _pg_numbytes = getECUPacketSize(_pg_pkt); + if(_pg_numbytes < getECU_RPMCommandMinDataLength()) + return 0; + + // The raw data from the packet + _pg_data = getECUPacketDataConst(_pg_pkt); + + // RPM command in units of 50 RPM + // Range of rpmCmdHigh is 0 to 255. + _pg_user->rpmCmdHigh = uint8FromBytes(_pg_data, &_pg_byteindex); + + // Low part of RPM command from 0 to 49 + // Range of rpmCmdLow is 0 to 255. + _pg_user->rpmCmdLow = uint8FromBytes(_pg_data, &_pg_byteindex); + + // Reconstruct the RPM command + _pg_user->rpmCmd = (uint16_t)(_pg_user->rpmCmdHigh*50 + _pg_user->rpmCmdLow); + + return 1; + +}// decodeECU_RPMCommandPacketStructure + +/*! + * \brief Encode a ECU_ecuStatusBits_t into a byte array + * + + * \param _pg_data points to the byte array to add encoded data to + * \param _pg_bytecount points to the starting location in the byte array, and will be incremented by the number of encoded bytes. + * \param _pg_user is the data to encode in the byte array + */ +void encodeECU_ecuStatusBits_t(uint8_t* _pg_data, int* _pg_bytecount, const ECU_ecuStatusBits_t* _pg_user) +{ + int _pg_byteindex = *_pg_bytecount; + + // 1 if driver 8 is on + _pg_data[_pg_byteindex] = (uint8_t)((_pg_user->driverPin8 == true) ? 1 : 0) << 7; + + // 1 if driver 7 is on + _pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->driverPin7 == true) ? 1 : 0) << 6; + + // 1 if driver 2 is on + _pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->driverPin2 == true) ? 1 : 0) << 5; + + // 1 if driver 1 is on + _pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->driverPin1 == true) ? 1 : 0) << 4; + + // 1 if the throttle curve is on. + _pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->throttleCurveOn == true) ? 1 : 0) << 3; + + // 1 if autronic, else auxiliary. + _pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->rs232mode == true) ? 1 : 0) << 2; + + // 1 if any errors are set - refer to [error packet](#PKT_ECU_ERROR_MSG) + _pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->errorIndicator == true) ? 1 : 0) << 1; + + // Global enable based on physical input + _pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->enabled == true) ? 1 : 0); + _pg_byteindex += 1; // close bit field + + *_pg_bytecount = _pg_byteindex; + +}// encodeECU_ecuStatusBits_t + +/*! + * \brief Decode a ECU_ecuStatusBits_t from a byte array + * + + * \param _pg_data points to the byte array to decoded data from + * \param _pg_bytecount points to the starting location in the byte array, and will be incremented by the number of bytes decoded + * \param _pg_user is the data to decode from the byte array + * \return 1 if the data are decoded, else 0. + */ +int decodeECU_ecuStatusBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ECU_ecuStatusBits_t* _pg_user) +{ + int _pg_byteindex = *_pg_bytecount; + + // 1 if driver 8 is on + _pg_user->driverPin8 = ((_pg_data[_pg_byteindex] >> 7)) ? true : false; + + // 1 if driver 7 is on + _pg_user->driverPin7 = (((_pg_data[_pg_byteindex] >> 6) & 0x1)) ? true : false; + + // 1 if driver 2 is on + _pg_user->driverPin2 = (((_pg_data[_pg_byteindex] >> 5) & 0x1)) ? true : false; + + // 1 if driver 1 is on + _pg_user->driverPin1 = (((_pg_data[_pg_byteindex] >> 4) & 0x1)) ? true : false; + + // 1 if the throttle curve is on. + _pg_user->throttleCurveOn = (((_pg_data[_pg_byteindex] >> 3) & 0x1)) ? true : false; + + // 1 if autronic, else auxiliary. + _pg_user->rs232mode = (((_pg_data[_pg_byteindex] >> 2) & 0x1)) ? true : false; + + // 1 if any errors are set - refer to [error packet](#PKT_ECU_ERROR_MSG) + _pg_user->errorIndicator = (((_pg_data[_pg_byteindex] >> 1) & 0x1)) ? true : false; + + // Global enable based on physical input + _pg_user->enabled = (((_pg_data[_pg_byteindex]) & 0x1)) ? true : false; + _pg_byteindex += 1; // close bit field + + *_pg_bytecount = _pg_byteindex; + + return 1; + +}// decodeECU_ecuStatusBits_t + +/*! + * \brief Create the ECU_TelemetryFast packet + * + * Fast telemetry contains high priority telemetry data and is transmitted at a + * user configurable period between 50ms (20Hz) and 10s. By default, the fast + * telemetry message is transmitted at 10Hz (every 100ms) + * \param _pg_pkt points to the packet which will be created by this function + * \param _pg_user points to the user data that will be encoded in _pg_pkt + */ +void encodeECU_TelemetryFastPacketStructure(void* _pg_pkt, const ECU_TelemetryFast_t* _pg_user) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // Throttle signal (0 to 100%) + // Range of throttle is 0.0f to 100.0f. + float32ScaledTo1UnsignedBytes(_pg_user->throttle, _pg_data, &_pg_byteindex, 0.0f, 2.55f); + + // Engine speed in revolutions per minute + // Range of rpm is 0 to 65535. + uint16ToBeBytes(_pg_user->rpm, _pg_data, &_pg_byteindex); + + // Fuel used in grams + // Range of fuelUsed is 0 to 4294967295. + uint32ToBeBytes(_pg_user->fuelUsed, _pg_data, &_pg_byteindex); + + encodeECU_ecuStatusBits_t(_pg_data, &_pg_byteindex, &_pg_user->ecuStatusBits); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_TelemetryFastPacketID()); + +}// encodeECU_TelemetryFastPacketStructure + +/*! + * \brief Decode the ECU_TelemetryFast packet + * + * Fast telemetry contains high priority telemetry data and is transmitted at a + * user configurable period between 50ms (20Hz) and 10s. By default, the fast + * telemetry message is transmitted at 10Hz (every 100ms) + * \param _pg_pkt points to the packet being decoded by this function + * \param _pg_user receives the data decoded from the packet + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_TelemetryFastPacketStructure(const void* _pg_pkt, ECU_TelemetryFast_t* _pg_user) +{ + int _pg_numbytes; + int _pg_byteindex = 0; + const uint8_t* _pg_data; + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_TelemetryFastPacketID()) + return 0; + + // Verify the packet size + _pg_numbytes = getECUPacketSize(_pg_pkt); + if(_pg_numbytes < getECU_TelemetryFastMinDataLength()) + return 0; + + // The raw data from the packet + _pg_data = getECUPacketDataConst(_pg_pkt); + + // Throttle signal (0 to 100%) + // Range of throttle is 0.0f to 100.0f. + _pg_user->throttle = float32ScaledFrom1UnsignedBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/2.55f); + + // Engine speed in revolutions per minute + // Range of rpm is 0 to 65535. + _pg_user->rpm = uint16FromBeBytes(_pg_data, &_pg_byteindex); + + // Fuel used in grams + // Range of fuelUsed is 0 to 4294967295. + _pg_user->fuelUsed = uint32FromBeBytes(_pg_data, &_pg_byteindex); + + if(decodeECU_ecuStatusBits_t(_pg_data, &_pg_byteindex, &_pg_user->ecuStatusBits) == 0) + return 0; + + return 1; + +}// decodeECU_TelemetryFastPacketStructure + +/*! + * \brief Create the ECU_TelemetryFast packet + * + * Fast telemetry contains high priority telemetry data and is transmitted at a + * user configurable period between 50ms (20Hz) and 10s. By default, the fast + * telemetry message is transmitted at 10Hz (every 100ms) + * \param _pg_pkt points to the packet which will be created by this function + * \param throttle is Throttle signal (0 to 100%) + * \param rpm is Engine speed in revolutions per minute + * \param fuelUsed is Fuel used in grams + * \param ecuStatusBits is + */ +void encodeECU_TelemetryFastPacket(void* _pg_pkt, float throttle, uint16_t rpm, uint32_t fuelUsed, const ECU_ecuStatusBits_t* ecuStatusBits) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // Throttle signal (0 to 100%) + // Range of throttle is 0.0f to 100.0f. + float32ScaledTo1UnsignedBytes(throttle, _pg_data, &_pg_byteindex, 0.0f, 2.55f); + + // Engine speed in revolutions per minute + // Range of rpm is 0 to 65535. + uint16ToBeBytes(rpm, _pg_data, &_pg_byteindex); + + // Fuel used in grams + // Range of fuelUsed is 0 to 4294967295. + uint32ToBeBytes(fuelUsed, _pg_data, &_pg_byteindex); + + encodeECU_ecuStatusBits_t(_pg_data, &_pg_byteindex, ecuStatusBits); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_TelemetryFastPacketID()); + +}// encodeECU_TelemetryFastPacket + +/*! + * \brief Decode the ECU_TelemetryFast packet + * + * Fast telemetry contains high priority telemetry data and is transmitted at a + * user configurable period between 50ms (20Hz) and 10s. By default, the fast + * telemetry message is transmitted at 10Hz (every 100ms) + * \param _pg_pkt points to the packet being decoded by this function + * \param throttle receives Throttle signal (0 to 100%) + * \param rpm receives Engine speed in revolutions per minute + * \param fuelUsed receives Fuel used in grams + * \param ecuStatusBits receives + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_TelemetryFastPacket(const void* _pg_pkt, float* throttle, uint16_t* rpm, uint32_t* fuelUsed, ECU_ecuStatusBits_t* ecuStatusBits) +{ + int _pg_byteindex = 0; + const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt); + int _pg_numbytes = getECUPacketSize(_pg_pkt); + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_TelemetryFastPacketID()) + return 0; + + if(_pg_numbytes < getECU_TelemetryFastMinDataLength()) + return 0; + + // Throttle signal (0 to 100%) + // Range of throttle is 0.0f to 100.0f. + (*throttle) = float32ScaledFrom1UnsignedBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/2.55f); + + // Engine speed in revolutions per minute + // Range of rpm is 0 to 65535. + (*rpm) = uint16FromBeBytes(_pg_data, &_pg_byteindex); + + // Fuel used in grams + // Range of fuelUsed is 0 to 4294967295. + (*fuelUsed) = uint32FromBeBytes(_pg_data, &_pg_byteindex); + + if(decodeECU_ecuStatusBits_t(_pg_data, &_pg_byteindex, ecuStatusBits) == 0) + return 0; + + return 1; + +}// decodeECU_TelemetryFastPacket + +/*! + * \brief Create the ECU_TelemetrySlow0 packet + * + * This is the first of three slower telemetry packets which are transmitted by + * the ECU at a user customizable period (between 0.5s and 10.0s). These three + * packets contain data that is not likely to change as quickly as the data in + * the fast telemetry packet. By default, the slow telemetry messages are + * transmitted at 1Hz (period of 1.0s). + * \param _pg_pkt points to the packet which will be created by this function + * \param _pg_user points to the user data that will be encoded in _pg_pkt + */ +void encodeECU_TelemetrySlow0PacketStructure(void* _pg_pkt, const ECU_TelemetrySlow0_t* _pg_user) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + unsigned int _pg_tempbitfield = 0; + + + + // RPM command in units of 50 RPM + uint8ToBytes((uint8_t)(0), _pg_data, &_pg_byteindex); + + // Source of the throttle information + _pg_data[_pg_byteindex] = (uint8_t)_pg_user->throttleSrc << 4; + + // Throttle pulse width in microseconds + // Range of throttlePulse is 0 to 4095. + _pg_tempbitfield = (unsigned int)limitMax(_pg_user->throttlePulse, 4095); + _pg_data[_pg_byteindex + 1] = (uint8_t)_pg_tempbitfield; + + _pg_tempbitfield >>= 8; + _pg_data[_pg_byteindex] |= (uint8_t)_pg_tempbitfield; + _pg_byteindex += 2; // close bit field + + + // Cylinder head temperature in Celsius + // Range of cht is -10.0f to 245.0f. + float32ScaledTo1UnsignedBytes(_pg_user->cht, _pg_data, &_pg_byteindex, -10.0f, 1.0f); + + // Low part of RPM command from 0 to 49 + uint8ToBytes((uint8_t)(0), _pg_data, &_pg_byteindex); + + // Barometric pressure in kilo-Pascals + // Range of baro is 0.0f to 131.07f. + float32ScaledTo2UnsignedBeBytes(_pg_user->baro, _pg_data, &_pg_byteindex, 0.0f, 500.0f); + + // Percentage ratio of manifold pressure to barometric pressure + uint8ToBytes((uint8_t)(0), _pg_data, &_pg_byteindex); + + // Reconstruct the RPM command + _pg_data[0] = (uint8_t)(_pg_user->rpmCmd/50); _pg_data[4] = (uint8_t)(_pg_user->rpmCmd - _pg_data[0]*50); + + // Reconstruct the manifold pressure + _pg_data[7] = (uint8_t)(0.5f + 100.0f*_pg_user->map/_pg_user->baro); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_TelemetrySlow0PacketID()); + +}// encodeECU_TelemetrySlow0PacketStructure + +/*! + * \brief Decode the ECU_TelemetrySlow0 packet + * + * This is the first of three slower telemetry packets which are transmitted by + * the ECU at a user customizable period (between 0.5s and 10.0s). These three + * packets contain data that is not likely to change as quickly as the data in + * the fast telemetry packet. By default, the slow telemetry messages are + * transmitted at 1Hz (period of 1.0s). + * \param _pg_pkt points to the packet being decoded by this function + * \param _pg_user receives the data decoded from the packet + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_TelemetrySlow0PacketStructure(const void* _pg_pkt, ECU_TelemetrySlow0_t* _pg_user) +{ + int _pg_numbytes; + int _pg_byteindex = 0; + const uint8_t* _pg_data; + unsigned int _pg_tempbitfield = 0; + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_TelemetrySlow0PacketID()) + return 0; + + // Verify the packet size + _pg_numbytes = getECUPacketSize(_pg_pkt); + if(_pg_numbytes < getECU_TelemetrySlow0MinDataLength()) + return 0; + + // The raw data from the packet + _pg_data = getECUPacketDataConst(_pg_pkt); + + // RPM command in units of 50 RPM + _pg_byteindex += 1; + + // Source of the throttle information + _pg_user->throttleSrc = (ECUThrottleSource)(_pg_data[_pg_byteindex] >> 4); + + // Throttle pulse width in microseconds + // Range of throttlePulse is 0 to 4095. + _pg_tempbitfield = (_pg_data[_pg_byteindex] & 0xF); + + _pg_tempbitfield <<= 8; + _pg_tempbitfield |= _pg_data[_pg_byteindex + 1]; + + _pg_user->throttlePulse = _pg_tempbitfield; + _pg_byteindex += 2; // close bit field + + // Cylinder head temperature in Celsius + // Range of cht is -10.0f to 245.0f. + _pg_user->cht = float32ScaledFrom1UnsignedBytes(_pg_data, &_pg_byteindex, -10.0f, 1.0f/1.0f); + + // Low part of RPM command from 0 to 49 + _pg_byteindex += 1; + + // Barometric pressure in kilo-Pascals + // Range of baro is 0.0f to 131.07f. + _pg_user->baro = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/500.0f); + + // Percentage ratio of manifold pressure to barometric pressure + _pg_byteindex += 1; + + // Reconstruct the RPM command + _pg_user->rpmCmd = (uint16_t)(_pg_data[0]*50 + _pg_data[4]); + + // Reconstruct the manifold pressure + _pg_user->map = _pg_data[7]*0.01f*_pg_user->baro; + + return 1; + +}// decodeECU_TelemetrySlow0PacketStructure + +/*! + * \brief Create the ECU_TelemetrySlow1 packet + * + * The second of three slow telemetry packets + * \param _pg_pkt points to the packet which will be created by this function + * \param _pg_user points to the user data that will be encoded in _pg_pkt + */ +void encodeECU_TelemetrySlow1PacketStructure(void* _pg_pkt, const ECU_TelemetrySlow1_t* _pg_user) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // Inlet air temperature in Celsius + // Range of mat is -127.0f to 127.0f. + float32ScaledTo1SignedBytes(_pg_user->mat, _pg_data, &_pg_byteindex, 1.0f); + + // Fuel pressure in kilo-Pascals + // Range of fuelPressure is 0.0f to 1310.7f. + float32ScaledTo2UnsignedBeBytes(_pg_user->fuelPressure, _pg_data, &_pg_byteindex, 0.0f, 50.0f); + + // Engine run time in seconds. + // Range of hobbs is 0 to 16777215. + uint24ToBeBytes((uint32_t)(limitMax(_pg_user->hobbs, 16777215)), _pg_data, &_pg_byteindex); + + // Input voltage in Volts + // Range of voltage is 0.0f to 25.5f. + float32ScaledTo1UnsignedBytes(_pg_user->voltage, _pg_data, &_pg_byteindex, 0.0f, 10.0f); + + _pg_data[_pg_byteindex] = 0; + + // Operational mode of the governor + _pg_data[_pg_byteindex] |= (uint8_t)_pg_user->governorMode; + _pg_byteindex += 1; // close bit field + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_TelemetrySlow1PacketID()); + +}// encodeECU_TelemetrySlow1PacketStructure + +/*! + * \brief Decode the ECU_TelemetrySlow1 packet + * + * The second of three slow telemetry packets + * \param _pg_pkt points to the packet being decoded by this function + * \param _pg_user receives the data decoded from the packet + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_TelemetrySlow1PacketStructure(const void* _pg_pkt, ECU_TelemetrySlow1_t* _pg_user) +{ + int _pg_numbytes; + int _pg_byteindex = 0; + const uint8_t* _pg_data; + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_TelemetrySlow1PacketID()) + return 0; + + // Verify the packet size + _pg_numbytes = getECUPacketSize(_pg_pkt); + if(_pg_numbytes < getECU_TelemetrySlow1MinDataLength()) + return 0; + + // The raw data from the packet + _pg_data = getECUPacketDataConst(_pg_pkt); + + // Inlet air temperature in Celsius + // Range of mat is -127.0f to 127.0f. + _pg_user->mat = float32ScaledFrom1SignedBytes(_pg_data, &_pg_byteindex, 1.0f/1.0f); + + // Fuel pressure in kilo-Pascals + // Range of fuelPressure is 0.0f to 1310.7f. + _pg_user->fuelPressure = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/50.0f); + + // Engine run time in seconds. + // Range of hobbs is 0 to 16777215. + _pg_user->hobbs = (uint32_t)uint24FromBeBytes(_pg_data, &_pg_byteindex); + + // Input voltage in Volts + // Range of voltage is 0.0f to 25.5f. + _pg_user->voltage = float32ScaledFrom1UnsignedBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/10.0f); + + // Operational mode of the governor + _pg_user->governorMode = (ECUGovernorMode)((_pg_data[_pg_byteindex]) & 0x7); + _pg_byteindex += 1; // close bit field + + return 1; + +}// decodeECU_TelemetrySlow1PacketStructure + +/*! + * \brief Create the ECU_TelemetrySlow2 packet + * + * The third of three slow telemetry packets + * \param _pg_pkt points to the packet which will be created by this function + * \param _pg_user points to the user data that will be encoded in _pg_pkt + */ +void encodeECU_TelemetrySlow2PacketStructure(void* _pg_pkt, const ECU_TelemetrySlow2_t* _pg_user) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // CPU load in percent + // Range of cpuLoad is 0.0f to 255.0f. + float32ScaledTo1UnsignedBytes(_pg_user->cpuLoad, _pg_data, &_pg_byteindex, 0.0f, 1.0f); + + // Charge temperature in Celsius + // Range of chargeTemp is -128.0f to 254.5f. + float32ScaledTo1UnsignedBytes(_pg_user->chargeTemp, _pg_data, &_pg_byteindex, -128.0f, 0.666666667f); + + // Injector duty cycle in percent + // Range of injectorDuty is 0.0f to 6553.5f. + float32ScaledTo2UnsignedBeBytes(_pg_user->injectorDuty, _pg_data, &_pg_byteindex, 0.0f, 10.0f); + + // First ignition advance angle in degrees + // Range of ignAngle1 is 0.0f to 127.5f. + float32ScaledTo1UnsignedBytes(_pg_user->ignAngle1, _pg_data, &_pg_byteindex, 0.0f, 2.0f); + + // Second ignition advance angle in degrees + // Range of ignAngle2 is 0.0f to 127.5f. + float32ScaledTo1UnsignedBytes(_pg_user->ignAngle2, _pg_data, &_pg_byteindex, 0.0f, 2.0f); + + // Fuel flow rate in grams per minute + // Range of flowRate is 0.0f to 1092.25f. + float32ScaledTo2UnsignedBeBytes(_pg_user->flowRate, _pg_data, &_pg_byteindex, 0.0f, 60.0f); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_TelemetrySlow2PacketID()); + +}// encodeECU_TelemetrySlow2PacketStructure + +/*! + * \brief Decode the ECU_TelemetrySlow2 packet + * + * The third of three slow telemetry packets + * \param _pg_pkt points to the packet being decoded by this function + * \param _pg_user receives the data decoded from the packet + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_TelemetrySlow2PacketStructure(const void* _pg_pkt, ECU_TelemetrySlow2_t* _pg_user) +{ + int _pg_numbytes; + int _pg_byteindex = 0; + const uint8_t* _pg_data; + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_TelemetrySlow2PacketID()) + return 0; + + // Verify the packet size + _pg_numbytes = getECUPacketSize(_pg_pkt); + if(_pg_numbytes < getECU_TelemetrySlow2MinDataLength()) + return 0; + + // The raw data from the packet + _pg_data = getECUPacketDataConst(_pg_pkt); + + // CPU load in percent + // Range of cpuLoad is 0.0f to 255.0f. + _pg_user->cpuLoad = float32ScaledFrom1UnsignedBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/1.0f); + + // Charge temperature in Celsius + // Range of chargeTemp is -128.0f to 254.5f. + _pg_user->chargeTemp = float32ScaledFrom1UnsignedBytes(_pg_data, &_pg_byteindex, -128.0f, 1.0f/0.666666667f); + + // Injector duty cycle in percent + // Range of injectorDuty is 0.0f to 6553.5f. + _pg_user->injectorDuty = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/10.0f); + + // First ignition advance angle in degrees + // Range of ignAngle1 is 0.0f to 127.5f. + _pg_user->ignAngle1 = float32ScaledFrom1UnsignedBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/2.0f); + + // Second ignition advance angle in degrees + // Range of ignAngle2 is 0.0f to 127.5f. + _pg_user->ignAngle2 = float32ScaledFrom1UnsignedBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/2.0f); + + // Fuel flow rate in grams per minute + // Range of flowRate is 0.0f to 1092.25f. + _pg_user->flowRate = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/60.0f); + + return 1; + +}// decodeECU_TelemetrySlow2PacketStructure + +/*! + * \brief Create the ECU_HardwareConfig packet + * + * The hardware config packet contains the ECU serial number and various ECU + * configuration data. Send a zero length packet to request this data. + * \param _pg_pkt points to the packet which will be created by this function + * \param _pg_user points to the user data that will be encoded in _pg_pkt + */ +void encodeECU_HardwareConfigPacketStructure(void* _pg_pkt, const ECU_HardwareConfig_t* _pg_user) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // ECU serial number + // Range of serialNumber is 0 to 65535. + uint16ToBeBytes(_pg_user->serialNumber, _pg_data, &_pg_byteindex); + + // Fuel used divisior. If the divisor is greater than 100 then it is interpreted as units of 0.01 (for a higher resolution fuel calibration) + // Range of fuelDivisor is 0 to 65535. + uint16ToBeBytes(_pg_user->fuelDivisor, _pg_data, &_pg_byteindex); + + _pg_data[_pg_byteindex] = 0; + + // Autronic relay state. This is a volatile status which will reset to AUT_RELAY_OFF on ECU power cycle. + _pg_data[_pg_byteindex] |= (uint8_t)_pg_user->relayState << 1; + + // Set if the fuel used value is reset each on each ECU power cycle + _pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->resetFuelUsedOnStart == true) ? 1 : 0); + _pg_byteindex += 1; // close bit field + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_HardwareConfigPacketID()); + +}// encodeECU_HardwareConfigPacketStructure + +/*! + * \brief Decode the ECU_HardwareConfig packet + * + * The hardware config packet contains the ECU serial number and various ECU + * configuration data. Send a zero length packet to request this data. + * \param _pg_pkt points to the packet being decoded by this function + * \param _pg_user receives the data decoded from the packet + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_HardwareConfigPacketStructure(const void* _pg_pkt, ECU_HardwareConfig_t* _pg_user) +{ + int _pg_numbytes; + int _pg_byteindex = 0; + const uint8_t* _pg_data; + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_HardwareConfigPacketID()) + return 0; + + // Verify the packet size + _pg_numbytes = getECUPacketSize(_pg_pkt); + if(_pg_numbytes < getECU_HardwareConfigMinDataLength()) + return 0; + + // The raw data from the packet + _pg_data = getECUPacketDataConst(_pg_pkt); + + // ECU serial number + // Range of serialNumber is 0 to 65535. + _pg_user->serialNumber = uint16FromBeBytes(_pg_data, &_pg_byteindex); + + // Fuel used divisior. If the divisor is greater than 100 then it is interpreted as units of 0.01 (for a higher resolution fuel calibration) + // Range of fuelDivisor is 0 to 65535. + _pg_user->fuelDivisor = uint16FromBeBytes(_pg_data, &_pg_byteindex); + + // Autronic relay state. This is a volatile status which will reset to AUT_RELAY_OFF on ECU power cycle. + _pg_user->relayState = (ECUAutronicRelayState)((_pg_data[_pg_byteindex] >> 1) & 0x3); + + // Set if the fuel used value is reset each on each ECU power cycle + _pg_user->resetFuelUsedOnStart = (((_pg_data[_pg_byteindex]) & 0x1)) ? true : false; + _pg_byteindex += 1; // close bit field + + return 1; + +}// decodeECU_HardwareConfigPacketStructure + +/*! + * \brief Create the ECU_Version packet + * + * The software version packet contains the auxiliary processor firmware + * version information. Send a zero length packet to request this data. + * \param _pg_pkt points to the packet which will be created by this function + * \param _pg_user points to the user data that will be encoded in _pg_pkt + */ +void encodeECU_VersionPacketStructure(void* _pg_pkt, const ECU_Version_t* _pg_user) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // 1 = Release version, 0 = Testing version + _pg_data[_pg_byteindex] = (uint8_t)((_pg_user->release == true) ? 1 : 0) << 7; + + // Reserved for future use + + // Major version number + // Range of versionMajor is 0 to 63. + _pg_data[_pg_byteindex] |= (uint8_t)_pg_user->versionMajor; + _pg_byteindex += 1; // close bit field + + + // Minor version number + // Range of versionMinor is 0 to 255. + uint8ToBytes(_pg_user->versionMinor, _pg_data, &_pg_byteindex); + + // Revision number + // Range of versionRev is 0 to 15. + _pg_data[_pg_byteindex] = (uint8_t)limitMax(_pg_user->versionRev, 15) << 4; + + // The release month from 1 (January) to 12 (December) + // Range of month is 0 to 15. + _pg_data[_pg_byteindex] |= (uint8_t)limitMax(_pg_user->month, 15); + _pg_byteindex += 1; // close bit field + + + // The release day of month from 1 to 31 + // Range of day is 0 to 255. + uint8ToBytes(_pg_user->day, _pg_data, &_pg_byteindex); + + // The release year + // Range of year is 0 to 65535. + uint16ToBeBytes(_pg_user->year, _pg_data, &_pg_byteindex); + + // Firmware checksum + // Range of checksum is 0 to 65535. + uint16ToBeBytes(_pg_user->checksum, _pg_data, &_pg_byteindex); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_VersionPacketID()); + +}// encodeECU_VersionPacketStructure + +/*! + * \brief Decode the ECU_Version packet + * + * The software version packet contains the auxiliary processor firmware + * version information. Send a zero length packet to request this data. + * \param _pg_pkt points to the packet being decoded by this function + * \param _pg_user receives the data decoded from the packet + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_VersionPacketStructure(const void* _pg_pkt, ECU_Version_t* _pg_user) +{ + int _pg_numbytes; + int _pg_byteindex = 0; + const uint8_t* _pg_data; + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_VersionPacketID()) + return 0; + + // Verify the packet size + _pg_numbytes = getECUPacketSize(_pg_pkt); + if(_pg_numbytes < getECU_VersionMinDataLength()) + return 0; + + // The raw data from the packet + _pg_data = getECUPacketDataConst(_pg_pkt); + + // 1 = Release version, 0 = Testing version + _pg_user->release = ((_pg_data[_pg_byteindex] >> 7)) ? true : false; + + // Reserved for future use + + // Major version number + // Range of versionMajor is 0 to 63. + _pg_user->versionMajor = ((_pg_data[_pg_byteindex]) & 0x3F); + _pg_byteindex += 1; // close bit field + + // Minor version number + // Range of versionMinor is 0 to 255. + _pg_user->versionMinor = uint8FromBytes(_pg_data, &_pg_byteindex); + + // Revision number + // Range of versionRev is 0 to 15. + _pg_user->versionRev = (_pg_data[_pg_byteindex] >> 4); + + // The release month from 1 (January) to 12 (December) + // Range of month is 0 to 15. + _pg_user->month = ((_pg_data[_pg_byteindex]) & 0xF); + _pg_byteindex += 1; // close bit field + + // The release day of month from 1 to 31 + // Range of day is 0 to 255. + _pg_user->day = uint8FromBytes(_pg_data, &_pg_byteindex); + + // The release year + // Range of year is 0 to 65535. + _pg_user->year = uint16FromBeBytes(_pg_data, &_pg_byteindex); + + // Firmware checksum + // Range of checksum is 0 to 65535. + _pg_user->checksum = uint16FromBeBytes(_pg_data, &_pg_byteindex); + + return 1; + +}// decodeECU_VersionPacketStructure + +/*! + * \brief Create the ECU_Errors packet + * + * The errors packet contains error status information for the ECU. If any + * error bits are set, then the global error bit in the [fast + * telemetry](#PKT_ECU_TELEMETRY_FAST) packet will also be set. Send a zero + * length packet to request this data. + * \param _pg_pkt points to the packet which will be created by this function + * \param _pg_user points to the user data that will be encoded in _pg_pkt + */ +void encodeECU_ErrorsPacketStructure(void* _pg_pkt, const ECU_Errors_t* _pg_user) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // Error bits for the Autronic processor + encodeECU_AutronicErrorBits_t(_pg_data, &_pg_byteindex, &_pg_user->autronicErrors); + + // Error bits for the auxiliary processor + encodeECU_AuxiliaryErrorBits_t(_pg_data, &_pg_byteindex, &_pg_user->auxiliaryErrors); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_ErrorsPacketID()); + +}// encodeECU_ErrorsPacketStructure + +/*! + * \brief Decode the ECU_Errors packet + * + * The errors packet contains error status information for the ECU. If any + * error bits are set, then the global error bit in the [fast + * telemetry](#PKT_ECU_TELEMETRY_FAST) packet will also be set. Send a zero + * length packet to request this data. + * \param _pg_pkt points to the packet being decoded by this function + * \param _pg_user receives the data decoded from the packet + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_ErrorsPacketStructure(const void* _pg_pkt, ECU_Errors_t* _pg_user) +{ + int _pg_numbytes; + int _pg_byteindex = 0; + const uint8_t* _pg_data; + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_ErrorsPacketID()) + return 0; + + // Verify the packet size + _pg_numbytes = getECUPacketSize(_pg_pkt); + if(_pg_numbytes < getECU_ErrorsMinDataLength()) + return 0; + + // The raw data from the packet + _pg_data = getECUPacketDataConst(_pg_pkt); + + // Error bits for the Autronic processor + if(decodeECU_AutronicErrorBits_t(_pg_data, &_pg_byteindex, &_pg_user->autronicErrors) == 0) + return 0; + + // Error bits for the auxiliary processor + if(decodeECU_AuxiliaryErrorBits_t(_pg_data, &_pg_byteindex, &_pg_user->auxiliaryErrors) == 0) + return 0; + + return 1; + +}// decodeECU_ErrorsPacketStructure + +/*! + * \brief Create the ECU_PowerCycles packet + * + * The power cycles packet contains information on the reset condition of the + * ECU. Send a zero length packet to request this data. + * \param _pg_pkt points to the packet which will be created by this function + * \param _pg_user points to the user data that will be encoded in _pg_pkt + */ +void encodeECU_PowerCyclesPacketStructure(void* _pg_pkt, const ECU_PowerCycles_t* _pg_user) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // Number of power cycles + // Range of powerCycles is 0 to 65535. + uint16ToBeBytes(_pg_user->powerCycles, _pg_data, &_pg_byteindex); + + // Range of reserved is 0 to 255. + uint8ToBytes(_pg_user->reserved, _pg_data, &_pg_byteindex); + + // Auxiliary processor reset code + // Range of resetCode is 0 to 255. + uint8ToBytes(_pg_user->resetCode, _pg_data, &_pg_byteindex); + + // Milliseconds since system reset + // Range of systemTime is 0 to 4294967295. + uint32ToBeBytes(_pg_user->systemTime, _pg_data, &_pg_byteindex); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_PowerCyclesPacketID()); + +}// encodeECU_PowerCyclesPacketStructure + +/*! + * \brief Decode the ECU_PowerCycles packet + * + * The power cycles packet contains information on the reset condition of the + * ECU. Send a zero length packet to request this data. + * \param _pg_pkt points to the packet being decoded by this function + * \param _pg_user receives the data decoded from the packet + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_PowerCyclesPacketStructure(const void* _pg_pkt, ECU_PowerCycles_t* _pg_user) +{ + int _pg_numbytes; + int _pg_byteindex = 0; + const uint8_t* _pg_data; + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_PowerCyclesPacketID()) + return 0; + + // Verify the packet size + _pg_numbytes = getECUPacketSize(_pg_pkt); + if(_pg_numbytes < getECU_PowerCyclesMinDataLength()) + return 0; + + // The raw data from the packet + _pg_data = getECUPacketDataConst(_pg_pkt); + + // Number of power cycles + // Range of powerCycles is 0 to 65535. + _pg_user->powerCycles = uint16FromBeBytes(_pg_data, &_pg_byteindex); + + // Range of reserved is 0 to 255. + _pg_user->reserved = uint8FromBytes(_pg_data, &_pg_byteindex); + + // Auxiliary processor reset code + // Range of resetCode is 0 to 255. + _pg_user->resetCode = uint8FromBytes(_pg_data, &_pg_byteindex); + + // Milliseconds since system reset + // Range of systemTime is 0 to 4294967295. + _pg_user->systemTime = uint32FromBeBytes(_pg_data, &_pg_byteindex); + + return 1; + +}// decodeECU_PowerCyclesPacketStructure + +/*! + * \brief Create the ECU_PumpDebug packet + * + * The fuel pump debug packet contains information on the pump control system. + * Send a zero length packet to request this data. + * \param _pg_pkt points to the packet which will be created by this function + * \param _pg_user points to the user data that will be encoded in _pg_pkt + */ +void encodeECU_PumpDebugPacketStructure(void* _pg_pkt, const ECU_PumpDebug_t* _pg_user) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // Proportional term of the pump feedback control in percent + // Range of pTerm is -3276.7f to 3276.7f. + float32ScaledTo2SignedBeBytes(_pg_user->pTerm, _pg_data, &_pg_byteindex, 10.0f); + + // Integral term of the pump feedback control in percent + // Range of iTerm is -3276.7f to 3276.7f. + float32ScaledTo2SignedBeBytes(_pg_user->iTerm, _pg_data, &_pg_byteindex, 10.0f); + + // Pump duty cycle in percent + // Range of dutyCycle is 0.0f to 6553.5f. + float32ScaledTo2UnsignedBeBytes(_pg_user->dutyCycle, _pg_data, &_pg_byteindex, 0.0f, 10.0f); + + // Fuel pressure in kilo-Pascals + // Range of fuelPressure is 0.0f to 1310.7f. + float32ScaledTo2UnsignedBeBytes(_pg_user->fuelPressure, _pg_data, &_pg_byteindex, 0.0f, 50.0f); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_PumpDebugPacketID()); + +}// encodeECU_PumpDebugPacketStructure + +/*! + * \brief Decode the ECU_PumpDebug packet + * + * The fuel pump debug packet contains information on the pump control system. + * Send a zero length packet to request this data. + * \param _pg_pkt points to the packet being decoded by this function + * \param _pg_user receives the data decoded from the packet + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_PumpDebugPacketStructure(const void* _pg_pkt, ECU_PumpDebug_t* _pg_user) +{ + int _pg_numbytes; + int _pg_byteindex = 0; + const uint8_t* _pg_data; + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_PumpDebugPacketID()) + return 0; + + // Verify the packet size + _pg_numbytes = getECUPacketSize(_pg_pkt); + if(_pg_numbytes < getECU_PumpDebugMinDataLength()) + return 0; + + // The raw data from the packet + _pg_data = getECUPacketDataConst(_pg_pkt); + + // Proportional term of the pump feedback control in percent + // Range of pTerm is -3276.7f to 3276.7f. + _pg_user->pTerm = float32ScaledFrom2SignedBeBytes(_pg_data, &_pg_byteindex, 1.0f/10.0f); + + // Integral term of the pump feedback control in percent + // Range of iTerm is -3276.7f to 3276.7f. + _pg_user->iTerm = float32ScaledFrom2SignedBeBytes(_pg_data, &_pg_byteindex, 1.0f/10.0f); + + // Pump duty cycle in percent + // Range of dutyCycle is 0.0f to 6553.5f. + _pg_user->dutyCycle = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/10.0f); + + // Fuel pressure in kilo-Pascals + // Range of fuelPressure is 0.0f to 1310.7f. + _pg_user->fuelPressure = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/50.0f); + + return 1; + +}// decodeECU_PumpDebugPacketStructure + +/*! + * \brief Create the ECU_TotalEngineTime packet + * + * While the engine time contained in the ECU telemetry packet can be reset by + * the user, the ECU also stores the total engine time, which cannot be reset + * by the user. Send a zero length packet to request this data. + * \param _pg_pkt points to the packet which will be created by this function + * \param hobbs is Total engine run time in seconds + */ +void encodeECU_TotalEngineTimePacket(void* _pg_pkt, uint32_t hobbs) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // Total engine run time in seconds + // Range of hobbs is 0 to 16777215. + uint24ToBeBytes((uint32_t)(limitMax(hobbs, 16777215)), _pg_data, &_pg_byteindex); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_TotalEngineTimePacketID()); + +}// encodeECU_TotalEngineTimePacket + +/*! + * \brief Decode the ECU_TotalEngineTime packet + * + * While the engine time contained in the ECU telemetry packet can be reset by + * the user, the ECU also stores the total engine time, which cannot be reset + * by the user. Send a zero length packet to request this data. + * \param _pg_pkt points to the packet being decoded by this function + * \param hobbs receives Total engine run time in seconds + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_TotalEngineTimePacket(const void* _pg_pkt, uint32_t* hobbs) +{ + int _pg_byteindex = 0; + const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt); + int _pg_numbytes = getECUPacketSize(_pg_pkt); + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_TotalEngineTimePacketID()) + return 0; + + if(_pg_numbytes < getECU_TotalEngineTimeMinDataLength()) + return 0; + + // Total engine run time in seconds + // Range of hobbs is 0 to 16777215. + (*hobbs) = (uint32_t)uint24FromBeBytes(_pg_data, &_pg_byteindex); + + return 1; + +}// decodeECU_TotalEngineTimePacket + +/*! + * \brief Create the ECU_eepromSettings packet + * + * The eeprom settings packet contains information on the non-volatile ECU + * settings stored in eeprom. In particular, it provides a checksum of the + * settings data for easy comparison of settings between different ECUs. Send a + * zero length packet to request this data. + * \param _pg_pkt points to the packet which will be created by this function + * \param _pg_user points to the user data that will be encoded in _pg_pkt + */ +void encodeECU_eepromSettingsPacketStructure(void* _pg_pkt, const ECU_eepromSettings_t* _pg_user) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // Version of the EEPROM data + // Range of eepromVersion is 0 to 255. + uint8ToBytes(_pg_user->eepromVersion, _pg_data, &_pg_byteindex); + + // Number of bytes of the EEPROM data + // Range of eepromSize is 0 to 65535. + uint16ToBeBytes(_pg_user->eepromSize, _pg_data, &_pg_byteindex); + + // Fletcher's checksum of the EEPROM data + // Range of eepromChecksum is 0 to 65535. + uint16ToBeBytes(_pg_user->eepromChecksum, _pg_data, &_pg_byteindex); + + // ECU compilation options + encodeECU_CompileOptions_t(_pg_data, &_pg_byteindex, &_pg_user->compileOptions); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_eepromSettingsPacketID()); + +}// encodeECU_eepromSettingsPacketStructure + +/*! + * \brief Decode the ECU_eepromSettings packet + * + * The eeprom settings packet contains information on the non-volatile ECU + * settings stored in eeprom. In particular, it provides a checksum of the + * settings data for easy comparison of settings between different ECUs. Send a + * zero length packet to request this data. + * \param _pg_pkt points to the packet being decoded by this function + * \param _pg_user receives the data decoded from the packet + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_eepromSettingsPacketStructure(const void* _pg_pkt, ECU_eepromSettings_t* _pg_user) +{ + int _pg_numbytes; + int _pg_byteindex = 0; + const uint8_t* _pg_data; + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_eepromSettingsPacketID()) + return 0; + + // Verify the packet size + _pg_numbytes = getECUPacketSize(_pg_pkt); + if(_pg_numbytes < getECU_eepromSettingsMinDataLength()) + return 0; + + // The raw data from the packet + _pg_data = getECUPacketDataConst(_pg_pkt); + + // Version of the EEPROM data + // Range of eepromVersion is 0 to 255. + _pg_user->eepromVersion = uint8FromBytes(_pg_data, &_pg_byteindex); + + // Number of bytes of the EEPROM data + // Range of eepromSize is 0 to 65535. + _pg_user->eepromSize = uint16FromBeBytes(_pg_data, &_pg_byteindex); + + // Fletcher's checksum of the EEPROM data + // Range of eepromChecksum is 0 to 65535. + _pg_user->eepromChecksum = uint16FromBeBytes(_pg_data, &_pg_byteindex); + + // ECU compilation options + if(decodeECU_CompileOptions_t(_pg_data, &_pg_byteindex, &_pg_user->compileOptions) == 0) + return 0; + + return 1; + +}// decodeECU_eepromSettingsPacketStructure + +/*! + * \brief Create the ECU_eepromSettings packet + * + * The eeprom settings packet contains information on the non-volatile ECU + * settings stored in eeprom. In particular, it provides a checksum of the + * settings data for easy comparison of settings between different ECUs. Send a + * zero length packet to request this data. + * \param _pg_pkt points to the packet which will be created by this function + * \param eepromVersion is Version of the EEPROM data + * \param eepromSize is Number of bytes of the EEPROM data + * \param eepromChecksum is Fletcher's checksum of the EEPROM data + * \param compileOptions is ECU compilation options + */ +void encodeECU_eepromSettingsPacket(void* _pg_pkt, uint8_t eepromVersion, uint16_t eepromSize, uint16_t eepromChecksum, const ECU_CompileOptions_t* compileOptions) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // Version of the EEPROM data + // Range of eepromVersion is 0 to 255. + uint8ToBytes(eepromVersion, _pg_data, &_pg_byteindex); + + // Number of bytes of the EEPROM data + // Range of eepromSize is 0 to 65535. + uint16ToBeBytes(eepromSize, _pg_data, &_pg_byteindex); + + // Fletcher's checksum of the EEPROM data + // Range of eepromChecksum is 0 to 65535. + uint16ToBeBytes(eepromChecksum, _pg_data, &_pg_byteindex); + + // ECU compilation options + encodeECU_CompileOptions_t(_pg_data, &_pg_byteindex, compileOptions); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_eepromSettingsPacketID()); + +}// encodeECU_eepromSettingsPacket + +/*! + * \brief Decode the ECU_eepromSettings packet + * + * The eeprom settings packet contains information on the non-volatile ECU + * settings stored in eeprom. In particular, it provides a checksum of the + * settings data for easy comparison of settings between different ECUs. Send a + * zero length packet to request this data. + * \param _pg_pkt points to the packet being decoded by this function + * \param eepromVersion receives Version of the EEPROM data + * \param eepromSize receives Number of bytes of the EEPROM data + * \param eepromChecksum receives Fletcher's checksum of the EEPROM data + * \param compileOptions receives ECU compilation options + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_eepromSettingsPacket(const void* _pg_pkt, uint8_t* eepromVersion, uint16_t* eepromSize, uint16_t* eepromChecksum, ECU_CompileOptions_t* compileOptions) +{ + int _pg_byteindex = 0; + const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt); + int _pg_numbytes = getECUPacketSize(_pg_pkt); + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_eepromSettingsPacketID()) + return 0; + + if(_pg_numbytes < getECU_eepromSettingsMinDataLength()) + return 0; + + // Version of the EEPROM data + // Range of eepromVersion is 0 to 255. + (*eepromVersion) = uint8FromBytes(_pg_data, &_pg_byteindex); + + // Number of bytes of the EEPROM data + // Range of eepromSize is 0 to 65535. + (*eepromSize) = uint16FromBeBytes(_pg_data, &_pg_byteindex); + + // Fletcher's checksum of the EEPROM data + // Range of eepromChecksum is 0 to 65535. + (*eepromChecksum) = uint16FromBeBytes(_pg_data, &_pg_byteindex); + + // ECU compilation options + if(decodeECU_CompileOptions_t(_pg_data, &_pg_byteindex, compileOptions) == 0) + return 0; + + return 1; + +}// decodeECU_eepromSettingsPacket + +/*! + * \brief Create the ECU_CHTLoopSettings packet + * + * Control loop settings for the CHT control loop + * \param _pg_pkt points to the packet which will be created by this function + * \param _pg_user points to the user data that will be encoded in _pg_pkt + */ +void encodeECU_CHTLoopSettingsPacketStructure(void* _pg_pkt, const ECU_CHTLoopSettings_t* _pg_user) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + _pg_data[_pg_byteindex] = 0; + + // Filter value for derivative term + // Range of dTermFilter is 0 to 31. + _pg_data[_pg_byteindex] |= (uint8_t)limitMax(_pg_user->dTermFilter, 31) << 1; + + // CHT control loop enabled + _pg_data[_pg_byteindex] |= (uint8_t)((_pg_user->enabled == true) ? 1 : 0); + _pg_byteindex += 1; // close bit field + + + // Target CHT temperature + // Range of targetTemp is 0 to 255. + uint8ToBytes(_pg_user->targetTemp, _pg_data, &_pg_byteindex); + + // Proportaional gain Kp + // Range of Kp is 0.0f to 65.535f. + float32ScaledTo2UnsignedBeBytes(_pg_user->Kp, _pg_data, &_pg_byteindex, 0.0f, 1000.0f); + + // Proportaional gain Ki + // Range of Ki is 0.0f to 65.535f. + float32ScaledTo2UnsignedBeBytes(_pg_user->Ki, _pg_data, &_pg_byteindex, 0.0f, 1000.0f); + + // Proportaional gain Kd + // Range of Kd is 0.0f to 65.535f. + float32ScaledTo2UnsignedBeBytes(_pg_user->Kd, _pg_data, &_pg_byteindex, 0.0f, 1000.0f); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_CHTLoopSettingsPacketID()); + +}// encodeECU_CHTLoopSettingsPacketStructure + +/*! + * \brief Decode the ECU_CHTLoopSettings packet + * + * Control loop settings for the CHT control loop + * \param _pg_pkt points to the packet being decoded by this function + * \param _pg_user receives the data decoded from the packet + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_CHTLoopSettingsPacketStructure(const void* _pg_pkt, ECU_CHTLoopSettings_t* _pg_user) +{ + int _pg_numbytes; + int _pg_byteindex = 0; + const uint8_t* _pg_data; + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_CHTLoopSettingsPacketID()) + return 0; + + // Verify the packet size + _pg_numbytes = getECUPacketSize(_pg_pkt); + if(_pg_numbytes < getECU_CHTLoopSettingsMinDataLength()) + return 0; + + // The raw data from the packet + _pg_data = getECUPacketDataConst(_pg_pkt); + + // Filter value for derivative term + // Range of dTermFilter is 0 to 31. + _pg_user->dTermFilter = ((_pg_data[_pg_byteindex] >> 1) & 0x1F); + + // CHT control loop enabled + _pg_user->enabled = (((_pg_data[_pg_byteindex]) & 0x1)) ? true : false; + _pg_byteindex += 1; // close bit field + + // Target CHT temperature + // Range of targetTemp is 0 to 255. + _pg_user->targetTemp = uint8FromBytes(_pg_data, &_pg_byteindex); + + // Proportaional gain Kp + // Range of Kp is 0.0f to 65.535f. + _pg_user->Kp = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/1000.0f); + + // Proportaional gain Ki + // Range of Ki is 0.0f to 65.535f. + _pg_user->Ki = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/1000.0f); + + // Proportaional gain Kd + // Range of Kd is 0.0f to 65.535f. + _pg_user->Kd = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/1000.0f); + + return 1; + +}// decodeECU_CHTLoopSettingsPacketStructure + +/*! + * \brief Create the ECU_CHTLoopSettings packet + * + * Control loop settings for the CHT control loop + * \param _pg_pkt points to the packet which will be created by this function + * \param dTermFilter is Filter value for derivative term + * \param enabled is CHT control loop enabled + * \param targetTemp is Target CHT temperature + * \param Kp is Proportaional gain Kp + * \param Ki is Proportaional gain Ki + * \param Kd is Proportaional gain Kd + */ +void encodeECU_CHTLoopSettingsPacket(void* _pg_pkt, uint8_t dTermFilter, bool enabled, uint8_t targetTemp, float Kp, float Ki, float Kd) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + _pg_data[_pg_byteindex] = 0; + + // Filter value for derivative term + // Range of dTermFilter is 0 to 31. + _pg_data[_pg_byteindex] |= (uint8_t)limitMax(dTermFilter, 31) << 1; + + // CHT control loop enabled + _pg_data[_pg_byteindex] |= (uint8_t)((enabled == true) ? 1 : 0); + _pg_byteindex += 1; // close bit field + + // Target CHT temperature + // Range of targetTemp is 0 to 255. + uint8ToBytes(targetTemp, _pg_data, &_pg_byteindex); + + // Proportaional gain Kp + // Range of Kp is 0.0f to 65.535f. + float32ScaledTo2UnsignedBeBytes(Kp, _pg_data, &_pg_byteindex, 0.0f, 1000.0f); + + // Proportaional gain Ki + // Range of Ki is 0.0f to 65.535f. + float32ScaledTo2UnsignedBeBytes(Ki, _pg_data, &_pg_byteindex, 0.0f, 1000.0f); + + // Proportaional gain Kd + // Range of Kd is 0.0f to 65.535f. + float32ScaledTo2UnsignedBeBytes(Kd, _pg_data, &_pg_byteindex, 0.0f, 1000.0f); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_CHTLoopSettingsPacketID()); + +}// encodeECU_CHTLoopSettingsPacket + +/*! + * \brief Decode the ECU_CHTLoopSettings packet + * + * Control loop settings for the CHT control loop + * \param _pg_pkt points to the packet being decoded by this function + * \param dTermFilter receives Filter value for derivative term + * \param enabled receives CHT control loop enabled + * \param targetTemp receives Target CHT temperature + * \param Kp receives Proportaional gain Kp + * \param Ki receives Proportaional gain Ki + * \param Kd receives Proportaional gain Kd + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_CHTLoopSettingsPacket(const void* _pg_pkt, uint8_t* dTermFilter, bool* enabled, uint8_t* targetTemp, float* Kp, float* Ki, float* Kd) +{ + int _pg_byteindex = 0; + const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt); + int _pg_numbytes = getECUPacketSize(_pg_pkt); + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_CHTLoopSettingsPacketID()) + return 0; + + if(_pg_numbytes < getECU_CHTLoopSettingsMinDataLength()) + return 0; + + // Filter value for derivative term + // Range of dTermFilter is 0 to 31. + (*dTermFilter) = ((_pg_data[_pg_byteindex] >> 1) & 0x1F); + + // CHT control loop enabled + (*enabled) = (((_pg_data[_pg_byteindex]) & 0x1)) ? true : false; + _pg_byteindex += 1; // close bit field + + // Target CHT temperature + // Range of targetTemp is 0 to 255. + (*targetTemp) = uint8FromBytes(_pg_data, &_pg_byteindex); + + // Proportaional gain Kp + // Range of Kp is 0.0f to 65.535f. + (*Kp) = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/1000.0f); + + // Proportaional gain Ki + // Range of Ki is 0.0f to 65.535f. + (*Ki) = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/1000.0f); + + // Proportaional gain Kd + // Range of Kd is 0.0f to 65.535f. + (*Kd) = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/1000.0f); + + return 1; + +}// decodeECU_CHTLoopSettingsPacket + +/*! + * \brief Create the ECU_DualPumpControlTelemetry packet + * + * Dual pump control telemetry. Send a zero-length packet with this identifier + * to the ECU to poll (request) this packet. + * \param _pg_pkt points to the packet which will be created by this function + * \param _pg_user points to the user data that will be encoded in _pg_pkt + */ +void encodeECU_DualPumpControlTelemetryPacketStructure(void* _pg_pkt, const ECU_DualPumpControlTelemetry_t* _pg_user) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + uint8ToBytes((uint8_t)(0xBB), _pg_data, &_pg_byteindex); + + // Current pump mode (which pump is running). Refer to the DualFuelPumpMode enumeration. + // Range of mode is 0 to 7. + _pg_data[_pg_byteindex] = (uint8_t)limitMax(_pg_user->mode, 7) << 5; + + // Current pump state machine state. Refer to the DualFuelPumpState enumeration. + // Range of state is 0 to 7. + _pg_data[_pg_byteindex] |= (uint8_t)limitMax(_pg_user->state, 7) << 2; + _pg_byteindex += 1; // close bit field + + + // Time spent in current state + // Range of stateTimer is 0 to 65535. + uint16ToBeBytes(_pg_user->stateTimer, _pg_data, &_pg_byteindex); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_DualPumpControlTelemetryPacketID()); + +}// encodeECU_DualPumpControlTelemetryPacketStructure + +/*! + * \brief Decode the ECU_DualPumpControlTelemetry packet + * + * Dual pump control telemetry. Send a zero-length packet with this identifier + * to the ECU to poll (request) this packet. + * \param _pg_pkt points to the packet being decoded by this function + * \param _pg_user receives the data decoded from the packet + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_DualPumpControlTelemetryPacketStructure(const void* _pg_pkt, ECU_DualPumpControlTelemetry_t* _pg_user) +{ + int _pg_numbytes; + int _pg_byteindex = 0; + const uint8_t* _pg_data; + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_DualPumpControlTelemetryPacketID()) + return 0; + + // Verify the packet size + _pg_numbytes = getECUPacketSize(_pg_pkt); + if(_pg_numbytes < getECU_DualPumpControlTelemetryMinDataLength()) + return 0; + + // The raw data from the packet + _pg_data = getECUPacketDataConst(_pg_pkt); + + if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) 0xBB) + return 0; + + // Current pump mode (which pump is running). Refer to the DualFuelPumpMode enumeration. + // Range of mode is 0 to 7. + _pg_user->mode = (_pg_data[_pg_byteindex] >> 5); + + // Current pump state machine state. Refer to the DualFuelPumpState enumeration. + // Range of state is 0 to 7. + _pg_user->state = ((_pg_data[_pg_byteindex] >> 2) & 0x7); + _pg_byteindex += 1; // close bit field + + // Time spent in current state + // Range of stateTimer is 0 to 65535. + _pg_user->stateTimer = uint16FromBeBytes(_pg_data, &_pg_byteindex); + + return 1; + +}// decodeECU_DualPumpControlTelemetryPacketStructure + +/*! + * \brief Create the ECU_DualPump_SetTelemetryPeriod packet + * + * Set the telemetry period for dual-pump messages + * \param _pg_pkt points to the packet which will be created by this function + * \param period is Telemetry period (0 = Off) + */ +void encodeECU_DualPump_SetTelemetryPeriodPacket(void* _pg_pkt, uint8_t period) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + uint8ToBytes((uint8_t)(0xBB), _pg_data, &_pg_byteindex); + + // Telemetry period (0 = Off) + // Range of period is 0 to 255. + uint8ToBytes(period, _pg_data, &_pg_byteindex); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_DualPump_SetTelemetryPeriodPacketID()); + +}// encodeECU_DualPump_SetTelemetryPeriodPacket + +/*! + * \brief Decode the ECU_DualPump_SetTelemetryPeriod packet + * + * Set the telemetry period for dual-pump messages + * \param _pg_pkt points to the packet being decoded by this function + * \param period receives Telemetry period (0 = Off) + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_DualPump_SetTelemetryPeriodPacket(const void* _pg_pkt, uint8_t* period) +{ + int _pg_byteindex = 0; + const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt); + int _pg_numbytes = getECUPacketSize(_pg_pkt); + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_DualPump_SetTelemetryPeriodPacketID()) + return 0; + + if(_pg_numbytes < getECU_DualPump_SetTelemetryPeriodMinDataLength()) + return 0; + + if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) 0xBB) + return 0; + + // Telemetry period (0 = Off) + // Range of period is 0 to 255. + (*period) = uint8FromBytes(_pg_data, &_pg_byteindex); + + return 1; + +}// decodeECU_DualPump_SetTelemetryPeriodPacket + +/*! + * \brief Create the ECU_DualPump_SelectPump packet + * + * Command to manually select a given pump mode. + * \param _pg_pkt points to the packet which will be created by this function + * \param pump is Pump selection (see DualFuelPumpMode enumeration) + */ +void encodeECU_DualPump_SelectPumpPacket(void* _pg_pkt, uint8_t pump) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + uint8ToBytes((uint8_t)(0xCC), _pg_data, &_pg_byteindex); + + uint8ToBytes((uint8_t)(ECU_DUAL_PUMP_CMD_SET_PUMP), _pg_data, &_pg_byteindex); + + // Pump selection (see DualFuelPumpMode enumeration) + // Range of pump is 0 to 255. + uint8ToBytes(pump, _pg_data, &_pg_byteindex); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_DualPump_SelectPumpPacketID()); + +}// encodeECU_DualPump_SelectPumpPacket + +/*! + * \brief Decode the ECU_DualPump_SelectPump packet + * + * Command to manually select a given pump mode. + * \param _pg_pkt points to the packet being decoded by this function + * \param pump receives Pump selection (see DualFuelPumpMode enumeration) + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_DualPump_SelectPumpPacket(const void* _pg_pkt, uint8_t* pump) +{ + int _pg_byteindex = 0; + const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt); + int _pg_numbytes = getECUPacketSize(_pg_pkt); + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_DualPump_SelectPumpPacketID()) + return 0; + + if(_pg_numbytes < getECU_DualPump_SelectPumpMinDataLength()) + return 0; + + if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) 0xCC) + return 0; + + if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) ECU_DUAL_PUMP_CMD_SET_PUMP) + return 0; + + // Pump selection (see DualFuelPumpMode enumeration) + // Range of pump is 0 to 255. + (*pump) = uint8FromBytes(_pg_data, &_pg_byteindex); + + return 1; + +}// decodeECU_DualPump_SelectPumpPacket + +/*! + * \brief Create the ECU_DualPump_TestPump packet + * + * Command to temporarily run a particular pump in test mode. ECU will revert + * to OTHER pump when test expires + * \param _pg_pkt points to the packet which will be created by this function + * \param _pg_user points to the user data that will be encoded in _pg_pkt + */ +void encodeECU_DualPump_TestPumpPacketStructure(void* _pg_pkt, const ECU_DualPump_TestPump_t* _pg_user) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + uint8ToBytes((uint8_t)(0xCC), _pg_data, &_pg_byteindex); + + uint8ToBytes((uint8_t)(ECU_DUAL_PUMP_CMD_TEST_PUMP), _pg_data, &_pg_byteindex); + + // Pump selection (see DualFuelPumpMode enumeration) + // Range of pump is 0 to 255. + uint8ToBytes(_pg_user->pump, _pg_data, &_pg_byteindex); + + // Test timeout + // Range of timeout is 0 to 255. + uint8ToBytes(_pg_user->timeout, _pg_data, &_pg_byteindex); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_DualPump_TestPumpPacketID()); + +}// encodeECU_DualPump_TestPumpPacketStructure + +/*! + * \brief Decode the ECU_DualPump_TestPump packet + * + * Command to temporarily run a particular pump in test mode. ECU will revert + * to OTHER pump when test expires + * \param _pg_pkt points to the packet being decoded by this function + * \param _pg_user receives the data decoded from the packet + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_DualPump_TestPumpPacketStructure(const void* _pg_pkt, ECU_DualPump_TestPump_t* _pg_user) +{ + int _pg_numbytes; + int _pg_byteindex = 0; + const uint8_t* _pg_data; + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_DualPump_TestPumpPacketID()) + return 0; + + // Verify the packet size + _pg_numbytes = getECUPacketSize(_pg_pkt); + if(_pg_numbytes < getECU_DualPump_TestPumpMinDataLength()) + return 0; + + // The raw data from the packet + _pg_data = getECUPacketDataConst(_pg_pkt); + + // this packet has default fields, make sure they are set + _pg_user->timeout = 30; + + if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) 0xCC) + return 0; + + if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) ECU_DUAL_PUMP_CMD_TEST_PUMP) + return 0; + + // Pump selection (see DualFuelPumpMode enumeration) + // Range of pump is 0 to 255. + _pg_user->pump = uint8FromBytes(_pg_data, &_pg_byteindex); + + if(_pg_byteindex + 1 > _pg_numbytes) + return 1; + + // Test timeout + // Range of timeout is 0 to 255. + _pg_user->timeout = uint8FromBytes(_pg_data, &_pg_byteindex); + + return 1; + +}// decodeECU_DualPump_TestPumpPacketStructure + +/*! + * \brief Create the ECU_ThrottleCalibration packet + * + * The throttle calibration packet sets the calibration values for minimum and + * maximum throttle position. The ECU uses these values to interpolate the + * throttle command. + * \param _pg_pkt points to the packet which will be created by this function + * \param _pg_user points to the user data that will be encoded in _pg_pkt + */ +void encodeECU_ThrottleCalibrationPacketStructure(void* _pg_pkt, const ECU_ThrottleSettings_t* _pg_user) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + unsigned int _pg_tempbitfield = 0; + + // Output position for 0% throttle in microseconds + // Range of pulseClosed is 0 to 65535. + uint16ToBeBytes(_pg_user->pulseClosed, _pg_data, &_pg_byteindex); + + // Output position for 100% throttle in microseconds + // Range of pulseOpen is 0 to 65535. + uint16ToBeBytes(_pg_user->pulseOpen, _pg_data, &_pg_byteindex); + + // Throttle configuration settings + encodeECU_ThrottleConfigBits_t(_pg_data, &_pg_byteindex, &_pg_user->config); + + // Input PWM in microseconds for 0% throttle + // Range of pulseInputClosed is 0 to 4095. + _pg_tempbitfield = (unsigned int)limitMax(_pg_user->pulseInputClosed, 4095); + _pg_data[_pg_byteindex + 1] = (uint8_t)(_pg_tempbitfield << 4); + + _pg_tempbitfield >>= 4; + _pg_data[_pg_byteindex] = (uint8_t)_pg_tempbitfield; + + + // Input PWM in microseconds for 100% throttle + // Range of pulseInputOpen is 0 to 4095. + _pg_tempbitfield = (unsigned int)limitMax(_pg_user->pulseInputOpen, 4095); + _pg_data[_pg_byteindex + 2] = (uint8_t)_pg_tempbitfield; + + _pg_tempbitfield >>= 8; + _pg_data[_pg_byteindex + 1] |= (uint8_t)_pg_tempbitfield; + _pg_byteindex += 3; // close bit field + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_ThrottleCalibrationPacketID()); + +}// encodeECU_ThrottleCalibrationPacketStructure + +/*! + * \brief Decode the ECU_ThrottleCalibration packet + * + * The throttle calibration packet sets the calibration values for minimum and + * maximum throttle position. The ECU uses these values to interpolate the + * throttle command. + * \param _pg_pkt points to the packet being decoded by this function + * \param _pg_user receives the data decoded from the packet + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_ThrottleCalibrationPacketStructure(const void* _pg_pkt, ECU_ThrottleSettings_t* _pg_user) +{ + int _pg_numbytes; + int _pg_byteindex = 0; + const uint8_t* _pg_data; + unsigned int _pg_tempbitfield = 0; + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_ThrottleCalibrationPacketID()) + return 0; + + // Verify the packet size + _pg_numbytes = getECUPacketSize(_pg_pkt); + if(_pg_numbytes < getECU_ThrottleCalibrationMinDataLength()) + return 0; + + // The raw data from the packet + _pg_data = getECUPacketDataConst(_pg_pkt); + + // Output position for 0% throttle in microseconds + // Range of pulseClosed is 0 to 65535. + _pg_user->pulseClosed = uint16FromBeBytes(_pg_data, &_pg_byteindex); + + // Output position for 100% throttle in microseconds + // Range of pulseOpen is 0 to 65535. + _pg_user->pulseOpen = uint16FromBeBytes(_pg_data, &_pg_byteindex); + + // Throttle configuration settings + if(decodeECU_ThrottleConfigBits_t(_pg_data, &_pg_byteindex, &_pg_user->config) == 0) + return 0; + + // Input PWM in microseconds for 0% throttle + // Range of pulseInputClosed is 0 to 4095. + _pg_tempbitfield = (_pg_data[_pg_byteindex] & 0xFF); + + _pg_tempbitfield <<= 4; + _pg_tempbitfield |= (_pg_data[_pg_byteindex + 1] >> 4); + + _pg_user->pulseInputClosed = _pg_tempbitfield; + + // Input PWM in microseconds for 100% throttle + // Range of pulseInputOpen is 0 to 4095. + _pg_tempbitfield = (_pg_data[_pg_byteindex + 1] & 0xF); + + _pg_tempbitfield <<= 8; + _pg_tempbitfield |= _pg_data[_pg_byteindex + 2]; + + _pg_user->pulseInputOpen = _pg_tempbitfield; + _pg_byteindex += 3; // close bit field + + return 1; + +}// decodeECU_ThrottleCalibrationPacketStructure + +/*! + * \brief Create the ECU_ThrottleCalibration packet + * + * The throttle calibration packet sets the calibration values for minimum and + * maximum throttle position. The ECU uses these values to interpolate the + * throttle command. + * \param _pg_pkt points to the packet which will be created by this function + * \param pulseClosed is Output position for 0% throttle in microseconds + * \param pulseOpen is Output position for 100% throttle in microseconds + * \param config is Throttle configuration settings + * \param pulseInputClosed is Input PWM in microseconds for 0% throttle + * \param pulseInputOpen is Input PWM in microseconds for 100% throttle + */ +void encodeECU_ThrottleCalibrationPacket(void* _pg_pkt, uint16_t pulseClosed, uint16_t pulseOpen, const ECU_ThrottleConfigBits_t* config, uint16_t pulseInputClosed, uint16_t pulseInputOpen) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + unsigned int _pg_tempbitfield = 0; + + // Output position for 0% throttle in microseconds + // Range of pulseClosed is 0 to 65535. + uint16ToBeBytes(pulseClosed, _pg_data, &_pg_byteindex); + + // Output position for 100% throttle in microseconds + // Range of pulseOpen is 0 to 65535. + uint16ToBeBytes(pulseOpen, _pg_data, &_pg_byteindex); + + // Throttle configuration settings + encodeECU_ThrottleConfigBits_t(_pg_data, &_pg_byteindex, config); + + // Input PWM in microseconds for 0% throttle + // Range of pulseInputClosed is 0 to 4095. + _pg_tempbitfield = (unsigned int)limitMax(pulseInputClosed, 4095); + _pg_data[_pg_byteindex + 1] = (uint8_t)(_pg_tempbitfield << 4); + + _pg_tempbitfield >>= 4; + _pg_data[_pg_byteindex] = (uint8_t)_pg_tempbitfield; + + // Input PWM in microseconds for 100% throttle + // Range of pulseInputOpen is 0 to 4095. + _pg_tempbitfield = (unsigned int)limitMax(pulseInputOpen, 4095); + _pg_data[_pg_byteindex + 2] = (uint8_t)_pg_tempbitfield; + + _pg_tempbitfield >>= 8; + _pg_data[_pg_byteindex + 1] |= (uint8_t)_pg_tempbitfield; + _pg_byteindex += 3; // close bit field + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_ThrottleCalibrationPacketID()); + +}// encodeECU_ThrottleCalibrationPacket + +/*! + * \brief Decode the ECU_ThrottleCalibration packet + * + * The throttle calibration packet sets the calibration values for minimum and + * maximum throttle position. The ECU uses these values to interpolate the + * throttle command. + * \param _pg_pkt points to the packet being decoded by this function + * \param pulseClosed receives Output position for 0% throttle in microseconds + * \param pulseOpen receives Output position for 100% throttle in microseconds + * \param config receives Throttle configuration settings + * \param pulseInputClosed receives Input PWM in microseconds for 0% throttle + * \param pulseInputOpen receives Input PWM in microseconds for 100% throttle + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_ThrottleCalibrationPacket(const void* _pg_pkt, uint16_t* pulseClosed, uint16_t* pulseOpen, ECU_ThrottleConfigBits_t* config, uint16_t* pulseInputClosed, uint16_t* pulseInputOpen) +{ + unsigned int _pg_tempbitfield = 0; + int _pg_byteindex = 0; + const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt); + int _pg_numbytes = getECUPacketSize(_pg_pkt); + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_ThrottleCalibrationPacketID()) + return 0; + + if(_pg_numbytes < getECU_ThrottleCalibrationMinDataLength()) + return 0; + + // Output position for 0% throttle in microseconds + // Range of pulseClosed is 0 to 65535. + (*pulseClosed) = uint16FromBeBytes(_pg_data, &_pg_byteindex); + + // Output position for 100% throttle in microseconds + // Range of pulseOpen is 0 to 65535. + (*pulseOpen) = uint16FromBeBytes(_pg_data, &_pg_byteindex); + + // Throttle configuration settings + if(decodeECU_ThrottleConfigBits_t(_pg_data, &_pg_byteindex, config) == 0) + return 0; + + // Input PWM in microseconds for 0% throttle + // Range of pulseInputClosed is 0 to 4095. + _pg_tempbitfield = (_pg_data[_pg_byteindex] & 0xFF); + + _pg_tempbitfield <<= 4; + _pg_tempbitfield |= (_pg_data[_pg_byteindex + 1] >> 4); + + (*pulseInputClosed) = _pg_tempbitfield; + + // Input PWM in microseconds for 100% throttle + // Range of pulseInputOpen is 0 to 4095. + _pg_tempbitfield = (_pg_data[_pg_byteindex + 1] & 0xF); + + _pg_tempbitfield <<= 8; + _pg_tempbitfield |= _pg_data[_pg_byteindex + 2]; + + (*pulseInputOpen) = _pg_tempbitfield; + _pg_byteindex += 3; // close bit field + + return 1; + +}// decodeECU_ThrottleCalibrationPacket + +/*! + * \brief Create the ECU_RPMLoopCalibration packet + * + * The RPM loop calibration packet controls the operating parameters of the RPM + * governor on the ECU. The control loop is implemented using a closed-loop PID + * controller with user-configurable proportional, integral, and derivative + * gains, and a gain scaler. + * \param _pg_pkt points to the packet which will be created by this function + * \param _pg_user points to the user data that will be encoded in _pg_pkt + */ +void encodeECU_RPMLoopCalibrationPacketStructure(void* _pg_pkt, const ECU_GovernorSettings_t* _pg_user) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // Proportaional feedback gain from normalized RPM error to throttle fraction + // Range of pGain is 0.0f to 6.5535f. + float32ScaledTo2UnsignedBeBytes(_pg_user->pGain, _pg_data, &_pg_byteindex, 0.0f, 10000.0f); + + // Integral feedback gain from normalized RPM error to throttle fraction + // Range of iGain is 0.0f to 6.5535f. + float32ScaledTo2UnsignedBeBytes(_pg_user->iGain, _pg_data, &_pg_byteindex, 0.0f, 10000.0f); + + // Derivative feedback gain from normalized RPM error to throttle fraction + // Range of dGain is 0.0f to 6.5535f. + float32ScaledTo2UnsignedBeBytes(_pg_user->dGain, _pg_data, &_pg_byteindex, 0.0f, 10000.0f); + + // Gain scaler power, positive numbers increase gain with RPM, and vice versa. User 0 to disable gain scaling + // Range of scalePower is -2.54f to 2.54f. + float32ScaledTo1SignedBytes(_pg_user->scalePower, _pg_data, &_pg_byteindex, 50.0f); + + // Maximum commandable RPM + // Range of maxRPM is 0.0f to 25500.0f. + float32ScaledTo1UnsignedBytes(_pg_user->maxRPM, _pg_data, &_pg_byteindex, 0.0f, 0.01f); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_RPMLoopCalibrationPacketID()); + +}// encodeECU_RPMLoopCalibrationPacketStructure + +/*! + * \brief Decode the ECU_RPMLoopCalibration packet + * + * The RPM loop calibration packet controls the operating parameters of the RPM + * governor on the ECU. The control loop is implemented using a closed-loop PID + * controller with user-configurable proportional, integral, and derivative + * gains, and a gain scaler. + * \param _pg_pkt points to the packet being decoded by this function + * \param _pg_user receives the data decoded from the packet + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_RPMLoopCalibrationPacketStructure(const void* _pg_pkt, ECU_GovernorSettings_t* _pg_user) +{ + int _pg_numbytes; + int _pg_byteindex = 0; + const uint8_t* _pg_data; + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_RPMLoopCalibrationPacketID()) + return 0; + + // Verify the packet size + _pg_numbytes = getECUPacketSize(_pg_pkt); + if(_pg_numbytes < getECU_RPMLoopCalibrationMinDataLength()) + return 0; + + // The raw data from the packet + _pg_data = getECUPacketDataConst(_pg_pkt); + + // Proportaional feedback gain from normalized RPM error to throttle fraction + // Range of pGain is 0.0f to 6.5535f. + _pg_user->pGain = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/10000.0f); + + // Integral feedback gain from normalized RPM error to throttle fraction + // Range of iGain is 0.0f to 6.5535f. + _pg_user->iGain = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/10000.0f); + + // Derivative feedback gain from normalized RPM error to throttle fraction + // Range of dGain is 0.0f to 6.5535f. + _pg_user->dGain = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/10000.0f); + + // Gain scaler power, positive numbers increase gain with RPM, and vice versa. User 0 to disable gain scaling + // Range of scalePower is -2.54f to 2.54f. + _pg_user->scalePower = float32ScaledFrom1SignedBytes(_pg_data, &_pg_byteindex, 1.0f/50.0f); + + // Maximum commandable RPM + // Range of maxRPM is 0.0f to 25500.0f. + _pg_user->maxRPM = float32ScaledFrom1UnsignedBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/0.01f); + + return 1; + +}// decodeECU_RPMLoopCalibrationPacketStructure + +/*! + * \brief Create the ECU_TPSDelayCalibration packet + * + * The throttle position delay configuration packet sends the desired throttle + * position delay (between 0 and 500ms) to the ECU, and also echoes back the + * TPS delay. + * \param _pg_pkt points to the packet which will be created by this function + * \param _pg_user points to the user data that will be encoded in _pg_pkt + */ +void encodeECU_TPSDelayCalibrationPacketStructure(void* _pg_pkt, const ECU_ThrottleSettings_t* _pg_user) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // Current TPS delay in seconds + // Range of delay is 0 to 255. + uint8ToBytes(_pg_user->delay, _pg_data, &_pg_byteindex); + + // Throttle delay configuration bits + encodeECU_ThrottleDelayConfigBits_t(_pg_data, &_pg_byteindex, &_pg_user->delayConfig); + + // Maximum TPS delay in seconds (for use with temperature dependent TPS delay setting + // Range of maxDelay is 0 to 255. + uint8ToBytes(_pg_user->maxDelay, _pg_data, &_pg_byteindex); + + // Minimum TPS delay in seconds (for use with temperature dependent TPS delay setting + // Range of minDelay is 0 to 255. + uint8ToBytes(_pg_user->minDelay, _pg_data, &_pg_byteindex); + + // throttle percentage below which the throttle position will gradually fall off rather than dropping instantaneously (Set this value to zero for the throttle to operate without a soft limit) + // Range of softLimit is 0 to 255. + uint8ToBytes(_pg_user->softLimit, _pg_data, &_pg_byteindex); + + // Throttle falloff rate. This determines the rate at which the throttle position decreases if it is below the soft limit + // Range of falloffRate is 0 to 255. + uint8ToBytes(_pg_user->falloffRate, _pg_data, &_pg_byteindex); + + // The throttle target position is the TPS input value, which may be given to the ECU via any of the available input types (analog, PWM, serial or CAN). This may vary from the output value, due to the dashpot functionality or the linearization curve. Note: this value cannot be written to the ECU + // Range of throttleTarget is 0 to 255. + uint8ToBytes(_pg_user->throttleTarget, _pg_data, &_pg_byteindex); + + // This value sets the minimum allowable throttle position in percent. The throttle position will not fall below this value + // Range of hardLimit is 0 to 255. + uint8ToBytes(_pg_user->hardLimit, _pg_data, &_pg_byteindex); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_TPSDelayCalibrationPacketID()); + +}// encodeECU_TPSDelayCalibrationPacketStructure + +/*! + * \brief Decode the ECU_TPSDelayCalibration packet + * + * The throttle position delay configuration packet sends the desired throttle + * position delay (between 0 and 500ms) to the ECU, and also echoes back the + * TPS delay. + * \param _pg_pkt points to the packet being decoded by this function + * \param _pg_user receives the data decoded from the packet + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_TPSDelayCalibrationPacketStructure(const void* _pg_pkt, ECU_ThrottleSettings_t* _pg_user) +{ + int _pg_numbytes; + int _pg_byteindex = 0; + const uint8_t* _pg_data; + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_TPSDelayCalibrationPacketID()) + return 0; + + // Verify the packet size + _pg_numbytes = getECUPacketSize(_pg_pkt); + if(_pg_numbytes < getECU_TPSDelayCalibrationMinDataLength()) + return 0; + + // The raw data from the packet + _pg_data = getECUPacketDataConst(_pg_pkt); + + // Current TPS delay in seconds + // Range of delay is 0 to 255. + _pg_user->delay = uint8FromBytes(_pg_data, &_pg_byteindex); + + // Throttle delay configuration bits + if(decodeECU_ThrottleDelayConfigBits_t(_pg_data, &_pg_byteindex, &_pg_user->delayConfig) == 0) + return 0; + + // Maximum TPS delay in seconds (for use with temperature dependent TPS delay setting + // Range of maxDelay is 0 to 255. + _pg_user->maxDelay = uint8FromBytes(_pg_data, &_pg_byteindex); + + // Minimum TPS delay in seconds (for use with temperature dependent TPS delay setting + // Range of minDelay is 0 to 255. + _pg_user->minDelay = uint8FromBytes(_pg_data, &_pg_byteindex); + + // throttle percentage below which the throttle position will gradually fall off rather than dropping instantaneously (Set this value to zero for the throttle to operate without a soft limit) + // Range of softLimit is 0 to 255. + _pg_user->softLimit = uint8FromBytes(_pg_data, &_pg_byteindex); + + // Throttle falloff rate. This determines the rate at which the throttle position decreases if it is below the soft limit + // Range of falloffRate is 0 to 255. + _pg_user->falloffRate = uint8FromBytes(_pg_data, &_pg_byteindex); + + // The throttle target position is the TPS input value, which may be given to the ECU via any of the available input types (analog, PWM, serial or CAN). This may vary from the output value, due to the dashpot functionality or the linearization curve. Note: this value cannot be written to the ECU + // Range of throttleTarget is 0 to 255. + _pg_user->throttleTarget = uint8FromBytes(_pg_data, &_pg_byteindex); + + // This value sets the minimum allowable throttle position in percent. The throttle position will not fall below this value + // Range of hardLimit is 0 to 255. + _pg_user->hardLimit = uint8FromBytes(_pg_data, &_pg_byteindex); + + return 1; + +}// decodeECU_TPSDelayCalibrationPacketStructure + +/*! + * \brief Create the ECU_TPSDelayCalibration packet + * + * The throttle position delay configuration packet sends the desired throttle + * position delay (between 0 and 500ms) to the ECU, and also echoes back the + * TPS delay. + * \param _pg_pkt points to the packet which will be created by this function + * \param delay is Current TPS delay in seconds + * \param delayConfig is Throttle delay configuration bits + * \param maxDelay is Maximum TPS delay in seconds (for use with temperature dependent TPS delay setting + * \param minDelay is Minimum TPS delay in seconds (for use with temperature dependent TPS delay setting + * \param softLimit is throttle percentage below which the throttle position will gradually fall off rather than dropping instantaneously (Set this value to zero for the throttle to operate without a soft limit) + * \param falloffRate is Throttle falloff rate. This determines the rate at which the throttle position decreases if it is below the soft limit + * \param throttleTarget is The throttle target position is the TPS input value, which may be given to the ECU via any of the available input types (analog, PWM, serial or CAN). This may vary from the output value, due to the dashpot functionality or the linearization curve. Note: this value cannot be written to the ECU + * \param hardLimit is This value sets the minimum allowable throttle position in percent. The throttle position will not fall below this value + */ +void encodeECU_TPSDelayCalibrationPacket(void* _pg_pkt, uint8_t delay, const ECU_ThrottleDelayConfigBits_t* delayConfig, uint8_t maxDelay, uint8_t minDelay, uint8_t softLimit, uint8_t falloffRate, uint8_t throttleTarget, uint8_t hardLimit) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // Current TPS delay in seconds + // Range of delay is 0 to 255. + uint8ToBytes(delay, _pg_data, &_pg_byteindex); + + // Throttle delay configuration bits + encodeECU_ThrottleDelayConfigBits_t(_pg_data, &_pg_byteindex, delayConfig); + + // Maximum TPS delay in seconds (for use with temperature dependent TPS delay setting + // Range of maxDelay is 0 to 255. + uint8ToBytes(maxDelay, _pg_data, &_pg_byteindex); + + // Minimum TPS delay in seconds (for use with temperature dependent TPS delay setting + // Range of minDelay is 0 to 255. + uint8ToBytes(minDelay, _pg_data, &_pg_byteindex); + + // throttle percentage below which the throttle position will gradually fall off rather than dropping instantaneously (Set this value to zero for the throttle to operate without a soft limit) + // Range of softLimit is 0 to 255. + uint8ToBytes(softLimit, _pg_data, &_pg_byteindex); + + // Throttle falloff rate. This determines the rate at which the throttle position decreases if it is below the soft limit + // Range of falloffRate is 0 to 255. + uint8ToBytes(falloffRate, _pg_data, &_pg_byteindex); + + // The throttle target position is the TPS input value, which may be given to the ECU via any of the available input types (analog, PWM, serial or CAN). This may vary from the output value, due to the dashpot functionality or the linearization curve. Note: this value cannot be written to the ECU + // Range of throttleTarget is 0 to 255. + uint8ToBytes(throttleTarget, _pg_data, &_pg_byteindex); + + // This value sets the minimum allowable throttle position in percent. The throttle position will not fall below this value + // Range of hardLimit is 0 to 255. + uint8ToBytes(hardLimit, _pg_data, &_pg_byteindex); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_TPSDelayCalibrationPacketID()); + +}// encodeECU_TPSDelayCalibrationPacket + +/*! + * \brief Decode the ECU_TPSDelayCalibration packet + * + * The throttle position delay configuration packet sends the desired throttle + * position delay (between 0 and 500ms) to the ECU, and also echoes back the + * TPS delay. + * \param _pg_pkt points to the packet being decoded by this function + * \param delay receives Current TPS delay in seconds + * \param delayConfig receives Throttle delay configuration bits + * \param maxDelay receives Maximum TPS delay in seconds (for use with temperature dependent TPS delay setting + * \param minDelay receives Minimum TPS delay in seconds (for use with temperature dependent TPS delay setting + * \param softLimit receives throttle percentage below which the throttle position will gradually fall off rather than dropping instantaneously (Set this value to zero for the throttle to operate without a soft limit) + * \param falloffRate receives Throttle falloff rate. This determines the rate at which the throttle position decreases if it is below the soft limit + * \param throttleTarget receives The throttle target position is the TPS input value, which may be given to the ECU via any of the available input types (analog, PWM, serial or CAN). This may vary from the output value, due to the dashpot functionality or the linearization curve. Note: this value cannot be written to the ECU + * \param hardLimit receives This value sets the minimum allowable throttle position in percent. The throttle position will not fall below this value + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_TPSDelayCalibrationPacket(const void* _pg_pkt, uint8_t* delay, ECU_ThrottleDelayConfigBits_t* delayConfig, uint8_t* maxDelay, uint8_t* minDelay, uint8_t* softLimit, uint8_t* falloffRate, uint8_t* throttleTarget, uint8_t* hardLimit) +{ + int _pg_byteindex = 0; + const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt); + int _pg_numbytes = getECUPacketSize(_pg_pkt); + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_TPSDelayCalibrationPacketID()) + return 0; + + if(_pg_numbytes < getECU_TPSDelayCalibrationMinDataLength()) + return 0; + + // Current TPS delay in seconds + // Range of delay is 0 to 255. + (*delay) = uint8FromBytes(_pg_data, &_pg_byteindex); + + // Throttle delay configuration bits + if(decodeECU_ThrottleDelayConfigBits_t(_pg_data, &_pg_byteindex, delayConfig) == 0) + return 0; + + // Maximum TPS delay in seconds (for use with temperature dependent TPS delay setting + // Range of maxDelay is 0 to 255. + (*maxDelay) = uint8FromBytes(_pg_data, &_pg_byteindex); + + // Minimum TPS delay in seconds (for use with temperature dependent TPS delay setting + // Range of minDelay is 0 to 255. + (*minDelay) = uint8FromBytes(_pg_data, &_pg_byteindex); + + // throttle percentage below which the throttle position will gradually fall off rather than dropping instantaneously (Set this value to zero for the throttle to operate without a soft limit) + // Range of softLimit is 0 to 255. + (*softLimit) = uint8FromBytes(_pg_data, &_pg_byteindex); + + // Throttle falloff rate. This determines the rate at which the throttle position decreases if it is below the soft limit + // Range of falloffRate is 0 to 255. + (*falloffRate) = uint8FromBytes(_pg_data, &_pg_byteindex); + + // The throttle target position is the TPS input value, which may be given to the ECU via any of the available input types (analog, PWM, serial or CAN). This may vary from the output value, due to the dashpot functionality or the linearization curve. Note: this value cannot be written to the ECU + // Range of throttleTarget is 0 to 255. + (*throttleTarget) = uint8FromBytes(_pg_data, &_pg_byteindex); + + // This value sets the minimum allowable throttle position in percent. The throttle position will not fall below this value + // Range of hardLimit is 0 to 255. + (*hardLimit) = uint8FromBytes(_pg_data, &_pg_byteindex); + + return 1; + +}// decodeECU_TPSDelayCalibrationPacket + +/*! + * \brief Create the ECU_TelemetrySettings packet + * + * The telmetry settings packet is used to configure the telemetry data rates + * for the ECU. The ECU will echo the packet as confirmation of its receipt. + * Send a zero length packet to request the current settings. + * \param _pg_pkt points to the packet which will be created by this function + * \param _pg_user points to the user data that will be encoded in _pg_pkt + */ +void encodeECU_TelemetrySettingsPacketStructure(void* _pg_pkt, const ECU_TelemetrySettings_t* _pg_user) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // Time between fast telemetry packets in 50ms increments + // Range of fastTelemetryPeriod is 0 to 255. + uint8ToBytes(_pg_user->fastTelemetryPeriod, _pg_data, &_pg_byteindex); + + // Time between slow telemetry packets in 500ms increments + // Range of slowTelemetryPeriod is 0 to 255. + uint8ToBytes(_pg_user->slowTelemetryPeriod, _pg_data, &_pg_byteindex); + + // Seconds of time the ECU waits after bootup before sending telemetry. + // Range of silencePeriod is 0 to 255. + uint8ToBytes(_pg_user->silencePeriod, _pg_data, &_pg_byteindex); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_TelemetrySettingsPacketID()); + +}// encodeECU_TelemetrySettingsPacketStructure + +/*! + * \brief Decode the ECU_TelemetrySettings packet + * + * The telmetry settings packet is used to configure the telemetry data rates + * for the ECU. The ECU will echo the packet as confirmation of its receipt. + * Send a zero length packet to request the current settings. + * \param _pg_pkt points to the packet being decoded by this function + * \param _pg_user receives the data decoded from the packet + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_TelemetrySettingsPacketStructure(const void* _pg_pkt, ECU_TelemetrySettings_t* _pg_user) +{ + int _pg_numbytes; + int _pg_byteindex = 0; + const uint8_t* _pg_data; + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_TelemetrySettingsPacketID()) + return 0; + + // Verify the packet size + _pg_numbytes = getECUPacketSize(_pg_pkt); + if(_pg_numbytes < getECU_TelemetrySettingsMinDataLength()) + return 0; + + // The raw data from the packet + _pg_data = getECUPacketDataConst(_pg_pkt); + + // Time between fast telemetry packets in 50ms increments + // Range of fastTelemetryPeriod is 0 to 255. + _pg_user->fastTelemetryPeriod = uint8FromBytes(_pg_data, &_pg_byteindex); + + // Time between slow telemetry packets in 500ms increments + // Range of slowTelemetryPeriod is 0 to 255. + _pg_user->slowTelemetryPeriod = uint8FromBytes(_pg_data, &_pg_byteindex); + + // Seconds of time the ECU waits after bootup before sending telemetry. + // Range of silencePeriod is 0 to 255. + _pg_user->silencePeriod = uint8FromBytes(_pg_data, &_pg_byteindex); + + return 1; + +}// decodeECU_TelemetrySettingsPacketStructure + +/*! + * \brief Create the ECU_PumpConfig packet + * + * The pump config packet is sent to the ECU to configure fuel pump control + * loop parameters. The ECU will echo the packet as confirmation of its + * receipt. Send a zero length packet to request the current settings. Note + * that the fuel pump configuration consists of two packets, this one and + * Pump2config. + * \param _pg_pkt points to the packet which will be created by this function + * \param _pg_user points to the user data that will be encoded in _pg_pkt + */ +void encodeECU_PumpConfigPacketStructure(void* _pg_pkt, const ECU_PumpSettings_t* _pg_user) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // Fuel pump proportional gain + // Range of kp is 0.0f to 655.35f. + float32ScaledTo2UnsignedBeBytes(_pg_user->kp, _pg_data, &_pg_byteindex, 0.0f, 100.0f); + + // Pump low pressure limit in kilo-Pascals + // Range of pressureLowerLimit is 0.0f to 4518.40871f. + float32ScaledTo2UnsignedBeBytes(_pg_user->pressureLowerLimit, _pg_data, &_pg_byteindex, 0.0f, 14.504f); + + // Pump high pressure limit in kilo-Pascals + // Range of pressureUpperLimit is 0.0f to 4518.40871f. + float32ScaledTo2UnsignedBeBytes(_pg_user->pressureUpperLimit, _pg_data, &_pg_byteindex, 0.0f, 14.504f); + + // Pump pressure setpoint in kilo-Pascals + // Range of pressureSetpoint is 0.0f to 4518.40871f. + float32ScaledTo2UnsignedBeBytes(_pg_user->pressureSetpoint, _pg_data, &_pg_byteindex, 0.0f, 14.504f); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_PumpConfigPacketID()); + +}// encodeECU_PumpConfigPacketStructure + +/*! + * \brief Decode the ECU_PumpConfig packet + * + * The pump config packet is sent to the ECU to configure fuel pump control + * loop parameters. The ECU will echo the packet as confirmation of its + * receipt. Send a zero length packet to request the current settings. Note + * that the fuel pump configuration consists of two packets, this one and + * Pump2config. + * \param _pg_pkt points to the packet being decoded by this function + * \param _pg_user receives the data decoded from the packet + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_PumpConfigPacketStructure(const void* _pg_pkt, ECU_PumpSettings_t* _pg_user) +{ + int _pg_numbytes; + int _pg_byteindex = 0; + const uint8_t* _pg_data; + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_PumpConfigPacketID()) + return 0; + + // Verify the packet size + _pg_numbytes = getECUPacketSize(_pg_pkt); + if(_pg_numbytes < getECU_PumpConfigMinDataLength()) + return 0; + + // The raw data from the packet + _pg_data = getECUPacketDataConst(_pg_pkt); + + // Fuel pump proportional gain + // Range of kp is 0.0f to 655.35f. + _pg_user->kp = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/100.0f); + + // Pump low pressure limit in kilo-Pascals + // Range of pressureLowerLimit is 0.0f to 4518.40871f. + _pg_user->pressureLowerLimit = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/14.504f); + + // Pump high pressure limit in kilo-Pascals + // Range of pressureUpperLimit is 0.0f to 4518.40871f. + _pg_user->pressureUpperLimit = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/14.504f); + + // Pump pressure setpoint in kilo-Pascals + // Range of pressureSetpoint is 0.0f to 4518.40871f. + _pg_user->pressureSetpoint = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/14.504f); + + return 1; + +}// decodeECU_PumpConfigPacketStructure + +/*! + * \brief Create the ECU_Pump2Config packet + * + * The pump 2 config packet is used for further configuration of pump + * operation. This packet allows the user to configure integral gain values and + * PWM limits. The ECU will echo the packet as confirmation of its receipt. + * Send a zero length packet to request the current settings. + * \param _pg_pkt points to the packet which will be created by this function + * \param _pg_user points to the user data that will be encoded in _pg_pkt + */ +void encodeECU_Pump2ConfigPacketStructure(void* _pg_pkt, const ECU_PumpSettings_t* _pg_user) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // Fuel pump integral gain + // Range of ki is 0.0f to 65.535f. + float32ScaledTo2UnsignedBeBytes(_pg_user->ki, _pg_data, &_pg_byteindex, 0.0f, 1000.0f); + + // Minimum duty cycle in percent (250 = 100%) + // Range of minimumPWM is 0 to 255. + uint8ToBytes(_pg_user->minimumPWM, _pg_data, &_pg_byteindex); + + // Maximum duty cycle in percent (250 = 100%) + // Range of maximumPWM is 0 to 255. + uint8ToBytes(_pg_user->maximumPWM, _pg_data, &_pg_byteindex); + + // Reserved for future use + uint16ToBeBytes((uint16_t)(0), _pg_data, &_pg_byteindex); + + // Pump duty cycle ramp rate + // Range of rampRate is 0 to 255. + uint8ToBytes(_pg_user->rampRate, _pg_data, &_pg_byteindex); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_Pump2ConfigPacketID()); + +}// encodeECU_Pump2ConfigPacketStructure + +/*! + * \brief Decode the ECU_Pump2Config packet + * + * The pump 2 config packet is used for further configuration of pump + * operation. This packet allows the user to configure integral gain values and + * PWM limits. The ECU will echo the packet as confirmation of its receipt. + * Send a zero length packet to request the current settings. + * \param _pg_pkt points to the packet being decoded by this function + * \param _pg_user receives the data decoded from the packet + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_Pump2ConfigPacketStructure(const void* _pg_pkt, ECU_PumpSettings_t* _pg_user) +{ + int _pg_numbytes; + int _pg_byteindex = 0; + const uint8_t* _pg_data; + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_Pump2ConfigPacketID()) + return 0; + + // Verify the packet size + _pg_numbytes = getECUPacketSize(_pg_pkt); + if(_pg_numbytes < getECU_Pump2ConfigMinDataLength()) + return 0; + + // The raw data from the packet + _pg_data = getECUPacketDataConst(_pg_pkt); + + // Fuel pump integral gain + // Range of ki is 0.0f to 65.535f. + _pg_user->ki = float32ScaledFrom2UnsignedBeBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/1000.0f); + + // Minimum duty cycle in percent (250 = 100%) + // Range of minimumPWM is 0 to 255. + _pg_user->minimumPWM = uint8FromBytes(_pg_data, &_pg_byteindex); + + // Maximum duty cycle in percent (250 = 100%) + // Range of maximumPWM is 0 to 255. + _pg_user->maximumPWM = uint8FromBytes(_pg_data, &_pg_byteindex); + + // Reserved for future use + _pg_byteindex += 2; + + // Pump duty cycle ramp rate + // Range of rampRate is 0 to 255. + _pg_user->rampRate = uint8FromBytes(_pg_data, &_pg_byteindex); + + return 1; + +}// decodeECU_Pump2ConfigPacketStructure + +/*! + * \brief Create the ECU_UserData packet + * + * The user data packet provides the user with 8 (eight) bytes of data for + * storing custom parameters or settings in ECU EEPROM (non-volatile) memory. + * The ECU does not make use of these values; they are simply for storing user + * data. Send a zero length packet to request the current settings. To set + * these values send the system command SET_USER_DATA. Data values must be set + * individually. + * \param _pg_pkt points to the packet which will be created by this function + * \param userData is 8 bytes of user data + */ +void encodeECU_UserDataPacket(void* _pg_pkt, const uint8_t userData[8]) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + unsigned _pg_i = 0; + + // 8 bytes of user data + // Range of userData is 0 to 255. + for(_pg_i = 0; _pg_i < 8; _pg_i++) + uint8ToBytes(userData[_pg_i], _pg_data, &_pg_byteindex); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_UserDataPacketID()); + +}// encodeECU_UserDataPacket + +/*! + * \brief Decode the ECU_UserData packet + * + * The user data packet provides the user with 8 (eight) bytes of data for + * storing custom parameters or settings in ECU EEPROM (non-volatile) memory. + * The ECU does not make use of these values; they are simply for storing user + * data. Send a zero length packet to request the current settings. To set + * these values send the system command SET_USER_DATA. Data values must be set + * individually. + * \param _pg_pkt points to the packet being decoded by this function + * \param userData receives 8 bytes of user data + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_UserDataPacket(const void* _pg_pkt, uint8_t userData[8]) +{ + unsigned _pg_i = 0; + int _pg_byteindex = 0; + const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt); + int _pg_numbytes = getECUPacketSize(_pg_pkt); + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_UserDataPacketID()) + return 0; + + if(_pg_numbytes < getECU_UserDataMinDataLength()) + return 0; + + // 8 bytes of user data + // Range of userData is 0 to 255. + for(_pg_i = 0; _pg_i < 8; _pg_i++) + userData[_pg_i] = uint8FromBytes(_pg_data, &_pg_byteindex); + + return 1; + +}// decodeECU_UserDataPacket + +/*! + * \brief Create the ECU_ThrottleCurve packet + * + * First throttle curve packet, which contains the lower 6 term of the throttle + * linearization table. To request the throttle curve data (both packets), send + * the system command REQUEST_THROTTLE_CURVE_DATA. To change the throttle curve + * data send the system command SET_THROTTLE_CURVE_ELEMENT. + * \param _pg_pkt points to the packet which will be created by this function + * \param throttleCurve is Throttle output values for the lower 6 cells in the throttle lookup table + */ +void encodeECU_ThrottleCurvePacket(void* _pg_pkt, const float throttleCurve[6]) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + unsigned _pg_i = 0; + + // Throttle output values for the lower 6 cells in the throttle lookup table + // Range of throttleCurve is 0.0f to 127.5f. + for(_pg_i = 0; _pg_i < 6; _pg_i++) + float32ScaledTo1UnsignedBytes(throttleCurve[_pg_i], _pg_data, &_pg_byteindex, 0.0f, 2.0f); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_ThrottleCurvePacketID()); + +}// encodeECU_ThrottleCurvePacket + +/*! + * \brief Decode the ECU_ThrottleCurve packet + * + * First throttle curve packet, which contains the lower 6 term of the throttle + * linearization table. To request the throttle curve data (both packets), send + * the system command REQUEST_THROTTLE_CURVE_DATA. To change the throttle curve + * data send the system command SET_THROTTLE_CURVE_ELEMENT. + * \param _pg_pkt points to the packet being decoded by this function + * \param throttleCurve receives Throttle output values for the lower 6 cells in the throttle lookup table + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_ThrottleCurvePacket(const void* _pg_pkt, float throttleCurve[6]) +{ + unsigned _pg_i = 0; + int _pg_byteindex = 0; + const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt); + int _pg_numbytes = getECUPacketSize(_pg_pkt); + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_ThrottleCurvePacketID()) + return 0; + + if(_pg_numbytes < getECU_ThrottleCurveMinDataLength()) + return 0; + + // Throttle output values for the lower 6 cells in the throttle lookup table + // Range of throttleCurve is 0.0f to 127.5f. + for(_pg_i = 0; _pg_i < 6; _pg_i++) + throttleCurve[_pg_i] = float32ScaledFrom1UnsignedBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/2.0f); + + return 1; + +}// decodeECU_ThrottleCurvePacket + +/*! + * \brief Create the ECU_ThrottleCurve1 packet + * + * Second throttle curve packet, which contains the upper 5 term of the + * throttle linearization table. To request the throttle curve data (both + * packets), send the system command REQUEST_THROTTLE_CURVE_DATA. To change the + * throttle curve data send the system command SET_THROTTLE_CURVE_ELEMENT. + * \param _pg_pkt points to the packet which will be created by this function + * \param throttleCurve is Throttle output values for the upper 5 cells in the throttle lookup table + */ +void encodeECU_ThrottleCurve1Packet(void* _pg_pkt, const float throttleCurve[5]) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + unsigned _pg_i = 0; + + // Throttle output values for the upper 5 cells in the throttle lookup table + // Range of throttleCurve is 0.0f to 127.5f. + for(_pg_i = 0; _pg_i < 5; _pg_i++) + float32ScaledTo1UnsignedBytes(throttleCurve[_pg_i], _pg_data, &_pg_byteindex, 0.0f, 2.0f); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_ThrottleCurve1PacketID()); + +}// encodeECU_ThrottleCurve1Packet + +/*! + * \brief Decode the ECU_ThrottleCurve1 packet + * + * Second throttle curve packet, which contains the upper 5 term of the + * throttle linearization table. To request the throttle curve data (both + * packets), send the system command REQUEST_THROTTLE_CURVE_DATA. To change the + * throttle curve data send the system command SET_THROTTLE_CURVE_ELEMENT. + * \param _pg_pkt points to the packet being decoded by this function + * \param throttleCurve receives Throttle output values for the upper 5 cells in the throttle lookup table + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_ThrottleCurve1Packet(const void* _pg_pkt, float throttleCurve[5]) +{ + unsigned _pg_i = 0; + int _pg_byteindex = 0; + const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt); + int _pg_numbytes = getECUPacketSize(_pg_pkt); + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_ThrottleCurve1PacketID()) + return 0; + + if(_pg_numbytes < getECU_ThrottleCurve1MinDataLength()) + return 0; + + // Throttle output values for the upper 5 cells in the throttle lookup table + // Range of throttleCurve is 0.0f to 127.5f. + for(_pg_i = 0; _pg_i < 5; _pg_i++) + throttleCurve[_pg_i] = float32ScaledFrom1UnsignedBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/2.0f); + + return 1; + +}// decodeECU_ThrottleCurve1Packet + +/*! + * \brief Create the ECU_SystemCommand packet + * + * The system command packets follow the format provided below. Refer further + * in the document for complete documentation on each system command packet. + * \param _pg_pkt points to the packet which will be created by this function + * \param _pg_user points to the user data that will be encoded in _pg_pkt + */ +void encodeECU_SystemCommandPacketStructure(void* _pg_pkt, const ECU_SystemCommand_t* _pg_user) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + unsigned _pg_i = 0; + + // The command enumeration + // Range of cmd is 0 to 255. + uint8ToBytes(_pg_user->cmd, _pg_data, &_pg_byteindex); + + // Up to 3 parameter bytes for a system command + // Range of parambytes is 0 to 255. + for(_pg_i = 0; _pg_i < 3; _pg_i++) + uint8ToBytes(_pg_user->parambytes[_pg_i], _pg_data, &_pg_byteindex); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_SystemCommandPacketID()); + +}// encodeECU_SystemCommandPacketStructure + +/*! + * \brief Decode the ECU_SystemCommand packet + * + * The system command packets follow the format provided below. Refer further + * in the document for complete documentation on each system command packet. + * \param _pg_pkt points to the packet being decoded by this function + * \param _pg_user receives the data decoded from the packet + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_SystemCommandPacketStructure(const void* _pg_pkt, ECU_SystemCommand_t* _pg_user) +{ + int _pg_numbytes; + int _pg_byteindex = 0; + const uint8_t* _pg_data; + unsigned _pg_i = 0; + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_SystemCommandPacketID()) + return 0; + + // Verify the packet size + _pg_numbytes = getECUPacketSize(_pg_pkt); + if(_pg_numbytes < getECU_SystemCommandMinDataLength()) + return 0; + + // The raw data from the packet + _pg_data = getECUPacketDataConst(_pg_pkt); + + // this packet has default fields, make sure they are set + for(_pg_i = 0; _pg_i < 3; _pg_i++) + _pg_user->parambytes[_pg_i] = 0; + + // The command enumeration + // Range of cmd is 0 to 255. + _pg_user->cmd = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex); + + if(_pg_byteindex + 1*3 > _pg_numbytes) + return 1; + + // Up to 3 parameter bytes for a system command + // Range of parambytes is 0 to 255. + for(_pg_i = 0; _pg_i < 3; _pg_i++) + _pg_user->parambytes[_pg_i] = uint8FromBytes(_pg_data, &_pg_byteindex); + + return 1; + +}// decodeECU_SystemCommandPacketStructure + +/*! + * \brief Create the ECU_CalibrateAnalogClosed packet + * + * Save the current value of the analog throttle position input as the 'Closed' + * position. To calibrate the closed analog input position, set the desired + * analog input level, and send this command to the ECU. + * \param _pg_pkt points to the packet which will be created by this function + */ +void encodeECU_CalibrateAnalogClosedPacket(void* _pg_pkt) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // The command enumeration + uint8ToBytes((uint8_t)(CMD_ECU_CALIBRATE_ANALOG_CLOSED), _pg_data, &_pg_byteindex); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_CalibrateAnalogClosedPacketID()); + +}// encodeECU_CalibrateAnalogClosedPacket + +/*! + * \brief Decode the ECU_CalibrateAnalogClosed packet + * + * Save the current value of the analog throttle position input as the 'Closed' + * position. To calibrate the closed analog input position, set the desired + * analog input level, and send this command to the ECU. + * \param _pg_pkt points to the packet being decoded by this function + * \param cmd receives The command enumeration + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_CalibrateAnalogClosedPacket(const void* _pg_pkt, ECUSystemCommands* cmd) +{ + int _pg_byteindex = 0; + const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt); + int _pg_numbytes = getECUPacketSize(_pg_pkt); + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_CalibrateAnalogClosedPacketID()) + return 0; + + if(_pg_numbytes < getECU_CalibrateAnalogClosedMinDataLength()) + return 0; + + // The command enumeration + // Range of cmd is 0 to 255. + // Decoded value must be CMD_ECU_CALIBRATE_ANALOG_CLOSED + (*cmd) = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex); + if ((*cmd) != CMD_ECU_CALIBRATE_ANALOG_CLOSED) + return 0; + + return 1; + +}// decodeECU_CalibrateAnalogClosedPacket + +/*! + * \brief Create the ECU_CalibrateAnalogOpen packet + * + * Save the current value of the analog throttle position input as the 'Open' + * position. To calibrate the open analog input position, set the desired + * analog input level, and send this command to the ECU. + * \param _pg_pkt points to the packet which will be created by this function + */ +void encodeECU_CalibrateAnalogOpenPacket(void* _pg_pkt) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // The command enumeration + uint8ToBytes((uint8_t)(CMD_ECU_CALIBRATE_ANALOG_OPEN), _pg_data, &_pg_byteindex); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_CalibrateAnalogOpenPacketID()); + +}// encodeECU_CalibrateAnalogOpenPacket + +/*! + * \brief Decode the ECU_CalibrateAnalogOpen packet + * + * Save the current value of the analog throttle position input as the 'Open' + * position. To calibrate the open analog input position, set the desired + * analog input level, and send this command to the ECU. + * \param _pg_pkt points to the packet being decoded by this function + * \param cmd receives The command enumeration + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_CalibrateAnalogOpenPacket(const void* _pg_pkt, ECUSystemCommands* cmd) +{ + int _pg_byteindex = 0; + const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt); + int _pg_numbytes = getECUPacketSize(_pg_pkt); + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_CalibrateAnalogOpenPacketID()) + return 0; + + if(_pg_numbytes < getECU_CalibrateAnalogOpenMinDataLength()) + return 0; + + // The command enumeration + // Range of cmd is 0 to 255. + // Decoded value must be CMD_ECU_CALIBRATE_ANALOG_OPEN + (*cmd) = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex); + if ((*cmd) != CMD_ECU_CALIBRATE_ANALOG_OPEN) + return 0; + + return 1; + +}// decodeECU_CalibrateAnalogOpenPacket + +/*! + * \brief Create the ECU_CalibratePulseClosed packet + * + * Save the current value of the throttle output pulse width to a temporary + * variable in the ECU. When the CALIBRATE_PULSE_WRITE command is sent to the + * ECU, this value will be saved as the 'Closed' pulse width. + * \param _pg_pkt points to the packet which will be created by this function + */ +void encodeECU_CalibratePulseClosedPacket(void* _pg_pkt) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // The command enumeration + uint8ToBytes((uint8_t)(CMD_ECU_CALIBRATE_PULSE_CLOSED), _pg_data, &_pg_byteindex); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_CalibratePulseClosedPacketID()); + +}// encodeECU_CalibratePulseClosedPacket + +/*! + * \brief Decode the ECU_CalibratePulseClosed packet + * + * Save the current value of the throttle output pulse width to a temporary + * variable in the ECU. When the CALIBRATE_PULSE_WRITE command is sent to the + * ECU, this value will be saved as the 'Closed' pulse width. + * \param _pg_pkt points to the packet being decoded by this function + * \param cmd receives The command enumeration + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_CalibratePulseClosedPacket(const void* _pg_pkt, ECUSystemCommands* cmd) +{ + int _pg_byteindex = 0; + const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt); + int _pg_numbytes = getECUPacketSize(_pg_pkt); + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_CalibratePulseClosedPacketID()) + return 0; + + if(_pg_numbytes < getECU_CalibratePulseClosedMinDataLength()) + return 0; + + // The command enumeration + // Range of cmd is 0 to 255. + // Decoded value must be CMD_ECU_CALIBRATE_PULSE_CLOSED + (*cmd) = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex); + if ((*cmd) != CMD_ECU_CALIBRATE_PULSE_CLOSED) + return 0; + + return 1; + +}// decodeECU_CalibratePulseClosedPacket + +/*! + * \brief Create the ECU_CalibratePulseOpen packet + * + * Save the current value of the throttle output pulse width to a temporary + * variable in the ECU. When the CALIBRATE_PULSE_WRITE command is sent to the + * ECU, this value will be saved as the 'Open' pulse width. + * \param _pg_pkt points to the packet which will be created by this function + */ +void encodeECU_CalibratePulseOpenPacket(void* _pg_pkt) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // The command enumeration + uint8ToBytes((uint8_t)(CMD_ECU_CALIBRATE_PULSE_OPEN), _pg_data, &_pg_byteindex); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_CalibratePulseOpenPacketID()); + +}// encodeECU_CalibratePulseOpenPacket + +/*! + * \brief Decode the ECU_CalibratePulseOpen packet + * + * Save the current value of the throttle output pulse width to a temporary + * variable in the ECU. When the CALIBRATE_PULSE_WRITE command is sent to the + * ECU, this value will be saved as the 'Open' pulse width. + * \param _pg_pkt points to the packet being decoded by this function + * \param cmd receives The command enumeration + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_CalibratePulseOpenPacket(const void* _pg_pkt, ECUSystemCommands* cmd) +{ + int _pg_byteindex = 0; + const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt); + int _pg_numbytes = getECUPacketSize(_pg_pkt); + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_CalibratePulseOpenPacketID()) + return 0; + + if(_pg_numbytes < getECU_CalibratePulseOpenMinDataLength()) + return 0; + + // The command enumeration + // Range of cmd is 0 to 255. + // Decoded value must be CMD_ECU_CALIBRATE_PULSE_OPEN + (*cmd) = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex); + if ((*cmd) != CMD_ECU_CALIBRATE_PULSE_OPEN) + return 0; + + return 1; + +}// decodeECU_CalibratePulseOpenPacket + +/*! + * \brief Create the ECU_CalibratePulseWrite packet + * + * Configure the throttle output positions. The CALIBRATE_PULSE_CLOSED and + * CALIBRATE_PULSE_OPEN commands should have already been sent to the ECU. The + * ECU then saves the temporary values as the 'Closed' and 'Open' throttle + * output values, respectively. + * \param _pg_pkt points to the packet which will be created by this function + */ +void encodeECU_CalibratePulseWritePacket(void* _pg_pkt) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // The command enumeration + uint8ToBytes((uint8_t)(CMD_ECU_CALIBRATE_PULSE_WRITE), _pg_data, &_pg_byteindex); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_CalibratePulseWritePacketID()); + +}// encodeECU_CalibratePulseWritePacket + +/*! + * \brief Decode the ECU_CalibratePulseWrite packet + * + * Configure the throttle output positions. The CALIBRATE_PULSE_CLOSED and + * CALIBRATE_PULSE_OPEN commands should have already been sent to the ECU. The + * ECU then saves the temporary values as the 'Closed' and 'Open' throttle + * output values, respectively. + * \param _pg_pkt points to the packet being decoded by this function + * \param cmd receives The command enumeration + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_CalibratePulseWritePacket(const void* _pg_pkt, ECUSystemCommands* cmd) +{ + int _pg_byteindex = 0; + const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt); + int _pg_numbytes = getECUPacketSize(_pg_pkt); + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_CalibratePulseWritePacketID()) + return 0; + + if(_pg_numbytes < getECU_CalibratePulseWriteMinDataLength()) + return 0; + + // The command enumeration + // Range of cmd is 0 to 255. + // Decoded value must be CMD_ECU_CALIBRATE_PULSE_WRITE + (*cmd) = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex); + if ((*cmd) != CMD_ECU_CALIBRATE_PULSE_WRITE) + return 0; + + return 1; + +}// decodeECU_CalibratePulseWritePacket + +/*! + * \brief Create the ECU_SetOutputDriver packet + * + * Set one of four high-current output drivers. + * \param _pg_pkt points to the packet which will be created by this function + * \param driver is Select driver number (1, 2, 3 or 4) + * \param status is Set driver status (1 = ON, 0 = OFF) + */ +void encodeECU_SetOutputDriverPacket(void* _pg_pkt, uint8_t driver, uint8_t status) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // The command enumeration + uint8ToBytes((uint8_t)(CMD_ECU_SET_OUTPUT_DRIVER), _pg_data, &_pg_byteindex); + + // Select driver number (1, 2, 3 or 4) + // Range of driver is 0 to 255. + uint8ToBytes(driver, _pg_data, &_pg_byteindex); + + // Set driver status (1 = ON, 0 = OFF) + // Range of status is 0 to 255. + uint8ToBytes(status, _pg_data, &_pg_byteindex); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_SetOutputDriverPacketID()); + +}// encodeECU_SetOutputDriverPacket + +/*! + * \brief Decode the ECU_SetOutputDriver packet + * + * Set one of four high-current output drivers. + * \param _pg_pkt points to the packet being decoded by this function + * \param cmd receives The command enumeration + * \param driver receives Select driver number (1, 2, 3 or 4) + * \param status receives Set driver status (1 = ON, 0 = OFF) + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_SetOutputDriverPacket(const void* _pg_pkt, ECUSystemCommands* cmd, uint8_t* driver, uint8_t* status) +{ + int _pg_byteindex = 0; + const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt); + int _pg_numbytes = getECUPacketSize(_pg_pkt); + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_SetOutputDriverPacketID()) + return 0; + + if(_pg_numbytes < getECU_SetOutputDriverMinDataLength()) + return 0; + + // The command enumeration + // Range of cmd is 0 to 255. + // Decoded value must be CMD_ECU_SET_OUTPUT_DRIVER + (*cmd) = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex); + if ((*cmd) != CMD_ECU_SET_OUTPUT_DRIVER) + return 0; + + // Select driver number (1, 2, 3 or 4) + // Range of driver is 0 to 255. + (*driver) = uint8FromBytes(_pg_data, &_pg_byteindex); + + // Set driver status (1 = ON, 0 = OFF) + // Range of status is 0 to 255. + (*status) = uint8FromBytes(_pg_data, &_pg_byteindex); + + return 1; + +}// decodeECU_SetOutputDriverPacket + +/*! + * \brief Create the ECU_SetThrottleCurveActive packet + * + * Turn the throttle linearization curve either on or off. + * \param _pg_pkt points to the packet which will be created by this function + * \param active is Curve active (1 = ON, 0 = OFF) + */ +void encodeECU_SetThrottleCurveActivePacket(void* _pg_pkt, uint8_t active) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // The command enumeration + uint8ToBytes((uint8_t)(CMD_ECU_SET_THROTTLE_CURVE_ACTIVE), _pg_data, &_pg_byteindex); + + // Curve active (1 = ON, 0 = OFF) + // Range of active is 0 to 255. + uint8ToBytes(active, _pg_data, &_pg_byteindex); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_SetThrottleCurveActivePacketID()); + +}// encodeECU_SetThrottleCurveActivePacket + +/*! + * \brief Decode the ECU_SetThrottleCurveActive packet + * + * Turn the throttle linearization curve either on or off. + * \param _pg_pkt points to the packet being decoded by this function + * \param cmd receives The command enumeration + * \param active receives Curve active (1 = ON, 0 = OFF) + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_SetThrottleCurveActivePacket(const void* _pg_pkt, ECUSystemCommands* cmd, uint8_t* active) +{ + int _pg_byteindex = 0; + const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt); + int _pg_numbytes = getECUPacketSize(_pg_pkt); + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_SetThrottleCurveActivePacketID()) + return 0; + + if(_pg_numbytes < getECU_SetThrottleCurveActiveMinDataLength()) + return 0; + + // The command enumeration + // Range of cmd is 0 to 255. + // Decoded value must be CMD_ECU_SET_THROTTLE_CURVE_ACTIVE + (*cmd) = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex); + if ((*cmd) != CMD_ECU_SET_THROTTLE_CURVE_ACTIVE) + return 0; + + // Curve active (1 = ON, 0 = OFF) + // Range of active is 0 to 255. + (*active) = uint8FromBytes(_pg_data, &_pg_byteindex); + + return 1; + +}// decodeECU_SetThrottleCurveActivePacket + +/*! + * \brief Create the ECU_SetThrottleCurveElement packet + * + * Set individual elements in the throttle linearization lookup table. + * \param _pg_pkt points to the packet which will be created by this function + * \param index is Index into the throttle curve table from 0 to 10 (0% to 100%) throttle input + * \param throttleOutput is Percentage throttle output for this curve element + */ +void encodeECU_SetThrottleCurveElementPacket(void* _pg_pkt, uint8_t index, float throttleOutput) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // The command enumeration + uint8ToBytes((uint8_t)(CMD_ECU_SET_THROTTLE_CURVE_ELEMENT), _pg_data, &_pg_byteindex); + + // Index into the throttle curve table from 0 to 10 (0% to 100%) throttle input + // Range of index is 0 to 255. + uint8ToBytes(index, _pg_data, &_pg_byteindex); + + // Percentage throttle output for this curve element + // Range of throttleOutput is 0.0f to 127.5f. + float32ScaledTo1UnsignedBytes(throttleOutput, _pg_data, &_pg_byteindex, 0.0f, 2.0f); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_SetThrottleCurveElementPacketID()); + +}// encodeECU_SetThrottleCurveElementPacket + +/*! + * \brief Decode the ECU_SetThrottleCurveElement packet + * + * Set individual elements in the throttle linearization lookup table. + * \param _pg_pkt points to the packet being decoded by this function + * \param cmd receives The command enumeration + * \param index receives Index into the throttle curve table from 0 to 10 (0% to 100%) throttle input + * \param throttleOutput receives Percentage throttle output for this curve element + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_SetThrottleCurveElementPacket(const void* _pg_pkt, ECUSystemCommands* cmd, uint8_t* index, float* throttleOutput) +{ + int _pg_byteindex = 0; + const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt); + int _pg_numbytes = getECUPacketSize(_pg_pkt); + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_SetThrottleCurveElementPacketID()) + return 0; + + if(_pg_numbytes < getECU_SetThrottleCurveElementMinDataLength()) + return 0; + + // The command enumeration + // Range of cmd is 0 to 255. + // Decoded value must be CMD_ECU_SET_THROTTLE_CURVE_ELEMENT + (*cmd) = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex); + if ((*cmd) != CMD_ECU_SET_THROTTLE_CURVE_ELEMENT) + return 0; + + // Index into the throttle curve table from 0 to 10 (0% to 100%) throttle input + // Range of index is 0 to 255. + (*index) = uint8FromBytes(_pg_data, &_pg_byteindex); + + // Percentage throttle output for this curve element + // Range of throttleOutput is 0.0f to 127.5f. + (*throttleOutput) = float32ScaledFrom1UnsignedBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/2.0f); + + return 1; + +}// decodeECU_SetThrottleCurveElementPacket + +/*! + * \brief Create the ECU_RequestThrottleCurveData packet + * + * Request the throttle curve lookup table data. If requested on CAN, the data + * will be returned on CAN. If requested on RS232, the data will be returned on + * RS232. + * \param _pg_pkt points to the packet which will be created by this function + */ +void encodeECU_RequestThrottleCurveDataPacket(void* _pg_pkt) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // The command enumeration + uint8ToBytes((uint8_t)(CMD_ECU_REQUEST_THROTTLE_CURVE_DATA), _pg_data, &_pg_byteindex); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_RequestThrottleCurveDataPacketID()); + +}// encodeECU_RequestThrottleCurveDataPacket + +/*! + * \brief Decode the ECU_RequestThrottleCurveData packet + * + * Request the throttle curve lookup table data. If requested on CAN, the data + * will be returned on CAN. If requested on RS232, the data will be returned on + * RS232. + * \param _pg_pkt points to the packet being decoded by this function + * \param cmd receives The command enumeration + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_RequestThrottleCurveDataPacket(const void* _pg_pkt, ECUSystemCommands* cmd) +{ + int _pg_byteindex = 0; + const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt); + int _pg_numbytes = getECUPacketSize(_pg_pkt); + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_RequestThrottleCurveDataPacketID()) + return 0; + + if(_pg_numbytes < getECU_RequestThrottleCurveDataMinDataLength()) + return 0; + + // The command enumeration + // Range of cmd is 0 to 255. + // Decoded value must be CMD_ECU_REQUEST_THROTTLE_CURVE_DATA + (*cmd) = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex); + if ((*cmd) != CMD_ECU_REQUEST_THROTTLE_CURVE_DATA) + return 0; + + return 1; + +}// decodeECU_RequestThrottleCurveDataPacket + +/*! + * \brief Create the ECU_ResetFuelUsed packet + * + * Reset the FuelUsed value. This will set the FuelUsed data to zero. + * \param _pg_pkt points to the packet which will be created by this function + */ +void encodeECU_ResetFuelUsedPacket(void* _pg_pkt) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // The command enumeration + uint8ToBytes((uint8_t)(CMD_ECU_RESET_FUEL_USED), _pg_data, &_pg_byteindex); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_ResetFuelUsedPacketID()); + +}// encodeECU_ResetFuelUsedPacket + +/*! + * \brief Decode the ECU_ResetFuelUsed packet + * + * Reset the FuelUsed value. This will set the FuelUsed data to zero. + * \param _pg_pkt points to the packet being decoded by this function + * \param cmd receives The command enumeration + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_ResetFuelUsedPacket(const void* _pg_pkt, ECUSystemCommands* cmd) +{ + int _pg_byteindex = 0; + const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt); + int _pg_numbytes = getECUPacketSize(_pg_pkt); + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_ResetFuelUsedPacketID()) + return 0; + + if(_pg_numbytes < getECU_ResetFuelUsedMinDataLength()) + return 0; + + // The command enumeration + // Range of cmd is 0 to 255. + // Decoded value must be CMD_ECU_RESET_FUEL_USED + (*cmd) = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex); + if ((*cmd) != CMD_ECU_RESET_FUEL_USED) + return 0; + + return 1; + +}// decodeECU_ResetFuelUsedPacket + +/*! + * \brief Create the ECU_SetFuelUsedDivisor packet + * + * Set the fuel used divisor + * \param _pg_pkt points to the packet which will be created by this function + * \param divisor is The fuel used divisor. The fuel used value is divided by this divisor before being transmitted by the auxiliary processor. Set this value to 1 to leave the fuel used data unaffected. If you use values greater than 100 the divisor is automatically interpreted as being in units of 0.01 (i.e. 100 times the resolution). + */ +void encodeECU_SetFuelUsedDivisorPacket(void* _pg_pkt, uint16_t divisor) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // The command enumeration + uint8ToBytes((uint8_t)(CMD_ECU_SET_FUEL_USED_DIVISOR), _pg_data, &_pg_byteindex); + + // The fuel used divisor. The fuel used value is divided by this divisor before being transmitted by the auxiliary processor. Set this value to 1 to leave the fuel used data unaffected. If you use values greater than 100 the divisor is automatically interpreted as being in units of 0.01 (i.e. 100 times the resolution). + // Range of divisor is 0 to 65535. + uint16ToBeBytes(divisor, _pg_data, &_pg_byteindex); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_SetFuelUsedDivisorPacketID()); + +}// encodeECU_SetFuelUsedDivisorPacket + +/*! + * \brief Decode the ECU_SetFuelUsedDivisor packet + * + * Set the fuel used divisor + * \param _pg_pkt points to the packet being decoded by this function + * \param cmd receives The command enumeration + * \param divisor receives The fuel used divisor. The fuel used value is divided by this divisor before being transmitted by the auxiliary processor. Set this value to 1 to leave the fuel used data unaffected. If you use values greater than 100 the divisor is automatically interpreted as being in units of 0.01 (i.e. 100 times the resolution). + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_SetFuelUsedDivisorPacket(const void* _pg_pkt, ECUSystemCommands* cmd, uint16_t* divisor) +{ + int _pg_byteindex = 0; + const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt); + int _pg_numbytes = getECUPacketSize(_pg_pkt); + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_SetFuelUsedDivisorPacketID()) + return 0; + + if(_pg_numbytes < getECU_SetFuelUsedDivisorMinDataLength()) + return 0; + + // The command enumeration + // Range of cmd is 0 to 255. + // Decoded value must be CMD_ECU_SET_FUEL_USED_DIVISOR + (*cmd) = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex); + if ((*cmd) != CMD_ECU_SET_FUEL_USED_DIVISOR) + return 0; + + // The fuel used divisor. The fuel used value is divided by this divisor before being transmitted by the auxiliary processor. Set this value to 1 to leave the fuel used data unaffected. If you use values greater than 100 the divisor is automatically interpreted as being in units of 0.01 (i.e. 100 times the resolution). + // Range of divisor is 0 to 65535. + (*divisor) = uint16FromBeBytes(_pg_data, &_pg_byteindex); + + return 1; + +}// decodeECU_SetFuelUsedDivisorPacket + +/*! + * \brief Create the ECU_SetFuelUsedResetFlag packet + * + * Set or clear the Fuel Used reset flag. If this flag is set, the FuelUsed + * data will reset (to zero) when the ECU is power cycled. + * \param _pg_pkt points to the packet which will be created by this function + * \param reset is 1 = Reset Fuel Used data on powerup 0 = Do not reset Fuel Used data on power up + */ +void encodeECU_SetFuelUsedResetFlagPacket(void* _pg_pkt, uint8_t reset) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // The command enumeration + uint8ToBytes((uint8_t)(CMD_ECU_FUEL_USED_RESET_ON_STARTUP), _pg_data, &_pg_byteindex); + + // 1 = Reset Fuel Used data on powerup 0 = Do not reset Fuel Used data on power up + // Range of reset is 0 to 255. + uint8ToBytes(reset, _pg_data, &_pg_byteindex); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_SetFuelUsedResetFlagPacketID()); + +}// encodeECU_SetFuelUsedResetFlagPacket + +/*! + * \brief Decode the ECU_SetFuelUsedResetFlag packet + * + * Set or clear the Fuel Used reset flag. If this flag is set, the FuelUsed + * data will reset (to zero) when the ECU is power cycled. + * \param _pg_pkt points to the packet being decoded by this function + * \param cmd receives The command enumeration + * \param reset receives 1 = Reset Fuel Used data on powerup 0 = Do not reset Fuel Used data on power up + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_SetFuelUsedResetFlagPacket(const void* _pg_pkt, ECUSystemCommands* cmd, uint8_t* reset) +{ + int _pg_byteindex = 0; + const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt); + int _pg_numbytes = getECUPacketSize(_pg_pkt); + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_SetFuelUsedResetFlagPacketID()) + return 0; + + if(_pg_numbytes < getECU_SetFuelUsedResetFlagMinDataLength()) + return 0; + + // The command enumeration + // Range of cmd is 0 to 255. + // Decoded value must be CMD_ECU_FUEL_USED_RESET_ON_STARTUP + (*cmd) = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex); + if ((*cmd) != CMD_ECU_FUEL_USED_RESET_ON_STARTUP) + return 0; + + // 1 = Reset Fuel Used data on powerup 0 = Do not reset Fuel Used data on power up + // Range of reset is 0 to 255. + (*reset) = uint8FromBytes(_pg_data, &_pg_byteindex); + + return 1; + +}// decodeECU_SetFuelUsedResetFlagPacket + +/*! + * \brief Create the ECU_SetGovernorMode packet + * + * Manually set the RPM governor mode. + * \param _pg_pkt points to the packet which will be created by this function + * \param mode is MODE 0 = Governor Off (Open loop throttle control) 1 = Governor based on throttle command 2 = Governor based on RPM command + */ +void encodeECU_SetGovernorModePacket(void* _pg_pkt, ECUGovernorMode mode) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // The command enumeration + uint8ToBytes((uint8_t)(CMD_ECU_SET_GOVERNOR_MODE), _pg_data, &_pg_byteindex); + + // MODE 0 = Governor Off (Open loop throttle control) 1 = Governor based on throttle command 2 = Governor based on RPM command + // Range of mode is 0 to 255. + uint8ToBytes(mode, _pg_data, &_pg_byteindex); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_SetGovernorModePacketID()); + +}// encodeECU_SetGovernorModePacket + +/*! + * \brief Decode the ECU_SetGovernorMode packet + * + * Manually set the RPM governor mode. + * \param _pg_pkt points to the packet being decoded by this function + * \param cmd receives The command enumeration + * \param mode receives MODE 0 = Governor Off (Open loop throttle control) 1 = Governor based on throttle command 2 = Governor based on RPM command + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_SetGovernorModePacket(const void* _pg_pkt, ECUSystemCommands* cmd, ECUGovernorMode* mode) +{ + int _pg_byteindex = 0; + const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt); + int _pg_numbytes = getECUPacketSize(_pg_pkt); + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_SetGovernorModePacketID()) + return 0; + + if(_pg_numbytes < getECU_SetGovernorModeMinDataLength()) + return 0; + + // The command enumeration + // Range of cmd is 0 to 255. + // Decoded value must be CMD_ECU_SET_GOVERNOR_MODE + (*cmd) = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex); + if ((*cmd) != CMD_ECU_SET_GOVERNOR_MODE) + return 0; + + // MODE 0 = Governor Off (Open loop throttle control) 1 = Governor based on throttle command 2 = Governor based on RPM command + // Range of mode is 0 to 255. + (*mode) = (ECUGovernorMode)uint8FromBytes(_pg_data, &_pg_byteindex); + + return 1; + +}// decodeECU_SetGovernorModePacket + +/*! + * \brief Create the ECU_SetSerialMode packet + * + * Set the serial mode used for Autronic relay. When Autronic relay is enabled + * the external serial port of the ECU is reconfigured to connect to ECUCal, + * relaying bytes to the internal autronic processor; while still allowing the + * auxiliary processor to see telemetry from Autronic. This is fundamentally + * different from using the switch to calibration mode, which bypasses the + * auxiliary processor altogether, cutting it off from autronic telemetry. + * \param _pg_pkt points to the packet which will be created by this function + * \param mode is The serial relay mode to command + */ +void encodeECU_SetSerialModePacket(void* _pg_pkt, ECUAutronicRelayState mode) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // The command enumeration + uint8ToBytes((uint8_t)(CMD_ECU_SET_SERIAL_MODE), _pg_data, &_pg_byteindex); + + // The serial relay mode to command + // Range of mode is 0 to 255. + uint8ToBytes(mode, _pg_data, &_pg_byteindex); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_SetSerialModePacketID()); + +}// encodeECU_SetSerialModePacket + +/*! + * \brief Decode the ECU_SetSerialMode packet + * + * Set the serial mode used for Autronic relay. When Autronic relay is enabled + * the external serial port of the ECU is reconfigured to connect to ECUCal, + * relaying bytes to the internal autronic processor; while still allowing the + * auxiliary processor to see telemetry from Autronic. This is fundamentally + * different from using the switch to calibration mode, which bypasses the + * auxiliary processor altogether, cutting it off from autronic telemetry. + * \param _pg_pkt points to the packet being decoded by this function + * \param cmd receives The command enumeration + * \param mode receives The serial relay mode to command + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_SetSerialModePacket(const void* _pg_pkt, ECUSystemCommands* cmd, ECUAutronicRelayState* mode) +{ + int _pg_byteindex = 0; + const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt); + int _pg_numbytes = getECUPacketSize(_pg_pkt); + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_SetSerialModePacketID()) + return 0; + + if(_pg_numbytes < getECU_SetSerialModeMinDataLength()) + return 0; + + // The command enumeration + // Range of cmd is 0 to 255. + // Decoded value must be CMD_ECU_SET_SERIAL_MODE + (*cmd) = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex); + if ((*cmd) != CMD_ECU_SET_SERIAL_MODE) + return 0; + + // The serial relay mode to command + // Range of mode is 0 to 255. + (*mode) = (ECUAutronicRelayState)uint8FromBytes(_pg_data, &_pg_byteindex); + + return 1; + +}// decodeECU_SetSerialModePacket + +/*! + * \brief Create the ECU_SetECUAddress packet + * + * Set a custom address value for the ECU. + * \param _pg_pkt points to the packet which will be created by this function + * \param address is ECU address in the range {1, 65534} + */ +void encodeECU_SetECUAddressPacket(void* _pg_pkt, uint16_t address) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // The command enumeration + uint8ToBytes((uint8_t)(CMD_ECU_SET_NODE_ID), _pg_data, &_pg_byteindex); + + // ECU address in the range {1, 65534} + // Range of address is 0 to 65535. + uint16ToBeBytes(address, _pg_data, &_pg_byteindex); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_SetECUAddressPacketID()); + +}// encodeECU_SetECUAddressPacket + +/*! + * \brief Decode the ECU_SetECUAddress packet + * + * Set a custom address value for the ECU. + * \param _pg_pkt points to the packet being decoded by this function + * \param cmd receives The command enumeration + * \param address receives ECU address in the range {1, 65534} + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_SetECUAddressPacket(const void* _pg_pkt, ECUSystemCommands* cmd, uint16_t* address) +{ + int _pg_byteindex = 0; + const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt); + int _pg_numbytes = getECUPacketSize(_pg_pkt); + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_SetECUAddressPacketID()) + return 0; + + if(_pg_numbytes < getECU_SetECUAddressMinDataLength()) + return 0; + + // The command enumeration + // Range of cmd is 0 to 255. + // Decoded value must be CMD_ECU_SET_NODE_ID + (*cmd) = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex); + if ((*cmd) != CMD_ECU_SET_NODE_ID) + return 0; + + // ECU address in the range {1, 65534} + // Range of address is 0 to 65535. + (*address) = uint16FromBeBytes(_pg_data, &_pg_byteindex); + + return 1; + +}// decodeECU_SetECUAddressPacket + +/*! + * \brief Create the ECU_SetUserData packet + * + * Save a single byte of USER_DATA in EEPROM. + * \param _pg_pkt points to the packet which will be created by this function + * \param index is USER_DATA address (0 to 7) + * \param userdata is USER_DATA variable + */ +void encodeECU_SetUserDataPacket(void* _pg_pkt, uint8_t index, uint8_t userdata) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // The command enumeration + uint8ToBytes((uint8_t)(CMD_ECU_SET_USER_DATA), _pg_data, &_pg_byteindex); + + // USER_DATA address (0 to 7) + // Range of index is 0 to 255. + uint8ToBytes(index, _pg_data, &_pg_byteindex); + + // USER_DATA variable + // Range of userdata is 0 to 255. + uint8ToBytes(userdata, _pg_data, &_pg_byteindex); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_SetUserDataPacketID()); + +}// encodeECU_SetUserDataPacket + +/*! + * \brief Decode the ECU_SetUserData packet + * + * Save a single byte of USER_DATA in EEPROM. + * \param _pg_pkt points to the packet being decoded by this function + * \param cmd receives The command enumeration + * \param index receives USER_DATA address (0 to 7) + * \param userdata receives USER_DATA variable + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_SetUserDataPacket(const void* _pg_pkt, ECUSystemCommands* cmd, uint8_t* index, uint8_t* userdata) +{ + int _pg_byteindex = 0; + const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt); + int _pg_numbytes = getECUPacketSize(_pg_pkt); + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_SetUserDataPacketID()) + return 0; + + if(_pg_numbytes < getECU_SetUserDataMinDataLength()) + return 0; + + // The command enumeration + // Range of cmd is 0 to 255. + // Decoded value must be CMD_ECU_SET_USER_DATA + (*cmd) = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex); + if ((*cmd) != CMD_ECU_SET_USER_DATA) + return 0; + + // USER_DATA address (0 to 7) + // Range of index is 0 to 255. + (*index) = uint8FromBytes(_pg_data, &_pg_byteindex); + + // USER_DATA variable + // Range of userdata is 0 to 255. + (*userdata) = uint8FromBytes(_pg_data, &_pg_byteindex); + + return 1; + +}// decodeECU_SetUserDataPacket + +/*! + * \brief Create the ECU_ResetEngineTime packet + * + * Reset the engine runtime. + * \param _pg_pkt points to the packet which will be created by this function + * \param time is The new value of the engine time counter in seconds + */ +void encodeECU_ResetEngineTimePacket(void* _pg_pkt, uint32_t time) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // The command enumeration + uint8ToBytes((uint8_t)(CMD_ECU_RESET_ENGINE_TIME), _pg_data, &_pg_byteindex); + + // The new value of the engine time counter in seconds + // Range of time is 0 to 16777215. + uint24ToBeBytes((uint32_t)(limitMax(time, 16777215)), _pg_data, &_pg_byteindex); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_ResetEngineTimePacketID()); + +}// encodeECU_ResetEngineTimePacket + +/*! + * \brief Decode the ECU_ResetEngineTime packet + * + * Reset the engine runtime. + * \param _pg_pkt points to the packet being decoded by this function + * \param cmd receives The command enumeration + * \param time receives The new value of the engine time counter in seconds + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_ResetEngineTimePacket(const void* _pg_pkt, ECUSystemCommands* cmd, uint32_t* time) +{ + int _pg_byteindex = 0; + const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt); + int _pg_numbytes = getECUPacketSize(_pg_pkt); + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_ResetEngineTimePacketID()) + return 0; + + if(_pg_numbytes < getECU_ResetEngineTimeMinDataLength()) + return 0; + + // this packet has default fields, make sure they are set + (*time) = 0; + + // The command enumeration + // Range of cmd is 0 to 255. + // Decoded value must be CMD_ECU_RESET_ENGINE_TIME + (*cmd) = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex); + if ((*cmd) != CMD_ECU_RESET_ENGINE_TIME) + return 0; + + if(_pg_byteindex + 3 > _pg_numbytes) + return 1; + + // The new value of the engine time counter in seconds + // Range of time is 0 to 16777215. + (*time) = (uint32_t)uint24FromBeBytes(_pg_data, &_pg_byteindex); + + return 1; + +}// decodeECU_ResetEngineTimePacket + +/*! + * \brief Create the ECU_ResetECU packet + * + * Reset the ECU + * \param _pg_pkt points to the packet which will be created by this function + */ +void encodeECU_ResetECUPacket(void* _pg_pkt) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // The command enumeration + uint8ToBytes((uint8_t)(CMD_ECU_RESET_ECU), _pg_data, &_pg_byteindex); + + // Required constant value + uint8ToBytes((uint8_t)(0xA5), _pg_data, &_pg_byteindex); + + // Required constant value + uint8ToBytes((uint8_t)(0x5A), _pg_data, &_pg_byteindex); + + // Required constant value + uint8ToBytes((uint8_t)(0xCC), _pg_data, &_pg_byteindex); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_ResetECUPacketID()); + +}// encodeECU_ResetECUPacket + +/*! + * \brief Decode the ECU_ResetECU packet + * + * Reset the ECU + * \param _pg_pkt points to the packet being decoded by this function + * \param cmd receives The command enumeration + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_ResetECUPacket(const void* _pg_pkt, ECUSystemCommands* cmd) +{ + int _pg_byteindex = 0; + const uint8_t* _pg_data = getECUPacketDataConst(_pg_pkt); + int _pg_numbytes = getECUPacketSize(_pg_pkt); + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_ResetECUPacketID()) + return 0; + + if(_pg_numbytes < getECU_ResetECUMinDataLength()) + return 0; + + // The command enumeration + // Range of cmd is 0 to 255. + // Decoded value must be CMD_ECU_RESET_ECU + (*cmd) = (ECUSystemCommands)uint8FromBytes(_pg_data, &_pg_byteindex); + if ((*cmd) != CMD_ECU_RESET_ECU) + return 0; + + // Required constant value + if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) 0xA5) + return 0; + + // Required constant value + if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) 0x5A) + return 0; + + // Required constant value + if (uint8FromBytes(_pg_data, &_pg_byteindex) != (uint8_t) 0xCC) + return 0; + + return 1; + +}// decodeECU_ResetECUPacket +// end of ECUPackets.c diff --git a/libraries/AP_PiccoloCAN/piccolo_protocol/ECUPackets.h b/libraries/AP_PiccoloCAN/piccolo_protocol/ECUPackets.h new file mode 100644 index 00000000000..1bdf0e9c264 --- /dev/null +++ b/libraries/AP_PiccoloCAN/piccolo_protocol/ECUPackets.h @@ -0,0 +1,1242 @@ +// ECUPackets.h was generated by ProtoGen version 3.2.a + +/* + * This file is free software: you can redistribute it and/or modify it + * under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program. If not, see . + * + * Author: Oliver Walters / Currawong Engineering Pty Ltd + */ + + +#ifndef _ECUPACKETS_H +#define _ECUPACKETS_H + +// Language target is C, C++ compilers: don't mangle us +#ifdef __cplusplus +extern "C" { +#endif + +/*! + * \file + */ + +#include +#include "ECUProtocol.h" +#include "ECUDefines.h" +#include "ECUSettings.h" + +/*! + * The throttle command packet sets the throttle position setpoint. The ECU + * will adjust the throttle position based on this command. + */ +typedef struct +{ + float throttleCommand; //!< Commanded throttle position in percent +}ECU_ThrottleCommand_t; + +//! Create the ECU_ThrottleCommand packet from parameters +void encodeECU_ThrottleCommandPacket(void* pkt, float throttleCommand); + +//! Decode the ECU_ThrottleCommand packet to parameters +int decodeECU_ThrottleCommandPacket(const void* pkt, float* throttleCommand); + +//! return the packet ID for the ECU_ThrottleCommand packet +#define getECU_ThrottleCommandPacketID() (PKT_ECU_THROTTLE) + +//! return the minimum encoded length for the ECU_ThrottleCommand packet +#define getECU_ThrottleCommandMinDataLength() (2) + +//! return the maximum encoded length for the ECU_ThrottleCommand packet +#define getECU_ThrottleCommandMaxDataLength() (2) + +/*! + * The RPM command is used to send a target to the RPM governor on the ECU. + * Based on this command, the ECU will use a feedback loop to maintain the + * commanded engine speed by adjusting the throttle servo accordingly. If a + * valid RPM command is received by the ECU, it will automatically enter RPM + * control mode, and adjust the throttle position to match the desired RPM. + * Sending a throttle command will cause the ECU to stop the RPM loop and enter + * open-loop throttle control mode. + */ +typedef struct +{ + uint16_t rpmCmd; //!< Engine speed command in revolutions per minute + uint8_t rpmCmdHigh; //!< RPM command in units of 50 RPM + uint8_t rpmCmdLow; //!< Low part of RPM command from 0 to 49 +}ECU_RPMCommand_t; + +//! Create the ECU_RPMCommand packet +void encodeECU_RPMCommandPacketStructure(void* pkt, const ECU_RPMCommand_t* user); + +//! Decode the ECU_RPMCommand packet +int decodeECU_RPMCommandPacketStructure(const void* pkt, ECU_RPMCommand_t* user); + +//! return the packet ID for the ECU_RPMCommand packet +#define getECU_RPMCommandPacketID() (PKT_ECU_RPM_COMMAND) + +//! return the minimum encoded length for the ECU_RPMCommand packet +#define getECU_RPMCommandMinDataLength() (2) + +//! return the maximum encoded length for the ECU_RPMCommand packet +#define getECU_RPMCommandMaxDataLength() (2) + +typedef struct +{ + bool driverPin8; //!< 1 if driver 8 is on + bool driverPin7; //!< 1 if driver 7 is on + bool driverPin2; //!< 1 if driver 2 is on + bool driverPin1; //!< 1 if driver 1 is on + bool throttleCurveOn; //!< 1 if the throttle curve is on. + bool rs232mode; //!< 1 if autronic, else auxiliary. + bool errorIndicator; //!< 1 if any errors are set - refer to [error packet](#PKT_ECU_ERROR_MSG) + bool enabled; //!< Global enable based on physical input +}ECU_ecuStatusBits_t; + +/*! + * Fast telemetry contains high priority telemetry data and is transmitted at a + * user configurable period between 50ms (20Hz) and 10s. By default, the fast + * telemetry message is transmitted at 10Hz (every 100ms) + */ +typedef struct +{ + float throttle; //!< Throttle signal (0 to 100%) + uint16_t rpm; //!< Engine speed in revolutions per minute + uint32_t fuelUsed; //!< Fuel used in grams + ECU_ecuStatusBits_t ecuStatusBits; +}ECU_TelemetryFast_t; + +//! Encode a ECU_ecuStatusBits_t into a byte array +void encodeECU_ecuStatusBits_t(uint8_t* data, int* bytecount, const ECU_ecuStatusBits_t* user); + +//! Decode a ECU_ecuStatusBits_t from a byte array +int decodeECU_ecuStatusBits_t(const uint8_t* data, int* bytecount, ECU_ecuStatusBits_t* user); + +//! Create the ECU_TelemetryFast packet +void encodeECU_TelemetryFastPacketStructure(void* pkt, const ECU_TelemetryFast_t* user); + +//! Decode the ECU_TelemetryFast packet +int decodeECU_TelemetryFastPacketStructure(const void* pkt, ECU_TelemetryFast_t* user); + +//! Create the ECU_TelemetryFast packet from parameters +void encodeECU_TelemetryFastPacket(void* pkt, float throttle, uint16_t rpm, uint32_t fuelUsed, const ECU_ecuStatusBits_t* ecuStatusBits); + +//! Decode the ECU_TelemetryFast packet to parameters +int decodeECU_TelemetryFastPacket(const void* pkt, float* throttle, uint16_t* rpm, uint32_t* fuelUsed, ECU_ecuStatusBits_t* ecuStatusBits); + +//! return the packet ID for the ECU_TelemetryFast packet +#define getECU_TelemetryFastPacketID() (PKT_ECU_TELEMETRY_FAST) + +//! return the minimum encoded length for the ECU_TelemetryFast packet +#define getECU_TelemetryFastMinDataLength() (8) + +//! return the maximum encoded length for the ECU_TelemetryFast packet +#define getECU_TelemetryFastMaxDataLength() (8) + +/*! + * This is the first of three slower telemetry packets which are transmitted by + * the ECU at a user customizable period (between 0.5s and 10.0s). These three + * packets contain data that is not likely to change as quickly as the data in + * the fast telemetry packet. By default, the slow telemetry messages are + * transmitted at 1Hz (period of 1.0s). + */ +typedef struct +{ + uint16_t rpmCmd; //!< The reconstructed RPM command + float map; //!< The reconstructed manifold pressure in kilo-Pascals + ECUThrottleSource throttleSrc; //!< Source of the throttle information + uint16_t throttlePulse; //!< Throttle pulse width in microseconds + float cht; //!< Cylinder head temperature in Celsius + float baro; //!< Barometric pressure in kilo-Pascals +}ECU_TelemetrySlow0_t; + +//! Create the ECU_TelemetrySlow0 packet +void encodeECU_TelemetrySlow0PacketStructure(void* pkt, const ECU_TelemetrySlow0_t* user); + +//! Decode the ECU_TelemetrySlow0 packet +int decodeECU_TelemetrySlow0PacketStructure(const void* pkt, ECU_TelemetrySlow0_t* user); + +//! return the packet ID for the ECU_TelemetrySlow0 packet +#define getECU_TelemetrySlow0PacketID() (PKT_ECU_TELEMETRY_SLOW_0) + +//! return the minimum encoded length for the ECU_TelemetrySlow0 packet +#define getECU_TelemetrySlow0MinDataLength() (8) + +//! return the maximum encoded length for the ECU_TelemetrySlow0 packet +#define getECU_TelemetrySlow0MaxDataLength() (8) + +/*! + * ECU RPM governor mode enumeration + */ +typedef enum +{ + ECU_GOV_MODE_NONE, //!< RPM governor is off + ECU_GOV_MODE_THROTTLE,//!< RPM governer setpoint is based on throttle input + ECU_GOV_MODE_DIRECT //!< RPM governor setpoint comes from direct command +} ECUGovernorMode; + +/*! + * The second of three slow telemetry packets + */ +typedef struct +{ + float mat; //!< Inlet air temperature in Celsius + float fuelPressure; //!< Fuel pressure in kilo-Pascals + uint32_t hobbs; //!< Engine run time in seconds. + float voltage; //!< Input voltage in Volts + ECUGovernorMode governorMode; //!< Operational mode of the governor +}ECU_TelemetrySlow1_t; + +//! Create the ECU_TelemetrySlow1 packet +void encodeECU_TelemetrySlow1PacketStructure(void* pkt, const ECU_TelemetrySlow1_t* user); + +//! Decode the ECU_TelemetrySlow1 packet +int decodeECU_TelemetrySlow1PacketStructure(const void* pkt, ECU_TelemetrySlow1_t* user); + +//! return the packet ID for the ECU_TelemetrySlow1 packet +#define getECU_TelemetrySlow1PacketID() (PKT_ECU_TELEMETRY_SLOW_1) + +//! return the minimum encoded length for the ECU_TelemetrySlow1 packet +#define getECU_TelemetrySlow1MinDataLength() (8) + +//! return the maximum encoded length for the ECU_TelemetrySlow1 packet +#define getECU_TelemetrySlow1MaxDataLength() (8) + +/*! + * The third of three slow telemetry packets + */ +typedef struct +{ + float cpuLoad; //!< CPU load in percent + float chargeTemp; //!< Charge temperature in Celsius + float injectorDuty; //!< Injector duty cycle in percent + float ignAngle1; //!< First ignition advance angle in degrees + float ignAngle2; //!< Second ignition advance angle in degrees + float flowRate; //!< Fuel flow rate in grams per minute +}ECU_TelemetrySlow2_t; + +//! Create the ECU_TelemetrySlow2 packet +void encodeECU_TelemetrySlow2PacketStructure(void* pkt, const ECU_TelemetrySlow2_t* user); + +//! Decode the ECU_TelemetrySlow2 packet +int decodeECU_TelemetrySlow2PacketStructure(const void* pkt, ECU_TelemetrySlow2_t* user); + +//! return the packet ID for the ECU_TelemetrySlow2 packet +#define getECU_TelemetrySlow2PacketID() (PKT_ECU_TELEMETRY_SLOW_2) + +//! return the minimum encoded length for the ECU_TelemetrySlow2 packet +#define getECU_TelemetrySlow2MinDataLength() (8) + +//! return the maximum encoded length for the ECU_TelemetrySlow2 packet +#define getECU_TelemetrySlow2MaxDataLength() (8) + +/*! + * Enumeration of auxiliary to autronic serial relay states. Autronic relay is + * an advanced feature used to allow simultaneous connection of the Autronic + * ECUCal software and the auxiliary processor. Autronic relay should only be + * needed for engine development. + */ +typedef enum +{ + AUT_RELAY_OFF, //!< Relay is disengaged, 19200 autronic interface rate; must use calibration switch to connect to Autronic + AUT_RELAY_PENDING,//!< Relay enabled but not detected, 19200 autronic and external serial interface rate + AUT_RELAY_ON //!< Relay detected, 38400 autronic and external serial interface rate +} ECUAutronicRelayState; + +/*! + * The hardware config packet contains the ECU serial number and various ECU + * configuration data. Send a zero length packet to request this data. + */ +typedef struct +{ + uint16_t serialNumber; //!< ECU serial number + uint16_t fuelDivisor; //!< Fuel used divisior. If the divisor is greater than 100 then it is interpreted as units of 0.01 (for a higher resolution fuel calibration) + ECUAutronicRelayState relayState; //!< Autronic relay state. This is a volatile status which will reset to AUT_RELAY_OFF on ECU power cycle. + bool resetFuelUsedOnStart; //!< Set if the fuel used value is reset each on each ECU power cycle +}ECU_HardwareConfig_t; + +//! Create the ECU_HardwareConfig packet +void encodeECU_HardwareConfigPacketStructure(void* pkt, const ECU_HardwareConfig_t* user); + +//! Decode the ECU_HardwareConfig packet +int decodeECU_HardwareConfigPacketStructure(const void* pkt, ECU_HardwareConfig_t* user); + +//! return the packet ID for the ECU_HardwareConfig packet +#define getECU_HardwareConfigPacketID() (PKT_ECU_HARDWARE_CONFIG) + +//! return the minimum encoded length for the ECU_HardwareConfig packet +#define getECU_HardwareConfigMinDataLength() (5) + +//! return the maximum encoded length for the ECU_HardwareConfig packet +#define getECU_HardwareConfigMaxDataLength() (5) + +/*! + * The software version packet contains the auxiliary processor firmware + * version information. Send a zero length packet to request this data. + */ +typedef struct +{ + bool release; //!< 1 = Release version, 0 = Testing version + unsigned versionMajor : 6; //!< Major version number + uint8_t versionMinor; //!< Minor version number + uint8_t versionRev; //!< Revision number + uint8_t month; //!< The release month from 1 (January) to 12 (December) + uint8_t day; //!< The release day of month from 1 to 31 + uint16_t year; //!< The release year + uint16_t checksum; //!< Firmware checksum +}ECU_Version_t; + +//! Create the ECU_Version packet +void encodeECU_VersionPacketStructure(void* pkt, const ECU_Version_t* user); + +//! Decode the ECU_Version packet +int decodeECU_VersionPacketStructure(const void* pkt, ECU_Version_t* user); + +//! return the packet ID for the ECU_Version packet +#define getECU_VersionPacketID() (PKT_ECU_SOFTWARE_VERSION) + +//! return the minimum encoded length for the ECU_Version packet +#define getECU_VersionMinDataLength() (8) + +//! return the maximum encoded length for the ECU_Version packet +#define getECU_VersionMaxDataLength() (8) + +/*! + * The errors packet contains error status information for the ECU. If any + * error bits are set, then the global error bit in the [fast + * telemetry](#PKT_ECU_TELEMETRY_FAST) packet will also be set. Send a zero + * length packet to request this data. + */ +typedef struct +{ + ECU_AutronicErrorBits_t autronicErrors; //!< Error bits for the Autronic processor + ECU_AuxiliaryErrorBits_t auxiliaryErrors; //!< Error bits for the auxiliary processor +}ECU_Errors_t; + +//! Create the ECU_Errors packet +void encodeECU_ErrorsPacketStructure(void* pkt, const ECU_Errors_t* user); + +//! Decode the ECU_Errors packet +int decodeECU_ErrorsPacketStructure(const void* pkt, ECU_Errors_t* user); + +//! return the packet ID for the ECU_Errors packet +#define getECU_ErrorsPacketID() (PKT_ECU_ERROR_MSG) + +//! return the minimum encoded length for the ECU_Errors packet +#define getECU_ErrorsMinDataLength() (8) + +//! return the maximum encoded length for the ECU_Errors packet +#define getECU_ErrorsMaxDataLength() (8) + +/*! + * The power cycles packet contains information on the reset condition of the + * ECU. Send a zero length packet to request this data. + */ +typedef struct +{ + uint16_t powerCycles; //!< Number of power cycles + uint8_t reserved; + uint8_t resetCode; //!< Auxiliary processor reset code + uint32_t systemTime; //!< Milliseconds since system reset +}ECU_PowerCycles_t; + +//! Create the ECU_PowerCycles packet +void encodeECU_PowerCyclesPacketStructure(void* pkt, const ECU_PowerCycles_t* user); + +//! Decode the ECU_PowerCycles packet +int decodeECU_PowerCyclesPacketStructure(const void* pkt, ECU_PowerCycles_t* user); + +//! return the packet ID for the ECU_PowerCycles packet +#define getECU_PowerCyclesPacketID() (PKT_ECU_POWER_CYCLES) + +//! return the minimum encoded length for the ECU_PowerCycles packet +#define getECU_PowerCyclesMinDataLength() (8) + +//! return the maximum encoded length for the ECU_PowerCycles packet +#define getECU_PowerCyclesMaxDataLength() (8) + +/*! + * The fuel pump debug packet contains information on the pump control system. + * Send a zero length packet to request this data. + */ +typedef struct +{ + float pTerm; //!< Proportional term of the pump feedback control in percent + float iTerm; //!< Integral term of the pump feedback control in percent + float dutyCycle; //!< Pump duty cycle in percent + float fuelPressure; //!< Fuel pressure in kilo-Pascals +}ECU_PumpDebug_t; + +//! Create the ECU_PumpDebug packet +void encodeECU_PumpDebugPacketStructure(void* pkt, const ECU_PumpDebug_t* user); + +//! Decode the ECU_PumpDebug packet +int decodeECU_PumpDebugPacketStructure(const void* pkt, ECU_PumpDebug_t* user); + +//! return the packet ID for the ECU_PumpDebug packet +#define getECU_PumpDebugPacketID() (PKT_ECU_PUMP_DEBUG) + +//! return the minimum encoded length for the ECU_PumpDebug packet +#define getECU_PumpDebugMinDataLength() (8) + +//! return the maximum encoded length for the ECU_PumpDebug packet +#define getECU_PumpDebugMaxDataLength() (8) + +/*! + * While the engine time contained in the ECU telemetry packet can be reset by + * the user, the ECU also stores the total engine time, which cannot be reset + * by the user. Send a zero length packet to request this data. + */ +typedef struct +{ + uint32_t hobbs; //!< Total engine run time in seconds +}ECU_TotalEngineTime_t; + +//! Create the ECU_TotalEngineTime packet from parameters +void encodeECU_TotalEngineTimePacket(void* pkt, uint32_t hobbs); + +//! Decode the ECU_TotalEngineTime packet to parameters +int decodeECU_TotalEngineTimePacket(const void* pkt, uint32_t* hobbs); + +//! return the packet ID for the ECU_TotalEngineTime packet +#define getECU_TotalEngineTimePacketID() (PKT_ECU_TOTAL_ENGINE_TIME) + +//! return the minimum encoded length for the ECU_TotalEngineTime packet +#define getECU_TotalEngineTimeMinDataLength() (3) + +//! return the maximum encoded length for the ECU_TotalEngineTime packet +#define getECU_TotalEngineTimeMaxDataLength() (3) + +/*! + * The eeprom settings packet contains information on the non-volatile ECU + * settings stored in eeprom. In particular, it provides a checksum of the + * settings data for easy comparison of settings between different ECUs. Send a + * zero length packet to request this data. + */ +typedef struct +{ + uint8_t eepromVersion; //!< Version of the EEPROM data + uint16_t eepromSize; //!< Number of bytes of the EEPROM data + uint16_t eepromChecksum; //!< Fletcher's checksum of the EEPROM data + ECU_CompileOptions_t compileOptions; //!< ECU compilation options +}ECU_eepromSettings_t; + +//! Create the ECU_eepromSettings packet +void encodeECU_eepromSettingsPacketStructure(void* pkt, const ECU_eepromSettings_t* user); + +//! Decode the ECU_eepromSettings packet +int decodeECU_eepromSettingsPacketStructure(const void* pkt, ECU_eepromSettings_t* user); + +//! Create the ECU_eepromSettings packet from parameters +void encodeECU_eepromSettingsPacket(void* pkt, uint8_t eepromVersion, uint16_t eepromSize, uint16_t eepromChecksum, const ECU_CompileOptions_t* compileOptions); + +//! Decode the ECU_eepromSettings packet to parameters +int decodeECU_eepromSettingsPacket(const void* pkt, uint8_t* eepromVersion, uint16_t* eepromSize, uint16_t* eepromChecksum, ECU_CompileOptions_t* compileOptions); + +//! return the packet ID for the ECU_eepromSettings packet +#define getECU_eepromSettingsPacketID() (PKT_ECU_SETTINGS_DATA) + +//! return the minimum encoded length for the ECU_eepromSettings packet +#define getECU_eepromSettingsMinDataLength() (7) + +//! return the maximum encoded length for the ECU_eepromSettings packet +#define getECU_eepromSettingsMaxDataLength() (7) + +/*! + * Control loop settings for the CHT control loop + */ +typedef struct +{ + uint8_t dTermFilter; //!< Filter value for derivative term + bool enabled; //!< CHT control loop enabled + uint8_t targetTemp; //!< Target CHT temperature + float Kp; //!< Proportaional gain Kp + float Ki; //!< Proportaional gain Ki + float Kd; //!< Proportaional gain Kd +}ECU_CHTLoopSettings_t; + +//! Create the ECU_CHTLoopSettings packet +void encodeECU_CHTLoopSettingsPacketStructure(void* pkt, const ECU_CHTLoopSettings_t* user); + +//! Decode the ECU_CHTLoopSettings packet +int decodeECU_CHTLoopSettingsPacketStructure(const void* pkt, ECU_CHTLoopSettings_t* user); + +//! Create the ECU_CHTLoopSettings packet from parameters +void encodeECU_CHTLoopSettingsPacket(void* pkt, uint8_t dTermFilter, bool enabled, uint8_t targetTemp, float Kp, float Ki, float Kd); + +//! Decode the ECU_CHTLoopSettings packet to parameters +int decodeECU_CHTLoopSettingsPacket(const void* pkt, uint8_t* dTermFilter, bool* enabled, uint8_t* targetTemp, float* Kp, float* Ki, float* Kd); + +//! return the packet ID for the ECU_CHTLoopSettings packet +#define getECU_CHTLoopSettingsPacketID() (PKT_ECU_CHT_LOOP) + +//! return the minimum encoded length for the ECU_CHTLoopSettings packet +#define getECU_CHTLoopSettingsMinDataLength() (8) + +//! return the maximum encoded length for the ECU_CHTLoopSettings packet +#define getECU_CHTLoopSettingsMaxDataLength() (8) + +/*! + * Dual pump control telemetry. Send a zero-length packet with this identifier + * to the ECU to poll (request) this packet. + */ +typedef struct +{ + uint8_t mode; //!< Current pump mode (which pump is running). Refer to the DualFuelPumpMode enumeration. + uint8_t state; //!< Current pump state machine state. Refer to the DualFuelPumpState enumeration. + uint16_t stateTimer; //!< Time spent in current state +}ECU_DualPumpControlTelemetry_t; + +//! Create the ECU_DualPumpControlTelemetry packet +void encodeECU_DualPumpControlTelemetryPacketStructure(void* pkt, const ECU_DualPumpControlTelemetry_t* user); + +//! Decode the ECU_DualPumpControlTelemetry packet +int decodeECU_DualPumpControlTelemetryPacketStructure(const void* pkt, ECU_DualPumpControlTelemetry_t* user); + +//! return the packet ID for the ECU_DualPumpControlTelemetry packet +#define getECU_DualPumpControlTelemetryPacketID() (0x08) + +//! return the minimum encoded length for the ECU_DualPumpControlTelemetry packet +#define getECU_DualPumpControlTelemetryMinDataLength() (4) + +//! return the maximum encoded length for the ECU_DualPumpControlTelemetry packet +#define getECU_DualPumpControlTelemetryMaxDataLength() (4) + +/*! + * Set the telemetry period for dual-pump messages + */ +typedef struct +{ + uint8_t period; //!< Telemetry period (0 = Off) +}ECU_DualPump_SetTelemetryPeriod_t; + +//! Create the ECU_DualPump_SetTelemetryPeriod packet from parameters +void encodeECU_DualPump_SetTelemetryPeriodPacket(void* pkt, uint8_t period); + +//! Decode the ECU_DualPump_SetTelemetryPeriod packet to parameters +int decodeECU_DualPump_SetTelemetryPeriodPacket(const void* pkt, uint8_t* period); + +//! return the packet ID for the ECU_DualPump_SetTelemetryPeriod packet +#define getECU_DualPump_SetTelemetryPeriodPacketID() (0x08) + +//! return the minimum encoded length for the ECU_DualPump_SetTelemetryPeriod packet +#define getECU_DualPump_SetTelemetryPeriodMinDataLength() (2) + +//! return the maximum encoded length for the ECU_DualPump_SetTelemetryPeriod packet +#define getECU_DualPump_SetTelemetryPeriodMaxDataLength() (2) + +/*! + * Command to manually select a given pump mode. + */ +typedef struct +{ + uint8_t pump; //!< Pump selection (see DualFuelPumpMode enumeration) +}ECU_DualPump_SelectPump_t; + +//! Create the ECU_DualPump_SelectPump packet from parameters +void encodeECU_DualPump_SelectPumpPacket(void* pkt, uint8_t pump); + +//! Decode the ECU_DualPump_SelectPump packet to parameters +int decodeECU_DualPump_SelectPumpPacket(const void* pkt, uint8_t* pump); + +//! return the packet ID for the ECU_DualPump_SelectPump packet +#define getECU_DualPump_SelectPumpPacketID() (0x08) + +//! return the minimum encoded length for the ECU_DualPump_SelectPump packet +#define getECU_DualPump_SelectPumpMinDataLength() (3) + +//! return the maximum encoded length for the ECU_DualPump_SelectPump packet +#define getECU_DualPump_SelectPumpMaxDataLength() (3) + +/*! + * Command to temporarily run a particular pump in test mode. ECU will revert + * to OTHER pump when test expires + */ +typedef struct +{ + uint8_t pump; //!< Pump selection (see DualFuelPumpMode enumeration) + uint8_t timeout; //!< Test timeout +}ECU_DualPump_TestPump_t; + +//! Create the ECU_DualPump_TestPump packet +void encodeECU_DualPump_TestPumpPacketStructure(void* pkt, const ECU_DualPump_TestPump_t* user); + +//! Decode the ECU_DualPump_TestPump packet +int decodeECU_DualPump_TestPumpPacketStructure(const void* pkt, ECU_DualPump_TestPump_t* user); + +//! return the packet ID for the ECU_DualPump_TestPump packet +#define getECU_DualPump_TestPumpPacketID() (0x08) + +//! return the minimum encoded length for the ECU_DualPump_TestPump packet +#define getECU_DualPump_TestPumpMinDataLength() (3) + +//! return the maximum encoded length for the ECU_DualPump_TestPump packet +#define getECU_DualPump_TestPumpMaxDataLength() (4) + +//! Create the ECU_ThrottleCalibration packet +void encodeECU_ThrottleCalibrationPacketStructure(void* pkt, const ECU_ThrottleSettings_t* user); + +//! Decode the ECU_ThrottleCalibration packet +int decodeECU_ThrottleCalibrationPacketStructure(const void* pkt, ECU_ThrottleSettings_t* user); + +//! Create the ECU_ThrottleCalibration packet from parameters +void encodeECU_ThrottleCalibrationPacket(void* pkt, uint16_t pulseClosed, uint16_t pulseOpen, const ECU_ThrottleConfigBits_t* config, uint16_t pulseInputClosed, uint16_t pulseInputOpen); + +//! Decode the ECU_ThrottleCalibration packet to parameters +int decodeECU_ThrottleCalibrationPacket(const void* pkt, uint16_t* pulseClosed, uint16_t* pulseOpen, ECU_ThrottleConfigBits_t* config, uint16_t* pulseInputClosed, uint16_t* pulseInputOpen); + +//! return the packet ID for the ECU_ThrottleCalibration packet +#define getECU_ThrottleCalibrationPacketID() (PKT_ECU_THROTTLE_CALIBRATION) + +//! return the minimum encoded length for the ECU_ThrottleCalibration packet +#define getECU_ThrottleCalibrationMinDataLength() (8) + +//! return the maximum encoded length for the ECU_ThrottleCalibration packet +#define getECU_ThrottleCalibrationMaxDataLength() (8) + +//! Create the ECU_RPMLoopCalibration packet +void encodeECU_RPMLoopCalibrationPacketStructure(void* pkt, const ECU_GovernorSettings_t* user); + +//! Decode the ECU_RPMLoopCalibration packet +int decodeECU_RPMLoopCalibrationPacketStructure(const void* pkt, ECU_GovernorSettings_t* user); + +//! return the packet ID for the ECU_RPMLoopCalibration packet +#define getECU_RPMLoopCalibrationPacketID() (PKT_ECU_RPM_CALIBRATION) + +//! return the minimum encoded length for the ECU_RPMLoopCalibration packet +#define getECU_RPMLoopCalibrationMinDataLength() (8) + +//! return the maximum encoded length for the ECU_RPMLoopCalibration packet +#define getECU_RPMLoopCalibrationMaxDataLength() (8) + +//! Create the ECU_TPSDelayCalibration packet +void encodeECU_TPSDelayCalibrationPacketStructure(void* pkt, const ECU_ThrottleSettings_t* user); + +//! Decode the ECU_TPSDelayCalibration packet +int decodeECU_TPSDelayCalibrationPacketStructure(const void* pkt, ECU_ThrottleSettings_t* user); + +//! Create the ECU_TPSDelayCalibration packet from parameters +void encodeECU_TPSDelayCalibrationPacket(void* pkt, uint8_t delay, const ECU_ThrottleDelayConfigBits_t* delayConfig, uint8_t maxDelay, uint8_t minDelay, uint8_t softLimit, uint8_t falloffRate, uint8_t throttleTarget, uint8_t hardLimit); + +//! Decode the ECU_TPSDelayCalibration packet to parameters +int decodeECU_TPSDelayCalibrationPacket(const void* pkt, uint8_t* delay, ECU_ThrottleDelayConfigBits_t* delayConfig, uint8_t* maxDelay, uint8_t* minDelay, uint8_t* softLimit, uint8_t* falloffRate, uint8_t* throttleTarget, uint8_t* hardLimit); + +//! return the packet ID for the ECU_TPSDelayCalibration packet +#define getECU_TPSDelayCalibrationPacketID() (PKT_ECU_TPS_DELAY_CONFIG) + +//! return the minimum encoded length for the ECU_TPSDelayCalibration packet +#define getECU_TPSDelayCalibrationMinDataLength() (8) + +//! return the maximum encoded length for the ECU_TPSDelayCalibration packet +#define getECU_TPSDelayCalibrationMaxDataLength() (8) + +/*! + * The telmetry settings packet is used to configure the telemetry data rates + * for the ECU. The ECU will echo the packet as confirmation of its receipt. + * Send a zero length packet to request the current settings. + */ +typedef struct +{ + uint8_t fastTelemetryPeriod; //!< Time between fast telemetry packets in 50ms increments + uint8_t slowTelemetryPeriod; //!< Time between slow telemetry packets in 500ms increments + uint8_t silencePeriod; //!< Seconds of time the ECU waits after bootup before sending telemetry. +}ECU_TelemetrySettings_t; + +//! Create the ECU_TelemetrySettings packet +void encodeECU_TelemetrySettingsPacketStructure(void* pkt, const ECU_TelemetrySettings_t* user); + +//! Decode the ECU_TelemetrySettings packet +int decodeECU_TelemetrySettingsPacketStructure(const void* pkt, ECU_TelemetrySettings_t* user); + +//! return the packet ID for the ECU_TelemetrySettings packet +#define getECU_TelemetrySettingsPacketID() (PKT_ECU_TELEMETRY_SETTINGS) + +//! return the minimum encoded length for the ECU_TelemetrySettings packet +#define getECU_TelemetrySettingsMinDataLength() (3) + +//! return the maximum encoded length for the ECU_TelemetrySettings packet +#define getECU_TelemetrySettingsMaxDataLength() (3) + +//! Create the ECU_PumpConfig packet +void encodeECU_PumpConfigPacketStructure(void* pkt, const ECU_PumpSettings_t* user); + +//! Decode the ECU_PumpConfig packet +int decodeECU_PumpConfigPacketStructure(const void* pkt, ECU_PumpSettings_t* user); + +//! return the packet ID for the ECU_PumpConfig packet +#define getECU_PumpConfigPacketID() (PKT_ECU_PUMP_CONFIG) + +//! return the minimum encoded length for the ECU_PumpConfig packet +#define getECU_PumpConfigMinDataLength() (8) + +//! return the maximum encoded length for the ECU_PumpConfig packet +#define getECU_PumpConfigMaxDataLength() (8) + +//! Create the ECU_Pump2Config packet +void encodeECU_Pump2ConfigPacketStructure(void* pkt, const ECU_PumpSettings_t* user); + +//! Decode the ECU_Pump2Config packet +int decodeECU_Pump2ConfigPacketStructure(const void* pkt, ECU_PumpSettings_t* user); + +//! return the packet ID for the ECU_Pump2Config packet +#define getECU_Pump2ConfigPacketID() (PKT_ECU_PUMP_2_CONFIG) + +//! return the minimum encoded length for the ECU_Pump2Config packet +#define getECU_Pump2ConfigMinDataLength() (7) + +//! return the maximum encoded length for the ECU_Pump2Config packet +#define getECU_Pump2ConfigMaxDataLength() (7) + +/*! + * The user data packet provides the user with 8 (eight) bytes of data for + * storing custom parameters or settings in ECU EEPROM (non-volatile) memory. + * The ECU does not make use of these values; they are simply for storing user + * data. Send a zero length packet to request the current settings. To set + * these values send the system command SET_USER_DATA. Data values must be set + * individually. + */ +typedef struct +{ + uint8_t userData[8]; //!< 8 bytes of user data +}ECU_UserData_t; + +//! Create the ECU_UserData packet from parameters +void encodeECU_UserDataPacket(void* pkt, const uint8_t userData[8]); + +//! Decode the ECU_UserData packet to parameters +int decodeECU_UserDataPacket(const void* pkt, uint8_t userData[8]); + +//! return the packet ID for the ECU_UserData packet +#define getECU_UserDataPacketID() (PKT_ECU_USER_DATA) + +//! return the minimum encoded length for the ECU_UserData packet +#define getECU_UserDataMinDataLength() (8) + +//! return the maximum encoded length for the ECU_UserData packet +#define getECU_UserDataMaxDataLength() (8) + +/*! + * First throttle curve packet, which contains the lower 6 term of the throttle + * linearization table. To request the throttle curve data (both packets), send + * the system command REQUEST_THROTTLE_CURVE_DATA. To change the throttle curve + * data send the system command SET_THROTTLE_CURVE_ELEMENT. + */ +typedef struct +{ + float throttleCurve[6]; //!< Throttle output values for the lower 6 cells in the throttle lookup table +}ECU_ThrottleCurve_t; + +//! Create the ECU_ThrottleCurve packet from parameters +void encodeECU_ThrottleCurvePacket(void* pkt, const float throttleCurve[6]); + +//! Decode the ECU_ThrottleCurve packet to parameters +int decodeECU_ThrottleCurvePacket(const void* pkt, float throttleCurve[6]); + +//! return the packet ID for the ECU_ThrottleCurve packet +#define getECU_ThrottleCurvePacketID() (PKT_ECU_THROTTLE_CURVE_0) + +//! return the minimum encoded length for the ECU_ThrottleCurve packet +#define getECU_ThrottleCurveMinDataLength() (6) + +//! return the maximum encoded length for the ECU_ThrottleCurve packet +#define getECU_ThrottleCurveMaxDataLength() (6) + +//! Create the ECU_ThrottleCurve1 packet from parameters +void encodeECU_ThrottleCurve1Packet(void* pkt, const float throttleCurve[5]); + +//! Decode the ECU_ThrottleCurve1 packet to parameters +int decodeECU_ThrottleCurve1Packet(const void* pkt, float throttleCurve[5]); + +//! return the packet ID for the ECU_ThrottleCurve1 packet +#define getECU_ThrottleCurve1PacketID() (PKT_ECU_THROTTLE_CURVE_1) + +//! return the minimum encoded length for the ECU_ThrottleCurve1 packet +#define getECU_ThrottleCurve1MinDataLength() (5) + +//! return the maximum encoded length for the ECU_ThrottleCurve1 packet +#define getECU_ThrottleCurve1MaxDataLength() (5) + +/*! + * The system command packets follow the format provided below. Refer further + * in the document for complete documentation on each system command packet. + */ +typedef struct +{ + ECUSystemCommands cmd; //!< The command enumeration + uint8_t parambytes[3]; //!< Up to 3 parameter bytes for a system command +}ECU_SystemCommand_t; + +//! Create the ECU_SystemCommand packet +void encodeECU_SystemCommandPacketStructure(void* pkt, const ECU_SystemCommand_t* user); + +//! Decode the ECU_SystemCommand packet +int decodeECU_SystemCommandPacketStructure(const void* pkt, ECU_SystemCommand_t* user); + +//! return the packet ID for the ECU_SystemCommand packet +#define getECU_SystemCommandPacketID() (PKT_ECU_SYS_CMD) + +//! return the minimum encoded length for the ECU_SystemCommand packet +#define getECU_SystemCommandMinDataLength() (1) + +//! return the maximum encoded length for the ECU_SystemCommand packet +#define getECU_SystemCommandMaxDataLength() (4) + +/*! + * Save the current value of the analog throttle position input as the 'Closed' + * position. To calibrate the closed analog input position, set the desired + * analog input level, and send this command to the ECU. + */ +typedef struct +{ + ECUSystemCommands cmd; //!< The command enumeration. Field is encoded constant. +}ECU_CalibrateAnalogClosed_t; + +//! Create the ECU_CalibrateAnalogClosed packet from parameters +void encodeECU_CalibrateAnalogClosedPacket(void* pkt); + +//! Decode the ECU_CalibrateAnalogClosed packet to parameters +int decodeECU_CalibrateAnalogClosedPacket(const void* pkt, ECUSystemCommands* cmd); + +//! return the packet ID for the ECU_CalibrateAnalogClosed packet +#define getECU_CalibrateAnalogClosedPacketID() (PKT_ECU_SYS_CMD) + +//! return the minimum encoded length for the ECU_CalibrateAnalogClosed packet +#define getECU_CalibrateAnalogClosedMinDataLength() (1) + +//! return the maximum encoded length for the ECU_CalibrateAnalogClosed packet +#define getECU_CalibrateAnalogClosedMaxDataLength() (1) + +/*! + * Save the current value of the analog throttle position input as the 'Open' + * position. To calibrate the open analog input position, set the desired + * analog input level, and send this command to the ECU. + */ +typedef struct +{ + ECUSystemCommands cmd; //!< The command enumeration. Field is encoded constant. +}ECU_CalibrateAnalogOpen_t; + +//! Create the ECU_CalibrateAnalogOpen packet from parameters +void encodeECU_CalibrateAnalogOpenPacket(void* pkt); + +//! Decode the ECU_CalibrateAnalogOpen packet to parameters +int decodeECU_CalibrateAnalogOpenPacket(const void* pkt, ECUSystemCommands* cmd); + +//! return the packet ID for the ECU_CalibrateAnalogOpen packet +#define getECU_CalibrateAnalogOpenPacketID() (PKT_ECU_SYS_CMD) + +//! return the minimum encoded length for the ECU_CalibrateAnalogOpen packet +#define getECU_CalibrateAnalogOpenMinDataLength() (1) + +//! return the maximum encoded length for the ECU_CalibrateAnalogOpen packet +#define getECU_CalibrateAnalogOpenMaxDataLength() (1) + +/*! + * Save the current value of the throttle output pulse width to a temporary + * variable in the ECU. When the CALIBRATE_PULSE_WRITE command is sent to the + * ECU, this value will be saved as the 'Closed' pulse width. + */ +typedef struct +{ + ECUSystemCommands cmd; //!< The command enumeration. Field is encoded constant. +}ECU_CalibratePulseClosed_t; + +//! Create the ECU_CalibratePulseClosed packet from parameters +void encodeECU_CalibratePulseClosedPacket(void* pkt); + +//! Decode the ECU_CalibratePulseClosed packet to parameters +int decodeECU_CalibratePulseClosedPacket(const void* pkt, ECUSystemCommands* cmd); + +//! return the packet ID for the ECU_CalibratePulseClosed packet +#define getECU_CalibratePulseClosedPacketID() (PKT_ECU_SYS_CMD) + +//! return the minimum encoded length for the ECU_CalibratePulseClosed packet +#define getECU_CalibratePulseClosedMinDataLength() (1) + +//! return the maximum encoded length for the ECU_CalibratePulseClosed packet +#define getECU_CalibratePulseClosedMaxDataLength() (1) + +/*! + * Save the current value of the throttle output pulse width to a temporary + * variable in the ECU. When the CALIBRATE_PULSE_WRITE command is sent to the + * ECU, this value will be saved as the 'Open' pulse width. + */ +typedef struct +{ + ECUSystemCommands cmd; //!< The command enumeration. Field is encoded constant. +}ECU_CalibratePulseOpen_t; + +//! Create the ECU_CalibratePulseOpen packet from parameters +void encodeECU_CalibratePulseOpenPacket(void* pkt); + +//! Decode the ECU_CalibratePulseOpen packet to parameters +int decodeECU_CalibratePulseOpenPacket(const void* pkt, ECUSystemCommands* cmd); + +//! return the packet ID for the ECU_CalibratePulseOpen packet +#define getECU_CalibratePulseOpenPacketID() (PKT_ECU_SYS_CMD) + +//! return the minimum encoded length for the ECU_CalibratePulseOpen packet +#define getECU_CalibratePulseOpenMinDataLength() (1) + +//! return the maximum encoded length for the ECU_CalibratePulseOpen packet +#define getECU_CalibratePulseOpenMaxDataLength() (1) + +/*! + * Configure the throttle output positions. The CALIBRATE_PULSE_CLOSED and + * CALIBRATE_PULSE_OPEN commands should have already been sent to the ECU. The + * ECU then saves the temporary values as the 'Closed' and 'Open' throttle + * output values, respectively. + */ +typedef struct +{ + ECUSystemCommands cmd; //!< The command enumeration. Field is encoded constant. +}ECU_CalibratePulseWrite_t; + +//! Create the ECU_CalibratePulseWrite packet from parameters +void encodeECU_CalibratePulseWritePacket(void* pkt); + +//! Decode the ECU_CalibratePulseWrite packet to parameters +int decodeECU_CalibratePulseWritePacket(const void* pkt, ECUSystemCommands* cmd); + +//! return the packet ID for the ECU_CalibratePulseWrite packet +#define getECU_CalibratePulseWritePacketID() (PKT_ECU_SYS_CMD) + +//! return the minimum encoded length for the ECU_CalibratePulseWrite packet +#define getECU_CalibratePulseWriteMinDataLength() (1) + +//! return the maximum encoded length for the ECU_CalibratePulseWrite packet +#define getECU_CalibratePulseWriteMaxDataLength() (1) + +/*! + * Set one of four high-current output drivers. + */ +typedef struct +{ + ECUSystemCommands cmd; //!< The command enumeration. Field is encoded constant. + uint8_t driver; //!< Select driver number (1, 2, 3 or 4) + uint8_t status; //!< Set driver status (1 = ON, 0 = OFF) +}ECU_SetOutputDriver_t; + +//! Create the ECU_SetOutputDriver packet from parameters +void encodeECU_SetOutputDriverPacket(void* pkt, uint8_t driver, uint8_t status); + +//! Decode the ECU_SetOutputDriver packet to parameters +int decodeECU_SetOutputDriverPacket(const void* pkt, ECUSystemCommands* cmd, uint8_t* driver, uint8_t* status); + +//! return the packet ID for the ECU_SetOutputDriver packet +#define getECU_SetOutputDriverPacketID() (PKT_ECU_SYS_CMD) + +//! return the minimum encoded length for the ECU_SetOutputDriver packet +#define getECU_SetOutputDriverMinDataLength() (3) + +//! return the maximum encoded length for the ECU_SetOutputDriver packet +#define getECU_SetOutputDriverMaxDataLength() (3) + +/*! + * Turn the throttle linearization curve either on or off. + */ +typedef struct +{ + ECUSystemCommands cmd; //!< The command enumeration. Field is encoded constant. + uint8_t active; //!< Curve active (1 = ON, 0 = OFF) +}ECU_SetThrottleCurveActive_t; + +//! Create the ECU_SetThrottleCurveActive packet from parameters +void encodeECU_SetThrottleCurveActivePacket(void* pkt, uint8_t active); + +//! Decode the ECU_SetThrottleCurveActive packet to parameters +int decodeECU_SetThrottleCurveActivePacket(const void* pkt, ECUSystemCommands* cmd, uint8_t* active); + +//! return the packet ID for the ECU_SetThrottleCurveActive packet +#define getECU_SetThrottleCurveActivePacketID() (PKT_ECU_SYS_CMD) + +//! return the minimum encoded length for the ECU_SetThrottleCurveActive packet +#define getECU_SetThrottleCurveActiveMinDataLength() (2) + +//! return the maximum encoded length for the ECU_SetThrottleCurveActive packet +#define getECU_SetThrottleCurveActiveMaxDataLength() (2) + +/*! + * Set individual elements in the throttle linearization lookup table. + */ +typedef struct +{ + ECUSystemCommands cmd; //!< The command enumeration. Field is encoded constant. + uint8_t index; //!< Index into the throttle curve table from 0 to 10 (0% to 100%) throttle input + float throttleOutput; //!< Percentage throttle output for this curve element +}ECU_SetThrottleCurveElement_t; + +//! Create the ECU_SetThrottleCurveElement packet from parameters +void encodeECU_SetThrottleCurveElementPacket(void* pkt, uint8_t index, float throttleOutput); + +//! Decode the ECU_SetThrottleCurveElement packet to parameters +int decodeECU_SetThrottleCurveElementPacket(const void* pkt, ECUSystemCommands* cmd, uint8_t* index, float* throttleOutput); + +//! return the packet ID for the ECU_SetThrottleCurveElement packet +#define getECU_SetThrottleCurveElementPacketID() (PKT_ECU_SYS_CMD) + +//! return the minimum encoded length for the ECU_SetThrottleCurveElement packet +#define getECU_SetThrottleCurveElementMinDataLength() (3) + +//! return the maximum encoded length for the ECU_SetThrottleCurveElement packet +#define getECU_SetThrottleCurveElementMaxDataLength() (3) + +/*! + * Request the throttle curve lookup table data. If requested on CAN, the data + * will be returned on CAN. If requested on RS232, the data will be returned on + * RS232. + */ +typedef struct +{ + ECUSystemCommands cmd; //!< The command enumeration. Field is encoded constant. +}ECU_RequestThrottleCurveData_t; + +//! Create the ECU_RequestThrottleCurveData packet from parameters +void encodeECU_RequestThrottleCurveDataPacket(void* pkt); + +//! Decode the ECU_RequestThrottleCurveData packet to parameters +int decodeECU_RequestThrottleCurveDataPacket(const void* pkt, ECUSystemCommands* cmd); + +//! return the packet ID for the ECU_RequestThrottleCurveData packet +#define getECU_RequestThrottleCurveDataPacketID() (PKT_ECU_SYS_CMD) + +//! return the minimum encoded length for the ECU_RequestThrottleCurveData packet +#define getECU_RequestThrottleCurveDataMinDataLength() (1) + +//! return the maximum encoded length for the ECU_RequestThrottleCurveData packet +#define getECU_RequestThrottleCurveDataMaxDataLength() (1) + +/*! + * Reset the FuelUsed value. This will set the FuelUsed data to zero. + */ +typedef struct +{ + ECUSystemCommands cmd; //!< The command enumeration. Field is encoded constant. +}ECU_ResetFuelUsed_t; + +//! Create the ECU_ResetFuelUsed packet from parameters +void encodeECU_ResetFuelUsedPacket(void* pkt); + +//! Decode the ECU_ResetFuelUsed packet to parameters +int decodeECU_ResetFuelUsedPacket(const void* pkt, ECUSystemCommands* cmd); + +//! return the packet ID for the ECU_ResetFuelUsed packet +#define getECU_ResetFuelUsedPacketID() (PKT_ECU_SYS_CMD) + +//! return the minimum encoded length for the ECU_ResetFuelUsed packet +#define getECU_ResetFuelUsedMinDataLength() (1) + +//! return the maximum encoded length for the ECU_ResetFuelUsed packet +#define getECU_ResetFuelUsedMaxDataLength() (1) + +/*! + * Set the fuel used divisor + */ +typedef struct +{ + ECUSystemCommands cmd; //!< The command enumeration. Field is encoded constant. + uint16_t divisor; //!< The fuel used divisor. The fuel used value is divided by this divisor before being transmitted by the auxiliary processor. Set this value to 1 to leave the fuel used data unaffected. If you use values greater than 100 the divisor is automatically interpreted as being in units of 0.01 (i.e. 100 times the resolution). +}ECU_SetFuelUsedDivisor_t; + +//! Create the ECU_SetFuelUsedDivisor packet from parameters +void encodeECU_SetFuelUsedDivisorPacket(void* pkt, uint16_t divisor); + +//! Decode the ECU_SetFuelUsedDivisor packet to parameters +int decodeECU_SetFuelUsedDivisorPacket(const void* pkt, ECUSystemCommands* cmd, uint16_t* divisor); + +//! return the packet ID for the ECU_SetFuelUsedDivisor packet +#define getECU_SetFuelUsedDivisorPacketID() (PKT_ECU_SYS_CMD) + +//! return the minimum encoded length for the ECU_SetFuelUsedDivisor packet +#define getECU_SetFuelUsedDivisorMinDataLength() (3) + +//! return the maximum encoded length for the ECU_SetFuelUsedDivisor packet +#define getECU_SetFuelUsedDivisorMaxDataLength() (3) + +/*! + * Set or clear the Fuel Used reset flag. If this flag is set, the FuelUsed + * data will reset (to zero) when the ECU is power cycled. + */ +typedef struct +{ + ECUSystemCommands cmd; //!< The command enumeration. Field is encoded constant. + uint8_t reset; //!< 1 = Reset Fuel Used data on powerup 0 = Do not reset Fuel Used data on power up +}ECU_SetFuelUsedResetFlag_t; + +//! Create the ECU_SetFuelUsedResetFlag packet from parameters +void encodeECU_SetFuelUsedResetFlagPacket(void* pkt, uint8_t reset); + +//! Decode the ECU_SetFuelUsedResetFlag packet to parameters +int decodeECU_SetFuelUsedResetFlagPacket(const void* pkt, ECUSystemCommands* cmd, uint8_t* reset); + +//! return the packet ID for the ECU_SetFuelUsedResetFlag packet +#define getECU_SetFuelUsedResetFlagPacketID() (PKT_ECU_SYS_CMD) + +//! return the minimum encoded length for the ECU_SetFuelUsedResetFlag packet +#define getECU_SetFuelUsedResetFlagMinDataLength() (2) + +//! return the maximum encoded length for the ECU_SetFuelUsedResetFlag packet +#define getECU_SetFuelUsedResetFlagMaxDataLength() (2) + +/*! + * Manually set the RPM governor mode. + */ +typedef struct +{ + ECUSystemCommands cmd; //!< The command enumeration. Field is encoded constant. + ECUGovernorMode mode; //!< MODE 0 = Governor Off (Open loop throttle control) 1 = Governor based on throttle command 2 = Governor based on RPM command +}ECU_SetGovernorMode_t; + +//! Create the ECU_SetGovernorMode packet from parameters +void encodeECU_SetGovernorModePacket(void* pkt, ECUGovernorMode mode); + +//! Decode the ECU_SetGovernorMode packet to parameters +int decodeECU_SetGovernorModePacket(const void* pkt, ECUSystemCommands* cmd, ECUGovernorMode* mode); + +//! return the packet ID for the ECU_SetGovernorMode packet +#define getECU_SetGovernorModePacketID() (PKT_ECU_SYS_CMD) + +//! return the minimum encoded length for the ECU_SetGovernorMode packet +#define getECU_SetGovernorModeMinDataLength() (2) + +//! return the maximum encoded length for the ECU_SetGovernorMode packet +#define getECU_SetGovernorModeMaxDataLength() (2) + +/*! + * Set the serial mode used for Autronic relay. When Autronic relay is enabled + * the external serial port of the ECU is reconfigured to connect to ECUCal, + * relaying bytes to the internal autronic processor; while still allowing the + * auxiliary processor to see telemetry from Autronic. This is fundamentally + * different from using the switch to calibration mode, which bypasses the + * auxiliary processor altogether, cutting it off from autronic telemetry. + */ +typedef struct +{ + ECUSystemCommands cmd; //!< The command enumeration. Field is encoded constant. + ECUAutronicRelayState mode; //!< The serial relay mode to command +}ECU_SetSerialMode_t; + +//! Create the ECU_SetSerialMode packet from parameters +void encodeECU_SetSerialModePacket(void* pkt, ECUAutronicRelayState mode); + +//! Decode the ECU_SetSerialMode packet to parameters +int decodeECU_SetSerialModePacket(const void* pkt, ECUSystemCommands* cmd, ECUAutronicRelayState* mode); + +//! return the packet ID for the ECU_SetSerialMode packet +#define getECU_SetSerialModePacketID() (PKT_ECU_SYS_CMD) + +//! return the minimum encoded length for the ECU_SetSerialMode packet +#define getECU_SetSerialModeMinDataLength() (2) + +//! return the maximum encoded length for the ECU_SetSerialMode packet +#define getECU_SetSerialModeMaxDataLength() (2) + +/*! + * Set a custom address value for the ECU. + */ +typedef struct +{ + ECUSystemCommands cmd; //!< The command enumeration. Field is encoded constant. + uint16_t address; //!< ECU address in the range {1, 65534} +}ECU_SetECUAddress_t; + +//! Create the ECU_SetECUAddress packet from parameters +void encodeECU_SetECUAddressPacket(void* pkt, uint16_t address); + +//! Decode the ECU_SetECUAddress packet to parameters +int decodeECU_SetECUAddressPacket(const void* pkt, ECUSystemCommands* cmd, uint16_t* address); + +//! return the packet ID for the ECU_SetECUAddress packet +#define getECU_SetECUAddressPacketID() (PKT_ECU_SYS_CMD) + +//! return the minimum encoded length for the ECU_SetECUAddress packet +#define getECU_SetECUAddressMinDataLength() (3) + +//! return the maximum encoded length for the ECU_SetECUAddress packet +#define getECU_SetECUAddressMaxDataLength() (3) + +/*! + * Save a single byte of USER_DATA in EEPROM. + */ +typedef struct +{ + ECUSystemCommands cmd; //!< The command enumeration. Field is encoded constant. + uint8_t index; //!< USER_DATA address (0 to 7) + uint8_t userdata; //!< USER_DATA variable +}ECU_SetUserData_t; + +//! Create the ECU_SetUserData packet from parameters +void encodeECU_SetUserDataPacket(void* pkt, uint8_t index, uint8_t userdata); + +//! Decode the ECU_SetUserData packet to parameters +int decodeECU_SetUserDataPacket(const void* pkt, ECUSystemCommands* cmd, uint8_t* index, uint8_t* userdata); + +//! return the packet ID for the ECU_SetUserData packet +#define getECU_SetUserDataPacketID() (PKT_ECU_SYS_CMD) + +//! return the minimum encoded length for the ECU_SetUserData packet +#define getECU_SetUserDataMinDataLength() (3) + +//! return the maximum encoded length for the ECU_SetUserData packet +#define getECU_SetUserDataMaxDataLength() (3) + +/*! + * Reset the engine runtime. + */ +typedef struct +{ + ECUSystemCommands cmd; //!< The command enumeration. Field is encoded constant. + uint32_t time; //!< The new value of the engine time counter in seconds +}ECU_ResetEngineTime_t; + +//! Create the ECU_ResetEngineTime packet from parameters +void encodeECU_ResetEngineTimePacket(void* pkt, uint32_t time); + +//! Decode the ECU_ResetEngineTime packet to parameters +int decodeECU_ResetEngineTimePacket(const void* pkt, ECUSystemCommands* cmd, uint32_t* time); + +//! return the packet ID for the ECU_ResetEngineTime packet +#define getECU_ResetEngineTimePacketID() (PKT_ECU_SYS_CMD) + +//! return the minimum encoded length for the ECU_ResetEngineTime packet +#define getECU_ResetEngineTimeMinDataLength() (1) + +//! return the maximum encoded length for the ECU_ResetEngineTime packet +#define getECU_ResetEngineTimeMaxDataLength() (4) + +/*! + * Reset the ECU + */ +typedef struct +{ + ECUSystemCommands cmd; //!< The command enumeration. Field is encoded constant. +}ECU_ResetECU_t; + +//! Create the ECU_ResetECU packet from parameters +void encodeECU_ResetECUPacket(void* pkt); + +//! Decode the ECU_ResetECU packet to parameters +int decodeECU_ResetECUPacket(const void* pkt, ECUSystemCommands* cmd); + +//! return the packet ID for the ECU_ResetECU packet +#define getECU_ResetECUPacketID() (PKT_ECU_SYS_CMD) + +//! return the minimum encoded length for the ECU_ResetECU packet +#define getECU_ResetECUMinDataLength() (4) + +//! return the maximum encoded length for the ECU_ResetECU packet +#define getECU_ResetECUMaxDataLength() (4) + +#ifdef __cplusplus +} +#endif +#endif // _ECUPACKETS_H diff --git a/libraries/AP_PiccoloCAN/piccolo_protocol/ECUProtocol.c b/libraries/AP_PiccoloCAN/piccolo_protocol/ECUProtocol.c new file mode 100644 index 00000000000..f2cd1cd96d6 --- /dev/null +++ b/libraries/AP_PiccoloCAN/piccolo_protocol/ECUProtocol.c @@ -0,0 +1,148 @@ +// ECUProtocol.c was generated by ProtoGen version 3.2.a + +/* + * This file is free software: you can redistribute it and/or modify it + * under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program. If not, see . + * + * Author: Oliver Walters / Currawong Engineering Pty Ltd + */ + + +#include "ECUProtocol.h" + +/*! + * \brief Lookup label for 'ECUPackets' enum entry + * + * \param value is the integer value of the enum entry + * \return string label of the given entry + */ +const char* ECUPackets_EnumLabel(int value) +{ + switch (value) + { + default: + return ""; + case PKT_ECU_TELEMETRY_FAST: + return translateECU("PKT_ECU_TELEMETRY_FAST"); + case PKT_ECU_TELEMETRY_SLOW_0: + return translateECU("PKT_ECU_TELEMETRY_SLOW_0"); + case PKT_ECU_TELEMETRY_SLOW_1: + return translateECU("PKT_ECU_TELEMETRY_SLOW_1"); + case PKT_ECU_TELEMETRY_SLOW_2: + return translateECU("PKT_ECU_TELEMETRY_SLOW_2"); + case PKT_ECU_TELEMETRY_SLOW_3: + return translateECU("PKT_ECU_TELEMETRY_SLOW_3"); + case PKT_ECU_THROTTLE_CALIBRATION: + return translateECU("PKT_ECU_THROTTLE_CALIBRATION"); + case PKT_ECU_THROTTLE: + return translateECU("PKT_ECU_THROTTLE"); + case PKT_ECU_RPM_COMMAND: + return translateECU("PKT_ECU_RPM_COMMAND"); + case PKT_ECU_RPM_CALIBRATION: + return translateECU("PKT_ECU_RPM_CALIBRATION"); + case PKT_ECU_HARDWARE_CONFIG: + return translateECU("PKT_ECU_HARDWARE_CONFIG"); + case PKT_ECU_SOFTWARE_VERSION: + return translateECU("PKT_ECU_SOFTWARE_VERSION"); + case PKT_ECU_TPS_DELAY_CONFIG: + return translateECU("PKT_ECU_TPS_DELAY_CONFIG"); + case PKT_ECU_TELEMETRY_SETTINGS: + return translateECU("PKT_ECU_TELEMETRY_SETTINGS"); + case PKT_ECU_PUMP_CONFIG: + return translateECU("PKT_ECU_PUMP_CONFIG"); + case PKT_ECU_ERROR_MSG: + return translateECU("PKT_ECU_ERROR_MSG"); + case PKT_ECU_POWER_CYCLES: + return translateECU("PKT_ECU_POWER_CYCLES"); + case PKT_ECU_PUMP_2_CONFIG: + return translateECU("PKT_ECU_PUMP_2_CONFIG"); + case PKT_ECU_PUMP_DEBUG: + return translateECU("PKT_ECU_PUMP_DEBUG"); + case PKT_ECU_TOTAL_ENGINE_TIME: + return translateECU("PKT_ECU_TOTAL_ENGINE_TIME"); + case PKT_ECU_SYS_CMD: + return translateECU("PKT_ECU_SYS_CMD"); + case PKT_ECU_USER_DATA: + return translateECU("PKT_ECU_USER_DATA"); + case PKT_ECU_THROTTLE_CURVE_0: + return translateECU("PKT_ECU_THROTTLE_CURVE_0"); + case PKT_ECU_THROTTLE_CURVE_1: + return translateECU("PKT_ECU_THROTTLE_CURVE_1"); + case PKT_ECU_GPIO: + return translateECU("PKT_ECU_GPIO"); + case PKT_ECU_SETTINGS_DATA: + return translateECU("PKT_ECU_SETTINGS_DATA"); + case PKT_ECU_CHT_LOOP: + return translateECU("PKT_ECU_CHT_LOOP"); + } +} + + +/*! + * \brief Lookup label for 'ECUSystemCommands' enum entry + * + * \param value is the integer value of the enum entry + * \return string label of the given entry + */ +const char* ECUSystemCommands_EnumLabel(int value) +{ + switch (value) + { + default: + return ""; + case CMD_ECU_CALIBRATE_ANALOG_CLOSED: + return translateECU("CMD_ECU_CALIBRATE_ANALOG_CLOSED"); + case CMD_ECU_CALIBRATE_ANALOG_OPEN: + return translateECU("CMD_ECU_CALIBRATE_ANALOG_OPEN"); + case CMD_ECU_CALIBRATE_PULSE_CLOSED: + return translateECU("CMD_ECU_CALIBRATE_PULSE_CLOSED"); + case CMD_ECU_CALIBRATE_PULSE_OPEN: + return translateECU("CMD_ECU_CALIBRATE_PULSE_OPEN"); + case CMD_ECU_CALIBRATE_PULSE_WRITE: + return translateECU("CMD_ECU_CALIBRATE_PULSE_WRITE"); + case CMD_ECU_SET_OUTPUT_DRIVER: + return translateECU("CMD_ECU_SET_OUTPUT_DRIVER"); + case CMD_ECU_SET_THROTTLE_CURVE_ACTIVE: + return translateECU("CMD_ECU_SET_THROTTLE_CURVE_ACTIVE"); + case CMD_ECU_SET_THROTTLE_CURVE_ELEMENT: + return translateECU("CMD_ECU_SET_THROTTLE_CURVE_ELEMENT"); + case CMD_ECU_REQUEST_THROTTLE_CURVE_DATA: + return translateECU("CMD_ECU_REQUEST_THROTTLE_CURVE_DATA"); + case CMD_ECU_RESET_FUEL_USED: + return translateECU("CMD_ECU_RESET_FUEL_USED"); + case CMD_ECU_SET_FUEL_USED_DIVISOR: + return translateECU("CMD_ECU_SET_FUEL_USED_DIVISOR"); + case CMD_ECU_FUEL_USED_RESET_ON_STARTUP: + return translateECU("CMD_ECU_FUEL_USED_RESET_ON_STARTUP"); + case CMD_ECU_SET_GOVERNOR_MODE: + return translateECU("CMD_ECU_SET_GOVERNOR_MODE"); + case CMD_ECU_SET_SERVO_CAN_MODE: + return translateECU("CMD_ECU_SET_SERVO_CAN_MODE"); + case CMD_ECU_RESET_INTO_BOOTLOADER: + return translateECU("CMD_ECU_RESET_INTO_BOOTLOADER"); + case CMD_ECU_RESET_DEFAULT_SETTINGS: + return translateECU("CMD_ECU_RESET_DEFAULT_SETTINGS"); + case CMD_ECU_SET_SERIAL_MODE: + return translateECU("CMD_ECU_SET_SERIAL_MODE"); + case CMD_ECU_SET_NODE_ID: + return translateECU("CMD_ECU_SET_NODE_ID"); + case CMD_ECU_SET_USER_DATA: + return translateECU("CMD_ECU_SET_USER_DATA"); + case CMD_ECU_RESET_ENGINE_TIME: + return translateECU("CMD_ECU_RESET_ENGINE_TIME"); + case CMD_ECU_RESET_ECU: + return translateECU("CMD_ECU_RESET_ECU"); + } +} + +// end of ECUProtocol.c diff --git a/libraries/AP_PiccoloCAN/piccolo_protocol/ECUProtocol.h b/libraries/AP_PiccoloCAN/piccolo_protocol/ECUProtocol.h new file mode 100644 index 00000000000..d5011f3bdb1 --- /dev/null +++ b/libraries/AP_PiccoloCAN/piccolo_protocol/ECUProtocol.h @@ -0,0 +1,211 @@ +// ECUProtocol.h was generated by ProtoGen version 3.2.a + +/* + * This file is free software: you can redistribute it and/or modify it + * under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program. If not, see . + * + * Author: Oliver Walters / Currawong Engineering Pty Ltd + */ + + +#ifndef _ECUPROTOCOL_H +#define _ECUPROTOCOL_H + +// Language target is C, C++ compilers: don't mangle us +#ifdef __cplusplus +extern "C" { +#endif + +/*! + * \file + * \mainpage ECU protocol stack + * + * ECU ICD + * + * The protocol API enumeration is incremented anytime the protocol is changed + * in a way that affects compatibility with earlier versions of the protocol. + * The protocol enumeration for this version is: 11 + * + * The protocol version is 7.0 + */ + +#include +#include + +//! \return the protocol API enumeration +#define getECUApi() 11 + +//! \return the protocol version string +#define getECUVersion() "7.0" + +// Translation provided externally. The macro takes a `const char *` and returns a `const char *` +#ifndef translateECU + #define translateECU(x) x +#endif + +/*! + * Enumeration defining RESET commands for ECU settings + */ +typedef enum +{ + ECU_RESET_THROTTLE = 0x01,//!< Reset throttle settings to default values + ECU_RESET_PUMP = 0x02, //!< Reset pump settings to default values + ECU_RESET_GOVERNOR = 0x04,//!< Reset governor settings to default values + ECU_RESET_TELEMETRY = 0x08,//!< Reset telemetry settings to default values + ECU_RESET_ALL = 0xFF //!< Reset all ECU settings to default values +} ECUResetCommands; + +typedef enum +{ + ECU_DEBUG_RESET_STACK_OVERFLOW = 0x01, + ECU_DEBUG_RESET_STACK_UNDERFLOW, + ECU_DEBUG_RESET_DIVIDE_BY_ZERO, + ECU_DEBUG_RESET_INFINITE_LOOP +} ECUDebugResetTests; + +/*! + * ECU throttle position signal source enumeration + */ +typedef enum +{ + ECU_TPS_SRC_NONE = 0x00, //!< No throttle source + ECU_TPS_SRC_RPM = 0x01, //!< Throttle is commanded by RPM governor + ECU_TPS_SRC_PWM = 0x02, //!< Throttle is commanded from PWM input + ECU_TPS_SRC_SERIAL = 0x04,//!< Throttle is commanded from serial command packet + ECU_TPS_SRC_CAN = 0x08, //!< Throttle is commanded from CAN command packet + ECU_TPS_SRC_ANALOG = 0x0F //!< Throttle is commanded from analog input +} ECUThrottleSource; + +typedef enum +{ + ECU_DUAL_PUMP_MODE_DISABLED = 0x00,//!< Both pumps disabled + ECU_DUAL_PUMP_MODE_PRIMARY_CE, //!< Primary pump running + ECU_DUAL_PUMP_MODE_SECONDARY_TSA,//!< Secondary pump running + ECU_DUAL_PUMP_MODE_BOTH //!< Both pumps running +} DualFuelPumpMode; + +typedef enum +{ + ECU_DUAL_PUMP_STATE_RESET = 0x00,//!< Pump state machine is in the initial reset state + ECU_DUAL_PUMP_STATE_CMD, //!< Pump was explicitly commanded to the current state + ECU_DUAL_PUMP_STATE_TEST, //!< Pump is running in manual test mode + ECU_DUAL_PUMP_STATE_FAILURE //!< Pump has switched over due to detected failure +} DualFuelPumpState; + +typedef enum +{ + ECU_DUAL_PUMP_CMD_SET_PUMP = 0x01,//!< Switch to a particular pump mode + ECU_DUAL_PUMP_CMD_TEST_PUMP = 0x02 //!< Temporarily switch to a particular pump mode +} DualFuelPumpCommands; + +/*! + * ECU packet identifier (ID) definitions + */ +typedef enum +{ + PKT_ECU_TELEMETRY_FAST = 0x00, //!< High priority telemetry data from the ECU + PKT_ECU_TELEMETRY_SLOW_0, //!< First low priority telemetry packet from the ECU + PKT_ECU_TELEMETRY_SLOW_1, //!< Second low priority telemetry packet from the ECU + PKT_ECU_TELEMETRY_SLOW_2, //!< Third low priority telemetry packet from the ECU + PKT_ECU_TELEMETRY_SLOW_3, //!< Fourth low priority telemetry packet from the ECU (reserved for future use) + PKT_ECU_THROTTLE_CALIBRATION = 0x05, //!< Throttle calibration values + PKT_ECU_THROTTLE, //!< ECU throttle command + PKT_ECU_THROTTLE_COMBINED, //!< ECU Throttle command (position and pulse) + PKT_ECU_RPM_COMMAND, //!< RPM setpoint command + PKT_ECU_RPM_CALIBRATION, //!< RPM control loop calibration values + PKT_ECU_HARDWARE_CONFIG, //!< Serial number information + PKT_ECU_SOFTWARE_VERSION, //!< Firmware version information + PKT_ECU_TPS_DELAY_CONFIG, //!< Throttle delay configuration + PKT_ECU_TELEMETRY_SETTINGS, //!< Telemetry configuration + PKT_ECU_PUMP_CONFIG, //!< ECU Pump configuration packet 1 of 2 + PKT_ECU_ERROR_MSG, //!< Error messages + PKT_ECU_POWER_CYCLES = 0x10, //!< System information + PKT_ECU_PUMP_2_CONFIG, //!< ECU Pump configuration packet 2 of 2 + PKT_ECU_PUMP_DEBUG, //!< Pump debug information + PKT_ECU_TOTAL_ENGINE_TIME, //!< Total engine run-time + PKT_ECU_SYS_CMD, //!< ECU System command + PKT_ECU_USER_DATA, //!< User-configurable data bytes + PKT_ECU_THROTTLE_CURVE_0, //!< Throttle curve data, packet 1 of 2 + PKT_ECU_THROTTLE_CURVE_1, //!< Throttle curve data, packet 2 of 2 + PKT_ECU_GPIO, //!< GPIO settings + PKT_ECU_SETTINGS_DATA, //!< Non-volatile settings information + PKT_ECU_AUTRONIC_MEMORY, //!< Read or write Autronic RAM + PKT_ECU_CHT_LOOP, //!< Control loop settings for the CHT control loop + PKT_ECU_CANAUTRONIC_RELAY = 0x1F //!< Relay Autronic data across CAN +} ECUPackets; + +//! \return the label of a 'ECUPackets' enum entry, based on its value +const char* ECUPackets_EnumLabel(int value); + +typedef enum +{ + ECU_CE_CAL_TITLE_1 = 0xA0, + ECU_CE_CAL_TITLE_2, + ECU_CE_CAL_TITLE_3 +} ECUSpecialPackets; + +/*! + * These system command identifiers are used with the [system + * command](#PKT_ECU_SYS_CMD) packet. + */ +typedef enum +{ + CMD_ECU_CALIBRATE_ANALOG_CLOSED = 0x01,//!< Save the current value of the analog throttle position input as the 'Closed' position. To calibrate the closed analog input position, set the desired analog input level, and send this command to the ECU. + CMD_ECU_CALIBRATE_ANALOG_OPEN, //!< Save the current value of the analog throttle position input as the 'Open' position. To calibrate the open analog input position, set the desired analog input level, and send this command to the ECU. + CMD_ECU_CALIBRATE_PULSE_CLOSED, //!< Save the current value of the throttle output pulse width to a temporary variable in the ECU. When the CALIBRATE_PULSE_WRITE command is sent to the ECU, this value will be saved as the 'Closed' pulse width. + CMD_ECU_CALIBRATE_PULSE_OPEN, //!< Save the current value of the throttle output pulse width to a temporary variable in the ECU. When the CALIBRATE_PULSE_WRITE command is sent to the ECU, this value will be saved as the 'Open' pulse width. + CMD_ECU_CALIBRATE_PULSE_WRITE, //!< Configure the throttle output positions. The CALIBRATE_PULSE_CLOSED and CALIBRATE_PULSE_OPEN commands should have already been sent to the ECU. The ECU then saves the temporary values as the 'Closed' and 'Open' throttle output values, respectively. + CMD_ECU_SET_OUTPUT_DRIVER = 0x0A, //!< Set one of four high-current output drivers. Send two bytes after the command byte. Byte 1: Driver - Select driver number (1, 2, 3 or 4) Byte 2: Status - Set driver status (1 = ON, 0 = OFF) + CMD_ECU_SET_THROTTLE_CURVE_ACTIVE, //!< Turn the throttle linearization curve either on or off. Byte 1: 1 = ON 0 = OFF + CMD_ECU_SET_THROTTLE_CURVE_ELEMENT, //!< Set individual elements in the throttle linearization lookup table. Byte 1 = Element number (0 to 10, inclusive) Byte 2 = Value (0 to 200 inclusive) Each bit of the 'value' byte represents 0.5% throttle. So, 0 = 0% and 200 = 100% + CMD_ECU_REQUEST_THROTTLE_CURVE_DATA, //!< Request the throttle curve lookup table data. If requested on CAN, the data will be returned on CAN. If requested on RS232, the data will be returned on RS232. + CMD_ECU_RESET_FUEL_USED = 0x10, //!< Reset the FuelUsed value. This will set the FuelUsed data to zero. + CMD_ECU_SET_FUEL_USED_DIVISOR, //!< Configure the FuelUsed divisor. This is an unsigned 16-bit value. The fuel used value is divided by this divisor before being transmitted by the auxiliary processor. Set this value to 1 to leave the fuel used data unaffected. If you use values greater than 100 the divisor is automatically interpreted as being in units of 0.01 (i.e. 100 times the resolution). + CMD_ECU_FUEL_USED_RESET_ON_STARTUP, //!< Set or clear the Fuel Used reset flag. If this flag is set, the FuelUsed data will reset (to zero) when the ECU is power cycled. 1 = Reset Fuel Used data on powerup 0 = Do not reset Fuel Used data on power up + CMD_ECU_SET_GOVERNOR_MODE = 0x20, //!< Manually set the RPM governor mode Byte1 = MODE 0 = Governor Off (Open loop throttle control) 1 = Governor based on throttle command 2 = Governor based on RPM command + CMD_ECU_SET_SERVO_CAN_MODE = 0x28, + CMD_ECU_RESET_INTO_BOOTLOADER = 0x30,//!< Reset the ECU into bootloader mode + CMD_ECU_RESET_DEFAULT_SETTINGS, //!< Set ECU settings to their default values + CMD_ECU_SET_SERIAL_MODE = 0x40, //!< Set the serial relay mode used for Autronic relay + CMD_ECU_SET_NODE_ID = 0x50, //!< Set the address (CAN node ID) for the ECU + CMD_ECU_SET_USER_DATA = 0x60, //!< Save a single byte of USER_DATA in EEPROM Byte1 = USER_DATA address (0 to 7) Byte2 = USER_DATA variable (0x00 to 0xFF) + CMD_ECU_RESET_ENGINE_TIME = 0xA5, //!< Reset the engine time counter. If no further bytes are sent after the RESET_ENGINE_TIME command, this will set the engine time (in seconds) to zero. Note that the 'Total Engine Time' counter is not reset. To set the engine time to a specific value, send the engine time in seconds as a 3-byte (big endian) number after the RESET_ENGINE_TIME command. + CMD_ECU_RESET_ECU = 0xD0 //!< Cause a system reset +} ECUSystemCommands; + +//! \return the label of a 'ECUSystemCommands' enum entry, based on its value +const char* ECUSystemCommands_EnumLabel(int value); + + +// The prototypes below provide an interface to the packets. +// They are not auto-generated functions, but must be hand-written + +//! \return the packet data pointer from the packet +uint8_t* getECUPacketData(void* pkt); + +//! \return the packet data pointer from the packet, const +const uint8_t* getECUPacketDataConst(const void* pkt); + +//! Complete a packet after the data have been encoded +void finishECUPacket(void* pkt, int size, uint32_t packetID); + +//! \return the size of a packet from the packet header +int getECUPacketSize(const void* pkt); + +//! \return the ID of a packet from the packet header +uint32_t getECUPacketID(const void* pkt); + +#ifdef __cplusplus +} +#endif +#endif // _ECUPROTOCOL_H diff --git a/libraries/AP_PiccoloCAN/piccolo_protocol/ECUSettings.c b/libraries/AP_PiccoloCAN/piccolo_protocol/ECUSettings.c new file mode 100644 index 00000000000..88c91e9eeeb --- /dev/null +++ b/libraries/AP_PiccoloCAN/piccolo_protocol/ECUSettings.c @@ -0,0 +1,642 @@ +// ECUSettings.c was generated by ProtoGen version 3.2.a + +/* + * This file is free software: you can redistribute it and/or modify it + * under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program. If not, see . + * + * Author: Oliver Walters / Currawong Engineering Pty Ltd + */ + + +#include "ECUSettings.h" +#include "fielddecode.h" +#include "fieldencode.h" +#include "scaleddecode.h" +#include "scaledencode.h" + +/*! + * \brief Encode a ECU_PumpOptionBits_t into a byte array + * + + * \param _pg_data points to the byte array to add encoded data to + * \param _pg_bytecount points to the starting location in the byte array, and will be incremented by the number of encoded bytes. + * \param _pg_user is the data to encode in the byte array + */ +void encodeECU_PumpOptionBits_t(uint8_t* _pg_data, int* _pg_bytecount, const ECU_PumpOptionBits_t* _pg_user) +{ + int _pg_byteindex = *_pg_bytecount; + + // Reserved for future use + // Range of reserved is 0 to 255. + _pg_data[_pg_byteindex] = (uint8_t)_pg_user->reserved; + _pg_byteindex += 1; // close bit field + + *_pg_bytecount = _pg_byteindex; + +}// encodeECU_PumpOptionBits_t + +/*! + * \brief Decode a ECU_PumpOptionBits_t from a byte array + * + + * \param _pg_data points to the byte array to decoded data from + * \param _pg_bytecount points to the starting location in the byte array, and will be incremented by the number of bytes decoded + * \param _pg_user is the data to decode from the byte array + * \return 1 if the data are decoded, else 0. + */ +int decodeECU_PumpOptionBits_t(const uint8_t* _pg_data, int* _pg_bytecount, ECU_PumpOptionBits_t* _pg_user) +{ + int _pg_byteindex = *_pg_bytecount; + + // Reserved for future use + // Range of reserved is 0 to 255. + _pg_user->reserved = _pg_data[_pg_byteindex]; + _pg_byteindex += 1; // close bit field + + *_pg_bytecount = _pg_byteindex; + + return 1; + +}// decodeECU_PumpOptionBits_t + +/*! + * \brief Create the ECU_ThrottleSettings packet + * + * Throttle settings + * \param _pg_pkt points to the packet which will be created by this function + * \param _pg_user points to the user data that will be encoded in _pg_pkt + */ +void encodeECU_ThrottleSettingsPacketStructure(void* _pg_pkt, const ECU_ThrottleSettings_t* _pg_user) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + unsigned int _pg_tempbitfield = 0; + unsigned _pg_i = 0; + + // Throttle open PWM value + // Range of pulseOpen is 0 to 65535. + uint16ToBeBytes(_pg_user->pulseOpen, _pg_data, &_pg_byteindex); + + // Throttle closed PWM value + // Range of pulseClosed is 0 to 65535. + uint16ToBeBytes(_pg_user->pulseClosed, _pg_data, &_pg_byteindex); + + // Throttle input open PWM value + // Range of pulseInputOpen is 0 to 4095. + _pg_tempbitfield = (unsigned int)limitMax(_pg_user->pulseInputOpen, 4095); + _pg_data[_pg_byteindex + 1] = (uint8_t)(_pg_tempbitfield << 4); + + _pg_tempbitfield >>= 4; + _pg_data[_pg_byteindex] = (uint8_t)_pg_tempbitfield; + + + // Throttle input closed PWM value + // Range of pulseInputClosed is 0 to 4095. + _pg_tempbitfield = (unsigned int)limitMax(_pg_user->pulseInputClosed, 4095); + _pg_data[_pg_byteindex + 2] = (uint8_t)_pg_tempbitfield; + + _pg_tempbitfield >>= 8; + _pg_data[_pg_byteindex + 1] |= (uint8_t)_pg_tempbitfield; + _pg_byteindex += 3; // close bit field + + + // Throttle delay, constant value + // Range of delay is 0 to 255. + uint8ToBytes(_pg_user->delay, _pg_data, &_pg_byteindex); + + // Throttle delay, minimum value + // Range of minDelay is 0 to 255. + uint8ToBytes(_pg_user->minDelay, _pg_data, &_pg_byteindex); + + // Throttle delay, minimum value + // Range of maxDelay is 0 to 255. + uint8ToBytes(_pg_user->maxDelay, _pg_data, &_pg_byteindex); + + encodeECU_ThrottleDelayConfigBits_t(_pg_data, &_pg_byteindex, &_pg_user->delayConfig); + + // Throttle dashpot soft limit value + // Range of softLimit is 0 to 255. + uint8ToBytes(_pg_user->softLimit, _pg_data, &_pg_byteindex); + + // Throttle dashpot hard limit value + // Range of hardLimit is 0 to 255. + uint8ToBytes(_pg_user->hardLimit, _pg_data, &_pg_byteindex); + + // Throttle dashpot falloff rate + // Range of falloffRate is 0 to 255. + uint8ToBytes(_pg_user->falloffRate, _pg_data, &_pg_byteindex); + + // Throttle curve lookup table elements + // Range of curve is 0 to 255. + for(_pg_i = 0; _pg_i < 11; _pg_i++) + uint8ToBytes(_pg_user->curve[_pg_i], _pg_data, &_pg_byteindex); + + // Throttle curve config bits + encodeECU_ThrottleCurveConfigBits_t(_pg_data, &_pg_byteindex, &_pg_user->curveConfig); + + encodeECU_ThrottleConfigBits_t(_pg_data, &_pg_byteindex, &_pg_user->config); + + // Range of analogSpan1 is 0 to 255. + uint8ToBytes(_pg_user->analogSpan1, _pg_data, &_pg_byteindex); + + // Range of analogSpan2 is 0 to 65535. + uint16ToBeBytes(_pg_user->analogSpan2, _pg_data, &_pg_byteindex); + + // Range of throttleTarget is 0 to 255. + uint8ToBytes(_pg_user->throttleTarget, _pg_data, &_pg_byteindex); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_ThrottleSettingsPacketID()); + +}// encodeECU_ThrottleSettingsPacketStructure + +/*! + * \brief Decode the ECU_ThrottleSettings packet + * + * Throttle settings + * \param _pg_pkt points to the packet being decoded by this function + * \param _pg_user receives the data decoded from the packet + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_ThrottleSettingsPacketStructure(const void* _pg_pkt, ECU_ThrottleSettings_t* _pg_user) +{ + int _pg_numbytes; + int _pg_byteindex = 0; + const uint8_t* _pg_data; + unsigned int _pg_tempbitfield = 0; + unsigned _pg_i = 0; + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_ThrottleSettingsPacketID()) + return 0; + + // Verify the packet size + _pg_numbytes = getECUPacketSize(_pg_pkt); + if(_pg_numbytes < getECU_ThrottleSettingsMinDataLength()) + return 0; + + // The raw data from the packet + _pg_data = getECUPacketDataConst(_pg_pkt); + + // Throttle open PWM value + // Range of pulseOpen is 0 to 65535. + _pg_user->pulseOpen = uint16FromBeBytes(_pg_data, &_pg_byteindex); + + // Throttle closed PWM value + // Range of pulseClosed is 0 to 65535. + _pg_user->pulseClosed = uint16FromBeBytes(_pg_data, &_pg_byteindex); + + // Throttle input open PWM value + // Range of pulseInputOpen is 0 to 4095. + _pg_tempbitfield = (_pg_data[_pg_byteindex] & 0xFF); + + _pg_tempbitfield <<= 4; + _pg_tempbitfield |= (_pg_data[_pg_byteindex + 1] >> 4); + + _pg_user->pulseInputOpen = _pg_tempbitfield; + + // Throttle input closed PWM value + // Range of pulseInputClosed is 0 to 4095. + _pg_tempbitfield = (_pg_data[_pg_byteindex + 1] & 0xF); + + _pg_tempbitfield <<= 8; + _pg_tempbitfield |= _pg_data[_pg_byteindex + 2]; + + _pg_user->pulseInputClosed = _pg_tempbitfield; + _pg_byteindex += 3; // close bit field + + // Throttle delay, constant value + // Range of delay is 0 to 255. + _pg_user->delay = uint8FromBytes(_pg_data, &_pg_byteindex); + + // Throttle delay, minimum value + // Range of minDelay is 0 to 255. + _pg_user->minDelay = uint8FromBytes(_pg_data, &_pg_byteindex); + + // Throttle delay, minimum value + // Range of maxDelay is 0 to 255. + _pg_user->maxDelay = uint8FromBytes(_pg_data, &_pg_byteindex); + + if(decodeECU_ThrottleDelayConfigBits_t(_pg_data, &_pg_byteindex, &_pg_user->delayConfig) == 0) + return 0; + + // Throttle dashpot soft limit value + // Range of softLimit is 0 to 255. + _pg_user->softLimit = uint8FromBytes(_pg_data, &_pg_byteindex); + + // Throttle dashpot hard limit value + // Range of hardLimit is 0 to 255. + _pg_user->hardLimit = uint8FromBytes(_pg_data, &_pg_byteindex); + + // Throttle dashpot falloff rate + // Range of falloffRate is 0 to 255. + _pg_user->falloffRate = uint8FromBytes(_pg_data, &_pg_byteindex); + + // Throttle curve lookup table elements + // Range of curve is 0 to 255. + for(_pg_i = 0; _pg_i < 11; _pg_i++) + _pg_user->curve[_pg_i] = uint8FromBytes(_pg_data, &_pg_byteindex); + + // Throttle curve config bits + if(decodeECU_ThrottleCurveConfigBits_t(_pg_data, &_pg_byteindex, &_pg_user->curveConfig) == 0) + return 0; + + if(decodeECU_ThrottleConfigBits_t(_pg_data, &_pg_byteindex, &_pg_user->config) == 0) + return 0; + + // Range of analogSpan1 is 0 to 255. + _pg_user->analogSpan1 = uint8FromBytes(_pg_data, &_pg_byteindex); + + // Range of analogSpan2 is 0 to 65535. + _pg_user->analogSpan2 = uint16FromBeBytes(_pg_data, &_pg_byteindex); + + // Range of throttleTarget is 0 to 255. + _pg_user->throttleTarget = uint8FromBytes(_pg_data, &_pg_byteindex); + + return 1; + +}// decodeECU_ThrottleSettingsPacketStructure + +/*! + * \brief Create the ECU_FuelUsedSettings packet + * + * Throttle settings + * \param _pg_pkt points to the packet which will be created by this function + * \param _pg_user points to the user data that will be encoded in _pg_pkt + */ +void encodeECU_FuelUsedSettingsPacketStructure(void* _pg_pkt, const ECU_FuelUsedSettings_t* _pg_user) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // Range of resetOnStartup is 0 to 255. + uint8ToBytes(_pg_user->resetOnStartup, _pg_data, &_pg_byteindex); + + // Range of divisor is 0 to 65535. + uint16ToBeBytes(_pg_user->divisor, _pg_data, &_pg_byteindex); + + // Range of offset is 0 to 65535. + uint16ToBeBytes(_pg_user->offset, _pg_data, &_pg_byteindex); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_FuelUsedSettingsPacketID()); + +}// encodeECU_FuelUsedSettingsPacketStructure + +/*! + * \brief Decode the ECU_FuelUsedSettings packet + * + * Throttle settings + * \param _pg_pkt points to the packet being decoded by this function + * \param _pg_user receives the data decoded from the packet + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_FuelUsedSettingsPacketStructure(const void* _pg_pkt, ECU_FuelUsedSettings_t* _pg_user) +{ + int _pg_numbytes; + int _pg_byteindex = 0; + const uint8_t* _pg_data; + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_FuelUsedSettingsPacketID()) + return 0; + + // Verify the packet size + _pg_numbytes = getECUPacketSize(_pg_pkt); + if(_pg_numbytes < getECU_FuelUsedSettingsMinDataLength()) + return 0; + + // The raw data from the packet + _pg_data = getECUPacketDataConst(_pg_pkt); + + // Range of resetOnStartup is 0 to 255. + _pg_user->resetOnStartup = uint8FromBytes(_pg_data, &_pg_byteindex); + + // Range of divisor is 0 to 65535. + _pg_user->divisor = uint16FromBeBytes(_pg_data, &_pg_byteindex); + + // Range of offset is 0 to 65535. + _pg_user->offset = uint16FromBeBytes(_pg_data, &_pg_byteindex); + + return 1; + +}// decodeECU_FuelUsedSettingsPacketStructure + +/*! + * \brief Create the ECU_GovernorSettings packet + * + * Throttle settings + * \param _pg_pkt points to the packet which will be created by this function + * \param _pg_user points to the user data that will be encoded in _pg_pkt + */ +void encodeECU_GovernorSettingsPacketStructure(void* _pg_pkt, const ECU_GovernorSettings_t* _pg_user) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // Range of pGain is -3.402823466e+38f to 3.402823466e+38f. + float32ToBeBytes((float)_pg_user->pGain, _pg_data, &_pg_byteindex); + + // Range of iGain is -3.402823466e+38f to 3.402823466e+38f. + float32ToBeBytes((float)_pg_user->iGain, _pg_data, &_pg_byteindex); + + // Range of dGain is -3.402823466e+38f to 3.402823466e+38f. + float32ToBeBytes((float)_pg_user->dGain, _pg_data, &_pg_byteindex); + + // Range of scalePower is -3.402823466e+38f to 3.402823466e+38f. + float32ToBeBytes((float)_pg_user->scalePower, _pg_data, &_pg_byteindex); + + // Range of maxRPM is 0.0f to 25500.0f. + float32ScaledTo1UnsignedBytes(_pg_user->maxRPM, _pg_data, &_pg_byteindex, 0.0f, 0.01f); + + // Range of minRPM is 0.0f to 25500.0f. + float32ScaledTo1UnsignedBytes(_pg_user->minRPM, _pg_data, &_pg_byteindex, 0.0f, 0.01f); + + // Range of mode is 0 to 255. + uint8ToBytes(_pg_user->mode, _pg_data, &_pg_byteindex); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_GovernorSettingsPacketID()); + +}// encodeECU_GovernorSettingsPacketStructure + +/*! + * \brief Decode the ECU_GovernorSettings packet + * + * Throttle settings + * \param _pg_pkt points to the packet being decoded by this function + * \param _pg_user receives the data decoded from the packet + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_GovernorSettingsPacketStructure(const void* _pg_pkt, ECU_GovernorSettings_t* _pg_user) +{ + int _pg_numbytes; + int _pg_byteindex = 0; + const uint8_t* _pg_data; + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_GovernorSettingsPacketID()) + return 0; + + // Verify the packet size + _pg_numbytes = getECUPacketSize(_pg_pkt); + if(_pg_numbytes < getECU_GovernorSettingsMinDataLength()) + return 0; + + // The raw data from the packet + _pg_data = getECUPacketDataConst(_pg_pkt); + + // Range of pGain is -3.402823466e+38f to 3.402823466e+38f. + _pg_user->pGain = float32FromBeBytes(_pg_data, &_pg_byteindex); + + // Range of iGain is -3.402823466e+38f to 3.402823466e+38f. + _pg_user->iGain = float32FromBeBytes(_pg_data, &_pg_byteindex); + + // Range of dGain is -3.402823466e+38f to 3.402823466e+38f. + _pg_user->dGain = float32FromBeBytes(_pg_data, &_pg_byteindex); + + // Range of scalePower is -3.402823466e+38f to 3.402823466e+38f. + _pg_user->scalePower = float32FromBeBytes(_pg_data, &_pg_byteindex); + + // Range of maxRPM is 0.0f to 25500.0f. + _pg_user->maxRPM = float32ScaledFrom1UnsignedBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/0.01f); + + // Range of minRPM is 0.0f to 25500.0f. + _pg_user->minRPM = float32ScaledFrom1UnsignedBytes(_pg_data, &_pg_byteindex, 0.0f, 1.0f/0.01f); + + // Range of mode is 0 to 255. + _pg_user->mode = uint8FromBytes(_pg_data, &_pg_byteindex); + + return 1; + +}// decodeECU_GovernorSettingsPacketStructure + +/*! + * \brief Create the ECU_PumpSettings packet + * + * Throttle settings + * \param _pg_pkt points to the packet which will be created by this function + * \param _pg_user points to the user data that will be encoded in _pg_pkt + */ +void encodeECU_PumpSettingsPacketStructure(void* _pg_pkt, const ECU_PumpSettings_t* _pg_user) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + + // Pump proportional gain + // Range of kp is -3.402823466e+38f to 3.402823466e+38f. + float32ToBeBytes((float)_pg_user->kp, _pg_data, &_pg_byteindex); + + // Pump integral gain + // Range of ki is -3.402823466e+38f to 3.402823466e+38f. + float32ToBeBytes((float)_pg_user->ki, _pg_data, &_pg_byteindex); + + // Pump IMC (internal model) gain + // Range of km is -3.402823466e+38f to 3.402823466e+38f. + float32ToBeBytes((float)_pg_user->km, _pg_data, &_pg_byteindex); + + // Pump lower pressure limit (PSI) + // Range of pressureLowerLimit is -3.402823466e+38f to 3.402823466e+38f. + float32ToBeBytes((float)_pg_user->pressureLowerLimit, _pg_data, &_pg_byteindex); + + // Pump upper pressure limit (PSI) + // Range of pressureUpperLimit is -3.402823466e+38f to 3.402823466e+38f. + float32ToBeBytes((float)_pg_user->pressureUpperLimit, _pg_data, &_pg_byteindex); + + // Fuel pressure setpoint + // Range of pressureSetpoint is -3.402823466e+38f to 3.402823466e+38f. + float32ToBeBytes((float)_pg_user->pressureSetpoint, _pg_data, &_pg_byteindex); + + // Range of minimumPWM is 0 to 255. + uint8ToBytes(_pg_user->minimumPWM, _pg_data, &_pg_byteindex); + + // Range of maximumPWM is 0 to 255. + uint8ToBytes(_pg_user->maximumPWM, _pg_data, &_pg_byteindex); + + // Pump duty cycle ramp rate + // Range of rampRate is 0 to 255. + uint8ToBytes(_pg_user->rampRate, _pg_data, &_pg_byteindex); + + // Pump control system options + encodeECU_PumpOptionBits_t(_pg_data, &_pg_byteindex, &_pg_user->options); + + // Reserved for future use + // Range of reservedA is 0 to 255. + uint8ToBytes(_pg_user->reservedA, _pg_data, &_pg_byteindex); + + // Reserved for future use + // Range of reservedB is 0 to 255. + uint8ToBytes(_pg_user->reservedB, _pg_data, &_pg_byteindex); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_PumpSettingsPacketID()); + +}// encodeECU_PumpSettingsPacketStructure + +/*! + * \brief Decode the ECU_PumpSettings packet + * + * Throttle settings + * \param _pg_pkt points to the packet being decoded by this function + * \param _pg_user receives the data decoded from the packet + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_PumpSettingsPacketStructure(const void* _pg_pkt, ECU_PumpSettings_t* _pg_user) +{ + int _pg_numbytes; + int _pg_byteindex = 0; + const uint8_t* _pg_data; + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_PumpSettingsPacketID()) + return 0; + + // Verify the packet size + _pg_numbytes = getECUPacketSize(_pg_pkt); + if(_pg_numbytes < getECU_PumpSettingsMinDataLength()) + return 0; + + // The raw data from the packet + _pg_data = getECUPacketDataConst(_pg_pkt); + + // Pump proportional gain + // Range of kp is -3.402823466e+38f to 3.402823466e+38f. + _pg_user->kp = float32FromBeBytes(_pg_data, &_pg_byteindex); + + // Pump integral gain + // Range of ki is -3.402823466e+38f to 3.402823466e+38f. + _pg_user->ki = float32FromBeBytes(_pg_data, &_pg_byteindex); + + // Pump IMC (internal model) gain + // Range of km is -3.402823466e+38f to 3.402823466e+38f. + _pg_user->km = float32FromBeBytes(_pg_data, &_pg_byteindex); + + // Pump lower pressure limit (PSI) + // Range of pressureLowerLimit is -3.402823466e+38f to 3.402823466e+38f. + _pg_user->pressureLowerLimit = float32FromBeBytes(_pg_data, &_pg_byteindex); + + // Pump upper pressure limit (PSI) + // Range of pressureUpperLimit is -3.402823466e+38f to 3.402823466e+38f. + _pg_user->pressureUpperLimit = float32FromBeBytes(_pg_data, &_pg_byteindex); + + // Fuel pressure setpoint + // Range of pressureSetpoint is -3.402823466e+38f to 3.402823466e+38f. + _pg_user->pressureSetpoint = float32FromBeBytes(_pg_data, &_pg_byteindex); + + // Range of minimumPWM is 0 to 255. + _pg_user->minimumPWM = uint8FromBytes(_pg_data, &_pg_byteindex); + + // Range of maximumPWM is 0 to 255. + _pg_user->maximumPWM = uint8FromBytes(_pg_data, &_pg_byteindex); + + // Pump duty cycle ramp rate + // Range of rampRate is 0 to 255. + _pg_user->rampRate = uint8FromBytes(_pg_data, &_pg_byteindex); + + // Pump control system options + if(decodeECU_PumpOptionBits_t(_pg_data, &_pg_byteindex, &_pg_user->options) == 0) + return 0; + + // Reserved for future use + // Range of reservedA is 0 to 255. + _pg_user->reservedA = uint8FromBytes(_pg_data, &_pg_byteindex); + + // Reserved for future use + // Range of reservedB is 0 to 255. + _pg_user->reservedB = uint8FromBytes(_pg_data, &_pg_byteindex); + + return 1; + +}// decodeECU_PumpSettingsPacketStructure + +/*! + * \brief Create the ECU_ECUData packet + * + * User data + * \param _pg_pkt points to the packet which will be created by this function + * \param _pg_user points to the user data that will be encoded in _pg_pkt + */ +void encodeECU_ECUDataPacketStructure(void* _pg_pkt, const ECU_ECUData_t* _pg_user) +{ + uint8_t* _pg_data = getECUPacketData(_pg_pkt); + int _pg_byteindex = 0; + unsigned _pg_i = 0; + + // Range of powerCycles is 0 to 65535. + uint16ToBeBytes(_pg_user->powerCycles, _pg_data, &_pg_byteindex); + + // Range of engineTime is 0 to 4294967295. + uint32ToBeBytes(_pg_user->engineTime, _pg_data, &_pg_byteindex); + + // Range of engineTimeTotal is 0 to 4294967295. + uint32ToBeBytes(_pg_user->engineTimeTotal, _pg_data, &_pg_byteindex); + + // Range of fuelUsedOverflows is 0 to 65535. + uint16ToBeBytes(_pg_user->fuelUsedOverflows, _pg_data, &_pg_byteindex); + + // Range of userValues is 0 to 255. + for(_pg_i = 0; _pg_i < 8; _pg_i++) + uint8ToBytes(_pg_user->userValues[_pg_i], _pg_data, &_pg_byteindex); + + // complete the process of creating the packet + finishECUPacket(_pg_pkt, _pg_byteindex, getECU_ECUDataPacketID()); + +}// encodeECU_ECUDataPacketStructure + +/*! + * \brief Decode the ECU_ECUData packet + * + * User data + * \param _pg_pkt points to the packet being decoded by this function + * \param _pg_user receives the data decoded from the packet + * \return 0 is returned if the packet ID or size is wrong, else 1 + */ +int decodeECU_ECUDataPacketStructure(const void* _pg_pkt, ECU_ECUData_t* _pg_user) +{ + int _pg_numbytes; + int _pg_byteindex = 0; + const uint8_t* _pg_data; + unsigned _pg_i = 0; + + // Verify the packet identifier + if(getECUPacketID(_pg_pkt) != getECU_ECUDataPacketID()) + return 0; + + // Verify the packet size + _pg_numbytes = getECUPacketSize(_pg_pkt); + if(_pg_numbytes < getECU_ECUDataMinDataLength()) + return 0; + + // The raw data from the packet + _pg_data = getECUPacketDataConst(_pg_pkt); + + // Range of powerCycles is 0 to 65535. + _pg_user->powerCycles = uint16FromBeBytes(_pg_data, &_pg_byteindex); + + // Range of engineTime is 0 to 4294967295. + _pg_user->engineTime = uint32FromBeBytes(_pg_data, &_pg_byteindex); + + // Range of engineTimeTotal is 0 to 4294967295. + _pg_user->engineTimeTotal = uint32FromBeBytes(_pg_data, &_pg_byteindex); + + // Range of fuelUsedOverflows is 0 to 65535. + _pg_user->fuelUsedOverflows = uint16FromBeBytes(_pg_data, &_pg_byteindex); + + // Range of userValues is 0 to 255. + for(_pg_i = 0; _pg_i < 8; _pg_i++) + _pg_user->userValues[_pg_i] = uint8FromBytes(_pg_data, &_pg_byteindex); + + return 1; + +}// decodeECU_ECUDataPacketStructure +// end of ECUSettings.c diff --git a/libraries/AP_PiccoloCAN/piccolo_protocol/ECUSettings.h b/libraries/AP_PiccoloCAN/piccolo_protocol/ECUSettings.h new file mode 100644 index 00000000000..47d9c7d5473 --- /dev/null +++ b/libraries/AP_PiccoloCAN/piccolo_protocol/ECUSettings.h @@ -0,0 +1,224 @@ +// ECUSettings.h was generated by ProtoGen version 3.2.a + +/* + * This file is free software: you can redistribute it and/or modify it + * under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program. If not, see . + * + * Author: Oliver Walters / Currawong Engineering Pty Ltd + */ + + +#ifndef _ECUSETTINGS_H +#define _ECUSETTINGS_H + +// Language target is C, C++ compilers: don't mangle us +#ifdef __cplusplus +extern "C" { +#endif + +/*! + * \file + */ + +#include +#include "ECUProtocol.h" +#include "ECUDefines.h" +/*! + * ECU settings packets (not available on CAN or RS232 interfaces) + */ +typedef enum +{ + PKT_ECU_SETTINGS_THROTTLE = 0xF0, //!< Throttle settings + PKT_ECU_SETTINGS_PUMP = 0xF1, //!< Throttle settings + PKT_ECU_SETTINGS_GOVERNOR = 0xF2, //!< Throttle settings + PKT_ECU_SETTINGS_TELEMETRY = 0xF3, //!< Throttle settings + PKT_ECU_SETTINGS_FUEL_USED = 0xF4, //!< Throttle settings + PKT_ECU_SETTINGS_ENGINE_TIME = 0xF5, //!< Engine run time + PKT_ECU_SETTINGS_USER = 0xFA //!< User data +} ECUSettingsPackets; + +typedef struct +{ + unsigned reserved : 8; //!< Reserved for future use +}ECU_PumpOptionBits_t; + +//! return the minimum encoded length for the ECU_PumpOptionBits_t structure +#define getMinLengthOfECU_PumpOptionBits_t() (1) + +//! return the maximum encoded length for the ECU_PumpOptionBits_t structure +#define getMaxLengthOfECU_PumpOptionBits_t() (1) + +//! Encode a ECU_PumpOptionBits_t into a byte array +void encodeECU_PumpOptionBits_t(uint8_t* data, int* bytecount, const ECU_PumpOptionBits_t* user); + +//! Decode a ECU_PumpOptionBits_t from a byte array +int decodeECU_PumpOptionBits_t(const uint8_t* data, int* bytecount, ECU_PumpOptionBits_t* user); + +/*! + * Throttle settings + */ +typedef struct +{ + uint16_t pulseOpen; //!< Throttle open PWM value + uint16_t pulseClosed; //!< Throttle closed PWM value + uint16_t pulseInputOpen; //!< Throttle input open PWM value + uint16_t pulseInputClosed; //!< Throttle input closed PWM value + uint8_t delay; //!< Throttle delay, constant value + uint8_t minDelay; //!< Throttle delay, minimum value + uint8_t maxDelay; //!< Throttle delay, minimum value + ECU_ThrottleDelayConfigBits_t delayConfig; + uint8_t softLimit; //!< Throttle dashpot soft limit value + uint8_t hardLimit; //!< Throttle dashpot hard limit value + uint8_t falloffRate; //!< Throttle dashpot falloff rate + uint8_t curve[11]; //!< Throttle curve lookup table elements + ECU_ThrottleCurveConfigBits_t curveConfig; //!< Throttle curve config bits + ECU_ThrottleConfigBits_t config; + uint8_t analogSpan1; + uint16_t analogSpan2; + uint8_t throttleTarget; +}ECU_ThrottleSettings_t; + +//! Create the ECU_ThrottleSettings packet +void encodeECU_ThrottleSettingsPacketStructure(void* pkt, const ECU_ThrottleSettings_t* user); + +//! Decode the ECU_ThrottleSettings packet +int decodeECU_ThrottleSettingsPacketStructure(const void* pkt, ECU_ThrottleSettings_t* user); + +//! return the packet ID for the ECU_ThrottleSettings packet +#define getECU_ThrottleSettingsPacketID() (PKT_ECU_SETTINGS_THROTTLE) + +//! return the minimum encoded length for the ECU_ThrottleSettings packet +#define getECU_ThrottleSettingsMinDataLength() (31) + +//! return the maximum encoded length for the ECU_ThrottleSettings packet +#define getECU_ThrottleSettingsMaxDataLength() (31) + +/*! + * Throttle settings + */ +typedef struct +{ + uint8_t resetOnStartup; + uint16_t divisor; + uint16_t offset; +}ECU_FuelUsedSettings_t; + +//! Create the ECU_FuelUsedSettings packet +void encodeECU_FuelUsedSettingsPacketStructure(void* pkt, const ECU_FuelUsedSettings_t* user); + +//! Decode the ECU_FuelUsedSettings packet +int decodeECU_FuelUsedSettingsPacketStructure(const void* pkt, ECU_FuelUsedSettings_t* user); + +//! return the packet ID for the ECU_FuelUsedSettings packet +#define getECU_FuelUsedSettingsPacketID() (PKT_ECU_SETTINGS_FUEL_USED) + +//! return the minimum encoded length for the ECU_FuelUsedSettings packet +#define getECU_FuelUsedSettingsMinDataLength() (5) + +//! return the maximum encoded length for the ECU_FuelUsedSettings packet +#define getECU_FuelUsedSettingsMaxDataLength() (5) + +/*! + * Throttle settings + */ +typedef struct +{ + float pGain; + float iGain; + float dGain; + float scalePower; + float maxRPM; + float minRPM; + uint8_t mode; +}ECU_GovernorSettings_t; + +//! Create the ECU_GovernorSettings packet +void encodeECU_GovernorSettingsPacketStructure(void* pkt, const ECU_GovernorSettings_t* user); + +//! Decode the ECU_GovernorSettings packet +int decodeECU_GovernorSettingsPacketStructure(const void* pkt, ECU_GovernorSettings_t* user); + +//! return the packet ID for the ECU_GovernorSettings packet +#define getECU_GovernorSettingsPacketID() (PKT_ECU_SETTINGS_GOVERNOR) + +//! return the minimum encoded length for the ECU_GovernorSettings packet +#define getECU_GovernorSettingsMinDataLength() (19) + +//! return the maximum encoded length for the ECU_GovernorSettings packet +#define getECU_GovernorSettingsMaxDataLength() (19) + +/*! + * Throttle settings + */ +typedef struct +{ + float kp; //!< Pump proportional gain + float ki; //!< Pump integral gain + float km; //!< Pump IMC (internal model) gain + float pressureLowerLimit; //!< Pump lower pressure limit (PSI) + float pressureUpperLimit; //!< Pump upper pressure limit (PSI) + float pressureSetpoint; //!< Fuel pressure setpoint + uint8_t minimumPWM; + uint8_t maximumPWM; + uint8_t rampRate; //!< Pump duty cycle ramp rate + ECU_PumpOptionBits_t options; //!< Pump control system options + uint8_t reservedA; //!< Reserved for future use + uint8_t reservedB; //!< Reserved for future use +}ECU_PumpSettings_t; + +//! Create the ECU_PumpSettings packet +void encodeECU_PumpSettingsPacketStructure(void* pkt, const ECU_PumpSettings_t* user); + +//! Decode the ECU_PumpSettings packet +int decodeECU_PumpSettingsPacketStructure(const void* pkt, ECU_PumpSettings_t* user); + +//! return the packet ID for the ECU_PumpSettings packet +#define getECU_PumpSettingsPacketID() (PKT_ECU_SETTINGS_PUMP) + +//! return the minimum encoded length for the ECU_PumpSettings packet +#define getECU_PumpSettingsMinDataLength() (30) + +//! return the maximum encoded length for the ECU_PumpSettings packet +#define getECU_PumpSettingsMaxDataLength() (30) + +/*! + * User data + */ +typedef struct +{ + uint16_t powerCycles; + uint32_t engineTime; + uint32_t engineTimeTotal; + uint16_t fuelUsedOverflows; + uint8_t userValues[8]; +}ECU_ECUData_t; + +//! Create the ECU_ECUData packet +void encodeECU_ECUDataPacketStructure(void* pkt, const ECU_ECUData_t* user); + +//! Decode the ECU_ECUData packet +int decodeECU_ECUDataPacketStructure(const void* pkt, ECU_ECUData_t* user); + +//! return the packet ID for the ECU_ECUData packet +#define getECU_ECUDataPacketID() (PKT_ECU_SETTINGS_USER) + +//! return the minimum encoded length for the ECU_ECUData packet +#define getECU_ECUDataMinDataLength() (20) + +//! return the maximum encoded length for the ECU_ECUData packet +#define getECU_ECUDataMaxDataLength() (20) + +#ifdef __cplusplus +} +#endif +#endif // _ECUSETTINGS_H diff --git a/libraries/AP_PiccoloCAN/piccolo_protocol/license.txt b/libraries/AP_PiccoloCAN/piccolo_protocol/license.txt index 266877bcc6c..61a7ef22ecb 100644 --- a/libraries/AP_PiccoloCAN/piccolo_protocol/license.txt +++ b/libraries/AP_PiccoloCAN/piccolo_protocol/license.txt @@ -12,5 +12,7 @@ * You should have received a copy of the GNU General Public License along * with this program. If not, see . * + * This license applies to all files in this directory. + * * Author: Oliver Walters */ diff --git a/libraries/AP_Proximity/AP_Proximity.cpp b/libraries/AP_Proximity/AP_Proximity.cpp index 70ba0306524..91d37466e15 100644 --- a/libraries/AP_Proximity/AP_Proximity.cpp +++ b/libraries/AP_Proximity/AP_Proximity.cpp @@ -27,130 +27,18 @@ #include "AP_Proximity_AirSimSITL.h" #include "AP_Proximity_Cygbot_D1.h" +#include + extern const AP_HAL::HAL &hal; // table of user settable parameters const AP_Param::GroupInfo AP_Proximity::var_info[] = { // 0 is reserved for possible addition of an ENABLED parameter - // @Param: _TYPE - // @DisplayName: Proximity type - // @Description: What type of proximity sensor is connected - // @Values: 0:None,7:LightwareSF40c,2:MAVLink,3:TeraRangerTower,4:RangeFinder,5:RPLidarA2,6:TeraRangerTowerEvo,8:LightwareSF45B,10:SITL,12:AirSimSITL,13:CygbotD1 - // @RebootRequired: True - // @User: Standard - AP_GROUPINFO_FLAGS("_TYPE", 1, AP_Proximity, _type[0], 0, AP_PARAM_FLAG_ENABLE), - - // @Param: _ORIENT - // @DisplayName: Proximity sensor orientation - // @Description: Proximity sensor orientation - // @Values: 0:Default,1:Upside Down - // @User: Standard - AP_GROUPINFO("_ORIENT", 2, AP_Proximity, _orientation[0], 0), - - // @Param: _YAW_CORR - // @DisplayName: Proximity sensor yaw correction - // @Description: Proximity sensor yaw correction - // @Units: deg - // @Range: -180 180 - // @User: Standard - AP_GROUPINFO("_YAW_CORR", 3, AP_Proximity, _yaw_correction[0], 0), - - // @Param: _IGN_ANG1 - // @DisplayName: Proximity sensor ignore angle 1 - // @Description: Proximity sensor ignore angle 1 - // @Units: deg - // @Range: 0 360 - // @User: Standard - AP_GROUPINFO("_IGN_ANG1", 4, AP_Proximity, _ignore_angle_deg[0], 0), - - // @Param: _IGN_WID1 - // @DisplayName: Proximity sensor ignore width 1 - // @Description: Proximity sensor ignore width 1 - // @Units: deg - // @Range: 0 127 - // @User: Standard - AP_GROUPINFO("_IGN_WID1", 5, AP_Proximity, _ignore_width_deg[0], 0), - - // @Param: _IGN_ANG2 - // @DisplayName: Proximity sensor ignore angle 2 - // @Description: Proximity sensor ignore angle 2 - // @Units: deg - // @Range: 0 360 - // @User: Standard - AP_GROUPINFO("_IGN_ANG2", 6, AP_Proximity, _ignore_angle_deg[1], 0), - - // @Param: _IGN_WID2 - // @DisplayName: Proximity sensor ignore width 2 - // @Description: Proximity sensor ignore width 2 - // @Units: deg - // @Range: 0 127 - // @User: Standard - AP_GROUPINFO("_IGN_WID2", 7, AP_Proximity, _ignore_width_deg[1], 0), - - // @Param: _IGN_ANG3 - // @DisplayName: Proximity sensor ignore angle 3 - // @Description: Proximity sensor ignore angle 3 - // @Units: deg - // @Range: 0 360 - // @User: Standard - AP_GROUPINFO("_IGN_ANG3", 8, AP_Proximity, _ignore_angle_deg[2], 0), - - // @Param: _IGN_WID3 - // @DisplayName: Proximity sensor ignore width 3 - // @Description: Proximity sensor ignore width 3 - // @Units: deg - // @Range: 0 127 - // @User: Standard - AP_GROUPINFO("_IGN_WID3", 9, AP_Proximity, _ignore_width_deg[2], 0), - - // @Param: _IGN_ANG4 - // @DisplayName: Proximity sensor ignore angle 4 - // @Description: Proximity sensor ignore angle 4 - // @Units: deg - // @Range: 0 360 - // @User: Standard - AP_GROUPINFO("_IGN_ANG4", 10, AP_Proximity, _ignore_angle_deg[3], 0), - - // @Param: _IGN_WID4 - // @DisplayName: Proximity sensor ignore width 4 - // @Description: Proximity sensor ignore width 4 - // @Units: deg - // @Range: 0 127 - // @User: Standard - AP_GROUPINFO("_IGN_WID4", 11, AP_Proximity, _ignore_width_deg[3], 0), - - // @Param: _IGN_ANG5 - // @DisplayName: Proximity sensor ignore angle 5 - // @Description: Proximity sensor ignore angle 5 - // @Units: deg - // @Range: 0 360 - // @User: Standard - AP_GROUPINFO("_IGN_ANG5", 12, AP_Proximity, _ignore_angle_deg[4], 0), - - // @Param: _IGN_WID5 - // @DisplayName: Proximity sensor ignore width 5 - // @Description: Proximity sensor ignore width 5 - // @Units: deg - // @Range: 0 127 - // @User: Standard - AP_GROUPINFO("_IGN_WID5", 13, AP_Proximity, _ignore_width_deg[4], 0), - - // @Param: _IGN_ANG6 - // @DisplayName: Proximity sensor ignore angle 6 - // @Description: Proximity sensor ignore angle 6 - // @Units: deg - // @Range: 0 360 - // @User: Standard - AP_GROUPINFO("_IGN_ANG6", 14, AP_Proximity, _ignore_angle_deg[5], 0), - - // @Param: _IGN_WID6 - // @DisplayName: Proximity sensor ignore width 6 - // @Description: Proximity sensor ignore width 6 - // @Units: deg - // @Range: 0 127 - // @User: Standard - AP_GROUPINFO("_IGN_WID6", 15, AP_Proximity, _ignore_width_deg[5], 0), + // 1 was _TYPE + // 2 was _ORIENT + // 3 was _YAW_CORR + // 4 to 15 was _IGN_ANG1 to _IGN_WID6 // @Param{Copter}: _IGN_GND // @DisplayName: Proximity sensor land detection @@ -174,21 +62,30 @@ const AP_Param::GroupInfo AP_Proximity::var_info[] = { // @User: Advanced AP_GROUPINFO("_FILT", 18, AP_Proximity, _filt_freq, 0.25f), - // @Param: _MIN - // @DisplayName: Proximity minimum range - // @Description: Minimum expected range for Proximity Sensor. Setting this to 0 will set value to manufacturer reported range. - // @Units: m - // @Range: 0 500 - // @User: Advanced - AP_GROUPINFO("_MIN", 19, AP_Proximity, _min_m, 0.0f), + // 19 was _MIN + // 20 was _MAX - // @Param: _MAX - // @DisplayName: Proximity maximum range - // @Description: Maximum expected range for Proximity Sensor. Setting this to 0 will set value to manufacturer reported range. - // @Units: m - // @Range: 0 500 - // @User: Advanced - AP_GROUPINFO("_MAX", 20, AP_Proximity, _max_m, 0.0f), + // @Group: 1 + // @Path: AP_Proximity_Params.cpp + AP_SUBGROUPINFO(params[0], "1", 21, AP_Proximity, AP_Proximity_Params), + +#if PROXIMITY_MAX_INSTANCES > 1 + // @Group: 2 + // @Path: AP_Proximity_Params.cpp + AP_SUBGROUPINFO(params[1], "2", 22, AP_Proximity, AP_Proximity_Params), +#endif + +#if PROXIMITY_MAX_INSTANCES > 2 + // @Group: 3 + // @Path: AP_Proximity_Params.cpp + AP_SUBGROUPINFO(params[2], "3", 23, AP_Proximity, AP_Proximity_Params), +#endif + +#if PROXIMITY_MAX_INSTANCES > 3 + // @Group: 4 + // @Path: AP_Proximity_Params.cpp + AP_SUBGROUPINFO(params[3], "4", 24, AP_Proximity, AP_Proximity_Params), +#endif AP_GROUPEND }; @@ -206,66 +103,128 @@ AP_Proximity::AP_Proximity() // initialise the Proximity class. We do detection of attached sensors here // we don't allow for hot-plugging of sensors (i.e. reboot required) -void AP_Proximity::init(void) +void AP_Proximity::init() { if (num_instances != 0) { // init called a 2nd time? return; } - for (uint8_t i=0; iupdate(); - drivers[i]->boundary_3D_checks(); } - // work out primary instance - first sensor returning good data - for (int8_t i=num_instances-1; i>=0; i--) { - if (drivers[i] != nullptr && (state[i].status == Status::Good)) { - primary_instance = i; - } - } -} + // set boundary cutoff freq for low pass filter + boundary.set_filter_freq(get_filter_freq()); -// return sensor orientation -uint8_t AP_Proximity::get_orientation(uint8_t instance) const -{ - if (!valid_instance(instance)) { - return 0; - } - - return _orientation[instance].get(); + // check if any face has valid distance when it should not + boundary.check_face_timeout(); } -// return sensor yaw correction -int16_t AP_Proximity::get_yaw_correction(uint8_t instance) const +AP_Proximity::Type AP_Proximity::get_type(uint8_t instance) const { - if (!valid_instance(instance)) { - return 0; + if (instance < PROXIMITY_MAX_INSTANCES) { + return (Type)((uint8_t)params[instance].type); } - - return _yaw_correction[instance].get(); + return Type::None; } // return sensor health -AP_Proximity::Status AP_Proximity::get_status(uint8_t instance) const +AP_Proximity::Status AP_Proximity::get_instance_status(uint8_t instance) const { // sanity check instance number if (!valid_instance(instance)) { @@ -277,203 +236,141 @@ AP_Proximity::Status AP_Proximity::get_status(uint8_t instance) const AP_Proximity::Status AP_Proximity::get_status() const { - return get_status(primary_instance); + for (uint8_t i=0; ihandle_msg(msg); + switch (get_instance_status(i)) { + case Status::NoData: + hal.util->snprintf(failure_msg, failure_msg_len, "PRX%d: No Data", i + 1); + return false; + case Status::NotConnected: + hal.util->snprintf(failure_msg, failure_msg_len, "PRX%d: Not Connected", i + 1); + return false; + case Status::Good: + break; } } + return true; } -// detect if an instance of a proximity sensor is connected. -void AP_Proximity::detect_instance(uint8_t instance) +// get maximum and minimum distances (in meters) +float AP_Proximity::distance_max() const { - switch (get_type(instance)) { - case Type::None: - return; - case Type::RPLidarA2: - if (AP_Proximity_RPLidarA2::detect()) { - state[instance].instance = instance; - drivers[instance] = new AP_Proximity_RPLidarA2(*this, state[instance]); - return; - } - break; - case Type::MAV: - state[instance].instance = instance; - drivers[instance] = new AP_Proximity_MAV(*this, state[instance]); - return; - - case Type::TRTOWER: - if (AP_Proximity_TeraRangerTower::detect()) { - state[instance].instance = instance; - drivers[instance] = new AP_Proximity_TeraRangerTower(*this, state[instance]); - return; - } - break; - case Type::TRTOWEREVO: - if (AP_Proximity_TeraRangerTowerEvo::detect()) { - state[instance].instance = instance; - drivers[instance] = new AP_Proximity_TeraRangerTowerEvo(*this, state[instance]); - return; - } - break; + float dist_max = 0; - case Type::RangeFinder: - state[instance].instance = instance; - drivers[instance] = new AP_Proximity_RangeFinder(*this, state[instance]); - return; - - case Type::SF40C: - if (AP_Proximity_LightWareSF40C::detect()) { - state[instance].instance = instance; - drivers[instance] = new AP_Proximity_LightWareSF40C(*this, state[instance]); - return; + // return longest distance from all backends + for (uint8_t i=0; idistance_max()); } - break; + } + return dist_max; +} +float AP_Proximity::distance_min() const +{ + float dist_min = 0; + bool found_dist_min = false; - case Type::SF45B: - if (AP_Proximity_LightWareSF45B::detect()) { - state[instance].instance = instance; - drivers[instance] = new AP_Proximity_LightWareSF45B(*this, state[instance]); - return; + // calculate shortest distance from all backends + for (uint8_t i=0; idistance_min(); + if (!found_dist_min || (disti_min <= dist_min)) { + dist_min = disti_min; + found_dist_min = true; + } } - break; - - case Type::CYGBOT_D1: -#if AP_PROXIMITY_CYGBOT_ENABLED - if (AP_Proximity_Cygbot_D1::detect()) { - state[instance].instance = instance; - drivers[instance] = new AP_Proximity_Cygbot_D1(*this, state[instance]); - return; } -# endif - break; -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL - case Type::SITL: - state[instance].instance = instance; - drivers[instance] = new AP_Proximity_SITL(*this, state[instance]); - return; - - case Type::AirSimSITL: - state[instance].instance = instance; - drivers[instance] = new AP_Proximity_AirSimSITL(*this, state[instance]); - return; - -#endif + if (found_dist_min) { + return dist_min; } + return 0; } + // get distances in 8 directions. used for sending distances to ground station bool AP_Proximity::get_horizontal_distances(Proximity_Distance_Array &prx_dist_array) const { - if (!valid_instance(primary_instance)) { - return false; - } - // get distances from backend - return drivers[primary_instance]->get_horizontal_distances(prx_dist_array); -} - -// get raw and filtered distances in 8 directions per layer. used for logging -bool AP_Proximity::get_active_layer_distances(uint8_t layer, AP_Proximity::Proximity_Distance_Array &prx_dist_array, AP_Proximity::Proximity_Distance_Array &prx_filt_dist_array) const -{ - if (!valid_instance(primary_instance)) { - return false; - } - // get distances from backend - return drivers[primary_instance]->get_active_layer_distances(layer, prx_dist_array, prx_filt_dist_array); + Proximity_Distance_Array prx_filt_dist_array; // unused + return boundary.get_layer_distances(PROXIMITY_MIDDLE_LAYER, distance_max(), prx_dist_array, prx_filt_dist_array); } // get total number of obstacles, used in GPS based Simple Avoidance uint8_t AP_Proximity::get_obstacle_count() const -{ - if (!valid_instance(primary_instance)) { - return 0; - } - return drivers[primary_instance]->get_obstacle_count(); -} - -// get number of layers. -uint8_t AP_Proximity::get_num_layers() const { - if (!valid_instance(primary_instance)) { - return 0; - } - return drivers[primary_instance]->get_num_layers(); + return boundary.get_obstacle_count(); } // get vector to obstacle based on obstacle_num passed, used in GPS based Simple Avoidance bool AP_Proximity::get_obstacle(uint8_t obstacle_num, Vector3f& vec_to_obstacle) const { - if (!valid_instance(primary_instance)) { - return false; - } - return drivers[primary_instance]->get_obstacle(obstacle_num, vec_to_obstacle); + return boundary.get_obstacle(obstacle_num, vec_to_obstacle); } // returns shortest distance to "obstacle_num" obstacle, from a line segment formed between "seg_start" and "seg_end" -// used in GPS based Simple Avoidance +// returns FLT_MAX if it's an invalid instance. bool AP_Proximity::closest_point_from_segment_to_obstacle(uint8_t obstacle_num, const Vector3f& seg_start, const Vector3f& seg_end, Vector3f& closest_point) const { - if (!valid_instance(primary_instance)) { - return false; - } - return drivers[primary_instance]->closest_point_from_segment_to_obstacle(obstacle_num, seg_start, seg_end, closest_point); + return boundary.closest_point_from_segment_to_obstacle(obstacle_num , seg_start, seg_end, closest_point); } // get distance and angle to closest object (used for pre-arm check) // returns true on success, false if no valid readings bool AP_Proximity::get_closest_object(float& angle_deg, float &distance) const { - if (!valid_instance(primary_instance)) { - return false; - } - // get closest object from backend - return drivers[primary_instance]->get_closest_object(angle_deg, distance); + return boundary.get_closest_object(angle_deg, distance); } -// get number of objects, used for non-GPS avoidance +// get number of objects, angle and distance - used for non-GPS avoidance uint8_t AP_Proximity::get_object_count() const { - if (!valid_instance(primary_instance)) { - return 0; - } - // get count from backend - return drivers[primary_instance]->get_horizontal_object_count(); + return boundary.get_horizontal_object_count(); } -// get an object's angle and distance, used for non-GPS avoidance -// returns false if no angle or distance could be returned for some reason +// get number of objects, angle and distance - used for non-GPS avoidance bool AP_Proximity::get_object_angle_and_distance(uint8_t object_number, float& angle_deg, float &distance) const { - if (!valid_instance(primary_instance)) { - return false; - } - // get angle and distance from backend - return drivers[primary_instance]->get_horizontal_object_angle_and_distance(object_number, angle_deg, distance); + return boundary.get_horizontal_object_angle_and_distance(object_number, angle_deg, distance); } -// get maximum and minimum distances (in meters) of primary sensor -float AP_Proximity::distance_max() const +// handle mavlink messages +void AP_Proximity::handle_msg(const mavlink_message_t &msg) { - if (!valid_instance(primary_instance)) { - return 0.0f; + for (uint8_t i=0; ihandle_msg(msg); + } } - // get maximum distance from backend - return drivers[primary_instance]->distance_max(); } -float AP_Proximity::distance_min() const + +// methods for mavlink SYS_STATUS message (send_sys_status) +bool AP_Proximity::sensor_present() const { - if (!valid_instance(primary_instance)) { - return 0.0f; - } - // get minimum distance from backend - return drivers[primary_instance]->distance_min(); + return get_status() != Status::NotConnected; +} + +bool AP_Proximity::sensor_enabled() const +{ + // check atleast one sensor is enabled + return (num_instances > 0); +} + +bool AP_Proximity::sensor_failed() const +{ + return get_status() != Status::Good; } // get distance in meters upwards, returns true on success @@ -488,40 +385,94 @@ bool AP_Proximity::get_upward_distance(uint8_t instance, float &distance) const bool AP_Proximity::get_upward_distance(float &distance) const { - return get_upward_distance(primary_instance, distance); + // get upward distance from backend + for (uint8_t i=0; i= PROXIMITY_MAX_INSTANCES) { + return false; } - // store alt at the backend - drivers[primary_instance]->set_rangefinder_alt(use, healthy, alt_cm); -} + if (drivers[i] == nullptr) { + return false; + } + return (Type)params[i].type.get() != Type::None; +} AP_Proximity *AP_Proximity::_singleton; diff --git a/libraries/AP_Proximity/AP_Proximity.h b/libraries/AP_Proximity/AP_Proximity.h index 43db39d2937..8dd2f2393ae 100644 --- a/libraries/AP_Proximity/AP_Proximity.h +++ b/libraries/AP_Proximity/AP_Proximity.h @@ -14,12 +14,7 @@ */ #pragma once -#include -#include - -#ifndef HAL_PROXIMITY_ENABLED -#define HAL_PROXIMITY_ENABLED (!HAL_MINIMIZE_FEATURES && BOARD_FLASH_SIZE > 1024) -#endif +#include "AP_Proximity_config.h" #if HAL_PROXIMITY_ENABLED @@ -27,10 +22,10 @@ #include #include #include +#include "AP_Proximity_Params.h" +#include "AP_Proximity_Boundary_3D.h" -#define PROXIMITY_MAX_INSTANCES 1 // Maximum number of proximity sensor instances available on this platform -#define PROXIMITY_MAX_IGNORE 6 // up to six areas can be ignored -#define PROXIMITY_MAX_DIRECTION 8 +#define PROXIMITY_MAX_INSTANCES 3 // Maximum number of proximity sensor instances available on this platform #define PROXIMITY_SENSOR_ID_START 10 class AP_Proximity_Backend; @@ -69,50 +64,45 @@ class AP_Proximity Good }; - // structure holding distances in PROXIMITY_MAX_DIRECTION directions. used for sending distances to ground station - struct Proximity_Distance_Array { - uint8_t orientation[PROXIMITY_MAX_DIRECTION]; // orientation (i.e. rough direction) of the distance (see MAV_SENSOR_ORIENTATION) - float distance[PROXIMITY_MAX_DIRECTION]; // distance in meters - bool valid(uint8_t offset) const { - // returns true if the distance stored at offset is valid - return (offset < 8 && (offset_valid & (1U< #include #include #include -#include - -extern const AP_HAL::HAL& hal; /* base class constructor. This incorporates initialisation as well. */ -AP_Proximity_Backend::AP_Proximity_Backend(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state) : +AP_Proximity_Backend::AP_Proximity_Backend(AP_Proximity& _frontend, AP_Proximity::Proximity_State& _state, AP_Proximity_Params& _params) : frontend(_frontend), - state(_state) + state(_state), + params(_params) { } static_assert(PROXIMITY_MAX_DIRECTION <= 8, "get_horizontal_distances assumes 8-bits is enough for validity bitmask"); -// get distances in PROXIMITY_MAX_DIRECTION directions horizontally. used for sending distances to ground station -bool AP_Proximity_Backend::get_horizontal_distances(AP_Proximity::Proximity_Distance_Array &prx_dist_array) const -{ - AP_Proximity::Proximity_Distance_Array prx_filt_dist_array; // unused - return boundary.get_layer_distances(PROXIMITY_MIDDLE_LAYER, distance_max(), prx_dist_array, prx_filt_dist_array); -} -// get distances in PROXIMITY_MAX_DIRECTION directions at a layer. used for logging -bool AP_Proximity_Backend::get_active_layer_distances(uint8_t layer, AP_Proximity::Proximity_Distance_Array &prx_dist_array, AP_Proximity::Proximity_Distance_Array &prx_filt_dist_array) const -{ - return boundary.get_layer_distances(layer, distance_max(), prx_dist_array, prx_filt_dist_array); -} - // set status and update valid count void AP_Proximity_Backend::set_status(AP_Proximity::Status status) { state.status = status; } -// timeout faces that have not received data recently and update filter frequencies -void AP_Proximity_Backend::boundary_3D_checks() -{ - // set the cutoff freq for low pass filter - boundary.set_filter_freq(frontend.get_filter_freq()); - - // check if any face has valid distance when it should not - const uint32_t now_ms = AP_HAL::millis(); - // run this check every PROXIMITY_BOUNDARY_3D_TIMEOUT_MS - if ((now_ms - _last_timeout_check_ms) > PROXIMITY_BOUNDARY_3D_TIMEOUT_MS) { - _last_timeout_check_ms = now_ms; - boundary.check_face_timeout(); - } -} - // correct an angle (in degrees) based on the orientation and yaw correction parameters float AP_Proximity_Backend::correct_angle_for_orientation(float angle_degrees) const { - const float angle_sign = (frontend.get_orientation(state.instance) == 1) ? -1.0f : 1.0f; - return wrap_360(angle_degrees * angle_sign + frontend.get_yaw_correction(state.instance)); + const float angle_sign = (params.orientation == 1) ? -1.0f : 1.0f; + return wrap_360(angle_degrees * angle_sign + params.yaw_correction); } // check if a reading should be ignored because it falls into an ignore area (check_for_ign_area should be sent as false if this check is not needed) @@ -85,15 +55,15 @@ float AP_Proximity_Backend::correct_angle_for_orientation(float angle_degrees) c bool AP_Proximity_Backend::ignore_reading(float pitch, float yaw, float distance_m, bool check_for_ign_area) const { // check if distances are supposed to be in a particular range - if (!is_zero(frontend._max_m)) { - if (distance_m > frontend._max_m) { + if (!is_zero(params.max_m)) { + if (distance_m > params.max_m) { // too far away return true; } } - if (!is_zero(frontend._min_m)) { - if (distance_m < frontend._min_m) { + if (!is_zero(params.min_m)) { + if (distance_m < params.min_m) { // too close return true; } @@ -102,8 +72,8 @@ bool AP_Proximity_Backend::ignore_reading(float pitch, float yaw, float distance if (check_for_ign_area) { // check angle vs each ignore area for (uint8_t i=0; i < PROXIMITY_MAX_IGNORE; i++) { - if (frontend._ignore_width_deg[i] != 0) { - if (abs(yaw - frontend._ignore_angle_deg[i]) <= (frontend._ignore_width_deg[i]/2)) { + if (params.ignore_width_deg[i] != 0) { + if (abs(yaw - params.ignore_angle_deg[i]) <= (params.ignore_width_deg[i]/2)) { return true; } } @@ -111,69 +81,7 @@ bool AP_Proximity_Backend::ignore_reading(float pitch, float yaw, float distance } // check if obstacle is near land - return check_obstacle_near_ground(pitch, yaw, distance_m); -} - -// store rangefinder values -void AP_Proximity_Backend::set_rangefinder_alt(bool use, bool healthy, float alt_cm) -{ - _last_downward_update_ms = AP_HAL::millis(); - _rangefinder_use = use; - _rangefinder_healthy = healthy; - _rangefinder_alt = alt_cm * 0.01f; -} - -// get alt from rangefinder in meters -bool AP_Proximity_Backend::get_rangefinder_alt(float &alt_m) const -{ - if (!_rangefinder_use || !_rangefinder_healthy) { - // range finder is not healthy - return false; - } - - const uint32_t dt = AP_HAL::millis() - _last_downward_update_ms; - if (dt > PROXIMITY_ALT_DETECT_TIMEOUT_MS) { - return false; - } - - // readings are healthy - alt_m = _rangefinder_alt; - return true; -} - -// Check if Obstacle defined by body-frame yaw and pitch is near ground -bool AP_Proximity_Backend::check_obstacle_near_ground(float pitch, float yaw, float distance) const -{ - if (!frontend._ign_gnd_enable) { - return false; - } - if (!hal.util->get_soft_armed()) { - // don't run this feature while vehicle is disarmed, otherwise proximity data will not show up on GCS - return false; - } - if ((pitch > 90.0f) || (pitch < -90.0f)) { - // sanity check on pitch - return false; - } - // Assume object is yaw and pitch bearing and distance meters away from the vehicle - Vector3f object_3D; - object_3D.offset_bearing(wrap_180(yaw), (pitch * -1.0f), distance); - const Matrix3f body_to_ned = AP::ahrs().get_rotation_body_to_ned(); - const Vector3f rotated_object_3D = body_to_ned * object_3D; - - float alt = FLT_MAX; - if (!get_rangefinder_alt(alt)) { - return false; - } - - if (rotated_object_3D.z > -0.5f) { - // obstacle is at the most 0.5 meters above vehicle - if ((alt - PROXIMITY_GND_DETECT_THRESHOLD) < rotated_object_3D.z) { - // obstacle is near or below ground - return true; - } - } - return false; + return frontend.check_obstacle_near_ground(pitch, yaw, distance_m); } // returns true if database is ready to be pushed to and all cached data is ready diff --git a/libraries/AP_Proximity/AP_Proximity_Backend.h b/libraries/AP_Proximity/AP_Proximity_Backend.h index 25603925df4..42f092c3747 100644 --- a/libraries/AP_Proximity/AP_Proximity_Backend.h +++ b/libraries/AP_Proximity/AP_Proximity_Backend.h @@ -17,20 +17,13 @@ #include "AP_Proximity.h" #if HAL_PROXIMITY_ENABLED -#include #include -#include -#include "AP_Proximity_Boundary_3D.h" - -#define PROXIMITY_GND_DETECT_THRESHOLD 1.0f // set ground detection threshold to be 1 meters -#define PROXIMITY_ALT_DETECT_TIMEOUT_MS 500 // alt readings should arrive within this much time -#define PROXIMITY_BOUNDARY_3D_TIMEOUT_MS 750 // we should check the 3D boundary faces after every this many ms class AP_Proximity_Backend { public: // constructor. This incorporates initialisation as well. - AP_Proximity_Backend(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state); + AP_Proximity_Backend(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state, AP_Proximity_Params &_params); // we declare a virtual destructor so that Proximity drivers can // override with a custom destructor if need be @@ -39,9 +32,6 @@ class AP_Proximity_Backend // update the state structure virtual void update() = 0; - // timeout faces that have not received data recently and update filter frequencies - void boundary_3D_checks(); - // get maximum and minimum distances (in meters) of sensor virtual float distance_max() const = 0; virtual float distance_min() const = 0; @@ -49,39 +39,9 @@ class AP_Proximity_Backend // get distance upwards in meters. returns true on success virtual bool get_upward_distance(float &distance) const { return false; } - // handle mavlink DISTANCE_SENSOR messages + // handle mavlink messages virtual void handle_msg(const mavlink_message_t &msg) {} - // get total number of obstacles, used in GPS based Simple Avoidance - uint8_t get_obstacle_count() { return boundary.get_obstacle_count(); } - - // get vector to obstacle based on obstacle_num passed, used in GPS based Simple Avoidance - bool get_obstacle(uint8_t obstacle_num, Vector3f& vec_to_obstacle) const { return boundary.get_obstacle(obstacle_num, vec_to_obstacle); } - - // returns shortest distance to "obstacle_num" obstacle, from a line segment formed between "seg_start" and "seg_end" - // used in GPS based Simple Avoidance - bool closest_point_from_segment_to_obstacle(const uint8_t obstacle_num, const Vector3f& seg_start, const Vector3f& seg_end, Vector3f& closest_point) const { return boundary.closest_point_from_segment_to_obstacle(obstacle_num , seg_start, seg_end, closest_point); } - - // get distance and angle to closest object (used for pre-arm check) - // returns true on success, false if no valid readings - bool get_closest_object(float& angle_deg, float &distance) const { return boundary.get_closest_object(angle_deg, distance); } - - // get number of objects, angle and distance - used for non-GPS avoidance - uint8_t get_horizontal_object_count() const {return boundary.get_horizontal_object_count(); } - bool get_horizontal_object_angle_and_distance(uint8_t object_number, float& angle_deg, float &distance) const { return boundary.get_horizontal_object_angle_and_distance(object_number, angle_deg, distance); } - - // get distances in 8 directions. used for sending distances to ground station - bool get_horizontal_distances(AP_Proximity::Proximity_Distance_Array &prx_dist_array) const; - - // get raw and filtered distances in 8 directions per layer. used for logging - bool get_active_layer_distances(uint8_t layer, AP_Proximity::Proximity_Distance_Array &prx_dist_array, AP_Proximity::Proximity_Distance_Array &prx_filt_dist_array) const; - - // get number of layers - uint8_t get_num_layers() const { return boundary.get_num_layers(); } - - // store rangefinder values - void set_rangefinder_alt(bool use, bool healthy, float alt_cm); - protected: // set status and update valid_count @@ -98,12 +58,6 @@ class AP_Proximity_Backend bool ignore_reading(float pitch, float yaw, float distance_m, bool check_for_ign_area = true) const; bool ignore_reading(float yaw, float distance_m, bool check_for_ign_area = true) const { return ignore_reading(0.0f, yaw, distance_m, check_for_ign_area); } - // get alt from rangefinder in meters. This reading is corrected for vehicle tilt - bool get_rangefinder_alt(float &alt_m) const; - - // Check if Obstacle defined by body-frame yaw and pitch is near ground - bool check_obstacle_near_ground(float pitch, float yaw, float distance) const; - // database helpers. All angles are in degrees static bool database_prepare_for_push(Vector3f ¤t_pos, Matrix3f &body_to_ned); // Note: "angle" refers to yaw (in body frame) towards the obstacle @@ -113,19 +67,9 @@ class AP_Proximity_Backend }; static void database_push(float angle, float pitch, float distance, uint32_t timestamp_ms, const Vector3f ¤t_pos, const Matrix3f &body_to_ned); - uint32_t _last_timeout_check_ms; // time when boundary was checked for non-updated valid faces - - // used for ground detection - uint32_t _last_downward_update_ms; - bool _rangefinder_use; - bool _rangefinder_healthy; - float _rangefinder_alt; - AP_Proximity &frontend; AP_Proximity::Proximity_State &state; // reference to this instances state - - // Methods to manipulate 3D boundary in this class - AP_Proximity_Boundary_3D boundary; + AP_Proximity_Params ¶ms; // parameters for this backend }; #endif // HAL_PROXIMITY_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_Backend_Serial.cpp b/libraries/AP_Proximity/AP_Proximity_Backend_Serial.cpp index 4d77598cce3..8d0de98c7d0 100644 --- a/libraries/AP_Proximity/AP_Proximity_Backend_Serial.cpp +++ b/libraries/AP_Proximity/AP_Proximity_Backend_Serial.cpp @@ -24,22 +24,25 @@ already know that we should setup the proximity sensor */ AP_Proximity_Backend_Serial::AP_Proximity_Backend_Serial(AP_Proximity &_frontend, - AP_Proximity::Proximity_State &_state) : - AP_Proximity_Backend(_frontend, _state) + AP_Proximity::Proximity_State &_state, + AP_Proximity_Params &_params, + uint8_t serial_instance) : + AP_Proximity_Backend(_frontend, _state, _params) { const AP_SerialManager &serial_manager = AP::serialmanager(); - _uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Lidar360, 0); + _uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Lidar360, serial_instance); if (_uart != nullptr) { // start uart with larger receive buffer - _uart->begin(serial_manager.find_baudrate(AP_SerialManager::SerialProtocol_Lidar360, 0), rxspace(), 0); + _uart->begin(serial_manager.find_baudrate(AP_SerialManager::SerialProtocol_Lidar360, serial_instance), rxspace(), 0); } } -// detect if a proximity sensor is connected by looking for a -// configured serial port -bool AP_Proximity_Backend_Serial::detect() +// static detection function +// detect if a proximity sensor is connected by looking for a configured serial port +// serial_instance affects which serial port is used. Should be 0 or 1 depending on whether this is the 1st or 2nd proximity sensor with a serial interface +bool AP_Proximity_Backend_Serial::detect(uint8_t serial_instance) { - return AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_Lidar360, 0); + return AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_Lidar360, serial_instance); } #endif // HAL_PROXIMITY_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_Backend_Serial.h b/libraries/AP_Proximity/AP_Proximity_Backend_Serial.h index af053345099..ac363fbe463 100644 --- a/libraries/AP_Proximity/AP_Proximity_Backend_Serial.h +++ b/libraries/AP_Proximity/AP_Proximity_Backend_Serial.h @@ -8,9 +8,14 @@ class AP_Proximity_Backend_Serial : public AP_Proximity_Backend { public: AP_Proximity_Backend_Serial(AP_Proximity &_frontend, - AP_Proximity::Proximity_State &_state); + AP_Proximity::Proximity_State &_state, + AP_Proximity_Params& _params, + uint8_t serial_instance); + // static detection function - static bool detect(); + // detect if a proximity sensor is connected by looking for a configured serial port + // serial_instance affects which serial port is used. Should be 0 or 1 depending on whether this is the 1st or 2nd proximity sensor with a serial interface + static bool detect(uint8_t serial_instance); protected: virtual uint16_t rxspace() const { return 0; }; diff --git a/libraries/AP_Proximity/AP_Proximity_Boundary_3D.cpp b/libraries/AP_Proximity/AP_Proximity_Boundary_3D.cpp index 3bb63f1809d..9fd2a7ae4eb 100644 --- a/libraries/AP_Proximity/AP_Proximity_Boundary_3D.cpp +++ b/libraries/AP_Proximity/AP_Proximity_Boundary_3D.cpp @@ -15,8 +15,7 @@ #include "AP_Proximity_Boundary_3D.h" -#if HAL_PROXIMITY_ENABLED -#include "AP_Proximity_Backend.h" +#define PROXIMITY_BOUNDARY_3D_TIMEOUT_MS 750 // we should check the 3D boundary faces after this many ms /* Constructor. @@ -46,7 +45,7 @@ void AP_Proximity_Boundary_3D::init() // pitch is the vertical body-frame angle (in degrees) to the obstacle (0=directly ahead, 90 is above the vehicle) // yaw is the horizontal body-frame angle (in degrees) to the obstacle (0=directly ahead of the vehicle, 90 is to the right of the vehicle) AP_Proximity_Boundary_3D::Face AP_Proximity_Boundary_3D::get_face(float pitch, float yaw) const -{ +{ const uint8_t sector = wrap_360(yaw + (PROXIMITY_SECTOR_WIDTH_DEG * 0.5f)) / 45.0f; const float pitch_limited = constrain_float(pitch, -75.0f, 74.9f); const uint8_t layer = (pitch_limited + 75.0f)/PROXIMITY_PITCH_WIDTH_DEG; @@ -54,17 +53,30 @@ AP_Proximity_Boundary_3D::Face AP_Proximity_Boundary_3D::get_face(float pitch, f } // Set the actual body-frame angle(yaw), pitch, and distance of the detected object. -// This method will also mark the sector and layer to be "valid", so this distance can be used for Obstacle Avoidance -void AP_Proximity_Boundary_3D::set_face_attributes(const Face &face, float pitch, float angle, float distance) +// This method will also mark the sector and layer to be "valid", +// This distance can then be used for Obstacle Avoidance +// Assume detected obstacle is horizontal (zero pitch), if no pitch is passed +// prx_instance should be set to the proximity sensor backend instance number +void AP_Proximity_Boundary_3D::set_face_attributes(const Face &face, float pitch, float angle, float distance, uint8_t prx_instance) { if (!face.valid()) { return; } + // ignore update if another instance has provided a shorter distance within the last 0.2 seconds + if ((prx_instance != _prx_instance[face.layer][face.sector]) && _distance_valid[face.layer][face.sector] && (_filtered_distance[face.layer][face.sector].get() < distance)) { + // check if recent + const uint32_t now_ms = AP_HAL::millis(); + if (now_ms - _last_update_ms[face.layer][face.sector] < PROXIMITY_FACE_RESET_MS) { + return; + } + } + _angle[face.layer][face.sector] = angle; _pitch[face.layer][face.sector] = pitch; _distance[face.layer][face.sector] = distance; _distance_valid[face.layer][face.sector] = true; + _prx_instance[face.layer][face.sector] = prx_instance; // apply filter set_filtered_distance(face, distance); @@ -171,11 +183,26 @@ void AP_Proximity_Boundary_3D::reset() // Reset this location, specified by Face object, back to default // i.e Distance is marked as not-valid, and set to a large number. -void AP_Proximity_Boundary_3D::reset_face(const Face &face) +// prx_instance should be set to the proximity sensor's backend instance number +void AP_Proximity_Boundary_3D::reset_face(const Face &face, uint8_t prx_instance) { if (!face.valid()) { return; } + + // return immediately if face already has no valid distance + if (!_distance_valid[face.layer][face.sector]) { + return; + } + + // ignore reset if another instance provided this face's distance within the last 0.2 seconds + if (prx_instance != _prx_instance[face.layer][face.sector]) { + const uint32_t now_ms = AP_HAL::millis(); + if (now_ms - _last_update_ms[face.layer][face.sector] < 200) { + return; + } + } + _distance_valid[face.layer][face.sector] = false; // update simple avoidance boundary @@ -185,13 +212,20 @@ void AP_Proximity_Boundary_3D::reset_face(const Face &face) // check if a face has valid distance even if it was updated a long time back void AP_Proximity_Boundary_3D::check_face_timeout() { + // exit immediately if already checked recently + const uint32_t now_ms = AP_HAL::millis(); + if ((now_ms - _last_check_face_timeout_ms) < PROXIMITY_BOUNDARY_3D_TIMEOUT_MS) { + return; + } + _last_check_face_timeout_ms = now_ms; + for (uint8_t layer=0; layer < PROXIMITY_NUM_LAYERS; layer++) { for (uint8_t sector=0; sector < PROXIMITY_NUM_SECTORS; sector++) { if (_distance_valid[layer][sector]) { - if ((AP_HAL::millis() - _last_update_ms[layer][sector]) > PROXIMITY_FACE_RESET_MS) { + if ((now_ms - _last_update_ms[layer][sector]) > PROXIMITY_FACE_RESET_MS) { // this face has a valid distance but wasn't updated for a long time, reset it - AP_Proximity_Boundary_3D::Face face{layer, sector}; - reset_face(face); + _distance_valid[layer][sector] = false; + update_boundary(AP_Proximity_Boundary_3D::Face{layer, sector}); } } } @@ -363,7 +397,7 @@ bool AP_Proximity_Boundary_3D::get_filtered_distance(const Face &face, float &di } // Get raw and filtered distances in 8 directions per layer -bool AP_Proximity_Boundary_3D::get_layer_distances(uint8_t layer_number, float dist_max, AP_Proximity::Proximity_Distance_Array &prx_dist_array, AP_Proximity::Proximity_Distance_Array &prx_filt_dist_array) const +bool AP_Proximity_Boundary_3D::get_layer_distances(uint8_t layer_number, float dist_max, Proximity_Distance_Array &prx_dist_array, Proximity_Distance_Array &prx_filt_dist_array) const { // cycle through all sectors filling in distances and orientations // see MAV_SENSOR_ORIENTATION for orientations (0 = forward, 1 = 45 degree clockwise from north, etc) @@ -411,16 +445,16 @@ void AP_Proximity_Temp_Boundary::add_distance(const AP_Proximity_Boundary_3D::Fa } // fill the original 3D boundary with the contents of this temporary boundary -void AP_Proximity_Temp_Boundary::update_3D_boundary(AP_Proximity_Boundary_3D &boundary) +// prx_instance should be set to the proximity sensor's backend instance number +void AP_Proximity_Temp_Boundary::update_3D_boundary(uint8_t prx_instance, AP_Proximity_Boundary_3D &boundary) { for (uint8_t layer=0; layer < PROXIMITY_NUM_LAYERS; layer++) { for (uint8_t sector=0; sector < PROXIMITY_NUM_SECTORS; sector++) { if (_distances[layer][sector] < FLT_MAX) { AP_Proximity_Boundary_3D::Face face{layer, sector}; - boundary.set_face_attributes(face, _pitch[layer][sector], _angle[layer][sector], _distances[layer][sector]); + boundary.set_face_attributes(face, _pitch[layer][sector], _angle[layer][sector], _distances[layer][sector], prx_instance); } } } } -#endif // HAL_PROXIMITY_ENABLED \ No newline at end of file diff --git a/libraries/AP_Proximity/AP_Proximity_Boundary_3D.h b/libraries/AP_Proximity/AP_Proximity_Boundary_3D.h index e3fd1d11b23..4f22db5a318 100644 --- a/libraries/AP_Proximity/AP_Proximity_Boundary_3D.h +++ b/libraries/AP_Proximity/AP_Proximity_Boundary_3D.h @@ -15,10 +15,8 @@ #pragma once -#include "AP_Proximity.h" - -#if HAL_PROXIMITY_ENABLED - +#include +#include #include #define PROXIMITY_NUM_SECTORS 8 // number of sectors @@ -31,6 +29,19 @@ #define PROXIMITY_FILT_RESET_TIME 1000 // reset filter if last distance was pushed more than this many ms away #define PROXIMITY_FACE_RESET_MS 1000 // face will be reset if not updated within this many ms +// structure holding distances in PROXIMITY_MAX_DIRECTION directions. used for sending distances to ground station +#define PROXIMITY_MAX_DIRECTION 8 +struct Proximity_Distance_Array { + uint8_t orientation[PROXIMITY_MAX_DIRECTION]; // orientation (i.e. rough direction) of the distance (see MAV_SENSOR_ORIENTATION) + float distance[PROXIMITY_MAX_DIRECTION]; // distance in meters + bool valid(uint8_t offset) const { + // returns true if the distance stored at offset is valid + return (offset < 8 && (offset_valid & (1U<= PROXIMITY_NUM_SECTORS-1) ? 0 : sector+1); } - - // get the prev sector which is CCW to the passed sector + + // get the prev sector which is CCW to the passed sector uint8_t get_prev_sector(uint8_t sector) const {return ((sector <= 0) ? PROXIMITY_NUM_SECTORS-1 : sector-1); } // Converts obstacle_num passed from avoidance library into appropriate face of the boundary @@ -159,12 +172,14 @@ class AP_Proximity_Boundary_3D float _distance[PROXIMITY_NUM_LAYERS][PROXIMITY_NUM_SECTORS]; // distance to closest object within each sector and layer bool _distance_valid[PROXIMITY_NUM_LAYERS][PROXIMITY_NUM_SECTORS]; // true if a valid distance received for each sector and layer uint32_t _last_update_ms[PROXIMITY_NUM_LAYERS][PROXIMITY_NUM_SECTORS]; // time when distance was last updated + uint8_t _prx_instance[PROXIMITY_NUM_LAYERS][PROXIMITY_NUM_SECTORS]; // proximity sensor backend instance that provided the distance LowPassFilterFloat _filtered_distance[PROXIMITY_NUM_LAYERS][PROXIMITY_NUM_SECTORS]; // low pass filter float _filter_freq; // cutoff freq of low pass filter + uint32_t _last_check_face_timeout_ms; // system time to throttle check_face_timeout method }; // This class gives an easy way of making a temporary boundary, used for "sorting" distances. -// When unkown number of distances at various orientations are sent we store the least distance in the temporary boundary. +// When unknown number of distances at various orientations are sent we store the least distance in the temporary boundary. // After all the messages are received, we copy the contents of the temporary boundary and put it in the main 3-D boundary. class AP_Proximity_Temp_Boundary { @@ -178,10 +193,11 @@ class AP_Proximity_Temp_Boundary // add a distance to the temp boundary if it is shorter than any other provided distance since the last time the boundary was reset // pitch and yaw are in degrees, distance is in meters void add_distance(const AP_Proximity_Boundary_3D::Face &face, float pitch, float yaw, float distance); - void add_distance(const AP_Proximity_Boundary_3D::Face &face, float yaw, float distance) { add_distance(face, 0.0f, PID_TUNING_YAW, distance); } + void add_distance(const AP_Proximity_Boundary_3D::Face &face, float yaw, float distance) { add_distance(face, 0.0f, yaw, distance); } // fill the original 3D boundary with the contents of this temporary boundary - void update_3D_boundary(AP_Proximity_Boundary_3D &boundary); + // prx_instance should be set to the proximity sensor's backend instance number + void update_3D_boundary(uint8_t prx_instance, AP_Proximity_Boundary_3D &boundary); private: @@ -189,5 +205,3 @@ class AP_Proximity_Temp_Boundary float _angle[PROXIMITY_NUM_LAYERS][PROXIMITY_NUM_SECTORS]; // yaw angle in degrees to closest object within each sector and layer float _pitch[PROXIMITY_NUM_LAYERS][PROXIMITY_NUM_SECTORS]; // pitch angle in degrees to the closest object within each sector and layer }; - -#endif // HAL_PROXIMITY_ENABLED \ No newline at end of file diff --git a/libraries/AP_Proximity/AP_Proximity_Cygbot_D1.cpp b/libraries/AP_Proximity/AP_Proximity_Cygbot_D1.cpp index 654f511dafd..25a0ed8a812 100644 --- a/libraries/AP_Proximity/AP_Proximity_Cygbot_D1.cpp +++ b/libraries/AP_Proximity/AP_Proximity_Cygbot_D1.cpp @@ -118,7 +118,7 @@ bool AP_Proximity_Cygbot_D1::parse_byte(uint8_t data) // checksum is valid, parse payload _last_distance_received_ms = AP_HAL::millis(); parse_payload(); - _temp_boundary.update_3D_boundary(boundary); + _temp_boundary.update_3D_boundary(state.instance, frontend.boundary); reset(); return true; } @@ -139,20 +139,22 @@ void AP_Proximity_Cygbot_D1::parse_payload() // start from second byte as first byte is part of the header for (uint16_t i = 2; i < _msg.payload_len; i += 2) { + const float corrected_angle = correct_angle_for_orientation(sampled_angle); const uint16_t distance_mm = UINT16_VALUE(_msg.payload[i], _msg.payload[i+1]); float distance_m = distance_mm * 0.001f; if (distance_m > distance_min() && distance_m < distance_max()) { - if (ignore_reading(sampled_angle, distance_m)) { + if (ignore_reading(corrected_angle, distance_m)) { // ignore this angle sampled_angle += CYGBOT_2D_ANGLE_STEP; continue; } // convert angle to face - const AP_Proximity_Boundary_3D::Face face = boundary.get_face(sampled_angle); + const AP_Proximity_Boundary_3D::Face face = frontend.boundary.get_face(corrected_angle); + // push face to temp boundary - _temp_boundary.add_distance(face, sampled_angle, distance_m); + _temp_boundary.add_distance(face, corrected_angle, distance_m); // push to OA_DB - database_push(sampled_angle, distance_m); + database_push(corrected_angle, distance_m); } // increment sampled angle sampled_angle += CYGBOT_2D_ANGLE_STEP; diff --git a/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp b/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp index a7fe1e5c063..8204a08001b 100644 --- a/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp +++ b/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp @@ -307,8 +307,8 @@ void AP_Proximity_LightWareSF40C::process_message() // process each point const float angle_inc_deg = (1.0f / point_total) * 360.0f; - const float angle_sign = (frontend.get_orientation(state.instance) == 1) ? -1.0f : 1.0f; - const float angle_correction = frontend.get_yaw_correction(state.instance); + const float angle_sign = (params.orientation == 1) ? -1.0f : 1.0f; + const float angle_correction = params.yaw_correction; const uint16_t dist_min_cm = distance_min() * 100; const uint16_t dist_max_cm = distance_max() * 100; @@ -320,16 +320,16 @@ void AP_Proximity_LightWareSF40C::process_message() const uint16_t idx = 14 + (i * 2); const int16_t dist_cm = (int16_t)buff_to_uint16(_msg.payload[idx], _msg.payload[idx+1]); const float angle_deg = wrap_360((point_start_index + i) * angle_inc_deg * angle_sign + angle_correction); - const AP_Proximity_Boundary_3D::Face face = boundary.get_face(angle_deg); + const AP_Proximity_Boundary_3D::Face face = frontend.boundary.get_face(angle_deg); // if point is on a new face then finish off previous face if (face != _face) { // update boundary used for avoidance if (_face_distance_valid) { - boundary.set_face_attributes(_face, _face_yaw_deg, _face_distance); + frontend.boundary.set_face_attributes(_face, _face_yaw_deg, _face_distance, state.instance); } else { // mark previous face invalid - boundary.reset_face(_face); + frontend.boundary.reset_face(_face, state.instance); } // init for new face _face = face; diff --git a/libraries/AP_Proximity/AP_Proximity_LightWareSF45B.cpp b/libraries/AP_Proximity/AP_Proximity_LightWareSF45B.cpp index 0867b30a7d3..79db05c6aed 100644 --- a/libraries/AP_Proximity/AP_Proximity_LightWareSF45B.cpp +++ b/libraries/AP_Proximity/AP_Proximity_LightWareSF45B.cpp @@ -141,13 +141,13 @@ void AP_Proximity_LightWareSF45B::process_message() // if distance is from a new face then update distance, angle and boundary for previous face // get face from 3D boundary based on yaw angle to the object - const AP_Proximity_Boundary_3D::Face face = boundary.get_face(angle_deg); + const AP_Proximity_Boundary_3D::Face face = frontend.boundary.get_face(angle_deg); if (face != _face) { if (_face_distance_valid) { - boundary.set_face_attributes(_face, _face_yaw_deg, _face_distance); + frontend.boundary.set_face_attributes(_face, _face_yaw_deg, _face_distance, state.instance); } else { // mark previous face invalid - boundary.reset_face(_face); + frontend.boundary.reset_face(_face, state.instance); } // record updated face _face = face; diff --git a/libraries/AP_Proximity/AP_Proximity_LightWareSF45B.h b/libraries/AP_Proximity/AP_Proximity_LightWareSF45B.h index 8438126d24f..fb32d7ca239 100644 --- a/libraries/AP_Proximity/AP_Proximity_LightWareSF45B.h +++ b/libraries/AP_Proximity/AP_Proximity_LightWareSF45B.h @@ -11,8 +11,10 @@ class AP_Proximity_LightWareSF45B : public AP_Proximity_LightWareSerial public: // constructor AP_Proximity_LightWareSF45B(AP_Proximity &_frontend, - AP_Proximity::Proximity_State &_state) : - AP_Proximity_LightWareSerial(_frontend, _state) {} + AP_Proximity::Proximity_State &_state, + AP_Proximity_Params& _params, + uint8_t serial_instance) : + AP_Proximity_LightWareSerial(_frontend, _state, _params, serial_instance) {} uint16_t rxspace() const override { return 1280; diff --git a/libraries/AP_Proximity/AP_Proximity_MAV.cpp b/libraries/AP_Proximity/AP_Proximity_MAV.cpp index 13375fbeae4..254f1f36d73 100644 --- a/libraries/AP_Proximity/AP_Proximity_MAV.cpp +++ b/libraries/AP_Proximity/AP_Proximity_MAV.cpp @@ -86,7 +86,7 @@ void AP_Proximity_MAV::handle_distance_sensor_msg(const mavlink_message_t &msg) // provided we got the new obstacle in less than PROXIMITY_TIMESTAMP_MSG_TIMEOUT_MS if ((previous_msg_timestamp != _last_msg_update_timestamp_ms) || (time_diff > PROXIMITY_TIMESTAMP_MSG_TIMEOUT_MS)) { // push data from temp boundary to the main 3-D proximity boundary - temp_boundary.update_3D_boundary(boundary); + temp_boundary.update_3D_boundary(state.instance, frontend.boundary); // clear temp boundary for new data temp_boundary.reset(); } @@ -95,7 +95,7 @@ void AP_Proximity_MAV::handle_distance_sensor_msg(const mavlink_message_t &msg) const uint8_t sector = packet.orientation; // get the face for this sector const float yaw_angle_deg = sector * 45; - const AP_Proximity_Boundary_3D::Face face = boundary.get_face(yaw_angle_deg); + const AP_Proximity_Boundary_3D::Face face = frontend.boundary.get_face(yaw_angle_deg); _distance_min = packet.min_distance * 0.01f; _distance_max = packet.max_distance * 0.01f; const bool in_range = distance <= _distance_max && distance >= _distance_min; @@ -141,9 +141,9 @@ void AP_Proximity_MAV::handle_obstacle_distance_msg(const mavlink_message_t &msg _last_update_ms = AP_HAL::millis(); // get user configured yaw correction from front end - const float param_yaw_offset = constrain_float(frontend.get_yaw_correction(state.instance), -360.0f, +360.0f); + const float param_yaw_offset = constrain_float(params.yaw_correction, -360.0f, +360.0f); const float yaw_correction = wrap_360(param_yaw_offset + packet.angle_offset); - if (frontend.get_orientation(state.instance) != 0) { + if (params.orientation != 0) { increment *= -1; } @@ -158,7 +158,7 @@ void AP_Proximity_MAV::handle_obstacle_distance_msg(const mavlink_message_t &msg bool face_distance_valid = false; // reset this boundary to fill with new data - boundary.reset(); + frontend.boundary.reset(); // iterate over message's sectors for (uint8_t j = 0; j < total_distances; j++) { @@ -174,13 +174,13 @@ void AP_Proximity_MAV::handle_obstacle_distance_msg(const mavlink_message_t &msg } // get face for this latest reading - AP_Proximity_Boundary_3D::Face latest_face = boundary.get_face(mid_angle); + AP_Proximity_Boundary_3D::Face latest_face = frontend.boundary.get_face(mid_angle); if (latest_face != face) { // store previous face if (face_distance_valid) { - boundary.set_face_attributes(face, face_yaw_deg, face_distance); + frontend.boundary.set_face_attributes(face, face_yaw_deg, face_distance, state.instance); } else { - boundary.reset_face(face); + frontend.boundary.reset_face(face, state.instance); } // init for latest face face = latest_face; @@ -202,9 +202,9 @@ void AP_Proximity_MAV::handle_obstacle_distance_msg(const mavlink_message_t &msg // process the last face if (face_distance_valid) { - boundary.set_face_attributes(face, face_yaw_deg, face_distance); + frontend.boundary.set_face_attributes(face, face_yaw_deg, face_distance, state.instance); } else { - boundary.reset_face(face); + frontend.boundary.reset_face(face, state.instance); } return; } @@ -231,7 +231,7 @@ void AP_Proximity_MAV::handle_obstacle_distance_3d_msg(const mavlink_message_t & if ((previous_msg_timestamp != _last_msg_update_timestamp_ms) || (time_diff > PROXIMITY_TIMESTAMP_MSG_TIMEOUT_MS)) { // push data from temp boundary to the main 3-D proximity boundary because a new timestamp has arrived - temp_boundary.update_3D_boundary(boundary); + temp_boundary.update_3D_boundary(state.instance, frontend.boundary); // clear temp boundary for new data temp_boundary.reset(); } @@ -263,7 +263,7 @@ void AP_Proximity_MAV::handle_obstacle_distance_3d_msg(const mavlink_message_t & } // allot to correct layer and sector based on calculated pitch and yaw - const AP_Proximity_Boundary_3D::Face face = boundary.get_face(pitch, yaw); + const AP_Proximity_Boundary_3D::Face face = frontend.boundary.get_face(pitch, yaw); temp_boundary.add_distance(face, pitch, yaw, obstacle.length()); if (database_ready) { diff --git a/libraries/AP_Proximity/AP_Proximity_Params.cpp b/libraries/AP_Proximity/AP_Proximity_Params.cpp new file mode 100644 index 00000000000..af045c2b1ba --- /dev/null +++ b/libraries/AP_Proximity/AP_Proximity_Params.cpp @@ -0,0 +1,116 @@ +#include "AP_Proximity_Params.h" + +// table of user settable parameters +const AP_Param::GroupInfo AP_Proximity_Params::var_info[] = { + + // 0 should not be used + + // @Param: _TYPE + // @DisplayName: Proximity type + // @Description: What type of proximity sensor is connected + // @Values: 0:None,7:LightwareSF40c,2:MAVLink,3:TeraRangerTower,4:RangeFinder,5:RPLidarA2,6:TeraRangerTowerEvo,8:LightwareSF45B,10:SITL,12:AirSimSITL,13:CygbotD1 + // @RebootRequired: True + // @User: Standard + AP_GROUPINFO_FLAGS("_TYPE", 1, AP_Proximity_Params, type, 0, AP_PARAM_FLAG_ENABLE), + + // @Param: _ORIENT + // @DisplayName: Proximity sensor orientation + // @Description: Proximity sensor orientation + // @Values: 0:Default,1:Upside Down + // @User: Standard + AP_GROUPINFO("_ORIENT", 2, AP_Proximity_Params, orientation, 0), + + // @Param: _YAW_CORR + // @DisplayName: Proximity sensor yaw correction + // @Description: Proximity sensor yaw correction + // @Units: deg + // @Range: -180 180 + // @User: Standard + AP_GROUPINFO("_YAW_CORR", 3, AP_Proximity_Params, yaw_correction, 0), + + // @Param: _IGN_ANG1 + // @DisplayName: Proximity sensor ignore angle 1 + // @Description: Proximity sensor ignore angle 1 + // @Units: deg + // @Range: 0 360 + // @User: Standard + AP_GROUPINFO("_IGN_ANG1", 4, AP_Proximity_Params, ignore_angle_deg[0], 0), + + // @Param: _IGN_WID1 + // @DisplayName: Proximity sensor ignore width 1 + // @Description: Proximity sensor ignore width 1 + // @Units: deg + // @Range: 0 127 + // @User: Standard + AP_GROUPINFO("_IGN_WID1", 5, AP_Proximity_Params, ignore_width_deg[0], 0), + + // @Param: _IGN_ANG2 + // @DisplayName: Proximity sensor ignore angle 2 + // @Description: Proximity sensor ignore angle 2 + // @Units: deg + // @Range: 0 360 + // @User: Standard + AP_GROUPINFO("_IGN_ANG2", 6, AP_Proximity_Params, ignore_angle_deg[1], 0), + + // @Param: _IGN_WID2 + // @DisplayName: Proximity sensor ignore width 2 + // @Description: Proximity sensor ignore width 2 + // @Units: deg + // @Range: 0 127 + // @User: Standard + AP_GROUPINFO("_IGN_WID2", 7, AP_Proximity_Params, ignore_width_deg[1], 0), + + // @Param: _IGN_ANG3 + // @DisplayName: Proximity sensor ignore angle 3 + // @Description: Proximity sensor ignore angle 3 + // @Units: deg + // @Range: 0 360 + // @User: Standard + AP_GROUPINFO("_IGN_ANG3", 8, AP_Proximity_Params, ignore_angle_deg[2], 0), + + // @Param: _IGN_WID3 + // @DisplayName: Proximity sensor ignore width 3 + // @Description: Proximity sensor ignore width 3 + // @Units: deg + // @Range: 0 127 + // @User: Standard + AP_GROUPINFO("_IGN_WID3", 9, AP_Proximity_Params, ignore_width_deg[2], 0), + + // @Param: _IGN_ANG4 + // @DisplayName: Proximity sensor ignore angle 4 + // @Description: Proximity sensor ignore angle 4 + // @Units: deg + // @Range: 0 360 + // @User: Standard + AP_GROUPINFO("_IGN_ANG4", 10, AP_Proximity_Params, ignore_angle_deg[3], 0), + + // @Param: _IGN_WID4 + // @DisplayName: Proximity sensor ignore width 4 + // @Description: Proximity sensor ignore width 4 + // @Units: deg + // @Range: 0 127 + // @User: Standard + AP_GROUPINFO("_IGN_WID4", 11, AP_Proximity_Params, ignore_width_deg[3], 0), + + // @Param: _MIN + // @DisplayName: Proximity minimum range + // @Description: Minimum expected range for Proximity Sensor. Setting this to 0 will set value to manufacturer reported range. + // @Units: m + // @Range: 0 500 + // @User: Advanced + AP_GROUPINFO("_MIN", 16, AP_Proximity_Params, min_m, 0.0f), + + // @Param: _MAX + // @DisplayName: Proximity maximum range + // @Description: Maximum expected range for Proximity Sensor. Setting this to 0 will set value to manufacturer reported range. + // @Units: m + // @Range: 0 500 + // @User: Advanced + AP_GROUPINFO("_MAX", 17, AP_Proximity_Params, max_m, 0.0f), + + AP_GROUPEND +}; + +AP_Proximity_Params::AP_Proximity_Params(void) { + AP_Param::setup_object_defaults(this, var_info); +} diff --git a/libraries/AP_Proximity/AP_Proximity_Params.h b/libraries/AP_Proximity/AP_Proximity_Params.h new file mode 100644 index 00000000000..21c5ba65527 --- /dev/null +++ b/libraries/AP_Proximity/AP_Proximity_Params.h @@ -0,0 +1,27 @@ +#pragma once + +#include +#include + +#define PROXIMITY_MAX_IGNORE 4 // up to six areas can be ignored + +class AP_Proximity_Params { + +public: + + static const struct AP_Param::GroupInfo var_info[]; + + AP_Proximity_Params(void); + + /* Do not allow copies */ + AP_Proximity_Params(const AP_Proximity_Params &other) = delete; + AP_Proximity_Params &operator=(const AP_Proximity_Params&) = delete; + + AP_Int8 type; // type of sensor + AP_Int8 orientation; // orientation (e.g. right-side-up or upside-down) + AP_Int16 yaw_correction; // yaw correction in degrees + AP_Int16 ignore_angle_deg[PROXIMITY_MAX_IGNORE]; // angle (in degrees) of area that should be ignored by sensor (i.e. leg shows up) + AP_Int8 ignore_width_deg[PROXIMITY_MAX_IGNORE]; // width of beam (in degrees) that should be ignored + AP_Float max_m; // maximum range in meters + AP_Float min_m; // minimum range in meters +}; diff --git a/libraries/AP_Proximity/AP_Proximity_RPLidarA2.cpp b/libraries/AP_Proximity/AP_Proximity_RPLidarA2.cpp index b470209ebc0..63d4c82230c 100644 --- a/libraries/AP_Proximity/AP_Proximity_RPLidarA2.cpp +++ b/libraries/AP_Proximity/AP_Proximity_RPLidarA2.cpp @@ -305,8 +305,8 @@ void AP_Proximity_RPLidarA2::parse_response_data() Debug(2, "UART %02x %02x%02x %02x%02x", payload[0], payload[2], payload[1], payload[4], payload[3]); //show HEX values // check if valid SCAN packet: a valid packet starts with startbits which are complementary plus a checkbit in byte+1 if ((payload.sensor_scan.startbit == !payload.sensor_scan.not_startbit) && payload.sensor_scan.checkbit) { - const float angle_sign = (frontend.get_orientation(state.instance) == 1) ? -1.0f : 1.0f; - const float angle_deg = wrap_360(payload.sensor_scan.angle_q6/64.0f * angle_sign + frontend.get_yaw_correction(state.instance)); + const float angle_sign = (params.orientation == 1) ? -1.0f : 1.0f; + const float angle_deg = wrap_360(payload.sensor_scan.angle_q6/64.0f * angle_sign + params.yaw_correction); const float distance_m = (payload.sensor_scan.distance_q2/4000.0f); #if RP_DEBUG_LEVEL >= 2 const uint8_t quality = payload.sensor_scan.quality; @@ -314,15 +314,15 @@ void AP_Proximity_RPLidarA2::parse_response_data() #endif _last_distance_received_ms = AP_HAL::millis(); if (!ignore_reading(angle_deg, distance_m)) { - const AP_Proximity_Boundary_3D::Face face = boundary.get_face(angle_deg); + const AP_Proximity_Boundary_3D::Face face = frontend.boundary.get_face(angle_deg); if (face != _last_face) { // distance is for a new face, the previous one can be updated now if (_last_distance_valid) { - boundary.set_face_attributes(_last_face, _last_angle_deg, _last_distance_m); + frontend.boundary.set_face_attributes(_last_face, _last_angle_deg, _last_distance_m, state.instance); } else { // reset distance from last face - boundary.reset_face(face); + frontend.boundary.reset_face(face, state.instance); } // initialize the new face diff --git a/libraries/AP_Proximity/AP_Proximity_RangeFinder.cpp b/libraries/AP_Proximity/AP_Proximity_RangeFinder.cpp index b7867913e8c..ebcca88be7d 100644 --- a/libraries/AP_Proximity/AP_Proximity_RangeFinder.cpp +++ b/libraries/AP_Proximity/AP_Proximity_RangeFinder.cpp @@ -45,17 +45,17 @@ void AP_Proximity_RangeFinder::update(void) if (sensor->orientation() <= ROTATION_YAW_315) { const uint8_t sector = (uint8_t)sensor->orientation(); const float angle = sector * 45; - const AP_Proximity_Boundary_3D::Face face = boundary.get_face(angle); + const AP_Proximity_Boundary_3D::Face face = frontend.boundary.get_face(angle); // distance in meters const float distance = sensor->distance(); _distance_min = sensor->min_distance_cm() * 0.01f; _distance_max = sensor->max_distance_cm() * 0.01f; if ((distance <= _distance_max) && (distance >= _distance_min) && !ignore_reading(angle, distance, false)) { - boundary.set_face_attributes(face, angle, distance); + frontend.boundary.set_face_attributes(face, angle, distance, state.instance); // update OA database database_push(angle, distance); } else { - boundary.reset_face(face); + frontend.boundary.reset_face(face, state.instance); } _last_update_ms = now; } diff --git a/libraries/AP_Proximity/AP_Proximity_SITL.cpp b/libraries/AP_Proximity/AP_Proximity_SITL.cpp index 730a8cb9705..f5a71de2f36 100644 --- a/libraries/AP_Proximity/AP_Proximity_SITL.cpp +++ b/libraries/AP_Proximity/AP_Proximity_SITL.cpp @@ -33,8 +33,9 @@ extern const AP_HAL::HAL& hal; The constructor also initialises the proximity sensor. */ AP_Proximity_SITL::AP_Proximity_SITL(AP_Proximity &_frontend, - AP_Proximity::Proximity_State &_state): - AP_Proximity_Backend(_frontend, _state), + AP_Proximity::Proximity_State &_state, + AP_Proximity_Params& _params): + AP_Proximity_Backend(_frontend, _state, _params), sitl(AP::sitl()) { ap_var_type ptype; @@ -51,6 +52,7 @@ void AP_Proximity_SITL::update(void) current_loc.lng = sitl->state.longitude * 1.0e7; current_loc.alt = sitl->state.altitude * 1.0e2; +#if AP_FENCE_ENABLED if (!AP::fence()->polyfence().breached()) { // only called to prompt polyfence to reload fence if required } @@ -59,24 +61,28 @@ void AP_Proximity_SITL::update(void) // update distance in each sector for (uint8_t sector=0; sector < PROXIMITY_NUM_SECTORS; sector++) { const float yaw_angle_deg = sector * 45.0f; - AP_Proximity_Boundary_3D::Face face = boundary.get_face(yaw_angle_deg); + AP_Proximity_Boundary_3D::Face face = frontend.boundary.get_face(yaw_angle_deg); float fence_distance; if (get_distance_to_fence(yaw_angle_deg, fence_distance)) { - boundary.set_face_attributes(face, yaw_angle_deg, fence_distance); + frontend.boundary.set_face_attributes(face, yaw_angle_deg, fence_distance, state.instance); // update OA database database_push(yaw_angle_deg, fence_distance); } else { - boundary.reset_face(face); + frontend.boundary.reset_face(face, state.instance); } } } else { set_status(AP_Proximity::Status::NoData); } +#else + set_status(AP_Proximity::Status::NoData); +#endif } // get distance in meters to fence in a particular direction in degrees (0 is forward, angles increase in the clockwise direction) bool AP_Proximity_SITL::get_distance_to_fence(float angle_deg, float &distance) const { +#if AP_FENCE_ENABLED if (!AP::fence()->polyfence().inclusion_boundary_available()) { return false; } @@ -106,6 +112,9 @@ bool AP_Proximity_SITL::get_distance_to_fence(float angle_deg, float &distance) return false; } return true; +#else + return false; +#endif } // get maximum and minimum distances (in meters) of primary sensor diff --git a/libraries/AP_Proximity/AP_Proximity_SITL.h b/libraries/AP_Proximity/AP_Proximity_SITL.h index e0620169126..ba85dd966d4 100644 --- a/libraries/AP_Proximity/AP_Proximity_SITL.h +++ b/libraries/AP_Proximity/AP_Proximity_SITL.h @@ -14,7 +14,7 @@ class AP_Proximity_SITL : public AP_Proximity_Backend public: // constructor - AP_Proximity_SITL(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state); + AP_Proximity_SITL(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state, AP_Proximity_Params& _params); // update state void update(void) override; @@ -31,9 +31,6 @@ class AP_Proximity_SITL : public AP_Proximity_Backend AP_Float *fence_alt_max; Location current_loc; - // latest sector updated - uint8_t last_sector; - // get distance in meters to fence in a particular direction in degrees (0 is forward, angles increase in the clockwise direction) bool get_distance_to_fence(float angle_deg, float &distance) const; diff --git a/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.cpp b/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.cpp index ab82f90d987..3c7119726a0 100644 --- a/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.cpp +++ b/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.cpp @@ -92,16 +92,16 @@ bool AP_Proximity_TeraRangerTower::read_sensor_data() } // process reply -void AP_Proximity_TeraRangerTower::update_sector_data(int16_t angle_deg, uint16_t distance_cm) +void AP_Proximity_TeraRangerTower::update_sector_data(int16_t angle_deg, uint16_t distance_mm) { // Get location on 3-D boundary based on angle to the object - const AP_Proximity_Boundary_3D::Face face = boundary.get_face(angle_deg); - if ((distance_cm != 0xffff) && !ignore_reading(angle_deg, distance_cm * 0.001f, false)) { - boundary.set_face_attributes(face, angle_deg, ((float) distance_cm) / 1000); + const AP_Proximity_Boundary_3D::Face face = frontend.boundary.get_face(angle_deg); + if ((distance_mm != 0xffff) && !ignore_reading(angle_deg, distance_mm * 0.001f, false)) { + frontend.boundary.set_face_attributes(face, angle_deg, ((float) distance_mm) / 1000, state.instance); // update OA database - database_push(angle_deg, ((float) distance_cm) / 1000); + database_push(angle_deg, ((float) distance_mm) / 1000); } else { - boundary.reset_face(face); + frontend.boundary.reset_face(face, state.instance); } _last_distance_received_ms = AP_HAL::millis(); } diff --git a/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.h b/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.h index bcbd40baadf..35006cad847 100644 --- a/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.h +++ b/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.h @@ -23,7 +23,7 @@ class AP_Proximity_TeraRangerTower : public AP_Proximity_Backend_Serial // check and process replies from sensor bool read_sensor_data(); - void update_sector_data(int16_t angle_deg, uint16_t distance_cm); + void update_sector_data(int16_t angle_deg, uint16_t distance_mm); // reply related variables uint8_t buffer[20]; // buffer where to store data from serial diff --git a/libraries/AP_Proximity/AP_Proximity_TeraRangerTowerEvo.cpp b/libraries/AP_Proximity/AP_Proximity_TeraRangerTowerEvo.cpp index 29a911b761b..e9aceee7863 100644 --- a/libraries/AP_Proximity/AP_Proximity_TeraRangerTowerEvo.cpp +++ b/libraries/AP_Proximity/AP_Proximity_TeraRangerTowerEvo.cpp @@ -145,18 +145,18 @@ bool AP_Proximity_TeraRangerTowerEvo::read_sensor_data() } // process reply -void AP_Proximity_TeraRangerTowerEvo::update_sector_data(int16_t angle_deg, uint16_t distance_cm) +void AP_Proximity_TeraRangerTowerEvo::update_sector_data(int16_t angle_deg, uint16_t distance_mm) { // Get location on 3-D boundary based on angle to the object - const AP_Proximity_Boundary_3D::Face face = boundary.get_face(angle_deg); + const AP_Proximity_Boundary_3D::Face face = frontend.boundary.get_face(angle_deg); //check for target too far, target too close and sensor not connected - const bool valid = (distance_cm != 0xffff) && (distance_cm > 0x0001); - if (valid && !ignore_reading(angle_deg, distance_cm * 0.001f, false)) { - boundary.set_face_attributes(face, angle_deg, ((float) distance_cm) / 1000); + const bool valid = (distance_mm != 0xffff) && (distance_mm > 0x0001); + if (valid && !ignore_reading(angle_deg, distance_mm * 0.001f, false)) { + frontend.boundary.set_face_attributes(face, angle_deg, ((float) distance_mm) / 1000, state.instance); // update OA database - database_push(angle_deg, ((float) distance_cm) / 1000); + database_push(angle_deg, ((float) distance_mm) / 1000); } else { - boundary.reset_face(face); + frontend.boundary.reset_face(face, state.instance); } _last_distance_received_ms = AP_HAL::millis(); } diff --git a/libraries/AP_Proximity/AP_Proximity_TeraRangerTowerEvo.h b/libraries/AP_Proximity/AP_Proximity_TeraRangerTowerEvo.h index 59261bf15ef..4b12d3fab6e 100644 --- a/libraries/AP_Proximity/AP_Proximity_TeraRangerTowerEvo.h +++ b/libraries/AP_Proximity/AP_Proximity_TeraRangerTowerEvo.h @@ -25,7 +25,7 @@ class AP_Proximity_TeraRangerTowerEvo : public AP_Proximity_Backend_Serial { // check and process replies from sensor void initialise_modes(); bool read_sensor_data(); - void update_sector_data(int16_t angle_deg, uint16_t distance_cm); + void update_sector_data(int16_t angle_deg, uint16_t distance_mm); void set_mode(const uint8_t *c, int length); enum InitState { diff --git a/libraries/AP_Proximity/AP_Proximity_Utils.cpp b/libraries/AP_Proximity/AP_Proximity_Utils.cpp new file mode 100644 index 00000000000..966f868a79a --- /dev/null +++ b/libraries/AP_Proximity/AP_Proximity_Utils.cpp @@ -0,0 +1,91 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +#include "AP_Proximity.h" +#include +#include +#include + +#if HAL_PROXIMITY_ENABLED + +#define PROXIMITY_GND_DETECT_THRESHOLD 1.0f // set ground detection threshold to be 1 meters +#define PROXIMITY_ALT_DETECT_TIMEOUT_MS 500 // alt readings should arrive within this much time + +extern const AP_HAL::HAL& hal; + +// set alt as read from downward facing rangefinder. Tilt is already adjusted for. +void AP_Proximity::set_rangefinder_alt(bool use, bool healthy, float alt_cm) +{ + _rangefinder_state.use = use; + _rangefinder_state.healthy = healthy; + _rangefinder_state.alt_cm = alt_cm; + _rangefinder_state.last_downward_update_ms = AP_HAL::millis(); +} + +// get alt from rangefinder in meters +bool AP_Proximity::get_rangefinder_alt(float &alt_m) const +{ + if (!_rangefinder_state.use || !_rangefinder_state.healthy) { + // range finder is not healthy + return false; + } + + const uint32_t dt = AP_HAL::millis() - _rangefinder_state.last_downward_update_ms; + if (dt > PROXIMITY_ALT_DETECT_TIMEOUT_MS) { + return false; + } + + // readings are healthy + alt_m = _rangefinder_state.alt_cm * 0.01f; + return true; +} + +// Check if Obstacle defined by body-frame yaw and pitch is near ground +bool AP_Proximity::check_obstacle_near_ground(float pitch, float yaw, float distance) const +{ + if (!_ign_gnd_enable) { + return false; + } + if (!hal.util->get_soft_armed()) { + // don't run this feature while vehicle is disarmed, otherwise proximity data will not show up on GCS + return false; + } + if ((pitch > 90.0f) || (pitch < -90.0f)) { + // sanity check on pitch + return false; + } + // Assume object is yaw and pitch bearing and distance meters away from the vehicle + Vector3f object_3D; + object_3D.offset_bearing(wrap_180(yaw), (pitch * -1.0f), distance); + const Matrix3f body_to_ned = AP::ahrs().get_rotation_body_to_ned(); + const Vector3f rotated_object_3D = body_to_ned * object_3D; + + float alt = FLT_MAX; + if (!get_rangefinder_alt(alt)) { + return false; + } + + if (rotated_object_3D.z > -0.5f) { + // obstacle is at the most 0.5 meters above vehicle + if ((alt - PROXIMITY_GND_DETECT_THRESHOLD) < rotated_object_3D.z) { + // obstacle is near or below ground + return true; + } + } + return false; +} + + +#endif // HAL_PROXIMITY_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_config.h b/libraries/AP_Proximity/AP_Proximity_config.h new file mode 100644 index 00000000000..92e87818bdc --- /dev/null +++ b/libraries/AP_Proximity/AP_Proximity_config.h @@ -0,0 +1,7 @@ +#pragma once + +#include + +#ifndef HAL_PROXIMITY_ENABLED +#define HAL_PROXIMITY_ENABLED (!HAL_MINIMIZE_FEATURES && BOARD_FLASH_SIZE > 1024) +#endif diff --git a/libraries/AP_Proximity/LogStructure.h b/libraries/AP_Proximity/LogStructure.h new file mode 100644 index 00000000000..3f13268fd49 --- /dev/null +++ b/libraries/AP_Proximity/LogStructure.h @@ -0,0 +1,82 @@ +#pragma once + +#include +#include "AP_Proximity_config.h" + +#define LOG_IDS_FROM_PROXIMITY \ + LOG_PROXIMITY_MSG, \ + LOG_RAW_PROXIMITY_MSG + +// @LoggerMessage: PRX +// @Description: Proximity Filtered sensor data +// @Field: TimeUS: Time since system startup +// @Field: Layer: Pitch(instance) at which the obstacle is at. 0th layer {-75,-45} degrees. 1st layer {-45,-15} degrees. 2nd layer {-15, 15} degrees. 3rd layer {15, 45} degrees. 4th layer {45,75} degrees. Minimum distance in each layer will be logged. +// @Field: He: True if proximity sensor is healthy +// @Field: D0: Nearest object in sector surrounding 0-degrees +// @Field: D45: Nearest object in sector surrounding 45-degrees +// @Field: D90: Nearest object in sector surrounding 90-degrees +// @Field: D135: Nearest object in sector surrounding 135-degrees +// @Field: D180: Nearest object in sector surrounding 180-degrees +// @Field: D225: Nearest object in sector surrounding 225-degrees +// @Field: D270: Nearest object in sector surrounding 270-degrees +// @Field: D315: Nearest object in sector surrounding 315-degrees +// @Field: DUp: Nearest object in upwards direction +// @Field: CAn: Angle to closest object +// @Field: CDis: Distance to closest object + +// proximity sensor logging +struct PACKED log_Proximity { + LOG_PACKET_HEADER; + uint64_t time_us; + uint8_t instance; + uint8_t health; + float dist0; + float dist45; + float dist90; + float dist135; + float dist180; + float dist225; + float dist270; + float dist315; + float distup; + float closest_angle; + float closest_dist; +}; + +// @LoggerMessage: PRXR +// @Description: Proximity Raw sensor data +// @Field: TimeUS: Time since system startup +// @Field: Layer: Pitch(instance) at which the obstacle is at. 0th layer {-75,-45} degrees. 1st layer {-45,-15} degrees. 2nd layer {-15, 15} degrees. 3rd layer {15, 45} degrees. 4th layer {45,75} degrees. Minimum distance in each layer will be logged. +// @Field: D0: Nearest object in sector surrounding 0-degrees +// @Field: D45: Nearest object in sector surrounding 45-degrees +// @Field: D90: Nearest object in sector surrounding 90-degrees +// @Field: D135: Nearest object in sector surrounding 135-degrees +// @Field: D180: Nearest object in sector surrounding 180-degrees +// @Field: D225: Nearest object in sector surrounding 225-degrees +// @Field: D270: Nearest object in sector surrounding 270-degrees +// @Field: D315: Nearest object in sector surrounding 315-degrees + +struct PACKED log_Proximity_raw { + LOG_PACKET_HEADER; + uint64_t time_us; + uint8_t instance; + float raw_dist0; + float raw_dist45; + float raw_dist90; + float raw_dist135; + float raw_dist180; + float raw_dist225; + float raw_dist270; + float raw_dist315; +}; + + +#if HAL_PROXIMITY_ENABLED +#define LOG_STRUCTURE_FROM_PROXIMITY \ + { LOG_PROXIMITY_MSG, sizeof(log_Proximity), \ + "PRX", "QBBfffffffffff", "TimeUS,Layer,He,D0,D45,D90,D135,D180,D225,D270,D315,DUp,CAn,CDis", "s#-mmmmmmmmmhm", "F--00000000000", true }, \ + { LOG_RAW_PROXIMITY_MSG, sizeof(log_Proximity_raw), \ + "PRXR", "QBffffffff", "TimeUS,Layer,D0,D45,D90,D135,D180,D225,D270,D315", "s#mmmmmmmm", "F-00000000", true }, +#else +#define LOG_STRUCTURE_FROM_PROXIMITY +#endif diff --git a/libraries/AP_RAMTRON/AP_RAMTRON.cpp b/libraries/AP_RAMTRON/AP_RAMTRON.cpp index f39160d7301..0f22bc71d31 100644 --- a/libraries/AP_RAMTRON/AP_RAMTRON.cpp +++ b/libraries/AP_RAMTRON/AP_RAMTRON.cpp @@ -46,10 +46,9 @@ bool AP_RAMTRON::init(void) { dev = hal.spi->get_device("ramtron"); if (!dev) { - hal.console->printf("No RAMTRON device\n"); + DEV_PRINTF("No RAMTRON device\n"); return false; } - WITH_SEMAPHORE(dev->get_semaphore()); struct cypress_rdid { uint8_t manufacturer[6]; @@ -65,8 +64,11 @@ bool AP_RAMTRON::init(void) uint8_t rdid[sizeof(cypress_rdid)]; - if (!dev->read_registers(RAMTRON_RDID, rdid, sizeof(rdid))) { - return false; + { + WITH_SEMAPHORE(dev->get_semaphore()); + if (!dev->read_registers(RAMTRON_RDID, rdid, sizeof(rdid))) { + return false; + } } for (uint8_t i = 0; i < ARRAY_SIZE(ramtron_ids); i++) { @@ -88,7 +90,7 @@ bool AP_RAMTRON::init(void) } if (id == UINT8_MAX) { - hal.console->printf("Unknown RAMTRON device\n"); + DEV_PRINTF("Unknown RAMTRON device\n"); return false; } diff --git a/libraries/AP_RCMapper/AP_RCMapper.cpp b/libraries/AP_RCMapper/AP_RCMapper.cpp index 4a4b9efbedf..fc09016e1df 100644 --- a/libraries/AP_RCMapper/AP_RCMapper.cpp +++ b/libraries/AP_RCMapper/AP_RCMapper.cpp @@ -5,7 +5,7 @@ const AP_Param::GroupInfo RCMapper::var_info[] = { // @Param: ROLL // @DisplayName: Roll channel // @Description: Roll channel number. This is useful when you have a RC transmitter that can't change the channel order easily. Roll is normally on channel 1, but you can move it to any channel with this parameter. Reboot is required for changes to take effect. - // @Range: 1 8 + // @Range: 1 16 // @Increment: 1 // @User: Advanced // @RebootRequired: True @@ -14,7 +14,7 @@ const AP_Param::GroupInfo RCMapper::var_info[] = { // @Param: PITCH // @DisplayName: Pitch channel // @Description: Pitch channel number. This is useful when you have a RC transmitter that can't change the channel order easily. Pitch is normally on channel 2, but you can move it to any channel with this parameter. Reboot is required for changes to take effect. - // @Range: 1 8 + // @Range: 1 16 // @Increment: 1 // @User: Advanced // @RebootRequired: True @@ -22,8 +22,8 @@ const AP_Param::GroupInfo RCMapper::var_info[] = { // @Param: THROTTLE // @DisplayName: Throttle channel - // @Description: Throttle channel number. This is useful when you have a RC transmitter that can't change the channel order easily. Throttle is normally on channel 3, but you can move it to any channel with this parameter. Warning APM 2.X: Changing the throttle channel could produce unexpected fail-safe results if connection between receiver and on-board PPM Encoder is lost. Disabling on-board PPM Encoder is recommended. Reboot is required for changes to take effect. - // @Range: 1 8 + // @Description: Throttle channel number. This is useful when you have a RC transmitter that can't change the channel order easily. Throttle is normally on channel 3, but you can move it to any channel with this parameter. Reboot is required for changes to take effect. + // @Range: 1 16 // @Increment: 1 // @User: Advanced // @RebootRequired: True @@ -32,25 +32,25 @@ const AP_Param::GroupInfo RCMapper::var_info[] = { // @Param: YAW // @DisplayName: Yaw channel // @Description: Yaw channel number. This is useful when you have a RC transmitter that can't change the channel order easily. Yaw (also known as rudder) is normally on channel 4, but you can move it to any channel with this parameter. Reboot is required for changes to take effect. - // @Range: 1 8 + // @Range: 1 16 // @Increment: 1 // @User: Advanced // @RebootRequired: True AP_GROUPINFO("YAW", 3, RCMapper, _ch_yaw, 4), - // @Param{Rover,Sub}: FORWARD + // @Param{Sub}: FORWARD // @DisplayName: Forward channel // @Description: Forward channel number. This is useful when you have a RC transmitter that can't change the channel order easily. Forward is normally on channel 5, but you can move it to any channel with this parameter. Reboot is required for changes to take effect. - // @Range: 1 8 + // @Range: 1 16 // @Increment: 1 // @User: Advanced // @RebootRequired: True AP_GROUPINFO_FRAME("FORWARD", 4, RCMapper, _ch_forward, 6, AP_PARAM_FRAME_SUB), - // @Param{Rover,Sub}: LATERAL + // @Param{Sub}: LATERAL // @DisplayName: Lateral channel // @Description: Lateral channel number. This is useful when you have a RC transmitter that can't change the channel order easily. Lateral is normally on channel 6, but you can move it to any channel with this parameter. Reboot is required for changes to take effect. - // @Range: 1 8 + // @Range: 1 16 // @Increment: 1 // @User: Advanced // @RebootRequired: True diff --git a/libraries/AP_RCProtocol/AP_RCProtocol.cpp b/libraries/AP_RCProtocol/AP_RCProtocol.cpp index 7a53e5b1e61..cffef306bc3 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol.cpp @@ -68,10 +68,15 @@ AP_RCProtocol::~AP_RCProtocol() bool AP_RCProtocol::should_search(uint32_t now_ms) const { -#ifndef IOMCU_FW +#if !defined(IOMCU_FW) && !APM_BUILD_TYPE(APM_BUILD_UNKNOWN) if (_detected_protocol != AP_RCProtocol::NONE && !rc().multiple_receiver_support()) { return false; } +#else + // on IOMCU don't allow protocol to change once detected + if (_detected_protocol != AP_RCProtocol::NONE) { + return false; + } #endif return (now_ms - _last_input_ms >= 200); } @@ -214,7 +219,7 @@ bool AP_RCProtocol::process_byte(uint8_t byte, uint32_t baudrate) } // stop decoding pulses to save CPU hal.rcin->pulse_input_enable(false); - break; + return true; } } } @@ -309,6 +314,13 @@ void AP_RCProtocol::check_added_uart(void) } added.opened = false; } + // power loss on CRSF requires re-bootstrap because the baudrate is reset to the default. The CRSF side will + // drop back down to 416k if it has received 200 incorrect characters (or none at all) + } else if (_detected_protocol != AP_RCProtocol::NONE + // protocols that want to be able to renegotiate should return false in is_rx_active() + && !backend[_detected_protocol]->is_rx_active() + && now - added.last_config_change_ms > 1000) { + added.opened = false; } } diff --git a/libraries/AP_RCProtocol/AP_RCProtocol.h b/libraries/AP_RCProtocol/AP_RCProtocol.h index 55b1960bac9..0c89b4a2556 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol.h +++ b/libraries/AP_RCProtocol/AP_RCProtocol.h @@ -67,6 +67,13 @@ class AP_RCProtocol { void process_handshake(uint32_t baudrate); void update(void); + bool failsafe_active() const { + return _failsafe_active; + } + void set_failsafe_active(bool active) { + _failsafe_active = active; + } + void disable_for_pulses(enum rcprotocol_t protocol) { _disabled_for_pulses |= (1U<<(uint8_t)protocol); } @@ -83,12 +90,12 @@ class AP_RCProtocol { case PPM: case FPORT: case FPORT2: + case CRSF: return true; case IBUS: case SUMD: case SRXL: case SRXL2: - case CRSF: case ST24: case NONE: return false; @@ -117,6 +124,7 @@ class AP_RCProtocol { // add a UART for RCIN void add_uart(AP_HAL::UARTDriver* uart); + bool has_uart() const { return added.uart != nullptr; } #ifdef IOMCU_FW // set allowed RC protocols @@ -135,6 +143,11 @@ class AP_RCProtocol { bool invert_rx; }; + // return true if we are decoding a byte stream, instead of pulses + bool using_uart(void) const { + return _detected_with_bytes; + } + private: void check_added_uart(void); @@ -147,6 +160,7 @@ class AP_RCProtocol { AP_RCProtocol_Backend *backend[NONE]; bool _new_input; uint32_t _last_input_ms; + bool _failsafe_active; bool _valid_serial_prot; // optional additional uart diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_Backend.cpp b/libraries/AP_RCProtocol/AP_RCProtocol_Backend.cpp index 6931ee9775a..3459f1748fa 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_Backend.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol_Backend.cpp @@ -64,7 +64,11 @@ void AP_RCProtocol_Backend::add_input(uint8_t num_values, uint16_t *values, bool memcpy(_pwm_values, values, num_values*sizeof(uint16_t)); _num_channels = num_values; rc_frame_count++; -#if !APM_BUILD_TYPE(APM_BUILD_iofirmware) + frontend.set_failsafe_active(in_failsafe); +#if APM_BUILD_TYPE(APM_BUILD_iofirmware) + // failsafed is sorted out in AP_IOMCU.cpp + in_failsafe = false; +#else if (rc().ignore_rc_failsafe()) { in_failsafe = false; } diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_Backend.h b/libraries/AP_RCProtocol/AP_RCProtocol_Backend.h index 1dc03a6c72f..b6cb6a3cae9 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_Backend.h +++ b/libraries/AP_RCProtocol/AP_RCProtocol_Backend.h @@ -85,6 +85,11 @@ class AP_RCProtocol_Backend { bool have_UART(void) const { return frontend.added.uart != nullptr; } + + // is the receiver active, used to detect power loss and baudrate changes + virtual bool is_rx_active() const { + return true; + } protected: struct Channels11Bit_8Chan { diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.cpp b/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.cpp index ef555bc8fe6..8671b832122 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.cpp @@ -147,14 +147,17 @@ static const char* get_frame_type(uint8_t byte, uint8_t subtype = 0) #define CRSF_INTER_FRAME_TIME_US_250HZ 4000U // At fastest, frames are sent by the transmitter every 4 ms, 250 Hz #define CRSF_INTER_FRAME_TIME_US_150HZ 6667U // At medium, frames are sent by the transmitter every 6.667 ms, 150 Hz #define CRSF_INTER_FRAME_TIME_US_50HZ 20000U // At slowest, frames are sent by the transmitter every 20ms, 50 Hz -#define CSRF_HEADER_LEN 2 // header length #define CSRF_HEADER_TYPE_LEN (CSRF_HEADER_LEN + 1) // header length including type #define CRSF_DIGITAL_CHANNEL_MIN 172 #define CRSF_DIGITAL_CHANNEL_MAX 1811 -constexpr uint16_t AP_RCProtocol_CRSF::elrs_air_rates[8]; +const uint16_t AP_RCProtocol_CRSF::RF_MODE_RATES[RFMode::RF_MODE_MAX_MODES] = { + 4, 50, 150, 250, // CRSF + 4, 25, 50, 100, 150, 200, 250, 500 // ELRS +}; + AP_RCProtocol_CRSF* AP_RCProtocol_CRSF::_singleton; AP_RCProtocol_CRSF::AP_RCProtocol_CRSF(AP_RCProtocol &_frontend) : AP_RCProtocol_Backend(_frontend) @@ -182,11 +185,23 @@ AP_RCProtocol_CRSF::~AP_RCProtocol_CRSF() { _singleton = nullptr; } -void AP_RCProtocol_CRSF::process_pulse(uint32_t width_s0, uint32_t width_s1) -{ - uint8_t b; - if (ss.process_pulse(width_s0, width_s1, b)) { - _process_byte(ss.get_byte_timestamp_us(), b); +// get the protocol string +const char* AP_RCProtocol_CRSF::get_protocol_string(ProtocolType protocol) const { + if (protocol == ProtocolType::PROTOCOL_ELRS) { + return "ELRS"; + } else if (_crsf_v3_active) { + return "CRSFv3"; + } else { + return "CRSFv2"; + } +} + +// return the link rate as defined by the LinkStatistics +uint16_t AP_RCProtocol_CRSF::get_link_rate(ProtocolType protocol) const { + if (protocol == ProtocolType::PROTOCOL_ELRS) { + return RF_MODE_RATES[_link_status.rf_mode + RFMode::ELRS_RF_MODE_4HZ]; + } else { + return RF_MODE_RATES[_link_status.rf_mode]; } } @@ -199,8 +214,6 @@ void AP_RCProtocol_CRSF::_process_byte(uint32_t timestamp_us, uint8_t byte) _frame_ofs = 0; } - _last_rx_time_us = timestamp_us; - // overflow check if (_frame_ofs >= CRSF_FRAMELEN_MAX) { _frame_ofs = 0; @@ -222,7 +235,7 @@ void AP_RCProtocol_CRSF::_process_byte(uint32_t timestamp_us, uint8_t byte) if (_frame_ofs == CSRF_HEADER_TYPE_LEN) { _frame_crc = crc8_dvb_s2(0, _frame.type); // check for garbage frame - if (_frame.length > CRSF_FRAMELEN_MAX) { + if (_frame.length > CRSF_FRAME_PAYLOAD_MAX) { _frame_ofs = 0; } return; @@ -246,14 +259,15 @@ void AP_RCProtocol_CRSF::_process_byte(uint32_t timestamp_us, uint8_t byte) // we consumed the partial frame, reset _frame_ofs = 0; - // bad CRC - if (_frame_crc != _frame.payload[_frame.length - CSRF_HEADER_LEN]) { + // bad CRC (payload start is +1 from frame start, so need to subtract that from frame length to get index) + if (_frame_crc != _frame.payload[_frame.length - 2]) { return; } - _last_frame_time_us = timestamp_us; + _last_frame_time_us = _last_rx_frame_time_us = timestamp_us; // decode here if (decode_crsf_packet()) { + _last_tx_frame_time_us = timestamp_us; // we have received a frame from the transmitter add_input(MAX_CHANNELS, _channels, false, _link_status.rssi, _link_status.link_quality); } } @@ -274,14 +288,15 @@ void AP_RCProtocol_CRSF::update(void) for (uint8_t i = 0; i < n; i++) { int16_t b = _uart->read(); if (b >= 0) { - _process_byte(now, uint8_t(b)); + process_byte(AP_HAL::micros(), uint8_t(b)); } } } // never received RC frames, but have received CRSF frames so make sure we give the telemetry opportunity to run uint32_t now = AP_HAL::micros(); - if (_last_frame_time_us > 0 && !get_rc_frame_count() && now - _last_frame_time_us > CRSF_INTER_FRAME_TIME_US_250HZ) { + if (_last_frame_time_us > 0 && (!get_rc_frame_count() || !is_tx_active()) + && now - _last_frame_time_us > CRSF_INTER_FRAME_TIME_US_250HZ) { process_telemetry(false); _last_frame_time_us = now; } @@ -306,6 +321,7 @@ void AP_RCProtocol_CRSF::write_frame(Frame* frame) frame->payload[frame->length - 2] = crc; uart->write((uint8_t*)frame, frame->length + 2); + uart->flush(); #ifdef CRSF_DEBUG hal.console->printf("CRSF: writing %s:", get_frame_type(frame->type, frame->payload[0])); @@ -386,7 +402,7 @@ bool AP_RCProtocol_CRSF::decode_crsf_packet() // now wait for 4ms to account for RX transmission and processing hal.scheduler->delay(4); // change the baud rate - uart->begin(_new_baud_rate, 128, 128); + uart->begin(_new_baud_rate); } _new_baud_rate = 0; } @@ -433,7 +449,7 @@ void AP_RCProtocol_CRSF::decode_variable_bit_channels(const uint8_t* payload, ui } // calculate the number of channels packed - uint8_t numOfChannels = ((frame_length - 2) * 8 - CRSF_SUBSET_RC_STARTING_CHANNEL_BITS) / channelBits; + uint8_t numOfChannels = MIN(uint8_t(((frame_length - 2) * 8 - CRSF_SUBSET_RC_STARTING_CHANNEL_BITS) / channelBits), CRSF_MAX_CHANNELS); // unpack the channel data uint8_t bitsMerged = 0; @@ -442,10 +458,18 @@ void AP_RCProtocol_CRSF::decode_variable_bit_channels(const uint8_t* payload, ui for (uint8_t n = 0; n < numOfChannels; n++) { while (bitsMerged < channelBits) { + // check for corrupt frame + if (readByteIndex >= CRSF_FRAME_PAYLOAD_MAX) { + return; + } uint8_t readByte = payload[readByteIndex++]; readValue |= ((uint32_t) readByte) << bitsMerged; bitsMerged += 8; } + // check for corrupt frame + if (uint8_t(channel_data->starting_channel + n) >= CRSF_MAX_CHANNELS) { + return; + } _channels[channel_data->starting_channel + n] = uint16_t(channelScale * float(uint16_t(readValue & channelMask)) + 988); readValue >>= channelBits; @@ -464,7 +488,7 @@ bool AP_RCProtocol_CRSF::process_telemetry(bool check_constraint) if (!telem_available) { #if HAL_CRSF_TELEM_ENABLED && !APM_BUILD_TYPE(APM_BUILD_iofirmware) - if (AP_CRSF_Telem::get_telem_data(&_telemetry_frame)) { + if (AP_CRSF_Telem::get_telem_data(&_telemetry_frame, is_tx_active())) { telem_available = true; } else { return false; @@ -551,7 +575,7 @@ void AP_RCProtocol_CRSF::start_uart() _uart->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE); _uart->set_blocking_writes(false); _uart->set_options(_uart->get_options() & ~AP_HAL::UARTDriver::OPTION_RXINV); - _uart->begin(CRSF_BAUDRATE, 128, 128); + _uart->begin(get_bootstrap_baud_rate()); } // change the baudrate of the protocol if we are able @@ -562,7 +586,7 @@ bool AP_RCProtocol_CRSF::change_baud_rate(uint32_t baudrate) return false; } #if !defined(STM32H7) - if (baudrate > CRSF_BAUDRATE && !uart->is_dma_enabled()) { + if (baudrate > get_bootstrap_baud_rate() && !uart->is_dma_enabled()) { return false; } #endif @@ -575,6 +599,23 @@ bool AP_RCProtocol_CRSF::change_baud_rate(uint32_t baudrate) return true; } +// change the bootstrap baud rate to ELRS standard if configured +void AP_RCProtocol_CRSF::process_handshake(uint32_t baudrate) +{ + AP_HAL::UARTDriver *uart = get_current_UART(); + + // only change the baudrate if we are bootstrapping CRSF + if (uart == nullptr + || baudrate != CRSF_BAUDRATE + || baudrate == get_bootstrap_baud_rate() + || uart->get_baud_rate() == get_bootstrap_baud_rate() + || (get_rc_protocols_mask() & ((1U<<(uint8_t(AP_RCProtocol::CRSF)+1))+1)) == 0) { + return; + } + + uart->begin(get_bootstrap_baud_rate()); +} + //returns uplink link quality on 0-255 scale int16_t AP_RCProtocol_CRSF::derive_scaled_lq_value(uint8_t uplink_lq) { diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.h b/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.h index 079308ff109..7562d594b5b 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.h +++ b/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.h @@ -20,22 +20,45 @@ #include "AP_RCProtocol.h" #include +#include #include "SoftSerial.h" #define CRSF_MAX_CHANNELS 24U // Maximum number of channels from crsf datastream #define CRSF_FRAMELEN_MAX 64U // maximum possible framelength -#define CRSF_BAUDRATE 416666 +#define CSRF_HEADER_LEN 2U // header length +#define CRSF_FRAME_PAYLOAD_MAX (CRSF_FRAMELEN_MAX - CSRF_HEADER_LEN) // maximum size of the frame length field in a packet +#define CRSF_BAUDRATE 416666U +#define ELRS_BAUDRATE 420000U +#define CRSF_TX_TIMEOUT 500000U // the period after which the transmitter is considered disconnected (matches copters failsafe) +#define CRSF_RX_TIMEOUT 150000U // the period after which the receiver is considered disconnected (>ping frequency) class AP_RCProtocol_CRSF : public AP_RCProtocol_Backend { public: AP_RCProtocol_CRSF(AP_RCProtocol &_frontend); virtual ~AP_RCProtocol_CRSF(); void process_byte(uint8_t byte, uint32_t baudrate) override; - void process_pulse(uint32_t width_s0, uint32_t width_s1) override; + void process_handshake(uint32_t baudrate) override; void update(void) override; // support for CRSF v3 bool change_baud_rate(uint32_t baudrate); - bool is_crsf_v3_active() const { return _crsf_v3_active; } + // bootstrap baudrate + uint32_t get_bootstrap_baud_rate() const { + return rc().use_420kbaud_for_elrs() ? ELRS_BAUDRATE : CRSF_BAUDRATE; + } + + // is the receiver active, used to detect power loss and baudrate changes + bool is_rx_active() const override { + // later versions of CRSFv3 will send link rate frames every 200ms + // but only before an initial failsafe + return AP_HAL::micros() < _last_rx_frame_time_us + CRSF_RX_TIMEOUT; + } + + // is the transmitter active, used to adjust telemetry data + bool is_tx_active() const { + // this is the same as the Copter failsafe timeout + return AP_HAL::micros() < _last_tx_frame_time_us + CRSF_TX_TIMEOUT; + } + // get singleton instance static AP_RCProtocol_CRSF* get_singleton() { return _singleton; @@ -169,7 +192,7 @@ class AP_RCProtocol_CRSF : public AP_RCProtocol_Backend { uint8_t device_address; uint8_t length; uint8_t type; - uint8_t payload[CRSF_FRAMELEN_MAX - 3]; // +1 for crc + uint8_t payload[CRSF_FRAME_PAYLOAD_MAX - 1]; // type is already accounted for } PACKED; struct LinkStatisticsFrame { @@ -209,13 +232,19 @@ class AP_RCProtocol_CRSF : public AP_RCProtocol_Backend { uint8_t starting_channel:5; // which channel number is the first one in the frame uint8_t res_configuration:2; // configuration for the RC data resolution (10 - 13 bits) uint8_t digital_switch_flag:1; // configuration bit for digital channel - uint8_t channels[CRSF_FRAMELEN_MAX - 4]; // +1 for crc + uint8_t channels[CRSF_FRAME_PAYLOAD_MAX - 2]; // payload less byte above // uint16_t channel[]:res; // variable amount of channels (with variable resolution based // on the res_configuration) based on the frame size // uint16_t digital_switch_channel[]:10; // digital switch channel } PACKED; - enum class RFMode : uint8_t { + enum class ProtocolType { + PROTOCOL_CRSF, + PROTOCOL_TRACER, + PROTOCOL_ELRS + }; + + enum RFMode { CRSF_RF_MODE_4HZ = 0, CRSF_RF_MODE_50HZ, CRSF_RF_MODE_150HZ, @@ -228,10 +257,9 @@ class AP_RCProtocol_CRSF : public AP_RCProtocol_Backend { ELRS_RF_MODE_200HZ, ELRS_RF_MODE_250HZ, ELRS_RF_MODE_500HZ, + RF_MODE_MAX_MODES, RF_MODE_UNKNOWN, }; - // nominal ELRS air rates - static constexpr uint16_t elrs_air_rates[8] = {4, 25, 50, 100, 150, 200, 250, 500}; struct LinkStatus { int16_t rssi = -1; @@ -245,6 +273,12 @@ class AP_RCProtocol_CRSF : public AP_RCProtocol_Backend { return _link_status; } + // return the link rate as defined by the LinkStatistics + uint16_t get_link_rate(ProtocolType protocol) const; + + // return the protocol string + const char* get_protocol_string(ProtocolType protocol) const; + private: struct Frame _frame; struct Frame _telemetry_frame; @@ -273,8 +307,9 @@ class AP_RCProtocol_CRSF : public AP_RCProtocol_Backend { void add_to_buffer(uint8_t index, uint8_t b) { ((uint8_t*)&_frame)[index] = b; } uint32_t _last_frame_time_us; + uint32_t _last_tx_frame_time_us; uint32_t _last_uart_start_time_ms; - uint32_t _last_rx_time_us; + uint32_t _last_rx_frame_time_us; uint32_t _start_frame_time_us; bool telem_available; uint32_t _new_baud_rate; @@ -285,9 +320,9 @@ class AP_RCProtocol_CRSF : public AP_RCProtocol_Backend { volatile struct LinkStatus _link_status; - AP_HAL::UARTDriver *_uart; + static const uint16_t RF_MODE_RATES[RFMode::RF_MODE_MAX_MODES]; - SoftSerial ss{CRSF_BAUDRATE, SoftSerial::SERIAL_CONFIG_8N1}; + AP_HAL::UARTDriver *_uart; }; namespace AP { diff --git a/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp b/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp index 2bb22130903..1dd14bf11f7 100644 --- a/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp +++ b/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp @@ -28,6 +28,7 @@ #include #include #include +#include #if HAL_CRSF_TELEM_ENABLED @@ -62,6 +63,7 @@ bool AP_CRSF_Telem::init(void) && !AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_CRSF, 0)) { return false; } + return AP_RCTelemetry::init(); } @@ -85,6 +87,9 @@ void AP_CRSF_Telem::setup_wfq_scheduler(void) add_scheduler_entry(5000, 100); // passthrough max 10Hz add_scheduler_entry(5000, 500); // status text max 2Hz add_scheduler_entry(5, 20); // command 50Hz (generally not active unless requested by the TX) + add_scheduler_entry(5, 500); // version ping 2Hz (only active at startup) + add_scheduler_entry(5, 100); // device ping 10Hz (only active during TX loss, also see CRSF_RX_TIMEOUT) + disable_scheduler_entry(DEVICE_PING); } void AP_CRSF_Telem::setup_custom_telemetry() @@ -153,7 +158,7 @@ void AP_CRSF_Telem::update_custom_telemetry_rates(AP_RCProtocol_CRSF::RFMode rf_ // standard telemetry for low data rates set_scheduler_entry(BATTERY, 1000, 2000); // 0.5Hz set_scheduler_entry(ATTITUDE, 1000, 3000); // 0.33Hz - if (_crsf_version.is_elrs) { + if (is_elrs()) { // ELRS custom telemetry for low data rates set_scheduler_entry(GPS, 550, 1000); // 1.0Hz set_scheduler_entry(PASSTHROUGH, 350, 500); // 2.0Hz @@ -167,7 +172,7 @@ void AP_CRSF_Telem::update_custom_telemetry_rates(AP_RCProtocol_CRSF::RFMode rf_ } } -void AP_CRSF_Telem::process_rf_mode_changes() +bool AP_CRSF_Telem::process_rf_mode_changes() { const AP_RCProtocol_CRSF::RFMode current_rf_mode = get_rf_mode(); uint32_t now = AP_HAL::millis(); @@ -179,23 +184,31 @@ void AP_CRSF_Telem::process_rf_mode_changes() uart = crsf->get_UART(); } if (uart == nullptr) { - return; + return true; } + // not ready yet + if (!uart->is_initialized()) { + return false; + } + // warn the user if their setup is sub-optimal - if (_telem_last_report_ms == 0 && !uart->is_dma_enabled()) { + if (_telem_bootstrap_msg_pending && !uart->is_dma_enabled()) { gcs().send_text(MAV_SEVERITY_WARNING, "%s: running on non-DMA serial port", get_protocol_string()); } // note if option was set to show LQ in place of RSSI bool current_lq_as_rssi_active = bool(rc().use_crsf_lq_as_rssi()); - if(_telem_last_report_ms == 0 || _noted_lq_as_rssi_active != current_lq_as_rssi_active){ + if(_telem_bootstrap_msg_pending || _noted_lq_as_rssi_active != current_lq_as_rssi_active){ _noted_lq_as_rssi_active = current_lq_as_rssi_active; gcs().send_text(MAV_SEVERITY_INFO, "%s: RSSI now displays %s", get_protocol_string(), current_lq_as_rssi_active ? " as LQ" : "normally"); } + _telem_bootstrap_msg_pending = false; + const bool is_high_speed = is_high_speed_telemetry(current_rf_mode); if ((now - _telem_last_report_ms > 5000)) { // report an RF mode change or a change in telemetry rate if we haven't done so in the last 5s if (!rc().suppress_crsf_message() && (_telem_rf_mode != current_rf_mode || abs(int16_t(_telem_last_avg_rate) - int16_t(_scheduler.avg_packet_rate)) > 25)) { - gcs().send_text(MAV_SEVERITY_INFO, "%s: RF Mode %d, telemetry rate is %dHz", get_protocol_string(), uint8_t(current_rf_mode) - (_crsf_version.is_elrs ? uint8_t(AP_RCProtocol_CRSF::RFMode::ELRS_RF_MODE_4HZ) : 0), get_telemetry_rate()); + gcs().send_text(MAV_SEVERITY_INFO, "%s: Link rate %dHz, Telemetry rate %dHz", + get_protocol_string(), crsf->get_link_rate(_crsf_version.protocol), get_telemetry_rate()); } // tune the scheduler based on telemetry speed high/low transitions if (_telem_is_high_speed != is_high_speed) { @@ -204,15 +217,20 @@ void AP_CRSF_Telem::process_rf_mode_changes() _telem_is_high_speed = is_high_speed; _telem_rf_mode = current_rf_mode; _telem_last_avg_rate = _scheduler.avg_packet_rate; + if (_telem_last_report_ms == 0) { // only want to show bootstrap messages once + _telem_bootstrap_msg_pending = true; + } _telem_last_report_ms = now; } + return true; } // return custom frame id based on fw version uint8_t AP_CRSF_Telem::get_custom_telem_frame_id() const { if (!_crsf_version.pending && - ((_crsf_version.major > 4 || (_crsf_version.major == 4 && _crsf_version.minor >= 6)) || _crsf_version.is_elrs)) { + ((_crsf_version.major > 4 || (_crsf_version.major == 4 && _crsf_version.minor >= 6)) + || is_elrs())) { return AP_RCProtocol_CRSF::CRSF_FRAMETYPE_AP_CUSTOM_TELEM; } return AP_RCProtocol_CRSF::CRSF_FRAMETYPE_AP_CUSTOM_TELEM_LEGACY; @@ -226,11 +244,11 @@ AP_RCProtocol_CRSF::RFMode AP_CRSF_Telem::get_rf_mode() const } if (!_crsf_version.pending && _crsf_version.use_rf_mode) { - if (_crsf_version.is_elrs) { + if (is_elrs()) { return static_cast(uint8_t(AP_RCProtocol_CRSF::RFMode::ELRS_RF_MODE_4HZ) + crsf->get_link_status().rf_mode); } return static_cast(crsf->get_link_status().rf_mode); - } else if (_crsf_version.is_tracer) { + } else if (is_tracer()) { return AP_RCProtocol_CRSF::RFMode::CRSF_RF_MODE_250HZ; } @@ -256,7 +274,7 @@ AP_RCProtocol_CRSF::RFMode AP_CRSF_Telem::get_rf_mode() const bool AP_CRSF_Telem::is_high_speed_telemetry(const AP_RCProtocol_CRSF::RFMode rf_mode) const { - if (!_crsf_version.is_elrs) { + if (_crsf_version.protocol != AP_RCProtocol_CRSF::ProtocolType::PROTOCOL_ELRS) { return rf_mode == AP_RCProtocol_CRSF::RFMode::CRSF_RF_MODE_150HZ || rf_mode == AP_RCProtocol_CRSF::RFMode::CRSF_RF_MODE_250HZ; } return get_telemetry_rate() > 30; @@ -264,7 +282,7 @@ bool AP_CRSF_Telem::is_high_speed_telemetry(const AP_RCProtocol_CRSF::RFMode rf_ uint16_t AP_CRSF_Telem::get_telemetry_rate() const { - if (!_crsf_version.is_elrs) { + if (_crsf_version.protocol != AP_RCProtocol_CRSF::ProtocolType::PROTOCOL_ELRS) { return get_avg_packet_rate(); } AP_RCProtocol_CRSF* crsf = AP::crsf(); @@ -275,7 +293,7 @@ uint16_t AP_CRSF_Telem::get_telemetry_rate() const // the 1:n ratio is user selected // RC rate is measured by get_avg_packet_rate() // telemetry rate = air rate - RC rate - return uint16_t(AP_RCProtocol_CRSF::elrs_air_rates[MIN(crsf->get_link_status().rf_mode, 7U)] - get_avg_packet_rate()); + return crsf->get_link_rate(_crsf_version.protocol) - get_avg_packet_rate(); } void AP_CRSF_Telem::queue_message(MAV_SEVERITY severity, const char *text) @@ -288,25 +306,25 @@ void AP_CRSF_Telem::queue_message(MAV_SEVERITY severity, const char *text) AP_RCTelemetry::queue_message(severity, text); } -void AP_CRSF_Telem::enter_scheduler_params_mode() +/* + disable telemetry entries that require a transmitter to be present + */ +void AP_CRSF_Telem::disable_tx_entries() { - debug("parameter passthrough enabled"); - set_scheduler_entry(HEARTBEAT, 50, 200); // heartbeat 5Hz - disable_scheduler_entry(ATTITUDE); disable_scheduler_entry(BATTERY); disable_scheduler_entry(GPS); disable_scheduler_entry(FLIGHT_MODE); disable_scheduler_entry(PASSTHROUGH); disable_scheduler_entry(STATUS_TEXT); + // GENERAL_COMMAND and PARAMETERS will only be sent under very specific circumstances } -void AP_CRSF_Telem::exit_scheduler_params_mode() +/* + enable telemetry entries that require a transmitter to be present + */ +void AP_CRSF_Telem::enable_tx_entries() { - debug("parameter passthrough disabled"); - // setup the crossfire scheduler for custom telemetry - set_scheduler_entry(HEARTBEAT, 2000, 5000); // 0.2Hz - enable_scheduler_entry(ATTITUDE); enable_scheduler_entry(BATTERY); enable_scheduler_entry(GPS); @@ -317,6 +335,21 @@ void AP_CRSF_Telem::exit_scheduler_params_mode() update_custom_telemetry_rates(_telem_rf_mode); } +void AP_CRSF_Telem::enter_scheduler_params_mode() +{ + debug("parameter passthrough enabled"); + set_scheduler_entry(HEARTBEAT, 50, 200); // heartbeat 5Hz + disable_tx_entries(); +} + +void AP_CRSF_Telem::exit_scheduler_params_mode() +{ + debug("parameter passthrough disabled"); + // setup the crossfire scheduler for custom telemetry + set_scheduler_entry(HEARTBEAT, 2000, 5000); // 0.2Hz + enable_tx_entries(); +} + void AP_CRSF_Telem::adjust_packet_weight(bool queue_empty) { uint32_t now_ms = AP_HAL::millis(); @@ -346,24 +379,12 @@ void AP_CRSF_Telem::adjust_packet_weight(bool queue_empty) // WFQ scheduler bool AP_CRSF_Telem::is_packet_ready(uint8_t idx, bool queue_empty) { - process_rf_mode_changes(); + if (!process_rf_mode_changes()) { + return false; + } switch (idx) { case PARAMETERS: - // to get crossfire firmware version we send an RX device ping until we get a response - // but only if there are no other requests pending - if (_crsf_version.pending && _pending_request.frame_type == 0) { - if (_crsf_version.retry_count++ > CRSF_RX_DEVICE_PING_MAX_RETRY) { - _crsf_version.pending = false; - _crsf_version.minor = 0; - _crsf_version.major = 0; - gcs().send_text(MAV_SEVERITY_DEBUG,"%s: RX device ping failed", get_protocol_string()); - } else { - _pending_request.destination = AP_RCProtocol_CRSF::CRSF_ADDRESS_CRSF_RECEIVER; - _pending_request.frame_type = AP_RCProtocol_CRSF::CRSF_FRAMETYPE_PARAM_DEVICE_PING; - gcs().send_text(MAV_SEVERITY_DEBUG,"%s: requesting RX device info", get_protocol_string()); - } - } return _pending_request.frame_type > 0; case VTX_PARAMETERS: return AP::vtx().have_params_changed() ||_vtx_power_change_pending || _vtx_freq_change_pending || _vtx_options_change_pending; @@ -373,6 +394,12 @@ bool AP_CRSF_Telem::is_packet_ready(uint8_t idx, bool queue_empty) return rc().crsf_custom_telemetry() && !queue_empty; case GENERAL_COMMAND: return _baud_rate_request.pending; + case VERSION_PING: + return _crsf_version.pending; + case HEARTBEAT: + return true; // always send heartbeat if enabled + case DEVICE_PING: + return !_crsf_version.pending; // only send pings if version has been negotiated default: return _enable_telemetry; } @@ -387,7 +414,7 @@ void AP_CRSF_Telem::process_packet(uint8_t idx) calc_heartbeat(); break; case PARAMETERS: // update parameter settings - update_params(); + process_pending_requests(); break; case ATTITUDE: calc_attitude(); @@ -412,7 +439,7 @@ void AP_CRSF_Telem::process_packet(uint8_t idx) } else { // on slower links we pack many passthrough // frames in a single crossfire one (up to 9) - const uint8_t size = _crsf_version.is_elrs ? 3 : AP_CRSF_Telem::PASSTHROUGH_MULTI_PACKET_FRAME_MAX_SIZE; + const uint8_t size = is_elrs() ? 3 : AP_CRSF_Telem::PASSTHROUGH_MULTI_PACKET_FRAME_MAX_SIZE; get_multi_packet_passthrough_telem_data(size); } break; @@ -422,6 +449,22 @@ void AP_CRSF_Telem::process_packet(uint8_t idx) case GENERAL_COMMAND: calc_command_response(); break; + case VERSION_PING: + // to get crossfire firmware version we send an RX device ping + if (_crsf_version.retry_count++ > CRSF_RX_DEVICE_PING_MAX_RETRY) { + _crsf_version.pending = false; + _crsf_version.minor = 0; + _crsf_version.major = 0; + disable_scheduler_entry(VERSION_PING); + gcs().send_text(MAV_SEVERITY_DEBUG,"%s: RX device ping failed", get_protocol_string()); + } else { + calc_device_ping(AP_RCProtocol_CRSF::CRSF_ADDRESS_CRSF_RECEIVER); + gcs().send_text(MAV_SEVERITY_DEBUG,"%s: requesting RX device info", get_protocol_string()); + } + break; + case DEVICE_PING: + calc_device_ping(AP_RCProtocol_CRSF::CRSF_ADDRESS_CRSF_RECEIVER); + break; default: break; } @@ -566,6 +609,7 @@ void AP_CRSF_Telem::process_ping_frame(ParameterPingFrame* ping) _param_request.origin = ping->origin; _pending_request.frame_type = AP_RCProtocol_CRSF::CRSF_FRAMETYPE_PARAM_DEVICE_INFO; + _pending_request.destination = ping->origin; } // request for device info @@ -592,25 +636,33 @@ void AP_CRSF_Telem::process_device_info_frame(ParameterDeviceInfoFrame* info) // get the terminator of the device name string const uint8_t offset = strnlen((char*)info->payload,42U); if (strncmp((char*)info->payload, "Tracer", 6) == 0) { - _crsf_version.is_tracer = true; + _crsf_version.protocol = AP_RCProtocol_CRSF::ProtocolType::PROTOCOL_TRACER; } else if (strncmp((char*)&info->payload[offset+1], "ELRS", 4) == 0) { // ELRS magic number is ELRS encoded in the serial number // 0x45 'E' 0x4C 'L' 0x52 'R' 0x53 'S' - _crsf_version.is_elrs = true; + _crsf_version.protocol = AP_RCProtocol_CRSF::ProtocolType::PROTOCOL_ELRS; + } + + if (!is_elrs()) { + /* + fw major ver = offset + terminator (8bits) + serial (32bits) + hw id (32bits) + 3rd byte of sw id = 11bytes + fw minor ver = offset + terminator (8bits) + serial (32bits) + hw id (32bits) + 4th byte of sw id = 12bytes + */ + _crsf_version.major = info->payload[offset+11]; + _crsf_version.minor = info->payload[offset+12]; + } else { + // ELRS does not populate the version field so cook up something sensible + _crsf_version.major = 1; + _crsf_version.minor = 0; } - /* - fw major ver = offset + terminator (8bits) + serial (32bits) + hw id (32bits) + 3rd byte of sw id = 11bytes - fw minor ver = offset + terminator (8bits) + serial (32bits) + hw id (32bits) + 4th byte of sw id = 12bytes - */ - _crsf_version.major = info->payload[offset+11]; - _crsf_version.minor = info->payload[offset+12]; // should we use rf_mode reported by link statistics? - if (_crsf_version.is_elrs || (!_crsf_version.is_tracer && (_crsf_version.major > 3 || (_crsf_version.major == 3 && _crsf_version.minor >= 72)))) { + if (is_elrs() || (!is_tracer() && (_crsf_version.major > 3 || (_crsf_version.major == 3 && _crsf_version.minor >= 72)))) { _crsf_version.use_rf_mode = true; } _crsf_version.pending = false; + disable_scheduler_entry(VERSION_PING); } // request for a general command @@ -658,7 +710,7 @@ void AP_CRSF_Telem::update() { } -void AP_CRSF_Telem::update_params() +void AP_CRSF_Telem::process_pending_requests() { // handle general parameter requests switch (_pending_request.frame_type) { @@ -669,7 +721,7 @@ void AP_CRSF_Telem::update_params() break; // construct a ping frame originating here case AP_RCProtocol_CRSF::CRSF_FRAMETYPE_PARAM_DEVICE_PING: - calc_device_ping(); + calc_device_ping(_pending_request.destination); break; case AP_RCProtocol_CRSF::CRSF_FRAMETYPE_PARAMETER_READ: // reset parameter passthrough timeout @@ -679,6 +731,8 @@ void AP_CRSF_Telem::update_params() default: break; } + + _pending_request.frame_type = 0; } void AP_CRSF_Telem::update_vtx_params() @@ -913,13 +967,11 @@ void AP_CRSF_Telem::calc_device_info() { } // send a device ping -void AP_CRSF_Telem::calc_device_ping() { - _telem.ext.ping.destination = _pending_request.destination; +void AP_CRSF_Telem::calc_device_ping(uint8_t destination) { + _telem.ext.ping.destination = destination; _telem.ext.ping.origin = AP_RCProtocol_CRSF::CRSF_ADDRESS_FLIGHT_CONTROLLER; _telem_size = 2; _telem_type = AP_RCProtocol_CRSF::CRSF_FRAMETYPE_PARAM_DEVICE_PING; - - _pending_request.destination = AP_RCProtocol_CRSF::CRSF_ADDRESS_BROADCAST; _pending_request.frame_type = 0; _telem_pending = true; @@ -1309,7 +1361,8 @@ void AP_CRSF_Telem::calc_status_text() if (!_statustext.available) { WITH_SEMAPHORE(_statustext.sem); // check link speed - if (!_crsf_version.is_elrs && !is_high_speed_telemetry(_telem_rf_mode)) { + if (_crsf_version.protocol != AP_RCProtocol_CRSF::ProtocolType::PROTOCOL_ELRS + && !is_high_speed_telemetry(_telem_rf_mode)) { // keep only warning/error/critical/alert/emergency status text messages bool got_message = false; while (_statustext.queue.pop(_statustext.next)) { @@ -1387,10 +1440,23 @@ void AP_CRSF_Telem::get_multi_packet_passthrough_telem_data(uint8_t size) /* fetch CRSF frame data + if is_tx_active is true then this will be a request for telemetry after receiving an RC frame */ -bool AP_CRSF_Telem::_get_telem_data(AP_RCProtocol_CRSF::Frame* data) +bool AP_CRSF_Telem::_get_telem_data(AP_RCProtocol_CRSF::Frame* data, bool is_tx_active) { memset(&_telem, 0, sizeof(TelemetryPayload)); + // update telemetry tasks if we either lost or regained the transmitter + if (_is_tx_active != is_tx_active) { + if (is_tx_active) { + disable_scheduler_entry(DEVICE_PING); + enable_tx_entries(); + } else { + disable_tx_entries(); + enable_scheduler_entry(DEVICE_PING); + } + _is_tx_active = is_tx_active; + } + run_wfq_scheduler(); if (!_telem_pending) { return false; @@ -1418,12 +1484,12 @@ bool AP_CRSF_Telem::process_frame(AP_RCProtocol_CRSF::FrameType frame_type, void /* fetch data for an external transport, such as CRSF */ -bool AP_CRSF_Telem::get_telem_data(AP_RCProtocol_CRSF::Frame* data) +bool AP_CRSF_Telem::get_telem_data(AP_RCProtocol_CRSF::Frame* data, bool is_tx_active) { if (!get_singleton()) { return false; } - return singleton->_get_telem_data(data); + return singleton->_get_telem_data(data, is_tx_active); } AP_CRSF_Telem *AP_CRSF_Telem::get_singleton(void) { diff --git a/libraries/AP_RCTelemetry/AP_CRSF_Telem.h b/libraries/AP_RCTelemetry/AP_CRSF_Telem.h index c9e92e9cf5f..5eda87aee6d 100644 --- a/libraries/AP_RCTelemetry/AP_CRSF_Telem.h +++ b/libraries/AP_RCTelemetry/AP_CRSF_Telem.h @@ -14,7 +14,6 @@ */ #pragma once -#include #include #include @@ -28,9 +27,6 @@ #if HAL_CRSF_TELEM_ENABLED -#include -#include -#include #include #include "AP_RCTelemetry.h" #include @@ -67,7 +63,7 @@ class AP_CRSF_Telem : public AP_RCTelemetry { }; struct HeartbeatFrame { - uint8_t origin; // Device addres + uint8_t origin; // Device address }; struct PACKED BatteryFrame { @@ -236,23 +232,19 @@ class AP_CRSF_Telem : public AP_RCTelemetry { }; // get the protocol string - const char* get_protocol_string() const { - if (_crsf_version.is_elrs) { - return "ELRS"; - } else { - const AP_RCProtocol_CRSF* crsf = AP::crsf(); - if (crsf && crsf->is_crsf_v3_active()) { - return "CRSFv3"; - } - return "CRSFv2"; - } - }; + const char* get_protocol_string() const { return AP::crsf()->get_protocol_string(_crsf_version.protocol); } + + // is the current protocol ELRS? + bool is_elrs() const { return _crsf_version.protocol == AP_RCProtocol_CRSF::ProtocolType::PROTOCOL_ELRS; } + // is the current protocol Tracer? + bool is_tracer() const { return _crsf_version.protocol == AP_RCProtocol_CRSF::ProtocolType::PROTOCOL_TRACER; } + // Process a frame from the CRSF protocol decoder static bool process_frame(AP_RCProtocol_CRSF::FrameType frame_type, void* data); // process any changed settings and schedule for transmission void update(); // get next telemetry data for external consumers of SPort data - static bool get_telem_data(AP_RCProtocol_CRSF::Frame* frame); + static bool get_telem_data(AP_RCProtocol_CRSF::Frame* frame, bool is_tx_active); private: @@ -267,6 +259,8 @@ class AP_CRSF_Telem : public AP_RCTelemetry { PASSTHROUGH, STATUS_TEXT, GENERAL_COMMAND, + VERSION_PING, + DEVICE_PING, NUM_SENSORS }; @@ -284,18 +278,18 @@ class AP_CRSF_Telem : public AP_RCTelemetry { void calc_attitude(); void calc_flight_mode(); void calc_device_info(); - void calc_device_ping(); + void calc_device_ping(uint8_t destination); void calc_command_response(); void calc_parameter(); #if HAL_CRSF_TELEM_TEXT_SELECTION_ENABLED void calc_text_selection( AP_OSD_ParamSetting* param, uint8_t chunk); #endif - void update_params(); + void process_pending_requests(); void update_vtx_params(); void get_single_packet_passthrough_telem_data(); void get_multi_packet_passthrough_telem_data(uint8_t size = PASSTHROUGH_MULTI_PACKET_FRAME_MAX_SIZE); void calc_status_text(); - void process_rf_mode_changes(); + bool process_rf_mode_changes(); uint8_t get_custom_telem_frame_id() const; AP_RCProtocol_CRSF::RFMode get_rf_mode() const; uint16_t get_telemetry_rate() const; @@ -315,9 +309,11 @@ class AP_CRSF_Telem : public AP_RCTelemetry { // setup the scheduler for parameters download void enter_scheduler_params_mode(); void exit_scheduler_params_mode(); + void disable_tx_entries(); + void enable_tx_entries(); // get next telemetry data for external consumers - bool _get_telem_data(AP_RCProtocol_CRSF::Frame* data); + bool _get_telem_data(AP_RCProtocol_CRSF::Frame* data, bool is_tx_active); bool _process_frame(AP_RCProtocol_CRSF::FrameType frame_type, void* data); TelemetryPayload _telem; @@ -327,10 +323,14 @@ class AP_CRSF_Telem : public AP_RCTelemetry { // reporting telemetry rate uint32_t _telem_last_report_ms; uint16_t _telem_last_avg_rate; + // do we need to report the initial state + bool _telem_bootstrap_msg_pending; bool _telem_is_high_speed; bool _telem_pending; bool _enable_telemetry; + // used to limit telemetry when in a failsafe condition + bool _is_tx_active; struct { uint8_t destination = AP_RCProtocol_CRSF::CRSF_ADDRESS_BROADCAST; @@ -342,9 +342,8 @@ class AP_CRSF_Telem : public AP_RCTelemetry { uint8_t major; uint8_t retry_count; bool use_rf_mode; - bool is_tracer; + AP_RCProtocol_CRSF::ProtocolType protocol; bool pending = true; - bool is_elrs; } _crsf_version; struct { diff --git a/libraries/AP_RCTelemetry/AP_RCTelemetry.cpp b/libraries/AP_RCTelemetry/AP_RCTelemetry.cpp index 76ccec2d5fd..aca7629fd3c 100644 --- a/libraries/AP_RCTelemetry/AP_RCTelemetry.cpp +++ b/libraries/AP_RCTelemetry/AP_RCTelemetry.cpp @@ -253,23 +253,23 @@ void AP_RCTelemetry::check_ekf_status(void) uint32_t now = AP_HAL::millis(); if ((now - check_ekf_status_timer) >= 10000) { // prevent repeating any ekf_status message unless 10 seconds have passed // multiple errors can be reported at a time. Same setup as Mission Planner. - if (velVar >= 1) { + if (velVar >= 0.8f) { queue_message(MAV_SEVERITY_CRITICAL, "Error velocity variance"); check_ekf_status_timer = now; } - if (posVar >= 1) { + if (posVar >= 0.8f) { queue_message(MAV_SEVERITY_CRITICAL, "Error pos horiz variance"); check_ekf_status_timer = now; } - if (hgtVar >= 1) { + if (hgtVar >= 0.8f) { queue_message(MAV_SEVERITY_CRITICAL, "Error pos vert variance"); check_ekf_status_timer = now; } - if (magVar.length() >= 1) { + if (magVar.length() >= 0.8f) { queue_message(MAV_SEVERITY_CRITICAL, "Error compass variance"); check_ekf_status_timer = now; } - if (tasVar >= 1) { + if (tasVar >= 0.8f) { queue_message(MAV_SEVERITY_CRITICAL, "Error terrain alt variance"); check_ekf_status_timer = now; } diff --git a/libraries/AP_RCTelemetry/AP_RCTelemetry.h b/libraries/AP_RCTelemetry/AP_RCTelemetry.h index 33250b85705..1228025a977 100644 --- a/libraries/AP_RCTelemetry/AP_RCTelemetry.h +++ b/libraries/AP_RCTelemetry/AP_RCTelemetry.h @@ -14,10 +14,10 @@ */ #pragma once -#include -#include +#include #include #include +#include #define TELEM_PAYLOAD_STATUS_CAPACITY 5 // size of the message buffer queue (max number of messages waiting to be sent) diff --git a/libraries/AP_RCTelemetry/AP_Spektrum_Telem.h b/libraries/AP_RCTelemetry/AP_Spektrum_Telem.h index 5ecb15af2c3..32321e81e1b 100644 --- a/libraries/AP_RCTelemetry/AP_Spektrum_Telem.h +++ b/libraries/AP_RCTelemetry/AP_Spektrum_Telem.h @@ -14,7 +14,7 @@ */ #pragma once -#include +#include #ifndef HAL_SPEKTRUM_TELEM_ENABLED #define HAL_SPEKTRUM_TELEM_ENABLED !HAL_MINIMIZE_FEATURES @@ -22,7 +22,6 @@ #if HAL_SPEKTRUM_TELEM_ENABLED -#include #include #include #include "AP_RCTelemetry.h" diff --git a/libraries/AP_ROMFS/AP_ROMFS.cpp b/libraries/AP_ROMFS/AP_ROMFS.cpp index 20ca115b99f..c56ce5e2db8 100644 --- a/libraries/AP_ROMFS/AP_ROMFS.cpp +++ b/libraries/AP_ROMFS/AP_ROMFS.cpp @@ -20,6 +20,11 @@ #include "tinf.h" #include +#include +#include + +#include + #ifdef HAL_HAVE_AP_ROMFS_EMBEDDED_H #include #else diff --git a/libraries/AP_ROMFS/AP_ROMFS.h b/libraries/AP_ROMFS/AP_ROMFS.h index 284ae9e57a5..78edc703dc2 100644 --- a/libraries/AP_ROMFS/AP_ROMFS.h +++ b/libraries/AP_ROMFS/AP_ROMFS.h @@ -3,7 +3,7 @@ */ #pragma once -#include +#include class AP_ROMFS { public: diff --git a/libraries/AP_RPM/AP_RPM.cpp b/libraries/AP_RPM/AP_RPM.cpp index 0b86a22b47c..9134e1afcbd 100644 --- a/libraries/AP_RPM/AP_RPM.cpp +++ b/libraries/AP_RPM/AP_RPM.cpp @@ -17,6 +17,7 @@ #include "RPM_Pin.h" #include "RPM_SITL.h" #include "RPM_EFI.h" +#include "RPM_Generator.h" #include "RPM_HarmonicNotch.h" #include "RPM_ESC_Telem.h" @@ -79,6 +80,11 @@ void AP_RPM::init(void) case RPM_TYPE_EFI: drivers[i] = new AP_RPM_EFI(*this, i, state[i]); break; +#endif +#if HAL_GENERATOR_ENABLED + case RPM_TYPE_GENERATOR: + drivers[i] = new AP_RPM_Generator(*this, i, state[i]); + break; #endif // include harmonic notch last // this makes whatever process is driving the dynamic notch appear as an RPM value @@ -104,8 +110,8 @@ PARAMETER_CONVERSION - Added: Aug-2021 */ void AP_RPM::convert_params(void) { - if (_params[0].type.configured_in_storage()) { - // _params[0].type will always be configured in storage after conversion is done the first time + if (_params[0].type.configured()) { + // _params[0].type will always be configured after conversion is done the first time return; } @@ -189,9 +195,11 @@ void AP_RPM::update(void) } } +#if HAL_LOGGING_ENABLED if (enabled(0) || enabled(1)) { - AP::logger().Write_RPM(*this); + Log_RPM(); } +#endif } /* @@ -246,11 +254,16 @@ bool AP_RPM::arming_checks(size_t buflen, char *buffer) const case RPM_TYPE_PWM: case RPM_TYPE_PIN: if (_params[i].pin == -1) { - hal.util->snprintf(buffer, buflen, "RPM[%u] no pin set", i + 1); + hal.util->snprintf(buffer, buflen, "RPM%u_PIN not set", unsigned(i + 1)); return false; } if (!hal.gpio->valid_pin(_params[i].pin)) { - hal.util->snprintf(buffer, buflen, "RPM[%u] pin %d invalid", unsigned(i + 1), int(_params[i].pin.get())); + uint8_t servo_ch; + if (hal.gpio->pin_to_servo_channel(_params[i].pin, servo_ch)) { + hal.util->snprintf(buffer, buflen, "RPM%u_PIN=%d, set SERVO%u_FUNCTION=-1", unsigned(i + 1), int(_params[i].pin.get()), unsigned(servo_ch+1)); + } else { + hal.util->snprintf(buffer, buflen, "RPM%u_PIN=%d invalid", unsigned(i + 1), int(_params[i].pin.get())); + } return false; } break; @@ -259,6 +272,24 @@ bool AP_RPM::arming_checks(size_t buflen, char *buffer) const return true; } +#if HAL_LOGGING_ENABLED +void AP_RPM::Log_RPM() +{ + float rpm1 = -1, rpm2 = -1; + + get_rpm(0, rpm1); + get_rpm(1, rpm2); + + const struct log_RPM pkt{ + LOG_PACKET_HEADER_INIT(LOG_RPM_MSG), + time_us : AP_HAL::micros64(), + rpm1 : rpm1, + rpm2 : rpm2 + }; + AP::logger().WriteBlock(&pkt, sizeof(pkt)); +} +#endif + // singleton instance AP_RPM *AP_RPM::_singleton; diff --git a/libraries/AP_RPM/AP_RPM.h b/libraries/AP_RPM/AP_RPM.h index 5d034b8a62a..e2519967770 100644 --- a/libraries/AP_RPM/AP_RPM.h +++ b/libraries/AP_RPM/AP_RPM.h @@ -15,10 +15,11 @@ #pragma once #include -#include +#include #include #include #include "AP_RPM_Params.h" +#include "AP_RPM_config.h" // Maximum number of RPM measurement instances available on this platform #define RPM_MAX_INSTANCES 2 @@ -32,9 +33,7 @@ class AP_RPM public: AP_RPM(); - /* Do not allow copies */ - AP_RPM(const AP_RPM &other) = delete; - AP_RPM &operator=(const AP_RPM&) = delete; + CLASS_NO_COPY(AP_RPM); /* Do not allow copies */ // RPM driver types enum RPM_Type { @@ -44,6 +43,7 @@ class AP_RPM RPM_TYPE_EFI = 3, RPM_TYPE_HNTCH = 4, RPM_TYPE_ESC_TELEM = 5, + RPM_TYPE_GENERATOR = 6, #if CONFIG_HAL_BOARD == HAL_BOARD_SITL RPM_TYPE_SITL = 10, #endif @@ -104,6 +104,8 @@ class AP_RPM uint8_t num_instances; void detect_instance(uint8_t instance); + + void Log_RPM(); }; namespace AP { diff --git a/libraries/AP_RPM/AP_RPM_Params.cpp b/libraries/AP_RPM/AP_RPM_Params.cpp index 4f087909d91..8a3419594e3 100644 --- a/libraries/AP_RPM/AP_RPM_Params.cpp +++ b/libraries/AP_RPM/AP_RPM_Params.cpp @@ -20,11 +20,11 @@ const AP_Param::GroupInfo AP_RPM_Params::var_info[] = { // @Param: TYPE // @DisplayName: RPM type // @Description: What type of RPM sensor is connected - // @Values: 0:None,1:Not Used,2:AUXPIN,3:EFI,4:Harmonic Notch,5:ESC Telemetry Motors Bitmask + // @Values: 0:None,1:Not Used,2:GPIO,3:EFI,4:Harmonic Notch,5:ESC Telemetry Motors Bitmask,6:Generator // @User: Standard AP_GROUPINFO_FLAGS("TYPE", 1, AP_RPM_Params, type, 0, AP_PARAM_FLAG_ENABLE), // Note, 1 was previously for type = PWM. This has been removed from docs to make setup less confusing for users. - // However, 1 is reserved as it does still fallthrough to type = AUXPIN. + // However, 1 is reserved as it does still fallthrough to type = GPIO. // @Param: SCALING // @DisplayName: RPM scaling @@ -35,14 +35,14 @@ const AP_Param::GroupInfo AP_RPM_Params::var_info[] = { // @Param: MAX // @DisplayName: Maximum RPM - // @Description: Maximum RPM to report. Only used on type = PWM. + // @Description: Maximum RPM to report. Only used on type = GPIO. // @Increment: 1 // @User: Standard AP_GROUPINFO("MAX", 3, AP_RPM_Params, maximum, 100000), // @Param: MIN // @DisplayName: Minimum RPM - // @Description: Minimum RPM to report. Only used on type = PWM. + // @Description: Minimum RPM to report. Only used on type = GPIO. // @Increment: 1 // @User: Standard AP_GROUPINFO("MIN", 4, AP_RPM_Params, minimum, 10), @@ -56,7 +56,7 @@ const AP_Param::GroupInfo AP_RPM_Params::var_info[] = { // @Param: PIN // @DisplayName: Input pin number - // @Description: Which pin to use. Only used on type = PWM. + // @Description: Which digital GPIO pin to use. Only used on type = GPIO. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot. // @Values: -1:Disabled,50:AUX1,51:AUX2,52:AUX3,53:AUX4,54:AUX5,55:AUX6 // @User: Standard AP_GROUPINFO("PIN", 6, AP_RPM_Params, pin, -1), diff --git a/libraries/AP_RPM/AP_RPM_config.h b/libraries/AP_RPM/AP_RPM_config.h new file mode 100644 index 00000000000..6a34bbb6976 --- /dev/null +++ b/libraries/AP_RPM/AP_RPM_config.h @@ -0,0 +1,4 @@ +#pragma once + +#define AP_RPM_ENABLED 1 + diff --git a/libraries/AP_RPM/LogStructure.h b/libraries/AP_RPM/LogStructure.h new file mode 100644 index 00000000000..d870fabeda7 --- /dev/null +++ b/libraries/AP_RPM/LogStructure.h @@ -0,0 +1,22 @@ +#pragma once + +#include + +#define LOG_IDS_FROM_RPM \ + LOG_RPM_MSG + +// @LoggerMessage: RPM +// @Description: Data from RPM sensors +// @Field: TimeUS: Time since system startup +// @Field: rpm1: First sensor's data +// @Field: rpm2: Second sensor's data +struct PACKED log_RPM { + LOG_PACKET_HEADER; + uint64_t time_us; + float rpm1; + float rpm2; +}; + +#define LOG_STRUCTURE_FROM_RPM \ + { LOG_RPM_MSG, sizeof(log_RPM), \ + "RPM", "Qff", "TimeUS,rpm1,rpm2", "sqq", "F00" , true }, diff --git a/libraries/AP_RPM/RPM_Backend.h b/libraries/AP_RPM/RPM_Backend.h index 77885969f38..c0a4c8cbccb 100644 --- a/libraries/AP_RPM/RPM_Backend.h +++ b/libraries/AP_RPM/RPM_Backend.h @@ -14,8 +14,6 @@ */ #pragma once -#include -#include #include "AP_RPM.h" class AP_RPM_Backend diff --git a/libraries/AP_RPM/RPM_Generator.cpp b/libraries/AP_RPM/RPM_Generator.cpp new file mode 100644 index 00000000000..50e2d3627d4 --- /dev/null +++ b/libraries/AP_RPM/RPM_Generator.cpp @@ -0,0 +1,38 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +#include + +#include "RPM_Generator.h" + +#if HAL_GENERATOR_ENABLED +extern const AP_HAL::HAL& hal; + +void AP_RPM_Generator::update(void) +{ + const auto *generator = AP::generator(); + if (generator == nullptr) { + return; + } + if (generator->healthy()) { + state.rate_rpm = generator->get_rpm(); + state.rate_rpm *= ap_rpm._params[state.instance].scaling; + state.signal_quality = 0.5; + } else { + state.signal_quality = 0; + } +} + +#endif // HAL_GENERATOR_ENABLED diff --git a/libraries/AP_RPM/RPM_Generator.h b/libraries/AP_RPM/RPM_Generator.h new file mode 100644 index 00000000000..82e8e0ff8d0 --- /dev/null +++ b/libraries/AP_RPM/RPM_Generator.h @@ -0,0 +1,34 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ +#pragma once + +#include "AP_RPM.h" +#include "RPM_Backend.h" +#include + +#if HAL_GENERATOR_ENABLED + +class AP_RPM_Generator : public AP_RPM_Backend +{ +public: + // constructor + using AP_RPM_Backend::AP_RPM_Backend; + + // update state + void update(void) override; +}; + +#endif // HAL_GENERATOR_ENABLED + diff --git a/libraries/AP_RPM/RPM_HarmonicNotch.cpp b/libraries/AP_RPM/RPM_HarmonicNotch.cpp index 883c45eb570..6846355f03c 100644 --- a/libraries/AP_RPM/RPM_HarmonicNotch.cpp +++ b/libraries/AP_RPM/RPM_HarmonicNotch.cpp @@ -32,11 +32,14 @@ AP_RPM_HarmonicNotch::AP_RPM_HarmonicNotch(AP_RPM &_ap_rpm, uint8_t _instance, A void AP_RPM_HarmonicNotch::update(void) { AP_InertialSensor& ins = AP::ins(); - if (ins.get_gyro_harmonic_notch_tracking_mode() != HarmonicNotchDynamicMode::Fixed) { - state.rate_rpm = ins.get_gyro_dynamic_notch_center_freq_hz() * 60.0f; - state.rate_rpm *= ap_rpm._params[state.instance].scaling; - state.signal_quality = 0.5f; - state.last_reading_ms = AP_HAL::millis(); + for (auto ¬ch : ins.harmonic_notches) { + if (notch.params.enabled() && + notch.params.tracking_mode() != HarmonicNotchDynamicMode::Fixed) { + state.rate_rpm = notch.calculated_notch_freq_hz[0] * 60; + state.rate_rpm *= ap_rpm._params[state.instance].scaling; + state.signal_quality = 0.5f; + state.last_reading_ms = AP_HAL::millis(); + } } } diff --git a/libraries/AP_RPM/RPM_Pin.cpp b/libraries/AP_RPM/RPM_Pin.cpp index 638bee03d3d..73360709905 100644 --- a/libraries/AP_RPM/RPM_Pin.cpp +++ b/libraries/AP_RPM/RPM_Pin.cpp @@ -50,22 +50,24 @@ void AP_RPM_Pin::update(void) { if (last_pin != get_pin()) { // detach from last pin - if (last_pin != (uint8_t)-1 && - !hal.gpio->detach_interrupt(last_pin)) { - gcs().send_text(MAV_SEVERITY_WARNING, "RPM: Failed to detach from pin %u", last_pin); - // ignore this failure or the user may be stuck + if (interrupt_attached) { + // ignore this failure of the user may be stuck + IGNORE_RETURN(hal.gpio->detach_interrupt(last_pin)); + interrupt_attached = false; } irq_state[state.instance].dt_count = 0; irq_state[state.instance].dt_sum = 0; // attach to new pin last_pin = get_pin(); - if (last_pin) { + if (last_pin > 0) { hal.gpio->pinMode(last_pin, HAL_GPIO_INPUT); - if (!hal.gpio->attach_interrupt( + if (hal.gpio->attach_interrupt( last_pin, FUNCTOR_BIND_MEMBER(&AP_RPM_Pin::irq_handler, void, uint8_t, bool, uint32_t), AP_HAL::GPIO::INTERRUPT_RISING)) { - gcs().send_text(MAV_SEVERITY_WARNING, "RPM: Failed to attach to pin %u", last_pin); + interrupt_attached = true; + } else { + gcs().send_text(MAV_SEVERITY_WARNING, "RPM: Failed to attach to pin %d", last_pin); } } } diff --git a/libraries/AP_RPM/RPM_Pin.h b/libraries/AP_RPM/RPM_Pin.h index 160bb8a419f..0bc069c6815 100644 --- a/libraries/AP_RPM/RPM_Pin.h +++ b/libraries/AP_RPM/RPM_Pin.h @@ -32,7 +32,8 @@ class AP_RPM_Pin : public AP_RPM_Backend private: ModeFilterFloat_Size5 signal_quality_filter {3}; - uint8_t last_pin = -1; + int8_t last_pin = -1; // last pin number checked vs PIN parameter + bool interrupt_attached; // true if an interrupt has been attached to last_pin struct IrqState { uint32_t last_pulse_us; uint32_t dt_sum; diff --git a/libraries/AP_RPM/RPM_SITL.cpp b/libraries/AP_RPM/RPM_SITL.cpp index 7df2fd03ec4..f553bfacbe2 100644 --- a/libraries/AP_RPM/RPM_SITL.cpp +++ b/libraries/AP_RPM/RPM_SITL.cpp @@ -13,14 +13,13 @@ along with this program. If not, see . */ -#include - -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL #include "RPM_SITL.h" -extern const AP_HAL::HAL& hal; +#if AP_RPM_SIM_ENABLED -/* +#include + +/* open the sensor in constructor */ AP_RPM_SITL::AP_RPM_SITL(AP_RPM &_ap_rpm, uint8_t _instance, AP_RPM::RPM_State &_state) : @@ -35,10 +34,17 @@ void AP_RPM_SITL::update(void) if (sitl == nullptr) { return; } - if (instance == 0) { - state.rate_rpm = sitl->state.rpm[0]; - } else { - state.rate_rpm = sitl->state.rpm[1]; + const uint32_t motor_mask = sitl->state.motor_mask; + uint8_t count = 0; + // find the motor with the corresponding index + for (uint8_t i=0; i<32; i++) { + if (motor_mask & (1U<state.rpm[i]; + break; + } + count++; + } } state.rate_rpm *= ap_rpm._params[state.instance].scaling; state.signal_quality = 0.5f; @@ -46,4 +52,4 @@ void AP_RPM_SITL::update(void) } -#endif // CONFIG_HAL_BOARD +#endif // AP_RPM_SIM_ENABLED diff --git a/libraries/AP_RPM/RPM_SITL.h b/libraries/AP_RPM/RPM_SITL.h index aff9b86f408..578b206156b 100644 --- a/libraries/AP_RPM/RPM_SITL.h +++ b/libraries/AP_RPM/RPM_SITL.h @@ -14,9 +14,12 @@ */ #pragma once -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL - #include "AP_RPM.h" + +#define AP_RPM_SIM_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL) + +#if AP_RPM_SIM_ENABLED + #include "RPM_Backend.h" #include @@ -33,4 +36,4 @@ class AP_RPM_SITL : public AP_RPM_Backend uint8_t instance; }; -#endif // CONFIG_HAL_BOARD +#endif // AP_RPM_SIM_ENABLED diff --git a/libraries/AP_RSSI/AP_RSSI.cpp b/libraries/AP_RSSI/AP_RSSI.cpp index 105da81a59a..594317fe8b2 100644 --- a/libraries/AP_RSSI/AP_RSSI.cpp +++ b/libraries/AP_RSSI/AP_RSSI.cpp @@ -141,7 +141,7 @@ float AP_RSSI::read_receiver_rssi() case RssiType::RECEIVER: { int16_t rssi = RC_Channels::get_receiver_rssi(); if (rssi != -1) { - return rssi / 255.0; + return rssi * (1/255.0); } return 0.0f; } diff --git a/libraries/AP_Radio/AP_Radio.h b/libraries/AP_Radio/AP_Radio.h index 231f11504fc..0095457de26 100644 --- a/libraries/AP_Radio/AP_Radio.h +++ b/libraries/AP_Radio/AP_Radio.h @@ -18,9 +18,8 @@ * base class for direct attached radios */ -#include #include -#include +#include class AP_Radio_backend; diff --git a/libraries/AP_Radio/AP_Radio_backend.h b/libraries/AP_Radio/AP_Radio_backend.h index e6c3bda92b6..a1fd9e168e8 100644 --- a/libraries/AP_Radio/AP_Radio_backend.h +++ b/libraries/AP_Radio/AP_Radio_backend.h @@ -21,6 +21,8 @@ #include #include "AP_Radio.h" +#include + class AP_Radio_backend { public: diff --git a/libraries/AP_Radio/AP_Radio_cc2500.cpp b/libraries/AP_Radio/AP_Radio_cc2500.cpp index 999ed188f7d..e5e3b443af1 100644 --- a/libraries/AP_Radio/AP_Radio_cc2500.cpp +++ b/libraries/AP_Radio/AP_Radio_cc2500.cpp @@ -16,7 +16,7 @@ #include #include #include -#include +#include #include #include @@ -365,7 +365,7 @@ void AP_Radio_cc2500::radio_init(void) hal.gpio->attach_interrupt(HAL_GPIO_RADIO_IRQ, trigger_irq_radio_event, AP_HAL::GPIO::INTERRUPT_RISING); // fill in rxid for use in double bind prevention - char sysid[40] {}; + char sysid[50] {}; hal.util->get_system_id(sysid); uint16_t sysid_crc = calc_crc((const uint8_t *)sysid, strnlen(sysid, sizeof(sysid))); if (sysid_crc == 0) { @@ -1113,7 +1113,7 @@ void AP_Radio_cc2500::irq_handler_thd(void *arg) switch (evt) { case EVT_IRQ: if (radio_singleton->protocolState == STATE_FCCTEST) { - hal.console->printf("IRQ FCC\n"); + DEV_PRINTF("IRQ FCC\n"); } radio_singleton->irq_handler(); break; diff --git a/libraries/AP_Radio/AP_Radio_cypress.cpp b/libraries/AP_Radio/AP_Radio_cypress.cpp index a9f08f7375b..a66de153587 100644 --- a/libraries/AP_Radio/AP_Radio_cypress.cpp +++ b/libraries/AP_Radio/AP_Radio_cypress.cpp @@ -11,7 +11,7 @@ #include #include "telem_structure.h" #include -#include +#include /* driver for CYRF6936 radio diff --git a/libraries/AP_Rally/AP_Rally.cpp b/libraries/AP_Rally/AP_Rally.cpp index ed49e2c744f..d1092ae94f0 100644 --- a/libraries/AP_Rally/AP_Rally.cpp +++ b/libraries/AP_Rally/AP_Rally.cpp @@ -122,18 +122,17 @@ bool AP_Rally::set_rally_point_with_index(uint8_t i, const RallyLocation &rallyL // helper function to translate a RallyLocation to a Location Location AP_Rally::rally_location_to_location(const RallyLocation &rally_loc) const { - Location ret = {}; - - // we return an absolute altitude, as we add homeloc.alt below - ret.relative_alt = false; - - //Currently can't do true AGL on the APM. Relative altitudes are - //relative to HOME point's altitude. Terrain on the board is inbound - //for the PX4, though. This line will need to be updated when that happens: - ret.alt = (rally_loc.alt*100UL) + AP::ahrs().get_home().alt; - - ret.lat = rally_loc.lat; - ret.lng = rally_loc.lng; + //Relative altitudes are relative to HOME point's altitude: + Location ret { + rally_loc.lat, + rally_loc.lng, + rally_loc.alt * 100, + Location::AltFrame::ABOVE_HOME + }; + + // notionally the following call can fail, but we have no facility + // to return that fact here: + ret.change_alt_frame(Location::AltFrame::ABSOLUTE); return ret; } @@ -167,17 +166,13 @@ bool AP_Rally::find_nearest_rally_point(const Location ¤t_loc, RallyLocati } // return best RTL location from current position -Location AP_Rally::calc_best_rally_or_home_location(const Location ¤t_loc, float rtl_home_alt) const +Location AP_Rally::calc_best_rally_or_home_location(const Location ¤t_loc, float rtl_home_alt_amsl_cm) const { - RallyLocation ral_loc = {}; - Location return_loc = {}; - const struct Location &home_loc = AP::ahrs().get_home(); - - // no valid rally point, return home position - return_loc = home_loc; - return_loc.alt = rtl_home_alt; - return_loc.relative_alt = false; // read_alt_to_hold returns an absolute altitude + // if no valid rally point, return home position: + Location return_loc { AP::ahrs().get_home() }; + return_loc.set_alt_cm(rtl_home_alt_amsl_cm, Location::AltFrame::ABSOLUTE); + RallyLocation ral_loc; if (find_nearest_rally_point(current_loc, ral_loc)) { Location loc = rally_location_to_location(ral_loc); // use the rally point if it's closer then home, or we aren't generally considering home as acceptable diff --git a/libraries/AP_Rally/AP_Rally.h b/libraries/AP_Rally/AP_Rally.h index 2f457d52c37..5758a802f16 100644 --- a/libraries/AP_Rally/AP_Rally.h +++ b/libraries/AP_Rally/AP_Rally.h @@ -14,7 +14,7 @@ */ #pragma once -#include +#include #ifndef HAL_RALLY_ENABLED #define HAL_RALLY_ENABLED 1 @@ -68,7 +68,7 @@ class AP_Rally { Location rally_location_to_location(const RallyLocation &ret) const; // logic handling - Location calc_best_rally_or_home_location(const Location ¤t_loc, float rtl_home_alt) const; + Location calc_best_rally_or_home_location(const Location ¤t_loc, float rtl_home_alt_amsl_cm) const; bool find_nearest_rally_point(const Location &myloc, RallyLocation &ret) const; // last time rally points changed diff --git a/libraries/AP_RangeFinder/AP_RangeFinder.cpp b/libraries/AP_RangeFinder/AP_RangeFinder.cpp index fe93be6f3a3..b349ced5195 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder.cpp @@ -30,6 +30,7 @@ #include "AP_RangeFinder_LeddarOne.h" #include "AP_RangeFinder_USD1_Serial.h" #include "AP_RangeFinder_TeraRangerI2C.h" +#include "AP_RangeFinder_TeraRanger_Serial.h" #include "AP_RangeFinder_VL53L0X.h" #include "AP_RangeFinder_VL53L1X.h" #include "AP_RangeFinder_NMEA.h" @@ -41,6 +42,7 @@ #include "AP_RangeFinder_PWM.h" #include "AP_RangeFinder_GYUS42v2.h" #include "AP_RangeFinder_HC_SR04.h" +#include "AP_RangeFinder_Bebop.h" #include "AP_RangeFinder_BLPing.h" #include "AP_RangeFinder_UAVCAN.h" #include "AP_RangeFinder_Lanbao.h" @@ -175,8 +177,9 @@ RangeFinder::RangeFinder() } void RangeFinder::convert_params(void) { - if (params[0].type.configured_in_storage()) { - // _params[0]._type will always be configured in storage after conversion is done the first time + if (params[0].type.configured()) { + // _params[0]._type will always be configured after conversion is done the first time + // or the user has set a type in a defaults.parm file or via apj tool return; } @@ -187,6 +190,7 @@ void RangeFinder::convert_params(void) { }; const struct ConversionTable conversionTable[] = { + // PARAMETER_CONVERSION - Added: Feb-2019 // rangefinder 1 {0, 0, 0}, //0, TYPE 1 {1, 1, 0}, //1, PIN 1 @@ -339,19 +343,25 @@ bool RangeFinder::_add_backend(AP_RangeFinder_Backend *backend, uint8_t instance */ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) { +#if AP_RANGEFINDER_ENABLED + AP_RangeFinder_Backend_Serial *(*serial_create_fn)(RangeFinder::RangeFinder_State&, AP_RangeFinder_Params&) = nullptr; + const Type _type = (Type)params[instance].type.get(); switch (_type) { case Type::PLI2C: case Type::PLI2CV3: case Type::PLI2CV3HP: +#if AP_RANGEFINDER_PULSEDLIGHTLRF_ENABLED FOREACH_I2C(i) { if (_add_backend(AP_RangeFinder_PulsedLightLRF::detect(i, state[instance], params[instance], _type), instance)) { break; } } +#endif break; case Type::MBI2C: { +#if AP_RANGEFINDER_MAXSONARI2CXL_ENABLED uint8_t addr = AP_RANGE_FINDER_MAXSONARI2CXL_DEFAULT_ADDR; if (params[instance].address != 0) { addr = params[instance].address; @@ -364,8 +374,10 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) } } break; +#endif } case Type::LWI2C: +#if AP_RANGEFINDER_LWI2C_ENABLED if (params[instance].address) { // the LW20 needs a long time to boot up, so we delay 1.5s here if (!hal.util->was_watchdog_armed()) { @@ -385,8 +397,10 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) } #endif } +#endif // AP_RANGEFINDER_LWI2C_ENABLED break; case Type::TRI2C: +#if AP_RANGEFINDER_TRI2C_ENABLED if (params[instance].address) { FOREACH_I2C(i) { if (_add_backend(AP_RangeFinder_TeraRangerI2C::detect(state[instance], params[instance], @@ -396,15 +410,19 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) } } } +#endif break; case Type::VL53L0X: case Type::VL53L1X_Short: FOREACH_I2C(i) { +#if AP_RANGEFINDER_VL53L0X_ENABLED if (_add_backend(AP_RangeFinder_VL53L0X::detect(state[instance], params[instance], hal.i2c_mgr->get_device(i, params[instance].address)), instance)) { break; } +#endif +#if AP_RANGEFINDER_VL53L1X_ENABLED if (_add_backend(AP_RangeFinder_VL53L1X::detect(state[instance], params[instance], hal.i2c_mgr->get_device(i, params[instance].address), _type == Type::VL53L1X_Short ? AP_RangeFinder_VL53L1X::DistanceMode::Short : @@ -412,10 +430,12 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) instance)) { break; } +#endif } break; case Type::BenewakeTFminiPlus: { - uint8_t addr = TFMINI_ADDR_DEFAULT; +#if AP_RANGEFINDER_BENEWAKE_TFMINIPLUS_ENABLED + uint8_t addr = TFMINIPLUS_ADDR_DEFAULT; if (params[instance].address != 0) { addr = params[instance].address; } @@ -427,62 +447,60 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) } } break; +#endif } case Type::PX4_PWM: -#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS -#ifndef HAL_BUILD_AP_PERIPH +#if AP_RANGEFINDER_PWM_ENABLED // to ease moving from PX4 to ChibiOS we'll lie a little about // the backend driver... if (AP_RangeFinder_PWM::detect()) { _add_backend(new AP_RangeFinder_PWM(state[instance], params[instance], estimated_terrain_height), instance); } -#endif #endif break; case Type::BBB_PRU: -#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI +#if AP_RANGEFINDER_BBB_PRU_ENABLED if (AP_RangeFinder_BBB_PRU::detect()) { _add_backend(new AP_RangeFinder_BBB_PRU(state[instance], params[instance]), instance); } #endif break; case Type::LWSER: - if (AP_RangeFinder_LightWareSerial::detect(serial_instance)) { - _add_backend(new AP_RangeFinder_LightWareSerial(state[instance], params[instance]), instance, serial_instance++); - } +#if AP_RANGEFINDER_LIGHTWARE_SERIAL_ENABLED + serial_create_fn = AP_RangeFinder_LightWareSerial::create; +#endif break; case Type::LEDDARONE: - if (AP_RangeFinder_LeddarOne::detect(serial_instance)) { - _add_backend(new AP_RangeFinder_LeddarOne(state[instance], params[instance]), instance, serial_instance++); - } +#if AP_RANGEFINDER_LEDDARONE_ENABLED + serial_create_fn = AP_RangeFinder_LeddarOne::create; +#endif break; case Type::USD1_Serial: - if (AP_RangeFinder_USD1_Serial::detect(serial_instance)) { - _add_backend(new AP_RangeFinder_USD1_Serial(state[instance], params[instance]), instance, serial_instance++); - } +#if AP_RANGEFINDER_USD1_SERIAL_ENABLED + serial_create_fn = AP_RangeFinder_USD1_Serial::create; +#endif break; case Type::BEBOP: -#if (CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || \ - CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO) && defined(HAVE_LIBIIO) +#if AP_RANGEFINDER_BEBOP_ENABLED if (AP_RangeFinder_Bebop::detect()) { _add_backend(new AP_RangeFinder_Bebop(state[instance], params[instance]), instance); } #endif break; case Type::MAVLink: -#ifndef HAL_BUILD_AP_PERIPH +#if AP_RANGEFINDER_MAVLINK_ENABLED if (AP_RangeFinder_MAVLink::detect()) { _add_backend(new AP_RangeFinder_MAVLink(state[instance], params[instance]), instance); } #endif break; case Type::MBSER: - if (AP_RangeFinder_MaxsonarSerialLV::detect(serial_instance)) { - _add_backend(new AP_RangeFinder_MaxsonarSerialLV(state[instance], params[instance]), instance, serial_instance++); - } +#if AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED + serial_create_fn = AP_RangeFinder_MaxsonarSerialLV::create; +#endif break; case Type::ANALOG: -#ifndef HAL_BUILD_AP_PERIPH +#if AP_RANGEFINDER_ANALOG_ENABLED // note that analog will always come back as present if the pin is valid if (AP_RangeFinder_analog::detect(params[instance])) { _add_backend(new AP_RangeFinder_analog(state[instance], params[instance]), instance); @@ -490,7 +508,7 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) #endif break; case Type::HC_SR04: -#ifndef HAL_BUILD_AP_PERIPH +#if AP_RANGEFINDER_HC_SR04_ENABLED // note that this will always come back as present if the pin is valid if (AP_RangeFinder_HC_SR04::detect(params[instance])) { _add_backend(new AP_RangeFinder_HC_SR04(state[instance], params[instance]), instance); @@ -498,55 +516,60 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) #endif break; case Type::NMEA: - if (AP_RangeFinder_NMEA::detect(serial_instance)) { - _add_backend(new AP_RangeFinder_NMEA(state[instance], params[instance]), instance, serial_instance++); - } +#if AP_RANGEFINDER_NMEA_ENABLED + serial_create_fn = AP_RangeFinder_NMEA::create; +#endif break; case Type::WASP: - if (AP_RangeFinder_Wasp::detect(serial_instance)) { - _add_backend(new AP_RangeFinder_Wasp(state[instance], params[instance]), instance, serial_instance++); - } +#if AP_RANGEFINDER_WASP_ENABLED + serial_create_fn = AP_RangeFinder_Wasp::create; +#endif break; case Type::BenewakeTF02: - if (AP_RangeFinder_Benewake_TF02::detect(serial_instance)) { - _add_backend(new AP_RangeFinder_Benewake_TF02(state[instance], params[instance]), instance, serial_instance++); - } +#if AP_RANGEFINDER_BENEWAKE_TF02_ENABLED + serial_create_fn = AP_RangeFinder_Benewake_TF02::create; +#endif break; case Type::BenewakeTFmini: - if (AP_RangeFinder_Benewake_TFMini::detect(serial_instance)) { - _add_backend(new AP_RangeFinder_Benewake_TFMini(state[instance], params[instance]), instance, serial_instance++); - } +#if AP_RANGEFINDER_BENEWAKE_TFMINI_ENABLED + serial_create_fn = AP_RangeFinder_Benewake_TFMini::create; +#endif break; case Type::BenewakeTF03: - if (AP_RangeFinder_Benewake_TF03::detect(serial_instance)) { - _add_backend(new AP_RangeFinder_Benewake_TF03(state[instance], params[instance]), instance, serial_instance++); - } +#if AP_RANGEFINDER_BENEWAKE_TF03_ENABLED + serial_create_fn = AP_RangeFinder_Benewake_TF03::create; +#endif + break; + case Type::TeraRanger_Serial: +#if AP_RANGEFINDER_TERARANGER_SERIAL_ENABLED + serial_create_fn = AP_RangeFinder_TeraRanger_Serial::create; +#endif break; case Type::PWM: -#ifndef HAL_BUILD_AP_PERIPH +#if AP_RANGEFINDER_PWM_ENABLED if (AP_RangeFinder_PWM::detect()) { _add_backend(new AP_RangeFinder_PWM(state[instance], params[instance], estimated_terrain_height), instance); } #endif break; case Type::BLPing: - if (AP_RangeFinder_BLPing::detect(serial_instance)) { - _add_backend(new AP_RangeFinder_BLPing(state[instance], params[instance]), instance, serial_instance++); - } +#if AP_RANGEFINDER_BLPING_ENABLED + serial_create_fn = AP_RangeFinder_BLPing::create; +#endif break; case Type::Lanbao: - if (AP_RangeFinder_Lanbao::detect(serial_instance)) { - _add_backend(new AP_RangeFinder_Lanbao(state[instance], params[instance]), instance, serial_instance++); - } +#if AP_RANGEFINDER_LANBAO_ENABLED + serial_create_fn = AP_RangeFinder_Lanbao::create; +#endif break; case Type::LeddarVu8_Serial: - if (AP_RangeFinder_LeddarVu8::detect(serial_instance)) { - _add_backend(new AP_RangeFinder_LeddarVu8(state[instance], params[instance]), instance, serial_instance++); - } +#if AP_RANGEFINDER_LEDDARVU8_ENABLED + serial_create_fn = AP_RangeFinder_LeddarVu8::create; +#endif break; case Type::UAVCAN: -#if HAL_CANMANAGER_ENABLED +#if AP_RANGEFINDER_UAVCAN_ENABLED /* the UAVCAN driver gets created when we first receive a measurement. We take the instance slot now, even if we don't @@ -557,13 +580,13 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) break; case Type::GYUS42v2: - if (AP_RangeFinder_GYUS42v2::detect(serial_instance)) { - _add_backend(new AP_RangeFinder_GYUS42v2(state[instance], params[instance]), instance, serial_instance++); - } +#if AP_RANGEFINDER_GYUS42V2_ENABLED + serial_create_fn = AP_RangeFinder_GYUS42v2::create; +#endif break; case Type::SIM: -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#if AP_RANGEFINDER_SIM_ENABLED _add_backend(new AP_RangeFinder_SITL(state[instance], params[instance], instance), instance); #endif break; @@ -576,19 +599,29 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) #endif // HAL_MSP_RANGEFINDER_ENABLED break; -#if HAL_MAX_CAN_PROTOCOL_DRIVERS case Type::USD1_CAN: +#if AP_RANGEFINDER_USD1_CAN_ENABLED _add_backend(new AP_RangeFinder_USD1_CAN(state[instance], params[instance]), instance); +#endif break; case Type::Benewake_CAN: +#if AP_RANGEFINDER_BENEWAKE_CAN_ENABLED _add_backend(new AP_RangeFinder_Benewake_CAN(state[instance], params[instance]), instance); break; #endif case Type::NONE: - default: break; } + if (serial_create_fn != nullptr) { + if (AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance)) { + auto *b = serial_create_fn(state[instance], params[instance]); + if (b != nullptr) { + _add_backend(b, instance, serial_instance++); + } + } + } + // if the backend has some local parameters then make those available in the tree if (drivers[instance] && state[instance].var_info) { backend_var_info[instance] = state[instance].var_info; @@ -597,6 +630,7 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) // param count could have changed AP_Param::invalidate_count(); } +#endif //AP_RANGEFINDER_ENABLED } AP_RangeFinder_Backend *RangeFinder::get_backend(uint8_t id) const { @@ -683,11 +717,7 @@ float RangeFinder::distance_orient(enum Rotation orientation) const uint16_t RangeFinder::distance_cm_orient(enum Rotation orientation) const { - AP_RangeFinder_Backend *backend = find_instance(orientation); - if (backend == nullptr) { - return 0; - } - return backend->distance_cm(); + return distance_orient(orientation) * 100.0; } int16_t RangeFinder::max_distance_cm_orient(enum Rotation orientation) const @@ -814,6 +844,37 @@ bool RangeFinder::prearm_healthy(char *failure_msg, const uint8_t failure_msg_le return false; } + // backend-specific checks. This might end up drivers[i]->arming_checks(...). + switch (drivers[i]->allocated_type()) { + case Type::ANALOG: + case Type::PX4_PWM: + case Type::PWM: { + // ensure pin is configured + if (params[i].pin == -1) { + hal.util->snprintf(failure_msg, failure_msg_len, "RNGFND%u_PIN not set", unsigned(i + 1)); + return false; + } + if (drivers[i]->allocated_type() == Type::ANALOG) { + // Analog backend does not use GPIO pin + break; + } + + // ensure that the pin we're configured to use is available + if (!hal.gpio->valid_pin(params[i].pin)) { + uint8_t servo_ch; + if (hal.gpio->pin_to_servo_channel(params[i].pin, servo_ch)) { + hal.util->snprintf(failure_msg, failure_msg_len, "RNGFND%u_PIN=%d, set SERVO%u_FUNCTION=-1", unsigned(i + 1), int(params[i].pin.get()), unsigned(servo_ch+1)); + } else { + hal.util->snprintf(failure_msg, failure_msg_len, "RNGFND%u_PIN=%d invalid", unsigned(i + 1), int(params[i].pin.get())); + } + return false; + } + break; + } + default: + break; + } + switch (drivers[i]->status()) { case Status::NoData: hal.util->snprintf(failure_msg, failure_msg_len, "Rangefinder %X: No Data", i + 1); @@ -841,3 +902,4 @@ RangeFinder *rangefinder() } } + diff --git a/libraries/AP_RangeFinder/AP_RangeFinder.h b/libraries/AP_RangeFinder/AP_RangeFinder.h index 7474c4cadfa..dfb01b56749 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder.h @@ -15,15 +15,28 @@ #pragma once #include -#include +#include +#include #include -#include +#include #include #include "AP_RangeFinder_Params.h" +#ifndef AP_RANGEFINDER_ENABLED +#define AP_RANGEFINDER_ENABLED 1 +#endif + +#ifndef AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#define AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED AP_RANGEFINDER_ENABLED +#endif + // Maximum number of range finder instances available on this platform -#ifndef RANGEFINDER_MAX_INSTANCES -#define RANGEFINDER_MAX_INSTANCES 10 +#ifndef RANGEFINDER_MAX_INSTANCES + #if AP_RANGEFINDER_ENABLED + #define RANGEFINDER_MAX_INSTANCES 10 + #else + #define RANGEFINDER_MAX_INSTANCES 1 + #endif #endif #define RANGEFINDER_GROUND_CLEARANCE_CM_DEFAULT 10 @@ -89,6 +102,7 @@ class RangeFinder MSP = 32, USD1_CAN = 33, Benewake_CAN = 34, + TeraRanger_Serial = 35, SIM = 100, }; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_BBB_PRU.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_BBB_PRU.cpp index dca89c814d3..d06b99b2096 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_BBB_PRU.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_BBB_PRU.cpp @@ -16,11 +16,10 @@ by Mirko Denecke */ -#include -#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI - #include "AP_RangeFinder_BBB_PRU.h" +#if AP_RANGEFINDER_BBB_PRU_ENABLED + #include #include #include @@ -105,4 +104,4 @@ void AP_RangeFinder_BBB_PRU::update(void) state.distance_m = rangerpru->distance * 0.01f; state.last_reading_ms = AP_HAL::millis(); } -#endif // CONFIG_HAL_BOARD_SUBTYPE +#endif // AP_RANGEFINDER_BBB_PRU_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_BBB_PRU.h b/libraries/AP_RangeFinder/AP_RangeFinder_BBB_PRU.h index 0335928d025..ddff67dda2a 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_BBB_PRU.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_BBB_PRU.h @@ -3,6 +3,16 @@ #include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend.h" +#include + +#ifndef AP_RANGEFINDER_BBB_PRU_ENABLED +#define AP_RANGEFINDER_BBB_PRU_ENABLED ( \ + AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED && \ + CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI \ + ) +#endif + +#if AP_RANGEFINDER_BBB_PRU_ENABLED #define PRU0_CTRL_BASE 0x4a322000 @@ -43,3 +53,5 @@ class AP_RangeFinder_BBB_PRU : public AP_RangeFinder_Backend private: }; + +#endif diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.cpp index bfc87f00d67..54036e2bba0 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.cpp @@ -13,10 +13,12 @@ along with this program. If not, see . */ -#include -#include #include "AP_RangeFinder_BLPing.h" +#if AP_RANGEFINDER_BLPING_ENABLED + +#include + void AP_RangeFinder_BLPing::update(void) { if (uart == nullptr) { @@ -226,3 +228,5 @@ PingProtocol::MessageId PingProtocol::parse_byte(uint8_t b) return msg.done ? get_message_id() : MessageId::INVALID; } + +#endif // AP_RANGEFINDER_BLPING_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.h b/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.h index 92d9fed4353..63be4121cce 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.h @@ -1,6 +1,13 @@ #pragma once #include "AP_RangeFinder.h" + +#ifndef AP_RANGEFINDER_BLPING_ENABLED +#define AP_RANGEFINDER_BLPING_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_RANGEFINDER_BLPING_ENABLED + #include "AP_RangeFinder_Backend_Serial.h" /** @@ -117,7 +124,12 @@ class AP_RangeFinder_BLPing : public AP_RangeFinder_Backend_Serial static constexpr uint16_t _sensor_rate_ms = 50; // initialise sensor at no more than 20hz public: - using AP_RangeFinder_Backend_Serial::AP_RangeFinder_Backend_Serial; + + static AP_RangeFinder_Backend_Serial *create( + RangeFinder::RangeFinder_State &_state, + AP_RangeFinder_Params &_params) { + return new AP_RangeFinder_BLPing(_state, _params); + } /** * @brief Update class state @@ -142,6 +154,9 @@ class AP_RangeFinder_BLPing : public AP_RangeFinder_Backend_Serial PingProtocol protocol; private: + + using AP_RangeFinder_Backend_Serial::AP_RangeFinder_Backend_Serial; + /** * @brief Do the necessary sensor initiation * @@ -170,3 +185,5 @@ class AP_RangeFinder_BLPing : public AP_RangeFinder_Backend_Serial */ uint32_t last_init_ms; }; + +#endif diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Backend.h b/libraries/AP_RangeFinder/AP_RangeFinder_Backend.h index ce9a83554a3..e5e2a02d221 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Backend.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Backend.h @@ -15,7 +15,8 @@ #pragma once #include -#include +#include +#include #include "AP_RangeFinder.h" class AP_RangeFinder_Backend @@ -68,6 +69,10 @@ class AP_RangeFinder_Backend // quality is not available virtual bool get_signal_quality_pct(uint8_t &quality_pct) const { return false; } + // return the actual type of the rangefinder, as opposed to the + // parameter value which may be changed at runtime. + RangeFinder::Type allocated_type() const { return _backend_type; } + protected: // update status based on distance measurement diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Backend_Serial.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Backend_Serial.cpp index cfacdb6ba16..186e4d1bd79 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Backend_Serial.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Backend_Serial.cpp @@ -47,16 +47,6 @@ uint32_t AP_RangeFinder_Backend_Serial::initial_baudrate(const uint8_t serial_in return AP::serialmanager().find_baudrate(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance); } -/* - detect if a Serial rangefinder is connected. We'll detect by simply - checking for SerialManager configuration -*/ -bool AP_RangeFinder_Backend_Serial::detect(uint8_t serial_instance) -{ - return AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance); -} - - /* update the state of the sensor */ diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Backend_Serial.h b/libraries/AP_RangeFinder/AP_RangeFinder_Backend_Serial.h index ce117f8e5ac..ecb7508d476 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Backend_Serial.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Backend_Serial.h @@ -10,8 +10,6 @@ class AP_RangeFinder_Backend_Serial : public AP_RangeFinder_Backend AP_RangeFinder_Params &_params); void init_serial(uint8_t serial_instance) override; - // static detection function - static bool detect(uint8_t serial_instance); protected: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Bebop.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Bebop.cpp index a9028ef2c9d..5d1dd73ff4b 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Bebop.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Bebop.cpp @@ -12,13 +12,14 @@ You should have received a copy of the GNU General Public License along with this program. If not, see . */ + +#include "AP_RangeFinder_Bebop.h" + +#if AP_RANGEFINDER_BEBOP_ENABLED + #include #include -#if (CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || \ - CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO) && \ - defined(HAVE_LIBIIO) - #include #include #include @@ -32,7 +33,6 @@ #include #include #include -#include "AP_RangeFinder_Bebop.h" #include #include @@ -245,12 +245,12 @@ void AP_RangeFinder_Bebop::_loop(void) _capture(); if (_apply_averaging_filter() < 0) { - hal.console->printf( + DEV_PRINTF( "AR_RangeFinder_Bebop: could not apply averaging filter"); } if (_search_local_maxima() < 0) { - hal.console->printf("Did not find any local maximum"); + DEV_PRINTF("Did not find any local maximum"); } max_index = _search_maximum_with_max_amplitude(); @@ -296,7 +296,7 @@ void AP_RangeFinder_Bebop::_configure_gpio(int value) _gpio->write(LINUX_GPIO_ULTRASOUND_VOLTAGE, 0); break; default: - hal.console->printf("bad gpio value (%d)", value); + DEV_PRINTF("bad gpio value (%d)", value); break; } } @@ -310,10 +310,10 @@ void AP_RangeFinder_Bebop::_reconfigure_wave() /* configure the output buffer for a purge */ /* perform a purge */ if (_launch_purge() < 0) { - hal.console->printf("purge could not send data overspi"); + DEV_PRINTF("purge could not send data overspi"); } if (_capture() < 0) { - hal.console->printf("purge could not capture data"); + DEV_PRINTF("purge could not capture data"); } _tx_buf = _tx[_mode]; @@ -325,13 +325,13 @@ void AP_RangeFinder_Bebop::_reconfigure_wave() _configure_gpio(1); break; default: - hal.console->printf("WARNING, invalid value to configure gpio\n"); + DEV_PRINTF("WARNING, invalid value to configure gpio\n"); break; } } /* - * First configuration of the the pulse that will be send over spi + * First configuration of the pulse that will be send over spi */ int AP_RangeFinder_Bebop::_configure_wave() { @@ -355,13 +355,13 @@ int AP_RangeFinder_Bebop::_configure_capture() _adc.device = iio_context_find_device(_iio, adcname); if (!_adc.device) { - hal.console->printf("Unable to find %s", adcname); + DEV_PRINTF("Unable to find %s", adcname); goto error_destroy_context; } _adc.channel = iio_device_find_channel(_adc.device, adcchannel, false); if (!_adc.channel) { - hal.console->printf("Fail to init adc channel %s", adcchannel); + DEV_PRINTF("Fail to init adc channel %s", adcchannel); goto error_destroy_context; } @@ -374,13 +374,13 @@ int AP_RangeFinder_Bebop::_configure_capture() /* Create input buffer */ _adc.buffer_size = RNFD_BEBOP_P7_COUNT; if (iio_device_set_kernel_buffers_count(_adc.device, 1)) { - hal.console->printf("cannot set buffer count"); + DEV_PRINTF("cannot set buffer count"); goto error_destroy_context; } _adc.buffer = iio_device_create_buffer(_adc.device, _adc.buffer_size, false); if (!_adc.buffer) { - hal.console->printf("Fail to create buffer : %s", strerror(errno)); + DEV_PRINTF("Fail to create buffer : %s", strerror(errno)); goto error_destroy_context; } @@ -474,4 +474,5 @@ int AP_RangeFinder_Bebop::_update_mode(float altitude) } return _mode; } -#endif + +#endif // AP_RANGEFINDER_BEBOP_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Bebop.h b/libraries/AP_RangeFinder/AP_RangeFinder_Bebop.h index cc7302183b2..fa1c0622032 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Bebop.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Bebop.h @@ -16,6 +16,20 @@ #include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend.h" + +#include +#include + +#ifndef AP_RANGEFINDER_BEBOP_ENABLED +#define AP_RANGEFINDER_BEBOP_ENABLED \ + AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED && \ + (CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || \ + CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO) && \ + defined(HAVE_LIBIIO) +#endif + +#if AP_RANGEFINDER_BEBOP_ENABLED + #include /* @@ -143,3 +157,5 @@ class AP_RangeFinder_Bebop : public AP_RangeFinder_Backend { int16_t _last_min_distance_cm = 32; }; + +#endif diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake.cpp index fed7778c488..ceea2fd1681 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake.cpp @@ -15,6 +15,8 @@ #include "AP_RangeFinder_Benewake.h" +#if AP_RANGEFINDER_BENEWAKE_ENABLED + #include #include @@ -91,8 +93,12 @@ bool AP_RangeFinder_Benewake::get_reading(float &reading_m) if (checksum == linebuf[BENEWAKE_FRAME_LENGTH-1]) { // calculate distance uint16_t dist = ((uint16_t)linebuf[3] << 8) | linebuf[2]; - if (dist >= BENEWAKE_DIST_MAX_CM) { - // this reading is out of range + if (dist >= BENEWAKE_DIST_MAX_CM || dist == uint16_t(model_dist_max_cm())) { + // this reading is out of range. Note that we + // consider getting exactly the model dist max + // is out of range. This fixes an issue with + // the TF03 which can give exactly 18000 cm + // when out of range count_out_of_range++; } else if (!has_signal_byte()) { // no signal byte from TFmini so add distance to sum @@ -132,3 +138,5 @@ bool AP_RangeFinder_Benewake::get_reading(float &reading_m) // no readings so return false return false; } + +#endif // AP_RANGEFINDER_BENEWAKE_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake.h b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake.h index 4dbe430d078..a52f042f779 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake.h @@ -1,6 +1,13 @@ #pragma once #include "AP_RangeFinder.h" + +#ifndef AP_RANGEFINDER_BENEWAKE_ENABLED +#define AP_RANGEFINDER_BENEWAKE_ENABLED AP_RANGEFINDER_ENABLED +#endif + +#if AP_RANGEFINDER_BENEWAKE_ENABLED + #include "AP_RangeFinder_Backend_Serial.h" class AP_RangeFinder_Benewake : public AP_RangeFinder_Backend_Serial @@ -28,3 +35,5 @@ class AP_RangeFinder_Benewake : public AP_RangeFinder_Backend_Serial uint8_t linebuf[10]; uint8_t linebuf_len; }; + +#endif // AP_RANGEFINDER_BENEWAKE_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_CAN.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_CAN.cpp index fa0c1032b50..40c8118ec6f 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_CAN.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_CAN.cpp @@ -1,8 +1,9 @@ #include #include #include "AP_RangeFinder_Benewake_CAN.h" +#include -#if HAL_MAX_CAN_PROTOCOL_DRIVERS +#if AP_RANGEFINDER_BENEWAKE_CAN_ENABLED const AP_Param::GroupInfo AP_RangeFinder_Benewake_CAN::var_info[] = { @@ -67,10 +68,46 @@ void AP_RangeFinder_Benewake_CAN::update(void) } } +// handler for incoming frames for H30 radar +bool AP_RangeFinder_Benewake_CAN::handle_frame_H30(AP_HAL::CANFrame &frame) +{ + /* + The H30 produces 3 targets, each as 16 bit unsigned integers in + cm. Only look at target1 for now + */ + const uint16_t target1_cm = be16toh_ptr(&frame.data[0]); + if (target1_cm == 0) { + // no target gives 0 + return false; + } + //uint16_t target2 = be16toh_ptr(&frame.data[2]); + //uint16_t target3 = be16toh_ptr(&frame.data[4]); + + _distance_sum_cm += target1_cm; + _distance_count++; + + return true; +} + // handler for incoming frames. These come in at 100Hz bool AP_RangeFinder_Benewake_CAN::handle_frame(AP_HAL::CANFrame &frame) { WITH_SEMAPHORE(_sem); + if (frame.isExtended()) { + // H30 radar uses extended frames + const int32_t id = int32_t(frame.id & AP_HAL::CANFrame::MaskExtID); + if (receive_id != 0 && id != receive_id.get()) { + // incorrect receive ID + return false; + } + if (last_recv_id != -1 && id != last_recv_id) { + // changing ID + return false; + } + last_recv_id = id; + return handle_frame_H30(frame); + } + const uint16_t id = frame.id & AP_HAL::CANFrame::MaskStdID; if (receive_id != 0 && id != uint16_t(receive_id.get())) { // incorrect receive ID @@ -82,8 +119,8 @@ bool AP_RangeFinder_Benewake_CAN::handle_frame(AP_HAL::CANFrame &frame) } last_recv_id = id; - const uint16_t dist_cm = (frame.data[1]<<8) | frame.data[0]; - const uint16_t snr = (frame.data[3]<<8) | frame.data[2]; + const uint16_t dist_cm = le16toh_ptr(&frame.data[0]); + const uint16_t snr = le16toh_ptr(&frame.data[2]); if (snr_min != 0 && snr < uint16_t(snr_min.get())) { // too low signal strength return true; @@ -104,4 +141,4 @@ void Benewake_MultiCAN::handle_frame(AP_HAL::CANFrame &frame) } } -#endif // HAL_MAX_CAN_PROTOCOL_DRIVERS +#endif // AP_RANGEFINDER_BENEWAKE_CAN_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_CAN.h b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_CAN.h index b72aa30d55c..265f2793b98 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_CAN.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_CAN.h @@ -1,9 +1,14 @@ #pragma once #include "AP_RangeFinder_Backend.h" + #include -#if HAL_MAX_CAN_PROTOCOL_DRIVERS +#ifndef AP_RANGEFINDER_BENEWAKE_CAN_ENABLED +#define AP_RANGEFINDER_BENEWAKE_CAN_ENABLED (HAL_MAX_CAN_PROTOCOL_DRIVERS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) +#endif + +#if AP_RANGEFINDER_BENEWAKE_CAN_ENABLED class Benewake_MultiCAN; @@ -17,6 +22,7 @@ class AP_RangeFinder_Benewake_CAN : public AP_RangeFinder_Backend { // handler for incoming frames. Return true if consumed bool handle_frame(AP_HAL::CANFrame &frame); + bool handle_frame_H30(AP_HAL::CANFrame &frame); static const struct AP_Param::GroupInfo var_info[]; @@ -52,6 +58,6 @@ class Benewake_MultiCAN : public CANSensor { AP_RangeFinder_Benewake_CAN *drivers; }; -#endif //HAL_MAX_CAN_PROTOCOL_DRIVERS +#endif // AP_RANGEFINDER_BENEWAKE_CAN_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TF02.h b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TF02.h index 89af15632cd..207eed4f27c 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TF02.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TF02.h @@ -2,12 +2,30 @@ #include "AP_RangeFinder_Benewake.h" +#ifndef AP_RANGEFINDER_BENEWAKE_TF02_ENABLED +#define AP_RANGEFINDER_BENEWAKE_TF02_ENABLED (AP_RANGEFINDER_BENEWAKE_ENABLED && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) +#endif + +#if AP_RANGEFINDER_BENEWAKE_TF02_ENABLED + class AP_RangeFinder_Benewake_TF02 : public AP_RangeFinder_Benewake { public: - using AP_RangeFinder_Benewake::AP_RangeFinder_Benewake; + + static AP_RangeFinder_Backend_Serial *create( + RangeFinder::RangeFinder_State &_state, + AP_RangeFinder_Params &_params) { + return new AP_RangeFinder_Benewake_TF02(_state, _params); + } protected: float model_dist_max_cm() const override { return 2200; } bool has_signal_byte() const override { return true; } + +private: + + using AP_RangeFinder_Benewake::AP_RangeFinder_Benewake; + }; + +#endif // AP_RANGEFINDER_BENEWAKE_TF02_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TF03.h b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TF03.h index 38f5746facb..8353307fc3d 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TF03.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TF03.h @@ -2,11 +2,27 @@ #include "AP_RangeFinder_Benewake.h" +#ifndef AP_RANGEFINDER_BENEWAKE_TF03_ENABLED +#define AP_RANGEFINDER_BENEWAKE_TF03_ENABLED (AP_RANGEFINDER_BENEWAKE_ENABLED && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) +#endif + +#if AP_RANGEFINDER_BENEWAKE_TF03_ENABLED + class AP_RangeFinder_Benewake_TF03 : public AP_RangeFinder_Benewake { public: - using AP_RangeFinder_Benewake::AP_RangeFinder_Benewake; + + static AP_RangeFinder_Backend_Serial *create( + RangeFinder::RangeFinder_State &_state, + AP_RangeFinder_Params &_params) { + return new AP_RangeFinder_Benewake_TF03(_state, _params); + } protected: float model_dist_max_cm() const override { return 18000; } + +private: + using AP_RangeFinder_Benewake::AP_RangeFinder_Benewake; }; + +#endif // AP_RANGEFINDER_BENEWAKE_TF03_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMini.h b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMini.h index b2b39704cbb..1116f748a6f 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMini.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMini.h @@ -2,13 +2,28 @@ #include "AP_RangeFinder_Benewake.h" -#define TFMINI_ADDR_DEFAULT 0x10 // TFMini default device id +#ifndef AP_RANGEFINDER_BENEWAKE_TFMINI_ENABLED +#define AP_RANGEFINDER_BENEWAKE_TFMINI_ENABLED (AP_RANGEFINDER_BENEWAKE_ENABLED && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) +#endif + +#if AP_RANGEFINDER_BENEWAKE_TFMINI_ENABLED class AP_RangeFinder_Benewake_TFMini : public AP_RangeFinder_Benewake { public: - using AP_RangeFinder_Benewake::AP_RangeFinder_Benewake; + + static AP_RangeFinder_Backend_Serial *create( + RangeFinder::RangeFinder_State &_state, + AP_RangeFinder_Params &_params) { + return new AP_RangeFinder_Benewake_TFMini(_state, _params); + } protected: float model_dist_max_cm() const override { return 1200; } + +private: + + using AP_RangeFinder_Benewake::AP_RangeFinder_Benewake; }; + +#endif // AP_RANGEFINDER_BENEWAKE_TFMINI diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMiniPlus.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMiniPlus.cpp index 6b0cd40caba..fc4e227c74b 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMiniPlus.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMiniPlus.cpp @@ -16,6 +16,8 @@ */ #include "AP_RangeFinder_Benewake_TFMiniPlus.h" +#if AP_RANGEFINDER_BENEWAKE_TFMINIPLUS_ENABLED + #include #include @@ -107,13 +109,13 @@ bool AP_RangeFinder_Benewake_TFMiniPlus::init() goto fail; } - hal.console->printf(DRIVER ": found fw version %u.%u.%u\n", + DEV_PRINTF(DRIVER ": found fw version %u.%u.%u\n", val[5], val[4], val[3]); for (i = 0; i < ARRAY_SIZE(cmds); i++) { ret = _dev->transfer(cmds[i], cmds[i][1], nullptr, 0); if (!ret) { - hal.console->printf(DRIVER ": Unable to set configuration register %u\n", + DEV_PRINTF(DRIVER ": Unable to set configuration register %u\n", cmds[i][2]); goto fail; } @@ -219,3 +221,5 @@ void AP_RangeFinder_Benewake_TFMiniPlus::timer() accum.count++; } } + +#endif // AP_RANGEFINDER_BENEWAKE_TFMINIPLUS_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMiniPlus.h b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMiniPlus.h index b19a44c0877..b3cd7e6a51c 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMiniPlus.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMiniPlus.h @@ -19,6 +19,14 @@ #include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend.h" +#ifndef AP_RANGEFINDER_BENEWAKE_TFMINIPLUS_ENABLED +#define AP_RANGEFINDER_BENEWAKE_TFMINIPLUS_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_RANGEFINDER_BENEWAKE_TFMINIPLUS_ENABLED + +#define TFMINIPLUS_ADDR_DEFAULT 0x10 // TFMini default device id + #include #include @@ -60,3 +68,5 @@ class AP_RangeFinder_Benewake_TFMiniPlus : public AP_RangeFinder_Backend uint32_t count; } accum; }; + +#endif diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_GYUS42v2.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_GYUS42v2.cpp index 8132235bb97..36bac115729 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_GYUS42v2.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_GYUS42v2.cpp @@ -13,11 +13,9 @@ along with this program. If not, see . */ -#include #include "AP_RangeFinder_GYUS42v2.h" -#include -extern const AP_HAL::HAL& hal; +#if AP_RANGEFINDER_GYUS42V2_ENABLED bool AP_RangeFinder_GYUS42v2::find_signature_in_buffer(uint8_t start) { @@ -70,3 +68,5 @@ bool AP_RangeFinder_GYUS42v2::get_reading(float &reading_m) return true; } + +#endif // AP_RANGEFINDER_GYUS42V2_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_GYUS42v2.h b/libraries/AP_RangeFinder/AP_RangeFinder_GYUS42v2.h index 3403b86d598..8e0d9281d33 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_GYUS42v2.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_GYUS42v2.h @@ -1,6 +1,13 @@ #pragma once #include "AP_RangeFinder.h" + +#ifndef AP_RANGEFINDER_GYUS42V2_ENABLED +#define AP_RANGEFINDER_GYUS42V2_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_RANGEFINDER_GYUS42V2_ENABLED + #include "AP_RangeFinder_Backend_Serial.h" class AP_RangeFinder_GYUS42v2 : public AP_RangeFinder_Backend_Serial @@ -8,7 +15,11 @@ class AP_RangeFinder_GYUS42v2 : public AP_RangeFinder_Backend_Serial public: - using AP_RangeFinder_Backend_Serial::AP_RangeFinder_Backend_Serial; + static AP_RangeFinder_Backend_Serial *create( + RangeFinder::RangeFinder_State &_state, + AP_RangeFinder_Params &_params) { + return new AP_RangeFinder_GYUS42v2(_state, _params); + } protected: @@ -22,6 +33,8 @@ class AP_RangeFinder_GYUS42v2 : public AP_RangeFinder_Backend_Serial private: + using AP_RangeFinder_Backend_Serial::AP_RangeFinder_Backend_Serial; + // get a reading bool get_reading(float &reading_m) override; @@ -32,3 +45,5 @@ class AP_RangeFinder_GYUS42v2 : public AP_RangeFinder_Backend_Serial uint8_t buffer[7]; uint8_t buffer_used; }; + +#endif // AP_RANGEFINDER_GYUS42V2_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_HC_SR04.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_HC_SR04.cpp index 877fba0d927..6e7cc156ec4 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_HC_SR04.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_HC_SR04.cpp @@ -25,10 +25,13 @@ * The second pin we use for triggering the ultransonic pulse */ +#include "AP_RangeFinder_HC_SR04.h" + +#if AP_RANGEFINDER_HC_SR04_ENABLED + #include #include "AP_RangeFinder.h" #include "AP_RangeFinder_Params.h" -#include "AP_RangeFinder_HC_SR04.h" #include @@ -140,3 +143,4 @@ void AP_RangeFinder_HC_SR04::update(void) } } +#endif // AP_RANGEFINDER_HC_SR04_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_HC_SR04.h b/libraries/AP_RangeFinder/AP_RangeFinder_HC_SR04.h index 5c8abe4589d..5ef460f6bba 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_HC_SR04.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_HC_SR04.h @@ -2,6 +2,13 @@ #include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend.h" + +#ifndef AP_RANGEFINDER_HC_SR04_ENABLED +#define AP_RANGEFINDER_HC_SR04_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_RANGEFINDER_HC_SR04_ENABLED + #include "AP_RangeFinder_Params.h" class AP_RangeFinder_HC_SR04 : public AP_RangeFinder_Backend @@ -37,3 +44,5 @@ class AP_RangeFinder_HC_SR04 : public AP_RangeFinder_Backend uint32_t last_ping_ms; }; + +#endif // AP_RANGEFINDER_HC_SR04_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Lanbao.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Lanbao.cpp index 6fcfc851160..d59b030e50e 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Lanbao.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Lanbao.cpp @@ -15,8 +15,11 @@ /* driver for Lanbao PSK-CM8JL65-CC5 Lidar */ -#include #include "AP_RangeFinder_Lanbao.h" + +#if AP_RANGEFINDER_LANBAO_ENABLED + +#include #include #include @@ -80,3 +83,5 @@ bool AP_RangeFinder_Lanbao::get_reading(float &reading_m) } return false; } + +#endif // AP_RANGEFINDER_LANBAO_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Lanbao.h b/libraries/AP_RangeFinder/AP_RangeFinder_Lanbao.h index 86c85ff8678..d65b607c8a6 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Lanbao.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Lanbao.h @@ -3,12 +3,22 @@ #include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend_Serial.h" +#ifndef AP_RANGEFINDER_LANBAO_ENABLED +#define AP_RANGEFINDER_LANBAO_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_RANGEFINDER_LANBAO_ENABLED + class AP_RangeFinder_Lanbao : public AP_RangeFinder_Backend_Serial { public: - using AP_RangeFinder_Backend_Serial::AP_RangeFinder_Backend_Serial; + static AP_RangeFinder_Backend_Serial *create( + RangeFinder::RangeFinder_State &_state, + AP_RangeFinder_Params &_params) { + return new AP_RangeFinder_Lanbao(_state, _params); + } // Lanbao is always 115200: uint32_t initial_baudrate(uint8_t serial_instance) const override { @@ -22,9 +32,14 @@ class AP_RangeFinder_Lanbao : public AP_RangeFinder_Backend_Serial } private: + + using AP_RangeFinder_Backend_Serial::AP_RangeFinder_Backend_Serial; + // get a reading bool get_reading(float &reading_m) override; uint8_t buf[6]; uint8_t buf_len = 0; }; + +#endif // AP_RANGEFINDER_LANBAO_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp index ce9ca93989c..e7e8b83cfdd 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp @@ -15,6 +15,8 @@ #include "AP_RangeFinder_LeddarOne.h" +#if AP_RANGEFINDER_LEDDARONE_ENABLED + #include #include @@ -70,7 +72,7 @@ bool AP_RangeFinder_LeddarOne::get_reading(float &reading_m) leddarone_status = parse_response(number_detections); if (leddarone_status == LEDDARONE_STATE_OK) { - reading_m = (sum_distance * 0.01f) / number_detections; + reading_m = (sum_distance_mm * 0.001f) / number_detections; // reset mod_bus status to read new buffer modbus_status = LEDDARONE_MODBUS_STATE_INIT; @@ -131,14 +133,13 @@ bool AP_RangeFinder_LeddarOne::CRC16(uint8_t *aBuffer, uint8_t aLength, bool aCh */ LeddarOne_Status AP_RangeFinder_LeddarOne::parse_response(uint8_t &number_detections) { - uint8_t index; uint8_t index_offset = LEDDARONE_DETECTION_DATA_INDEX_OFFSET; // read serial uint32_t nbytes = uart->available(); if (nbytes != 0) { - for (index=read_len; index= LEDDARONE_READ_BUFFER_SIZE) { return LEDDARONE_STATE_ERR_BAD_RESPONSE; } @@ -170,12 +171,10 @@ LeddarOne_Status AP_RangeFinder_LeddarOne::parse_response(uint8_t &number_detect return LEDDARONE_STATE_ERR_NUMBER_DETECTIONS; } - memset(detections, 0, sizeof(detections)); - sum_distance = 0; - for (index=0; index(read_buffer[index_offset])*256 + read_buffer[index_offset+1]) / 10; - sum_distance += detections[index]; + sum_distance_mm = 0; + for (uint8_t index=0; index #include @@ -202,3 +204,5 @@ bool AP_RangeFinder_LeddarVu8::parse_byte(uint8_t b, bool &valid_reading, uint16 valid_reading = false; return false; } + +#endif // AP_RANGEFINDER_LEDDARVU8_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarVu8.h b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarVu8.h index 75fa8dd67f7..f4492557da2 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarVu8.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarVu8.h @@ -3,6 +3,12 @@ #include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend_Serial.h" +#ifndef AP_RANGEFINDER_LEDDARVU8_ENABLED +#define AP_RANGEFINDER_LEDDARVU8_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_RANGEFINDER_LEDDARVU8_ENABLED + #define LEDDARVU8_PAYLOAD_LENGTH (8*2) class AP_RangeFinder_LeddarVu8 : public AP_RangeFinder_Backend_Serial @@ -10,7 +16,11 @@ class AP_RangeFinder_LeddarVu8 : public AP_RangeFinder_Backend_Serial public: - using AP_RangeFinder_Backend_Serial::AP_RangeFinder_Backend_Serial; + static AP_RangeFinder_Backend_Serial *create( + RangeFinder::RangeFinder_State &_state, + AP_RangeFinder_Params &_params) { + return new AP_RangeFinder_LeddarVu8(_state, _params); + } protected: @@ -32,6 +42,8 @@ class AP_RangeFinder_LeddarVu8 : public AP_RangeFinder_Backend_Serial private: + using AP_RangeFinder_Backend_Serial::AP_RangeFinder_Backend_Serial; + // function codes enum class FunctionCode : uint8_t { READ_HOLDING_REGISTER = 0x03, @@ -90,3 +102,5 @@ class AP_RangeFinder_LeddarVu8 : public AP_RangeFinder_Backend_Serial uint32_t last_distance_ms; // system time of last successful distance sensor read uint32_t last_distance_request_ms; // system time of last request to sensor to send distances }; + +#endif // AP_RANGEFINDER_LEDDARVU8_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp index 8ae8e50e3bb..725b76f4f63 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp @@ -13,6 +13,9 @@ along with this program. If not, see . */ #include "AP_RangeFinder_LightWareI2C.h" + +#if AP_RANGEFINDER_LWI2C_ENABLED + #include #include @@ -188,14 +191,14 @@ void AP_RangeFinder_LightWareI2C::sf20_get_version(const char* send_msg, const c bool AP_RangeFinder_LightWareI2C::init() { if (sf20_init()) { - hal.console->printf("Found SF20 native Lidar\n"); + DEV_PRINTF("Found SF20 native Lidar\n"); return true; } if (legacy_init()) { - hal.console->printf("Found SF20 legacy Lidar\n"); + DEV_PRINTF("Found SF20 legacy Lidar\n"); return true; } - hal.console->printf("SF20 not found\n"); + DEV_PRINTF("SF20 not found\n"); return false; } @@ -242,7 +245,7 @@ bool AP_RangeFinder_LightWareI2C::sf20_init() sf20_get_version("?P\r\n", "p:", version); if (version[0]) { - hal.console->printf("SF20 Lidar version %s\n", version); + DEV_PRINTF("SF20 Lidar version %s\n", version); } // Makes sure that "address tagging" is turned off. @@ -500,3 +503,5 @@ bool AP_RangeFinder_LightWareI2C::sf20_wait_on_reply(uint8_t *rx_two_byte) } return false; } + +#endif // AP_RANGEFINDER_LWI2C_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.h b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.h index fd75e483c2b..ebc5e760ce0 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.h @@ -2,6 +2,13 @@ #include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend.h" + +#ifndef AP_RANGEFINDER_LWI2C_ENABLED +#define AP_RANGEFINDER_LWI2C_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_RANGEFINDER_LWI2C_ENABLED + #include #define NUM_SF20_DATA_STREAMS 1 @@ -58,3 +65,5 @@ class AP_RangeFinder_LightWareI2C : public AP_RangeFinder_Backend void data_log(uint16_t *val); AP_HAL::OwnPtr _dev; }; + +#endif // AP_RANGEFINDER_LWI2C_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.cpp index 79a1e2055c3..9636b47bf27 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.cpp @@ -15,6 +15,8 @@ #include "AP_RangeFinder_LightWareSerial.h" +#if AP_RANGEFINDER_LIGHTWARE_SERIAL_ENABLED + #include #include @@ -149,3 +151,5 @@ bool AP_RangeFinder_LightWareSerial::is_lost_signal_distance(int16_t distance_cm } return false; } + +#endif diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h index 590f1c55e7d..a5fb37f3563 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h @@ -3,15 +3,27 @@ #include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend_Serial.h" +#ifndef AP_RANGEFINDER_LIGHTWARE_SERIAL_ENABLED +#define AP_RANGEFINDER_LIGHTWARE_SERIAL_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_RANGEFINDER_LIGHTWARE_SERIAL_ENABLED + class AP_RangeFinder_LightWareSerial : public AP_RangeFinder_Backend_Serial { public: - using AP_RangeFinder_Backend_Serial::AP_RangeFinder_Backend_Serial; + static AP_RangeFinder_Backend_Serial *create( + RangeFinder::RangeFinder_State &_state, + AP_RangeFinder_Params &_params) { + return new AP_RangeFinder_LightWareSerial(_state, _params); + } protected: + using AP_RangeFinder_Backend_Serial::AP_RangeFinder_Backend_Serial; + MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override { return MAV_DISTANCE_SENSOR_LASER; } @@ -43,3 +55,5 @@ class AP_RangeFinder_LightWareSerial : public AP_RangeFinder_Backend_Serial bool no_signal = false; }; + +#endif // AP_RANGEFINDER_LIGHTWARE_SERIAL_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp index a441e017b95..5e52a9a2223 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp @@ -14,6 +14,9 @@ */ #include "AP_RangeFinder_MAVLink.h" + +#if AP_RANGEFINDER_MAVLINK_ENABLED + #include /* @@ -73,3 +76,5 @@ void AP_RangeFinder_MAVLink::update(void) update_status(); } } + +#endif diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h b/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h index ba39e1f5aff..94a3e633732 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h @@ -3,6 +3,12 @@ #include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend.h" +#ifndef AP_RANGEFINDER_MAVLINK_ENABLED +#define AP_RANGEFINDER_MAVLINK_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_RANGEFINDER_MAVLINK_ENABLED + // Data timeout #define AP_RANGEFINDER_MAVLINK_TIMEOUT_MS 500 @@ -10,6 +16,7 @@ class AP_RangeFinder_MAVLink : public AP_RangeFinder_Backend { public: + // constructor using AP_RangeFinder_Backend::AP_RangeFinder_Backend; @@ -45,3 +52,5 @@ class AP_RangeFinder_MAVLink : public AP_RangeFinder_Backend MAV_DISTANCE_SENSOR sensor_type = MAV_DISTANCE_SENSOR_UNKNOWN; }; + +#endif diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp index 020c0e6e719..ed6e1d722fa 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp @@ -23,6 +23,8 @@ */ #include "AP_RangeFinder_MaxsonarI2CXL.h" +#if AP_RANGEFINDER_MAXSONARI2CXL_ENABLED + #include #include @@ -151,3 +153,5 @@ void AP_RangeFinder_MaxsonarI2CXL::update(void) set_status(RangeFinder::Status::NoData); } } + +#endif // AP_RANGEFINDER_MAXSONARI2CXL_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.h b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.h index 48bbf074244..7cae78c3267 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.h @@ -2,6 +2,13 @@ #include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend.h" + +#ifndef AP_RANGEFINDER_MAXSONARI2CXL_ENABLED +#define AP_RANGEFINDER_MAXSONARI2CXL_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_RANGEFINDER_MAXSONARI2CXL_ENABLED + #include #define AP_RANGE_FINDER_MAXSONARI2CXL_DEFAULT_ADDR 0x70 @@ -41,3 +48,5 @@ class AP_RangeFinder_MaxsonarI2CXL : public AP_RangeFinder_Backend bool get_reading(uint16_t &reading_cm); AP_HAL::OwnPtr _dev; }; + +#endif // AP_RANGEFINDER_MAXSONARI2CXL_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.cpp index e67ca9e7ce6..7f0173947c6 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.cpp @@ -17,6 +17,8 @@ #include "AP_RangeFinder_MaxsonarSerialLV.h" +#if AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED + #include #include @@ -68,3 +70,5 @@ bool AP_RangeFinder_MaxsonarSerialLV::get_reading(float &reading_m) return true; } + +#endif // AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.h b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.h index ddb6c502510..041d74c933f 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.h @@ -3,12 +3,22 @@ #include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend_Serial.h" +#ifndef AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED +#define AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED + class AP_RangeFinder_MaxsonarSerialLV : public AP_RangeFinder_Backend_Serial { public: - AP_RangeFinder_MaxsonarSerialLV(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params); + static AP_RangeFinder_Backend_Serial *create( + RangeFinder::RangeFinder_State &_state, + AP_RangeFinder_Params &_params) { + return new AP_RangeFinder_MaxsonarSerialLV(_state, _params); + } protected: @@ -17,6 +27,9 @@ class AP_RangeFinder_MaxsonarSerialLV : public AP_RangeFinder_Backend_Serial } private: + + AP_RangeFinder_MaxsonarSerialLV(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params); + // get a reading bool get_reading(float &reading_m) override; @@ -25,3 +38,5 @@ class AP_RangeFinder_MaxsonarSerialLV : public AP_RangeFinder_Backend_Serial char linebuf[10]; uint8_t linebuf_len = 0; }; + +#endif // AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_NMEA.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_NMEA.cpp index 02f5f18c545..61945ca7c3a 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_NMEA.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_NMEA.cpp @@ -15,6 +15,8 @@ #include "AP_RangeFinder_NMEA.h" +#if AP_RANGEFINDER_NMEA_ENABLED + #include #include @@ -187,3 +189,5 @@ bool AP_RangeFinder_NMEA::decode_latest_term() return false; } + +#endif // AP_RANGEFINDER_NMEA_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_NMEA.h b/libraries/AP_RangeFinder/AP_RangeFinder_NMEA.h index ccb12203208..8f9cf0406a4 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_NMEA.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_NMEA.h @@ -18,12 +18,22 @@ #include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend_Serial.h" +#ifndef AP_RANGEFINDER_NMEA_ENABLED +#define AP_RANGEFINDER_NMEA_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_RANGEFINDER_NMEA_ENABLED + class AP_RangeFinder_NMEA : public AP_RangeFinder_Backend_Serial { public: - using AP_RangeFinder_Backend_Serial::AP_RangeFinder_Backend_Serial; + static AP_RangeFinder_Backend_Serial *create( + RangeFinder::RangeFinder_State &_state, + AP_RangeFinder_Params &_params) { + return new AP_RangeFinder_NMEA(_state, _params); + } protected: @@ -33,6 +43,8 @@ class AP_RangeFinder_NMEA : public AP_RangeFinder_Backend_Serial private: + using AP_RangeFinder_Backend_Serial::AP_RangeFinder_Backend_Serial; + /// enum for handled messages enum sentence_types : uint8_t { SONAR_UNKNOWN = 0, @@ -72,3 +84,5 @@ class AP_RangeFinder_NMEA : public AP_RangeFinder_Backend_Serial sentence_types _sentence_type; // the sentence type currently being processed bool _sentence_done; // true if this sentence has already been decoded }; + +#endif // AP_RANGEFINDER_NMEA_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_PWM.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_PWM.cpp index c30c93c418e..97352b2d4a8 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_PWM.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_PWM.cpp @@ -15,6 +15,8 @@ #include "AP_RangeFinder_PWM.h" +#if AP_RANGEFINDER_PWM_ENABLED + #include #include @@ -29,6 +31,8 @@ AP_RangeFinder_PWM::AP_RangeFinder_PWM(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Backend(_state, _params), estimated_terrain_height(_estimated_terrain_height) { + // this gives one mm per us + params.scaling.set_default(1.0); } /* @@ -47,7 +51,8 @@ bool AP_RangeFinder_PWM::get_reading(float &reading_m) return false; } - reading_m = value_us * 10.0f; // correct for LidarLite. Parameter needed? Converts from decimetres -> m here + // LidarLite uses one mm per us + reading_m = value_us * 0.001 * params.scaling; return true; } @@ -127,3 +132,5 @@ void AP_RangeFinder_PWM::update(void) bool AP_RangeFinder_PWM::out_of_range(void) const { return params.powersave_range > 0 && estimated_terrain_height > params.powersave_range; } + +#endif // AP_RANGEFINDER_PWM_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_PWM.h b/libraries/AP_RangeFinder/AP_RangeFinder_PWM.h index 7e64a54ae38..597861d1d01 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_PWM.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_PWM.h @@ -17,6 +17,14 @@ #include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend.h" +#ifndef AP_RANGEFINDER_PWM_ENABLED +#define AP_RANGEFINDER_PWM_ENABLED \ + (CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && \ + AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) +#endif + +#if AP_RANGEFINDER_PWM_ENABLED + class AP_RangeFinder_PWM : public AP_RangeFinder_Backend { public: @@ -58,3 +66,5 @@ class AP_RangeFinder_PWM : public AP_RangeFinder_Backend bool was_out_of_range = -1; // this odd initialisation ensures we transition to new state }; + +#endif // AP_RANGEFINDER_PWM_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Params.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Params.cpp index d9d6bf17883..197305ebacb 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Params.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Params.cpp @@ -1,18 +1,27 @@ #include "AP_RangeFinder_Params.h" #include "AP_RangeFinder.h" +#ifndef AP_RANGEFINDER_DEFAULT_ORIENTATION +#ifndef HAL_BUILD_AP_PERIPH +#define AP_RANGEFINDER_DEFAULT_ORIENTATION ROTATION_PITCH_270 +#else +// AP_Periph expects ROTATION_NONE +#define AP_RANGEFINDER_DEFAULT_ORIENTATION ROTATION_NONE +#endif +#endif + // table of user settable parameters const AP_Param::GroupInfo AP_RangeFinder_Params::var_info[] = { // @Param: TYPE // @DisplayName: Rangefinder type // @Description: Type of connected rangefinder - // @Values: 0:None,1:Analog,2:MaxbotixI2C,3:LidarLite-I2C,5:PWM,6:BBB-PRU,7:LightWareI2C,8:LightWareSerial,9:Bebop,10:MAVLink,11:USD1_Serial,12:LeddarOne,13:MaxbotixSerial,14:TeraRangerI2C,15:LidarLiteV3-I2C,16:VL53L0X or VL53L1X,17:NMEA,18:WASP-LRF,19:BenewakeTF02,20:Benewake-Serial,21:LidarLightV3HP,22:PWM,23:BlueRoboticsPing,24:DroneCAN,25:BenewakeTFminiPlus-I2C,26:LanbaoPSK-CM8JL65-CC5,27:BenewakeTF03,28:VL53L1X-ShortRange,29:LeddarVu8-Serial,30:HC-SR04,31:GYUS42v2,32:MSP,33:USD1_CAN,34:Benewake_CAN,100:SITL + // @Values: 0:None,1:Analog,2:MaxbotixI2C,3:LidarLite-I2C,5:PWM,6:BBB-PRU,7:LightWareI2C,8:LightWareSerial,9:Bebop,10:MAVLink,11:USD1_Serial,12:LeddarOne,13:MaxbotixSerial,14:TeraRangerI2C,15:LidarLiteV3-I2C,16:VL53L0X or VL53L1X,17:NMEA,18:WASP-LRF,19:BenewakeTF02,20:Benewake-Serial,21:LidarLightV3HP,22:PWM,23:BlueRoboticsPing,24:DroneCAN,25:BenewakeTFminiPlus-I2C,26:LanbaoPSK-CM8JL65-CC5,27:BenewakeTF03,28:VL53L1X-ShortRange,29:LeddarVu8-Serial,30:HC-SR04,31:GYUS42v2,32:MSP,33:USD1_CAN,34:Benewake_CAN,35:TeraRangerSerial,100:SITL // @User: Standard AP_GROUPINFO_FLAGS("TYPE", 1, AP_RangeFinder_Params, type, 0, AP_PARAM_FLAG_ENABLE), // @Param: PIN // @DisplayName: Rangefinder pin - // @Description: Analog or PWM input pin that rangefinder is connected to. Airspeed ports can be used for Analog input, AUXOUT can be used for PWM input. When using analog pin 103, the maximum value of the input in 3.3V. + // @Description: Analog or PWM input pin that rangefinder is connected to. Airspeed ports can be used for Analog input, AUXOUT can be used for PWM input. When using analog pin 103, the maximum value of the input in 3.3V. For PWM input, the pin must be configured as a digital GPIO, see the Wiki's "GPIOs" section for details. // @Values: -1:Not Used,11:Pixracer,13:Pixhawk ADC4,14:Pixhawk ADC3,15:Pixhawk ADC6/Pixhawk2 ADC,50:AUX1,51:AUX2,52:AUX3,53:AUX4,54:AUX5,55:AUX6,103:Pixhawk SBUS // @User: Standard AP_GROUPINFO("PIN", 2, AP_RangeFinder_Params, pin, -1), @@ -58,7 +67,7 @@ const AP_Param::GroupInfo AP_RangeFinder_Params::var_info[] = { // @Param: STOP_PIN // @DisplayName: Rangefinder stop pin - // @Description: Digital pin that enables/disables rangefinder measurement for the pwm rangefinder. A value of -1 means no pin. If this is set, then the pin is set to 1 to enable the rangefinder and set to 0 to disable it. This is used to enable powersaving when out of range. + // @Description: Digital pin that enables/disables rangefinder measurement for the pwm rangefinder. A value of -1 means no pin. If this is set, then the pin is set to 1 to enable the rangefinder and set to 0 to disable it. This is used to enable powersaving when out of range. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot. // @Values: -1:Not Used,50:AUX1,51:AUX2,52:AUX3,53:AUX4,54:AUX5,55:AUX6,111:PX4 FMU Relay1,112:PX4 FMU Relay2,113:PX4IO Relay1,114:PX4IO Relay2,115:PX4IO ACC1,116:PX4IO ACC2 // @User: Standard AP_GROUPINFO("STOP_PIN", 8, AP_RangeFinder_Params, stop_pin, -1), @@ -127,7 +136,7 @@ const AP_Param::GroupInfo AP_RangeFinder_Params::var_info[] = { // @Description: Orientation of rangefinder // @Values: 0:Forward, 1:Forward-Right, 2:Right, 3:Back-Right, 4:Back, 5:Back-Left, 6:Left, 7:Forward-Left, 24:Up, 25:Down // @User: Advanced - AP_GROUPINFO("ORIENT", 53, AP_RangeFinder_Params, orientation, ROTATION_PITCH_270), + AP_GROUPINFO("ORIENT", 53, AP_RangeFinder_Params, orientation, AP_RANGEFINDER_DEFAULT_ORIENTATION), AP_GROUPEND }; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.cpp index 89009f6775e..608f2492efa 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.cpp @@ -14,6 +14,8 @@ */ #include "AP_RangeFinder_PulsedLightLRF.h" +#if AP_RANGEFINDER_PULSEDLIGHTLRF_ENABLED + #include #include @@ -218,3 +220,4 @@ bool AP_RangeFinder_PulsedLightLRF::init(void) return false; } +#endif // AP_RANGEFINDER_PULSEDLIGHTLRF_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.h b/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.h index 4a02a8a783c..8f6d40e2003 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.h @@ -2,6 +2,13 @@ #include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend.h" + +#ifndef AP_RANGEFINDER_PULSEDLIGHTLRF_ENABLED +#define AP_RANGEFINDER_PULSEDLIGHTLRF_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_RANGEFINDER_PULSEDLIGHTLRF_ENABLED + #include /* Connection diagram @@ -57,3 +64,5 @@ class AP_RangeFinder_PulsedLightLRF : public AP_RangeFinder_Backend enum { PHASE_MEASURE, PHASE_COLLECT } phase; }; + +#endif // AP_RANGEFINDER_PULSEDLIGHTLRF_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_SITL.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_SITL.cpp index a2903a90a74..2e6e3613d88 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_SITL.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_SITL.cpp @@ -12,13 +12,11 @@ You should have received a copy of the GNU General Public License along with this program. If not, see . */ -#include - -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL - #include "AP_RangeFinder_SITL.h" -extern const AP_HAL::HAL& hal; +#if AP_RANGEFINDER_SIM_ENABLED + +#include /* constructor - registers instance at top RangeFinder driver @@ -49,4 +47,4 @@ void AP_RangeFinder_SITL::update(void) update_status(); } -#endif +#endif // AP_RANGEFINDER_SIM_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_SITL.h b/libraries/AP_RangeFinder/AP_RangeFinder_SITL.h index 13a1e238dc0..e11763a26f6 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_SITL.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_SITL.h @@ -14,9 +14,15 @@ */ #pragma once +#include + #include "AP_RangeFinder_Backend.h" -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#ifndef AP_RANGEFINDER_SIM_ENABLED +#define AP_RANGEFINDER_SIM_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) +#endif + +#if AP_RANGEFINDER_SIM_ENABLED #include @@ -41,4 +47,4 @@ class AP_RangeFinder_SITL : public AP_RangeFinder_Backend { }; -#endif +#endif // AP_RANGEFINDER_SIM_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp index 312e9fd97d8..c1772bfbad1 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp @@ -17,6 +17,8 @@ */ #include "AP_RangeFinder_TeraRangerI2C.h" +#if AP_RANGEFINDER_TRI2C_ENABLED + #include #include #include @@ -189,3 +191,5 @@ void AP_RangeFinder_TeraRangerI2C::update(void) set_status(RangeFinder::Status::NoData); } } + +#endif // AP_RANGEFINDER_TRI2C_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.h b/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.h index 2af3630ac42..09bdb5f0a7c 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.h @@ -2,6 +2,13 @@ #include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend.h" + +#ifndef AP_RANGEFINDER_TRI2C_ENABLED +#define AP_RANGEFINDER_TRI2C_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_RANGEFINDER_TRI2C_ENABLED + #include class AP_RangeFinder_TeraRangerI2C : public AP_RangeFinder_Backend @@ -40,3 +47,5 @@ class AP_RangeFinder_TeraRangerI2C : public AP_RangeFinder_Backend uint32_t count; } accum; }; + +#endif // AP_RANGEFINDER_TRI2C_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_TeraRanger_Serial.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_TeraRanger_Serial.cpp new file mode 100644 index 00000000000..e9a502de79e --- /dev/null +++ b/libraries/AP_RangeFinder/AP_RangeFinder_TeraRanger_Serial.cpp @@ -0,0 +1,120 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +#include "AP_RangeFinder_TeraRanger_Serial.h" + +#if AP_RANGEFINDER_TERARANGER_SERIAL_ENABLED + + +#include +#include +#include +#include + +extern const AP_HAL::HAL& hal; + +#define FRAME_HEADER 0x54 +#define FRAME_LENGTH 5 +#define DIST_MAX_CM 3000 +#define OUT_OF_RANGE_ADD_CM 1000 +#define STATUS_MASK 0x1F +#define DISTANCE_ERROR 0x0001 + +// format of serial packets received from rangefinder +// +// Data Bit Definition Description +// ------------------------------------------------ +// byte 0 Frame header 0x54 +// byte 1 DIST_H Distance (in mm) high 8 bits +// byte 2 DIST_L Distance (in mm) low 8 bits +// byte 3 STATUS Status,Strengh,OverTemp +// byte 4 CRC8 packet CRC + +// distance returned in reading_m, set to true if sensor reports a good reading +bool AP_RangeFinder_TeraRanger_Serial::get_reading(float &reading_m) +{ + if (uart == nullptr) { + return false; + } + + float sum_mm = 0; + uint16_t count = 0; + uint16_t bad_read = 0; + + // read any available lines from the lidar + int16_t nbytes = uart->available(); + while (nbytes-- > 0) { + int16_t r = uart->read(); + if (r < 0) { + continue; + } + uint8_t c = (uint8_t)r; + // if buffer is empty and this byte is 0x57, add to buffer + if (linebuf_len == 0) { + if (c == FRAME_HEADER) { + linebuf[linebuf_len++] = c; + } + // buffer is not empty, add byte to buffer + } else { + // add character to buffer + linebuf[linebuf_len++] = c; + // if buffer now has 5 items try to decode it + if (linebuf_len == FRAME_LENGTH) { + // calculate CRC8 (tbd) + uint8_t crc = 0; + crc =crc_crc8(linebuf,FRAME_LENGTH-1); + // if crc matches, extract contents + if (crc == linebuf[FRAME_LENGTH-1]) { + // calculate distance + uint16_t dist = ((uint16_t)linebuf[1] << 8) | linebuf[2]; + if (dist >= DIST_MAX_CM *10) { + // this reading is out of range and a bad read + bad_read++; + } else { + // check if reading is good, no errors, no overtemp, reading is not the special case of 1mm + if ((STATUS_MASK & linebuf[3]) == 0 && (dist != DISTANCE_ERROR)) { + // add distance to sum + sum_mm += dist; + count++; + } else { + // this reading is bad + bad_read++; + } + } + } + // clear buffer + linebuf_len = 0; + } + } + } + + if (count > 0) { + // return average distance of readings since last update + reading_m = (sum_mm * 0.001f) / count; + return true; + } + + if (bad_read > 0) { + // if a bad read has occurred this update overwrite return with larger of + // driver defined maximum range for the model and user defined max range + 1m + reading_m = MAX(DIST_MAX_CM, max_distance_cm() + OUT_OF_RANGE_ADD_CM) * 0.01f; + return true; + } + + // no readings so return false + return false; +} + +#endif // AP_RANGEFINDER_TERARANGER_SERIAL_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_TeraRanger_Serial.h b/libraries/AP_RangeFinder/AP_RangeFinder_TeraRanger_Serial.h new file mode 100644 index 00000000000..6840849e07d --- /dev/null +++ b/libraries/AP_RangeFinder/AP_RangeFinder_TeraRanger_Serial.h @@ -0,0 +1,40 @@ +#pragma once + +#include "AP_RangeFinder.h" +#include "AP_RangeFinder_Backend_Serial.h" + +#ifndef AP_RANGEFINDER_TERARANGER_SERIAL_ENABLED +#define AP_RANGEFINDER_TERARANGER_SERIAL_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_RANGEFINDER_TERARANGER_SERIAL_ENABLED + +class AP_RangeFinder_TeraRanger_Serial : public AP_RangeFinder_Backend_Serial +{ + +public: + + static AP_RangeFinder_Backend_Serial *create( + RangeFinder::RangeFinder_State &_state, + AP_RangeFinder_Params &_params) { + return new AP_RangeFinder_TeraRanger_Serial(_state, _params); + } + +protected: + + using AP_RangeFinder_Backend_Serial::AP_RangeFinder_Backend_Serial; + + MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override { + return MAV_DISTANCE_SENSOR_LASER; + } + +private: + + // get a reading + // distance returned in reading_m + bool get_reading(float &reading_m) override; + + uint8_t linebuf[10]; + uint8_t linebuf_len; +}; +#endif // AP_RANGEFINDER_TERARANGER_SERIAL_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.cpp index 252e672058e..bf6f4e857d8 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.cpp @@ -1,9 +1,8 @@ -#include - -#if HAL_CANMANAGER_ENABLED - #include "AP_RangeFinder_UAVCAN.h" +#if AP_RANGEFINDER_UAVCAN_ENABLED + +#include #include #include @@ -173,5 +172,4 @@ void AP_RangeFinder_UAVCAN::handle_measurement(AP_UAVCAN* ap_uavcan, uint8_t nod } } -#endif // HAL_CANMANAGER_ENABLED - +#endif // AP_RANGEFINDER_UAVCAN_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.h b/libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.h index 2f48c260c88..5a928227448 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.h @@ -2,7 +2,12 @@ #include "AP_RangeFinder_Backend.h" -#if HAL_CANMANAGER_ENABLED +#ifndef AP_RANGEFINDER_UAVCAN_ENABLED +#define AP_RANGEFINDER_UAVCAN_ENABLED (HAL_CANMANAGER_ENABLED && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) +#endif + +#if AP_RANGEFINDER_UAVCAN_ENABLED + #include class MeasurementCb; @@ -34,4 +39,4 @@ class AP_RangeFinder_UAVCAN : public AP_RangeFinder_Backend { bool new_data; MAV_DISTANCE_SENSOR _sensor_type; }; -#endif //HAL_CANMANAGER_ENABLED +#endif // AP_RANGEFINDER_UAVCAN_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_USD1_CAN.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_USD1_CAN.cpp index dd74fda2ba0..4928a93e99e 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_USD1_CAN.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_USD1_CAN.cpp @@ -1,7 +1,8 @@ -#include #include "AP_RangeFinder_USD1_CAN.h" -#if HAL_MAX_CAN_PROTOCOL_DRIVERS +#if AP_RANGEFINDER_USD1_CAN_ENABLED + +#include /* constructor @@ -39,4 +40,4 @@ void AP_RangeFinder_USD1_CAN::handle_frame(AP_HAL::CANFrame &frame) _distance_count++; } -#endif // HAL_MAX_CAN_PROTOCOL_DRIVERS +#endif // AP_RANGEFINDER_USD1_CAN_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_USD1_CAN.h b/libraries/AP_RangeFinder/AP_RangeFinder_USD1_CAN.h index 761f72b8fdd..874e44ebeaf 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_USD1_CAN.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_USD1_CAN.h @@ -3,7 +3,11 @@ #include "AP_RangeFinder_Backend.h" #include -#if HAL_MAX_CAN_PROTOCOL_DRIVERS +#ifndef AP_RANGEFINDER_USD1_CAN_ENABLED +#define AP_RANGEFINDER_USD1_CAN_ENABLED (HAL_MAX_CAN_PROTOCOL_DRIVERS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) +#endif + +#if AP_RANGEFINDER_USD1_CAN_ENABLED class AP_RangeFinder_USD1_CAN : public CANSensor, public AP_RangeFinder_Backend { public: @@ -22,5 +26,5 @@ class AP_RangeFinder_USD1_CAN : public CANSensor, public AP_RangeFinder_Backend float _distance_sum; uint32_t _distance_count; }; -#endif //HAL_MAX_CAN_PROTOCOL_DRIVERS +#endif // AP_RANGEFINDER_USD1_CAN_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_USD1_Serial.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_USD1_Serial.cpp index 16dec00a9af..04d8c063298 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_USD1_Serial.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_USD1_Serial.cpp @@ -13,15 +13,15 @@ along with this program. If not, see . */ -#include #include "AP_RangeFinder_USD1_Serial.h" + +#if AP_RANGEFINDER_USD1_SERIAL_ENABLED + #include #define USD1_HDR 254 // Header Byte from USD1_Serial (0xFE) #define USD1_HDR_V0 72 // Header Byte for beta V0 of USD1_Serial (0x48) -extern const AP_HAL::HAL& hal; - /* detect USD1_Serial Firmware Version */ @@ -173,3 +173,5 @@ bool AP_RangeFinder_USD1_Serial::get_reading(float &reading_m) return true; } + +#endif // AP_RANGEFINDER_USD1_SERIAL_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_USD1_Serial.h b/libraries/AP_RangeFinder/AP_RangeFinder_USD1_Serial.h index 042ffba3a08..7fa2d2642c0 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_USD1_Serial.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_USD1_Serial.h @@ -3,12 +3,22 @@ #include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend_Serial.h" +#ifndef AP_RANGEFINDER_USD1_SERIAL_ENABLED +#define AP_RANGEFINDER_USD1_SERIAL_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_RANGEFINDER_USD1_SERIAL_ENABLED + class AP_RangeFinder_USD1_Serial : public AP_RangeFinder_Backend_Serial { public: - using AP_RangeFinder_Backend_Serial::AP_RangeFinder_Backend_Serial; + static AP_RangeFinder_Backend_Serial *create( + RangeFinder::RangeFinder_State &_state, + AP_RangeFinder_Params &_params) { + return new AP_RangeFinder_USD1_Serial(_state, _params); + } protected: @@ -25,6 +35,9 @@ class AP_RangeFinder_USD1_Serial : public AP_RangeFinder_Backend_Serial uint16_t tx_bufsize() const override { return 128; } private: + + using AP_RangeFinder_Backend_Serial::AP_RangeFinder_Backend_Serial; + // detect USD1_Serial Firmware Version bool detect_version(void); @@ -37,3 +50,5 @@ class AP_RangeFinder_USD1_Serial : public AP_RangeFinder_Backend_Serial uint8_t _header; uint8_t _version; }; + +#endif // AP_RANGEFINDER_USD1_SERIAL_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.cpp index 05b748f2fda..51c10dec8cd 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.cpp @@ -20,6 +20,8 @@ */ #include "AP_RangeFinder_VL53L0X.h" +#if AP_RANGEFINDER_VL53L0X_ENABLED + #include #include @@ -780,3 +782,5 @@ void AP_RangeFinder_VL53L0X::timer(void) counter++; } } + +#endif // AP_RANGEFINDER_VL53L0X_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.h b/libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.h index 1f0933dae4c..9ffa4f96e55 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.h @@ -4,6 +4,12 @@ #include "AP_RangeFinder_Backend.h" #include +#ifndef AP_RANGEFINDER_VL53L0X_ENABLED +#define AP_RANGEFINDER_VL53L0X_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_RANGEFINDER_VL53L0X_ENABLED + class AP_RangeFinder_VL53L0X : public AP_RangeFinder_Backend { @@ -80,3 +86,5 @@ class AP_RangeFinder_VL53L0X : public AP_RangeFinder_Backend uint32_t sum_mm; uint32_t counter; }; + +#endif // AP_RANGEFINDER_VL53L0X_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.cpp index 1b9df363447..e0eba359eee 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.cpp @@ -20,6 +20,8 @@ */ #include "AP_RangeFinder_VL53L1X.h" +#if AP_RANGEFINDER_VL53L1X_ENABLED + #include #include @@ -84,6 +86,11 @@ bool AP_RangeFinder_VL53L1X::check_id(void) } bool AP_RangeFinder_VL53L1X::reset(void) { + if (dev->get_bus_id()!=0x29) { + // if sensor is on a different port than the default do not reset sensor otherwise we will lose the addess. + // we assume it is already confirgured. + return true; + } if (!write_register(SOFT_RESET, 0x00)) { return false; } @@ -573,3 +580,5 @@ void AP_RangeFinder_VL53L1X::update(void) set_status(RangeFinder::Status::NoData); } } + +#endif // AP_RANGEFINDER_VL53L1X_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.h b/libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.h index 5cd6efe58e2..f073781d4ce 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.h @@ -2,6 +2,13 @@ #include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend.h" + +#ifndef AP_RANGEFINDER_VL53L1X_ENABLED +#define AP_RANGEFINDER_VL53L1X_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_RANGEFINDER_VL53L1X_ENABLED + #include class AP_RangeFinder_VL53L1X : public AP_RangeFinder_Backend @@ -1293,3 +1300,5 @@ class AP_RangeFinder_VL53L1X : public AP_RangeFinder_Backend uint32_t calcMacroPeriod(uint8_t vcsel_period) const; bool setupManualCalibration(void); }; + +#endif // AP_RANGEFINDER_VL53L1X_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Wasp.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Wasp.cpp index 36fed34a8a3..cda423c79b1 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Wasp.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Wasp.cpp @@ -15,6 +15,8 @@ #include "AP_RangeFinder_Wasp.h" +#if AP_RANGEFINDER_WASP_ENABLED + #include #include @@ -247,3 +249,4 @@ void AP_RangeFinder_Wasp::parse_response(void) { } } +#endif // AP_RANGEFINDER_WASP_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Wasp.h b/libraries/AP_RangeFinder/AP_RangeFinder_Wasp.h index a58f779ff62..876e0cd41ad 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Wasp.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Wasp.h @@ -3,14 +3,24 @@ #include "AP_RangeFinder.h" #include "AP_RangeFinder_Backend_Serial.h" +#ifndef AP_RANGEFINDER_WASP_ENABLED +#define AP_RANGEFINDER_WASP_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_RANGEFINDER_WASP_ENABLED + // WASP 200 LRF // http://www.attolloengineering.com/wasp-200-lrf.html class AP_RangeFinder_Wasp : public AP_RangeFinder_Backend_Serial { public: - AP_RangeFinder_Wasp(RangeFinder::RangeFinder_State &_state, - AP_RangeFinder_Params &_params); + + static AP_RangeFinder_Backend_Serial *create( + RangeFinder::RangeFinder_State &_state, + AP_RangeFinder_Params &_params) { + return new AP_RangeFinder_Wasp(_state, _params); + } void update(void) override; @@ -29,6 +39,9 @@ class AP_RangeFinder_Wasp : public AP_RangeFinder_Backend_Serial { private: + AP_RangeFinder_Wasp(RangeFinder::RangeFinder_State &_state, + AP_RangeFinder_Params &_params); + enum wasp_configuration_stage { WASP_CFG_RATE, // set the baudrate WASP_CFG_ENCODING, // set the encoding to LBE @@ -59,3 +72,5 @@ class AP_RangeFinder_Wasp : public AP_RangeFinder_Backend_Serial { AP_Int16 thr; AP_Int8 baud; }; + +#endif diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_analog.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_analog.cpp index 33cd9156a05..b9ffb1f06c6 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_analog.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_analog.cpp @@ -18,12 +18,15 @@ * */ +#include "AP_RangeFinder_analog.h" + +#if AP_RANGEFINDER_ANALOG_ENABLED + #include #include #include #include "AP_RangeFinder.h" #include "AP_RangeFinder_Params.h" -#include "AP_RangeFinder_analog.h" extern const AP_HAL::HAL& hal; @@ -118,3 +121,4 @@ void AP_RangeFinder_analog::update(void) update_status(); } +#endif // AP_RANGEFINDER_ANALOG_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_analog.h b/libraries/AP_RangeFinder/AP_RangeFinder_analog.h index b102a2d3faa..052782a0dd4 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_analog.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_analog.h @@ -4,6 +4,12 @@ #include "AP_RangeFinder_Backend.h" #include "AP_RangeFinder_Params.h" +#ifndef AP_RANGEFINDER_ANALOG_ENABLED +#define AP_RANGEFINDER_ANALOG_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + +#if AP_RANGEFINDER_ANALOG_ENABLED + class AP_RangeFinder_analog : public AP_RangeFinder_Backend { public: @@ -28,3 +34,5 @@ class AP_RangeFinder_analog : public AP_RangeFinder_Backend AP_HAL::AnalogSource *source; }; + +#endif diff --git a/libraries/AP_RangeFinder/examples/RFIND_test/RFIND_test.cpp b/libraries/AP_RangeFinder/examples/RFIND_test/RFIND_test.cpp index 2cb6c5fb06a..a281962e1b4 100644 --- a/libraries/AP_RangeFinder/examples/RFIND_test/RFIND_test.cpp +++ b/libraries/AP_RangeFinder/examples/RFIND_test/RFIND_test.cpp @@ -4,6 +4,12 @@ #include #include +#include + +const struct AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { + AP_GROUPEND +}; +GCS_Dummy _gcs; void setup(); void loop(); diff --git a/libraries/AP_Relay/AP_Relay.cpp b/libraries/AP_Relay/AP_Relay.cpp index 5bb26299fe4..578ab4fdf59 100644 --- a/libraries/AP_Relay/AP_Relay.cpp +++ b/libraries/AP_Relay/AP_Relay.cpp @@ -7,6 +7,7 @@ #include #include "AP_Relay.h" +#include #if CONFIG_HAL_BOARD == HAL_BOARD_SITL #define RELAY1_PIN_DEFAULT 13 @@ -55,28 +56,28 @@ const AP_Param::GroupInfo AP_Relay::var_info[] = { // @Param: PIN // @DisplayName: First Relay Pin - // @Description: Digital pin number for first relay control. This is the pin used for camera control. + // @Description: Digital pin number for first relay control. This is the pin used for camera shutter control. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot. // @User: Standard // @Values: -1:Disabled,49:BB Blue GP0 pin 4,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6,57:BB Blue GP0 pin 3,113:BB Blue GP0 pin 6,116:BB Blue GP0 pin 5,27:BBBMini Pin P8.17,101:MainOut1,102:MainOut2,103:MainOut3,104:MainOut4,105:MainOut5,106:MainOut6,107:MainOut7,108:MainOut8 AP_GROUPINFO("PIN", 0, AP_Relay, _pin[0], RELAY1_PIN_DEFAULT), // @Param: PIN2 // @DisplayName: Second Relay Pin - // @Description: Digital pin number for 2nd relay control. + // @Description: Digital pin number for 2nd relay control. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot. // @User: Standard // @Values: -1:Disabled,49:BB Blue GP0 pin 4,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6,57:BB Blue GP0 pin 3,113:BB Blue GP0 pin 6,116:BB Blue GP0 pin 5,65:BBBMini Pin P8.18,101:MainOut1,102:MainOut2,103:MainOut3,104:MainOut4,105:MainOut5,106:MainOut6,107:MainOut7,108:MainOut8 AP_GROUPINFO("PIN2", 1, AP_Relay, _pin[1], RELAY2_PIN_DEFAULT), // @Param: PIN3 // @DisplayName: Third Relay Pin - // @Description: Digital pin number for 3rd relay control. + // @Description: Digital pin number for 3rd relay control. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot. // @User: Standard // @Values: -1:Disabled,49:BB Blue GP0 pin 4,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6,57:BB Blue GP0 pin 3,113:BB Blue GP0 pin 6,116:BB Blue GP0 pin 5,22:BBBMini Pin P8.19,101:MainOut1,102:MainOut2,103:MainOut3,104:MainOut4,105:MainOut5,106:MainOut6,107:MainOut7,108:MainOut8 AP_GROUPINFO("PIN3", 2, AP_Relay, _pin[2], RELAY3_PIN_DEFAULT), // @Param: PIN4 // @DisplayName: Fourth Relay Pin - // @Description: Digital pin number for 4th relay control. + // @Description: Digital pin number for 4th relay control. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot. // @User: Standard // @Values: -1:Disabled,49:BB Blue GP0 pin 4,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6,57:BB Blue GP0 pin 3,113:BB Blue GP0 pin 6,116:BB Blue GP0 pin 5,63:BBBMini Pin P8.34,101:MainOut1,102:MainOut2,103:MainOut3,104:MainOut4,105:MainOut5,106:MainOut6,107:MainOut7,108:MainOut8 AP_GROUPINFO("PIN4", 3, AP_Relay, _pin[3], RELAY4_PIN_DEFAULT), @@ -90,14 +91,14 @@ const AP_Param::GroupInfo AP_Relay::var_info[] = { // @Param: PIN5 // @DisplayName: Fifth Relay Pin - // @Description: Digital pin number for 5th relay control. + // @Description: Digital pin number for 5th relay control. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot. // @User: Standard // @Values: -1:Disabled,49:BB Blue GP0 pin 4,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6,57:BB Blue GP0 pin 3,113:BB Blue GP0 pin 6,116:BB Blue GP0 pin 5,62:BBBMini Pin P8.13,101:MainOut1,102:MainOut2,103:MainOut3,104:MainOut4,105:MainOut5,106:MainOut6,107:MainOut7,108:MainOut8 AP_GROUPINFO("PIN5", 5, AP_Relay, _pin[4], RELAY5_PIN_DEFAULT), // @Param: PIN6 // @DisplayName: Sixth Relay Pin - // @Description: Digital pin number for 6th relay control. + // @Description: Digital pin number for 6th relay control. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot. // @User: Standard // @Values: -1:Disabled,49:BB Blue GP0 pin 4,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6,57:BB Blue GP0 pin 3,113:BB Blue GP0 pin 6,116:BB Blue GP0 pin 5,37:BBBMini Pin P8.14,101:MainOut1,102:MainOut2,103:MainOut3,104:MainOut4,105:MainOut5,106:MainOut6,107:MainOut7,108:MainOut8 AP_GROUPINFO("PIN6", 6, AP_Relay, _pin[5], RELAY6_PIN_DEFAULT), @@ -140,6 +141,18 @@ void AP_Relay::set(const uint8_t instance, const bool value) if (_pin[instance] == -1) { return; } + const uint32_t now = AP_HAL::millis(); + _pin_states = value ? _pin_states | (1U< 10)) { + AP::logger().Write("RELY", "TimeUS,State", "s-", "F-", "QB", + AP_HAL::micros64(), + _pin_states); + _last_log_ms = now; + _last_logged_pin_states = _pin_states; + } +#if AP_SIM_ENABLED && (CONFIG_HAL_BOARD != HAL_BOARD_SITL) + return; +#endif hal.gpio->pinMode(_pin[instance], HAL_GPIO_OUTPUT); hal.gpio->write(_pin[instance], value); } @@ -156,8 +169,18 @@ void AP_Relay::toggle(uint8_t instance) bool AP_Relay::arming_checks(size_t buflen, char *buffer) const { for (uint8_t i=0; ivalid_pin(_pin[i])) { - hal.util->snprintf(buffer, buflen, "Relay[%u] pin %d invalid", i + 1, int(_pin[i].get())); + int8_t pin = _pin[i].get(); + if (pin != -1 && !hal.gpio->valid_pin(pin)) { + char param_name_buf[11] = "RELAY_PIN"; + if (i > 0) { + hal.util->snprintf(param_name_buf, ARRAY_SIZE(param_name_buf), "RELAY_PIN%u", unsigned(i+1)); + } + uint8_t servo_ch; + if (hal.gpio->pin_to_servo_channel(pin, servo_ch)) { + hal.util->snprintf(buffer, buflen, "%s=%d, set SERVO%u_FUNCTION=-1", param_name_buf, int(pin), unsigned(servo_ch+1)); + } else { + hal.util->snprintf(buffer, buflen, "%s=%d invalid", param_name_buf, int(pin)); + } return false; } } diff --git a/libraries/AP_Relay/AP_Relay.h b/libraries/AP_Relay/AP_Relay.h index a13748d9d51..18aad6e93b0 100644 --- a/libraries/AP_Relay/AP_Relay.h +++ b/libraries/AP_Relay/AP_Relay.h @@ -32,6 +32,11 @@ class AP_Relay { // de-activate the relay void off(uint8_t instance) { set(instance, false); } + // get state of relay + uint8_t get(uint8_t instance) const { + return instance < AP_RELAY_NUM_RELAYS ? _pin_states & (1U< #include #include #include -#include "AP_RobotisServo.h" - -#if NUM_SERVO_CHANNELS - extern const AP_HAL::HAL& hal; #define BROADCAST_ID 0xFE @@ -340,11 +340,11 @@ void AP_RobotisServo::process_packet(const uint8_t *pkt, uint8_t length) // easier return; } - uint16_t id_mask = (1U<<(id-1)); + uint32_t id_mask = (1U<<(id-1)); if (!(id_mask & servo_mask)) { // mark the servo as present servo_mask |= id_mask; - hal.console->printf("Robotis: new servo %u\n", id); + DEV_PRINTF("Robotis: new servo %u\n", id); } } @@ -406,4 +406,5 @@ void AP_RobotisServo::update() send_command(i+1, REG_GOAL_POSITION, value, 4); } } -#endif //NUM_SERVO_CHANNELS + +#endif // AP_ROBOTISSERVO_ENABLED diff --git a/libraries/AP_RobotisServo/AP_RobotisServo.h b/libraries/AP_RobotisServo/AP_RobotisServo.h index 39e10b31e1a..cd81cf5f9bd 100644 --- a/libraries/AP_RobotisServo/AP_RobotisServo.h +++ b/libraries/AP_RobotisServo/AP_RobotisServo.h @@ -18,6 +18,14 @@ #pragma once +#include + +#ifndef AP_ROBOTISSERVO_ENABLED +#define AP_ROBOTISSERVO_ENABLED (!HAL_MINIMIZE_FEATURES && BOARD_FLASH_SIZE > 1024) +#endif + +#if AP_ROBOTISSERVO_ENABLED + #include #include @@ -50,7 +58,7 @@ class AP_RobotisServo { void configure_servos(void); // auto-detected mask of available servos, from a broadcast ping - uint16_t servo_mask; + uint32_t servo_mask; uint8_t detection_count; uint8_t configured_servos; bool initialised; @@ -65,3 +73,5 @@ class AP_RobotisServo { uint32_t last_send_us; uint32_t delay_time_us; }; + +#endif // AP_ROBOTISSERVO_ENABLED diff --git a/libraries/AP_Scheduler/AP_Scheduler.cpp b/libraries/AP_Scheduler/AP_Scheduler.cpp index e5534e3edfb..68698b3d331 100644 --- a/libraries/AP_Scheduler/AP_Scheduler.cpp +++ b/libraries/AP_Scheduler/AP_Scheduler.cpp @@ -27,6 +27,7 @@ #include #include #include +#include #if CONFIG_HAL_BOARD == HAL_BOARD_SITL #include @@ -70,8 +71,7 @@ const AP_Param::GroupInfo AP_Scheduler::var_info[] = { }; // constructor -AP_Scheduler::AP_Scheduler(scheduler_fastloop_fn_t fastloop_fn) : - _fastloop_fn(fastloop_fn) +AP_Scheduler::AP_Scheduler() { if (_singleton) { #if CONFIG_HAL_BOARD == HAL_BOARD_SITL @@ -212,33 +212,37 @@ void AP_Scheduler::run(uint32_t time_available) common_tasks_offset++; } - const uint16_t dt = _tick_counter - _last_run[i]; - // we allow 0 to mean loop rate - uint32_t interval_ticks = (is_zero(task.rate_hz) ? 1 : _loop_rate_hz / task.rate_hz); - if (interval_ticks < 1) { - interval_ticks = 1; - } - if (dt < interval_ticks) { - // this task is not yet scheduled to run again - continue; - } - // this task is due to run. Do we have enough time to run it? - _task_time_allowed = task.max_time_micros; + if (task.priority > MAX_FAST_TASK_PRIORITIES) { + const uint16_t dt = _tick_counter - _last_run[i]; + // we allow 0 to mean loop rate + uint32_t interval_ticks = (is_zero(task.rate_hz) ? 1 : _loop_rate_hz / task.rate_hz); + if (interval_ticks < 1) { + interval_ticks = 1; + } + if (dt < interval_ticks) { + // this task is not yet scheduled to run again + continue; + } + // this task is due to run. Do we have enough time to run it? + _task_time_allowed = task.max_time_micros; - if (dt >= interval_ticks*2) { - perf_info.task_slipped(i); - } + if (dt >= interval_ticks*2) { + perf_info.task_slipped(i); + } - if (dt >= interval_ticks*max_task_slowdown) { - // we are going beyond the maximum slowdown factor for a - // task. This will trigger increasing the time budget - task_not_achieved++; - } + if (dt >= interval_ticks*max_task_slowdown) { + // we are going beyond the maximum slowdown factor for a + // task. This will trigger increasing the time budget + task_not_achieved++; + } - if (_task_time_allowed > time_available) { - // not enough time to run this task. Continue loop - - // maybe another task will fit into time remaining - continue; + if (_task_time_allowed > time_available) { + // not enough time to run this task. Continue loop - + // maybe another task will fit into time remaining + continue; + } + } else { + _task_time_allowed = get_loop_period_us(); } // run it @@ -271,10 +275,19 @@ void AP_Scheduler::run(uint32_t time_available) perf_info.update_task_info(i, time_taken, overrun); if (time_taken >= time_available) { + /* + we are out of time, but we need to keep walking the task + table in case there is another fast loop task after this + task, plus we need to update the accouting so we can + work out if we need to allocate extra time for the loop + (lower the loop rate) + Just set time_available to zero, which means we will + only run fast tasks after this one + */ time_available = 0; - break; + } else { + time_available -= time_taken; } - time_available -= time_taken; } // update number of spare microseconds @@ -304,6 +317,10 @@ uint16_t AP_Scheduler::time_available_usec(void) const */ float AP_Scheduler::load_average() { + // return 1 if filtered main loop rate is 5% below the configured rate + if (get_filtered_loop_rate_hz() < get_loop_rate_hz() * 0.95) { + return 1.0; + } if (_spare_ticks == 0) { return 0.0f; } @@ -330,14 +347,6 @@ void AP_Scheduler::loop() _last_loop_time_s = (sample_time_us - _loop_timer_start_us) * 1.0e-6; } - // Execute the fast loop - // --------------------- - if (_fastloop_fn) { - hal.util->persistent_data.scheduler_task = -2; - _fastloop_fn(); - hal.util->persistent_data.scheduler_task = -1; - } - #if CONFIG_HAL_BOARD == HAL_BOARD_SITL { /* @@ -368,8 +377,6 @@ void AP_Scheduler::loop() // add in extra loop time determined by not achieving scheduler tasks time_available += extra_loop_us; - // update the task info for the fast loop - perf_info.update_task_info(_num_tasks, loop_tick_us, loop_tick_us > loop_us); // run the tasks run(time_available); @@ -400,6 +407,10 @@ void AP_Scheduler::loop() perf_info.check_loop_time(sample_time_us - _loop_timer_start_us); _loop_timer_start_us = sample_time_us; + +#if AP_SIM_ENABLED && CONFIG_HAL_BOARD != HAL_BOARD_SITL + hal.simstate->update(); +#endif } void AP_Scheduler::update_logging() @@ -428,6 +439,7 @@ void AP_Scheduler::Log_Write_Performance() struct log_Performance pkt = { LOG_PACKET_HEADER_INIT(LOG_PERFORMANCE_MSG), time_us : AP_HAL::micros64(), + loop_rate : (uint16_t)(get_filtered_loop_rate_hz() + 0.5f), num_long_running : perf_info.get_num_long_running(), num_loops : perf_info.get_num_loops(), max_time : perf_info.get_max_time(), @@ -452,7 +464,7 @@ void AP_Scheduler::task_info(ExpandingString &str) // dynamically enable statistics collection if (!(_options & uint8_t(Options::RECORD_TASK_INFO))) { - _options |= uint8_t(Options::RECORD_TASK_INFO); + _options.set(_options | uint8_t(Options::RECORD_TASK_INFO)); return; } @@ -472,67 +484,41 @@ void AP_Scheduler::task_info(ExpandingString &str) uint8_t vehicle_tasks_offset = 0; uint8_t common_tasks_offset = 0; - for (uint8_t i = 0; i < _num_tasks + 1; i++) { - const AP::PerfInfo::TaskInfo* ti; + for (uint8_t i = 0; i < _num_tasks; i++) { + const AP::PerfInfo::TaskInfo* ti = perf_info.get_task_info(i); const char *task_name; - if (i == 0) { - // put the fast-loop entry at the top of the list - it's the last task in perf_info - ti = perf_info.get_task_info(_num_tasks); - task_name = "fast_loop"; - } else { - ti = perf_info.get_task_info(i - 1); - - // now find the task name: - - // determine which of the common task / vehicle task to run - bool run_vehicle_task = false; - if (vehicle_tasks_offset < _num_vehicle_tasks && - common_tasks_offset < _num_common_tasks) { - // still have entries on both lists; compare the - // priorities. In case of a tie the vehicle-specific - // entry wins. - const Task &vehicle_task = _vehicle_tasks[vehicle_tasks_offset]; - const Task &common_task = _common_tasks[common_tasks_offset]; - if (vehicle_task.priority <= common_task.priority) { - run_vehicle_task = true; - } - } else if (vehicle_tasks_offset < _num_vehicle_tasks) { - // out of common tasks to run - run_vehicle_task = true; - } else if (common_tasks_offset < _num_common_tasks) { - // out of vehicle tasks to run - run_vehicle_task = false; - } else { - // this is an error; the outside loop should have terminated - INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); - return; - } - if (run_vehicle_task) { - task_name = _vehicle_tasks[vehicle_tasks_offset++].name; - } else { - task_name = _common_tasks[common_tasks_offset++].name; + // determine which of the common task / vehicle task to run + bool run_vehicle_task = false; + if (vehicle_tasks_offset < _num_vehicle_tasks && + common_tasks_offset < _num_common_tasks) { + // still have entries on both lists; compare the + // priorities. In case of a tie the vehicle-specific + // entry wins. + const Task &vehicle_task = _vehicle_tasks[vehicle_tasks_offset]; + const Task &common_task = _common_tasks[common_tasks_offset]; + if (vehicle_task.priority <= common_task.priority) { + run_vehicle_task = true; } - // the loop counter i is adjusted here because we emit the - // fast-loop entry first but it appears last in the - // perf_info list + } else if (vehicle_tasks_offset < _num_vehicle_tasks) { + // out of common tasks to run + run_vehicle_task = true; + } else if (common_tasks_offset < _num_common_tasks) { + // out of vehicle tasks to run + run_vehicle_task = false; + } else { + // this is an error; the outside loop should have terminated + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + return; } - uint16_t avg = 0; - float pct = 0.0f; - if (ti != nullptr && ti->tick_count > 0) { - pct = ti->elapsed_time_us * 100.0f / total_time; - avg = MIN(uint16_t(ti->elapsed_time_us / ti->tick_count), 9999); + if (run_vehicle_task) { + task_name = _vehicle_tasks[vehicle_tasks_offset++].name; + } else { + task_name = _common_tasks[common_tasks_offset++].name; } -#if HAL_MINIMIZE_FEATURES - const char* fmt = "%-16.16s MIN=%4u MAX=%4u AVG=%4u OVR=%3u SLP=%3u, TOT=%4.1f%%\n"; -#else - const char* fmt = "%-32.32s MIN=%4u MAX=%4u AVG=%4u OVR=%3u SLP=%3u, TOT=%4.1f%%\n"; -#endif - str.printf(fmt, task_name, - unsigned(MIN(ti->min_time_us, 9999)), unsigned(MIN(ti->max_time_us, 9999)), unsigned(avg), - unsigned(MIN(ti->overrun_count, 999)), unsigned(MIN(ti->slip_count, 999)), pct); + ti->print(task_name, total_time, str); } } diff --git a/libraries/AP_Scheduler/AP_Scheduler.h b/libraries/AP_Scheduler/AP_Scheduler.h index 7d009ca05f3..f24e2340e23 100644 --- a/libraries/AP_Scheduler/AP_Scheduler.h +++ b/libraries/AP_Scheduler/AP_Scheduler.h @@ -20,20 +20,24 @@ */ #pragma once +#include + #ifndef HAL_SCHEDULER_ENABLED #define HAL_SCHEDULER_ENABLED 1 #endif #include +#include #include -#include #include #include "PerfInfo.h" // loop perf monitoring #if HAL_MINIMIZE_FEATURES #define AP_SCHEDULER_NAME_INITIALIZER(_clazz,_name) .name = #_name, +#define AP_FAST_NAME_INITIALIZER(_clazz,_name) .name = #_name "*", #else #define AP_SCHEDULER_NAME_INITIALIZER(_clazz,_name) .name = #_clazz "::" #_name, +#define AP_FAST_NAME_INITIALIZER(_clazz,_name) .name = #_clazz "::" #_name "*", #endif #define LOOP_RATE 0 @@ -48,6 +52,17 @@ .priority = _priority \ } +/* + useful macro for creating the fastloop task table + */ +#define FAST_TASK_CLASS(classname, classptr, func) { \ + .function = FUNCTOR_BIND(classptr, &classname::func, void),\ + AP_FAST_NAME_INITIALIZER(classname, func)\ + .rate_hz = 0,\ + .max_time_micros = 0,\ + .priority = AP_Scheduler::FAST_TASK_PRI0 \ +} + /* A task scheduler for APM main loops @@ -61,10 +76,7 @@ class AP_Scheduler { public: - - FUNCTOR_TYPEDEF(scheduler_fastloop_fn_t, void); - - AP_Scheduler(scheduler_fastloop_fn_t fastloop_fn = nullptr); + AP_Scheduler(); /* Do not allow copies */ AP_Scheduler(const AP_Scheduler &other) = delete; @@ -87,6 +99,13 @@ class AP_Scheduler RECORD_TASK_INFO = 1 << 0 }; + enum FastTaskPriorities { + FAST_TASK_PRI0 = 0, + FAST_TASK_PRI1 = 1, + FAST_TASK_PRI2 = 2, + MAX_FAST_TASK_PRIORITIES = 3 + }; + // initialise scheduler void init(const Task *tasks, uint8_t num_tasks, uint32_t log_performance_bit); @@ -144,10 +163,16 @@ class AP_Scheduler return _loop_period_s; } + // get the filtered main loop time in seconds float get_filtered_loop_time(void) const { return perf_info.get_filtered_time(); } + // get the filtered active main loop rate + float get_filtered_loop_rate_hz() { + return perf_info.get_filtered_loop_rate_hz(); + } + // get the time in seconds that the last loop took float get_last_loop_time_s(void) const { return _last_loop_time_s; @@ -168,9 +193,6 @@ class AP_Scheduler AP::PerfInfo perf_info; private: - // function that is called before anything in the scheduler table: - scheduler_fastloop_fn_t _fastloop_fn; - // used to enable scheduler debugging AP_Int8 _debug; diff --git a/libraries/AP_Scheduler/PerfInfo.cpp b/libraries/AP_Scheduler/PerfInfo.cpp index 56bdb9f035f..77962687b60 100644 --- a/libraries/AP_Scheduler/PerfInfo.cpp +++ b/libraries/AP_Scheduler/PerfInfo.cpp @@ -23,7 +23,7 @@ void AP::PerfInfo::reset() sigma_time = 0; sigmasquared_time = 0; if (_task_info != nullptr) { - memset(_task_info, 0, (_num_tasks + 1) * sizeof(TaskInfo)); + memset(_task_info, 0, (_num_tasks) * sizeof(TaskInfo)); } } @@ -36,9 +36,9 @@ void AP::PerfInfo::ignore_this_loop() // allocate the array of task statistics for use by @SYS/tasks.txt void AP::PerfInfo::allocate_task_info(uint8_t num_tasks) { - _task_info = new TaskInfo[num_tasks + 1]; // add an extra slot for the fast_loop + _task_info = new TaskInfo[num_tasks]; if (_task_info == nullptr) { - hal.console->printf("Unable to allocate scheduler TaskInfo\n"); + DEV_PRINTF("Unable to allocate scheduler TaskInfo\n"); _num_tasks = 0; return; } @@ -59,22 +59,45 @@ void AP::PerfInfo::update_task_info(uint8_t task_index, uint16_t task_time_us, b return; } - if (task_index > _num_tasks) { + if (task_index >= _num_tasks) { INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); return; } TaskInfo& ti = _task_info[task_index]; - ti.max_time_us = MAX(ti.max_time_us, task_time_us); - if (ti.min_time_us == 0) { - ti.min_time_us = task_time_us; + ti.update(task_time_us, overrun); +} + +void AP::PerfInfo::TaskInfo::update(uint16_t task_time_us, bool overrun) +{ + max_time_us = MAX(max_time_us, task_time_us); + if (min_time_us == 0) { + min_time_us = task_time_us; } else { - ti.min_time_us = MIN(ti.min_time_us, task_time_us); + min_time_us = MIN(min_time_us, task_time_us); } - ti.elapsed_time_us += task_time_us; - ti.tick_count++; + elapsed_time_us += task_time_us; + tick_count++; if (overrun) { - ti.overrun_count++; + overrun_count++; + } +} + +void AP::PerfInfo::TaskInfo::print(const char* task_name, uint32_t total_time, ExpandingString& str) const +{ + uint16_t avg = 0; + float pct = 0.0f; + if (tick_count > 0) { + pct = elapsed_time_us * 100.0f / total_time; + avg = MIN(uint16_t(elapsed_time_us / tick_count), 9999); } +#if HAL_MINIMIZE_FEATURES + const char* fmt = "%-16.16s MIN=%4u MAX=%4u AVG=%4u OVR=%3u SLP=%3u, TOT=%4.1f%%\n"; +#else + const char* fmt = "%-32.32s MIN=%4u MAX=%4u AVG=%4u OVR=%3u SLP=%3u, TOT=%4.1f%%\n"; +#endif + str.printf(fmt, task_name, + unsigned(MIN(min_time_us, 9999)), unsigned(MIN(max_time_us, 9999)), unsigned(avg), + unsigned(MIN(overrun_count, 999)), unsigned(MIN(slip_count, 999)), pct); } // check_loop_time - check latest loop time vs min, max and overtime threshold @@ -160,6 +183,17 @@ float AP::PerfInfo::get_filtered_time() const return filtered_loop_time; } +// return low pass filtered loop rate in hz +float AP::PerfInfo::get_filtered_loop_rate_hz() const +{ + const float filt_time_s = get_filtered_time(); + if (filt_time_s <= 0) { + return loop_rate_hz; + } + return 1.0 / filt_time_s; +} + + void AP::PerfInfo::update_logging() const { gcs().send_text(MAV_SEVERITY_INFO, @@ -168,7 +202,7 @@ void AP::PerfInfo::update_logging() const (unsigned)get_num_loops(), (unsigned long)get_max_time(), (unsigned long)get_min_time(), - (unsigned)(0.5+(1.0f/get_filtered_time())), + (unsigned)(0.5+get_filtered_loop_rate_hz()), (unsigned long)get_stddev_time(), (unsigned long)AP::scheduler().get_extra_loop_us()); } diff --git a/libraries/AP_Scheduler/PerfInfo.h b/libraries/AP_Scheduler/PerfInfo.h index b763d842284..d8c08db6c23 100644 --- a/libraries/AP_Scheduler/PerfInfo.h +++ b/libraries/AP_Scheduler/PerfInfo.h @@ -1,6 +1,7 @@ #pragma once #include +#include namespace AP { @@ -16,6 +17,9 @@ class PerfInfo { uint32_t tick_count; uint16_t slip_count; uint16_t overrun_count; + + void update(uint16_t task_time_us, bool overrun); + void print(const char* task_name, uint32_t total_time, ExpandingString& str) const; }; /* Do not allow copies */ @@ -32,6 +36,7 @@ class PerfInfo { uint32_t get_avg_time() const; uint32_t get_stddev_time() const; float get_filtered_time() const; + float get_filtered_loop_rate_hz() const; void set_loop_rate(uint16_t rate_hz); void update_logging() const; @@ -43,13 +48,13 @@ class PerfInfo { bool has_task_info() { return _task_info != nullptr; } // return a task info const TaskInfo* get_task_info(uint8_t task_index) const { - return (_task_info && task_index <= _num_tasks) ? &_task_info[task_index] : nullptr; + return (_task_info && task_index < _num_tasks) ? &_task_info[task_index] : nullptr; } // called after each run of a task to update its statistics based on measurements taken by the scheduler void update_task_info(uint8_t task_index, uint16_t task_time_us, bool overrun); // record that a task slipped void task_slipped(uint8_t task_index) { - if (_task_info && task_index <= _num_tasks) { + if (_task_info && task_index < _num_tasks) { _task_info[task_index].overrun_count++; } } diff --git a/libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp b/libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp index 736ecbfed45..04754e651a7 100644 --- a/libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp +++ b/libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp @@ -8,6 +8,12 @@ #include #include #include +#include + +const struct AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { + AP_GROUPEND +}; +GCS_Dummy _gcs; const AP_HAL::HAL& hal = AP_HAL::get_HAL(); @@ -25,7 +31,7 @@ class SchedTest { #if HAL_EXTERNAL_AHRS_ENABLED AP_ExternalAHRS eAHRS; #endif // HAL_EXTERNAL_AHRS_ENABLED - AP_Scheduler scheduler{nullptr}; + AP_Scheduler scheduler; uint32_t ins_counter; static const AP_Scheduler::Task scheduler_tasks[]; diff --git a/libraries/AP_Scripting/AP_Scripting.cpp b/libraries/AP_Scripting/AP_Scripting.cpp index 256a66091fa..ff1e1e052c9 100644 --- a/libraries/AP_Scripting/AP_Scripting.cpp +++ b/libraries/AP_Scripting/AP_Scripting.cpp @@ -33,8 +33,8 @@ #endif // !defined(SCRIPTING_STACK_MAX_SIZE) #if !defined(SCRIPTING_HEAP_SIZE) - #if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX - #define SCRIPTING_HEAP_SIZE (64 * 1024) + #if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX || HAL_MEM_CLASS >= HAL_MEM_CLASS_500 + #define SCRIPTING_HEAP_SIZE (100 * 1024) #else #define SCRIPTING_HEAP_SIZE (43 * 1024) #endif @@ -78,7 +78,7 @@ const AP_Param::GroupInfo AP_Scripting::var_info[] = { // @Param: DEBUG_OPTS // @DisplayName: Scripting Debug Level // @Description: Debugging options - // @Bitmask: 0:No Scripts to run message if all scripts have stopped, 1:Runtime messages for memory usage and execution time, 2:Suppress logging scripts to dataflash, 3:log runtime memory usage and execution time + // @Bitmask: 0:No Scripts to run message if all scripts have stopped, 1:Runtime messages for memory usage and execution time, 2:Suppress logging scripts to dataflash, 3:log runtime memory usage and execution time, 4:Disable pre-arm check // @User: Advanced AP_GROUPINFO("DEBUG_OPTS", 4, AP_Scripting, _debug_options, 0), @@ -148,15 +148,14 @@ void AP_Scripting::init(void) { const char *dir_name = SCRIPTING_DIRECTORY; if (AP::FS().mkdir(dir_name)) { if (errno != EEXIST) { - gcs().send_text(MAV_SEVERITY_INFO, "Lua: failed to create (%s)", dir_name); + gcs().send_text(MAV_SEVERITY_INFO, "Scripting: failed to create (%s)", dir_name); } } if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Scripting::thread, void), "Scripting", SCRIPTING_STACK_SIZE, AP_HAL::Scheduler::PRIORITY_SCRIPTING, 0)) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "Could not create scripting stack (%d)", SCRIPTING_STACK_SIZE); - gcs().send_text(MAV_SEVERITY_ERROR, "Scripting failed to start"); - _init_failed = true; + gcs().send_text(MAV_SEVERITY_ERROR, "Scripting: %s", "failed to start"); + _thread_failed = true; } } @@ -192,7 +191,7 @@ bool AP_Scripting::repl_start(void) { if ((AP::FS().stat(REPL_DIRECTORY, &st) == -1) && (AP::FS().unlink(REPL_DIRECTORY) == -1) && (errno != EEXIST)) { - gcs().send_text(MAV_SEVERITY_INFO, "Unable to delete old REPL %s", strerror(errno)); + gcs().send_text(MAV_SEVERITY_INFO, "Scripting: Unable to delete old REPL %s", strerror(errno)); } // create a new folder @@ -204,7 +203,7 @@ bool AP_Scripting::repl_start(void) { // make the output pointer terminal.output_fd = AP::FS().open(REPL_OUT, O_WRONLY|O_CREAT|O_TRUNC); if (terminal.output_fd == -1) { - gcs().send_text(MAV_SEVERITY_INFO, "Unable to make new REPL"); + gcs().send_text(MAV_SEVERITY_INFO, "Scripting: %s", "Unable to make new REPL"); return false; } @@ -217,24 +216,42 @@ void AP_Scripting::repl_stop(void) { // can't do any more cleanup here, closing the open FD's is the REPL's responsibility } +/* + avoid optimisation of the thread function. This avoids nasty traps + where setjmp/longjmp does not properly handle save/restore of + floating point registers on exceptions. This is an extra protection + over the top of the fix in luaD_rawrunprotected() for the same issue + */ +#pragma GCC push_options +#pragma GCC optimize ("O0") + void AP_Scripting::thread(void) { while (true) { // reset flags _stop = false; _restart = false; + _init_failed = false; lua_scripts *lua = new lua_scripts(_script_vm_exec_count, _script_heap_size, _debug_options, terminal); if (lua == nullptr || !lua->heap_allocated()) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "Unable to allocate scripting memory"); + gcs().send_text(MAV_SEVERITY_CRITICAL, "Scripting: %s", "Unable to allocate memory"); _init_failed = true; } else { // run won't return while scripting is still active lua->run(); // only reachable if the lua backend has died for any reason - gcs().send_text(MAV_SEVERITY_CRITICAL, "Scripting has stopped"); + gcs().send_text(MAV_SEVERITY_CRITICAL, "Scripting: %s", "stopped"); } delete lua; + lua = nullptr; + + // clear allocated i2c devices + for (uint8_t i=0; i(mission_cmd_queue_size); + if (mission_data != nullptr && mission_data->get_size() == 0) { + delete mission_data; + mission_data = nullptr; + } if (mission_data == nullptr) { - gcs().send_text(MAV_SEVERITY_INFO, "scripting: unable to receive mission command"); + gcs().send_text(MAV_SEVERITY_INFO, "Scripting: %s", "unable to receive mission command"); return; } } @@ -281,6 +303,34 @@ void AP_Scripting::handle_mission_command(const AP_Mission::Mission_Command& cmd mission_data->push(cmd); } +bool AP_Scripting::arming_checks(size_t buflen, char *buffer) const +{ + if (!enabled() || ((_debug_options.get() & uint8_t(lua_scripts::DebugLevel::DISABLE_PRE_ARM)) != 0)) { + return true; + } + + if (_thread_failed) { + hal.util->snprintf(buffer, buflen, "Scripting: %s", "failed to start"); + return false; + } + + if (_init_failed) { + hal.util->snprintf(buffer, buflen, "Scripting: %s", "out of memory"); + return false; + } + + lua_scripts::get_last_error_semaphore()->take_blocking(); + const char *error_buf = lua_scripts::get_last_error_message(); + if (error_buf != nullptr) { + hal.util->snprintf(buffer, buflen, "Scripting: %s", error_buf); + lua_scripts::get_last_error_semaphore()->give(); + return false; + } + lua_scripts::get_last_error_semaphore()->give(); + + return true; +} + AP_Scripting *AP_Scripting::_singleton = nullptr; namespace AP { diff --git a/libraries/AP_Scripting/AP_Scripting.h b/libraries/AP_Scripting/AP_Scripting.h index 943fd0a0fbc..1befe3b3ace 100644 --- a/libraries/AP_Scripting/AP_Scripting.h +++ b/libraries/AP_Scripting/AP_Scripting.h @@ -18,7 +18,8 @@ #include #include -#include +#include +#include #include #include #include "AP_Scripting_CANSensor.h" @@ -37,7 +38,6 @@ class AP_Scripting AP_Scripting &operator=(const AP_Scripting&) = delete; void init(void); - bool init_failed(void) const { return _init_failed; } bool enabled(void) const { return _enable != 0; }; bool should_run(void) const { return enabled() && !_stop; } @@ -48,7 +48,9 @@ class AP_Scripting MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet); - void handle_mission_command(const AP_Mission::Mission_Command& cmd); + void handle_mission_command(const class AP_Mission::Mission_Command& cmd); + + bool arming_checks(size_t buflen, char *buffer) const; // User parameters for inputs into scripts AP_Float _user[6]; @@ -72,6 +74,7 @@ class AP_Scripting #if HAL_MAX_CAN_PROTOCOL_DRIVERS // Scripting CAN sensor ScriptingCANSensor *_CAN_dev; + ScriptingCANSensor *_CAN_dev2; #endif // mission item buffer @@ -100,6 +103,7 @@ class AP_Scripting AP_Int8 _debug_options; AP_Int16 _dir_disable; + bool _thread_failed; // thread allocation failed bool _init_failed; // true if memory allocation failed bool _restart; // true if scripts should be restarted bool _stop; // true if scripts should be stopped diff --git a/libraries/AP_Scripting/AP_Scripting_CANSensor.h b/libraries/AP_Scripting/AP_Scripting_CANSensor.h index ccb9d5ce111..400eb97ceed 100644 --- a/libraries/AP_Scripting/AP_Scripting_CANSensor.h +++ b/libraries/AP_Scripting/AP_Scripting_CANSensor.h @@ -25,8 +25,9 @@ class ScriptingCANBuffer; class ScriptingCANSensor : public CANSensor { public: - ScriptingCANSensor():CANSensor("Script") { - register_driver(AP_CANManager::Driver_Type::Driver_Type_Scripting); + ScriptingCANSensor(AP_CANManager::Driver_Type dtype) + : CANSensor("Script") { + register_driver(dtype); } // handler for outgoing frames, using uint32 diff --git a/libraries/AP_Scripting/applets/QuadPlane_Low_Alt_FW_mode_prevention.lua b/libraries/AP_Scripting/applets/QuadPlane_Low_Alt_FW_mode_prevention.lua new file mode 100644 index 00000000000..f2d40b1251d --- /dev/null +++ b/libraries/AP_Scripting/applets/QuadPlane_Low_Alt_FW_mode_prevention.lua @@ -0,0 +1,136 @@ +-- This is a script overrides a forward flight mode at low altitude and within radius of home +-- configured with Q_LOW_ALT_* params + +-- maker sure on a quadplane +assert(quadplane, "Quadplane not setup") + +-- add new params +local PARAM_TABLE_KEY = 76 +assert(param:add_table(PARAM_TABLE_KEY, "Q_LOW_ALT_", 3), "could not add param table") +assert(param:add_param(PARAM_TABLE_KEY, 1, "ENABLE", 0), "could not add param") -- enable low alt mode change, 1: Switch to QLAND, 2: Switch back to previous mode +assert(param:add_param(PARAM_TABLE_KEY, 2, "ALT", 15), "could not add param") -- threshold altitude +assert(param:add_param(PARAM_TABLE_KEY, 3, "RADIUS", 50), "could not add param") -- threshold radius + +local enabled = Parameter() +local alt = Parameter() +local radius = Parameter() + +assert(enabled:init("Q_LOW_ALT_ENABLE"), "could not find param") +assert(alt:init("Q_LOW_ALT_ALT"), "could not find param") +assert(radius:init("Q_LOW_ALT_RADIUS"), "could not find param") + +-- all plane mode numbers +local MODE_MANUAL = 0 +local MODE_CIRCLE = 1 +local MODE_STABILIZE = 2 +local MODE_TRAINING = 3 +local MODE_ACRO = 4 +local MODE_FLY_BY_WIRE_A = 5 +local MODE_FLY_BY_WIRE_B = 6 +local MODE_CRUISE = 7 +local MODE_AUTOTUNE = 8 +local MODE_AUTO = 10 +local MODE_RTL = 11 +local MODE_LOITER = 12 +local MODE_TAKEOFF = 13 +local MODE_AVOID_ADSB = 14 +local MODE_GUIDED = 15 +local MODE_INITIALISING = 16 +local MODE_QSTABILIZE = 17 +local MODE_QHOVER = 18 +local MODE_QLOITER = 19 +local MODE_QLAND = 20 +local MODE_QRTL = 21 +local MODE_QAUTOTUNE = 22 +local MODE_QACRO = 23 +local MODE_THERMAL = 24 +local MODE_LOITER_ALT_QLAND = 25 + +local FS_enabled_in_mode = {} + +-- enable in all FW modes except auto and guided +FS_enabled_in_mode[MODE_MANUAL] = true +FS_enabled_in_mode[MODE_CIRCLE] = true +FS_enabled_in_mode[MODE_STABILIZE] = true +FS_enabled_in_mode[MODE_TRAINING] = true +FS_enabled_in_mode[MODE_ACRO] = true +FS_enabled_in_mode[MODE_FLY_BY_WIRE_A] = true +FS_enabled_in_mode[MODE_FLY_BY_WIRE_B] = true +FS_enabled_in_mode[MODE_CRUISE] = true +FS_enabled_in_mode[MODE_AUTOTUNE] = true +FS_enabled_in_mode[MODE_AUTO] = false +FS_enabled_in_mode[MODE_RTL] = true +FS_enabled_in_mode[MODE_LOITER] = true +FS_enabled_in_mode[MODE_TAKEOFF] = true +FS_enabled_in_mode[MODE_AVOID_ADSB] = true +FS_enabled_in_mode[MODE_GUIDED] = false +FS_enabled_in_mode[MODE_INITIALISING] = true +FS_enabled_in_mode[MODE_QSTABILIZE] = false +FS_enabled_in_mode[MODE_QHOVER] = false +FS_enabled_in_mode[MODE_QLOITER] = false +FS_enabled_in_mode[MODE_QLAND] = false +FS_enabled_in_mode[MODE_QRTL] = false +FS_enabled_in_mode[MODE_QAUTOTUNE] = false +FS_enabled_in_mode[MODE_QACRO] = false +FS_enabled_in_mode[MODE_THERMAL] = true +FS_enabled_in_mode[MODE_LOITER_ALT_QLAND] = true + +local last_mode = vehicle:get_mode() +function update() + + local mode = vehicle:get_mode() + local previous_mode = last_mode + if mode == last_mode then + -- no mode change + return update, 100 + end + last_mode = mode + + if enabled:get() <= 0 or not arming:is_armed() then + -- not enabled or not armed + return update, 100 + end + + if not FS_enabled_in_mode[mode] then + -- not enabled in this mode + return update, 100 + end + + if FS_enabled_in_mode[previous_mode] then + -- fail safe is enabled in this mode, but it was also enabled in the last mode + -- Don't stop switch from one FW flight mode to another + return update, 100 + end + + local pos = ahrs:get_relative_position_NED_home() + if not pos then + -- no position + return update, 100 + end + + if pos:xy():length() > radius:get() or -pos:z() > alt:get() then + -- outside threshold radius or above altitude + return update, 100 + end + + -- Enabled, armed and in enabled mode, switching out of disabled mode + -- Within radius and below altitude threshold + -- switch to Qland or back to previous mode + + local new_mode = MODE_QLAND + if enabled:get() == 2 then + new_mode = previous_mode + gcs:send_text(5, 'Too low for fixedwing flight') + else + gcs:send_text(5, 'Too low for fixedwing flight, mode set to QLand') + end + + vehicle:set_mode(new_mode) + + -- update last mode to prevent trigger on this mode change + last_mode = new_mode + + return update, 100 +end + +return update() diff --git a/libraries/AP_Scripting/applets/QuadPlane_Low_Alt_FW_mode_prevention.md b/libraries/AP_Scripting/applets/QuadPlane_Low_Alt_FW_mode_prevention.md new file mode 100644 index 00000000000..83858087fec --- /dev/null +++ b/libraries/AP_Scripting/applets/QuadPlane_Low_Alt_FW_mode_prevention.md @@ -0,0 +1,11 @@ +# Quadplane low altitude forward flight mode prevention + +This script prevents inadvertent switching into a fixed wing flight mode at low altitude. Its behaviour is controlled by Q_LOW_ALT_* parameters. + +- Q_LOW_ALT_ENABLE: Enable script. 1: switch to Qland instead of fixed wing mode. 2: Switch back to previous mode instead of fixed wing mode. + +- Q_LOW_ALT_ALT: Altitude threshold in meters above home. If vehicle is above this altitude the script will not take action + +- Q_LOT_ALT_RADIUS: Radius threshold in meters from home. If vehicle is outside this radius the script wil not take action + +Note: vehicle is always allowed to switch into auto mode or guided mode. diff --git a/libraries/AP_Scripting/applets/VTOL-quicktune.lua b/libraries/AP_Scripting/applets/VTOL-quicktune.lua new file mode 100644 index 00000000000..d37e9af03fd --- /dev/null +++ b/libraries/AP_Scripting/applets/VTOL-quicktune.lua @@ -0,0 +1,496 @@ +--[[ + fast tuning of VTOL gains for multirotors and quadplanes + + This should be used in QLOITER mode for quadplanes and LOITER mode + for copters, although it will work in other VTOL modes + +--]] + +--[[ + - TODO: + - disable weathervaning while tuning? + - possibly lower P XY gains during tuning? + - bail out on a large angle error? +--]] + +local MAV_SEVERITY_INFO = 6 +local MAV_SEVERITY_NOTICE = 5 +local MAV_SEVERITY_EMERGENCY = 0 + +local PARAM_TABLE_KEY = 8 +local PARAM_TABLE_PREFIX = "QUIK_" + +local is_quadplane = false +local atc_prefix = "ATC" + +-- bind a parameter to a variable +function bind_param(name) + local p = Parameter() + assert(p:init(name), string.format('could not find %s parameter', name)) + return p +end + +-- add a parameter and bind it to a variable +function bind_add_param(name, idx, default_value) + assert(param:add_param(PARAM_TABLE_KEY, idx, name, default_value), string.format('could not add param %s', name)) + return bind_param(PARAM_TABLE_PREFIX .. name) +end + +-- setup quicktune specific parameters +assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 12), 'could not add param table') + +local QUIK_ENABLE = bind_add_param('ENABLE', 1, 0) +local QUIK_AXES = bind_add_param('AXES', 2, 7) +local QUIK_DOUBLE_TIME = bind_add_param('DOUBLE_TIME', 3, 10) +local QUIK_GAIN_MARGIN = bind_add_param('GAIN_MARGIN', 4, 60) +local QUIK_OSC_SMAX = bind_add_param('OSC_SMAX', 5, 5) +local QUIK_YAW_P_MAX = bind_add_param('YAW_P_MAX', 6, 0.5) +local QUIK_YAW_D_MAX = bind_add_param('YAW_D_MAX', 7, 0.01) +local QUIK_RP_PI_RATIO = bind_add_param('RP_PI_RATIO', 8, 1.0) +local QUIK_Y_PI_RATIO = bind_add_param('Y_PI_RATIO', 9, 10) +local QUIK_AUTO_FILTER = bind_add_param('AUTO_FILTER', 10, 1) +local QUIK_AUTO_SAVE = bind_add_param('AUTO_SAVE', 11, 0) +local QUIK_RC_FUNC = bind_add_param('RC_FUNC', 12, 300) + +local INS_GYRO_FILTER = bind_param("INS_GYRO_FILTER") + +local RCMAP_ROLL = bind_param("RCMAP_ROLL") +local RCMAP_PITCH = bind_param("RCMAP_PITCH") +local RCMAP_YAW = bind_param("RCMAP_YAW") + +local RCIN_ROLL = rc:get_channel(RCMAP_ROLL:get()) +local RCIN_PITCH = rc:get_channel(RCMAP_PITCH:get()) +local RCIN_YAW = rc:get_channel(RCMAP_YAW:get()) + +local UPDATE_RATE_HZ = 40 +local STAGE_DELAY = 4.0 +local PILOT_INPUT_DELAY = 4.0 + +local YAW_FLTE_MAX = 2.0 +local FLTD_MUL = 0.5 +local FLTT_MUL = 0.5 + +-- SMAX to set if none set at start +local DEFAULT_SMAX = 50.0 + +-- work out vehicle type +if param:get("Q_A_RAT_RLL_SMAX") then + is_quadplane = true + atc_prefix = "Q_A" + gcs:send_text(MAV_SEVERITY_EMERGENCY, "Quicktune for quadplane loaded") +elseif param:get("ATC_RAT_RLL_SMAX") then + is_quadplane = false + gcs:send_text(MAV_SEVERITY_EMERGENCY, "Quicktune for multicopter loaded") +else + gcs:send_text(MAV_SEVERITY_EMERGENCY, "Quicktune unknown vehicle") + return +end + +-- get time in seconds since boot +function get_time() + return millis():tofloat() * 0.001 +end + +local axis_names = { "RLL", "PIT", "YAW" } +local param_suffixes = { "FF", "P", "I", "D", "SMAX", "FLTT", "FLTD", "FLTE" } +local stages = { "D", "P" } +local stage = stages[1] +local last_stage_change = get_time() +local last_gain_report = get_time() +local last_pilot_input = get_time() +local last_notice = get_time() +local tune_done_time = nil +local slew_parm = nil +local slew_target = 0 +local slew_delta = 0 + +local axes_done = {} +local filters_done = {} + + +-- create params dictionary indexed by name, such as "RLL_P" +local params = {} +local param_saved = {} +local param_changed = {} +local need_restore = false + +for i, axis in ipairs(axis_names) do + for j, suffix in ipairs(param_suffixes) do + local pname = axis .. "_" .. suffix + params[pname] = bind_param(atc_prefix .. "_" .. "RAT_" .. pname) + param_changed[pname] = false + end +end + +-- reset to start +function reset_axes_done() + for i, axis in ipairs(axis_names) do + axes_done[axis] = false + filters_done[axis] = false + end + stage = stages[1] +end + +-- get all current param values into param_saved dictionary +function get_all_params() + for pname in pairs(params) do + param_saved[pname] = params[pname]:get() + end +end + +-- restore all param values from param_saved dictionary +function restore_all_params() + for pname in pairs(params) do + local changed = param_changed[pname] and 1 or 0 + if param_changed[pname] then + params[pname]:set(param_saved[pname]) + param_changed[pname] = false + end + end +end + +-- save all param values to storage +function save_all_params() + for pname in pairs(params) do + if param_changed[pname] then + params[pname]:set_and_save(params[pname]:get()) + param_saved[pname] = params[pname]:get() + param_changed[pname] = false + end + end +end + +-- setup a default SMAX if zero +function setup_SMAX() + for i, axis in ipairs(axis_names) do + local smax = axis .. "_SMAX" + if params[smax]:get() <= 0 then + adjust_gain(smax, DEFAULT_SMAX) + end + end +end + +-- setup filter frequencies +function setup_filters(axis) + if QUIK_AUTO_FILTER:get() <= 0 then + return + end + local fltd = axis .. "_FLTD" + local fltt = axis .. "_FLTT" + local flte = axis .. "_FLTE" + adjust_gain(fltt, INS_GYRO_FILTER:get() * FLTT_MUL) + adjust_gain(fltd, INS_GYRO_FILTER:get() * FLTD_MUL) + if axis == "YAW" then + local FLTE = params[flte] + if FLTE:get() <= 0.0 or FLTE:get() > YAW_FLTE_MAX then + adjust_gain(flte, YAW_FLTE_MAX) + end + end + filters_done[axis] = true +end + +-- check for pilot input to pause tune +function have_pilot_input() + if (math.abs(RCIN_ROLL:norm_input_dz()) > 0 or + math.abs(RCIN_PITCH:norm_input_dz()) > 0 or + math.abs(RCIN_YAW:norm_input_dz()) > 0) then + return true + end + return false +end + +reset_axes_done() +get_all_params() + +-- 3 position switch +local quick_switch = nil + +function axis_enabled(axis) + local axes = QUIK_AXES:get() + for i = 1, #axis_names do + local mask = (1 << (i-1)) + local axis_name = axis_names[i] + if axis == axis_name and (mask & axes) ~= 0 then + return true + end + end + return false +end + +-- get the axis name we are working on, or nil for all done +function get_current_axis() + local axes = QUIK_AXES:get() + for i = 1, #axis_names do + local mask = (1 << (i-1)) + local axis_name = axis_names[i] + if (mask & axes) ~= 0 and axes_done[axis_name] == false then + return axis_names[i] + end + end + return nil +end + +-- get slew rate for an axis +function get_slew_rate(axis) + local roll_srate, pitch_srate, yaw_srate = AC_AttitudeControl:get_rpy_srate() + if axis == "RLL" then + return roll_srate + end + if axis == "PIT" then + return pitch_srate + end + if axis == "YAW" then + return yaw_srate + end + return 0.0 +end + +-- move to next stage of tune +function advance_stage(axis) + if stage == "D" then + stage = "P" + else + axes_done[axis] = true + gcs:send_text(5, string.format("Tuning: %s done", axis)) + stage = "D" + end +end + +-- get param name, such as RLL_P, used as index into param dictionaries +function get_pname(axis, stage) + return axis .. "_" .. stage +end + +-- get axis name from parameter name +function param_axis(pname) + return string.sub(pname, 1, 3) +end + +-- get parameter suffix from parameter name +function param_suffix(pname) + return string.sub(pname, 4) +end + +-- change a gain +function adjust_gain(pname, value) + local P = params[pname] + need_restore = true + param_changed[pname] = true + P:set(value) + if string.sub(pname, -2) == "_P" then + -- also change I gain + local iname = string.gsub(pname, "_P", "_I") + local ffname = string.gsub(pname, "_P", "_FF") + local I = params[iname] + local FF = params[ffname] + if FF:get() > 0 then + -- if we have any FF on an axis then we don't couple I to P, + -- usually we want I = FF for a one sectond time constant for trim + return + end + param_changed[iname] = true + + -- work out ratio of P to I that we want + local PI_ratio = QUIK_RP_PI_RATIO:get() + if param_axis(pname) == "YAW" then + PI_ratio = QUIK_Y_PI_RATIO:get() + end + if PI_ratio >= 1 then + I:set(value/PI_ratio) + end + end +end + +-- return gain multipler for one loop +function get_gain_mul() + return math.exp(math.log(2.0)/(UPDATE_RATE_HZ*QUIK_DOUBLE_TIME:get())) +end + +function setup_slew_gain(pname, gain) + slew_parm = pname + slew_target = gain + slew_steps = UPDATE_RATE_HZ/2 + slew_delta = (gain - params[pname]:get()) / slew_steps +end + +function update_slew_gain() + if slew_parm ~= nil then + local P = params[slew_parm] + local axis = param_axis(slew_parm) + local ax_stage = string.sub(slew_parm, -1) + adjust_gain(slew_parm, P:get()+slew_delta) + slew_steps = slew_steps - 1 + logger:write('QUIK','SRate,Gain,Param', 'ffn', get_slew_rate(axis), P:get(), axis .. ax_stage) + if slew_steps == 0 then + gcs:send_text(MAV_SEVERITY_INFO, string.format("%s %.4f", slew_parm, P:get())) + slew_parm = nil + if get_current_axis() == nil then + gcs:send_text(MAV_SEVERITY_NOTICE, string.format("Tuning: DONE")) + tune_done_time = get_time() + end + end + end +end + +-- return gain limits on a parameter, or 0 for no limit +function gain_limit(pname) + if param_axis(pname) == "YAW" then + local suffix = param_suffix(pname) + if suffix == "_P" then + return QUIK_YAW_P_MAX:get() + end + if suffix == "_D" then + return QUIK_YAW_D_MAX:get() + end + end + return 0.0 +end + +function reached_limit(pname, gain) + local limit = gain_limit(pname) + if limit > 0.0 and gain >= limit then + return true + end + return false +end + +-- main update function +local last_warning = get_time() +function update() + if quick_switch == nil then + quick_switch = rc:find_channel_for_option(math.floor(QUIK_RC_FUNC:get())) + end + if quick_switch == nil or QUIK_ENABLE:get() < 1 then + return + end + + if have_pilot_input() then + last_pilot_input = get_time() + end + + local sw_pos = quick_switch:get_aux_switch_pos() + if sw_pos == 1 and (not arming:is_armed() or not vehicle:get_likely_flying()) and get_time() > last_warning + 5 then + gcs:send_text(MAV_SEVERITY_EMERGENCY, string.format("Tuning: Must be flying to tune")) + last_warning = get_time() + return + end + if sw_pos == 0 or not arming:is_armed() or not vehicle:get_likely_flying() then + -- abort, revert parameters + if need_restore then + need_restore = false + restore_all_params() + gcs:send_text(MAV_SEVERITY_EMERGENCY, string.format("Tuning: reverted")) + tune_done_time = nil + end + reset_axes_done() + return + end + if sw_pos == 2 then + -- save all params + if need_restore then + need_restore = false + save_all_params() + gcs:send_text(MAV_SEVERITY_NOTICE, string.format("Tuning: saved")) + end + end + if sw_pos ~= 1 then + return + end + + if get_time() - last_stage_change < STAGE_DELAY then + update_slew_gain() + return + end + + axis = get_current_axis() + if axis == nil then + -- nothing left to do, check autosave time + if tune_done_time ~= nil and QUIK_AUTO_SAVE:get() > 0 then + if get_time() - tune_done_time > QUIK_AUTO_SAVE:get() then + need_restore = false + save_all_params() + gcs:send_text(MAV_SEVERITY_NOTICE, string.format("Tuning: saved")) + tune_done_time = nil + end + end + return + end + + if not need_restore then + -- we are just starting tuning, get current values + gcs:send_text(MAV_SEVERITY_NOTICE, string.format("Tuning: starting tune")) + get_all_params() + setup_SMAX() + end + + if get_time() - last_pilot_input < PILOT_INPUT_DELAY then + return + end + + if not filters_done[axis] then + gcs:send_text(MAV_SEVERITY_INFO, string.format("Starting %s tune", axis)) + setup_filters(axis) + end + + local srate = get_slew_rate(axis) + local pname = get_pname(axis, stage) + local P = params[pname] + local oscillating = srate > QUIK_OSC_SMAX:get() + local limited = reached_limit(pname, P:get()) + if limited or oscillating then + local reduction = (100.0-QUIK_GAIN_MARGIN:get())*0.01 + if not oscillating then + reduction = 1.0 + end + local new_gain = P:get() * reduction + local limit = gain_limit(pname) + if limit > 0.0 and new_gain > limit then + new_gain = limit + end + local old_gain = param_saved[pname] + if new_gain < old_gain and string.sub(pname,-2) == '_D' and param_axis(pname) ~= 'YAW' then + -- we are lowering a D gain from the original gain. Also lower the P gain by the same amount + -- so that we don't trigger P oscillation. We don't drop P by more than a factor of 2 + local ratio = math.max(new_gain / old_gain, 0.5) + local P_name = string.gsub(pname, "_D", "_P") + local old_P = params[P_name]:get() + local new_P = old_P * ratio + gcs:send_text(MAV_SEVERITY_INFO, string.format("adjusting %s %.3f -> %.3f", P_name, old_P, new_P)) + adjust_gain(P_name, new_P) + end + setup_slew_gain(pname, new_gain) + logger:write('QUIK','SRate,Gain,Param', 'ffn', srate, P:get(), axis .. stage) + gcs:send_text(6, string.format("Tuning: %s done", pname)) + advance_stage(axis) + last_stage_change = get_time() + else + local new_gain = P:get()*get_gain_mul() + if new_gain <= 0.0001 then + new_gain = 0.001 + end + adjust_gain(pname, new_gain) + logger:write('QUIK','SRate,Gain,Param', 'ffn', srate, P:get(), axis .. stage) + if get_time() - last_gain_report > 3 then + last_gain_report = get_time() + gcs:send_text(MAV_SEVERITY_INFO, string.format("%s %.4f sr:%.2f", pname, new_gain, srate)) + end + end +end + +-- wrapper around update(). This calls update() at 10Hz, +-- and if update faults then an error is displayed, but the script is not +-- stopped +function protected_wrapper() + local success, err = pcall(update) + if not success then + gcs:send_text(MAV_SEVERITY_EMERGENCY, "Internal Error: " .. err) + -- when we fault we run the update function again after 1s, slowing it + -- down a bit so we don't flood the console with errors + --return protected_wrapper, 1000 + return + end + return protected_wrapper, 1000/UPDATE_RATE_HZ +end + +-- start running update loop +return protected_wrapper() diff --git a/libraries/AP_Scripting/applets/VTOL-quicktune.md b/libraries/AP_Scripting/applets/VTOL-quicktune.md new file mode 100644 index 00000000000..66045689627 --- /dev/null +++ b/libraries/AP_Scripting/applets/VTOL-quicktune.md @@ -0,0 +1,157 @@ +# VTOL QuickTune + +This script implements a fast VTOL tuning system for multicopters and +quadplanes. This script can be used to automate the process of +producing a good "manual tune" for the VTOL rate control parameters. + +The script is designed to be used in QLOITER mode for quadplanes or +LOITER mode in multicopters, although it can also be used in other +VTOL modes. + +# Parameters + +The script adds 7 parameters to control it's behaviour. The parameters +are: + +## QUIK_ENABLE + +this must be set to 1 to enable the script + +## QUIK_RC_FUNC + +The RCz_OPTIONS scripting function binding to be used for this script. +Default RCz_OPTIONS binding is 300 (scripting1). + +## QUIK_AXES + +This is the set of axes that the tune will run on. The default is 7, +which means roll, pitch and yaw. It is a bitmask, so if you want just +roll and pitch then set this to 3. For just yaw you would set it to 4. + +## QUIK_DOUBLE_TIME + +This controls how quickly a gain is raised while tuning. It is a time +in seconds for the gain to double. Most users will want to leave this +at the default of 10 seconds. + +## QUIK_GAIN_MARGIN + +This is the percentage gain margin to use. Once the oscillation point +for a gain is found the gain is reduced by this percentage. The +default of 60% is good for most users. + +## QUIK_OSC_SMAX + +This is the oscillation threshold in Hertz for detecting oscillation +when a gain is raised. The default of 5Hz is good for most vehicles, +but on very large vehicles you may wish to lower this. For a vehicle +of 50kg a value of 3 is likely to be good. For a vehicle of 100kg a +value of 1.5 is likely to be good. + +You can tell you have this set too high if you still have visible +oscillations after a parameter has completed tuning. In that case +halve this parameter and try again. + +## QUIK_YAW_P_MAX + +This sets a limit on the YAW_P rate gain. The yaw axis on most +multirotor style vehicles needs to have a much lower limit on the P +gain than the oscillation limit to ensure that enough control remains +for roll, pitch and thrust. A maximum of 0.5 is good for most VTOL +vehicles. + +## QUIK_YAW_D_MAX + +This sets a limit on the YAW_D rate gain. The yaw axis on most +multirotor style vehicles needs to have a much lower limit on the D +gain than the oscillation limit to ensure that enough control remains +for roll, pitch and thrust. A maximum of 0.01 is good for most VTOL +vehicles. + +## QUIK_RP_PI_RATIO + +This is the ratio for P to I for roll and pitch axes. This should +normally be 1, but on some large vehicles a value of up to 3 can be +used if the I term in the PID is causing too much phase lag. + +If QUIK_RP_PI_RATIO is less than 1 then the I value will not be +changed at all when P is changed. + +## QUIK_Y_PI_RATIO + +This is the ratio for P to I for the yax axis. This should +normally be 10, but a different value may be needed on some vehicle +types. + +If QUIK_Y_PI_RATIO is less than 1 then the I value will not be +changed at all when P is changed. + +## QUIK_AUTO_FILTER + +This enables automatic setting of the PID filters based on the +INS_GYRO_FILTER value. Set to zero to disable this feature. + +## QUIK_AUTO_SAVE + +This enables automatic saving of the tune if this number of seconds +pass after the end of the tune without reverting the tune. Setting +this to a non-zero value allows you to use quicktune with a 2-position +switch, with the switch settings as low and mid positions. A zero +value disables auto-save and you need to have a 3 position switch. + +# Operation + +First you should setup harmonic notch filtering using the guide in the +ArduPilot wiki. This tuning system relies on you already having +reduced gyro noise using the harmonic notch filter. It will fail if +your noise is too high. + +Install the lua script in the APM/SCRIPTS directory on the flight +controllers microSD card, then set SCR_ENABLE to 1. Reboot, and +refresh parameters. Then set QUIK_ENABLE to 1. + +You will then need to setup a 3 position switch on an available RC +input channel for controlling the tune (or 2 position if you set +QUIK_AUTO_SAVE). If for example channel 6 is available with a 3 +position switch then you should set RC6_OPTION=300 (scripting1) to associate the +tuning control with that switch. + +If needed, the QUIK_RC_FUNC option can be used to associate the tuning switch +with a different scripting binding such as RCz_OPTION = 302 (scripting3). + +You should then takeoff and put the vehicle into QLOITER mode (for +quadplanes) or LOITER mode (for multicopters) and have it in a steady +hover in low wind. + +Then move the control switch you setup with option 300 (or via QUIK_RC_FUNC) +to the middle position. This will start the tuning process. You will see text +messages on the ground station showing the progress of the tune. As +the aircraft reaches the oscillation limit of each parameter it will +start a small oscillation, then it will reduce that gain by the +configured QUIK_GAIN_MARGIN percentage and then move onto the next +parameter. + +With default settings the parameters to be tuned will be: + + - RLL_D + - RLL_P + - PIT_D + - PIT_P + - YAW_D + - YAW_P + +The script will also adjust filter settings using the following rules: + + - the FLTD and FLTT settings will be set to half of the INS_GYRO_FILTER value + - the YAW_FLTE filter will be set to a maximum of 2Hz + - if no SMAX is set for a rate controller than the SMAX will be set to 50Hz + +Once the tuning is finished you will see a "Tuning: done" message. You +can save the tune by moving the switch to the high position (Tune Save). You +should do this to save before you land and disarm. If you save before the tune is completed the tune will pause, and any parameters completed will be saved and the current value of the one being actively tuned will remain active. You can resume tuning by returning the switch again to the middle position, or if moved to the low position, the parameter currently being tuned will be reverted but any previously saved parameters will remain. + +If you move the switch to the low position at any time in the tune before using the Tune Save switch position, then all parameters will be reverted to their original +values. Parameters will also be reverted if you disarm before saving. + +If the pilot gives roll, pitch or yaw input while tuning then the tune +is paused until 4 seconds after the pilot input stops. diff --git a/libraries/AP_Scripting/applets/forward_flight_motor_shutdown.md b/libraries/AP_Scripting/applets/forward_flight_motor_shutdown.md new file mode 100644 index 00000000000..4055be44bd5 --- /dev/null +++ b/libraries/AP_Scripting/applets/forward_flight_motor_shutdown.md @@ -0,0 +1,9 @@ +# Forward flight motor shutdown script for tailsitters and tiltrotors + +This allows to shutdown selected motors to be stopped once in forward flight for efficiency. + +Set the motors to shutdown in with the `stop_motors` variable. Enable and disable the functionality with a RC switch with options 300 (Scripting1). + +Motors will automatically be shutdown if forward throttle is lower than the value set in `throttle_off_threshold` (50% by default) the motors will then be re-enabled if the throttle goes above the value set in `throttle_on_threshold` (75% by default). + +Time for stopped motors to go from throttle value to 0 and 0 back to throttle can be set with `slew_down_time` and `slew_up_time`. diff --git a/libraries/AP_Scripting/applets/motor_failure_test.lua b/libraries/AP_Scripting/applets/motor_failure_test.lua new file mode 100644 index 00000000000..64f64440e60 --- /dev/null +++ b/libraries/AP_Scripting/applets/motor_failure_test.lua @@ -0,0 +1,67 @@ +-- This is a script that stops motors in flight, for use testing motor failure handling + +-- add new param MOT_STOP_BITMASK +local PARAM_TABLE_KEY = 75 +assert(param:add_table(PARAM_TABLE_KEY, "MOT_", 1), "could not add param table") +assert(param:add_param(PARAM_TABLE_KEY, 1, "STOP_BITMASK", 0), "could not add param") + +local stop_motor_bitmask = Parameter() +assert(stop_motor_bitmask:init("MOT_STOP_BITMASK"), "could not find param") + +-- find rc switch with option 300 +local switch = assert(rc:find_channel_for_option(300),"Lua: Could not find switch") + +-- read spin min param, we set motors to this PWM to stop them +local pwm_min +if quadplane then + pwm_min = assert(param:get("Q_M_PWM_MIN"),"Lua: Could not read Q_M_PWM_MIN") +else + pwm_min = assert(param:get("MOT_PWM_MIN"),"Lua: Could not read MOT_PWM_MIN") +end + +local stop_motor_chan +local last_motor_bitmask + +-- find any motors enabled, populate channels numbers to stop +local function update_stop_motors(new_bitmask) + if last_motor_bitmask == new_bitmask then + return + end + stop_motor_chan = {} + for i = 1, 12 do + if ((1 << (i-1)) & new_bitmask) ~= 0 then + -- convert motor number to output function number + local output_function + if i <= 8 then + output_function = i+32 + else + output_function = i+81-8 + end + + -- get channel number for output function + local temp_chan = SRV_Channels:find_channel(output_function) + if temp_chan then + table.insert(stop_motor_chan, temp_chan) + end + end + end + last_motor_bitmask = new_bitmask +end + +function update() + + update_stop_motors(stop_motor_bitmask:get()) + + if switch:get_aux_switch_pos() == 2 then + for i = 1, #stop_motor_chan do + -- override for 15ms, called every 10ms + -- using timeout means if the script dies the timeout will expire and all motors will come back + -- we cant leave the vehicle in a un-flyable state + SRV_Channels:set_output_pwm_chan_timeout(stop_motor_chan[i],pwm_min,15) + end + end + + return update, 10 -- reschedule at 100hz +end + +return update() -- run immediately before starting to reschedule diff --git a/libraries/AP_Scripting/applets/motor_failure_test.md b/libraries/AP_Scripting/applets/motor_failure_test.md new file mode 100644 index 00000000000..8a749b7506a --- /dev/null +++ b/libraries/AP_Scripting/applets/motor_failure_test.md @@ -0,0 +1,7 @@ +# Motor Failure testing Lua script + +This script allows testing failure of motors on copter and quadplane (VTOL only). Vehicles with eight or more motors should be able to fly easily with a single failed motor. Hexacopters can also cope with motor failure if they have sufficient thrust. + +Motor failure is triggered by a RC switch configured to option 300 (Scripting1). Switch low all motors will run, switch high will stop motors. + +Configure which motors stop with the param MOT_STOP_BITMASK, this is added by the script so will only show up once the script is loaded on the SD card. The parameters is a bitmask of motors to stop. A value of 1 will stop motor 1, value of 2 stop motor 2, a value of 3 stops both motors 1 and 2. diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index f74195d5ebb..044314b9c59 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -67,6 +67,117 @@ i2c = {} ---@return AP_HAL__I2CDevice_ud function i2c:get_device(bus, address, clock, smbus) end +-- EFI state structure +---@class EFI_State_ud +local EFI_State_ud = {} + +---@return EFI_State_ud +function EFI_State() end + +-- set field +---@param value Cylinder_Status_ud +function EFI_State_ud:cylinder_status(value) end + +-- set field +---@param value integer +function EFI_State_ud:ecu_index(value) end + +-- set field +---@param value integer +function EFI_State_ud:throttle_position_percent(value) end + +-- set field +---@param value number +function EFI_State_ud:estimated_consumed_fuel_volume_cm3(value) end + +-- set field +---@param value number +function EFI_State_ud:fuel_consumption_rate_cm3pm(value) end + +-- set field +---@param value number +function EFI_State_ud:fuel_pressure(value) end + +-- set field +---@param value number +function EFI_State_ud:oil_temperature(value) end + +-- set field +---@param value number +function EFI_State_ud:oil_pressure(value) end + +-- set field +---@param value number +function EFI_State_ud:coolant_temperature(value) end + +-- set field +---@param value number +function EFI_State_ud:intake_manifold_temperature(value) end + +-- set field +---@param value number +function EFI_State_ud:intake_manifold_pressure_kpa(value) end + +-- set field +---@param value number +function EFI_State_ud:atmospheric_pressure_kpa(value) end + +-- set field +---@param value number +function EFI_State_ud:spark_dwell_time_ms(value) end + +-- set field +---@param value uint32_t_ud +function EFI_State_ud:engine_speed_rpm(value) end + +-- set field +---@param value integer +function EFI_State_ud:engine_load_percent(value) end + +-- set field +---@param value boolean +function EFI_State_ud:general_error(value) end + +-- set field +---@param value uint32_t_ud +function EFI_State_ud:last_updated_ms(value) end + + +-- EFI Cylinder_Status structure +---@class Cylinder_Status_ud +local Cylinder_Status_ud = {} + +---@return Cylinder_Status_ud +function Cylinder_Status() end + +-- set field +---@param value number +function Cylinder_Status_ud:lambda_coefficient(value) end + +-- set field +---@param value number +function Cylinder_Status_ud:exhaust_gas_temperature(value) end + +-- set field +---@param value number +function Cylinder_Status_ud:cylinder_head_temperature(value) end + +-- set field +---@param value number +function Cylinder_Status_ud:injection_time_ms(value) end + +-- set field +---@param value number +function Cylinder_Status_ud:ignition_timing_deg(value) end + +-- desc +---@class efi +efi = {} + +-- EFI handle scripting update +---@param efi_state EFI_State_ud +function efi:handle_scripting(efi_state) end + -- CAN bus interaction ---@class CAN @@ -388,6 +499,9 @@ function Vector2f_ud:normalize() end ---@return number function Vector2f_ud:length() end +-- desc +---@return number +function Vector2f_ud:angle() end -- desc ---@class Vector3f_ud @@ -458,6 +572,14 @@ function Vector3f_ud:normalize() end ---@return number function Vector3f_ud:length() end +-- desc +---@param param1 number -- XY rotation in radians +function Vector3f_ud:rotate_xy(param1) end + +-- desc +---@return Vector2f_ud +function Vector3f_ud:xy() end + -- desc ---@class Location_ud @@ -615,10 +737,12 @@ local AP_HAL__I2CDevice_ud = {} ---@param address integer function AP_HAL__I2CDevice_ud:set_address(address) end --- desc +-- If no read length is provided a single register will be read and returned. +-- If read length is provided a table of register values are returned. ---@param register_num integer ----@return integer|nil -function AP_HAL__I2CDevice_ud:read_registers(register_num) end +---@param read_length? integer +---@return integer|table|nil +function AP_HAL__I2CDevice_ud:read_registers(register_num, read_length) end -- desc ---@param register_num integer @@ -668,14 +792,58 @@ local RC_Channel_ud = {} ---@return number function RC_Channel_ud:norm_input_ignore_trim() end +-- desc +---@param PWM integer +function RC_Channel_ud:set_override(PWM) end + -- desc ---@return integer function RC_Channel_ud:get_aux_switch_pos() end --- desc +-- desc return input on a channel from -1 to 1, centered on the trim. Ignores the deadzone ---@return number function RC_Channel_ud:norm_input() end +-- desc return input on a channel from -1 to 1, centered on the trim. Returns zero when within deadzone of the trim +---@return number +function RC_Channel_ud:norm_input_dz() end + + +-- desc +---@class mount +mount = {} + +-- desc +---@param instance integer +---@param target_loc Location_ud +function mount:set_roi_target(instance, target_loc) end + +-- desc +---@param instance integer +---@param roll_degs number +---@param pitch_degs number +---@param yaw_degs number +---@param yaw_is_earth_frame boolean +function mount:set_rate_target(instance, roll_degs, pitch_degs, yaw_degs, yaw_is_earth_frame) end + +-- desc +---@param instance integer +---@param roll_deg number +---@param pitch_deg number +---@param yaw_deg number +---@param yaw_is_earth_frame boolean +function mount:set_angle_target(instance, roll_deg, pitch_deg, yaw_deg, yaw_is_earth_frame) end + +-- desc +---@param instance integer +---@param mode integer +function mount:set_mode(instance, mode) end + +-- desc +---@param instance integer +---@return integer +function mount:get_mode(instance) end + -- desc ---@class motors @@ -727,6 +895,9 @@ function periph:get_vehicle_state() end ---@return number function periph:get_yaw_earth() end +-- desc +---@param text string +function periph:can_printf(text) end -- desc ---@class ins @@ -1055,6 +1226,16 @@ function esc_telem:get_temperature(instance) end ---@return number|nil function esc_telem:get_rpm(instance) end +-- update RPM for an ESC +---@param param1 integer -- ESC number +---@param param2 integer -- RPM +---@param param3 number -- error rate +function esc_telem:update_rpm(esc_index, rpm, error_rate) end + +-- set scale factor for RPM on a motor +---@param param1 motor index (0 is first motor) +---@param param2 scale factor +function esc_telem:set_rpm_scale(esc_index, scale_factor) end -- desc ---@class optical_flow @@ -1094,10 +1275,12 @@ function baro:get_pressure() end ---@class serial serial = {} --- desc ----@param protocol integer ----@return AP_HAL__UARTDriver_ud -function serial:find_serial(protocol) end +-- Returns the UART instance that allows connections from scripts (those with SERIALx_PROTOCOL = 28`). +-- For instance = 0, returns first such UART, second for instance = 1, and so on. +-- If such an instance is not found, returns nil. +---@param instance integer -- the 0-based index of the UART instance to return. +---@return AP_HAL__UARTDriver_ud -- the requested UART instance available for scripting, or nil if none. +function serial:find_serial(instance) end -- desc @@ -1113,6 +1296,11 @@ function rc:get_channel(chan_num) end ---@return boolean function rc:has_valid_input() end +-- return cached level of aux function +---@param aux_fn integer +---@return integer|nil +function rc:get_aux_cached(aux_fn) end + -- desc ---@param aux_fun integer ---@param ch_flag integer @@ -1309,6 +1497,12 @@ function vehicle:set_target_posvel_NED(target_pos, target_vel) end ---@return boolean function vehicle:set_target_pos_NED(target_pos, use_yaw, yaw_deg, use_yaw_rate, yaw_rate_degs, yaw_relative, terrain_alt) end +-- desc +---@param current_target Location_ud -- current target, from get_target_location() +---@param new_target Location_ud -- new target +---@return boolean +function vehicle:update_target_location(current_target, new_target) end + -- desc ---@return Location_ud|nil function vehicle:get_target_location() end @@ -1357,6 +1551,37 @@ function vehicle:get_mode() end ---@return boolean function vehicle:set_mode(mode_number) end +-- desc +---@param param1 Vector2f_ud +---@return boolean +function vehicle:set_velocity_match(param1) end + +-- desc +---@param param1 integer +---@return boolean +function vehicle:nav_scripting_enable(param1) end + +-- desc sets autopilot nav speed (Copter and Rover) +---@param param1 number +---@return boolean +function vehicle:set_desired_speed(param1) end + +-- desc +---@param param1 number +---@param param2 number +---@return boolean +function vehicle:set_desired_turn_rate_and_speed(param1, param2) end + +-- desc +---@param param1 number -- throttle percent +---@param param2 number -- roll rate deg/s +---@param param3 number -- pitch rate deg/s +---@param param4 number -- yaw rate deg/s +function vehicle:set_target_throttle_rate_rpy(param1, param2, param3, param4) end + +-- desc +---@param param1 integer +function vehicle:nav_script_time_done(param1) end -- desc ---@class onvif @@ -1429,6 +1654,11 @@ function relay:toggle(instance) end ---@return boolean function relay:enabled(instance) end +-- return state of a relay +---@param instance integer +---@return uint8_t +function relay:get(instance) end + -- desc ---@param instance integer function relay:off(instance) end @@ -1778,6 +2008,10 @@ function arming:arm() end ---@return boolean function arming:is_armed() end +-- desc +---@return boolean +function arming:pre_arm_checks() end + -- desc ---@return boolean function arming:disarm() end @@ -1905,4 +2139,38 @@ function ahrs:get_pitch() end ---@return number function ahrs:get_roll() end +-- desc +---@class AC_AttitudeControl +AC_AttitudeControl = {} +-- return slew rates for VTOL controller +---@return number -- roll slew rate +---@return number -- pitch slew rate +---@return number -- yaw slew rate +function AC_AttitudeControl:get_rpy_srate() end + +-- desc +---@class follow +follow = {} + +-- desc +---@return number|nil +function follow:get_target_heading_deg() end + +-- desc +---@return Location_ud|nil +---@return Vector3f_ud|nil +function follow:get_target_location_and_velocity_ofs() end + +-- desc +---@return Location_ud|nil +---@return Vector3f_ud|nil +function follow:get_target_location_and_velocity() end + +-- desc +---@return uint32_t_ud +function follow:get_last_update_ms() end + +-- desc +---@return boolean +function follow:have_target() end diff --git a/libraries/AP_Scripting/drivers/EFI_HFE.lua b/libraries/AP_Scripting/drivers/EFI_HFE.lua new file mode 100644 index 00000000000..f15448d129d --- /dev/null +++ b/libraries/AP_Scripting/drivers/EFI_HFE.lua @@ -0,0 +1,305 @@ +--[[ + EFI Scripting backend driver for HFE based on HFEDCN0191 Rev E +--]] + +-- Check Script uses a miniumum firmware version +local SCRIPT_AP_VERSION = 4.3 +local SCRIPT_NAME = "EFI: HFE CAN" + +local VERSION = FWVersion:major() + (FWVersion:minor() * 0.1) + +assert(VERSION >= SCRIPT_AP_VERSION, string.format('%s Requires: %s:%.1f. Found Version: %s', SCRIPT_NAME, FWVersion:type(), SCRIPT_AP_VERSION, VERSION)) + +local MAV_SEVERITY_ERROR = 3 + +PARAM_TABLE_KEY = 37 +PARAM_TABLE_PREFIX = "EFI_HFE_" + +K_THROTTLE = 70 +K_IGNITION = 67 + +-- bind a parameter to a variable given +function bind_param(name) + local p = Parameter() + assert(p:init(name), string.format('could not find %s parameter', name)) + return p +end + +-- add a parameter and bind it to a variable +function bind_add_param(name, idx, default_value) + assert(param:add_param(PARAM_TABLE_KEY, idx, name, default_value), string.format('could not add param %s', name)) + return bind_param(PARAM_TABLE_PREFIX .. name) +end + +function get_time_sec() + return millis():tofloat() * 0.001 +end + +-- Type conversion functions +function get_uint8(frame, ofs) + return frame:data(ofs) +end + +function get_uint16(frame, ofs) + return frame:data(ofs+1) + (frame:data(ofs) << 8) +end + +function constrain(v, vmin, vmax) + if v < vmin then + v = vmin + end + if v > vmax then + v = vmax + end + return v +end + +local efi_backend = nil + +-- Setup EFI Parameters +assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 6), 'could not add EFI_HFE param table') + +local EFI_HFE_ENABLE = bind_add_param('ENABLE', 1, 0) +local EFI_HFE_RATE_HZ = bind_add_param('RATE_HZ', 2, 200) -- Script update frequency in Hz +local EFI_HFE_ECU_IDX = bind_add_param('ECU_IDX', 3, 0) -- ECU index on CAN bus, 0 for automatic +local EFI_HFE_FUEL_DTY = bind_add_param('FUEL_DTY', 4, 740) -- fuel density, g/litre +local EFI_HFE_REL_IDX = bind_add_param('REL_IDX', 5, 0) -- relay number for engine enable +local EFI_HFE_CANDRV = bind_add_param('CANDRV', 6, 0) -- CAN driver number + +local ICE_PWM_IGN_ON = bind_param("ICE_PWM_IGN_ON") + +if EFI_HFE_ENABLE:get() == 0 then + return +end + +-- Register for the CAN drivers +local CAN_BUF_LEN = 25 +if EFI_HFE_CANDRV:get() == 1 then + driver1 = CAN.get_device(CAN_BUF_LEN) +elseif EFI_HFE_CANDRV:get() == 2 then + driver1 = CAN.get_device2(CAN_BUF_LEN) +end + +if not driver1 then + gcs:send_text(0, string.format("EFI_HFE: Failed to load driver")) + return +end + + +local now_s = get_time_sec() + +--[[ + EFI Engine Object +--]] +local function engine_control(_driver) + local self = {} + + -- Build up the EFI_State that is passed into the EFI Scripting backend + local efi_state = EFI_State() + local cylinder_state = Cylinder_Status() + + -- private fields as locals + local rpm = 0 + local air_pressure = 0 + local map_ratio = 0.0 + local driver = _driver + local last_rpm_t = get_time_sec() + local last_state_update_t = get_time_sec() + local throttle_pos = 0.0 + local last_thr_t = get_time_sec() + local C_TO_KELVIN = 273.2 + local fuel_flow_gph = 0.0 + local fuel_total_g = 0.0 + local fuel_press = 0.0 + local last_fuel_s = 0.0 + local ecu_voltage = 0.0 + local injector_duty = 0.0 + local ignition_angle = 0.0 + + -- Generator Data Structure + local gen = {} + gen.amps = 0.0 + gen.rpm = 0.0 + gen.batt_current = 0.0 + + -- Temperature Data Structure + local temps = {} + temps.egt = 0.0 -- Engine Gas Temperature + temps.iat = 0.0 -- inlet air temperature + temps.mat = 0.0 -- manifold air temperature + temps.cht = 0.0 -- cylinder head temperature + + -- read telemetry packets + function self.update_telemetry() + local max_packets = 25 + local count = 0 + while count < max_packets do + frame = driver:read_frame() + count = count + 1 + if not frame then + break + end + + -- All Frame IDs for this EFI Engine are in the 29-bit extended address space + if frame:isExtended() then + self.handle_EFI_packet(frame) + end + end + if last_rpm_t > last_state_update_t then + -- update state if we have an updated RPM + last_state_update_t = last_rpm_t + self.set_EFI_State() + end + end + + -- handle an EFI packet + function self.handle_EFI_packet(frame) + local id = frame:id_signed() + if id >> 24 ~= 0x08 then + -- not from ECU + return + end + local ecu = id & 0xff + if ecu ~= 0 and EFI_HFE_ECU_IDX:get() == 0 then + EFI_HFE_ECU_IDX:set(ecu) + gcs:send_text(0, string.format("EFI_HFE: found ECU %u", ecu)) + end + if ecu ~= EFI_HFE_ECU_IDX:get() then + -- not from correct ECU + return + end + local cmd = (id >> 16) & 0xff + if cmd == 0x0 then + -- fast telemetry + throttle_pos = get_uint8(frame, 0) + rpm = get_uint16(frame, 1) + last_rpm_t = get_time_sec() + elseif cmd == 0x01 then + -- slow telem0 + air_pressure = get_uint16(frame, 5) * 2 + map_ratio = get_uint8(frame, 7) * 0.01 + temps.cht = get_uint8(frame,3) - 10.0 + elseif cmd == 0x02 then + -- slow telem1 + temps.iat = get_uint8(frame, 0) + ecu_voltage = get_uint8(frame, 6) * 0.1 + fuel_press = get_uint16(frame,1)*20.0 + elseif cmd == 0x03 then + -- slow telem2 + temps.mat = (1.5*get_uint8(frame, 1)) - 128 + fuel_flow_gph = get_uint16(frame, 6) + if last_fuel_s > 0 then + local dt = now_s - last_fuel_s + local fuel_gps = fuel_flow_gph / 3600.0 + fuel_total_g = fuel_total_g + fuel_gps * dt + end + injector_duty = get_uint16(frame,2) + last_fuel_s = now_s + ignition_angle = get_uint8(frame,4)*2.0 + end + end + + -- Build and set the EFI_State that is passed into the EFI Scripting backend + function self.set_EFI_State() + -- Cylinder_Status + cylinder_state:cylinder_head_temperature(temps.cht + C_TO_KELVIN) + cylinder_state:exhaust_gas_temperature(temps.mat) + cylinder_state:ignition_timing_deg(ignition_angle) + if rpm > 0 then + cylinder_state:injection_time_ms((60.0/rpm)*1000*injector_duty) + else + cylinder_state:injection_time_ms(0) + end + + efi_state:engine_speed_rpm(uint32_t(rpm)) + + efi_state:atmospheric_pressure_kpa(air_pressure*0.001) + efi_state:intake_manifold_pressure_kpa(air_pressure*0.001*map_ratio) + efi_state:intake_manifold_temperature(temps.mat + C_TO_KELVIN) + efi_state:throttle_position_percent(math.floor((throttle_pos*100/255)+0.5)) + efi_state:ignition_voltage(ecu_voltage) + efi_state:fuel_pressure(fuel_press*0.001) + + local gram_to_cm3 = EFI_HFE_FUEL_DTY:get() * 0.001 + efi_state:fuel_consumption_rate_cm3pm((fuel_flow_gph/60.0) * gram_to_cm3) + efi_state:estimated_consumed_fuel_volume_cm3(fuel_total_g * gram_to_cm3) + + -- copy cylinder_state to efi_state + efi_state:cylinder_status(cylinder_state) + + efi_state:last_updated_ms(millis()) + + -- Set the EFI_State into the EFI scripting driver + efi_backend:handle_scripting(efi_state) + end + + -- send throttle + function self.send_throttle() + if now_s - last_thr_t < 0.02 then + -- limit to 50Hz + return + end + last_thr_t = now_s + local thr = SRV_Channels:get_output_scaled(K_THROTTLE) + local msg = CANFrame() + msg:id(uint32_t(0x89060000 | EFI_HFE_ECU_IDX:get())) + msg:data(0,math.floor((thr*255/100)+0.5)) + msg:dlc(2) + driver:write_frame(msg, 10000) + + -- throttle calibration request, for debug + --msg = CANFrame() + --msg:id(uint32_t(0x89050000 | EFI_HFE_ECU_IDX:get())) + --msg:dlc(0) + --driver:write_frame(msg, 10000) + + -- map K_IGNITION to relay for enable of engine + local relay_idx = EFI_HFE_REL_IDX:get() + if relay_idx > 0 then + local ignition_pwm = SRV_Channels:get_output_pwm(K_IGNITION) + if ignition_pwm == ICE_PWM_IGN_ON:get() then + relay:on(relay_idx-1) + else + relay:off(relay_idx-1) + end + end + end + + -- return the instance + return self +end -- end function engine_control(_driver) + +local engine1 = engine_control(driver1, 1) + +function update() + now_s = get_time_sec() + + if not efi_backend then + efi_backend = efi:get_backend(0) + if not efi_backend then + return + end + end + + -- Parse Driver Messages + engine1.update_telemetry() + engine1.send_throttle() +end + +gcs:send_text(0, SCRIPT_NAME .. string.format(" loaded")) + +-- wrapper around update(). This calls update() and if update faults +-- then an error is displayed, but the script is not stopped +function protected_wrapper() + local success, err = pcall(update) + if not success then + gcs:send_text(MAV_SEVERITY_ERROR, "Internal Error: " .. err) + -- when we fault we run the update function again after 1s, slowing it + -- down a bit so we don't flood the console with errors + return protected_wrapper, 1000 + end + return protected_wrapper, 1000 / EFI_HFE_RATE_HZ:get() +end + +-- start running update loop +return protected_wrapper() diff --git a/libraries/AP_Scripting/drivers/EFI_HFE.md b/libraries/AP_Scripting/drivers/EFI_HFE.md new file mode 100644 index 00000000000..0db521194ba --- /dev/null +++ b/libraries/AP_Scripting/drivers/EFI_HFE.md @@ -0,0 +1,65 @@ +# EFI HFE Driver + +This driver implements support for the HFE International range of EFI +CAN engine control units. It supports monitoring and control of HFE +engines on fixed wing aircraft. This driver assumes you are using the +ICE subsystem in fixed wing aircraft for engine control. + +# Parameters + +The script used the following parameters: + +## EFI_HFE_ENABLE + +this must be set to 1 to enable the driver + +## EFI_HFE_CANDRV + +This sets the CAN scripting driver number to attach to. This is +normally set to 1 to use a CAN driver with CAN_Dx_PROTOCOL=10. To use +the 2nd scripting CAN driver set this to 2 and set CAN_Dx_PROTOCOL=12. + +## EFI_HFE_ECU_IDX + +This sets the ECU number on the CAN bus. A value of zero means that +the ECU number is auto-detected based on the first ECU seen on the +bus. + +## EFI_HFE_RATE_HZ + +This sets the update rate of the driver. A value of 200 is reasonable + +## EFI_HFE_FUEL_DTY + +This sets the fuel density in grams per litre, for fuel consumption +calculations + +## EFI_HFE_REL_IDX + +This sets a relay number to use for the ECU enable function. if the +ECU requires a high voltage GPIO to enable then you should set a +RELAY_PIN that the ECU enable is attached to and set the relay number +here. + +# Operation + +This driver should be loaded by placing the lua script in the +APM/SCRIPTS directory on the microSD card, which can be done either +directly or via MAVFTP. The following key parameters should be set: + + - SCR_ENABLE should be set to 1 + - EFI_TYPE should be set to 7 + - ICE_ENABLE should be set to 1 + +then the flight controller should rebooted and parameters should be +refreshed. + +Once loaded the EFI_HFE parameters will appear and should be set +according to the parameter list above. + +The ICE start channel will be monitored for starter control. + +The GCS will receive EFI_STATUS MAVLink messages which includes RPM, +cylinder head temperature, injection timing, engine load, fuel +consumption rate, throttle position atmospheric pressure and ECU +voltage. diff --git a/libraries/AP_Scripting/drivers/EFI_SkyPower.lua b/libraries/AP_Scripting/drivers/EFI_SkyPower.lua new file mode 100644 index 00000000000..2c4a85992a9 --- /dev/null +++ b/libraries/AP_Scripting/drivers/EFI_SkyPower.lua @@ -0,0 +1,404 @@ +--[[ +Name: EFI Scripting backend driver for SkyPower +Authors: Andrew Tridgell & Josh Henderson + +The protocol has high CAN utilization due to CAN packets that are used +internal to the enigne being published externally, as well as being +limited to 500 kbit/s. + +CAN_D1_PROTOCOL 10 (Scripting Driver 1) +CAN_P1_DRIVER 1 (First driver) +CAN_D1_BITRATE 500000 (500 kbit/s) + +--]] + +-- Check Script uses a miniumum firmware version +local SCRIPT_AP_VERSION = 4.3 +local SCRIPT_NAME = "EFI: Skypower CAN" + +local VERSION = FWVersion:major() + (FWVersion:minor() * 0.1) + +assert(VERSION >= SCRIPT_AP_VERSION, string.format('%s Requires: %s:%.1f. Found Version: %s', SCRIPT_NAME, FWVersion:type(), SCRIPT_AP_VERSION, VERSION)) + + +local MAV_SEVERITY_ERROR = 3 + +local K_THROTTLE = 70 +local K_HELIRSC = 31 + +PARAM_TABLE_KEY = 36 +PARAM_TABLE_PREFIX = "EFI_SP_" + +-- bind a parameter to a variable given +function bind_param(name) + local p = Parameter() + assert(p:init(name), string.format('could not find %s parameter', name)) + return p +end + +-- add a parameter and bind it to a variable +function bind_add_param(name, idx, default_value) + assert(param:add_param(PARAM_TABLE_KEY, idx, name, default_value), string.format('could not add param %s', name)) + return bind_param(PARAM_TABLE_PREFIX .. name) +end + +function get_time_sec() + return millis():tofloat() * 0.001 +end + +-- Type conversion functions +function get_uint16(frame, ofs) + return frame:data(ofs) + (frame:data(ofs + 1) << 8) +end + +function constrain(v, vmin, vmax) + if v < vmin then + v = vmin + end + if v > vmax then + v = vmax + end + return v +end + +---- GLOBAL VARIABLES +local GKWH_TO_LBS_HP_HR = 0.0016439868 +local LITRES_TO_LBS = 1.6095 -- 6.1 lbs of fuel per gallon -> 1.6095 + +local efi_backend = nil + +-- Setup EFI Parameters +assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 10), 'could not add EFI_SP param table') + +local EFI_SP_ENABLE = bind_add_param('ENABLE', 1, 0) +local EFI_SP_CANDRV = bind_add_param('CANDRV', 2, 1) -- CAN driver to use +local EFI_SP_UPDATE_HZ = bind_add_param('UPDATE_HZ', 3, 200) -- Script update frequency in Hz +local EFI_SP_THR_FN = bind_add_param('THR_FN', 4, 0) -- servo function for throttle +local EFI_SP_THR_RATE = bind_add_param('THR_RATE', 5, 0) -- throttle update rate +local EFI_SP_START_FN = bind_add_param('START_FN', 6, 0) -- start control function (RC option) +local EFI_SP_GEN_FN = bind_add_param('GEN_FN', 7, 0) -- generator control function (RC option) +local EFI_SP_MIN_RPM = bind_add_param('MIN_RPM', 8, 0) -- min RPM, for engine restart + +if EFI_SP_ENABLE:get() == 0 then + gcs:send_text(0, string.format("EFISP: disabled")) + return +end + +-- Register for the CAN drivers +local driver1 + +local CAN_BUF_LEN = 25 +if EFI_SP_CANDRV:get() == 1 then + driver1 = CAN.get_device(CAN_BUF_LEN) +elseif EFI_SP_CANDRV:get() == 2 then + driver1 = CAN.get_device2(CAN_BUF_LEN) +end + +if not driver1 then + gcs:send_text(0, string.format("EFISP: Failed to load driver")) + return +end + + +local now_s = get_time_sec() + +function C_TO_KELVIN(temp) + return temp + 273.15 +end + +--[[ + EFI Engine Object +--]] +local function engine_control(_driver, _idx) + local self = {} + + -- Build up the EFI_State that is passed into the EFI Scripting backend + local efi_state = EFI_State() + local cylinder_state = Cylinder_Status() + + -- private fields as locals + local rpm = 0 + local air_pressure = 0 + local inj_ang = 0 + local inj_time = 0 + local target_load = 0 + local current_load = 0 + local throttle_angle = 0 + local ignition_angle = 0 + local sfc = 0 + local sfc_icao = 0 + local last_sfc_t = 0 + local supply_voltage = 0 + local fuel_consumption_lph = 0 + local fuel_total_l = 0 + local last_fuel_s = 0 + local driver = _driver + local idx = _idx + local last_rpm_t = get_time_sec() + local last_state_update_t = get_time_sec() + local last_thr_update = get_time_sec() + local engine_started = false + local generator_started = false + local engine_start_t = 0.0 + + -- frames for sending commands + local FRM_500 = uint32_t(0x500) + local FRM_505 = uint32_t(0x505) + local FRM_506 = uint32_t(0x506) + + -- Generator Data Structure + local gen = {} + gen.amps = 0.0 + gen.rpm = 0.0 + gen.batt_current = 0.0 + + -- Temperature Data Structure + local temps = {} + temps.egt = 0.0 -- Exhaust Gas Temperature + temps.cht = 0.0 -- Cylinder Head Temperature + temps.imt = 0.0 -- intake manifold temperature + + -- read telemetry packets + function self.update_telemetry() + local max_packets = 25 + local count = 0 + while count < max_packets do + frame = driver:read_frame() + count = count + 1 + if not frame then + break + end + + -- All Frame IDs for this EFI Engine are in the 11-bit address space + if frame:isExtended() then + self.handle_EFI_packet(frame, _idx) + end + end + if last_rpm_t > last_state_update_t then + -- update state if we have an updated RPM + last_state_update_t = last_rpm_t + self.set_EFI_State() + end + end + + -- handle an EFI packet + function self.handle_EFI_packet(frame, idx) + local id = frame:id_signed() + if id == 0x100 then + rpm = get_uint16(frame, 0) + ignition_angle = get_uint16(frame, 2) * 0.1 + throttle_angle = get_uint16(frame, 4) * 0.1 + last_rpm_t = get_time_sec() + elseif id == 0x101 then + current_load = get_uint16(frame, 0) * 0.1 + target_load = get_uint16(frame, 2) * 0.1 + inj_time = get_uint16(frame, 4) + inj_ang = get_uint16(frame, 6) * 0.1 + elseif id == 0x102 then + -- unused fields + elseif id == 0x104 then + supply_voltage = get_uint16(frame, 0) * 0.1 + ecu_temp = get_uint16(frame, 2) * 0.1 + air_pressure = get_uint16(frame, 4) + fuel_consumption_lph = get_uint16(frame,6)*0.001 + if last_fuel_s > 0 then + local dt = now_s - last_fuel_s + local fuel_lps = fuel_consumption_lph / 3600.0 + fuel_total_l = fuel_total_l + fuel_lps * dt + end + last_fuel_s = now_s + elseif id == 0x105 then + temps.cht = get_uint16(frame, 0) * 0.1 + temps.imt = get_uint16(frame, 2) * 0.1 + temps.egt = get_uint16(frame, 4) * 0.1 + end + end + + -- Build and set the EFI_State that is passed into the EFI Scripting backend + function self.set_EFI_State() + -- Cylinder_Status + cylinder_state:cylinder_head_temperature(C_TO_KELVIN(temps.cht)) + cylinder_state:exhaust_gas_temperature(C_TO_KELVIN(temps.egt)) + cylinder_state:ignition_timing_deg(ignition_angle) + cylinder_state:injection_time_ms(inj_time*0.001) + + efi_state:engine_speed_rpm(uint32_t(rpm)) + efi_state:engine_load_percent(current_load) + + efi_state:fuel_consumption_rate_cm3pm(fuel_consumption_lph * 1000.0 / 60.0) + efi_state:estimated_consumed_fuel_volume_cm3(fuel_total_l * 1000.0) + efi_state:throttle_position_percent(math.floor(throttle_angle*100.0/90.0+0.5)) + efi_state:atmospheric_pressure_kpa(air_pressure*0.1) + efi_state:ignition_voltage(supply_voltage) + efi_state:intake_manifold_temperature(C_TO_KELVIN(temps.imt)) + + -- copy cylinder_state to efi_state + efi_state:cylinder_status(cylinder_state) + + last_efi_state_time = millis() + efi_state:last_updated_ms(last_efi_state_time) + + + -- Set the EFI_State into the EFI scripting driver + efi_backend:handle_scripting(efi_state) + end + + --- send throttle command, thr is 0 to 1 + function self.send_throttle(thr) + local msg = CANFrame() + msg:id(FRM_500) + msg:data(0,1) + msg:data(1,0) + thr = math.floor(thr*1000) + msg:data(2,thr&0xFF) + msg:data(3,thr>>8) + msg:dlc(8) + driver:write_frame(msg, 10000) + end + + -- send an engine start command + function self.send_engine_start() + local msg = CANFrame() + msg:id(FRM_505) + msg:data(0,10) + msg:dlc(8) + driver:write_frame(msg, 10000) + end + + -- send an engine stop command + function self.send_engine_stop() + local msg = CANFrame() + msg:id(FRM_505) + msg:data(7,10) + msg:dlc(8) + driver:write_frame(msg, 10000) + end + + -- start generator + function self.send_generator_start() + local msg = CANFrame() + msg:id(FRM_506) + msg:data(2,10) + msg:dlc(8) + driver:write_frame(msg, 10000) + end + + -- stop generator + function self.send_generator_stop() + local msg = CANFrame() + msg:id(FRM_506) + msg:data(2,0) + msg:dlc(8) + driver:write_frame(msg, 10000) + end + + -- update starter control + function self.update_starter() + local start_fn = EFI_SP_START_FN:get() + if start_fn == 0 then + return + end + local start_state = rc:get_aux_cached(start_fn) + if start_state == 0 and engine_started then + engine_started = false + gcs:send_text(0, string.format("EFISP: stopping engine")) + engine_start_t = 0 + self.send_engine_stop() + end + if start_state == 2 and not engine_started then + engine_started = true + gcs:send_text(0, string.format("EFISP: starting engine")) + engine_start_t = get_time_sec() + self.send_engine_start() + end + local min_rpm = EFI_SP_MIN_RPM:get() + if min_rpm > 0 and engine_started and rpm < min_rpm then + local now = get_time_sec() + local dt = now - engine_start_t + if dt > 2.0 then + gcs:send_text(0, string.format("EFISP: re-starting engine")) + engine_start_t = get_time_sec() + self.send_engine_start() + end + end + end + + -- update generator control + function self.update_generator() + local gen_state = rc:get_aux_cached(EFI_SP_GEN_FN:get()) + if gen_state == 0 and generator_started then + generator_started = false + gcs:send_text(0, string.format("EFISP: stopping generator")) + self.send_generator_stop() + end + if gen_state == 2 and not generator_started then + generator_started = true + gcs:send_text(0, string.format("EFISP: starting generator")) + self.send_generator_start() + end + end + + -- update throttle output + function self.update_throttle() + local thr_func = EFI_SP_THR_FN:get() + local thr_rate = EFI_SP_THR_RATE:get() + if thr_func == 0 or thr_rate == 0 then + return + end + local now = get_time_sec() + if now - last_thr_update < 1.0 / thr_rate then + return + end + last_thr_update = now + local thr = 0.0 + local scaled = SRV_Channels:get_output_scaled(thr_func) + if thr_func == K_THROTTLE then + thr = scaled * 0.01 + elseif thr_func == K_HELIRSC then + thr = scaled * 0.001 + end + self.send_throttle(thr) + end + + -- return the instance + return self +end -- end function engine_control(_driver, _idx) + +local engine1 = engine_control(driver1, 1) + +local last_efi_state_time = 0.0 + +function update() + now_s = get_time_sec() + + if not efi_backend then + efi_backend = efi:get_backend(0) + if not efi_backend then + return + end + end + + -- Parse Driver Messages + engine1.update_telemetry() + engine1.update_starter() + engine1.update_generator() + engine1.update_throttle() +end + +gcs:send_text(0, SCRIPT_NAME .. string.format(" loaded")) + +-- wrapper around update(). This calls update() and if update faults +-- then an error is displayed, but the script is not stopped +function protected_wrapper() + local success, err = pcall(update) + if not success then + gcs:send_text(MAV_SEVERITY_ERROR, "Internal Error: " .. err) + -- when we fault we run the update function again after 1s, slowing it + -- down a bit so we don't flood the console with errors + return protected_wrapper, 1000 + end + return protected_wrapper, 1000 / EFI_SP_UPDATE_HZ:get() +end + +-- start running update loop +return protected_wrapper() diff --git a/libraries/AP_Scripting/drivers/EFI_SkyPower.md b/libraries/AP_Scripting/drivers/EFI_SkyPower.md new file mode 100644 index 00000000000..26aa004bdcd --- /dev/null +++ b/libraries/AP_Scripting/drivers/EFI_SkyPower.md @@ -0,0 +1,91 @@ +# EFI SkyPower Driver + +This driver implements support for the SkyPower range of EFI engine +control units. It supports monitoring and control of SkyPower engines. + +# Parameters + +The script used the following parameters: + +## EFI_SP_ENABLE + +this must be set to 1 to enable the driver + +## EFI_SP_CANDRV + +This sets the CAN scripting driver number to attach to. This is +normally set to 1 to use a CAN driver with CAN_Dx_PROTOCOL=10. To use +the 2nd scripting CAN driver set this to 2 and set CAN_Dx_PROTOCOL=12. + +## EFI_SP_UPDATE_HZ + +This sets the update rate of the script in Hz (how often it checks for +new data from the ECU). A value of 200 is reasonable. + +## EFI_SP_THR_FN + +This sets the SERVOn_FUNCTION number to monitor for throttle +command. For fixed wing forward throttle this should be set to 70. For +heli RSC control this should be set to 31. If set to zero then no +throttle control will be done by the driver. + +## EFI_SPI_THR_RATE + +This is the throttle output rate in Hz. A value of zero will disable +throttle control. A typical rate would be 50Hz. + +## EFI_SP_START_FN + +This is the RC option to use to monitor start control. This should be +set to one of the scripting RC options (from 300 to 307). Then an +RCn_OPTION should be set to the same value. When this switch goes high +the engine start function will be sent to the ECU. When this switch +goes low a engine stop will be sent. A value of 0 disables the starter +control. + +## EFI_SP_GEN_FN + +This is the RC option (auxiliary function) to use for generator +control. This should be set to one of the scripting RC options (from +300 to 307) if generator control is needed. Then an RCn_OPTION should +be set to the same value. When this switch goes high the generator +start function will be sent to the ECU. When this switch goes low a +generator stop will be sent. A value of 0 disables the generator +control. + +## EFI_SP_MIN_RPM + +This is the minimum running RPM. When set to a positive value then the +driver will monitor engine RPM when the engine is started and if it +drops below this value then an engine start will be sent to restart +the engine. + +# Operation + +This driver should be loaded by placing the lua script in the +APM/SCRIPTS directory on the microSD card, which can be done either +directly or via MAVFTP. The following key parameters should be set: + + - SCR_ENABLE should be set to 1 + - EFI_TYPE should be set to 7 + +then the flight controller should rebooted and parameters should be +refreshed. + +Once loaded the EFI_SP parameters will appear and should be set +according to the parameter list above. + +A 2 position RC switch should be setup with RCn_OPTION=300 (or the +value of EFI_SP_START_FN) to enable starter control. When that switch +goes high the engine will be started. When it goes low the engine will +be stopped. + +The GCS will receive EFI_STATUS MAVLink messages which includes RPM, +cylinder head temperature, exhaust gas temperature, injection timing, +engine load, fuel consumption rate, throttle position atmospheric +pressure and ignition voltage. + +Setting EFI_SP_RPM_MIN allows for automatic in-flight engine +restart. If the engine RPM drops below this EFI_SP_RPM_MIN for 2 +seconds while the engine should be started then an engine start +command will be sent to restart the engine. diff --git a/libraries/AP_Scripting/examples/Aerobatics/Missions/plane_aerobatics.lua b/libraries/AP_Scripting/examples/Aerobatics/Missions/plane_aerobatics.lua index 5ef1524ba33..f04c65a372c 100644 --- a/libraries/AP_Scripting/examples/Aerobatics/Missions/plane_aerobatics.lua +++ b/libraries/AP_Scripting/examples/Aerobatics/Missions/plane_aerobatics.lua @@ -1,7 +1,7 @@ --[[ perform simple aerobatic manoeuvres in AUTO mode cmd = 1: axial rolls, arg1 = roll rate dps, arg2 = number of rolls cmd = 2: loops or 180deg return, arg1 = pitch rate dps, arg2 = number of loops, if zero do a 1/2 cuban8-like return -cmd = 3: rolling circle, arg1 = radius, arg2 = number of rolls +cmd = 3: rolling circle, arg1 = earth frame yaw rate, dps, arg2 = roll rate, dps cmd = 4: knife edge at any angle, arg1 = roll angle to hold, arg2 = duration cmd = 5: pause, holding heading and alt to allow stabilization after a move, arg1 = duration in seconds ]]-- @@ -164,7 +164,7 @@ local function PI_controller(kP,kI,iMax) -- log the controller internals function self.log(name, add_total) -- allow for an external addition to total - logger.write(name,'Targ,Curr,P,I,Total,Add','ffffff',_target,_current,_P,_I,_total,add_total) + logger:write(name,'Targ,Curr,P,I,Total,Add','ffffff',_target,_current,_P,_I,_total,add_total) end -- return the instance return self @@ -342,7 +342,7 @@ local rolling_circle_yaw = 0 local rolling_circle_last_ms = 0 function do_rolling_circle(arg1, arg2) - -- constant roll rate circle roll, arg1 radius of circle, positive to right, neg to left, arg2 is number of rolls to do + -- constant roll rate circle roll, arg1 = earth frame yaw rate, dps, positive to right, neg to left, arg2 = roll rate, dps if not running then running = true rolling_circle_stage = 0 diff --git a/libraries/AP_Scripting/examples/Aerobatics/Via_Switch/10_loops-and-immelman.lua b/libraries/AP_Scripting/examples/Aerobatics/Via_Switch/10_loops-and-immelman.lua index c5aa5b9a2f4..9627cc0cc93 100644 --- a/libraries/AP_Scripting/examples/Aerobatics/Via_Switch/10_loops-and-immelman.lua +++ b/libraries/AP_Scripting/examples/Aerobatics/Via_Switch/10_loops-and-immelman.lua @@ -139,7 +139,7 @@ local function PI_controller(kP,kI,iMax) -- log the controller internals function self.log(name, add_total) -- allow for an external addition to total - logger.write(name,'Targ,Curr,P,I,Total,Add','ffffff',_target,_current,_P,_I,_total,add_total) + logger:write(name,'Targ,Curr,P,I,Total,Add','ffffff',_target,_current,_P,_I,_total,add_total) end -- return the instance return self diff --git a/libraries/AP_Scripting/examples/Aerobatics/Via_Switch/5_knifedges.lua b/libraries/AP_Scripting/examples/Aerobatics/Via_Switch/5_knifedges.lua index 777024ee5ef..5aa317f5b34 100644 --- a/libraries/AP_Scripting/examples/Aerobatics/Via_Switch/5_knifedges.lua +++ b/libraries/AP_Scripting/examples/Aerobatics/Via_Switch/5_knifedges.lua @@ -104,7 +104,7 @@ local function PI_controller(kP,kI,iMax) -- log the controller internals function self.log(name, add_total) -- allow for an external addition to total - logger.write(name,'Targ,Curr,P,I,Total,Add','ffffff',_target,_current,_P,_I,_total,add_total) + logger:write(name,'Targ,Curr,P,I,Total,Add','ffffff',_target,_current,_P,_I,_total,add_total) end -- return the instance return self diff --git a/libraries/AP_Scripting/examples/CAN_MiniCheetah_drive.lua b/libraries/AP_Scripting/examples/CAN_MiniCheetah_drive.lua index de9aefcb643..a06f15b7629 100644 --- a/libraries/AP_Scripting/examples/CAN_MiniCheetah_drive.lua +++ b/libraries/AP_Scripting/examples/CAN_MiniCheetah_drive.lua @@ -2,7 +2,7 @@ -- https://os.mbed.com/users/benkatz/code/HKC_MiniCheetah/docs/tip/CAN__com_8cpp_source.html -- Load CAN driver with a buffer size of 20 -local driver = CAN.get_device(20) +local driver = CAN:get_device(20) local target_ID = uint32_t(1) diff --git a/libraries/AP_Scripting/examples/CAN_read.lua b/libraries/AP_Scripting/examples/CAN_read.lua index 4e1276ddad2..ca310faf3e0 100644 --- a/libraries/AP_Scripting/examples/CAN_read.lua +++ b/libraries/AP_Scripting/examples/CAN_read.lua @@ -1,19 +1,36 @@ -- This script is an example of reading from the CAN bus --- Load CAN driver, using the scripting protocol and with a buffer size of 5 -local driver = CAN.get_device(5) +-- Load CAN driver1. The first will attach to a protocol of 10, the 2nd to a protocol of 12 +-- this allows the script to distinguish packets on two CAN interfaces +local driver1 = CAN:get_device(5) +local driver2 = CAN:get_device2(5) -function update() +if not driver1 and not driver2 then + gcs:send_text(0,"No scripting CAN interfaces found") + return +end - -- Read a message from the buffer - frame = driver:read_frame() +function show_frame(dnum, frame) + gcs:send_text(0,string.format("CAN[%u] msg from " .. tostring(frame:id()) .. ": %i, %i, %i, %i, %i, %i, %i, %i", dnum, frame:data(0), frame:data(1), frame:data(2), frame:data(3), frame:data(4), frame:data(5), frame:data(6), frame:data(7))) +end + +function update() - if frame then - -- note that we have to be careful to keep the ID as a uint32_t userdata to retain precision - gcs:send_text(0,string.format("CAN msg from " .. tostring(frame:id()) .. ": %i, %i, %i, %i, %i, %i, %i, %i", frame:data(0), frame:data(1), frame:data(2), frame:data(3), frame:data(4), frame:data(5), frame:data(6), frame:data(7))) - end + -- see if we got any frames + if driver1 then + frame = driver1:read_frame() + if frame then + show_frame(1, frame) + end + end + if driver2 then + frame = driver2:read_frame() + if frame then + show_frame(2, frame) + end + end - return update, 100 + return update, 10 end diff --git a/libraries/AP_Scripting/examples/CAN_write.lua b/libraries/AP_Scripting/examples/CAN_write.lua index bb715af2f7f..30763917519 100644 --- a/libraries/AP_Scripting/examples/CAN_write.lua +++ b/libraries/AP_Scripting/examples/CAN_write.lua @@ -1,7 +1,7 @@ -- This script is an example of writing to CAN bus -- Load CAN driver, using the scripting protocol and with a buffer size of 5 -local driver = CAN.get_device(5) +local driver = CAN:get_device(5) -- transfer ID of the message were sending local Transfer_ID = 0 diff --git a/libraries/AP_Scripting/examples/EFI_tester.lua b/libraries/AP_Scripting/examples/EFI_tester.lua new file mode 100644 index 00000000000..0d44bee207f --- /dev/null +++ b/libraries/AP_Scripting/examples/EFI_tester.lua @@ -0,0 +1,231 @@ +--[[ + simulator for CAN EFI + this can be used with a loopback cable between CAN1 and CAN2 to test CAN EFI Drivers +--]] + +local driver2 = CAN.get_device2(25) +if not driver2 then + gcs:send_text(0,string.format("EFISIM: Failed to load CAN driver")) + return +end + +local PARAM_TABLE_KEY = 13 +local PARAM_TABLE_PREFIX = "EFISIM_" + +-- add a parameter and bind it to a variable +function bind_add_param(name, idx, default_value) + assert(param:add_param(PARAM_TABLE_KEY, idx, name, default_value), string.format('could not add param %s', name)) + return Parameter(PARAM_TABLE_PREFIX .. name) +end + +assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 2), 'could not add param table') + +local EFISIM_TYPE = bind_add_param('TYPE', 1, 0) +local EFISIM_RATE_HZ = bind_add_param('RATE_HZ', 2, 100) + +function get_time_sec() + return millis():tofloat() * 0.001 +end + +local FRM_100 = uint32_t(0x100) +local FRM_101 = uint32_t(0x101) +local FRM_102 = uint32_t(0x102) +local FRM_104 = uint32_t(0x104) +local FRM_105 = uint32_t(0x105) +local FRM_106 = uint32_t(0x106) +local FRM_10A = uint32_t(0x10A) +local FRM_10C = uint32_t(0x10C) +local FRM_10D = uint32_t(0x10D) +local FRM_10F = uint32_t(0x10F) +local FRM_113 = uint32_t(0x113) +local FRM_114 = uint32_t(0x114) +local FRM_115 = uint32_t(0x115) + +function put_u8(msg, ofs, v) + msg:data(ofs,v&0xFF) +end + +function put_u16(msg, ofs, v) + msg:data(ofs,v&0xFF) + msg:data(ofs+1,v>>8) +end + +function put_u32(msg, ofs, v) + msg:data(ofs+0,v&0xFF) + msg:data(ofs+1,(v>>8)&0xFF) + msg:data(ofs+2,(v>>16)&0xFF) + msg:data(ofs+3,(v>>24)&0xFF) +end + +local rev_counter = 0 + +--[[ + send SkyPower data. Called at 100Hz +--]] +function send_SkyPower(driver) + + --local msg = CANFrame() + local t = get_time_sec() + + local RPM = 1200 + math.floor(1000*math.sin(t)) + rev_counter = rev_counter + (RPM/60.0)*0.01 + + -- 0x100 + local msg = CANFrame() + msg:id(FRM_100) + put_u16(msg,0,RPM) + put_u16(msg,2,13*10) -- ignition angle + put_u16(msg,4,45*10) -- throttle angle + msg:dlc(8) + driver:write_frame(msg, 10000) + + -- 0x101 + msg = CANFrame() + msg:id(FRM_101) + put_u16(msg,2,917) -- air pressure + msg:dlc(8) + driver:write_frame(msg, 10000) + + -- 0x102 + msg = CANFrame() + msg:id(FRM_102) + put_u16(msg,0,7*10) -- ingition gap + put_u16(msg,2,270*10) -- injection angle + put_u16(msg,4,37000) -- injection time + msg:dlc(8) + driver:write_frame(msg, 10000) + + -- 0x104 + msg = CANFrame() + msg:id(FRM_104) + put_u16(msg,0,math.floor(14.8*10)) -- supply voltage + msg:dlc(8) + driver:write_frame(msg, 10000) + + -- 0x105 + msg = CANFrame() + msg:id(FRM_105) + put_u16(msg,0,172*10) -- engine temp head 1 + put_u16(msg,2,65*10) -- air temp + put_u16(msg,4,320*10) -- exhaust temp + put_u16(msg,6,113*10) -- ecu temp + msg:dlc(8) + driver:write_frame(msg, 10000) + + -- 0x106 + msg = CANFrame() + msg:id(FRM_106) + put_u32(msg,0,math.floor(rev_counter)) + put_u8(msg,4,math.floor(t)) + put_u8(msg,5,math.floor(t/60)) + put_u16(msg,6,math.floor(t/3600)) + msg:dlc(8) + driver:write_frame(msg, 10000) + + -- 0x10A + msg = CANFrame() + msg:id(FRM_10A) + put_u16(msg,6,72*10) -- target load + msg:dlc(8) + driver:write_frame(msg, 10000) + + -- 0x10C + msg = CANFrame() + msg:id(FRM_10C) + put_u16(msg,4,145*10) -- engine head temp 2 + put_u16(msg,6,315*10) -- exhaust temp 2 + msg:dlc(8) + driver:write_frame(msg, 10000) + + -- 0x10D + msg = CANFrame() + msg:id(FRM_10D) + put_u16(msg,4,72*10) -- current load + msg:dlc(8) + driver:write_frame(msg, 10000) + + -- 0x10F + msg = CANFrame() + msg:id(FRM_10F) + put_u16(msg,4,2*10) -- fuel consumption + msg:dlc(8) + driver:write_frame(msg, 10000) + + -- 0x113 + msg = CANFrame() + msg:id(FRM_113) + put_u16(msg,2,1*10) -- gen amps + msg:dlc(8) + driver:write_frame(msg, 10000) + + -- 0x114 + msg = CANFrame() + msg:id(FRM_114) + put_u16(msg,2,2400*10) -- gen RPM + msg:dlc(8) + driver:write_frame(msg, 10000) + + -- 0x115 + msg = CANFrame() + msg:id(FRM_115) + put_u16(msg,4,30*100) -- gen current + msg:dlc(8) + driver:write_frame(msg, 10000) +end + +--[[ + send HFE data. Called at 100Hz +--]] +function send_HFE(driver) + + --local msg = CANFrame() + local t = get_time_sec() + + local RPM = 1200 + math.floor(1000*math.sin(t)) + rev_counter = rev_counter + (RPM/60.0)*0.01 + + -- fast telem + local msg = CANFrame() + local base_id = uint32_t(0x88000005) + msg:id(base_id | 0x00000) + put_u16(msg,1,RPM) + msg:dlc(8) + driver:write_frame(msg, 10000) + + -- slow telem0 + msg = CANFrame() + msg:id(base_id | 0x10000) + put_u16(msg,5,101324/2) -- air pressure + msg:dlc(8) + driver:write_frame(msg, 10000) + + -- slow telem1 + msg = CANFrame() + msg:id(base_id | 0x20000) + put_u8(msg,0,35) -- inlet air temp, signed, deg C + msg:dlc(8) + driver:write_frame(msg, 10000) + + -- slow telem2 + msg = CANFrame() + msg:id(base_id | 0x30000) + put_u8(msg,1,math.floor((67+128)/1.5)) -- MAT + put_u16(msg,6,173) -- fuel flow in grams/hr + msg:dlc(8) + driver:write_frame(msg, 10000) + + +end + +function update() + if EFISIM_TYPE:get() == 1 then + send_SkyPower(driver2) + elseif EFISIM_TYPE:get() == 2 then + send_HFE(driver2) + end + return update, math.floor(1000/EFISIM_RATE_HZ:get()) +end + +gcs:send_text(0,string.format("EFISIM: loaded")) + +return update() diff --git a/libraries/AP_Scripting/examples/OOP_example.lua b/libraries/AP_Scripting/examples/OOP_example.lua index feb37612318..0172393ba02 100644 --- a/libraries/AP_Scripting/examples/OOP_example.lua +++ b/libraries/AP_Scripting/examples/OOP_example.lua @@ -57,7 +57,7 @@ local function PIFF(kFF,kP,kI,iMax) -- log the controller internals function self.log(name) - logger.write(name,'Targ,Curr,FF,P,I,Total','ffffff',table.unpack(_log_data)) + logger:write(name,'Targ,Curr,FF,P,I,Total','ffffff',table.unpack(_log_data)) end -- return the instance @@ -110,7 +110,7 @@ function PIFF2.update(self, target, current) end function PIFF2.log(self, name) - logger.write(name,'Targ,Curr,FF,P,I,Total','ffffff',table.unpack(self.log_data)) + logger:write(name,'Targ,Curr,FF,P,I,Total','ffffff',table.unpack(self.log_data)) end --[[ diff --git a/libraries/AP_Scripting/examples/RC_override.lua b/libraries/AP_Scripting/examples/RC_override.lua new file mode 100644 index 00000000000..52b19f2945c --- /dev/null +++ b/libraries/AP_Scripting/examples/RC_override.lua @@ -0,0 +1,14 @@ +-- example of overriding RC inputs + +local RC4 = rc:get_channel(4) + +function update() + -- mirror RC1 onto RC4 + rc1_input = rc:get_pwm(1) + RC4:set_override(rc1_input) + return update, 10 +end + +gcs:send_text(0, "RC_override example") + +return update() diff --git a/libraries/AP_Scripting/examples/SN-GCJA5-particle-sensor.lua b/libraries/AP_Scripting/examples/SN-GCJA5-particle-sensor.lua index 9fbe0ea9761..08a1f2ad8d2 100644 --- a/libraries/AP_Scripting/examples/SN-GCJA5-particle-sensor.lua +++ b/libraries/AP_Scripting/examples/SN-GCJA5-particle-sensor.lua @@ -28,7 +28,7 @@ file:write('Lattitude (°), Longitude (°), Absolute Altitude (m), PM 1.0, PM 2. file:close() -- load the i2c driver, bus 0 -local sensor = i2c.get_device(0,0x33) +local sensor = i2c:get_device(0,0x33) sensor:set_retries(10) -- register names @@ -173,7 +173,7 @@ function update() -- this is the loop which periodically runs file:close() -- save to data flash - logger.write('PART','PM1,PM2.5,PM10,Cnt0.5,Cnt1,Cnt2.5,Cnt5,Cnt7.5,Cnt10','fffffffff',PM1_0,PM2_5,PM10,PC0_5,PC1_0,PC2_5,PC5_0,PC7_5,PC10) + logger:write('PART','PM1,PM2.5,PM10,Cnt0.5,Cnt1,Cnt2.5,Cnt5,Cnt7.5,Cnt10','fffffffff',PM1_0,PM2_5,PM10,PC0_5,PC1_0,PC2_5,PC5_0,PC7_5,PC10) -- send to GCS gcs:send_named_float('PM 1.0',PM1_0) diff --git a/libraries/AP_Scripting/examples/UART_log.lua b/libraries/AP_Scripting/examples/UART_log.lua index 9cc425c3b92..28b91b0ee2c 100644 --- a/libraries/AP_Scripting/examples/UART_log.lua +++ b/libraries/AP_Scripting/examples/UART_log.lua @@ -100,7 +100,7 @@ function update() -- format characters specify the type of variable to be logged, see AP_Logger/README.md -- not all format types are supported by scripting only: i, L, e, f, n, M, B, I, E, N, and Z -- Note that Lua automatically adds a timestamp in micro seconds - logger.write('SCR','Sensor1, Sensor2, Sensor3','fff',table.unpack(log_data)) + logger:write('SCR','Sensor1, Sensor2, Sensor3','fff',table.unpack(log_data)) -- reset for the next message log_data = {} diff --git a/libraries/AP_Scripting/examples/active_source_set.lua b/libraries/AP_Scripting/examples/active_source_set.lua new file mode 100644 index 00000000000..a149086d78d --- /dev/null +++ b/libraries/AP_Scripting/examples/active_source_set.lua @@ -0,0 +1,12 @@ + +--returns active source set used by EKF3 +-- can be used for infering the current source set in use without RC for autonomous source switching + +function update() -- this is the loop which periodically runs + + gcs:send_text(0, string.format("current source set in use :%d", ahrs:get_posvelyaw_source_set())) + + return update, 1000 -- 1000ms reschedules the loop (1Hz) +end + +return update() -- run immediately before starting to reschedule diff --git a/libraries/AP_Scripting/examples/ahrs-set-origin.lua b/libraries/AP_Scripting/examples/ahrs-set-origin.lua index 0e12e544e8f..37ec058d2cd 100644 --- a/libraries/AP_Scripting/examples/ahrs-set-origin.lua +++ b/libraries/AP_Scripting/examples/ahrs-set-origin.lua @@ -12,7 +12,7 @@ function update () location = Location() location:lat(-353632640) location:lng(1491652352) location:alt(58409) if ahrs:set_origin(location) then - gcs:send_text(0, string.format("Origin Set - Lat:%.7f Long:%.7f Alt:%.1f", location:lat()/10000000, location:lng()/10000000, location:alt()/100)) + gcs:send_text(6, string.format("Origin Set - Lat:%.7f Long:%.7f Alt:%.1f", location:lat()/10000000, location:lng()/10000000, location:alt()/100)) else gcs:send_text(0, "Refused to set EKF origin") end diff --git a/libraries/AP_Scripting/examples/aux_cached.lua b/libraries/AP_Scripting/examples/aux_cached.lua new file mode 100644 index 00000000000..de3dde1fff2 --- /dev/null +++ b/libraries/AP_Scripting/examples/aux_cached.lua @@ -0,0 +1,37 @@ +--[[ + example for getting cached aux function value +--]] + +local RATE_HZ = 10 + +local MAV_SEVERITY_ERROR = 3 +local MAV_SEVERITY_INFO = 6 + +local AUX_FUNCTION_NUM = 302 + +local last_func_val = nil +local last_aux_pos = nil + +function update() + local aux_pos = rc:get_aux_cached(AUX_FUNCTION_NUM) + if aux_pos ~= last_aux_pos then + last_aux_pos = aux_pos + gcs:send_text(MAV_SEVERITY_INFO, string.format("Aux set to %u", aux_pos)) + end +end + +-- wrapper around update(). This calls update() and if update faults +-- then an error is displayed, but the script is not stopped +function protected_wrapper() + local success, err = pcall(update) + if not success then + gcs:send_text(MAV_SEVERITY_ERROR, "Internal Error: " .. err) + -- when we fault we run the update function again after 1s, slowing it + -- down a bit so we don't flood the console with errors + return protected_wrapper, 1000 + end + return protected_wrapper, math.floor(1000 / RATE_HZ) +end + +-- start running update loop +return protected_wrapper() diff --git a/libraries/AP_Scripting/examples/copter-deadreckon-home.lua b/libraries/AP_Scripting/examples/copter-deadreckon-home.lua new file mode 100644 index 00000000000..8fc421386c7 --- /dev/null +++ b/libraries/AP_Scripting/examples/copter-deadreckon-home.lua @@ -0,0 +1,356 @@ +-- Copter attempts to fly home using dead reckoning if the GPS quality deteriorates or an EKF failsafe triggers +-- +-- CAUTION: This script only works for Copter 4.3 (and higher) +-- this script checks for low GPS quality and/or an EKF failsafe and if either occurs, flies in the last known direction towards home +-- +-- DR_ENABLE : 1 = enabled, 0 = disabled +-- DR_ENABLE_DIST : distance from home (in meters) beyond which the dead reckoning will be enabled +-- DR_GPS_SACC_MAX : GPS speed accuracy maximum, above which deadreckoning home will begin (default is 0.8). Lower values trigger with good GPS quality, higher values will allow poorer GPS before triggering. Set to 0 to disable use of GPS speed accuracy. +-- DR_GPS_SAT_MIN : GPS satellite count threshold below which deadreckoning home will begin (default is 6). Higher values trigger with good GPS quality, Lower values trigger with worse GPS quality. Set to 0 to disable use of GPS satellite count. +-- DR_GPS_TRIGG_SEC : GPS checks must fail for this many seconds before dead reckoning will be triggered. +-- DR_FLY_ANGLE : lean angle (in degrees) during deadreckoning. Most vehicles reach maximum speed at 22deg +-- DR_FLY_ALT_MIN : min alt (above home in meters) during deadreckoning. zero to return at current alt +-- DR_FLY_TIMEOUT : timeout (in seconds). Vehicle will attempt to switch to NEXT_MODE after this many seconds of deadreckoning. If it cannot switch modes it will continue in Guided_NoGPS. Set to 0 to disable timeout +-- DR_NEXT_MODE : flight mode vehicle will change to when GPS / EKF recovers or DR_FLY_TIMEOUT expires. Default is 6=RTL, see FLTMODE1 parameter description for list of flight mode number. Set to -1 to return to mode used before deadreckoning was triggered + +-- How to use: +-- 1. set SCR_ENABLE = 1 to enable scripting (and reboot the autopilot) +-- 2. set SCR_HEAP_SIZE to 80000 or higher to allocate enough memory for this script +-- 3. set DR_ENABLE = 1 to enable dead reckoning +-- 4. optionally set DR_GPS_SACC_MAX and/or DR_GPS_SAT_MIN parameters to adjust how bad the GPS quality must be before triggering +-- 5. confirm "DR: waiting for dist (Xm < 50m)" message is displayed on ground station (so you know script is working) +-- 6. arm and takeoff to a safe altitude +-- 7. fly at least DR_ENABLE_DIST meters from home and confirm "DR: activated!" is displayed on ground station +-- +-- If this script senses low GPS quality or an EKF failsafe triggers: +-- - vehicle will change to Guided_NoGPS mode +-- - vehicle will lean in the last known direction of home (see DR_FLY_ANGLE) +-- - if GPS recovers or EKF failsafe is cleared the vehicle will switch to DR_NEXT_MODE (if -1 then it will switch back to the mode in use before the GPS/EKF failure) +-- - if the timeout is surpassed (see DR_FLY_TIMEOUT) the vehicle will try to switch to DR_NEXT_MODE. If it fails to change it will continue in Guided_NoGPS but keep trying to change mode +-- - the pilot can retake control by switching to an "unprotected" mode like AltHold, Loiter (see "protected_mode_array" below) +-- +-- Testing in SITL: +-- a. set map setshowsimpos 1 (to allow seeing where vehicle really is in simulator even with GPS disabled) +-- b. set SIM_GPS_DISABLE = 1 to disable GPS (confirm dead reckoning begins) +-- c. set SIM_GPS_DISABLE = 0 to re-enable GPS +-- d. set SIM_GPS_NUMSAT = 3 to lower simulated satellite count to confirm script triggers +-- e. set DR_GPS_SACC_MAX = 0.01 to lower the threshold and trigger below the simulator value which is 0.04 (remember to set this back after testing!) +-- +-- Test on a real vehicle: +-- A. set DR_FLY_TIMEOUT to a low value (e.g. 5 seconds) +-- B. fly the vehicle at least DR_DIST_MIN meters from home and confirm the "DR: activated!" message is displayed +-- C. set GPS_TYPE = 0 to disable GPS and confirm the vehicle begins deadreckoning after a few seconds +-- D. restore GPS_TYPE to its original value (normally 1) and confirm the vehicle switches to DR_NEXT_MODE +-- E. restore DR_FLY_TIMEOUT to a higher value for real-world use +-- Note: Instaed of setting GPS_TYPE, an auxiliary function switch can be setup to disable the GPS (e.g. RC9_OPTION = 65/"Disable GPS") +-- +-- Testing that it does not require RC (in SITL): +-- a. set FS_OPTIONS's "Continue if in Guided on RC failsafe" bit +-- b. set FS_GCS_ENABLE = 1 (to enable GCS failsafe otherwise RC failsafe will trigger anyway) +-- c. optionally set SYSID_MYGCS = 77 (or almost any other unused system id) to trick the above check so that GCS failsafe can really be disabled +-- d. set SIM_RC_FAIL = 1 (to simulate RC failure, note vehicle keeps flying) +-- e. set SIM_RC_FAIL = 0 (to simulate RC recovery) +-- +-- Test with wind (in SITL) +-- a. SIM_WIND_DIR <-- sets direction wind is coming from +-- b. SIM_WIND_SPD <-- sets wind speed in m/s +-- + +-- create and initialise parameters +local PARAM_TABLE_KEY = 86 -- parameter table key must be used by only one script on a particular flight controller +assert(param:add_table(PARAM_TABLE_KEY, "DR_", 9), 'could not add param table') +assert(param:add_param(PARAM_TABLE_KEY, 1, 'ENABLE', 1), 'could not add DR_ENABLE param') -- 1 = enabled, 0 = disabled +assert(param:add_param(PARAM_TABLE_KEY, 2, 'ENABLE_DIST', 50), 'could not add DR_ENABLE_DIST param') -- distance from home (in meters) beyond which the dead reckoning will be enabled +assert(param:add_param(PARAM_TABLE_KEY, 3, 'GPS_SACC_MAX', 0.8), 'could not add DR_GPS_SACC_MAX param') -- GPS speed accuracy max threshold +assert(param:add_param(PARAM_TABLE_KEY, 4, 'GPS_SAT_MIN', 6), 'could not add DR_GPS_SAT_MIN param') -- GPS satellite count min threshold +assert(param:add_param(PARAM_TABLE_KEY, 5, 'GPS_TRIGG_SEC', 3), 'could not add DR_GPS_TRIGG_SEC parameter') -- GPS checks must fail for this many seconds before dead reckoning will be triggered + +assert(param:add_param(PARAM_TABLE_KEY, 6, 'FLY_ANGLE', 10), 'could not add DR_FLY_ANGLE param') -- lean angle (in degrees) during deadreckoning +assert(param:add_param(PARAM_TABLE_KEY, 7, 'FLY_ALT_MIN', 0), 'could not add DR_FLY_ALT_MIN param') -- min alt above home (in meters) during deadreckoning. zero to return at current alt +assert(param:add_param(PARAM_TABLE_KEY, 8, 'FLY_TIMEOUT', 30), 'could not add DR_FLY_TIMEOUT param')-- deadreckoning timeout (in seconds) +assert(param:add_param(PARAM_TABLE_KEY, 9, 'NEXT_MODE', 6), 'could not add DR_NEXT_MODE param') -- mode to switch to after GPS recovers or timeout elapses + +-- bind parameters to variables +function bind_param(name) + local p = Parameter() + assert(p:init(name), string.format('could not find %s parameter', name)) + return p +end +local enable = bind_param("DR_ENABLE") -- 1 = enabled, 0 = disabled +local enable_dist = bind_param("DR_ENABLE_DIST") -- distance from home (in meters) beyond which the dead reckoning will be enabled +local gps_speed_acc_max = bind_param("DR_GPS_SACC_MAX") -- GPS speed accuracy max threshold +local gps_sat_count_min = bind_param("DR_GPS_SAT_MIN") -- GPS satellite count min threshold +local gps_trigger_sec = bind_param("DR_GPS_TRIGG_SEC") -- GPS checks must fail for this many seconds before dead reckoning will be triggered +local fly_angle = bind_param("DR_FLY_ANGLE") -- lean angle (in degrees) during deadreckoning +local fly_alt_min = bind_param("DR_FLY_ALT_MIN") -- min alt above home (in meters) during deadreckoning +local fly_timeoout = bind_param("DR_FLY_TIMEOUT") -- deadreckoning timeout (in seconds) +local next_mode = bind_param("DR_NEXT_MODE") -- mode to switch to after GPS recovers or timeout elapses +local wpnav_speedup = bind_param("WPNAV_SPEED_UP") -- maximum climb rate from WPNAV_SPEED_UP +local wpnav_accel_z = bind_param("WPNAV_ACCEL_Z") -- maximum vertical acceleration from WPNAV_ACCEL_Z + +-- modes deadreckoning may be activated from +-- comment out lines below to remove protection from these modes +local protected_mode_array = { + 3, -- AUTO + 4, -- GUIDED + --5, -- LOITER + 6, -- RTL + 7, -- CIRCLE + 9, -- LAND + --11, -- DRIFT + --16, -- POSHOLD + 17, -- BRAKE + 21, -- SMART_RTL + 27, -- AUTO_RTL + } +function is_protected_mode() + local curr_mode = vehicle:get_mode() + for i = 1, #protected_mode_array do + if curr_mode == protected_mode_array[i] then + return true + end + end + return false +end + +local copter_guided_nogps_mode = 20 -- Guided_NoGPS is mode 20 on Copter +local copter_RTL_mode = 6 -- RTL is mode 6 on Copter +local recovery_delay_ms = 3000 -- switch to NEXT_MODE happens this many milliseconds after GPS and EKF failsafe recover + +local gps_bad = false -- true if GPS is failing checks +local ekf_bad = false -- true if EKF failsafe has triggered +local gps_or_ekf_bad = true -- true if GPS and/or EKF is bad, true once both have recovered + +local flight_stage = 0 -- 0. wait for good-gps and dist-from-home, 1=wait for bad gps or ekf, 2=level vehicle, 3=deadreckon home +local gps_bad_start_time_ms = 0 -- system time GPS quality went bad (0 if not bad) +local recovery_start_time_ms = 0-- system time GPS quality and EKF failsafe recovered (0 if not recovered) +local fly_start_time_ms = 0 -- system time fly using deadreckoning started + +local home_dist = 0 -- distance to home in meters +local home_yaw = 0 -- direction to home in degrees + +local target_yaw = 0 -- deg +local climb_rate = 0 -- m/s + +local stage1_flight_mode = nil -- flight mode vehicle was in during stage1 (may be used during recovery) +local stage2_start_time_ms -- system time stage2 started (level vehicle) +local stage3_start_time_ms -- system time stage3 started (deadreckon home) +local last_print_ms = 0 -- pilot update timer +local interval_ms = 100 -- update at 10hz + +function update() + + -- exit immediately if not enabled + if (enable:get() < 1) then + return update, 1000 + end + + -- determine if progress update should be sent to user + local now_ms = millis() + local update_user = false + if (now_ms - last_print_ms > 5000) then + last_print_ms = now_ms + update_user = true + end + + -- check GPS + local gps_primary = gps:primary_sensor() + local gps_speed_acc = gps:speed_accuracy(gps:primary_sensor()) + if gps_speed_acc == nil then + gps_speed_acc = 99 + end + local gps_speed_acc_bad = ((gps_speed_acc_max:get() > 0) and (gps_speed_acc > gps_speed_acc_max:get())) + local gps_num_sat = gps:num_sats(gps:primary_sensor()) + local gps_num_sat_bad = (gps_sat_count_min:get() > 0) and ((gps_num_sat == nil) or (gps:num_sats(gps:primary_sensor()) < gps_sat_count_min:get())) + if gps_bad then + -- GPS is bad, check for recovery + if (not gps_speed_acc_bad and not gps_num_sat_bad) then + gps_bad = false + end + else + -- GPS is good, check for GPS going bad + if (gps_speed_acc_bad or gps_num_sat_bad) then + if (gps_bad_start_time_ms == 0) then + -- start gps bad timer + gps_bad_start_time_ms = now_ms + elseif (now_ms - gps_bad_start_time_ms > gps_trigger_sec:get()) then + gps_bad = true + end + end + end + + -- check EKF failsafe + local fs_ekf = vehicle:has_ekf_failsafed() + if not (ekf_bad == fs_ekf) then + ekf_bad = fs_ekf + end + + -- check for GPS and/or EKF going bad + if not gps_or_ekf_bad and (gps_bad or ekf_bad) then + gps_or_ekf_bad = true + gcs:send_text(0, "DR: GPS or EKF bad") + end + + -- check for GPS and/or EKF recovery + if (gps_or_ekf_bad and (not gps_bad and not ekf_bad)) then + -- start recovery timer + if recovery_start_time_ms == 0 then + recovery_start_time_ms = now_ms + end + if (now_ms - recovery_start_time_ms > recovery_delay_ms) then + gps_or_ekf_bad = false + recovery_start_time_ms = 0 + gcs:send_text(0, "DR: GPS and EKF recovered") + end + end + + -- update distance and direction home while GPS and EKF are good + if (not gps_or_ekf_bad) then + local home = ahrs:get_home() + local curr_loc = ahrs:get_location() + if home and curr_loc then + home_dist = curr_loc:get_distance(home) + home_yaw = math.deg(curr_loc:get_bearing(home)) + elseif (update_user) then + -- warn user of unexpected failure + gcs:send_text(0, "DR: could not get home or vehicle location") + end + end + + -- reset flight_stage when disarmed + if not arming:is_armed() then + flight_stage = 0 + fly_start_time_ms = 0 + transition_start_time_ms = 0 + return update, interval_ms + end + + -- flight_stage 0: wait for good gps and dist-from-home + if (flight_stage == 0) then + + -- wait for GPS and EKF to be good + if (gps_or_ekf_bad) then + return update, interval_ms + end + + -- wait for distance from home to pass DR_ENABLE_DIST + if ((home_dist > 0) and (home_dist >= enable_dist:get())) then + gcs:send_text(5, "DR: enabled") + flight_stage = 1 + elseif (update_user) then + gcs:send_text(5, "DR: waiting for dist:" .. tostring(math.floor(home_dist)) .. " need:" .. tostring(math.floor(enable_dist:get()))) + end + return update, interval_ms + end + + -- flight_stage 1: wait for bad gps or ekf + if (flight_stage == 1) then + if (gps_or_ekf_bad and is_protected_mode()) then + -- change to Guided_NoGPS and initialise stage2 + if (vehicle:set_mode(copter_guided_nogps_mode)) then + flight_stage = 2 + target_yaw = math.deg(ahrs:get_yaw()) + stage2_start_time_ms = now_ms + else + -- warn user of unexpected failure + if (update_user) then + gcs:send_text(5, "DR: failed to change to Guided_NoGPS mode") + end + end + else + -- store flight mode (may be used during recovery) + stage1_flight_mode = vehicle:get_mode() + end + return update, interval_ms + end + + -- flight_stage 2: level vehicle for 5 seconds + if (flight_stage == 2) then + -- allow pilot to retake control + if (vehicle:get_mode() ~= copter_guided_nogps_mode) then + gcs:send_text(5, "DR: pilot retook control") + flight_stage = 1 + return update, interval_ms + end + + -- level vehicle for 5 seconds + climb_rate = 0 + vehicle:set_target_angle_and_climbrate(0, 0, target_yaw, climb_rate, false, 0) + if ((now_ms - stage2_start_time_ms) >= 5000) then + flight_stage = 3 + stage3_start_time_ms = now_ms + gcs:send_text(5, "DR: flying home") + end + if (update_user) then + gcs:send_text(5, "DR: leveling vehicle") + end + return update, interval_ms + end + + -- flight_stage 3: deadreckon towards home + if (flight_stage == 3) then + + -- allow pilot to retake control + if (vehicle:get_mode() ~= copter_guided_nogps_mode) then + gcs:send_text(5, "DR: pilot retook control") + flight_stage = 1 + return update, interval_ms + end + + -- check for timeout + local time_elapsed_ms = now_ms - stage3_start_time_ms + local timeout = (fly_timeoout:get() > 0) and (time_elapsed_ms >= (fly_timeoout:get() * 1000)) + + -- calculate climb rate in m/s + if (fly_alt_min:get() > 0) then + local curr_alt_below_home = ahrs:get_relative_position_D_home() + if curr_alt_below_home then + local target_alt_above_vehicle = fly_alt_min:get() + curr_alt_below_home + if target_alt_above_vehicle > 0 then + -- climb at up to 1m/s towards target above vehicle. climb rate change is limited by WPNAV_ACCEL_Z + local climb_rate_chg_max = interval_ms * 0.001 * (wpnav_accel_z:get() * 0.01) + climb_rate = math.min(target_alt_above_vehicle * 0.1, wpnav_speedup:get() * 0.01, climb_rate + climb_rate_chg_max) + end + end + end + + -- set angle target to roll 0, pitch to lean angle (note: negative is forward), yaw towards home + if (vehicle:set_target_angle_and_climbrate(0, -math.abs(fly_angle:get()), home_yaw, climb_rate, false, 0)) then + if (update_user) then + local time_left_str = "" + if (not timeout and (fly_timeoout:get() > 0)) then + time_left_str = " t:" .. tostring(math.max(0, ((fly_timeoout:get() * 1000) - time_elapsed_ms) / 1000)) + end + gcs:send_text(5, "DR: fly home yaw:" .. tostring(math.floor(home_yaw)) .. " pit:" .. tostring(math.floor(fly_angle:get())) .. " cr:" .. tostring(math.floor(climb_rate*10)/10) .. time_left_str) + end + elseif (update_user) then + gcs:send_text(0, "DR: failed to set attitude target") + end + + -- if GPS and EKF recover or timeout switch to next mode + if (not gps_or_ekf_bad) or timeout then + local recovery_mode = stage1_flight_mode + if (next_mode:get() >= 0) then + recovery_mode = next_mode:get() + end + if (recovery_mode == nil) then + recovery_mode = copter_RTL_mode + gcs:send_text(0, "DR: NEXT_MODE=-1 but fallingback to RTL") + end + -- change to DR_NEXT_MODE + if (vehicle:set_mode(recovery_mode)) then + flight_stage = 0 + elseif (update_user) then + -- warn user of unexpected failure + gcs:send_text(0, "DR: failed to change to mode " .. tostring(recovery_mode)) + end + end + return update, interval_ms + end + + -- we should never get here but just in case + return update, interval_ms +end + +return update() + diff --git a/libraries/AP_Scripting/examples/copter-fast-descent.lua b/libraries/AP_Scripting/examples/copter-fast-descent.lua index 620fdd92133..86735fdce84 100644 --- a/libraries/AP_Scripting/examples/copter-fast-descent.lua +++ b/libraries/AP_Scripting/examples/copter-fast-descent.lua @@ -81,8 +81,8 @@ function update() -- activate_type 0: reset stage when disarmed or not in Guided mode if not arming:is_armed() or (vehicle:get_mode() ~= copter_guided_mode_num) then stage = 0 - if (update_user) then - gcs:send_text(0, "Fast Descent: waiting for Guided") + if (update_user and arming:is_armed()) then + gcs:send_text(6, "Fast Descent: waiting for Guided") end return update, interval_ms end @@ -91,8 +91,8 @@ function update() auto_last_id, cmd, arg1, arg2 = vehicle:nav_script_time() if not arming:is_armed() or not auto_last_id then stage = 0 - if (update_user) then - gcs:send_text(0, "Fast Descent: waiting for NAV_SCRIPT_TIME") + if (update_user and arming:is_armed()) then + gcs:send_text(6, "Fast Descent: waiting for NAV_SCRIPT_TIME") end return update, interval_ms end @@ -120,7 +120,7 @@ function update() speed_xy = 0 speed_z = 0 stage = stage + 1 -- advance to next stage - gcs:send_text(0, "Fast Descent: starting") + gcs:send_text(5, "Fast Descent: starting") end elseif (stage == 1) then -- Stage1: descend @@ -136,25 +136,28 @@ function update() speed_xy = math.max(speed_xy - (accel_xy * dt), 0) -- decelerate horizontal speed to zero speed_z = math.max(speed_z - (accel_z * dt), 0) -- decelerate vertical speed to zero else - -- determine if below slowdown point - local slowdown = false - local stopping_distance_z = 0.5 * speed_z_max:get() * speed_z_max:get() / accel_z - if (rel_pos_home_NED) then - if (-rel_pos_home_NED:z() <= alt_above_home_min:get() + stopping_distance_z) then - slowdown = true - end + -- calculate conversion between alt-above-home and alt-above-ekf-origin + local home_alt_above_origin = 0 + local home = ahrs:get_home() + local ekf_origin = ahrs:get_origin() + if home and ekf_origin then + local dist_NED = home:get_distance_NED(ekf_origin) + home_alt_above_origin = dist_NED:z() end - if (slowdown) then - -- slow down vertical and then horizontal speed - speed_z = math.max(speed_z - (accel_z * dt), math.min(speed_z_slowdown, speed_z_max:get())) -- decelerate to 0.1m/s vertically - if speed_z <= speed_z_slowdown then - speed_xy = math.max(speed_xy - (accel_xy * dt), 0) - end + -- calculate target speeds + local target_dist_to_alt_min = -target_alt_D - home_alt_above_origin - alt_above_home_min:get() -- alt target's distance to alt_min + if (target_dist_to_alt_min > 0) then + local speed_z_limit = speed_z_max:get() + speed_z_limit = math.min(speed_z_limit, math.sqrt(2.0 * target_dist_to_alt_min * accel_z)) -- limit speed so vehicle can stop at ALT_MIN + speed_z_limit = math.max(speed_z_limit, speed_z_slowdown) -- vertical speed should never be less than 0.1 m/s when above ALT_MIN + speed_z = math.min(speed_z + (accel_z * dt), speed_z_limit) + + speed_xy = math.min(speed_xy + (accel_xy * dt), speed_xy_max:get()) -- accelerate horizontal speed to maximum else - -- normal speed - speed_xy = math.min(speed_xy + (accel_xy * dt), speed_xy_max:get()) -- accelerate horizontal speed to max - speed_z = math.min(speed_z + (accel_z * dt), speed_z_max:get()) -- accelerate to max descent rate + -- below alt min so decelerate target speeds to zero + speed_xy = math.max(speed_xy - (accel_xy * dt), 0) -- decelerate horizontal speed to zero + speed_z = math.max(speed_z - (accel_z * dt), 0) -- decelerate vertical speed to zero end end @@ -205,22 +208,22 @@ function update() -- send targets to vehicle with yaw target vehicle:set_target_posvelaccel_NED(target_pos, target_vel, target_accel, true, target_yaw_deg, false, 0, false) - -- advance to stage 2 when below target altitude + -- advance to stage 2 when below target altitude and target speeds are zero if (rel_pos_home_NED) then - if (-rel_pos_home_NED:z() <= alt_above_home_min:get()) then + if (-rel_pos_home_NED:z() <= alt_above_home_min:get() and (speed_xy==0) and (speed_z==0)) then stage = stage + 1 end if (update_user) then - gcs:send_text(0, string.format("Fast Descent: alt:%d target:%d", math.floor(-rel_pos_home_NED:z()), math.floor(alt_above_home_min:get()))) + gcs:send_text(5, string.format("Fast Descent: alt:%d target:%d", math.floor(-rel_pos_home_NED:z()), math.floor(alt_above_home_min:get()))) end else - gcs:send_text(0, "Fast Descent: lost position estimate, aborting") + gcs:send_text(5, "Fast Descent: lost position estimate, aborting") stage = stage + 1 end elseif (stage == 2) then -- Stage2: done! stage = stage + 1 - gcs:send_text(0, "Fast Descent: done!") + gcs:send_text(5, "Fast Descent: done!") if (activate_type:get() == 0) then -- if activated from Guided change to RTL mode vehicle:set_mode(copter_rtl_mode_num) diff --git a/libraries/AP_Scripting/examples/esc-usage.lua b/libraries/AP_Scripting/examples/esc-usage.lua deleted file mode 100644 index 5ffbecfb0c2..00000000000 --- a/libraries/AP_Scripting/examples/esc-usage.lua +++ /dev/null @@ -1,31 +0,0 @@ --- This script displays ESC usage time (supported only by ToshibaCAN ESCs) - -local usage_hours_max = 100 -- maximum safe usage for these ESCs in hours -local usage_sec_max = usage_hours_max*60*60 - -function update() -- this is the loop which periodically runs - if not arming:is_armed() then -- only run check when disarmed - local got_esc_usage = false - local esc_over_max = false - for i = 0, 3 do -- check first four ESCs - local usage_sec = esc_telem:get_usage_seconds(i) - if usage_sec > 0 then - got_esc_usage = true - end - if usage_sec > usage_sec_max then - esc_over_max = true - local usage_hours = usage_sec / 3600 - local usage_minutes = (usage_sec / 60) % 60 - gcs:send_text(0, string.format("ESC" .. tostring(i) .. ": " .. tostring(usage_hours) .. "hrs " .. tostring(usage_minutes) .. "min (limit is " .. tostring(usage_hours_max) .. "hrs)")) - end - end - if not got_esc_usage then - gcs:send_text(0, "Could not retrieve ESC usage time") - elseif not esc_over_max then - gcs:send_text(0, string.format("ESC usage time OK (under " .. tostring(usage_hours_max) .. "hrs limit)")) - end - end - return update, 5000 -- reschedules the loop in 5 seconds -end - -return update() -- run immediately before starting to reschedule diff --git a/libraries/AP_Scripting/examples/esc_rpm_scale.lua b/libraries/AP_Scripting/examples/esc_rpm_scale.lua new file mode 100644 index 00000000000..9a18afed8d5 --- /dev/null +++ b/libraries/AP_Scripting/examples/esc_rpm_scale.lua @@ -0,0 +1,11 @@ +--[[ +set scale factor for RPM on some ESCs to allow for different pole count on some ESCs +--]] + +-- set ESC 4 (index 3) to 2.0 times reported RPM +esc_telem:set_rpm_scale(3, 2.0) + +-- set ESC 6 (index 5) to 2.0 times reported RPM +esc_telem:set_rpm_scale(5, 2.0) + +gcs:send_text(0,"Setup motor poles") diff --git a/libraries/AP_Scripting/examples/fw_vtol_failsafe.lua b/libraries/AP_Scripting/examples/fw_vtol_failsafe.lua index ea5f9013f66..d2522ffa491 100644 --- a/libraries/AP_Scripting/examples/fw_vtol_failsafe.lua +++ b/libraries/AP_Scripting/examples/fw_vtol_failsafe.lua @@ -8,20 +8,35 @@ -- If the aircraft drops below a predetermined minimum altitude, QLAND mode is engaged and the aircraft lands at its current position. -- If the aircraft arrives within Q_FW_LND_APR_RAD of the return point before dropping below the minimum altitude, it should loiter down to the minimum altitude before switching to QRTL and landing. +-- setup param block for VTOL failsafe params +local PARAM_TABLE_KEY = 77 +local PARAM_TABLE_PREFIX = "VTFS_" +assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 4), 'could not add param table') + +-- bind a parameter to a variable +function bind_param(name) + local p = Parameter() + assert(p:init(name), string.format('could not find %s parameter', name)) + return p +end + +-- add a parameter and bind it to a variable +function bind_add_param(name, idx, default_value) + assert(param:add_param(PARAM_TABLE_KEY, idx, name, default_value), string.format('could not add param %s', name)) + return bind_param(PARAM_TABLE_PREFIX .. name) +end + -- consider engine stopped when vibe is low and RPM low for more than 4s -local ENGINE_STOPPED_MS = 4000 +ENGINE_STOPPED_MS = bind_add_param('ENG_STOP_MS', 1, 4000) -- RPM threshold below which engine may be stopped -local RPM_LOW_THRESH = 500 +RPM_LOW_THRESH = bind_add_param('RPM_THRESH', 2, 500) -- vibration threshold below which engine may be stopped -local VIBE_LOW_THRESH = 2 +VIBE_LOW_THRESH = bind_add_param('VIBE_LOW', 3, 2) -- altitude threshold for QLAND -local LOW_ALT_THRESH = 70 - --- when below MIN_AIRSPEED assume we are not in forward flight -local MIN_AIRSPEED = 5 +LOW_ALT_THRESH = bind_add_param('LOW_ALT', 4, 70) -- time when engine stopped local engine_stop_ms = -1 @@ -48,7 +63,7 @@ function check_engine() local vibe = ahrs:get_vibration():length() -- if either RPM is high or vibe is high then assume engine is running - if (rpm and (rpm > RPM_LOW_THRESH)) or (vibe > VIBE_LOW_THRESH) then + if (rpm and (rpm > RPM_LOW_THRESH:get())) or (vibe > VIBE_LOW_THRESH:get()) then -- engine is definately running engine_stop_ms = -1 if engine_stopped then @@ -65,7 +80,7 @@ function check_engine() engine_stop_ms = now return true end - if now - engine_stop_ms < ENGINE_STOPPED_MS then + if now - engine_stop_ms < ENGINE_STOPPED_MS:get() then return false end -- engine has been stopped for ENGINE_STOPPED_MS milliseconds, notify user @@ -104,10 +119,10 @@ function check_qland() local dist = target:get_distance(pos) local terrain_height = terrain:height_above_terrain(true) local threshold = param:get('Q_FW_LND_APR_RAD') - if dist < threshold and (terrain_height and (terrain_height < LOW_ALT_THRESH)) then + if dist < threshold and (terrain_height and (terrain_height < LOW_ALT_THRESH:get())) then gcs:send_text(0, "Failsafe: LANDING QRTL") vehicle:set_mode(MODE_QRTL) - elseif terrain_height and terrain_height < LOW_ALT_THRESH then + elseif terrain_height and terrain_height < LOW_ALT_THRESH:get() then gcs:send_text(0, "Failsafe: LANDING QLAND") vehicle:set_mode(MODE_QLAND) end diff --git a/libraries/AP_Scripting/examples/i2c_scan.lua b/libraries/AP_Scripting/examples/i2c_scan.lua index 421c81ddf36..9e93806af75 100644 --- a/libraries/AP_Scripting/examples/i2c_scan.lua +++ b/libraries/AP_Scripting/examples/i2c_scan.lua @@ -2,7 +2,7 @@ local address = 0 local found = 0 -local i2c_bus = i2c.get_device(0,0) +local i2c_bus = i2c:get_device(0,0) i2c_bus:set_retries(10) function update() -- this is the loop which periodically runs diff --git a/libraries/AP_Scripting/examples/lidar_control.lua b/libraries/AP_Scripting/examples/lidar_control.lua new file mode 100644 index 00000000000..88492350307 --- /dev/null +++ b/libraries/AP_Scripting/examples/lidar_control.lua @@ -0,0 +1,53 @@ +-- enable use of Lidar on quadplanes only for landing, by changing RNGFN_LANDING + +-- bind a parameter to a variable +function bind_param(name) + local p = Parameter() + assert(p:init(name), string.format('could not find %s parameter', name)) + return p +end + +local RNGFND_LANDING = bind_param("RNGFND_LANDING") + +MODE_QLAND = 20 +MODE_QRTL = 21 +MODE_AUTO = 10 + +local NAV_LAND = 21 +local NAV_VTOL_LAND = 85 + +function in_landing() + local mode = vehicle:get_mode() + if mode == MODE_QRTL or mode == MODE_QLAND then + return true + end + if mode == MODE_AUTO then + local id = mission:get_current_nav_id() + if id == NAV_VTOL_LAND or id == NAV_LAND then + return true + end + end + return false +end + +-- convert a boolean to an int +function bool_to_int(v) + return v and 1 or 0 +end + +function update() + local v = bool_to_int(in_landing()) + if v ~= RNGFND_LANDING:get() then + if v == 1 then + gcs:send_text(0,"Enabling Lidar") + else + gcs:send_text(0,"Disabling Lidar") + end + RNGFND_LANDING:set(v) + end + + -- run at 1Hz + return update, 1000 +end + +return update() diff --git a/libraries/AP_Scripting/examples/logging.lua b/libraries/AP_Scripting/examples/logging.lua index ccfd450d845..aed80c9911f 100644 --- a/libraries/AP_Scripting/examples/logging.lua +++ b/libraries/AP_Scripting/examples/logging.lua @@ -30,10 +30,10 @@ local function write_to_dataflash() -- https://github.com/ArduPilot/ardupilot/tree/master/libraries/AP_Logger -- not all format types are supported by scripting only: i, L, e, f, n, M, B, I, E, and N -- lua automatically adds a timestamp in micro seconds - logger.write('SCR1','roll(deg),pitch(deg),yaw(deg)','fff',interesting_data[roll],interesting_data[pitch],interesting_data[yaw]) + logger:write('SCR1','roll(deg),pitch(deg),yaw(deg)','fff',interesting_data[roll],interesting_data[pitch],interesting_data[yaw]) -- it is also possible to give units and multipliers - logger.write('SCR2','roll,pitch,yaw','fff','ddd','---',interesting_data[roll],interesting_data[pitch],interesting_data[yaw]) + logger:write('SCR2','roll,pitch,yaw','fff','ddd','---',interesting_data[roll],interesting_data[pitch],interesting_data[yaw]) end diff --git a/libraries/AP_Scripting/examples/mag_heading.lua b/libraries/AP_Scripting/examples/mag_heading.lua new file mode 100644 index 00000000000..d6c1e24c01a --- /dev/null +++ b/libraries/AP_Scripting/examples/mag_heading.lua @@ -0,0 +1,50 @@ +--[[ + send magnetic heading in degrees as NAMED_VALUE_FLOAT[MAG_HEAD] and NAMED_VALUE_FLOAT[MAG_GCRS] +--]] + +local RATE_HZ = 2 + +-- bind a parameter to a variable given +function bind_param(name) + local p = Parameter() + assert(p:init(name), string.format('could not find %s parameter', name)) + return p +end + +COMPASS_DEC = bind_param("COMPASS_DEC") + +function wrap_360(angle) + local res = angle % 360 + if res < 0 then + res = res + 360 + end + return res +end + +function update() + local yaw_deg = wrap_360(math.deg(ahrs:get_yaw() - COMPASS_DEC:get())) + local gspd = ahrs:groundspeed_vector() + local gcrs_deg = wrap_360(math.deg(math.atan(gspd:y(), gspd:x()) - COMPASS_DEC:get())) + gcs:send_named_float("MAG_HEAD", yaw_deg) + gcs:send_named_float("MAG_GCRS", gcrs_deg) +end + +gcs:send_text(0, "MagHeading loaded") + +local MAV_SEVERITY_ERROR = 3 + +-- wrapper around update(). This calls update() and if update faults +-- then an error is displayed, but the script is not stopped +function protected_wrapper() + local success, err = pcall(update) + if not success then + gcs:send_text(MAV_SEVERITY_ERROR, "Internal Error: " .. err) + -- when we fault we run the update function again after 1s, slowing it + -- down a bit so we don't flood the console with errors + return protected_wrapper, 1000 + end + return protected_wrapper, math.floor(1000 / RATE_HZ) +end + +-- start running update loop +return protected_wrapper() diff --git a/libraries/AP_Scripting/examples/mount-test.lua b/libraries/AP_Scripting/examples/mount-test.lua new file mode 100644 index 00000000000..18ef6449890 --- /dev/null +++ b/libraries/AP_Scripting/examples/mount-test.lua @@ -0,0 +1,130 @@ +-- moves 3-axis gimbal (aka "mount") using earth-frame and body-frame rates and angles +-- +-- stage 0: move gimbal to neutral position +-- stage 1: yaw CW at 10deg/s in body-frame +-- stage 2: yaw CCW at 10 deg/s in body-frame +-- stage 3: pitch at 10 deg/s in body-frame +-- stage 4: pitch at -10 deg/s in body-frame +-- stage 5: roll at 10 deg/s in body-frame +-- stage 6: roll at -10 deg/s in body-frame +-- stage 7: point North +-- stage 8: point South and center +-- stage 9: point North and Down +-- stage 10: move angle to neutral position + +local stage = 0 +local stage_time_ms = 5000 +local stage_start_time_ms = 0 +local last_stage = 10 + +-- the main update function that performs a simplified version of RTL +function update() + + -- get current system time + local now_ms = millis() + + -- start + if stage_start_time_ms == 0 then + stage_start_time_ms = now_ms + end + + -- check if time to move to next stage + local update_user = false + if (now_ms - stage_start_time_ms > stage_time_ms) and (stage < last_stage) then + stage = stage + 1 + stage_start_time_ms = now_ms + update_user = true + end + + if stage == 0 or stage >= last_stage then + -- move angle to neutral position + mount:set_angle_target(0, 0, 0, 0, false) + if update_user then + gcs:send_text(6, "stage:" .. tostring(stage) .. " move to neutral position") + end + end + + if stage == 1 then + -- yaw CW at 10deg/s in body-frame + mount:set_rate_target(0, 0, 0, 10, false) + if update_user then + gcs:send_text(6, "stage:" .. tostring(stage) .. " yaw at 10deg/s") + end + end + + if stage == 2 then + -- yaw CCW at 10 deg/s in body-frame + mount:set_rate_target(0, 0, 0, -10, false) + if update_user then + gcs:send_text(6, "stage:" .. tostring(stage) .. " yaw at -10deg/s") + end + end + + if stage == 3 then + -- pitch at 10 deg/s in body-frame + mount:set_rate_target(0, 0, 10, 0, false) + if update_user then + gcs:send_text(6, "stage:" .. tostring(stage) .. " pitch at 10deg/s") + end + end + + if stage == 4 then + -- pitch at -10 deg/s in body-frame + mount:set_rate_target(0, 0, -10, 0, false) + if update_user then + gcs:send_text(6, "stage:" .. tostring(stage) .. " pitch at -10deg/s") + end + end + + if stage == 5 then + -- roll at 10 deg/s in body-frame + mount:set_rate_target(0, 10, 0, 0, false) + if update_user then + gcs:send_text(6, "stage:" .. tostring(stage) .. " roll at 10deg/s") + end + end + + if stage == 6 then + -- roll at -10 deg/s in body-frame + mount:set_rate_target(0, -10, 0, 0, false) + if update_user then + gcs:send_text(6, "stage:" .. tostring(stage) .. " roll at -10deg/s") + end + end + + if stage == 7 then + -- point North + mount:set_angle_target(0, 0, 0, 0, true) + if update_user then + gcs:send_text(6, "stage:" .. tostring(stage) .. " point North") + end + end + + if stage == 8 then + -- point South and center + mount:set_angle_target(0, 0, 0, 180, true) + if update_user then + gcs:send_text(6, "stage:" .. tostring(stage) .. " point South") + end + end + + if stage == 9 then + -- point North and Down + mount:set_angle_target(0, 0, -90, 0, false) + if update_user then + gcs:send_text(6, "stage:" .. tostring(stage) .. " point Down") + end + end + + if stage > last_stage then + -- move angle to neutral position + mount:set_angle_target(0, 0, 0, 0, false) + if update_user then + gcs:send_text(6, "stage:" .. tostring(stage) .. " done!") + end + end + + return update, 100 +end + +return update() diff --git a/libraries/AP_Scripting/examples/orbit_follow.lua b/libraries/AP_Scripting/examples/orbit_follow.lua new file mode 100644 index 00000000000..5629bbbe1a7 --- /dev/null +++ b/libraries/AP_Scripting/examples/orbit_follow.lua @@ -0,0 +1,44 @@ +-- example that does an orbit of a vehicle that is being followed +-- by adjusting the follow offset X and Y parameters +-- user settable FOLL_ORB_TIME and FOLL_ORB_RADIUS parameters +-- are provided for the time for one orbit (in seconds) and the radius +-- of the orbit + +-- setup param block for FOLL_ extensions +local PARAM_TABLE_KEY = 83 +local PARAM_TABLE_PREFIX = "FOLL_" +assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 2), 'could not add param table') + +function bind_param(name) + local p = Parameter() + assert(p:init(name), string.format('could not find %s parameter', name)) + return p +end + +function bind_add_param(name, index, default_value) + assert(param:add_param(PARAM_TABLE_KEY, index, name, default_value), string.format('could not add %s', PARAM_TABLE_PREFIX .. name)) + return bind_param(PARAM_TABLE_PREFIX .. name) +end + +local FOLL_OFS_X = bind_param("FOLL_OFS_X") +local FOLL_OFS_Y = bind_param("FOLL_OFS_Y") +local FOLL_ORB_RADIUS = bind_add_param("ORB_RADIUS", 1, 5) +local FOLL_ORB_TIME = bind_add_param("ORB_TIME", 2, 10) + +local t = 0 + +function update() + t = t + 0.1 + --gcs:send_text(0, string.format("t=%.2f X=%.2f Y=%.2f", t, FOLL_OFS_X:get(), FOLL_OFS_Y:get())) + if t > FOLL_ORB_TIME:get() then + t = t - FOLL_ORB_TIME:get() + end + FOLL_OFS_X:set(math.cos((t/FOLL_ORB_TIME:get())*2*math.pi)*FOLL_ORB_RADIUS:get()) + FOLL_OFS_Y:set(math.sin((t/FOLL_ORB_TIME:get())*2*math.pi)*FOLL_ORB_RADIUS:get()) + return update, 100 +end + +gcs:send_text(0, string.format("orbit started")) +return update, 100 + + diff --git a/libraries/AP_Scripting/examples/plane-wind-fs.lua b/libraries/AP_Scripting/examples/plane-wind-fs.lua index d7d6e32856a..9f3002651eb 100644 --- a/libraries/AP_Scripting/examples/plane-wind-fs.lua +++ b/libraries/AP_Scripting/examples/plane-wind-fs.lua @@ -244,7 +244,7 @@ function track_return_time() end end - logger.write('SFSC','total_return_time,remaining_return_time','If','ss','--',total_time,return_time) + logger:write('SFSC','total_return_time,remaining_return_time','If','ss','--',total_time,return_time) end return track_return_time, 100 end @@ -332,7 +332,7 @@ function update() return_q = 0.5 * density * return_airspeed^2 -- we could estimate the change in density also, but will be negligible end - logger.write('SFSA','return_time,return_airspeed,Q,return_Q','ffff','snPP','----',return_time,return_airspeed,q,return_q) + logger:write('SFSA','return_time,return_airspeed,Q,return_Q','ffff','snPP','----',return_time,return_airspeed,q,return_q) for i = 1, #batt_info do local instance, norm_filtered_amps, rated_capacity_mah = table.unpack(batt_info[i]) @@ -354,7 +354,7 @@ function update() local remaining_time = remaining_capacity / return_amps local buffer_time = remaining_time - ((return_time * time_SF) + margin) - logger.write('SFSB','Instance,current,rem_cap,rem_time,buffer','Bffff','#Aiss','--C--',i-1,return_amps,remaining_capacity,remaining_time,buffer_time) + logger:write('SFSB','Instance,current,rem_cap,rem_time,buffer','Bffff','#Aiss','--C--',i-1,return_amps,remaining_capacity,remaining_time,buffer_time) if (return_time < 0) or buffer_time < 0 then if return_time < 0 then gcs:send_text(0, "Failsafe: ground speed low can not get home") diff --git a/libraries/AP_Scripting/examples/plane_aerobatics.lua b/libraries/AP_Scripting/examples/plane_aerobatics.lua deleted file mode 100644 index e823263f606..00000000000 --- a/libraries/AP_Scripting/examples/plane_aerobatics.lua +++ /dev/null @@ -1,395 +0,0 @@ --- perform simple aerobatic manoeuvres in AUTO mode - -local running = false - -local roll_stage = 0 - -local ROLL_TCONST = param:get('RLL2SRV_TCONST') * 0.5 -local PITCH_TCONST = param:get('PTCH2SRV_TCONST') * 0.5 - -DO_JUMP = 177 -NAV_WAYPOINT = 16 - -k_throttle = 70 - -function bind_param(name) - local p = Parameter() - assert(p:init(name), string.format('could not find %s parameter', name)) - return p -end - -local SCR_USER1 = bind_param("SCR_USER1") -- height P gain -local SCR_USER2 = bind_param("SCR_USER2") -- height I gain -local SCR_USER3 = bind_param("SCR_USER3") -- throttle FF from pitch -local SCR_USER4 = bind_param("SCR_USER4") -- height knifeedge addition for pitch -local SCR_USER5 = bind_param("SCR_USER5") -- speed P gain -local SCR_USER6 = bind_param("SCR_USER6") -- speed I gain -local TRIM_THROTTLE = bind_param("TRIM_THROTTLE") -local TRIM_ARSPD_CM = bind_param("TRIM_ARSPD_CM") - -local last_roll_err = 0.0 -local last_id = 0 -local initial_yaw_deg = 0 -local wp_yaw_deg = 0 -local initial_height = 0 - --- constrain a value between limits -function constrain(v, vmin, vmax) - if v < vmin then - v = vmin - end - if v > vmax then - v = vmax - end - return v -end - --- a controller to target a zero roll angle, coping with inverted flight --- output is a body frame roll rate, with convergence over time tconst in seconds -function roll_zero_controller(tconst) - local roll_deg = math.deg(ahrs:get_roll()) - local pitch_deg = math.deg(ahrs:get_pitch()) - local roll_err = 0.0 - if math.abs(pitch_deg) > 85 then - -- close to 90 we retain the last roll rate - roll_err = last_roll_err - elseif roll_deg > 90 then - roll_err = 180 - roll_deg - elseif roll_deg < -90 then - roll_err = (-180) - roll_deg - else - roll_err = -roll_deg - end - last_roll_err = roll_err - return roll_err / tconst -end - - -function wrap_360(angle) - local res = math.fmod(angle, 360.0) - if res < 0 then - res = res + 360.0 - end - return res -end - -function wrap_180(angle) - local res = wrap_360(angle) - if res > 180 then - res = res - 360 - end - return res -end - --- a PI controller implemented as a Lua object -local function PI_controller(kP,kI,iMax) - -- the new instance. You can put public variables inside this self - -- declaration if you want to - local self = {} - - -- private fields as locals - local _kP = kP or 0.0 - local _kI = kI or 0.0 - local _kD = kD or 0.0 - local _iMax = iMax - local _last_t = nil - local _I = 0 - local _P = 0 - local _total = 0 - local _counter = 0 - local _target = 0 - local _current = 0 - - -- update the controller. - function self.update(target, current) - local now = millis():tofloat() * 0.001 - if not _last_t then - _last_t = now - end - local dt = now - _last_t - _last_t = now - local err = target - current - _counter = _counter + 1 - - local P = _kP * err - _I = _I + _kI * err * dt - if _iMax then - _I = constrain(_I, -_iMax, iMax) - end - local I = _I - local ret = P + I - - _target = target - _current = current - _P = P - _total = ret - return ret - end - - -- reset integrator to an initial value - function self.reset(integrator) - _I = integrator - end - - function self.set_I(I) - _kI = I - end - - function self.set_P(P) - _kP = P - end - - function self.set_Imax(Imax) - _iMax = Imax - end - - -- log the controller internals - function self.log(name, add_total) - -- allow for an external addition to total - logger.write(name,'Targ,Curr,P,I,Total,Add','ffffff',_target,_current,_P,_I,_total,add_total) - end - - -- return the instance - return self -end - -local function height_controller(kP_param,kI_param,KnifeEdge_param,Imax) - local self = {} - local kP = kP_param - local kI = kI_param - local KnifeEdge = KnifeEdge_param - local PI = PI_controller(kP:get(), kI:get(), Imax) - - function self.update(target) - local target_pitch = PI.update(initial_height, ahrs:get_location():alt()*0.01) - local roll_rad = ahrs:get_roll() - local ke_add = math.abs(math.sin(roll_rad)) * KnifeEdge:get() - target_pitch = target_pitch + ke_add - PI.log("HPI", ke_add) - return target_pitch - end - - function self.reset() - PI.reset(math.max(math.deg(ahrs:get_pitch()), 3.0)) - PI.set_P(kP:get()) - PI.set_I(kI:get()) - end - - return self -end - -local height_PI = height_controller(SCR_USER1, SCR_USER2, SCR_USER4, 20.0) -local speed_PI = PI_controller(SCR_USER5:get(), SCR_USER6:get(), 100.0) - --- a controller to target a zero pitch angle and zero heading change, used in a roll --- output is a body frame pitch rate, with convergence over time tconst in seconds -function pitch_controller(target_pitch_deg, target_yaw_deg, tconst) - local roll_deg = math.deg(ahrs:get_roll()) - local pitch_deg = math.deg(ahrs:get_pitch()) - local yaw_deg = math.deg(ahrs:get_yaw()) - - -- get earth frame pitch and yaw rates - local ef_pitch_rate = (target_pitch_deg - pitch_deg) / tconst - local ef_yaw_rate = wrap_180(target_yaw_deg - yaw_deg) / tconst - - local bf_pitch_rate = math.sin(math.rad(roll_deg)) * ef_yaw_rate + math.cos(math.rad(roll_deg)) * ef_pitch_rate - local bf_yaw_rate = math.cos(math.rad(roll_deg)) * ef_yaw_rate - math.sin(math.rad(roll_deg)) * ef_pitch_rate - return bf_pitch_rate, bf_yaw_rate -end - --- a controller for throttle to account for pitch -function throttle_controller(tconst) - local pitch_rad = ahrs:get_pitch() - local thr_ff = SCR_USER3:get() - local throttle = TRIM_THROTTLE:get() + math.sin(pitch_rad) * thr_ff - return constrain(throttle, 0.0, 100.0) -end - -function do_axial_roll(arg1, arg2) - -- constant roll rate axial roll - if not running then - running = true - roll_stage = 0 - height_PI.reset() - gcs:send_text(0, string.format("Starting roll")) - end - local roll_rate = arg1 - local throttle = arg2 - local pitch_deg = math.deg(ahrs:get_pitch()) - local roll_deg = math.deg(ahrs:get_roll()) - if roll_stage == 0 then - if roll_deg > 45 then - roll_stage = 1 - end - elseif roll_stage == 1 then - if roll_deg > -5 and roll_deg < 5 then - running = false - -- we're done - gcs:send_text(0, string.format("Finished roll r=%.1f p=%.1f", roll_deg, pitch_deg)) - vehicle:nav_script_time_done(last_id) - roll_stage = 2 - return - end - end - if roll_stage < 2 then - target_pitch = height_PI.update(initial_height) - pitch_rate, yaw_rate = pitch_controller(target_pitch, wp_yaw_deg, PITCH_TCONST) - vehicle:set_target_throttle_rate_rpy(throttle, roll_rate, pitch_rate, yaw_rate) - end -end - -local loop_stage = 0 - -function do_loop(arg1, arg2) - -- do one loop with controllable pitch rate and throttle - if not running then - running = true - loop_stage = 0 - gcs:send_text(0, string.format("Starting loop")) - end - local pitch_rate = arg1 - local throttle = throttle_controller() - local pitch_deg = math.deg(ahrs:get_pitch()) - local roll_deg = math.deg(ahrs:get_roll()) - if loop_stage == 0 then - if pitch_deg > 60 then - loop_stage = 1 - end - elseif loop_stage == 1 then - if math.abs(roll_deg) < 90 and pitch_deg > -5 and pitch_deg < 5 then - running = false - -- we're done - gcs:send_text(0, string.format("Finished loop p=%.1f", pitch_deg)) - vehicle:nav_script_time_done(last_id) - loop_stage = 2 - return - end - end - if loop_stage < 2 then - local roll_rate = roll_zero_controller(ROLL_TCONST) - vehicle:set_target_throttle_rate_rpy(throttle, roll_rate, pitch_rate, 0) - end -end - -local rolling_circle_stage = 0 -local rolling_circle_yaw = 0 -local rolling_circle_last_ms = 0 - -function do_rolling_circle(arg1, arg2) - -- constant roll rate circle roll - if not running then - running = true - rolling_circle_stage = 0 - rolling_circle_yaw = 0 - rolling_circle_last_ms = millis() - height_PI.reset() - - speed_PI.set_P(SCR_USER5:get()) - speed_PI.set_I(SCR_USER6:get()) - speed_PI.reset(math.max(SRV_Channels:get_output_scaled(k_throttle), TRIM_THROTTLE:get())) - gcs:send_text(0, string.format("Starting rolling circle")) - end - local radius = arg1 - local num_rolls = arg2 - local pitch_deg = math.deg(ahrs:get_pitch()) - local roll_deg = math.deg(ahrs:get_roll()) - local yaw_deg = math.deg(ahrs:get_yaw()) - local gspeed = ahrs:groundspeed_vector():length() - local circumference = math.abs(math.pi * 2.0 * radius) - local circle_time = circumference / gspeed - local yaw_rate_dps = 360.0 / circle_time - local now_ms = millis() - local dt = (now_ms - rolling_circle_last_ms):tofloat() * 0.001 - rolling_circle_last_ms = now_ms - - if radius < 0.0 then - yaw_rate_dps = -yaw_rate_dps - end - - local roll_rate = (360.0 * num_rolls) / circle_time - - rolling_circle_yaw = rolling_circle_yaw + yaw_rate_dps * dt - - if rolling_circle_stage == 0 then - if math.abs(rolling_circle_yaw) > 10.0 then - rolling_circle_stage = 1 - end - elseif rolling_circle_stage == 1 then - if math.abs(rolling_circle_yaw) >= 360.0 then - running = false - -- we're done - gcs:send_text(0, string.format("Finished rollcircle r=%.1f p=%.1f", roll_deg, pitch_deg)) - vehicle:nav_script_time_done(last_id) - rolling_circle_stage = 2 - return - end - end - - local target_roll = num_rolls * math.abs(rolling_circle_yaw) - local roll_error = wrap_180(target_roll - roll_deg) - local roll_error_P = 0.5 - local roll_rate_corrected = roll_rate + roll_error * roll_error_P - - if rolling_circle_stage < 2 then - target_pitch = height_PI.update(initial_height) - vel = ahrs:get_velocity_NED() - throttle = speed_PI.update(TRIM_ARSPD_CM:get()*0.01, vel:length()) - throttle = constrain(throttle, 0, 100.0) - speed_PI.log("SPI", 0.0) - pitch_rate, yaw_rate = pitch_controller(target_pitch, wrap_360(rolling_circle_yaw+initial_yaw_deg), PITCH_TCONST) - vehicle:set_target_throttle_rate_rpy(throttle, roll_rate_corrected, pitch_rate, yaw_rate) - end -end - ---- get a location object for a given WP number -function get_wp_location(i) - local m = mission:get_item(i) - local loc = Location() - loc:lat(m:x()) - loc:lng(m:y()) - loc:relative_alt(false) - loc:terrain_alt(false) - loc:origin_alt(false) - loc:alt(math.floor(m:z()*100)) - return loc -end - -function resolve_jump(i) - local m = mission:get_item(i) - while m:command() == DO_JUMP do - i = math.floor(m:param1()) - m = mission:get_item(i) - end - return i -end - -function update() - id, cmd, arg1, arg2 = vehicle:nav_script_time() - if id then - if id ~= last_id then - -- we've started a new command - running = false - last_id = id - initial_yaw_deg = math.deg(ahrs:get_yaw()) - initial_height = ahrs:get_location():alt()*0.01 - - -- work out yaw between previous WP and next WP - local cnum = mission:get_current_nav_index() - local loc_prev = get_wp_location(cnum-1) - local loc_next = get_wp_location(resolve_jump(cnum+1)) - wp_yaw_deg = math.deg(loc_prev:get_bearing(loc_next)) - end - if cmd == 1 then - do_axial_roll(arg1, arg2) - elseif cmd == 2 then - do_loop(arg1, arg2) - elseif cmd == 3 then - do_rolling_circle(arg1, arg2) - end - else - running = false - end - return update, 10 -end - -return update() diff --git a/libraries/AP_Scripting/examples/plane_ship_landing.lua b/libraries/AP_Scripting/examples/plane_ship_landing.lua new file mode 100644 index 00000000000..79a407d9cdf --- /dev/null +++ b/libraries/AP_Scripting/examples/plane_ship_landing.lua @@ -0,0 +1,457 @@ +-- support takeoff and landing on moving platforms for VTOL planes + +local PARAM_TABLE_KEY = 7 +local PARAM_TABLE_PREFIX = "SHIP_" + +local MODE_MANUAL = 0 +local MODE_RTL = 11 +local MODE_QRTL = 21 +local MODE_AUTO = 10 +local MODE_QLOITER = 19 + +local NAV_TAKEOFF = 22 +local NAV_VTOL_TAKEOFF = 84 + +local ALT_FRAME_ABSOLUTE = 0 + +-- 3 throttle position +local THROTTLE_LOW = 0 +local THROTTLE_MID = 1 +local THROTTLE_HIGH = 2 + +-- bind a parameter to a variable +function bind_param(name) + local p = Parameter() + assert(p:init(name), string.format('could not find %s parameter', name)) + return p +end + +-- add a parameter and bind it to a variable +function bind_add_param(name, idx, default_value) + assert(param:add_param(PARAM_TABLE_KEY, idx, name, default_value), string.format('could not add param %s', name)) + return bind_param(PARAM_TABLE_PREFIX .. name) +end + +-- setup SHIP specific parameters +assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 3), 'could not add param table') +SHIP_ENABLE = bind_add_param('ENABLE', 1, 0) +SHIP_LAND_ANGLE = bind_add_param('LAND_ANGLE', 2, 0) +SHIP_AUTO_OFS = bind_add_param('AUTO_OFS', 3, 0) + +-- other parameters +RCMAP_THROTTLE = bind_param("RCMAP_THROTTLE") +ALT_HOLD_RTL = bind_param("ALT_HOLD_RTL") +Q_RTL_ALT = bind_param("Q_RTL_ALT") +TRIM_ARSPD_CM = bind_param("TRIM_ARSPD_CM") +TECS_LAND_ARSPD = bind_param("TECS_LAND_ARSPD") +Q_TRANS_DECEL = bind_param("Q_TRANS_DECEL") +WP_LOITER_RAD = bind_param("WP_LOITER_RAD") +RTL_RADIUS = bind_param("RTL_RADIUS") +FOLL_OFS_X = bind_param("FOLL_OFS_X") +FOLL_OFS_Y = bind_param("FOLL_OFS_Y") +FOLL_OFS_Z = bind_param("FOLL_OFS_Z") + +-- an auth ID to disallow arming when we don't have the beacon +local auth_id = arming:get_aux_auth_id() +arming:set_aux_auth_failed(auth_id, "Ship: no beacon") + +-- current target +local target_pos = Location() +local current_pos = Location() +local target_velocity = Vector3f() +local target_heading = 0.0 + +-- landing stages +local STAGE_HOLDOFF = 0 +local STAGE_DESCEND = 1 +local STAGE_APPROACH = 2 +local STAGE_IDLE = 2 +local landing_stage = STAGE_HOLDOFF + +-- other state +local vehicle_mode = MODE_MANUAL +local reached_alt = false +local throttle_pos = THROTTLE_HIGH +local have_target = false + +-- square a variable +function sq(v) + return v*v +end + +-- check key parameters +function check_parameters() + --[[ + parameter values which are auto-set on startup + --]] + local key_params = { + FOLL_ENABLE = 1, + FOLL_OFS_TYPE = 1, + FOLL_ALT_TYPE = 0, + } + + for p, v in pairs(key_params) do + local current = param:get(p) + assert(current, string.format("Parameter %s not found", p)) + if math.abs(v-current) > 0.001 then + param:set_and_save(p, v) + gcs:send_text(0,string.format("Parameter %s set to %.2f was %.2f", p, v, current)) + end + end +end + +-- update the pilots throttle position +function update_throttle_pos() + local tpos + if not rc:has_valid_input() then + tpos = THROTTLE_LOW + else + local tchan = rc:get_channel(RCMAP_THROTTLE:get()) + local tval = (tchan:norm_input_ignore_trim()+1.0)*0.5 + if tval >= 0.40 then + tpos = THROTTLE_HIGH + elseif tval >= 0.1 then + tpos = THROTTLE_MID + else + tpos = THROTTLE_LOW + end + end + if tpos ~= throttle_pos then + reached_alt = false + if landing_stage == STAGE_HOLDOFF and tpos <= THROTTLE_MID then + landing_stage = STAGE_DESCEND + gcs:send_text(0, string.format("Descending for approach (hd=%.1fm h=%.1f th=%.1f)", + get_holdoff_distance(), current_pos:alt()*0.01, get_target_alt())) + end + if landing_stage == STAGE_DESCEND and tpos == THROTTLE_HIGH then + gcs:send_text(0,"Climbing for holdoff") + landing_stage = STAGE_HOLDOFF + end + end + throttle_pos = tpos +end + +-- get landing airspeed +function get_land_airspeed() + if TECS_LAND_ARSPD:get() < 0 then + return TRIM_ARSPD_CM:get() * 0.01 + end + return TECS_LAND_ARSPD:get() +end + +--[[ + calculate stopping distance assuming we are flying at + TECS_LAND_ARSPD and are approaching the landing target from + behind. Take account of the wind estimate to get approach + groundspeed +--]] +function stopping_distance() + -- get the target true airspeed for approach + local tas = get_land_airspeed() * ahrs:get_EAS2TAS() + + -- add in wind in direction of flight + local wind = ahrs:wind_estimate():xy() + + -- rotate wind to be in approach frame + wind:rotate(-math.rad(target_heading + SHIP_LAND_ANGLE:get())) + + -- ship velocity rotated to the approach frame + local ship2d = target_velocity:xy() + ship2d:rotate(-math.rad(target_heading + SHIP_LAND_ANGLE:get())) + + -- calculate closing speed + -- use pythagoras theorem to solve for the wind triangle + local tas_sq = sq(tas) + local y_sq = sq(wind:y()) + local closing_speed + if tas_sq >= y_sq then + closing_speed = math.sqrt(tas_sq - y_sq) + else + -- min 1 m/s + closing_speed = 1.0 + end + + -- include the wind in the direction of the ship + closing_speed = closing_speed + wind:x() + + -- account for the ship velocity + closing_speed = closing_speed - ship2d:x() + + -- calculate stopping distance + return sq(closing_speed) / (2.0 * Q_TRANS_DECEL:get()) +end + +-- get holdoff distance +function get_holdoff_radius() + if RTL_RADIUS:get() ~= 0 then + return RTL_RADIUS:get() + end + return WP_LOITER_RAD:get() +end + +-- get holdoff distance +function get_holdoff_distance() + local radius = get_holdoff_radius() + local holdoff_dist = math.abs(radius*1.5) + local stop_distance = stopping_distance() + + -- increase holdoff distance by up to 50% to ensure we can stop + holdoff_dist = math.max(holdoff_dist, math.min(holdoff_dist*2.5, stop_distance*2)) + return holdoff_dist +end + +-- get the holdoff position +function get_holdoff_position() + local radius = get_holdoff_radius() + local heading_deg = target_heading + SHIP_LAND_ANGLE:get() + local holdoff_dist = get_holdoff_distance() + + local ofs = Vector2f() + ofs:x(-holdoff_dist) + ofs:y(radius) + ofs:rotate(math.rad(heading_deg)) + local target = target_pos:copy() + target:offset(ofs:x(), ofs:y()) + return target +end + +function wrap_360(angle) + local res = math.fmod(angle, 360.0) + if res < 0 then + res = res + 360.0 + end + return res +end + +function wrap_180(angle) + local res = wrap_360(angle) + if res > 180 then + res = res - 360 + end + return res +end + +--[[ + check if we have reached the tangent to the landing location +--]] +function check_approach_tangent() + local distance = current_pos:get_distance(target_pos) + local holdoff_dist = get_holdoff_distance() + if landing_stage == STAGE_HOLDOFF and throttle_pos <= THROTTLE_MID and distance < 4*holdoff_dist then + gcs:send_text(0, string.format("Descending for approach (hd=%.1fm)", holdoff_dist)) + landing_stage = STAGE_DESCEND + end + if reached_alt and landing_stage == STAGE_DESCEND then + -- go to approach stage when throttle is low, we are + -- pointing at the ship and have reached target alt. + -- Also require we are within 2.5 radius of the ship, and our heading is within 20 + -- degrees of the target heading + local target_bearing_deg = wrap_180(math.deg(current_pos:get_bearing(target_pos))) + local ground_bearing_deg = wrap_180(math.deg(ahrs:groundspeed_vector():angle())) + local margin = 10 + local distance = current_pos:get_distance(target_pos) + local holdoff_dist = get_holdoff_distance() + local error1 = math.abs(wrap_180(target_bearing_deg - ground_bearing_deg)) + local error2 = math.abs(wrap_180(ground_bearing_deg - (target_heading + SHIP_LAND_ANGLE:get()))) + logger:write('SLND','TBrg,GBrg,Dist,HDist,Err1,Err2','ffffff',target_bearing_deg, ground_bearing_deg, distance, holdoff_dist, error1, error2) + if (error1 < margin and + distance < 2.5*holdoff_dist and + distance > 0.7*holdoff_dist and + error2 < 2*margin) then + -- we are on the tangent, switch to QRTL + gcs:send_text(0, "Starting approach") + landing_stage = STAGE_APPROACH + vehicle:set_mode(MODE_QRTL) + end + end +end + +--[[ + check if we should abort a QRTL landing +--]] +function check_approach_abort() + local alt = current_pos:alt() * 0.01 + local target_alt = get_target_alt() + if alt > target_alt then + gcs:send_text(0, "Aborting landing") + landing_stage = STAGE_HOLDOFF + vehicle:set_mode(MODE_RTL) + end +end + +-- update state based on vehicle mode +function update_mode() + local mode = vehicle:get_mode() + if mode == vehicle_mode then + return + end + vehicle_mode = mode + if mode == MODE_RTL then + landing_stage = STAGE_HOLDOFF + reached_alt = false + elseif mode ~= MODE_QRTL then + landing_stage = STAGE_IDLE + reached_alt = false + end +end + +-- update target state +function update_target() + if not follow:have_target() then + if have_target then + gcs:send_text(0,"Lost beacon") + arming:set_aux_auth_failed(auth_id, "Ship: no beacon") + end + have_target = false + return + end + if not have_target then + gcs:send_text(0,"Have beacon") + arming:set_aux_auth_passed(auth_id) + end + have_target = true + + target_pos, target_velocity = follow:get_target_location_and_velocity_ofs() + target_pos:change_alt_frame(ALT_FRAME_ABSOLUTE) + target_heading = follow:get_target_heading_deg() + -- zero vertical velocity to reduce impact of ship movement + target_velocity:z(0) +end + +-- get the alt target for holdoff, AMSL +function get_target_alt() + local base_alt = target_pos:alt() * 0.01 + if landing_stage == STAGE_HOLDOFF then + return base_alt + ALT_HOLD_RTL:get() * 0.01 + end + return base_alt + Q_RTL_ALT:get() +end + +function update_alt() + local alt = current_pos:alt() * 0.01 + local target_alt = get_target_alt() + if landing_stage == STAGE_HOLDOFF or landing_stage == STAGE_DESCEND then + if math.abs(alt - target_alt) < 3 then + if not reached_alt then + gcs:send_text(0,"Reached target altitude") + end + reached_alt = true + end + end +end + +--[[ + update automatic beacon offsets +--]] + +function update_auto_offset() + if arming:is_armed() or math.floor(SHIP_AUTO_OFS:get()) ~= 1 then + return + end + + -- get target without offsets applied + target_no_ofs, vel = follow:get_target_location_and_velocity() + target_no_ofs:change_alt_frame(ALT_FRAME_ABSOLUTE) + + -- setup offsets so target location will be current location + local new = target_no_ofs:get_distance_NED(current_pos) + new:rotate_xy(-math.rad(target_heading)) + + gcs:send_text(0,string.format("Set follow offset (%.2f,%.2f,%.2f)", new:x(), new:y(), new:z())) + FOLL_OFS_X:set_and_save(new:x()) + FOLL_OFS_Y:set_and_save(new:y()) + FOLL_OFS_Z:set_and_save(new:z()) + + SHIP_AUTO_OFS:set_and_save(0) +end + +-- main update function +function update() + if SHIP_ENABLE:get() < 1 then + return + end + + update_target() + if not have_target then + return + end + + current_pos = ahrs:get_position() + if not current_pos then + return + end + current_pos:change_alt_frame(ALT_FRAME_ABSOLUTE) + + update_throttle_pos() + update_mode() + update_alt() + update_auto_offset() + + ahrs:set_home(target_pos) + + local next_WP = vehicle:get_target_location() + if not next_WP then + -- not in a flight mode with a target location + return + end + next_WP:change_alt_frame(ALT_FRAME_ABSOLUTE) + + if vehicle_mode == MODE_RTL then + local holdoff_pos = get_holdoff_position() + holdoff_pos:change_alt_frame(ALT_FRAME_ABSOLUTE) + holdoff_pos:alt(math.floor(get_target_alt()*100)) + vehicle:update_target_location(next_WP, holdoff_pos) + + if throttle_pos == THROTTLE_LOW then + check_approach_tangent() + end + + elseif vehicle_mode == MODE_QRTL then + vehicle:set_velocity_match(target_velocity:xy()) + target_pos:alt(next_WP:alt()) + vehicle:update_target_location(next_WP, target_pos) + + if throttle_pos == THROTTLE_HIGH then + check_approach_abort() + end + + elseif vehicle_mode == MODE_AUTO then + local id = mission:get_current_nav_id() + if id == NAV_VTOL_TAKEOFF or id == NAV_TAKEOFF then + vehicle:set_velocity_match(target_velocity:xy()) + local tpos = current_pos:copy() + tpos:alt(next_WP:alt()) + vehicle:update_target_location(next_WP, tpos) + end + + elseif vehicle_mode == MODE_QLOITER then + vehicle:set_velocity_match(target_velocity:xy()) + end + +end + +function loop() + update() + -- run at 20Hz + return loop, 50 +end + +check_parameters() + +-- wrapper around update(). This calls update() at 20Hz, +-- and if update faults then an error is displayed, but the script is not +-- stopped +function protected_wrapper() + local success, err = pcall(update) + if not success then + gcs:send_text(0, "Internal Error: " .. err) + -- when we fault we run the update function again after 1s, slowing it + -- down a bit so we don't flood the console with errors + return protected_wrapper, 1000 + end + return protected_wrapper, 50 +end + +-- start running update loop +return protected_wrapper() + diff --git a/libraries/AP_Scripting/examples/rover-MinFixType.lua b/libraries/AP_Scripting/examples/rover-MinFixType.lua new file mode 100755 index 00000000000..aabe1f44d61 --- /dev/null +++ b/libraries/AP_Scripting/examples/rover-MinFixType.lua @@ -0,0 +1,196 @@ +--[[---------------------------------------------------------------------------- + +MinFixType ArduPilot Lua script + +Checks for mission running and commands a hold/pause if the GPS fix type is less +than a threshold value. + +CAUTION: This script is capable of engaging and disengaging autonomous control +of a vehicle. Use this script AT YOUR OWN RISK. + +-- Yuri -- Aug 2021, revised Apr 2022 + +LICENSE - GNU GPLv3 https://www.gnu.org/licenses/gpl-3.0.en.html +------------------------------------------------------------------------------]] + +local SCRIPT_NAME = 'MinFixType' + +-------- MAVLINK/AUTOPILOT 'CONSTANTS' -------- +local ROVER_MODE_MANUAL = 0 +local ROVER_MODE_HOLD = 4 +local ROVER_MODE_AUTO = 10 +local MAV_SEVERITY_WARNING = 4 +local MAV_SEVERITY_INFO = 6 + +-------- USER EDITABLE GLOBALS -------- +local GPS_INSTANCE = 0 -- GPS to monitor (moving base, most likely) +local MIN_FIX_TYPE = 6 -- see table below +local MSN_PAUSE_MODE = ROVER_MODE_MANUAL -- mode to command when GPS fix is inadequate +local THR_SAFEGUARD_MODE = ROVER_MODE_HOLD -- mode to command if mission paused with non-zero throttle +local BAD_FIX_TIMEOUT = 1600 -- how long a bad fix type must be present before pausing the mission +local GOOD_FIX_TIMEOUT = 600 -- how long a good fix type must be present before resuming the mission +local RUN_INTERVAL_MS = 200 -- (ms) how often to run this script (50-250 should work fine) +local VERBOSE_MODE = 2 -- 0 to suppress all GCS messages, + -- 1 for normal status messages + -- 2 for additional debug messages +local MSG_NORMAL = 1 +local MSG_DEBUG = 2 + +local FIX_TYPES = { + [0] = 'No GPS', -- Lua arrays are 1 based unless you specify discrete indices like this + [1] = 'No Fix', + [2] = '2D Fix', + [3] = '3D Fix', + [4] = 'DGPS Fix', + [5] = 'RTK Float', + [6] = 'RTK Fixed', + [7] = 'Static Fixed', + [8] = 'PPP, 3D'} + +local MODE_THRESHOLDS = {1231, 1361, 1491, 1621, 1750, 2050} + +local USER_MODES = { + param:get('MODE1'), + param:get('MODE2'), + param:get('MODE3'), + param:get('MODE4'), + param:get('MODE5'), + param:get('MODE6') +} + +local MODE_CH = param:get('MODE_CH') +local THR_CH = param:get('RCMAP_THROTTLE') +local THR_TRIM = param:get(string.format('RC%d_TRIM', THR_CH)) +local THR_DZ = param:get(string.format('RC%d_DZ', THR_CH)) + +-- wrapper for gcs:send_text() +local function gcs_msg(msg_type, severity, txt) + if type(msg_type) == 'string' then + -- allow just a string to be passed for simple/routine messages + txt = msg_type + msg_type = MSG_NORMAL + severity = MAV_SEVERITY_INFO + end + if msg_type <= VERBOSE_MODE then + gcs:send_text(severity, string.format('%s: %s', SCRIPT_NAME, txt)) + end +end + +-- return RC transmitter selected mode +local function get_user_mode() + local pwm = rc:get_pwm(MODE_CH) + local mode_num = 6 + for i, threshold in pairs(MODE_THRESHOLDS) do + if (pwm < threshold) then + mode_num = i + break + end + end + return USER_MODES[mode_num] +end + +local function get_pause_mode() + if math.abs(rc:get_pwm(THR_CH) - THR_TRIM) > THR_DZ then + return THR_SAFEGUARD_MODE + end + return MSN_PAUSE_MODE +end + +function resume_mission() + if get_user_mode() ~= ROVER_MODE_AUTO then + gcs_msg(MSG_NORMAL, MAV_SEVERITY_WARNING, 'Pause Canceled - Mode Change') + return standby, RUN_INTERVAL_MS + end + if not arming:is_armed() then + gcs_msg(MSG_NORMAL, MAV_SEVERITY_WARNING, 'Pause Canceled - Disarmed') + return standby, RUN_INTERVAL_MS + end + + if gps:status(GPS_INSTANCE) < MIN_FIX_TYPE then + return mission_paused, RUN_INTERVAL_MS + end + + vehicle:set_mode(ROVER_MODE_AUTO) + gcs_msg('Mission Resumed') + return monitor, RUN_INTERVAL_MS +end + +function mission_paused() + if get_user_mode() ~= ROVER_MODE_AUTO then + gcs_msg(MSG_NORMAL, MAV_SEVERITY_WARNING, 'Pause Canceled - Mode Change') + return standby, RUN_INTERVAL_MS + end + if not arming:is_armed() then + gcs_msg(MSG_NORMAL, MAV_SEVERITY_WARNING, 'Pause Canceled - Disarmed') + return standby, RUN_INTERVAL_MS + end + + local fix_type = gps:status(GPS_INSTANCE) + if fix_type >= MIN_FIX_TYPE then + return resume_mission, GOOD_FIX_TIMEOUT + end + + if vehicle:get_mode() == THR_SAFEGUARD_MODE then + local mode = get_pause_mode() + if mode == MSN_PAUSE_MODE then + gcs_msg(MSG_NORMAL, MAV_SEVERITY_WARNING, 'Throttle neutral') + vehicle:set_mode(mode) + end + return mission_paused, RUN_INTERVAL_MS + end + + -- for edge cases where a non-RC command to resume was issued but fix type is still unsuitable + if vehicle:get_mode() ~= MSN_PAUSE_MODE then + gcs_msg(MSG_NORMAL, MAV_SEVERITY_WARNING, 'Cannot resume - ' .. FIX_TYPES[fix_type]) + vehicle:set_mode(get_pause_mode()) + end + return mission_paused, RUN_INTERVAL_MS +end + +function transition_to_pause() + if mission:state() ~= mission.MISSION_RUNNING then + return standby, RUN_INTERVAL_MS + end + + local fix_type = gps:status(GPS_INSTANCE) + + if fix_type >= MIN_FIX_TYPE then + return monitor, RUN_INTERVAL_MS + end + + local mode = get_pause_mode() + if mode == THR_SAFEGUARD_MODE then + gcs_msg(MSG_NORMAL, MAV_SEVERITY_WARNING, 'Throttle not neutral!') + end + + vehicle:set_mode(mode) + gcs_msg(MSG_NORMAL, MAV_SEVERITY_WARNING, 'Mission Paused - ' .. FIX_TYPES[fix_type]) + + return mission_paused, RUN_INTERVAL_MS +end + +function monitor() -- monitor for reduced GPS fix state during auto mission + if mission:state() ~= mission.MISSION_RUNNING then + return standby, RUN_INTERVAL_MS + end + + local fix_type = gps:status(GPS_INSTANCE) + + if fix_type < MIN_FIX_TYPE then + gcs_msg(MSG_DEBUG, MAV_SEVERITY_WARNING, 'GPS ' .. (GPS_INSTANCE + 1) .. ' - ' .. FIX_TYPES[fix_type]) + return transition_to_pause, BAD_FIX_TIMEOUT + end + + return monitor, RUN_INTERVAL_MS +end + +function standby() -- wait here until an auto mission is active + if mission:state() == mission.MISSION_RUNNING then + return monitor, RUN_INTERVAL_MS + end + return standby, RUN_INTERVAL_MS +end + +gcs_msg('Script active') + +return standby() diff --git a/libraries/AP_Scripting/examples/rover-SaveTurns.lua b/libraries/AP_Scripting/examples/rover-SaveTurns.lua new file mode 100755 index 00000000000..e90b4f90f30 --- /dev/null +++ b/libraries/AP_Scripting/examples/rover-SaveTurns.lua @@ -0,0 +1,161 @@ +--[[---------------------------------------------------------------------------- + +SaveTurns ArduPilot Lua script + +Saves the locations of vehicle turns as waypoints in the current nav mission. + +CAUTION: This script is capable of engaging and disengaging autonomous control +of a vehicle. Use this script AT YOUR OWN RISK. + +-- Yuri -- Nov 2021, revised Apr 2022 + +LICENSE - GNU GPLv3 https://www.gnu.org/licenses/gpl-3.0.en.html +------------------------------------------------------------------------------]] + +local SCRIPT_NAME = 'SaveTurns' + +-------- USER EDITABLE GLOBALS -------- +local RC_OPTION = 300 -- RC option number for switched control (300, 301, etc) +local MIN_DIST = 2.0 -- (m) min distance between waypoints +local HDG_DELTA = 8.0 -- (deg) save wp after heading change of this magnitude +local RUN_INTERVAL_MS = 200 -- (ms) how often to run this script +local VERBOSE_MODE = 2 -- 0 to suppress all GCS messages, + -- 1 for normal status messages + -- 2 for additional GPS/debug messages + +-------- MAVLINK/AUTOPILOT 'CONSTANTS' -------- +local ROVER_MODE_AUTO = 10 +local STANDBY = 0 +local SAVE_WPS = 1 +local CLEAR_WPS = 2 +local WAYPOINT = 16 -- waypoint command +local MAV_SEVERITY_WARNING = 4 +local MAV_SEVERITY_INFO = 6 +local MSG_NORMAL = 1 +local MSG_DEBUG = 2 + +local RC_CHAN = rc:find_channel_for_option(RC_OPTION) +local last_wp = Location() +local last_yaw = 999.0 + +-- wrapper for gcs:send_text() +local function gcs_msg(msg_type, severity, txt) + if type(msg_type) == 'string' then + -- allow just a string to be passed for simple/routine messages + txt = msg_type + msg_type = MSG_NORMAL + severity = MAV_SEVERITY_INFO + end + if msg_type <= VERBOSE_MODE then + gcs:send_text(severity, string.format('%s: %s', SCRIPT_NAME, txt)) + end +end + +local function yaw_diff(yaw1, yaw2) + --https://stackoverflow.com/questions/5024375/getting-the-difference-between-two-headings + return math.abs((yaw2 - yaw1 + 540.0) % 360.0 - 180.0) +end + +local function new_mission() + local home = ahrs:get_home() + local item = mavlink_mission_item_int_t() + + mission:clear() + + item:command(WAYPOINT) + item:x(home:lat()) + item:y(home:lng()) + item:z(home:alt()) + + if not mission:set_item(0, item) then + gcs_msg(MSG_NORMAL, MAV_SEVERITY_WARNING, 'Failed to create new mission') + return false + end + + return true +end + +local function save_wp(position, index) + local item = mavlink_mission_item_int_t() + + if (not position) then + gcs_msg(MSG_NORMAL, MAV_SEVERITY_WARNING, string.format('WP %d - invalid position', index)) + return false + end + + item:command(WAYPOINT) + item:x(position:lat()) + item:y(position:lng()) + item:z(0) + + if not mission:set_item(index, item) then + gcs_msg(MSG_NORMAL, MAV_SEVERITY_WARNING, string.format('WP %d - failed to save', index)) + return false + end + + return true +end + +function collect_breadcrumbs() + if vehicle:get_mode() == ROVER_MODE_AUTO then + gcs_msg('AUTO mode - saving canceled') + return standby, RUN_INTERVAL_MS + end + local sw_pos = RC_CHAN:get_aux_switch_pos() + if sw_pos ~= SAVE_WPS then return standby, RUN_INTERVAL_MS end + + if not ahrs:healthy() then return collect_breadcrumbs, RUN_INTERVAL_MS end + + local cur_pos = ahrs:get_location() + local cur_yaw = ahrs:get_yaw() * 180.0 / math.pi + + if cur_pos:get_distance(last_wp) < MIN_DIST then + last_yaw = cur_yaw + return collect_breadcrumbs, RUN_INTERVAL_MS + end + + if yaw_diff(cur_yaw, last_yaw) > HDG_DELTA then + local idx = mission:num_commands() + if save_wp(cur_pos, idx) then + gcs_msg(string.format('WP %d - saved', idx)) + last_wp = cur_pos + last_yaw = cur_yaw + end + end + + return collect_breadcrumbs, RUN_INTERVAL_MS +end + +function await_switch_change() + local sw_pos = RC_CHAN:get_aux_switch_pos() + if sw_pos == STANDBY then return standby, RUN_INTERVAL_MS end + if sw_pos == SAVE_WPS then return collect_breadcrumbs, RUN_INTERVAL_MS end + return await_switch_change, RUN_INTERVAL_MS +end + +function standby() + if vehicle:get_mode() == ROVER_MODE_AUTO then return standby, RUN_INTERVAL_MS end + local sw_pos = RC_CHAN:get_aux_switch_pos() + if sw_pos == SAVE_WPS then + last_wp = Location() + last_yaw = 999.0 + return collect_breadcrumbs, RUN_INTERVAL_MS + end + if sw_pos == CLEAR_WPS then + if new_mission() then + gcs_msg(MSG_NORMAL, MAV_SEVERITY_WARNING, 'Mission cleared') + end + return await_switch_change, RUN_INTERVAL_MS + end + return standby, RUN_INTERVAL_MS +end + +function initialize() + if not ahrs:healthy() then return initialize, RUN_INTERVAL_MS end + gcs_msg('Ready') + return standby, RUN_INTERVAL_MS +end + +gcs_msg('Awaiting AHRS initialization...') + +return initialize() diff --git a/libraries/AP_Scripting/examples/rover-TerrainDetector.lua b/libraries/AP_Scripting/examples/rover-TerrainDetector.lua new file mode 100644 index 00000000000..7ba86468210 --- /dev/null +++ b/libraries/AP_Scripting/examples/rover-TerrainDetector.lua @@ -0,0 +1,209 @@ +--[[---------------------------------------------------------------------------- + +TerrainDetector ArduPilot Lua script + +Uses gyro and accelerometer data to detect rough terrain and slow the +vehicle's speed accordingly during auto missions. + +Provides a set of custom tuning parameters: +ROUGH_SPEED : (m/s) rough terrain desired speed, set to -1 to disable detection +ROUGH_TIMEOUT_MS: (ms) min time to remain slowed down for rough terrain +ROUGH_GZ_MAX : (G) slow down on Gz impulses greater than this value +ROUGH_RATE_MAX : (deg/s) slow down on rate transients greater than this value + +These gain values are used for smooth terrain detection. +Smaller values (less than 1.0) are more restrictive about resuming normal speed. +ROUGH_GZ_GAIN : Gz impulse gain +ROUGH_RATE_GAIN : gyro transient rate gain + +CAUTION: This script is capable of engaging and disengaging autonomous control +of a vehicle. Use this script AT YOUR OWN RISK. + +-- Yuri -- Jul 2022 + +LICENSE - GNU GPLv3 https://www.gnu.org/licenses/gpl-3.0.en.html + +Concept first presented during this live stream: +https://www.youtube.com/watch?v=UdXGXjigxAo&t=7155s +Credit to @ktrussell for the idea and discussion! +------------------------------------------------------------------------------]] + +local SCRIPT_NAME = 'TerrainDetector' +local RUN_INTERVAL_MS = 25 -- needs to be pretty fast for good detection +local SBY_INTERVAL_MS = 500 -- slower interval when detection is disabled +local PARAM_TABLE_KEY = 117 -- unique index value between 0 and 200 + +-- GCS messages +local VERBOSE_MODE = 1 -- 0 to suppress all GCS messages, + -- 1 for normal status messages + -- 2 for additional debug messages +local MSG_NORMAL = 1 +local MSG_DEBUG = 2 + +-- MAVLink values +local MAV_SEVERITY_WARNING = 4 +local MAV_SEVERITY_INFO = 6 + +-- mathematical/physical constants +local G = -9.81 -- m/s/s + +-- create custom parameter set +local function add_params(key, prefix, tbl) + assert(param:add_table(key, prefix, #tbl), string.format('Could not add %s param table.', prefix)) + for num = 1, #tbl do + assert(param:add_param(key, num, tbl[num][1], tbl[num][2]), string.format('Could not add %s%s.', prefix, tbl[num][1])) + end +end + +add_params(PARAM_TABLE_KEY, 'ROUGH_', { + -- { name, default value }, + { 'SPEED', 0.7 }, + { 'GZ_MAX', 1.33 }, + { 'RATE_MAX', 28 }, + { 'GZ_GAIN', 0.9 }, + { 'RATE_GAIN', 0.8 }, + { 'TIMEOUT_MS', 7500 } + }) + +-- wrapper for gcs:send_text() +local function gcs_msg(msg_type, severity, txt) + if type(msg_type) == 'string' then + -- allow just a string to be passed for simple/routine messages + txt = msg_type + msg_type = MSG_NORMAL + severity = MAV_SEVERITY_INFO + end + if type(severity) == 'string' then + -- allow just severity and string to be passed for normal messages + txt = severity + severity = msg_type + msg_type = MSG_NORMAL + end + if msg_type <= VERBOSE_MODE then + gcs:send_text(severity, string.format('%s: %s', SCRIPT_NAME, txt)) + end +end + +local last_g_z = 0 -- to calculate impulse Gz +local timeout_ms = 0 + +-- debug values +local max_g_z = 0 +local max_gyro_rate = 0 + +local wp_speed_normal = nil +local wp_speed_rough = nil +local impulse_gz_threshold = nil +local gyro_rate_threshold = nil +local rough_terrain_timeout_ms = nil +local impulse_gain = nil +local gyro_gain = nil + +function standby() + wp_speed_rough = param:get('ROUGH_SPEED') + if wp_speed_rough < 0 then return standby, SBY_INTERVAL_MS end + + if mission:state() == mission.MISSION_RUNNING then + -- only poll remaining parameters at start of mission + wp_speed_normal = param:get('WP_SPEED') + impulse_gz_threshold = param:get('ROUGH_GZ_MAX') + gyro_rate_threshold = param:get('ROUGH_RATE_MAX') + rough_terrain_timeout_ms = param:get('ROUGH_TIMEOUT_MS') + impulse_gain = param:get('ROUGH_GZ_GAIN') + gyro_gain = param:get('ROUGH_RATE_GAIN') + -- if ROUGH_SPEED param not set or invalid, use half of WP_SPEED + if wp_speed_rough == 0 or wp_speed_rough > wp_speed_normal then + wp_speed_rough = wp_speed_normal / 2 + gcs_msg(MAV_SEVERITY_WARNING, 'ROUGH_SPEED invalid, using half WP_SPEED') + end + + last_g_z = 0 + return do_normal_speed, RUN_INTERVAL_MS + end + return standby, SBY_INTERVAL_MS +end + +function initiate_rough_speed() + gcs_msg(MSG_NORMAL, MAV_SEVERITY_WARNING, 'Slowing for rough terrain') + vehicle:set_desired_speed(wp_speed_rough) + last_g_z = 0 + timeout_ms = millis() + rough_terrain_timeout_ms + max_g_z = 0 + max_gyro_rate = 0 + return do_rough_speed, RUN_INTERVAL_MS +end + +function initiate_normal_speed() + gcs_msg(MSG_NORMAL, MAV_SEVERITY_WARNING, 'Resuming normal speed') + vehicle:set_desired_speed(wp_speed_normal) + last_g_z = 0 + return do_normal_speed, RUN_INTERVAL_MS +end + +function do_normal_speed() + if mission:state() ~= mission.MISSION_RUNNING then + return standby, SBY_INTERVAL_MS + end + + local g_z = ahrs:get_accel():z() / G -- convert to G from m/s/s + local gyro = ahrs:get_gyro() + -- sample max of roll/pitch rates + local gyro_rate = math.deg(math.max(math.abs(gyro:x()), math.abs(gyro:y()))) + local impulse_g_z = math.abs(g_z - last_g_z) -- sample delta is the measured impulse + last_g_z = g_z + + if impulse_g_z > impulse_gz_threshold then -- slow down + gcs_msg(MSG_DEBUG, MAV_SEVERITY_INFO, string.format('Impulse - %.2f Gz', impulse_g_z)) + return initiate_rough_speed, RUN_INTERVAL_MS + end + + if gyro_rate > gyro_rate_threshold then -- slow down + gcs_msg(MSG_DEBUG, MAV_SEVERITY_INFO, string.format('Transient - %.2f deg/s', gyro_rate)) + return initiate_rough_speed, RUN_INTERVAL_MS + end + + return do_normal_speed, RUN_INTERVAL_MS +end + +function do_rough_speed() + if mission:state() ~= mission.MISSION_RUNNING then + return standby, SBY_INTERVAL_MS + end + + local g_z = ahrs:get_accel():z() / G -- convert to G from m/s/s + local gyro = ahrs:get_gyro() + -- sample max of roll/pitch rates + local gyro_rate = math.deg(math.max(math.abs(gyro:x()), math.abs(gyro:y()))) + local impulse_g_z = math.abs(g_z - last_g_z) -- sample delta is the measured impulse + last_g_z = g_z + + max_g_z = math.max(g_z, max_g_z) + max_gyro_rate = math.max(gyro_rate, max_gyro_rate) + + local now = millis() + + if impulse_g_z > impulse_gz_threshold * impulse_gain then -- stay slow + gcs_msg(MSG_DEBUG, MAV_SEVERITY_INFO, string.format('Timer reset - %.2fGz', impulse_g_z)) + max_g_z = 0 + timeout_ms = now + rough_terrain_timeout_ms + return do_rough_speed, RUN_INTERVAL_MS + end + + if gyro_rate > gyro_rate_threshold * gyro_gain then -- stay slow + gcs_msg(MSG_DEBUG, MAV_SEVERITY_INFO, string.format('Timer reset - %.2f deg/s', gyro_rate)) + max_gyro_rate = 0 + timeout_ms = now + rough_terrain_timeout_ms + return do_rough_speed, RUN_INTERVAL_MS + end + + if now > timeout_ms then -- no longer in rough terrain + gcs_msg(MSG_DEBUG, MAV_SEVERITY_INFO, string.format('Max - %.2fGz ... %.2f deg/s', max_g_z, max_gyro_rate)) + return initiate_normal_speed, RUN_INTERVAL_MS + end + + return do_rough_speed, RUN_INTERVAL_MS +end + +gcs_msg('Script active') + +return standby, SBY_INTERVAL_MS diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index fba015b46e7..83e168fa57c 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -23,13 +23,13 @@ userdata Location method copy Location include AP_AHRS/AP_AHRS.h -singleton AP_AHRS alias ahrs +singleton AP_AHRS rename ahrs singleton AP_AHRS semaphore singleton AP_AHRS method get_roll float singleton AP_AHRS method get_pitch float singleton AP_AHRS method get_yaw float singleton AP_AHRS method get_location boolean Location'Null -singleton AP_AHRS method get_position boolean Location'Null +singleton AP_AHRS method get_location alias get_position singleton AP_AHRS method get_home Location singleton AP_AHRS method get_gyro Vector3f singleton AP_AHRS method get_accel Vector3f @@ -39,6 +39,7 @@ singleton AP_AHRS method groundspeed_vector Vector2f singleton AP_AHRS method get_velocity_NED boolean Vector3f'Null singleton AP_AHRS method get_relative_position_NED_home boolean Vector3f'Null singleton AP_AHRS method get_relative_position_NED_origin boolean Vector3f'Null +singleton AP_AHRS method get_relative_position_D_home void float'Ref singleton AP_AHRS method home_is_set boolean singleton AP_AHRS method healthy boolean singleton AP_AHRS method airspeed_estimate boolean float'Null @@ -53,12 +54,14 @@ singleton AP_AHRS method set_home boolean Location singleton AP_AHRS method get_origin boolean Location'Null singleton AP_AHRS method set_origin boolean Location singleton AP_AHRS method initialised boolean +singleton AP_AHRS method get_posvelyaw_source_set uint8_t include AP_Arming/AP_Arming.h -singleton AP_Arming alias arming +singleton AP_Arming rename arming singleton AP_Arming method disarm boolean AP_Arming::Method::SCRIPTING'literal singleton AP_Arming method is_armed boolean +singleton AP_Arming method pre_arm_checks boolean false'literal singleton AP_Arming method arm boolean AP_Arming::Method::SCRIPTING'literal singleton AP_Arming method get_aux_auth_id boolean uint8_t'Null singleton AP_Arming method set_aux_auth_passed void uint8_t 0 UINT8_MAX @@ -66,7 +69,7 @@ singleton AP_Arming method set_aux_auth_failed void uint8_t 0 UINT8_MAX string include AP_BattMonitor/AP_BattMonitor.h -singleton AP_BattMonitor alias battery +singleton AP_BattMonitor rename battery singleton AP_BattMonitor method num_instances uint8_t singleton AP_BattMonitor method healthy boolean uint8_t 0 ud->num_instances() singleton AP_BattMonitor method voltage float uint8_t 0 ud->num_instances() @@ -84,7 +87,7 @@ singleton AP_BattMonitor method reset_remaining boolean uint8_t 0 ud->num_instan include AP_GPS/AP_GPS.h -singleton AP_GPS alias gps +singleton AP_GPS rename gps singleton AP_GPS enum NO_GPS NO_FIX GPS_OK_FIX_2D GPS_OK_FIX_3D GPS_OK_FIX_3D_DGPS GPS_OK_FIX_3D_RTK_FLOAT GPS_OK_FIX_3D_RTK_FIXED singleton AP_GPS method num_sensors uint8_t singleton AP_GPS method primary_sensor uint8_t @@ -123,6 +126,8 @@ userdata Vector3f method dot float Vector3f userdata Vector3f method cross Vector3f Vector3f userdata Vector3f method scale Vector3f float'skip_check userdata Vector3f method copy Vector3f +userdata Vector3f method xy Vector2f +userdata Vector3f method rotate_xy void float'skip_check userdata Vector2f field x float'skip_check read write userdata Vector2f field y float'skip_check read write @@ -131,6 +136,7 @@ userdata Vector2f method normalize void userdata Vector2f method is_nan boolean userdata Vector2f method is_inf boolean userdata Vector2f method is_zero boolean +userdata Vector2f method angle float userdata Vector2f method rotate void float'skip_check userdata Vector2f operator + userdata Vector2f operator - @@ -138,7 +144,7 @@ userdata Vector2f method copy Vector2f include AP_Notify/AP_Notify.h -singleton AP_Notify alias notify +singleton AP_Notify rename notify singleton AP_Notify method play_tune void string singleton AP_Notify method handle_rgb void uint8_t 0 UINT8_MAX uint8_t 0 UINT8_MAX uint8_t 0 UINT8_MAX uint8_t 0 UINT8_MAX singleton AP_Notify method handle_rgb_id void uint8_t 0 UINT8_MAX uint8_t 0 UINT8_MAX uint8_t 0 UINT8_MAX uint8_t 0 UINT8_MAX @@ -146,7 +152,7 @@ singleton AP_Notify method handle_rgb_id void uint8_t 0 UINT8_MAX uint8_t 0 UINT include AP_Proximity/AP_Proximity.h singleton AP_Proximity depends HAL_PROXIMITY_ENABLED == 1 -singleton AP_Proximity alias proximity +singleton AP_Proximity rename proximity singleton AP_Proximity method get_status uint8_t singleton AP_Proximity method num_sensors uint8_t singleton AP_Proximity method get_object_count uint8_t @@ -155,7 +161,7 @@ singleton AP_Proximity method get_object_angle_and_distance boolean uint8_t 0 UI include AP_RangeFinder/AP_RangeFinder.h -singleton RangeFinder alias rangefinder +singleton RangeFinder rename rangefinder singleton RangeFinder method num_sensors uint8_t singleton RangeFinder method has_orientation boolean Rotation'enum ROTATION_NONE ROTATION_MAX-1 singleton RangeFinder method distance_cm_orient uint16_t Rotation'enum ROTATION_NONE ROTATION_MAX-1 @@ -169,7 +175,7 @@ singleton RangeFinder method get_pos_offset_orient Vector3f Rotation'enum ROTATI include AP_Terrain/AP_Terrain.h singleton AP_Terrain depends defined(AP_TERRAIN_AVAILABLE) && AP_TERRAIN_AVAILABLE == 1 -singleton AP_Terrain alias terrain +singleton AP_Terrain rename terrain singleton AP_Terrain method enabled boolean singleton AP_Terrain enum TerrainStatusDisabled TerrainStatusUnhealthy TerrainStatusOK singleton AP_Terrain method status uint8_t @@ -179,28 +185,29 @@ singleton AP_Terrain method height_above_terrain boolean float'Null boolean include AP_Relay/AP_Relay.h -singleton AP_Relay alias relay +singleton AP_Relay rename relay singleton AP_Relay method on void uint8_t 0 AP_RELAY_NUM_RELAYS singleton AP_Relay method off void uint8_t 0 AP_RELAY_NUM_RELAYS singleton AP_Relay method enabled boolean uint8_t 0 AP_RELAY_NUM_RELAYS singleton AP_Relay method toggle void uint8_t 0 AP_RELAY_NUM_RELAYS +singleton AP_Relay method get uint8_t uint8_t 0 AP_RELAY_NUM_RELAYS include GCS_MAVLink/GCS.h -singleton GCS alias gcs +singleton GCS rename gcs singleton GCS method send_text void MAV_SEVERITY'enum MAV_SEVERITY_EMERGENCY MAV_SEVERITY_DEBUG "%s"'literal string singleton GCS method set_message_interval MAV_RESULT'enum uint8_t 0 MAVLINK_COMM_NUM_BUFFERS uint32_t 0U UINT32_MAX int32_t -1 INT32_MAX singleton GCS method send_named_float void string float'skip_check include AP_ONVIF/AP_ONVIF.h depends ENABLE_ONVIF == 1 singleton AP_ONVIF depends ENABLE_ONVIF == 1 -singleton AP_ONVIF alias onvif +singleton AP_ONVIF rename onvif singleton AP_ONVIF method start boolean string string string singleton AP_ONVIF method set_absolutemove boolean float'skip_check float'skip_check float'skip_check singleton AP_ONVIF method get_pan_tilt_limit_min Vector2f singleton AP_ONVIF method get_pan_tilt_limit_max Vector2f include AP_Vehicle/AP_Vehicle.h -singleton AP_Vehicle alias vehicle +singleton AP_Vehicle rename vehicle singleton AP_Vehicle scheduler-semaphore singleton AP_Vehicle method set_mode boolean uint8_t 0 UINT8_MAX ModeReason::SCRIPTING'literal singleton AP_Vehicle method get_mode uint8_t @@ -211,6 +218,7 @@ singleton AP_Vehicle method get_control_output boolean AP_Vehicle::ControlOutput singleton AP_Vehicle method start_takeoff boolean float (-LOCATION_ALT_MAX_M*100+1) (LOCATION_ALT_MAX_M*100-1) singleton AP_Vehicle method set_target_location boolean Location singleton AP_Vehicle method get_target_location boolean Location'Null +singleton AP_Vehicle method update_target_location boolean Location Location singleton AP_Vehicle method set_target_pos_NED boolean Vector3f boolean float -360 +360 boolean float'skip_check boolean boolean singleton AP_Vehicle method set_target_posvel_NED boolean Vector3f Vector3f singleton AP_Vehicle method set_target_posvelaccel_NED boolean Vector3f Vector3f Vector3f boolean float -360 +360 boolean float'skip_check boolean @@ -228,18 +236,20 @@ singleton AP_Vehicle method nav_script_time boolean uint16_t'Null uint8_t'Null f singleton AP_Vehicle method nav_script_time_done void uint16_t'skip_check singleton AP_Vehicle method set_target_throttle_rate_rpy void float -100 100 float'skip_check float'skip_check float'skip_check singleton AP_Vehicle method set_desired_turn_rate_and_speed boolean float'skip_check float'skip_check +singleton AP_Vehicle method set_desired_speed boolean float'skip_check singleton AP_Vehicle method nav_scripting_enable boolean uint8_t 0 UINT8_MAX - +singleton AP_Vehicle method set_velocity_match boolean Vector2f +singleton AP_Vehicle method has_ekf_failsafed boolean include AP_SerialLED/AP_SerialLED.h -singleton AP_SerialLED alias serialLED +singleton AP_SerialLED rename serialLED singleton AP_SerialLED method set_num_neopixel boolean uint8_t 1 16 uint8_t 0 AP_SERIALLED_MAX_LEDS singleton AP_SerialLED method set_num_profiled boolean uint8_t 1 16 uint8_t 0 AP_SERIALLED_MAX_LEDS singleton AP_SerialLED method set_RGB void uint8_t 1 16 int8_t -1 INT8_MAX uint8_t 0 UINT8_MAX uint8_t 0 UINT8_MAX uint8_t 0 UINT8_MAX singleton AP_SerialLED method send void uint8_t 1 16 include SRV_Channel/SRV_Channel.h -singleton SRV_Channels alias SRV_Channels +singleton SRV_Channels rename SRV_Channels singleton SRV_Channels method find_channel boolean SRV_Channel::Aux_servo_function_t'enum SRV_Channel::k_none SRV_Channel::k_nr_aux_servo_functions-1 uint8_t'Null singleton SRV_Channels method set_output_pwm void SRV_Channel::Aux_servo_function_t'enum SRV_Channel::k_none SRV_Channel::k_nr_aux_servo_functions-1 uint16_t 0 UINT16_MAX singleton SRV_Channels method set_output_pwm_chan void uint8_t 0 NUM_SERVO_CHANNELS-1 uint16_t 0 UINT16_MAX @@ -252,18 +262,21 @@ singleton SRV_Channels method set_angle void SRV_Channel::Aux_servo_function_t'e singleton SRV_Channels method set_range void SRV_Channel::Aux_servo_function_t'enum SRV_Channel::k_none SRV_Channel::k_nr_aux_servo_functions-1 uint16_t 0 UINT16_MAX ap_object RC_Channel method norm_input float +ap_object RC_Channel method norm_input_dz float ap_object RC_Channel method get_aux_switch_pos uint8_t ap_object RC_Channel method norm_input_ignore_trim float +ap_object RC_Channel method set_override void uint16_t 0 2200 0'literal include RC_Channel/RC_Channel.h -singleton RC_Channels alias rc +singleton RC_Channels rename rc singleton RC_Channels scheduler-semaphore singleton RC_Channels method get_pwm boolean uint8_t 1 NUM_RC_CHANNELS uint16_t'Null singleton RC_Channels method find_channel_for_option RC_Channel RC_Channel::AUX_FUNC'enum 0 UINT16_MAX singleton RC_Channels method run_aux_function boolean RC_Channel::AUX_FUNC'enum 0 UINT16_MAX RC_Channel::AuxSwitchPos'enum RC_Channel::AuxSwitchPos::LOW RC_Channel::AuxSwitchPos::HIGH RC_Channel::AuxFuncTriggerSource::SCRIPTING'literal singleton RC_Channels method has_valid_input boolean singleton RC_Channels method lua_rc_channel RC_Channel uint8_t 1 NUM_RC_CHANNELS -singleton RC_Channels method lua_rc_channel alias get_channel +singleton RC_Channels method lua_rc_channel rename get_channel +singleton RC_Channels method get_aux_cached boolean RC_Channel::AUX_FUNC'enum 0 UINT16_MAX uint8_t'Null include AP_SerialManager/AP_SerialManager.h @@ -273,25 +286,25 @@ ap_object AP_HAL::UARTDriver method write uint32_t uint8_t 0 UINT8_MAX ap_object AP_HAL::UARTDriver method available uint32_t ap_object AP_HAL::UARTDriver method set_flow_control void AP_HAL::UARTDriver::flow_control'enum AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE AP_HAL::UARTDriver::FLOW_CONTROL_AUTO -singleton AP_SerialManager alias serial +singleton AP_SerialManager rename serial singleton AP_SerialManager method find_serial AP_HAL::UARTDriver AP_SerialManager::SerialProtocol_Scripting'literal uint8_t 0 UINT8_MAX include AP_Baro/AP_Baro.h -singleton AP_Baro alias baro +singleton AP_Baro rename baro singleton AP_Baro method get_pressure float singleton AP_Baro method get_temperature float singleton AP_Baro method get_external_temperature float include AP_OpticalFlow/AP_OpticalFlow.h -singleton OpticalFlow depends AP_OPTICALFLOW_ENABLED -singleton OpticalFlow alias optical_flow -singleton OpticalFlow method enabled boolean -singleton OpticalFlow method healthy boolean -singleton OpticalFlow method quality uint8_t +singleton AP_OpticalFlow depends AP_OPTICALFLOW_ENABLED +singleton AP_OpticalFlow rename optical_flow +singleton AP_OpticalFlow method enabled boolean +singleton AP_OpticalFlow method healthy boolean +singleton AP_OpticalFlow method quality uint8_t include AP_ESC_Telem/AP_ESC_Telem.h singleton AP_ESC_Telem depends HAL_WITH_ESC_TELEM == 1 -singleton AP_ESC_Telem alias esc_telem +singleton AP_ESC_Telem rename esc_telem singleton AP_ESC_Telem method get_rpm boolean uint8_t 0 NUM_SERVO_CHANNELS float'Null singleton AP_ESC_Telem method get_temperature boolean uint8_t 0 NUM_SERVO_CHANNELS int16_t'Null singleton AP_ESC_Telem method get_motor_temperature boolean uint8_t 0 NUM_SERVO_CHANNELS int16_t'Null @@ -299,16 +312,18 @@ singleton AP_ESC_Telem method get_current boolean uint8_t 0 NUM_SERVO_CHANNELS f singleton AP_ESC_Telem method get_voltage boolean uint8_t 0 NUM_SERVO_CHANNELS float'Null singleton AP_ESC_Telem method get_consumption_mah boolean uint8_t 0 NUM_SERVO_CHANNELS float'Null singleton AP_ESC_Telem method get_usage_seconds boolean uint8_t 0 NUM_SERVO_CHANNELS uint32_t'Null +singleton AP_ESC_Telem method update_rpm void uint8_t 0 NUM_SERVO_CHANNELS uint16_t'skip_check float'skip_check +singleton AP_ESC_Telem method set_rpm_scale void uint8_t 0 NUM_SERVO_CHANNELS float'skip_check include AP_Param/AP_Param.h -singleton AP_Param alias param +singleton AP_Param rename param singleton AP_Param method get boolean string float'Null singleton AP_Param method set_by_name boolean string float'skip_check -singleton AP_Param method set_by_name alias set +singleton AP_Param method set_by_name rename set singleton AP_Param method set_and_save_by_name boolean string float'skip_check -singleton AP_Param method set_and_save_by_name alias set_and_save +singleton AP_Param method set_and_save_by_name rename set_and_save singleton AP_Param method set_default_by_name boolean string float'skip_check -singleton AP_Param method set_default_by_name alias set_default +singleton AP_Param method set_default_by_name rename set_default singleton AP_Param method add_table boolean uint8_t 0 200 string uint8_t 1 63 singleton AP_Param method add_param boolean uint8_t 0 200 uint8_t 1 63 string float'skip_check @@ -323,7 +338,7 @@ userdata Parameter method set_default boolean float'skip_check include AP_Mission/AP_Mission.h -singleton AP_Mission alias mission +singleton AP_Mission rename mission singleton AP_Mission scheduler-semaphore singleton AP_Mission enum MISSION_STOPPED MISSION_RUNNING MISSION_COMPLETE singleton AP_Mission method state uint8_t @@ -354,39 +369,39 @@ userdata mavlink_mission_item_int_t field current uint8_t read write 0 UINT8_MA include AP_RPM/AP_RPM.h -singleton AP_RPM alias RPM +singleton AP_RPM rename RPM singleton AP_RPM method get_rpm boolean uint8_t 0 RPM_MAX_INSTANCES float'Null include AP_Button/AP_Button.h singleton AP_Button depends HAL_BUTTON_ENABLED == 1 -singleton AP_Button alias button +singleton AP_Button rename button singleton AP_Button method get_button_state boolean uint8_t 1 AP_BUTTON_NUM_PINS include AP_Notify/ScriptingLED.h -singleton ScriptingLED alias LED +singleton ScriptingLED rename LED singleton ScriptingLED method get_rgb void uint8_t'Ref uint8_t'Ref uint8_t'Ref include ../ArduPlane/quadplane.h depends APM_BUILD_TYPE(APM_BUILD_ArduPlane) -singleton QuadPlane alias quadplane +singleton QuadPlane rename quadplane singleton QuadPlane depends APM_BUILD_TYPE(APM_BUILD_ArduPlane) && HAL_QUADPLANE_ENABLED singleton QuadPlane method in_vtol_mode boolean singleton QuadPlane method in_assisted_flight boolean include AP_Motors/AP_MotorsMatrix.h depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI singleton AP_MotorsMatrix depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI -singleton AP_MotorsMatrix alias MotorsMatrix +singleton AP_MotorsMatrix rename MotorsMatrix singleton AP_MotorsMatrix method init boolean uint8_t 0 AP_MOTORS_MAX_NUM_MOTORS singleton AP_MotorsMatrix method add_motor_raw void int8_t 0 (AP_MOTORS_MAX_NUM_MOTORS-1) float'skip_check float'skip_check float'skip_check uint8_t 0 AP_MOTORS_MAX_NUM_MOTORS singleton AP_MotorsMatrix method set_throttle_factor boolean int8_t 0 (AP_MOTORS_MAX_NUM_MOTORS-1) float 0 FLT_MAX include AP_Frsky_Telem/AP_Frsky_SPort.h -singleton AP_Frsky_SPort alias frsky_sport +singleton AP_Frsky_SPort rename frsky_sport singleton AP_Frsky_SPort method sport_telemetry_push boolean uint8_t 0 UINT8_MAX uint8_t 0 UINT8_MAX uint16_t 0 UINT16_MAX int32_t -INT32_MAX INT32_MAX singleton AP_Frsky_SPort method prep_number uint16_t int32_t INT32_MIN INT32_MAX uint8_t 0 UINT8_MAX uint8_t 0 UINT8_MAX include AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.h depends APM_BUILD_TYPE(APM_BUILD_ArduCopter) singleton AC_AttitudeControl_Multi_6DoF depends APM_BUILD_TYPE(APM_BUILD_ArduCopter) -singleton AC_AttitudeControl_Multi_6DoF alias attitude_control +singleton AC_AttitudeControl_Multi_6DoF rename attitude_control singleton AC_AttitudeControl_Multi_6DoF method set_lateral_enable void boolean singleton AC_AttitudeControl_Multi_6DoF method set_forward_enable void boolean singleton AC_AttitudeControl_Multi_6DoF method set_offset_roll_pitch void float'skip_check float'skip_check @@ -394,7 +409,7 @@ singleton AC_AttitudeControl_Multi_6DoF method set_offset_roll_pitch void float' include AP_Motors/AP_MotorsMatrix_6DoF_Scripting.h depends APM_BUILD_TYPE(APM_BUILD_ArduCopter) singleton AP_MotorsMatrix_6DoF_Scripting depends APM_BUILD_TYPE(APM_BUILD_ArduCopter) -singleton AP_MotorsMatrix_6DoF_Scripting alias Motors_6DoF +singleton AP_MotorsMatrix_6DoF_Scripting rename Motors_6DoF singleton AP_MotorsMatrix_6DoF_Scripting method init boolean uint8_t 0 AP_MOTORS_MAX_NUM_MOTORS singleton AP_MotorsMatrix_6DoF_Scripting method add_motor void int8_t 0 (AP_MOTORS_MAX_NUM_MOTORS-1) float'skip_check float'skip_check float'skip_check float'skip_check float'skip_check float'skip_check boolean uint8_t 0 AP_MOTORS_MAX_NUM_MOTORS @@ -402,7 +417,7 @@ include AP_HAL/I2CDevice.h ap_object AP_HAL::I2CDevice semaphore-pointer ap_object AP_HAL::I2CDevice method set_retries void uint8_t 0 20 ap_object AP_HAL::I2CDevice method write_register boolean uint8_t 0 UINT8_MAX uint8_t 0 UINT8_MAX -ap_object AP_HAL::I2CDevice method read_registers boolean uint8_t 0 UINT8_MAX &uint8_t'Null 1'literal +ap_object AP_HAL::I2CDevice manual read_registers AP_HAL__I2CDevice_read_registers ap_object AP_HAL::I2CDevice method set_address void uint8_t 0 UINT8_MAX @@ -411,49 +426,54 @@ ap_object AP_HAL::AnalogSource method voltage_average float ap_object AP_HAL::AnalogSource method voltage_latest float ap_object AP_HAL::AnalogSource method voltage_average_ratiometric float -userdata AP_HAL::PWMSource alias PWMSource -userdata AP_HAL::PWMSource method set_pin boolean uint8_t 0 UINT8_MAX "Scripting"'literal -userdata AP_HAL::PWMSource method get_pwm_us uint16_t -userdata AP_HAL::PWMSource method get_pwm_avg_us uint16_t +-- disabled for 4.3.4 due to interrupt handling bug +-- userdata AP_HAL::PWMSource rename PWMSource +-- userdata AP_HAL::PWMSource method set_pin boolean uint8_t 0 UINT8_MAX "Scripting"'literal +-- userdata AP_HAL::PWMSource method get_pwm_us uint16_t +-- userdata AP_HAL::PWMSource method get_pwm_avg_us uint16_t -singleton hal.gpio alias gpio +singleton hal.gpio rename gpio singleton hal.gpio literal singleton hal.gpio method read boolean uint8_t 0 UINT8_MAX singleton hal.gpio method write void uint8_t 0 UINT8_MAX uint8_t 0 1 singleton hal.gpio method toggle void uint8_t 0 UINT8_MAX singleton hal.gpio method pinMode void uint8_t 0 UINT8_MAX uint8_t 0 1 -singleton hal.analogin alias analog +singleton hal.analogin rename analog singleton hal.analogin literal singleton hal.analogin method channel AP_HAL::AnalogSource ANALOG_INPUT_NONE'literal include AP_Motors/AP_MotorsMatrix_Scripting_Dynamic.h depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI singleton AP_MotorsMatrix_Scripting_Dynamic depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI -singleton AP_MotorsMatrix_Scripting_Dynamic alias Motors_dynamic +singleton AP_MotorsMatrix_Scripting_Dynamic rename Motors_dynamic singleton AP_MotorsMatrix_Scripting_Dynamic method init boolean uint8_t 0 AP_MOTORS_MAX_NUM_MOTORS singleton AP_MotorsMatrix_Scripting_Dynamic method add_motor void uint8_t 0 (AP_MOTORS_MAX_NUM_MOTORS-1) uint8_t 0 AP_MOTORS_MAX_NUM_MOTORS singleton AP_MotorsMatrix_Scripting_Dynamic method load_factors void AP_MotorsMatrix_Scripting_Dynamic::factor_table userdata AP_MotorsMatrix_Scripting_Dynamic::factor_table depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI -userdata AP_MotorsMatrix_Scripting_Dynamic::factor_table alias motor_factor_table +userdata AP_MotorsMatrix_Scripting_Dynamic::factor_table rename motor_factor_table userdata AP_MotorsMatrix_Scripting_Dynamic::factor_table field roll'array AP_MOTORS_MAX_NUM_MOTORS float'skip_check read write userdata AP_MotorsMatrix_Scripting_Dynamic::factor_table field pitch'array AP_MOTORS_MAX_NUM_MOTORS float'skip_check read write userdata AP_MotorsMatrix_Scripting_Dynamic::factor_table field yaw'array AP_MOTORS_MAX_NUM_MOTORS float'skip_check read write userdata AP_MotorsMatrix_Scripting_Dynamic::factor_table field throttle'array AP_MOTORS_MAX_NUM_MOTORS float'skip_check read write include AP_InertialSensor/AP_InertialSensor.h -singleton AP_InertialSensor alias ins +singleton AP_InertialSensor rename ins singleton AP_InertialSensor method get_temperature float uint8_t 0 INS_MAX_INSTANCES +singleton CAN manual get_device lua_get_CAN_device +singleton CAN manual get_device2 lua_get_CAN_device2 +singleton CAN depends HAL_MAX_CAN_PROTOCOL_DRIVERS include AP_Scripting/AP_Scripting_CANSensor.h depends HAL_MAX_CAN_PROTOCOL_DRIVERS include AP_HAL/AP_HAL.h userdata AP_HAL::CANFrame depends HAL_MAX_CAN_PROTOCOL_DRIVERS -userdata AP_HAL::CANFrame alias CANFrame +userdata AP_HAL::CANFrame rename CANFrame userdata AP_HAL::CANFrame field id uint32_t read write 0U UINT32_MAX userdata AP_HAL::CANFrame field data'array int(ARRAY_SIZE(ud->data)) uint8_t read write 0 UINT8_MAX userdata AP_HAL::CANFrame field dlc uint8_t read write 0 int(ARRAY_SIZE(ud->data)) +userdata AP_HAL::CANFrame method id_signed int32_t userdata AP_HAL::CANFrame method isExtended boolean userdata AP_HAL::CANFrame method isRemoteTransmissionRequest boolean userdata AP_HAL::CANFrame method isErrorFrame boolean @@ -465,27 +485,122 @@ ap_object ScriptingCANBuffer method read_frame boolean AP_HAL::CANFrame'Null include ../Tools/AP_Periph/AP_Periph.h depends defined(HAL_BUILD_AP_PERIPH) singleton AP_Periph_FW depends defined(HAL_BUILD_AP_PERIPH) -singleton AP_Periph_FW alias periph +singleton AP_Periph_FW rename periph singleton AP_Periph_FW method get_yaw_earth float singleton AP_Periph_FW method get_vehicle_state uint32_t +singleton AP_Periph_FW method can_printf void "%s"'literal string include AP_Motors/AP_Motors_Class.h depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI singleton AP::motors() depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI singleton AP::motors() literal -singleton AP::motors() alias motors +singleton AP::motors() rename motors singleton AP::motors() method set_frame_string void string include AP_Common/AP_FWVersion.h singleton AP::fwversion() literal singleton AP::fwversion() reference -singleton AP::fwversion() alias FWVersion +singleton AP::fwversion() rename FWVersion singleton AP::fwversion() field fw_short_string string read -singleton AP::fwversion() field fw_short_string alias string +singleton AP::fwversion() field fw_short_string rename string singleton AP::fwversion() field vehicle_type uint8_t read -singleton AP::fwversion() field vehicle_type alias type +singleton AP::fwversion() field vehicle_type rename type singleton AP::fwversion() field major uint8_t read singleton AP::fwversion() field minor uint8_t read singleton AP::fwversion() field patch uint8_t read singleton AP::fwversion() field fw_hash_str string read -singleton AP::fwversion() field fw_hash_str alias hash +singleton AP::fwversion() field fw_hash_str rename hash + +include AP_Follow/AP_Follow.h depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI +singleton AP_Follow depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI +singleton AP_Follow rename follow +singleton AP_Follow method have_target boolean +singleton AP_Follow method get_last_update_ms uint32_t +singleton AP_Follow method get_target_location_and_velocity boolean Location'Null Vector3f'Null +singleton AP_Follow method get_target_location_and_velocity_ofs boolean Location'Null Vector3f'Null +singleton AP_Follow method get_target_heading_deg boolean float'Null + +include AC_AttitudeControl/AC_AttitudeControl.h depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI +singleton AC_AttitudeControl depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI +singleton AC_AttitudeControl method get_rpy_srate void float'Ref float'Ref float'Ref + +include AP_Mount/AP_Mount.h +singleton AP_Mount depends HAL_MOUNT_ENABLED == 1 +singleton AP_Mount rename mount +singleton AP_Mount method get_mode MAV_MOUNT_MODE'enum uint8_t 0 UINT8_MAX +singleton AP_Mount method set_mode void uint8_t 0 UINT8_MAX MAV_MOUNT_MODE'enum MAV_MOUNT_MODE_RETRACT MAV_MOUNT_MODE_HOME_LOCATION +singleton AP_Mount method set_angle_target void uint8_t 0 UINT8_MAX float'skip_check float'skip_check float'skip_check boolean +singleton AP_Mount method set_rate_target void uint8_t 0 UINT8_MAX float'skip_check float'skip_check float'skip_check boolean +singleton AP_Mount method set_roi_target void uint8_t 0 UINT8_MAX Location + +-- ----EFI Library---- +include AP_EFI/AP_EFI.h depends HAL_EFI_ENABLED +include AP_EFI/AP_EFI_Scripting.h depends HAL_EFI_ENABLED +include AP_EFI/AP_EFI_config.h + +userdata Cylinder_Status depends (AP_EFI_SCRIPTING_ENABLED == 1) +userdata Cylinder_Status field ignition_timing_deg float'skip_check write +userdata Cylinder_Status field injection_time_ms float'skip_check write +userdata Cylinder_Status field cylinder_head_temperature float'skip_check write +userdata Cylinder_Status field exhaust_gas_temperature float'skip_check write +userdata Cylinder_Status field lambda_coefficient float'skip_check write + +userdata EFI_State depends (AP_EFI_SCRIPTING_ENABLED == 1) +userdata EFI_State field last_updated_ms uint32_t'skip_check write +userdata EFI_State field general_error boolean write +userdata EFI_State field engine_load_percent uint8_t write 0 UINT8_MAX +userdata EFI_State field engine_speed_rpm uint32_t'skip_check write +userdata EFI_State field spark_dwell_time_ms float'skip_check write +userdata EFI_State field atmospheric_pressure_kpa float'skip_check write +userdata EFI_State field intake_manifold_pressure_kpa float'skip_check write +userdata EFI_State field intake_manifold_temperature float'skip_check write +userdata EFI_State field coolant_temperature float'skip_check write +userdata EFI_State field oil_pressure float'skip_check write +userdata EFI_State field oil_temperature float'skip_check write +userdata EFI_State field fuel_pressure float'skip_check write +userdata EFI_State field fuel_consumption_rate_cm3pm float'skip_check write +userdata EFI_State field estimated_consumed_fuel_volume_cm3 float'skip_check write +userdata EFI_State field throttle_position_percent uint8_t write 0 UINT8_MAX +userdata EFI_State field ecu_index uint8_t write 0 UINT8_MAX +userdata EFI_State field cylinder_status Cylinder_Status write +userdata EFI_State field ignition_voltage float'skip_check write +userdata EFI_State field throttle_out float'skip_check write +userdata EFI_State field pt_compensation float'skip_check write + +ap_object AP_EFI_Backend depends (AP_EFI_SCRIPTING_ENABLED == 1) +ap_object AP_EFI_Backend method handle_scripting boolean EFI_State + +singleton AP_EFI depends (AP_EFI_SCRIPTING_ENABLED == 1) +singleton AP_EFI rename efi +singleton AP_EFI method get_backend AP_EFI_Backend uint8_t 0 UINT8_MAX + +-- ----END EFI Library---- + +singleton AP_Logger rename logger +singleton AP_Logger manual write AP_Logger_Write + +singleton i2c manual get_device lua_get_i2c_device + +global manual millis lua_millis +global manual micros lua_micros +global manual mission_receive lua_mission_receive + +userdata uint32_t creation lua_new_uint32_t +userdata uint32_t manual_operator __add uint32_t___add +userdata uint32_t manual_operator __sub uint32_t___sub +userdata uint32_t manual_operator __mul uint32_t___mul +userdata uint32_t manual_operator __div uint32_t___div +userdata uint32_t manual_operator __mod uint32_t___mod +userdata uint32_t manual_operator __idiv uint32_t___div +userdata uint32_t manual_operator __band uint32_t___band +userdata uint32_t manual_operator __bor uint32_t___bor +userdata uint32_t manual_operator __bxor uint32_t___bxor +userdata uint32_t manual_operator __shl uint32_t___shl +userdata uint32_t manual_operator __shr uint32_t___shr +userdata uint32_t manual_operator __eq uint32_t___eq +userdata uint32_t manual_operator __lt uint32_t___lt +userdata uint32_t manual_operator __le uint32_t___le +userdata uint32_t manual_operator __bnot uint32_t___bnot +userdata uint32_t manual_operator __tostring uint32_t___tostring +userdata uint32_t manual toint uint32_t_toint +userdata uint32_t manual tofloat uint32_t_tofloat diff --git a/libraries/AP_Scripting/generator/src/main.c b/libraries/AP_Scripting/generator/src/main.c index e228d18fc2f..2f9cbfa7aa7 100644 --- a/libraries/AP_Scripting/generator/src/main.c +++ b/libraries/AP_Scripting/generator/src/main.c @@ -8,6 +8,7 @@ #include char keyword_alias[] = "alias"; +char keyword_rename[] = "rename"; char keyword_ap_object[] = "ap_object"; char keyword_comment[] = "--"; char keyword_depends[] = "depends"; @@ -25,6 +26,11 @@ char keyword_userdata[] = "userdata"; char keyword_write[] = "write"; char keyword_literal[] = "literal"; char keyword_reference[] = "reference"; +char keyword_deprecate[] = "deprecate"; +char keyword_manual[] = "manual"; +char keyword_global[] = "global"; +char keyword_creation[] = "creation"; +char keyword_manual_operator[] = "manual_operator"; // attributes (should include the leading ' ) char keyword_attr_enum[] = "'enum"; @@ -55,6 +61,8 @@ enum error_codes { ERROR_GENERAL = 6, // general error ERROR_SINGLETON = 7, // singletons ERROR_DEPENDS = 8, // dependencies + ERROR_DOCS = 9, // Documentation + ERROR_GLOBALS = 10, }; struct header { @@ -129,6 +137,7 @@ enum operator_type { OP_SUB = (1U << 1), OP_MUL = (1U << 2), OP_DIV = (1U << 3), + OP_MANUAL = (1U << 4), OP_LAST }; @@ -323,6 +332,7 @@ enum userdata_type { UD_USERDATA, UD_SINGLETON, UD_AP_OBJECT, + UD_GLOBAL, }; struct argument { @@ -336,17 +346,32 @@ struct method { struct method * next; char *name; char *sanatized_name; // sanatized name of the C++ singleton - char *alias; // (optional) used for scripting access + char *rename; // (optional) used for scripting access + char *deprecate; // (optional) issue deprecateion warning string on first call int line; // line declared on struct type return_type; struct argument * arguments; uint32_t flags; // filled out with TYPE_FLAGS }; +enum alias_type { + ALIAS_TYPE_NONE, + ALIAS_TYPE_MANUAL, + ALIAS_TYPE_MANUAL_OPERATOR, +}; + +struct method_alias { + struct method_alias *next; + char *name; + char *alias; + int line; + enum alias_type type; +}; + struct userdata_field { struct userdata_field * next; char * name; - char * alias; + char * rename; struct type type; // field type, points to a string int line; // line declared on unsigned int access_flags; @@ -370,18 +395,21 @@ struct userdata { struct userdata * next; char *name; // name of the C++ singleton char *sanatized_name; // sanatized name of the C++ singleton - char *alias; // (optional) used for scripting access + char *rename; // (optional) used for scripting access struct userdata_field *fields; struct method *methods; + struct method_alias *method_aliases; struct userdata_enum *enums; enum userdata_type ud_type; uint32_t operations; // bitset of enum operation_types int flags; // flags from the userdata_flags enum char *dependency; + char *creation; // name of a manual creation function if set, note that this will not be used internally }; static struct userdata *parsed_userdata; static struct userdata *parsed_ap_objects; +static struct userdata *parsed_globals; void sanitize_character(char **str, char character) { char *position = strchr(*str, character); @@ -562,8 +590,8 @@ int parse_type(struct type *type, const uint32_t restrictions, enum range_check_ string_copy(&(type->data.enum_name), data_type); } else if (type->type == TYPE_LITERAL) { string_copy(&(type->data.literal), data_type); - } else if (strcmp(data_type, keyword_alias) == 0) { - error(ERROR_USERDATA, "Cant add alias to unknown function"); + } else if (strcmp(data_type, keyword_rename) == 0) { + error(ERROR_USERDATA, "Cant add rename to unknown function"); } else { // this must be a user data or an ap_object, check if it's already been declared as an object struct userdata *node = parsed_ap_objects; @@ -671,11 +699,11 @@ void handle_userdata_field(struct userdata *data) { } if (field != NULL) { char *token = next_token(); - if (strcmp(token, keyword_alias) != 0) { + if (strcmp(token, keyword_rename) != 0) { error(ERROR_USERDATA, "Field %s already exists in userdata %s (declared on %d)", field_name, data->name, field->line); } - char *alias = next_token(); - string_copy(&(field->alias), alias); + char *rename = next_token(); + string_copy(&(field->rename), rename); return; } @@ -700,8 +728,9 @@ void handle_userdata_field(struct userdata *data) { field->access_flags = parse_access_flags(&(field->type)); } -void handle_method(char *parent_name, struct method **methods) { +void handle_method(struct userdata *node) { trace(TRACE_USERDATA, "Adding a method"); + char * parent_name = node->name; // find the field name char * name = next_token(); @@ -709,24 +738,60 @@ void handle_method(char *parent_name, struct method **methods) { error(ERROR_USERDATA, "Missing method name for %s", parent_name); } - struct method * method = *methods; + struct method * method = node->methods; while (method != NULL && strcmp(method->name, name)) { method = method-> next; } if (method != NULL) { char *token = next_token(); - if (strcmp(token, keyword_alias) != 0) { - error(ERROR_USERDATA, "Method %s already exists for %s (declared on %d)", name, parent_name, method->line); + if (strcmp(token, keyword_rename) == 0) { + char *rename = next_token(); + string_copy(&(method->rename), rename); + return; + + } else if (strcmp(token, keyword_alias) == 0) { + char *alias_name = next_token(); + + struct method * method = node->methods; + while (method != NULL && strcmp(method->name, alias_name)) { + method = method-> next; + } + if (method != NULL) { + error(ERROR_USERDATA, "Method %s already exists for %s (declared on %d) cannot alias to %s", alias_name, parent_name, method->line, name); + } + + + struct method_alias *alias = allocate(sizeof(struct method_alias)); + string_copy(&(alias->name), name); + string_copy(&(alias->alias), alias_name); + alias->line = state.line_num; + alias->next = node->method_aliases; + node->method_aliases = alias; + return; + + } else if (strcmp(token, keyword_deprecate) == 0) { + char *deprecate = strtok(NULL, ""); + if (deprecate == NULL) { + error(ERROR_USERDATA, "Expected a deprecate string for %s %s on line", parent_name, name, state.line_num); + } + string_copy(&(method->deprecate), deprecate); + return; } - char *alias = next_token(); - string_copy(&(method->alias), alias); - return; + error(ERROR_USERDATA, "Method %s already exists for %s (declared on %d)", name, parent_name, method->line); + } + + struct method_alias * alias = node->method_aliases; + while (alias != NULL && strcmp(alias->alias, name)) { + alias = alias-> next; + } + if (alias != NULL) { + error(ERROR_USERDATA, "alias %s already exists for %s (declared on %d)", name, alias->name, alias->line); } trace(TRACE_USERDATA, "Adding method %s", name); method = allocate(sizeof(struct method)); - method->next = *methods; - *methods = method; + method->next = node->methods; + node->methods = method; string_copy(&(method->name), name); sanatize_name(&(method->sanatized_name), name); method->line = state.line_num; @@ -770,6 +835,24 @@ void handle_method(char *parent_name, struct method **methods) { } } +void handle_manual(struct userdata *node, enum alias_type type) { + char *name = next_token(); + if (name == NULL) { + error(ERROR_SINGLETON, "Expected a lua name for manual %s method",node->name); + } + char *cpp_function_name = next_token(); + if (cpp_function_name == NULL) { + error(ERROR_SINGLETON, "Expected a cpp name for manual %s method",node->name); + } + struct method_alias *alias = allocate(sizeof(struct method_alias)); + string_copy(&(alias->name), cpp_function_name); + string_copy(&(alias->alias), name); + alias->line = state.line_num; + alias->type = type; + alias->next = node->method_aliases; + node->method_aliases = alias; +} + void handle_operator(struct userdata *data) { trace(TRACE_USERDATA, "Adding a operator"); @@ -830,7 +913,7 @@ void handle_userdata(void) { node->next = parsed_userdata; parsed_userdata = node; } else { - trace(TRACE_USERDATA, "Found exsisting userdata for %s", name); + trace(TRACE_USERDATA, "Found existing userdata for %s", name); } // read type @@ -845,16 +928,16 @@ void handle_userdata(void) { } else if (strcmp(type, keyword_operator) == 0) { handle_operator(node); } else if (strcmp(type, keyword_method) == 0) { - handle_method(node->name, &(node->methods)); + handle_method(node); } else if (strcmp(type, keyword_enum) == 0) { handle_userdata_enum(node); - } else if (strcmp(type, keyword_alias) == 0) { - const char *alias = next_token(); - if (alias == NULL) { - error(ERROR_SINGLETON, "Missing the name of the alias for userdata %s", node->name); + } else if (strcmp(type, keyword_rename) == 0) { + const char *rename = next_token(); + if (rename == NULL) { + error(ERROR_SINGLETON, "Missing the name of the rename for userdata %s", node->name); } - node->alias = (char *)allocate(strlen(alias) + 1); - strcpy(node->alias, alias); + node->rename = (char *)allocate(strlen(rename) + 1); + strcpy(node->rename, rename); } else if (strcmp(type, keyword_depends) == 0) { if (node->dependency != NULL) { @@ -866,6 +949,23 @@ void handle_userdata(void) { } string_copy(&(node->dependency), depends); + } else if (strcmp(type, keyword_manual) == 0) { + handle_manual(node, ALIAS_TYPE_MANUAL); + + } else if (strcmp(type, keyword_creation) == 0) { + if (node->creation != NULL) { + error(ERROR_SINGLETON, "Userdata only support a single creation function"); + } + char *creation = strtok(NULL, ""); + if (creation == NULL) { + error(ERROR_USERDATA, "Expected a creation string for %s",node->name); + } + string_copy(&(node->creation), creation); + + } else if (strcmp(type, keyword_manual_operator) == 0) { + handle_manual(node, ALIAS_TYPE_MANUAL_OPERATOR); + node->operations |= OP_MANUAL; + } else { error(ERROR_USERDATA, "Unknown or unsupported type for userdata: %s", type); } @@ -904,16 +1004,16 @@ void handle_singleton(void) { error(ERROR_SINGLETON, "Expected a access type for userdata %s", name); } - if (strcmp(type, keyword_alias) == 0) { - if (node->alias != NULL) { - error(ERROR_SINGLETON, "Alias of %s was already declared for %s", node->alias, node->name); + if (strcmp(type, keyword_rename) == 0) { + if (node->rename != NULL) { + error(ERROR_SINGLETON, "rename of %s was already declared for %s", node->rename, node->name); } - const char *alias = next_token(); - if (alias == NULL) { - error(ERROR_SINGLETON, "Missing the name of the alias for %s", node->name); + const char *rename = next_token(); + if (rename == NULL) { + error(ERROR_SINGLETON, "Missing the name of the rename for %s", node->name); } - node->alias = (char *)allocate(strlen(alias) + 1); - strcpy(node->alias, alias); + node->rename = (char *)allocate(strlen(rename) + 1); + strcpy(node->rename, rename); } else if (strcmp(type, keyword_semaphore) == 0) { node->flags |= UD_FLAG_SEMAPHORE; @@ -922,7 +1022,7 @@ void handle_singleton(void) { } else if (strcmp(type, keyword_semaphore_pointer) == 0) { node->flags |= UD_FLAG_SCHEDULER_SEMAPHORE; } else if (strcmp(type, keyword_method) == 0) { - handle_method(node->name, &(node->methods)); + handle_method(node); } else if (strcmp(type, keyword_enum) == 0) { handle_userdata_enum(node); } else if (strcmp(type, keyword_depends) == 0) { @@ -940,8 +1040,10 @@ void handle_singleton(void) { handle_userdata_field(node); } else if (strcmp(type, keyword_reference) == 0) { node->flags |= UD_FLAG_REFERENCE; + } else if (strcmp(type, keyword_manual) == 0) { + handle_manual(node, ALIAS_TYPE_MANUAL); } else { - error(ERROR_SINGLETON, "Singletons only support aliases, methods, semaphore, depends or literal keywords (got %s)", type); + error(ERROR_SINGLETON, "Singletons only support renames, methods, semaphore, depends, literal or manual keywords (got %s)", type); } // ensure no more tokens on the line @@ -980,16 +1082,16 @@ void handle_ap_object(void) { error(ERROR_SINGLETON, "Expected a access type for ap_object %s", name); } - if (strcmp(type, keyword_alias) == 0) { - if (node->alias != NULL) { - error(ERROR_SINGLETON, "Alias of %s was already declared for %s", node->alias, node->name); + if (strcmp(type, keyword_rename) == 0) { + if (node->rename != NULL) { + error(ERROR_SINGLETON, "Rename of %s was already declared for %s", node->rename, node->name); } - const char *alias = next_token(); - if (alias == NULL) { - error(ERROR_SINGLETON, "Missing the name of the alias for %s", node->name); + const char *rename = next_token(); + if (rename == NULL) { + error(ERROR_SINGLETON, "Missing the name of the rename for %s", node->name); } - node->alias = (char *)allocate(strlen(alias) + 1); - strcpy(node->alias, alias); + node->rename = (char *)allocate(strlen(rename) + 1); + strcpy(node->rename, rename); } else if (strcmp(type, keyword_semaphore) == 0) { node->flags |= UD_FLAG_SEMAPHORE; @@ -998,7 +1100,7 @@ void handle_ap_object(void) { } else if (strcmp(type, keyword_semaphore_pointer) == 0) { node->flags |= UD_FLAG_SEMAPHORE_POINTER; } else if (strcmp(type, keyword_method) == 0) { - handle_method(node->name, &(node->methods)); + handle_method(node); } else if (strcmp(type, keyword_depends) == 0) { if (node->dependency != NULL) { error(ERROR_SINGLETON, "AP_Objects only support a single depends"); @@ -1009,8 +1111,11 @@ void handle_ap_object(void) { } string_copy(&(node->dependency), depends); + } else if (strcmp(type, keyword_manual) == 0) { + handle_manual(node, ALIAS_TYPE_MANUAL); + } else { - error(ERROR_SINGLETON, "AP_Objects only support aliases, methods or semaphore keyowrds (got %s)", type); + error(ERROR_SINGLETON, "AP_Objects only support renames, methods, semaphore or manual keywords (got %s)", type); } // check that we didn't just add 2 singleton flags @@ -1027,10 +1132,35 @@ void handle_ap_object(void) { } } +void handle_global(void) { + + if (parsed_globals == NULL) { + parsed_globals = (struct userdata *)allocate(sizeof(struct userdata)); + parsed_globals->ud_type = UD_GLOBAL; + } + + // read type + char *type = next_token(); + if (type == NULL) { + error(ERROR_GLOBALS, "Expected a access type for global"); + } + + if (strcmp(type, keyword_manual) == 0) { + handle_manual(parsed_globals, ALIAS_TYPE_MANUAL); + } else { + error(ERROR_GLOBALS, "globals only support manual keyword (got %s)", type); + } + + // ensure no more tokens on the line + if (next_token()) { + error(ERROR_GLOBALS, "global contained an unexpected extra token: %s", state.token); + } +} + void sanity_check_userdata(void) { struct userdata * node = parsed_userdata; while(node) { - if ((node->fields == NULL) && (node->methods == NULL)) { + if ((node->fields == NULL) && (node->methods == NULL) && (node->method_aliases == NULL)) { error(ERROR_USERDATA, "Userdata %s has no fields or methods", node->name); } node = node->next; @@ -1068,7 +1198,7 @@ void emit_userdata_allocators(void) { fprintf(source, " void *ud = lua_newuserdata(L, sizeof(%s));\n", node->name); fprintf(source, " memset(ud, 0, sizeof(%s));\n", node->name); fprintf(source, " new (ud) %s();\n", node->name); - fprintf(source, " luaL_getmetatable(L, \"%s\");\n", node->alias ? node->alias : node->name); + fprintf(source, " luaL_getmetatable(L, \"%s\");\n", node->rename ? node->rename : node->name); fprintf(source, " lua_setmetatable(L, -2);\n"); fprintf(source, " return 1;\n"); fprintf(source, "}\n"); @@ -1101,7 +1231,7 @@ void emit_userdata_checkers(void) { while (node) { start_dependency(source, node->dependency); fprintf(source, "%s * check_%s(lua_State *L, int arg) {\n", node->name, node->sanatized_name); - fprintf(source, " void *data = luaL_checkudata(L, arg, \"%s\");\n", node->alias ? node->alias : node->name); + fprintf(source, " void *data = luaL_checkudata(L, arg, \"%s\");\n", node->rename ? node->rename : node->name); fprintf(source, " return (%s *)data;\n", node->name); fprintf(source, "}\n"); end_dependency(source, node->dependency); @@ -1447,10 +1577,12 @@ void emit_userdata_fields() { struct userdata * node = parsed_userdata; while(node) { struct userdata_field *field = node->fields; - start_dependency(source, node->dependency); - while(field) { - emit_userdata_field(node, field); - field = field->next; + if (field) { + start_dependency(source, node->dependency); + while(field) { + emit_userdata_field(node, field); + field = field->next; + } } end_dependency(source, node->dependency); node = node->next; @@ -1465,7 +1597,7 @@ void emit_singleton_field(const struct userdata *data, const struct userdata_fie // fetch and check the singleton pointer fprintf(source, " %s * ud = %s::get_singleton();\n", data->name, data->name); fprintf(source, " if (ud == nullptr) {\n"); - fprintf(source, " return not_supported_error(L, %d, \"%s\");\n", 1, data->alias ? data->alias : data->name); + fprintf(source, " return not_supported_error(L, %d, \"%s\");\n", 1, data->rename ? data->rename : data->name); fprintf(source, " }\n\n"); } const char *ud_name = (data->flags & UD_FLAG_LITERAL)?data->name:"ud"; @@ -1545,12 +1677,14 @@ void emit_singleton_fields() { struct userdata * node = parsed_singletons; while(node) { struct userdata_field *field = node->fields; - start_dependency(source, node->dependency); - while(field) { - emit_singleton_field(node, field); - field = field->next; + if (field) { + start_dependency(source, node->dependency); + while(field) { + emit_singleton_field(node, field); + field = field->next; + } + end_dependency(source, node->dependency); } - end_dependency(source, node->dependency); node = node->next; } } @@ -1611,7 +1745,7 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth start_dependency(source, data->dependency); - const char *access_name = data->alias ? data->alias : data->name; + const char *access_name = data->rename ? data->rename : data->name; // bind ud early if it's a singleton, so that we can use it in the range checks fprintf(source, "static int %s_%s(lua_State *L) {\n", data->sanatized_name, method->sanatized_name); // emit comments on expected arg/type @@ -1625,6 +1759,16 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth fprintf(source, " }\n\n"); } + // emit warning if configured + if (method->deprecate != NULL) { + fprintf(source, " static bool warned = false;\n"); + fprintf(source, " if (!warned) {\n"); + fprintf(source, " lua_scripts::set_and_print_new_error_message(MAV_SEVERITY_WARNING, \"%s:%s %s\");\n", data->rename, method->rename ? method->rename : method->name, method->deprecate); + fprintf(source, " warned = true;\n"); + fprintf(source, " }\n\n"); + } + + // sanity check number of args called with arg_count = 1; while (arg != NULL) { @@ -1641,6 +1785,7 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth fprintf(source, " %s * ud = check_%s(L, 1);\n", data->name, data->sanatized_name); break; case UD_SINGLETON: + case UD_GLOBAL: // this was bound early break; case UD_AP_OBJECT: @@ -1893,6 +2038,7 @@ const char * get_name_for_operation(enum operator_type op) { case OP_DIV: return "__div"; break; + case OP_MANUAL: case OP_LAST: return NULL; } @@ -1924,6 +2070,7 @@ void emit_operators(struct userdata *data) { case OP_DIV: op_sym = '/'; break; + case OP_MANUAL: case OP_LAST: return; } @@ -1961,40 +2108,6 @@ void emit_methods(struct userdata *node) { } } -void emit_userdata_metatables(void) { - struct userdata * node = parsed_userdata; - while(node) { - start_dependency(source, node->dependency); - fprintf(source, "const luaL_Reg %s_meta[] = {\n", node->sanatized_name); - - struct userdata_field *field = node->fields; - while(field) { - fprintf(source, " {\"%s\", %s_%s},\n", field->alias ? field->alias : field->name, node->sanatized_name, field->name); - field = field->next; - } - - struct method *method = node->methods; - while(method) { - fprintf(source, " {\"%s\", %s_%s},\n", method->alias ? method->alias : method->name, node->sanatized_name, method->sanatized_name); - method = method->next; - } - - for (uint32_t i = 1; i < OP_LAST; i = i << 1) { - const char * op_name = get_name_for_operation((node->operations) & i); - if (op_name == NULL) { - continue; - } - fprintf(source, " {\"%s\", %s_%s},\n", op_name, node->sanatized_name, op_name); - } - - fprintf(source, " {NULL, NULL}\n"); - fprintf(source, "};\n"); - end_dependency(source, node->dependency); - fprintf(source, "\n"); - node = node->next; - } -} - void emit_enum(struct userdata * data) { fprintf(source, "struct userdata_enum %s_enums[] = {\n", data->sanatized_name); struct userdata_enum *ud_enum = data->enums; @@ -2015,16 +2128,26 @@ void emit_index(struct userdata *head) { struct method *method = node->methods; while (method) { - fprintf(source, " {\"%s\", %s_%s},\n", method->alias ? method->alias : method->name, node->sanatized_name, method->name); + fprintf(source, " {\"%s\", %s_%s},\n", method->rename ? method->rename : method->name, node->sanatized_name, method->name); method = method->next; } struct userdata_field *field = node->fields; while(field) { - fprintf(source, " {\"%s\", %s_%s},\n", field->alias ? field->alias : field->name, node->sanatized_name, field->name); + fprintf(source, " {\"%s\", %s_%s},\n", field->rename ? field->rename : field->name, node->sanatized_name, field->name); field = field->next; } + struct method_alias *alias = node->method_aliases; + while(alias) { + if (alias->type == ALIAS_TYPE_MANUAL) { + fprintf(source, " {\"%s\", %s},\n", alias->alias, alias->name); + } else if (alias->type == ALIAS_TYPE_NONE) { + fprintf(source, " {\"%s\", %s_%s},\n", alias->alias, node->sanatized_name, alias->name); + } + alias = alias->next; + } + fprintf(source, "};\n\n"); if (node->operations) { @@ -2036,6 +2159,13 @@ void emit_index(struct userdata *head) { } fprintf(source, " {\"%s\", %s_%s},\n", op_name, node->sanatized_name, op_name); } + struct method_alias *alias = node->method_aliases; + while(alias) { + if (alias->type == ALIAS_TYPE_MANUAL_OPERATOR) { + fprintf(source, " {\"%s\", %s},\n", alias->alias, alias->name); + } + alias = alias->next; + } fprintf(source, " {NULL, NULL},\n"); fprintf(source, "};\n\n"); } @@ -2065,7 +2195,7 @@ void emit_type_index(struct userdata * data, char * meta_name) { fprintf(source, "const struct luaL_Reg %s_fun[] = {\n", meta_name); while (data) { start_dependency(source, data->dependency); - fprintf(source, " {\"%s\", %s_index},\n", data->alias ? data->alias : data->name, data->sanatized_name); + fprintf(source, " {\"%s\", %s_index},\n", data->rename ? data->rename : data->name, data->sanatized_name); end_dependency(source, data->dependency); data = data->next; } @@ -2077,9 +2207,9 @@ void emit_type_index_with_operators(struct userdata * data, char * meta_name) { while (data) { start_dependency(source, data->dependency); if (data->operations == 0) { - fprintf(source, " {\"%s\", %s_index, nullptr},\n", data->alias ? data->alias : data->name, data->sanatized_name); + fprintf(source, " {\"%s\", %s_index, nullptr},\n", data->rename ? data->rename : data->name, data->sanatized_name); } else { - fprintf(source, " {\"%s\", %s_index, %s_operators},\n", data->alias ? data->alias : data->name, data->sanatized_name, data->sanatized_name); + fprintf(source, " {\"%s\", %s_index, %s_operators},\n", data->rename ? data->rename : data->name, data->sanatized_name, data->sanatized_name); } end_dependency(source, data->dependency); data = data->next; @@ -2151,8 +2281,6 @@ void emit_loaders(void) { fprintf(source, " }\n"); fprintf(source, "\n"); - fprintf(source, " load_boxed_numerics(L);\n"); - fprintf(source, "}\n\n"); } @@ -2164,7 +2292,12 @@ void emit_sandbox(void) { fprintf(source, "} new_userdata[] = {\n"); while (data) { start_dependency(source, data->dependency); - fprintf(source, " {\"%s\", new_%s},\n", data->alias ? data->alias : data->name, data->sanatized_name); + if (data->creation) { + // expose custom creation function to user (not used internally) + fprintf(source, " {\"%s\", %s},\n", data->rename ? data->rename : data->name, data->creation); + } else { + fprintf(source, " {\"%s\", new_%s},\n", data->rename ? data->rename : data->name, data->sanatized_name); + } end_dependency(source, data->dependency); data = data->next; } @@ -2175,6 +2308,16 @@ void emit_sandbox(void) { end_dependency(source, data->dependency); data = data->next; } + if (parsed_globals) { + struct method_alias *manual_aliases = parsed_globals->method_aliases; + while (manual_aliases) { + if (manual_aliases->type != ALIAS_TYPE_MANUAL) { + error(ERROR_GLOBALS, "Globals only support manual methods"); + } + fprintf(source, " {\"%s\", %s},\n", manual_aliases->alias, manual_aliases->name); + manual_aliases = manual_aliases->next; + } + } fprintf(source, "};\n\n"); fprintf(source, "void load_generated_sandbox(lua_State *L) {\n"); @@ -2185,7 +2328,7 @@ void emit_sandbox(void) { fprintf(source, " lua_settable(L, -3);\n"); fprintf(source, " }\n"); - // load the userdata allactors + // load the userdata allactors and globals fprintf(source, " for (uint32_t i = 0; i < ARRAY_SIZE(new_userdata); i++) {\n"); fprintf(source, " lua_pushstring(L, new_userdata[i].name);\n"); fprintf(source, " lua_pushcfunction(L, new_userdata[i].fun);\n"); @@ -2193,16 +2336,13 @@ void emit_sandbox(void) { fprintf(source, " }\n"); fprintf(source, "\n"); - fprintf(source, " load_boxed_numerics_sandbox(L);\n"); - - // load the userdata complex functions fprintf(source, "}\n"); } void emit_argcheck_helper(void) { // tagging this with NOINLINE can save a large amount of flash // but until we need it we will allow the compilier to choose to inline this for us - fprintf(source, "static int binding_argcheck(lua_State *L, int expected_arg_count) {\n"); + fprintf(source, "int binding_argcheck(lua_State *L, int expected_arg_count) {\n"); fprintf(source, " const int args = lua_gettop(L);\n"); fprintf(source, " if (args > expected_arg_count) {\n"); fprintf(source, " return luaL_argerror(L, args, \"too many arguments\");\n"); @@ -2244,7 +2384,7 @@ void emit_docs_type(struct type type, const char *prefix, const char *suffix) { fprintf(docs, "%s uint32_t_ud%s", prefix, suffix); break; case TYPE_USERDATA: { - // userdata may have alias + // userdata may have rename struct userdata *data = parsed_userdata; int found = 0; while (data) { @@ -2257,7 +2397,7 @@ void emit_docs_type(struct type type, const char *prefix, const char *suffix) { if (found == 0) { error(ERROR_GENERAL, "Could not find userdata %s", type.data.ud.sanatized_name); } - fprintf(docs, "%s %s_ud%s", prefix, data->alias ? data->alias : data->sanatized_name, suffix); + fprintf(docs, "%s %s_ud%s", prefix, data->rename ? data->rename : data->sanatized_name, suffix); break; } case TYPE_AP_OBJECT: @@ -2269,13 +2409,64 @@ void emit_docs_type(struct type type, const char *prefix, const char *suffix) { } } +void emit_docs_method(const char *name, const char *method_name, struct method *method) { + + fprintf(docs, "-- desc\n"); + + if (method->deprecate != NULL) { + fprintf(docs, "---@deprecated %s\n", method->deprecate); + } + + struct argument *arg = method->arguments; + int count = 1; + // input arguments + while (arg != NULL) { + if ((arg->type.type != TYPE_LITERAL) && (arg->type.flags & (TYPE_FLAGS_NULLABLE | TYPE_FLAGS_REFERNCE)) == 0) { + char *param_name = (char *)allocate(20); + sprintf(param_name, "---@param param%i", count); + emit_docs_type(arg->type, param_name, "\n"); + free(param_name); + count++; + } + arg = arg->next; + } + + // return type + if ((method->flags & TYPE_FLAGS_NULLABLE) == 0) { + emit_docs_type(method->return_type, "---@return", "\n"); + } + + arg = method->arguments; + // nulable and refences returns + while (arg != NULL) { + if ((arg->type.type != TYPE_LITERAL) && (arg->type.flags & (TYPE_FLAGS_NULLABLE | TYPE_FLAGS_REFERNCE))) { + if (arg->type.flags & TYPE_FLAGS_NULLABLE) { + emit_docs_type(arg->type, "---@return", "|nil\n"); + } else { + emit_docs_type(arg->type, "---@return", "\n"); + } + } + arg = arg->next; + } + + // function name + fprintf(docs, "function %s:%s(", name, method_name); + for (int i = 1; i < count; ++i) { + fprintf(docs, "param%i", i); + if (i < count-1) { + fprintf(docs, ", "); + } + } + fprintf(docs, ") end\n\n"); +} + void emit_docs(struct userdata *node, int is_userdata, int emit_creation) { while(node) { - char *name = (char *)allocate(strlen(node->alias ? node->alias : node->sanatized_name) + 5); + char *name = (char *)allocate(strlen(node->rename ? node->rename : node->sanatized_name) + 5); if (is_userdata) { - sprintf(name, "%s_ud", node->alias ? node->alias : node->sanatized_name); + sprintf(name, "%s_ud", node->rename ? node->rename : node->sanatized_name); } else { - sprintf(name, "%s", node->alias ? node->alias : node->sanatized_name); + sprintf(name, "%s", node->rename ? node->rename : node->sanatized_name); } @@ -2298,7 +2489,7 @@ void emit_docs(struct userdata *node, int is_userdata, int emit_creation) { if (emit_creation) { // creation function fprintf(docs, "---@return %s\n", name); - fprintf(docs, "function %s() end\n\n", node->alias ? node->alias : node->sanatized_name); + fprintf(docs, "function %s() end\n\n", node->rename ? node->rename : node->sanatized_name); } } else { // global @@ -2315,12 +2506,12 @@ void emit_docs(struct userdata *node, int is_userdata, int emit_creation) { if (field->access_flags & ACCESS_FLAG_READ) { fprintf(docs, "-- get field\n"); emit_docs_type(field->type, "---@return", "\n"); - fprintf(docs, "function %s:%s() end\n\n", name, field->alias ? field->alias : field->name); + fprintf(docs, "function %s:%s() end\n\n", name, field->rename ? field->rename : field->name); } if (field->access_flags & ACCESS_FLAG_WRITE) { fprintf(docs, "-- set field\n"); emit_docs_type(field->type, "---@param value", "\n"); - fprintf(docs, "function %s:%s(value) end\n\n", name, field->alias ? field->alias : field->name); + fprintf(docs, "function %s:%s(value) end\n\n", name, field->rename ? field->rename : field->name); } } else { // array feild @@ -2328,13 +2519,13 @@ void emit_docs(struct userdata *node, int is_userdata, int emit_creation) { fprintf(docs, "-- get array field\n"); fprintf(docs, "---@param index integer\n"); emit_docs_type(field->type, "---@return", "\n"); - fprintf(docs, "function %s:%s(index) end\n\n", name, field->alias ? field->alias : field->name); + fprintf(docs, "function %s:%s(index) end\n\n", name, field->rename ? field->rename : field->name); } if (field->access_flags & ACCESS_FLAG_WRITE) { fprintf(docs, "-- set array field\n"); fprintf(docs, "---@param index integer\n"); emit_docs_type(field->type, "---@param value", "\n"); - fprintf(docs, "function %s:%s(index, value) end\n\n", name, field->alias ? field->alias : field->name); + fprintf(docs, "function %s:%s(index, value) end\n\n", name, field->rename ? field->rename : field->name); } } field = field->next; @@ -2344,50 +2535,28 @@ void emit_docs(struct userdata *node, int is_userdata, int emit_creation) { // methods struct method *method = node->methods; while(method) { - fprintf(docs, "-- desc\n"); - - struct argument *arg = method->arguments; - int count = 1; - // input arguments - while (arg != NULL) { - if ((arg->type.type != TYPE_LITERAL) && (arg->type.flags & (TYPE_FLAGS_NULLABLE | TYPE_FLAGS_REFERNCE)) == 0) { - char *param_name = (char *)allocate(20); - sprintf(param_name, "---@param param%i", count); - emit_docs_type(arg->type, param_name, "\n"); - free(param_name); - count++; - } - arg = arg->next; - } + emit_docs_method(name, method->rename ? method->rename : method->name, method); - // return type - if ((method->flags & TYPE_FLAGS_NULLABLE) == 0) { - emit_docs_type(method->return_type, "---@return", "\n"); - } + method = method->next; + } - arg = method->arguments; - // nulable and refences returns - while (arg != NULL) { - if ((arg->type.type != TYPE_LITERAL) && (arg->type.flags & (TYPE_FLAGS_NULLABLE | TYPE_FLAGS_REFERNCE))) { - if (arg->type.flags & TYPE_FLAGS_NULLABLE) { - emit_docs_type(arg->type, "---@return", "|nil\n"); - } else { - emit_docs_type(arg->type, "---@return", "\n"); - } + // aliases + struct method_alias *alias = node->method_aliases; + while(alias) { + // dont do manual bindings + if (alias->type == ALIAS_TYPE_NONE) { + // find the method this is a alias of + struct method * method = node->methods; + while (method != NULL && strcmp(method->name, alias->name)) { + method = method-> next; } - arg = arg->next; - } - - // function name - fprintf(docs, "function %s:%s(", name, method->alias ? method->alias : method->name); - for (int i = 1; i < count; ++i) { - fprintf(docs, "param%i", i); - if (i < count-1) { - fprintf(docs, ", "); + if (method == NULL) { + error(ERROR_DOCS, "Could not fine Method %s to alias to %s", alias->name, alias->alias); } + + emit_docs_method(name, alias->alias, method); } - fprintf(docs, ") end\n\n"); - method = method->next; + alias = alias->next; } fprintf(docs, "\n"); free(name); @@ -2491,6 +2660,8 @@ int main(int argc, char **argv) { handle_singleton(); } else if (strcmp (state.token, keyword_ap_object) == 0){ handle_ap_object(); + } else if (strcmp (state.token, keyword_global) == 0){ + handle_global(); } else { error(ERROR_UNKNOWN_KEYWORD, "Expected a keyword, got: %s", state.token); } @@ -2519,6 +2690,10 @@ int main(int argc, char **argv) { fprintf(source, "#pragma GCC optimize(\"Os\")\n"); fprintf(source, "#include \"lua_generated_bindings.h\"\n"); fprintf(source, "#include \n"); + fprintf(source, "#include \n"); + + // for set_and_print_new_error_message deprecate warning + fprintf(source, "#include \n"); trace(TRACE_GENERAL, "Starting emission"); @@ -2582,6 +2757,7 @@ int main(int argc, char **argv) { fprintf(header, "void load_generated_bindings(lua_State *L);\n"); fprintf(header, "void load_generated_sandbox(lua_State *L);\n"); + fprintf(header, "int binding_argcheck(lua_State *L, int expected_arg_count);\n"); fclose(header); header = NULL; diff --git a/libraries/AP_Scripting/lua/src/lauxlib.c b/libraries/AP_Scripting/lua/src/lauxlib.c index 0822d949591..1b3872e3098 100644 --- a/libraries/AP_Scripting/lua/src/lauxlib.c +++ b/libraries/AP_Scripting/lua/src/lauxlib.c @@ -1044,3 +1044,15 @@ LUALIB_API void luaL_checkversion_ (lua_State *L, lua_Number ver, size_t sz) { (LUAI_UACNUMBER)ver, (LUAI_UACNUMBER)*v); } + +/* + 32 bit random number generator for lua internals + */ +uint32_t lua_random32(void) +{ + static uint32_t m_z = 1234; + static uint32_t m_w = 76542; + m_z = 36969 * (m_z & 0xFFFFu) + (m_z >> 16); + m_w = 18000 * (m_w & 0xFFFFu) + (m_w >> 16); + return ((m_z << 16) + m_w); +} diff --git a/libraries/AP_Scripting/lua/src/lauxlib.h b/libraries/AP_Scripting/lua/src/lauxlib.h index 9857d3a835a..6a6195a5ba9 100644 --- a/libraries/AP_Scripting/lua/src/lauxlib.h +++ b/libraries/AP_Scripting/lua/src/lauxlib.h @@ -36,6 +36,8 @@ typedef struct luaL_Reg { #define LUAL_NUMSIZES (sizeof(lua_Integer)*16 + sizeof(lua_Number)) +uint32_t lua_random32(void); + LUALIB_API void (luaL_checkversion_) (lua_State *L, lua_Number ver, size_t sz); #define luaL_checkversion(L) \ luaL_checkversion_(L, LUA_VERSION_NUM, LUAL_NUMSIZES) diff --git a/libraries/AP_Scripting/lua/src/ldo.c b/libraries/AP_Scripting/lua/src/ldo.c index 951a5b52239..7372bd3b398 100644 --- a/libraries/AP_Scripting/lua/src/ldo.c +++ b/libraries/AP_Scripting/lua/src/ldo.c @@ -133,21 +133,29 @@ l_noret luaD_throw (lua_State *L, int errcode) { } } - +// remove optimization +#pragma GCC push_options +#pragma GCC optimize ("O0") int luaD_rawrunprotected (lua_State *L, Pfunc f, void *ud) { unsigned short oldnCcalls = L->nCcalls; struct lua_longjmp lj; lj.status = LUA_OK; lj.previous = L->errorJmp; /* chain new error handler */ L->errorJmp = &lj; +#ifdef ARM_MATH_CM7 + __asm__("vpush {s16-s31}"); +#endif LUAI_TRY(L, &lj, (*f)(L, ud); ); +#ifdef ARM_MATH_CM7 + __asm__("vpop {s16-s31}"); +#endif L->errorJmp = lj.previous; /* restore old error handler */ L->nCcalls = oldnCcalls; return lj.status; } - +#pragma GCC pop_options /* }====================================================== */ diff --git a/libraries/AP_Scripting/lua/src/lstate.c b/libraries/AP_Scripting/lua/src/lstate.c index 25580bff244..796deb781bf 100644 --- a/libraries/AP_Scripting/lua/src/lstate.c +++ b/libraries/AP_Scripting/lua/src/lstate.c @@ -26,6 +26,7 @@ #include "lstring.h" #include "ltable.h" #include "ltm.h" +#include "lauxlib.h" // lua code does lots of casting, these warnings are not helpful #pragma GCC diagnostic ignored "-Wcast-align" @@ -44,10 +45,14 @@ ** a macro to help the creation of a unique random seed when a state is ** created; the seed is used to randomize hashes. */ +#if defined(ARDUPILOT_BUILD) +#define luai_makeseed() lua_random32() +#else #if !defined(luai_makeseed) #include #define luai_makeseed() cast(unsigned int, time(NULL)) #endif +#endif diff --git a/libraries/AP_Scripting/lua/src/ltablib.c b/libraries/AP_Scripting/lua/src/ltablib.c index c5349578ec7..d2b04fe5e20 100644 --- a/libraries/AP_Scripting/lua/src/ltablib.c +++ b/libraries/AP_Scripting/lua/src/ltablib.c @@ -256,6 +256,9 @@ typedef unsigned int IdxT; ** is to copy them to an array of a known type and use the array values. */ static unsigned int l_randomizePivot (void) { +#if defined(ARDUPILOT_BUILD) + return lua_random32(); +#else clock_t c = clock(); time_t t = time(NULL); unsigned int buff[sof(c) + sof(t)]; @@ -265,6 +268,7 @@ static unsigned int l_randomizePivot (void) { for (i = 0; i < sof(buff); i++) rnd += buff[i]; return rnd; +#endif } #endif /* } */ diff --git a/libraries/AP_Scripting/lua_bindings.cpp b/libraries/AP_Scripting/lua_bindings.cpp index 225623267ab..e564f6dfd44 100644 --- a/libraries/AP_Scripting/lua_bindings.cpp +++ b/libraries/AP_Scripting/lua_bindings.cpp @@ -1,5 +1,4 @@ #include -#include #include #include @@ -13,24 +12,9 @@ extern const AP_HAL::HAL& hal; -int check_arguments(lua_State *L, int expected_arguments, const char *fn_name); -int check_arguments(lua_State *L, int expected_arguments, const char *fn_name) { -#if defined(AP_SCRIPTING_CHECKS) && AP_SCRIPTING_CHECKS >= 1 - if (expected_arguments < 0) { - AP_HAL::panic("Lua: Attempted to check for negative arguments"); - } -#endif - - const int args = lua_gettop(L); - if (args != expected_arguments) { - return luaL_error(L, "%s expected %d arguments got %d", fn_name, expected_arguments, args); - } - return 0; -} - // millis -static int lua_millis(lua_State *L) { - check_arguments(L, 0, "millis"); +int lua_millis(lua_State *L) { + binding_argcheck(L, 0); new_uint32_t(L); *check_uint32_t(L, -1) = AP_HAL::millis(); @@ -39,8 +23,8 @@ static int lua_millis(lua_State *L) { } // micros -static int lua_micros(lua_State *L) { - check_arguments(L, 0, "micros"); +int lua_micros(lua_State *L) { + binding_argcheck(L, 0); new_uint32_t(L); *check_uint32_t(L, -1) = AP_HAL::micros(); @@ -48,8 +32,8 @@ static int lua_micros(lua_State *L) { return 1; } -static int lua_mission_receive(lua_State *L) { - check_arguments(L, 0, "mission_receive"); +int lua_mission_receive(lua_State *L) { + binding_argcheck(L, 0); ObjectBuffer *input = AP::scripting()->mission_data; @@ -76,29 +60,24 @@ static int lua_mission_receive(lua_State *L) { return 5; } -static const luaL_Reg global_functions[] = -{ - {"millis", lua_millis}, - {"micros", lua_micros}, - {"mission_receive", lua_mission_receive}, - {NULL, NULL} -}; - -static int AP_Logger_Write(lua_State *L) { +int AP_Logger_Write(lua_State *L) { AP_Logger * AP_logger = AP_Logger::get_singleton(); if (AP_logger == nullptr) { return luaL_argerror(L, 1, "logger not supported on this firmware"); } + // Allow : and . access + const int arg_offset = (luaL_testudata(L, 1, "logger") != NULL) ? 1 : 0; + // check we have at least 4 arguments passed in - const int args = lua_gettop(L); + const int args = lua_gettop(L) - arg_offset; if (args < 4) { return luaL_argerror(L, args, "too few arguments"); } - const char * name = luaL_checkstring(L, 1); - const char * labels = luaL_checkstring(L, 2); - const char * fmt = luaL_checkstring(L, 3); + const char * name = luaL_checkstring(L, 1 + arg_offset); + const char * labels = luaL_checkstring(L, 2 + arg_offset); + const char * fmt = luaL_checkstring(L, 3 + arg_offset); // cheack the name, labels and format are not too long if (strlen(name) >= LS_NAME_SIZE) { @@ -156,8 +135,8 @@ static int AP_Logger_Write(lua_State *L) { } else { // read in units and multiplers strings field_start += 2; - const char * units = luaL_checkstring(L, 4); - const char * multipliers = luaL_checkstring(L, 5); + const char * units = luaL_checkstring(L, 4 + arg_offset); + const char * multipliers = luaL_checkstring(L, 5 + arg_offset); if (length != strlen(units)) { return luaL_error(L, "units must be same length as format"); @@ -204,6 +183,7 @@ static int AP_Logger_Write(lua_State *L) { for (uint8_t i=field_start; i<=args; i++) { uint8_t charlen = 0; uint8_t index = have_units ? i-5 : i-3; + uint8_t arg_index = i + arg_offset; switch(fmt_cat[index]) { // logger varable types not available to scripting // 'b': int8_t @@ -218,15 +198,15 @@ static int AP_Logger_Write(lua_State *L) { case 'i': case 'L': case 'e': { - const lua_Integer tmp1 = luaL_checkinteger(L, i); - luaL_argcheck(L, ((tmp1 >= INT32_MIN) && (tmp1 <= INT32_MAX)), i, "argument out of range"); + const lua_Integer tmp1 = luaL_checkinteger(L, arg_index); + luaL_argcheck(L, ((tmp1 >= INT32_MIN) && (tmp1 <= INT32_MAX)), arg_index, "argument out of range"); int32_t tmp = tmp1; luaL_addlstring(&buffer, (char *)&tmp, sizeof(int32_t)); break; } case 'f': { - float tmp = luaL_checknumber(L, i); - luaL_argcheck(L, ((tmp >= -INFINITY) && (tmp <= INFINITY)), i, "argument out of range"); + float tmp = luaL_checknumber(L, arg_index); + luaL_argcheck(L, ((tmp >= -INFINITY) && (tmp <= INFINITY)), arg_index, "argument out of range"); luaL_addlstring(&buffer, (char *)&tmp, sizeof(float)); break; } @@ -236,15 +216,15 @@ static int AP_Logger_Write(lua_State *L) { } case 'M': case 'B': { - const lua_Integer tmp1 = luaL_checkinteger(L, i); - luaL_argcheck(L, ((tmp1 >= 0) && (tmp1 <= UINT8_MAX)), i, "argument out of range"); + const lua_Integer tmp1 = luaL_checkinteger(L, arg_index); + luaL_argcheck(L, ((tmp1 >= 0) && (tmp1 <= UINT8_MAX)), arg_index, "argument out of range"); uint8_t tmp = static_cast(tmp1); luaL_addlstring(&buffer, (char *)&tmp, sizeof(uint8_t)); break; } case 'I': case 'E': { - const uint32_t tmp = coerce_to_uint32_t(L, i); + const uint32_t tmp = coerce_to_uint32_t(L, arg_index); luaL_addlstring(&buffer, (char *)&tmp, sizeof(uint32_t)); break; } @@ -257,14 +237,14 @@ static int AP_Logger_Write(lua_State *L) { break; } default: { - return luaL_error(L, "%c unsupported format",fmt_cat[i-3]); + return luaL_error(L, "%c unsupported format",fmt_cat[arg_index-3]); } } if (charlen != 0) { - const char *tmp = luaL_checkstring(L, i); + const char *tmp = luaL_checkstring(L, arg_index); const size_t slen = strlen(tmp); if (slen > charlen) { - return luaL_error(L, "arg %i too long for %c format",i,fmt_cat[i-3]); + return luaL_error(L, "arg %i too long for %c format",arg_index,fmt_cat[arg_index-3]); } char tstr[charlen]; memcpy(tstr, tmp, slen); @@ -283,14 +263,12 @@ static int AP_Logger_Write(lua_State *L) { return 0; } -const luaL_Reg AP_Logger_functions[] = { - {"write", AP_Logger_Write}, - {NULL, NULL} -}; +int lua_get_i2c_device(lua_State *L) { -static int lua_get_i2c_device(lua_State *L) { + // Allow : and . access + const int arg_offset = (luaL_testudata(L, 1, "i2c") != NULL) ? 1 : 0; - const int args = lua_gettop(L); + const int args = lua_gettop(L) - arg_offset; if (args < 2) { return luaL_argerror(L, args, "require i2c bus and address"); } @@ -298,12 +276,12 @@ static int lua_get_i2c_device(lua_State *L) { return luaL_argerror(L, args, "too many arguments"); } - const lua_Integer bus_in = luaL_checkinteger(L, 1); - luaL_argcheck(L, ((bus_in >= 0) && (bus_in <= 4)), 1, "bus out of range"); + const lua_Integer bus_in = luaL_checkinteger(L, 1 + arg_offset); + luaL_argcheck(L, ((bus_in >= 0) && (bus_in <= 4)), 1 + arg_offset, "bus out of range"); const uint8_t bus = static_cast(bus_in); - const lua_Integer address_in = luaL_checkinteger(L, 2); - luaL_argcheck(L, ((address_in >= 0) && (address_in <= 128)), 2, "address out of range"); + const lua_Integer address_in = luaL_checkinteger(L, 2 + arg_offset); + luaL_argcheck(L, ((address_in >= 0) && (address_in <= 128)), 2 + arg_offset, "address out of range"); const uint8_t address = static_cast(address_in); // optional arguments, use the same defaults as the hal get_device function @@ -311,10 +289,10 @@ static int lua_get_i2c_device(lua_State *L) { bool use_smbus = false; if (args > 2) { - bus_clock = coerce_to_uint32_t(L, 3); + bus_clock = coerce_to_uint32_t(L, 3 + arg_offset); if (args > 3) { - use_smbus = static_cast(lua_toboolean(L, 4)); + use_smbus = static_cast(lua_toboolean(L, 4 + arg_offset)); } } @@ -342,22 +320,69 @@ static int lua_get_i2c_device(lua_State *L) { return 1; } -const luaL_Reg i2c_functions[] = { - {"get_device", lua_get_i2c_device}, - {NULL, NULL} -}; +int AP_HAL__I2CDevice_read_registers(lua_State *L) { + const int args = lua_gettop(L); + bool multi_register; + if (args == 2) { + multi_register = false; + } else if (args == 3) { + multi_register = true; + } else { + return luaL_argerror(L, args, "expected 1 or 2 arguments"); + } + + AP_HAL::I2CDevice * ud = *check_AP_HAL__I2CDevice(L, 1); + if (ud == NULL) { + return luaL_error(L, "Internal error, null pointer"); + } + + const lua_Integer raw_first_reg = luaL_checkinteger(L, 2); + luaL_argcheck(L, ((raw_first_reg >= MAX(0, 0)) && (raw_first_reg <= MIN(UINT8_MAX, UINT8_MAX))), 2, "argument out of range"); + const uint8_t first_reg = static_cast(raw_first_reg); + + uint8_t recv_length = 1; + if (multi_register) { + const lua_Integer raw_recv_length = luaL_checkinteger(L, 3); + luaL_argcheck(L, ((raw_recv_length >= MAX(0, 0)) && (raw_recv_length <= MIN(UINT8_MAX, UINT8_MAX))), 3, "argument out of range"); + recv_length = static_cast(raw_recv_length); + } + + uint8_t data[recv_length]; + + ud->get_semaphore()->take_blocking(); + const bool success = static_cast(ud->read_registers(first_reg, data, recv_length)); + ud->get_semaphore()->give(); + + if (success) { + if (!multi_register) { + lua_pushinteger(L, data[0]); + } else { + // push to table + lua_newtable(L); + for (uint8_t i=0; i < recv_length; i++) { + lua_pushinteger(L, i+1); + lua_pushinteger(L, data[i]); + lua_settable(L, -3); + } + } + } + return success; +} #if HAL_MAX_CAN_PROTOCOL_DRIVERS -static int lua_get_CAN_device(lua_State *L) { +int lua_get_CAN_device(lua_State *L) { - check_arguments(L, 1, "CAN:get_device"); + // Allow : and . access + const int arg_offset = (luaL_testudata(L, 1, "CAN") != NULL) ? 1 : 0; - const uint32_t raw_buffer_len = coerce_to_uint32_t(L, 1); - luaL_argcheck(L, ((raw_buffer_len >= 1U) && (raw_buffer_len <= 25U)), 1, "argument out of range"); + binding_argcheck(L, 1 + arg_offset); + + const uint32_t raw_buffer_len = coerce_to_uint32_t(L, 1 + arg_offset); + luaL_argcheck(L, ((raw_buffer_len >= 1U) && (raw_buffer_len <= 25U)), 1 + arg_offset, "argument out of range"); const uint32_t buffer_len = static_cast(raw_buffer_len); if (AP::scripting()->_CAN_dev == nullptr) { - AP::scripting()->_CAN_dev = new ScriptingCANSensor(); + AP::scripting()->_CAN_dev = new ScriptingCANSensor(AP_CANManager::Driver_Type::Driver_Type_Scripting); if (AP::scripting()->_CAN_dev == nullptr) { return luaL_argerror(L, 1, "CAN device nullptr"); } @@ -369,27 +394,27 @@ static int lua_get_CAN_device(lua_State *L) { return 1; } -const luaL_Reg CAN_functions[] = { - {"get_device", lua_get_CAN_device}, - {NULL, NULL} -}; -#endif // HAL_MAX_CAN_PROTOCOL_DRIVERS +int lua_get_CAN_device2(lua_State *L) { -void load_lua_bindings(lua_State *L) { - lua_pushstring(L, "logger"); - luaL_newlib(L, AP_Logger_functions); - lua_settable(L, -3); + // Allow : and . access + const int arg_offset = (luaL_testudata(L, 1, "CAN") != NULL) ? 1 : 0; - lua_pushstring(L, "i2c"); - luaL_newlib(L, i2c_functions); - lua_settable(L, -3); + binding_argcheck(L, 1 + arg_offset); -#if HAL_MAX_CAN_PROTOCOL_DRIVERS - lua_pushstring(L, "CAN"); - luaL_newlib(L, CAN_functions); - lua_settable(L, -3); -#endif + const uint32_t raw_buffer_len = coerce_to_uint32_t(L, 1 + arg_offset); + luaL_argcheck(L, ((raw_buffer_len >= 1U) && (raw_buffer_len <= 25U)), 1 + arg_offset, "argument out of range"); + const uint32_t buffer_len = static_cast(raw_buffer_len); - luaL_setfuncs(L, global_functions, 0); -} + if (AP::scripting()->_CAN_dev2 == nullptr) { + AP::scripting()->_CAN_dev2 = new ScriptingCANSensor(AP_CANManager::Driver_Type::Driver_Type_Scripting2); + if (AP::scripting()->_CAN_dev2 == nullptr) { + return luaL_argerror(L, 1, "CAN device nullptr"); + } + } + new_ScriptingCANBuffer(L); + *check_ScriptingCANBuffer(L, -1) = AP::scripting()->_CAN_dev2->add_buffer(buffer_len); + + return 1; +} +#endif // HAL_MAX_CAN_PROTOCOL_DRIVERS diff --git a/libraries/AP_Scripting/lua_bindings.h b/libraries/AP_Scripting/lua_bindings.h index 21099e8bff8..c32930e36c2 100644 --- a/libraries/AP_Scripting/lua_bindings.h +++ b/libraries/AP_Scripting/lua_bindings.h @@ -2,5 +2,11 @@ #include "lua/src/lua.hpp" -// load all known lua bindings into the state -void load_lua_bindings(lua_State *state); +int lua_millis(lua_State *L); +int lua_micros(lua_State *L); +int lua_mission_receive(lua_State *L); +int AP_Logger_Write(lua_State *L); +int lua_get_i2c_device(lua_State *L); +int AP_HAL__I2CDevice_read_registers(lua_State *L); +int lua_get_CAN_device(lua_State *L); +int lua_get_CAN_device2(lua_State *L); diff --git a/libraries/AP_Scripting/lua_boxed_numerics.cpp b/libraries/AP_Scripting/lua_boxed_numerics.cpp index 065bca77e4a..ce7a9f64a32 100644 --- a/libraries/AP_Scripting/lua_boxed_numerics.cpp +++ b/libraries/AP_Scripting/lua_boxed_numerics.cpp @@ -1,5 +1,6 @@ #include #include "lua_boxed_numerics.h" +#include extern const AP_HAL::HAL& hal; @@ -19,7 +20,7 @@ uint32_t coerce_to_uint32_t(lua_State *L, int arg) { int success; const lua_Integer v = lua_tointegerx(L, arg, &success); - if (success && v >= 0) { + if (success) { return static_cast(v); } } @@ -34,18 +35,7 @@ uint32_t coerce_to_uint32_t(lua_State *L, int arg) { return luaL_argerror(L, arg, "Unable to coerce to uint32_t"); } -// creates a new userdata for a uint32_t -int new_uint32_t(lua_State *L) { - luaL_checkstack(L, 2, "Out of stack"); - - *static_cast(lua_newuserdata(L, sizeof(uint32_t))) = 0; - luaL_getmetatable(L, "uint32_t"); - lua_setmetatable(L, -2); - return 1; -} - // the exposed constructor to lua calls to create a uint32_t -int lua_new_uint32_t(lua_State *L); int lua_new_uint32_t(lua_State *L) { const int args = lua_gettop(L); if (args > 1) { @@ -58,19 +48,9 @@ int lua_new_uint32_t(lua_State *L) { return 1; } -uint32_t * check_uint32_t(lua_State *L, int arg) { - void *data = luaL_checkudata(L, arg, "uint32_t"); - return static_cast(data); -} - #define UINT32_T_BOX_OP(name, sym) \ - static int uint32_t___##name(lua_State *L) { \ - const int args = lua_gettop(L); \ - if (args > 2) { \ - return luaL_argerror(L, args, "too many arguments"); \ - } else if (args < 2) { \ - return luaL_argerror(L, args, "too few arguments"); \ - } \ + int uint32_t___##name(lua_State *L) { \ + binding_argcheck(L, 2); \ \ uint32_t v1 = coerce_to_uint32_t(L, 1); \ uint32_t v2 = coerce_to_uint32_t(L, 2); \ @@ -85,7 +65,6 @@ UINT32_T_BOX_OP(sub, -) UINT32_T_BOX_OP(mul, *) UINT32_T_BOX_OP(div, /) UINT32_T_BOX_OP(mod, %) -UINT32_T_BOX_OP(idiv, /) UINT32_T_BOX_OP(band, &) UINT32_T_BOX_OP(bor, |) UINT32_T_BOX_OP(bxor, ^) @@ -93,14 +72,8 @@ UINT32_T_BOX_OP(shl, <<) UINT32_T_BOX_OP(shr, >>) #define UINT32_T_BOX_OP_BOOL(name, sym) \ - static int uint32_t___##name(lua_State *L) { \ - const int args = lua_gettop(L); \ - luaL_checkstack(L, 1, "Out of stack"); \ - if (args > 2) { \ - return luaL_argerror(L, args, "too many arguments"); \ - } else if (args < 2) { \ - return luaL_argerror(L, args, "too few arguments"); \ - } \ + int uint32_t___##name(lua_State *L) { \ + binding_argcheck(L, 2); \ \ uint32_t v1 = coerce_to_uint32_t(L, 1); \ uint32_t v2 = coerce_to_uint32_t(L, 2); \ @@ -114,12 +87,8 @@ UINT32_T_BOX_OP_BOOL(lt, <) UINT32_T_BOX_OP_BOOL(le, <=) #define UINT32_T_BOX_OP_UNARY(name, sym) \ - static int uint32_t___##name(lua_State *L) { \ - const int args = lua_gettop(L); \ - luaL_checkstack(L, 1, "Out of stack"); \ - if (args != 1) { \ - return luaL_argerror(L, args, "Expected 1 argument"); \ - } \ + int uint32_t___##name(lua_State *L) { \ + binding_argcheck(L, 1); \ \ uint32_t v1 = coerce_to_uint32_t(L, 1); \ \ @@ -131,11 +100,8 @@ UINT32_T_BOX_OP_BOOL(le, <=) // DO NOT SUPPORT UNARY NEGATION UINT32_T_BOX_OP_UNARY(bnot, ~) -static int uint32_t_toint(lua_State *L) { - const int args = lua_gettop(L); - if (args != 1) { - return luaL_argerror(L, args, "Expected 1 argument"); - } +int uint32_t_toint(lua_State *L) { + binding_argcheck(L, 1); uint32_t v = *static_cast(luaL_checkudata(L, 1, "uint32_t")); @@ -144,11 +110,8 @@ static int uint32_t_toint(lua_State *L) { return 1; } -static int uint32_t_tofloat(lua_State *L) { - const int args = lua_gettop(L); - if (args != 1) { - return luaL_argerror(L, args, "Expected 1 argument"); - } +int uint32_t_tofloat(lua_State *L) { + binding_argcheck(L, 1); uint32_t v = *static_cast(luaL_checkudata(L, 1, "uint32_t")); @@ -157,11 +120,8 @@ static int uint32_t_tofloat(lua_State *L) { return 1; } -static int uint32_t___tostring(lua_State *L) { - const int args = lua_gettop(L); - if (args != 1) { - return luaL_argerror(L, args, "Expected 1 argument"); - } +int uint32_t___tostring(lua_State *L) { + binding_argcheck(L, 1); uint32_t v = *static_cast(luaL_checkudata(L, 1, "uint32_t")); @@ -172,43 +132,3 @@ static int uint32_t___tostring(lua_State *L) { return 1; } - -const luaL_Reg uint32_t_meta[] = { - {"__add", uint32_t___add}, - {"__sub", uint32_t___sub}, - {"__mul", uint32_t___mul}, - {"__div", uint32_t___div}, - {"__mod", uint32_t___mod}, - {"__idiv", uint32_t___idiv}, - {"__band", uint32_t___band}, - {"__bor", uint32_t___bor}, - {"__bxor", uint32_t___bxor}, - {"__shl", uint32_t___shl}, - {"__shr", uint32_t___shr}, - {"__shr", uint32_t___shr}, - {"__eq", uint32_t___eq}, - {"__lt", uint32_t___lt}, - {"__le", uint32_t___le}, - {"__bnot", uint32_t___bnot}, - {"__tostring", uint32_t___tostring}, - {"toint", uint32_t_toint}, - {"tofloat", uint32_t_tofloat}, - {NULL, NULL} -}; - -void load_boxed_numerics(lua_State *L) { - luaL_checkstack(L, 5, "Out of stack"); - luaL_newmetatable(L, "uint32_t"); - luaL_setfuncs(L, uint32_t_meta, 0); - lua_pushstring(L, "__index"); - lua_pushvalue(L, -2); - lua_settable(L, -3); - lua_pop(L, 1); -} - -void load_boxed_numerics_sandbox(lua_State *L) { - // if there are ever more drivers then move to a table based solution - lua_pushstring(L, "uint32_t"); - lua_pushcfunction(L, lua_new_uint32_t); - lua_settable(L, -3); -} diff --git a/libraries/AP_Scripting/lua_boxed_numerics.h b/libraries/AP_Scripting/lua_boxed_numerics.h index 22ee1ea6996..e98ce898260 100644 --- a/libraries/AP_Scripting/lua_boxed_numerics.h +++ b/libraries/AP_Scripting/lua_boxed_numerics.h @@ -2,9 +2,23 @@ #include "lua/src/lua.hpp" -int new_uint32_t(lua_State *L); -uint32_t *check_uint32_t(lua_State *L, int arg); uint32_t coerce_to_uint32_t(lua_State *L, int arg); +int lua_new_uint32_t(lua_State *L); -void load_boxed_numerics(lua_State *L); -void load_boxed_numerics_sandbox(lua_State *L); +int uint32_t___add(lua_State *L); +int uint32_t___sub(lua_State *L); +int uint32_t___mul(lua_State *L); +int uint32_t___div(lua_State *L); +int uint32_t___mod(lua_State *L); +int uint32_t___band(lua_State *L); +int uint32_t___bor(lua_State *L); +int uint32_t___bxor(lua_State *L); +int uint32_t___shl(lua_State *L); +int uint32_t___shr(lua_State *L); +int uint32_t___eq(lua_State *L); +int uint32_t___lt(lua_State *L); +int uint32_t___le(lua_State *L); +int uint32_t___bnot(lua_State *L); +int uint32_t___tostring(lua_State *L); +int uint32_t_toint(lua_State *L); +int uint32_t_tofloat(lua_State *L); diff --git a/libraries/AP_Scripting/lua_repl.cpp b/libraries/AP_Scripting/lua_repl.cpp index b5d775431dd..373276ca102 100644 --- a/libraries/AP_Scripting/lua_repl.cpp +++ b/libraries/AP_Scripting/lua_repl.cpp @@ -10,6 +10,8 @@ #include "lua/src/lauxlib.h" #include "lua/src/lualib.h" +#include + #if !defined(LUA_MAXINPUT) #define LUA_MAXINPUT 256 #endif diff --git a/libraries/AP_Scripting/lua_scripts.cpp b/libraries/AP_Scripting/lua_scripts.cpp index 389429a36a7..01e675cd62b 100644 --- a/libraries/AP_Scripting/lua_scripts.cpp +++ b/libraries/AP_Scripting/lua_scripts.cpp @@ -16,6 +16,7 @@ #include "lua_scripts.h" #include #include "AP_Scripting.h" +#include #include @@ -26,6 +27,7 @@ extern const AP_HAL::HAL& hal; bool lua_scripts::overtime; jmp_buf lua_scripts::panic_jmp; char *lua_scripts::error_msg_buf; +HAL_Semaphore lua_scripts::error_msg_buf_sem; uint8_t lua_scripts::print_error_count; uint32_t lua_scripts::last_print_ms; @@ -36,6 +38,10 @@ lua_scripts::lua_scripts(const AP_Int32 &vm_steps, const AP_Int32 &heap_size, co _heap = hal.util->allocate_heap_memory(heap_size); } +lua_scripts::~lua_scripts() { + free(_heap); +} + void lua_scripts::hook(lua_State *L, lua_Debug *ar) { lua_scripts::overtime = true; @@ -47,14 +53,19 @@ void lua_scripts::hook(lua_State *L, lua_Debug *ar) { } void lua_scripts::print_error(MAV_SEVERITY severity) { + error_msg_buf_sem.take_blocking(); if (error_msg_buf == nullptr) { + error_msg_buf_sem.give(); return; } last_print_ms = AP_HAL::millis(); GCS_SEND_TEXT(severity, "Lua: %s", error_msg_buf); + error_msg_buf_sem.give(); } void lua_scripts::set_and_print_new_error_message(MAV_SEVERITY severity, const char *fmt, ...) { + error_msg_buf_sem.take_blocking(); + // reset buffer and print count print_error_count = 0; if (error_msg_buf) { @@ -68,7 +79,7 @@ void lua_scripts::set_and_print_new_error_message(MAV_SEVERITY severity, const c va_copy(arg_list_copy, arg_list); // dry run to work out the required length - int len = hal.util->vsnprintf(NULL, 0, fmt, arg_list_copy); + int len = hal.util->vsnprintf(nullptr, 0, fmt, arg_list_copy); // finished with copy va_end(arg_list_copy); @@ -76,6 +87,7 @@ void lua_scripts::set_and_print_new_error_message(MAV_SEVERITY severity, const c if (len <= 0) { // nothing to print, something has gone wrong va_end(arg_list); + error_msg_buf_sem.give(); return; } @@ -84,6 +96,7 @@ void lua_scripts::set_and_print_new_error_message(MAV_SEVERITY severity, const c if (!error_msg_buf) { // allocation failed va_end(arg_list); + error_msg_buf_sem.give(); return; } @@ -92,7 +105,9 @@ void lua_scripts::set_and_print_new_error_message(MAV_SEVERITY severity, const c va_end(arg_list); // print to cosole and GCS - hal.console->printf("Lua: %s\n", error_msg_buf); + DEV_PRINTF("Lua: %s\n", error_msg_buf); + + error_msg_buf_sem.give(); print_error(severity); } @@ -162,7 +177,6 @@ void lua_scripts::create_sandbox(lua_State *L) { lua_pushstring(L, "utf8"); luaopen_utf8(L); lua_settable(L, -3); - load_lua_bindings(L); load_generated_sandbox(L); } @@ -527,12 +541,26 @@ void lua_scripts::run(void) { // re-print the latest error message every 10 seconds 10 times const uint8_t error_prints = 10; if ((print_error_count < error_prints) && (AP_HAL::millis() - last_print_ms > 10000)) { + // note that we do not clear the buffer after we have finished printing, this allows it to be used for a pre-arm check print_error(MAV_SEVERITY_DEBUG); print_error_count++; - if ((print_error_count >= error_prints) && (error_msg_buf != nullptr)) { - hal.util->heap_realloc(_heap, error_msg_buf, 0); - error_msg_buf = nullptr; - } } } + + // make sure all scripts have been removed + while (scripts != nullptr) { + remove_script(lua_state, scripts); + } + + if (lua_state != nullptr) { + lua_close(lua_state); // shutdown the old state + lua_state = nullptr; + } + + error_msg_buf_sem.take_blocking(); + if (error_msg_buf != nullptr) { + hal.util->heap_realloc(_heap, error_msg_buf, 0); + error_msg_buf = nullptr; + } + error_msg_buf_sem.give(); } diff --git a/libraries/AP_Scripting/lua_scripts.h b/libraries/AP_Scripting/lua_scripts.h index 4b7a830c75f..879d699196f 100644 --- a/libraries/AP_Scripting/lua_scripts.h +++ b/libraries/AP_Scripting/lua_scripts.h @@ -19,9 +19,11 @@ #include #include -#include "lua_bindings.h" #include #include +#include + +#include "lua/src/lua.hpp" #ifndef REPL_DIRECTORY #if HAL_OS_FATFS_IO @@ -52,9 +54,9 @@ class lua_scripts public: lua_scripts(const AP_Int32 &vm_steps, const AP_Int32 &heap_size, const AP_Int8 &debug_options, struct AP_Scripting::terminal_s &_terminal); - /* Do not allow copies */ - lua_scripts(const lua_scripts &other) = delete; - lua_scripts &operator=(const lua_scripts&) = delete; + ~lua_scripts(); + + CLASS_NO_COPY(lua_scripts); // return true if initialisation failed bool heap_allocated() const { return _heap != nullptr; } @@ -69,6 +71,7 @@ class lua_scripts RUNTIME_MSG = 1U << 1, SUPPRESS_SCRIPT_LOG = 1U << 2, LOG_RUNTIME = 1U << 3, + DISABLE_PRE_ARM = 1U << 4, }; private: @@ -132,8 +135,19 @@ class lua_scripts // must be static for use in atpanic static void print_error(MAV_SEVERITY severity); - static void set_and_print_new_error_message(MAV_SEVERITY severity, const char *fmt, ...) FMT_PRINTF(2,3); static char *error_msg_buf; + static HAL_Semaphore error_msg_buf_sem; static uint8_t print_error_count; static uint32_t last_print_ms; + +public: + // must be static for use in atpanic, public to allow bindings to issue none fatal warnings + static void set_and_print_new_error_message(MAV_SEVERITY severity, const char *fmt, ...) FMT_PRINTF(2,3); + + // return last error message, nullptr if none, must use semaphore as this is updated in the scripting thread + static const char* get_last_error_message() { return error_msg_buf; } + + // get semaphore for above error buffer + static AP_HAL::Semaphore* get_last_error_semaphore() { return &error_msg_buf_sem; } + }; diff --git a/libraries/AP_SerialLED/AP_SerialLED.cpp b/libraries/AP_SerialLED/AP_SerialLED.cpp index 4c78fe5328f..90562559289 100644 --- a/libraries/AP_SerialLED/AP_SerialLED.cpp +++ b/libraries/AP_SerialLED/AP_SerialLED.cpp @@ -38,7 +38,7 @@ bool AP_SerialLED::set_num_profiled(uint8_t chan, uint8_t num_leds) { if (chan >= 1 && chan <= 16 && num_leds <= AP_SERIALLED_MAX_LEDS - 2) { // must have a clock - uint16_t Clock_mask = 0; + uint32_t Clock_mask = 0; if (!SRV_Channels::function_assigned((SRV_Channel::Aux_servo_function_t)((uint8_t)SRV_Channel::k_ProfiLED_Clock))) { return false; } diff --git a/libraries/AP_SerialLED/AP_SerialLED.h b/libraries/AP_SerialLED/AP_SerialLED.h index 69c5a2ca327..5b71982b5f7 100644 --- a/libraries/AP_SerialLED/AP_SerialLED.h +++ b/libraries/AP_SerialLED/AP_SerialLED.h @@ -17,7 +17,7 @@ */ #pragma once -#include +#include // limit number of LEDs, mostly to keep DMA memory consumption within // reasonable bounds diff --git a/libraries/AP_SerialManager/AP_SerialManager.cpp b/libraries/AP_SerialManager/AP_SerialManager.cpp index 3aa3407b7c6..1b04c6d0b52 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.cpp +++ b/libraries/AP_SerialManager/AP_SerialManager.cpp @@ -136,7 +136,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = { // @Param: 1_PROTOCOL // @DisplayName: Telem1 protocol selection // @Description: Control what protocol to use on the Telem1 port. Note that the Frsky options require external converter hardware. See the wiki for details. - // @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN, 23:RCIN, 24:MegaSquirt EFI, 25:LTM, 26:RunCam, 27:HottTelem, 28:Scripting, 29:Crossfire VTX, 30:Generator, 31:Winch, 32:MSP, 33:DJI FPV, 34:AirSpeed, 35:ADSB, 36:AHRS, 37:SmartAudio, 38:FETtecOneWire, 39:Torqeedo, 40:AIS, 41:CoDevESC, 42:DisplayPort + // @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN, 23:RCIN, 24:EFI Serial, 25:LTM, 26:RunCam, 27:HottTelem, 28:Scripting, 29:Crossfire VTX, 30:Generator, 31:Winch, 32:MSP, 33:DJI FPV, 34:AirSpeed, 35:ADSB, 36:AHRS, 37:SmartAudio, 38:FETtecOneWire, 39:Torqeedo, 40:AIS, 41:CoDevESC, 42:DisplayPort, 43:MAVLink High Latency, 44:IRC Tramp // @User: Standard // @RebootRequired: True AP_GROUPINFO("1_PROTOCOL", 1, AP_SerialManager, state[1].protocol, SerialProtocol_MAVLink2), @@ -461,38 +461,39 @@ void AP_SerialManager::init() case SerialProtocol_Console: case SerialProtocol_MAVLink: case SerialProtocol_MAVLink2: - uart->begin(map_baudrate(state[i].baud), + case SerialProtocol_MAVLinkHL: + uart->begin(state[i].baudrate(), AP_SERIALMANAGER_MAVLINK_BUFSIZE_RX, AP_SERIALMANAGER_MAVLINK_BUFSIZE_TX); break; case SerialProtocol_FrSky_D: // Note baudrate is hardcoded to 9600 - state[i].baud = AP_SERIALMANAGER_FRSKY_D_BAUD/1000; // update baud param in case user looks at it + state[i].baud.set_and_default(AP_SERIALMANAGER_FRSKY_D_BAUD/1000); // update baud param in case user looks at it // begin is handled by AP_Frsky_telem library break; case SerialProtocol_FrSky_SPort: case SerialProtocol_FrSky_SPort_Passthrough: // Note baudrate is hardcoded to 57600 - state[i].baud = AP_SERIALMANAGER_FRSKY_SPORT_BAUD/1000; // update baud param in case user looks at it + state[i].baud.set_and_default(AP_SERIALMANAGER_FRSKY_SPORT_BAUD/1000); // update baud param in case user looks at it // begin is handled by AP_Frsky_telem library break; case SerialProtocol_GPS: case SerialProtocol_GPS2: - uart->begin(map_baudrate(state[i].baud), + uart->begin(state[i].baudrate(), AP_SERIALMANAGER_GPS_BUFSIZE_RX, AP_SERIALMANAGER_GPS_BUFSIZE_TX); break; case SerialProtocol_AlexMos: // Note baudrate is hardcoded to 115200 - state[i].baud = AP_SERIALMANAGER_ALEXMOS_BAUD / 1000; // update baud param in case user looks at it + state[i].baud.set_and_default(AP_SERIALMANAGER_ALEXMOS_BAUD / 1000); // update baud param in case user looks at it uart->begin(AP_SERIALMANAGER_ALEXMOS_BAUD, AP_SERIALMANAGER_ALEXMOS_BUFSIZE_RX, AP_SERIALMANAGER_ALEXMOS_BUFSIZE_TX); break; case SerialProtocol_SToRM32: // Note baudrate is hardcoded to 115200 - state[i].baud = AP_SERIALMANAGER_SToRM32_BAUD / 1000; // update baud param in case user looks at it - uart->begin(map_baudrate(state[i].baud), + state[i].baud.set_and_default(AP_SERIALMANAGER_SToRM32_BAUD / 1000); // update baud param in case user looks at it + uart->begin(state[i].baudrate(), AP_SERIALMANAGER_SToRM32_BUFSIZE_RX, AP_SERIALMANAGER_SToRM32_BUFSIZE_TX); break; @@ -501,16 +502,16 @@ void AP_SerialManager::init() break; case SerialProtocol_Volz: // Note baudrate is hardcoded to 115200 - state[i].baud = AP_SERIALMANAGER_VOLZ_BAUD; // update baud param in case user looks at it - uart->begin(map_baudrate(state[i].baud), + state[i].baud.set_and_default(AP_SERIALMANAGER_VOLZ_BAUD); // update baud param in case user looks at it + uart->begin(state[i].baudrate(), AP_SERIALMANAGER_VOLZ_BUFSIZE_RX, AP_SERIALMANAGER_VOLZ_BUFSIZE_TX); uart->set_unbuffered_writes(true); uart->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE); break; case SerialProtocol_Sbus1: - state[i].baud = AP_SERIALMANAGER_SBUS1_BAUD / 1000; // update baud param in case user looks at it - uart->begin(map_baudrate(state[i].baud), + state[i].baud.set_and_default(AP_SERIALMANAGER_SBUS1_BAUD / 1000); // update baud param in case user looks at it + uart->begin(state[i].baudrate(), AP_SERIALMANAGER_SBUS1_BUFSIZE_RX, AP_SERIALMANAGER_SBUS1_BUFSIZE_TX); uart->configure_parity(2); // enable even parity @@ -521,13 +522,13 @@ void AP_SerialManager::init() case SerialProtocol_ESCTelemetry: // ESC telemetry protocol from BLHeli32 ESCs. Note that baudrate is hardcoded to 115200 - state[i].baud = 115200 / 1000; - uart->begin(map_baudrate(state[i].baud), 30, 30); + state[i].baud.set_and_default(115200 / 1000); + uart->begin(state[i].baudrate(), 30, 30); uart->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE); break; case SerialProtocol_Robotis: - uart->begin(map_baudrate(state[i].baud), + uart->begin(state[i].baudrate(), AP_SERIALMANAGER_ROBOTIS_BUFSIZE_RX, AP_SERIALMANAGER_ROBOTIS_BUFSIZE_TX); uart->set_unbuffered_writes(true); @@ -535,20 +536,23 @@ void AP_SerialManager::init() break; case SerialProtocol_SLCAN: - uart->begin(map_baudrate(state[i].baud), + uart->begin(state[i].baudrate(), AP_SERIALMANAGER_SLCAN_BUFSIZE_RX, AP_SERIALMANAGER_SLCAN_BUFSIZE_TX); break; #ifndef HAL_BUILD_AP_PERIPH case SerialProtocol_RCIN: - AP::RC().add_uart(uart); + if (!AP::RC().has_uart()) { + AP::RC().add_uart(uart); + } + break; #endif case SerialProtocol_EFI: state[i].baud.set_default(AP_SERIALMANAGER_EFI_MS_BAUD); - uart->begin(map_baudrate(state[i].baud), + uart->begin(state[i].baudrate(), AP_SERIALMANAGER_EFI_MS_BUFSIZE_RX, AP_SERIALMANAGER_EFI_MS_BUFSIZE_TX); uart->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE); @@ -562,7 +566,7 @@ void AP_SerialManager::init() case SerialProtocol_MSP_DisplayPort: // baudrate defaults to 115200 state[i].baud.set_default(AP_SERIALMANAGER_MSP_BAUD/1000); - uart->begin(map_baudrate(state[i].baud), + uart->begin(state[i].baudrate(), AP_SERIALMANAGER_MSP_BUFSIZE_RX, AP_SERIALMANAGER_MSP_BUFSIZE_TX); uart->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE); @@ -570,7 +574,7 @@ void AP_SerialManager::init() break; #endif default: - uart->begin(map_baudrate(state[i].baud)); + uart->begin(state[i].baudrate()); } } } @@ -629,7 +633,7 @@ uint32_t AP_SerialManager::find_baudrate(enum SerialProtocol protocol, uint8_t i if (_state == nullptr) { return 0; } - return map_baudrate(_state->baud); + return _state->baudrate(); } // find_portnum - find port number (SERIALn index) for a protocol and instance, -1 for not found @@ -642,50 +646,6 @@ int8_t AP_SerialManager::find_portnum(enum SerialProtocol protocol, uint8_t inst return int8_t(_state - &state[0]); } -// get_mavlink_channel - provides the mavlink channel associated with a given protocol -// instance should be zero if searching for the first instance, 1 for the second, etc -// returns true if a channel is found, false if not -bool AP_SerialManager::get_mavlink_channel(enum SerialProtocol protocol, uint8_t instance, mavlink_channel_t &mav_chan) const -{ - // check for MAVLink - if (protocol_match(protocol, SerialProtocol_MAVLink)) { - if (instance < MAVLINK_COMM_NUM_BUFFERS) { - mav_chan = (mavlink_channel_t)(MAVLINK_COMM_0 + instance); - return true; - } - } - // report failure - return false; -} - -// should_forward_mavlink_telemetry - returns true if this port should forward telemetry -bool AP_SerialManager::should_forward_mavlink_telemetry(enum SerialProtocol protocol, uint8_t instance) const -{ - const struct UARTState *_state = find_protocol_instance(protocol, instance); - if (_state == nullptr) { - return true; - } - return (_state->options & AP_HAL::UARTDriver::OPTION_MAVLINK_NO_FORWARD) != AP_HAL::UARTDriver::OPTION_MAVLINK_NO_FORWARD; -} - -// get_mavlink_protocol - provides the specific MAVLink protocol for a -// given channel, or SerialProtocol_None if not found -AP_SerialManager::SerialProtocol AP_SerialManager::get_mavlink_protocol(mavlink_channel_t mav_chan) const -{ - uint8_t instance = 0; - uint8_t chan_idx = (uint8_t)(mav_chan - MAVLINK_COMM_0); - for (uint8_t i=0; iset_options(opt.options)) { - hal.console->printf("Unable to setup options for Serial%u\n", i); + DEV_PRINTF("Unable to setup options for Serial%u\n", i); } } @@ -791,8 +751,8 @@ bool AP_SerialManager::get_passthru(AP_HAL::UARTDriver *&port1, AP_HAL::UARTDriv } port1 = hal.serial(passthru_port1); port2 = hal.serial(passthru_port2); - baud1 = map_baudrate(state[passthru_port1].baud); - baud2 = map_baudrate(state[passthru_port2].baud); + baud1 = state[passthru_port1].baudrate(); + baud2 = state[passthru_port2].baudrate(); timeout_s = MAX(passthru_timeout, 0); return true; } diff --git a/libraries/AP_SerialManager/AP_SerialManager.h b/libraries/AP_SerialManager/AP_SerialManager.h index c60be5648a3..c183016e93a 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.h +++ b/libraries/AP_SerialManager/AP_SerialManager.h @@ -22,7 +22,6 @@ #pragma once #include -#include #include #ifdef HAL_UART_NUM_SERIAL_PORTS @@ -169,6 +168,8 @@ class AP_SerialManager { SerialProtocol_AIS = 40, SerialProtocol_CoDevESC = 41, SerialProtocol_MSP_DisplayPort = 42, + SerialProtocol_MAVLinkHL = 43, + SerialProtocol_Tramp = 44, SerialProtocol_NumProtocols // must be the last value }; @@ -200,18 +201,6 @@ class AP_SerialManager { // find_portnum - find port number (SERIALn index) for a protocol and instance, -1 for not found int8_t find_portnum(enum SerialProtocol protocol, uint8_t instance) const; - // get_mavlink_channel - provides the mavlink channel associated with a given protocol (and instance) - // instance should be zero if searching for the first instance, 1 for the second, etc - // returns true if a channel is found, false if not - bool get_mavlink_channel(enum SerialProtocol protocol, uint8_t instance, mavlink_channel_t &mav_chan) const; - - // should_forward_mavlink_telemetry - returns true if this port should forward telemetry - bool should_forward_mavlink_telemetry(enum SerialProtocol protocol, uint8_t instance) const; - - // get_mavlink_protocol - provides the specific MAVLink protocol for a - // given channel, or SerialProtocol_None if not found - SerialProtocol get_mavlink_protocol(mavlink_channel_t mav_chan) const; - // set_blocking_writes_all - sets block_writes on or off for all serial channels void set_blocking_writes_all(bool blocking); @@ -233,27 +222,46 @@ class AP_SerialManager { // parameter var table static const struct AP_Param::GroupInfo var_info[]; + class UARTState { + friend class AP_SerialManager; + public: + bool option_enabled(uint16_t option) const { + return (options & option) == option; + } + // returns a baudrate such as 9600. May map from a special + // parameter value like "57" to "57600": + uint32_t baudrate() const { + return AP_SerialManager::map_baudrate(baud); + } + AP_SerialManager::SerialProtocol get_protocol() const { + return AP_SerialManager::SerialProtocol(protocol.get()); + } + private: + AP_Int32 baud; + AP_Int16 options; + AP_Int8 protocol; + }; + + // search through managed serial connections looking for the + // instance-nth UART which is running protocol protocol. + // protocol_match is used to determine equivalence of one protocol + // to another, e.g. MAVLink2 is considered MAVLink1 for finding + // mavlink1 protocol instances. + const UARTState *find_protocol_instance(enum SerialProtocol protocol, + uint8_t instance) const; + private: static AP_SerialManager *_singleton; // array of uart info. See comment above about // SERIALMANAGER_MAX_PORTS - struct UARTState { - AP_Int32 baud; - AP_Int16 options; - AP_Int8 protocol; - } state[SERIALMANAGER_MAX_PORTS]; + UARTState state[SERIALMANAGER_MAX_PORTS]; // pass-through serial support AP_Int8 passthru_port1; AP_Int8 passthru_port2; AP_Int8 passthru_timeout; - // search through managed serial connections looking for the - // instance-nth UART which is running protocol protocol - const UARTState *find_protocol_instance(enum SerialProtocol protocol, - uint8_t instance) const; - // protocol_match - returns true if the protocols match bool protocol_match(enum SerialProtocol protocol1, enum SerialProtocol protocol2) const; diff --git a/libraries/AP_SmartRTL/AP_SmartRTL.cpp b/libraries/AP_SmartRTL/AP_SmartRTL.cpp index 0a9ecf3a852..f751dbd4766 100644 --- a/libraries/AP_SmartRTL/AP_SmartRTL.cpp +++ b/libraries/AP_SmartRTL/AP_SmartRTL.cpp @@ -99,7 +99,7 @@ void AP_SmartRTL::init() } // constrain the path length, in case the user decided to make the path unreasonably long. - _points_max = constrain_int16(_points_max, 0, SMARTRTL_POINTS_MAX); + _points_max.set(constrain_int16(_points_max, 0, SMARTRTL_POINTS_MAX)); // check if user has disabled SmartRTL if (_points_max == 0 || !is_positive(_accuracy)) { diff --git a/libraries/AP_Soaring/AP_Soaring.h b/libraries/AP_Soaring/AP_Soaring.h index 71d1e73bffe..203bdd45f1e 100644 --- a/libraries/AP_Soaring/AP_Soaring.h +++ b/libraries/AP_Soaring/AP_Soaring.h @@ -30,6 +30,7 @@ class SoaringController { + Variometer::PolarParams _polarParams; ExtendedKalmanFilter _ekf{}; AP_TECS &_tecs; Variometer _vario; @@ -61,8 +62,6 @@ class SoaringController { LowPassFilter _position_x_filter{1/60.0}; LowPassFilter _position_y_filter{1/60.0}; - Variometer::PolarParams _polarParams; - protected: AP_Int8 soar_active; AP_Float thermal_vspeed; diff --git a/libraries/AP_Soaring/SpeedToFly.h b/libraries/AP_Soaring/SpeedToFly.h index 526653a043a..a433e821572 100644 --- a/libraries/AP_Soaring/SpeedToFly.h +++ b/libraries/AP_Soaring/SpeedToFly.h @@ -11,10 +11,10 @@ class SpeedToFly { float _CL_estimate = -1.0f; - Variometer::PolarParams &_polarParams; + const Variometer::PolarParams &_polarParams; public: - SpeedToFly(Variometer::PolarParams &polarParams) :_polarParams(polarParams) {} + SpeedToFly(const Variometer::PolarParams &polarParams) :_polarParams(polarParams) {} void update(float Wx, float Wz, float Wexp, float CLmin, float CLmax); diff --git a/libraries/AP_Soaring/Variometer.cpp b/libraries/AP_Soaring/Variometer.cpp index 28c19fc01f7..eb1ca5493ed 100644 --- a/libraries/AP_Soaring/Variometer.cpp +++ b/libraries/AP_Soaring/Variometer.cpp @@ -6,7 +6,7 @@ Manages the estimation of aircraft total energy, drag and vertical air velocity. #include -Variometer::Variometer(const AP_Vehicle::FixedWing &parms, PolarParams &polarParams) : +Variometer::Variometer(const AP_Vehicle::FixedWing &parms, const PolarParams &polarParams) : _aparm(parms), _polarParams(polarParams) { @@ -21,7 +21,7 @@ void Variometer::update(const float thermal_bank) float aspd = 0; if (!_ahrs.airspeed_estimate(aspd)) { - aspd = _aparm.airspeed_cruise_cm / 100.0f; + aspd = _aparm.airspeed_cruise_cm * 0.01f; } float aspd_filt = _sp_filter.apply(aspd); @@ -126,7 +126,7 @@ float Variometer::calculate_aircraft_sinkrate(float phi) const return _aspd_filt_constrained * (C1 + C2 / (cosphi * cosphi)); } -float Variometer::calculate_circling_time_constant(float thermal_bank) +float Variometer::calculate_circling_time_constant(float thermal_bank) const { // Calculate a time constant to use to filter quantities over a full thermal orbit. // This is used for rejecting variation in e.g. climb rate, or estimated climb rate diff --git a/libraries/AP_Soaring/Variometer.h b/libraries/AP_Soaring/Variometer.h index 3f0ae2653bf..0678884ee91 100644 --- a/libraries/AP_Soaring/Variometer.h +++ b/libraries/AP_Soaring/Variometer.h @@ -53,7 +53,7 @@ class Variometer { AP_Float B; }; - Variometer(const AP_Vehicle::FixedWing &parms, PolarParams &polarParams); + Variometer(const AP_Vehicle::FixedWing &parms, const PolarParams &polarParams); float alt; float reading; @@ -78,9 +78,9 @@ class Variometer { float get_exp_thermalling_sink(void) const {return _expected_thermalling_sink;}; - float calculate_circling_time_constant(const float thermal_bank); + float calculate_circling_time_constant(const float thermal_bank) const; private: - PolarParams &_polarParams; + const PolarParams &_polarParams; }; diff --git a/libraries/AP_TECS/AP_TECS.cpp b/libraries/AP_TECS/AP_TECS.cpp index 8b6480440a2..ff71b39711f 100644 --- a/libraries/AP_TECS/AP_TECS.cpp +++ b/libraries/AP_TECS/AP_TECS.cpp @@ -263,7 +263,7 @@ const AP_Param::GroupInfo AP_TECS::var_info[] = { // @Range: -5.0 0.0 // @User: Advanced AP_GROUPINFO("PTCH_FF_K", 30, AP_TECS, _pitch_ff_k, 0.0), - + AP_GROUPEND }; @@ -383,20 +383,24 @@ void AP_TECS::_update_speed(float load_factor) _TASmin = _TAS_dem; } + // limit the airspeed to a minimum of 3 m/s + const float min_airspeed = 3.0; + // Reset states of time since last update is too large if (DT > 1.0f) { _TAS_state = (_EAS * EAS2TAS); + _TAS_state = MAX(_TAS_state, min_airspeed); _integDTAS_state = 0.0f; DT = 0.1f; // when first starting TECS, use a // small time constant } - // Get airspeed or default to halfway between min and max if - // airspeed is not being used and set speed rate to zero + // Get measured airspeed or default to trim speed and constrain to range between min and max if + // airspeed sensor data cannot be used bool use_airspeed = _use_synthetic_airspeed_once || _use_synthetic_airspeed.get() || _ahrs.airspeed_sensor_enabled(); if (!use_airspeed || !_ahrs.airspeed_estimate(_EAS)) { // If no airspeed available use average of min and max - _EAS = 0.5f * (aparm.airspeed_min.get() + (float)aparm.airspeed_max.get()); + _EAS = constrain_float(0.01f * (float)aparm.airspeed_cruise_cm.get(), (float)aparm.airspeed_min.get(), (float)aparm.airspeed_max.get()); } // Implement a second order complementary filter to obtain a @@ -406,13 +410,12 @@ void AP_TECS::_update_speed(float load_factor) float integDTAS_input = aspdErr * _spdCompFiltOmega * _spdCompFiltOmega; // Prevent state from winding up if (_TAS_state < 3.1f) { - integDTAS_input = MAX(integDTAS_input , 0.0f); + integDTAS_input = MAX(integDTAS_input, 0.0f); } _integDTAS_state = _integDTAS_state + integDTAS_input * DT; float TAS_input = _integDTAS_state + _vel_dot + aspdErr * _spdCompFiltOmega * 1.4142f; _TAS_state = _TAS_state + TAS_input * DT; - // limit the airspeed to a minimum of 3 m/s - _TAS_state = MAX(_TAS_state, 3.0f); + _TAS_state = MAX(_TAS_state, min_airspeed); } @@ -423,8 +426,7 @@ void AP_TECS::_update_speed_demand(void) // This will minimise the rate of descent resulting from an engine failure, // enable the maximum climb rate to be achieved and prevent continued full power descent // into the ground due to an unachievable airspeed value - if ((_flags.badDescent) || (_flags.underspeed)) - { + if ((_flags.badDescent) || (_flags.underspeed)) { _TAS_dem = _TASmin; } @@ -442,18 +444,13 @@ void AP_TECS::_update_speed_demand(void) const float dt = 0.1; // Apply rate limit - if ((_TAS_dem - TAS_dem_previous) > (velRateMax * dt)) - { + if ((_TAS_dem - TAS_dem_previous) > (velRateMax * dt)) { _TAS_dem_adj = TAS_dem_previous + velRateMax * dt; _TAS_rate_dem = velRateMax; - } - else if ((_TAS_dem - TAS_dem_previous) < (velRateMin * dt)) - { + } else if ((_TAS_dem - TAS_dem_previous) < (velRateMin * dt)) { _TAS_dem_adj = TAS_dem_previous + velRateMin * dt; _TAS_rate_dem = velRateMin; - } - else - { + } else { _TAS_rate_dem = (_TAS_dem - TAS_dem_previous) / dt; _TAS_dem_adj = _TAS_dem; } @@ -478,15 +475,11 @@ void AP_TECS::_update_height_demand(void) } // Limit height rate of change - if ((_hgt_dem - _hgt_dem_prev) > (_maxClimbRate * 0.1f)) - { + if ((_hgt_dem - _hgt_dem_prev) > (_maxClimbRate * 0.1f)) { _hgt_dem = _hgt_dem_prev + _maxClimbRate * 0.1f; - } - else if ((_hgt_dem - _hgt_dem_prev) < (-max_sink_rate * 0.1f)) - { + } else if ((_hgt_dem - _hgt_dem_prev) < (-max_sink_rate * 0.1f)) { _hgt_dem = _hgt_dem_prev - max_sink_rate * 0.1f; } - _hgt_dem_prev = _hgt_dem; // Apply first order lag to height demand _hgt_dem_adj = 0.05f * _hgt_dem + 0.95f * _hgt_dem_adj_last; @@ -564,18 +557,15 @@ void AP_TECS::_detect_underspeed(void) if (_flight_stage == AP_Vehicle::FixedWing::FLIGHT_VTOL) { _flags.underspeed = false; } else if (((_TAS_state < _TASmin * 0.9f) && - (_throttle_dem >= _THRmaxf * 0.95f) && - !_landing.is_flaring()) || - ((_height < _hgt_dem_adj) && _flags.underspeed)) - { + (_throttle_dem >= _THRmaxf * 0.95f) && + !_landing.is_flaring()) || + ((_height < _hgt_dem_adj) && _flags.underspeed)) { _flags.underspeed = true; if (_TAS_state < _TASmin * 0.9f) { // reset start time as we are still underspeed _underspeed_start_ms = AP_HAL::millis(); } - } - else - { + } else { // this clears underspeed if we reach our demanded height and // we are either below 95% throttle or we above 90% of min // airspeed @@ -637,7 +627,7 @@ void AP_TECS::_update_throttle_with_airspeed(void) */ SPE_err_max = SPE_err_min = 0; } - + // Calculate total energy error _STE_error = constrain_float((_SPE_dem - _SPE_est), SPE_err_min, SPE_err_max) + _SKE_dem - _SKE_est; float STEdot_dem = constrain_float((_SPEdot_dem + _SKEdot_dem), _STEdot_min, _STEdot_max); @@ -650,16 +640,11 @@ void AP_TECS::_update_throttle_with_airspeed(void) // Calculate throttle demand // If underspeed condition is set, then demand full throttle - if (_flags.underspeed) - { + if (_flags.underspeed) { _throttle_dem = 1.0f; - } - else if (_flags.is_gliding) - { + } else if (_flags.is_gliding) { _throttle_dem = 0.0f; - } - else - { + } else { // Calculate gain scaler from specific energy error to throttle // (_STEdot_max - _STEdot_min) / (_THRmaxf - _THRminf) is the derivative of STEdot wrt throttle measured across the max allowed throttle range. float K_STE2Thr = 1 / (timeConstant() * (_STEdot_max - _STEdot_min) / (_THRmaxf - _THRminf)); @@ -672,7 +657,7 @@ void AP_TECS::_update_throttle_with_airspeed(void) // additional component which scales with (1/cos(bank angle) - 1) to compensate for induced // drag increase during turns. float cosPhi = sqrtf((rotMat.a.y*rotMat.a.y) + (rotMat.b.y*rotMat.b.y)); - STEdot_dem = STEdot_dem + _rollComp * (1.0f/constrain_float(cosPhi * cosPhi , 0.1f, 1.0f) - 1.0f); + STEdot_dem = STEdot_dem + _rollComp * (1.0f/constrain_float(cosPhi * cosPhi, 0.1f, 1.0f) - 1.0f); ff_throttle = nomThr + STEdot_dem / (_STEdot_max - _STEdot_min) * (_THRmaxf - _THRminf); // Calculate PD + FF throttle @@ -682,17 +667,6 @@ void AP_TECS::_update_throttle_with_airspeed(void) } _throttle_dem = (_STE_error + STEdot_error * throttle_damp) * K_STE2Thr + ff_throttle; - // Constrain throttle demand and record clipping - if (_throttle_dem > _THRmaxf) { - _thr_clip_status = ThrClipStatus::MAX; - _throttle_dem = _THRmaxf; - } else if (_throttle_dem < _THRminf) { - _thr_clip_status = ThrClipStatus::MIN; - _throttle_dem = _THRminf; - } else { - _thr_clip_status = ThrClipStatus::NONE; - } - float THRminf_clipped_to_zero = constrain_float(_THRminf, 0, _THRmaxf); // Calculate integrator state upper and lower limits @@ -705,16 +679,13 @@ void AP_TECS::_update_throttle_with_airspeed(void) // Calculate integrator state, constraining state // Set integrator to a max throttle value during climbout _integTHR_state = _integTHR_state + (_STE_error * _get_i_gain()) * _DT * K_STE2Thr; - if (_flight_stage == AP_Vehicle::FixedWing::FLIGHT_TAKEOFF || _flight_stage == AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND) - { + if (_flight_stage == AP_Vehicle::FixedWing::FLIGHT_TAKEOFF || _flight_stage == AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND) { if (!_flags.reached_speed_takeoff) { // ensure we run at full throttle until we reach the target airspeed _throttle_dem = MAX(_throttle_dem, _THRmaxf - _integTHR_state); } _integTHR_state = integ_max; - } - else - { + } else { _integTHR_state = constrain_float(_integTHR_state, integ_min, integ_max); } @@ -741,13 +712,15 @@ void AP_TECS::_update_throttle_with_airspeed(void) _throttle_dem = _throttle_dem + _integTHR_state; } - // Constrain throttle demand and record clip status + // Constrain throttle demand and record clipping if (_throttle_dem > _THRmaxf) { _thr_clip_status = ThrClipStatus::MAX; _throttle_dem = _THRmaxf; } else if (_throttle_dem < _THRminf) { _thr_clip_status = ThrClipStatus::MIN; _throttle_dem = _THRminf; + } else { + _thr_clip_status = ThrClipStatus::NONE; } } @@ -781,21 +754,15 @@ void AP_TECS::_update_throttle_without_airspeed(int16_t throttle_nudge) nomThr = (aparm.throttle_cruise + throttle_nudge)* 0.01f; } - if (_pitch_dem > 0.0f && _PITCHmaxf > 0.0f) - { + if (_pitch_dem > 0.0f && _PITCHmaxf > 0.0f) { _throttle_dem = nomThr + (_THRmaxf - nomThr) * _pitch_dem / _PITCHmaxf; - } - else if (_pitch_dem < 0.0f && _PITCHminf < 0.0f) - { + } else if (_pitch_dem < 0.0f && _PITCHminf < 0.0f) { _throttle_dem = nomThr + (_THRminf - nomThr) * _pitch_dem / _PITCHminf; - } - else - { + } else { _throttle_dem = nomThr; } - if (_flags.is_gliding) - { + if (_flags.is_gliding) { _throttle_dem = 0.0f; return; } @@ -806,14 +773,14 @@ void AP_TECS::_update_throttle_without_airspeed(int16_t throttle_nudge) // additional component which scales with (1/cos(bank angle) - 1) to compensate for induced // drag increase during turns. float cosPhi = sqrtf((rotMat.a.y*rotMat.a.y) + (rotMat.b.y*rotMat.b.y)); - float STEdot_dem = _rollComp * (1.0f/constrain_float(cosPhi * cosPhi , 0.1f, 1.0f) - 1.0f); + float STEdot_dem = _rollComp * (1.0f/constrain_float(cosPhi * cosPhi, 0.1f, 1.0f) - 1.0f); _throttle_dem = _throttle_dem + STEdot_dem / (_STEdot_max - _STEdot_min) * (_THRmaxf - _THRminf); } void AP_TECS::_detect_bad_descent(void) { // Detect a demanded airspeed too high for the aircraft to achieve. This will be - // evident by the the following conditions: + // evident by the following conditions: // 1) Underspeed protection not active // 2) Specific total energy error > 200 (greater than ~20m height error) // 3) Specific total energy reducing @@ -825,12 +792,9 @@ void AP_TECS::_detect_bad_descent(void) // 2) Specific total energy error > 0 // This mode will produce an undulating speed and height response as it cuts in and out but will prevent the aircraft from descending into the ground if an unachievable speed demand is set float STEdot = _SPEdot + _SKEdot; - if (((!_flags.underspeed && (_STE_error > 200.0f) && (STEdot < 0.0f) && (_throttle_dem >= _THRmaxf * 0.9f)) || (_flags.badDescent && !_flags.underspeed && (_STE_error > 0.0f))) && !_flags.is_gliding) - { + if (((!_flags.underspeed && (_STE_error > 200.0f) && (STEdot < 0.0f) && (_throttle_dem >= _THRmaxf * 0.9f)) || (_flags.badDescent && !_flags.underspeed && (_STE_error > 0.0f))) && !_flags.is_gliding) { _flags.badDescent = true; - } - else - { + } else { _flags.badDescent = false; } } @@ -851,7 +815,7 @@ void AP_TECS::_update_pitch(void) // speed. Speed is also taken care of independently of // height. This is needed as the usual relationship of speed // and height is broken by the VTOL motors - SKE_weighting = 0.0f; + SKE_weighting = 0.0f; } else if ( _flags.underspeed || _flight_stage == AP_Vehicle::FixedWing::FLIGHT_TAKEOFF || _flight_stage == AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND || _flags.is_gliding) { SKE_weighting = 2.0f; } else if (_flags.is_doing_auto_land) { @@ -865,7 +829,7 @@ void AP_TECS::_update_pitch(void) } logging.SKE_weighting = SKE_weighting; - + float SPE_weighting = 2.0f - SKE_weighting; // Calculate Specific Energy Balance demand, and error @@ -876,15 +840,12 @@ void AP_TECS::_update_pitch(void) logging.SKE_error = _SKE_dem - _SKE_est; logging.SPE_error = _SPE_dem - _SPE_est; - + // Calculate integrator state, constraining input if pitch limits are exceeded float integSEB_input = SEB_error * _get_i_gain(); - if (_pitch_dem > _PITCHmaxf) - { + if (_pitch_dem > _PITCHmaxf) { integSEB_input = MIN(integSEB_input, _PITCHmaxf - _pitch_dem); - } - else if (_pitch_dem < _PITCHminf) - { + } else if (_pitch_dem < _PITCHminf) { integSEB_input = MAX(integSEB_input, _PITCHminf - _pitch_dem); } float integSEB_delta = integSEB_input * _DT; @@ -924,7 +885,7 @@ void AP_TECS::_update_pitch(void) float integSEB_range = integSEB_max - integSEB_min; logging.SEB_delta = integSEB_delta; - + // don't allow the integrator to rise by more than 20% of its full // range in one step. This prevents single value glitches from // causing massive integrator changes. See Issue#4066 @@ -958,12 +919,9 @@ void AP_TECS::_update_pitch(void) // acceleration limit float ptchRateIncr = _DT * _vertAccLim / _TAS_state; - if ((_pitch_dem - _last_pitch_dem) > ptchRateIncr) - { + if ((_pitch_dem - _last_pitch_dem) > ptchRateIncr) { _pitch_dem = _last_pitch_dem + ptchRateIncr; - } - else if ((_pitch_dem - _last_pitch_dem) < -ptchRateIncr) - { + } else if ((_pitch_dem - _last_pitch_dem) < -ptchRateIncr) { _pitch_dem = _last_pitch_dem - ptchRateIncr; } @@ -976,8 +934,7 @@ void AP_TECS::_update_pitch(void) void AP_TECS::_initialise_states(int32_t ptchMinCO_cd, float hgt_afe) { // Initialise states and variables if DT > 1 second or in climbout - if (_DT > 1.0f || _need_reset) - { + if (_DT > 1.0f || _need_reset) { _integTHR_state = 0.0f; _integSEB_state = 0.0f; _last_throttle_dem = aparm.throttle_cruise * 0.01f; @@ -993,9 +950,7 @@ void AP_TECS::_initialise_states(int32_t ptchMinCO_cd, float hgt_afe) _DT = 0.1f; // when first starting TECS, use a // small time constant _need_reset = false; - } - else if (_flight_stage == AP_Vehicle::FixedWing::FLIGHT_TAKEOFF || _flight_stage == AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND) - { + } else if (_flight_stage == AP_Vehicle::FixedWing::FLIGHT_TAKEOFF || _flight_stage == AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND) { _PITCHminf = 0.000174533f * ptchMinCO_cd; _hgt_dem_adj_last = hgt_afe; _hgt_dem_adj = _hgt_dem_adj_last; @@ -1004,10 +959,10 @@ void AP_TECS::_initialise_states(int32_t ptchMinCO_cd, float hgt_afe) _flags.underspeed = false; _flags.badDescent = false; } - + if (_flight_stage != AP_Vehicle::FixedWing::FLIGHT_TAKEOFF && _flight_stage != AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND) { // reset takeoff speed flag when not in takeoff - _flags.reached_speed_takeoff = false; + _flags.reached_speed_takeoff = false; } } @@ -1047,7 +1002,7 @@ void AP_TECS::update_pitch_throttle(int32_t hgt_dem_cm, _update_speed(load_factor); if (aparm.takeoff_throttle_max != 0 && - (_flight_stage == AP_Vehicle::FixedWing::FLIGHT_TAKEOFF || _flight_stage == AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND)) { + (_flight_stage == AP_Vehicle::FixedWing::FLIGHT_TAKEOFF || _flight_stage == AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND)) { _THRmaxf = aparm.takeoff_throttle_max * 0.01f; } else { _THRmaxf = aparm.throttle_max * 0.01f; @@ -1084,7 +1039,7 @@ void AP_TECS::update_pitch_throttle(int32_t hgt_dem_cm, // reset land pitch min when not landing _land_pitch_min = _PITCHminf; } - + if (_landing.is_flaring()) { // in flare use min pitch from LAND_PITCH_CD _PITCHminf = MAX(_PITCHminf, _landing.get_pitch_cd() * 0.01f); @@ -1147,7 +1102,7 @@ void AP_TECS::update_pitch_throttle(int32_t hgt_dem_cm, _flags.reached_speed_takeoff = true; } } - + // convert to radians _PITCHmaxf = radians(_PITCHmaxf); _PITCHminf = radians(_PITCHminf); @@ -1189,78 +1144,80 @@ void AP_TECS::update_pitch_throttle(int32_t hgt_dem_cm, _detect_bad_descent(); if (_options & OPTION_GLIDER_ONLY) { - _flags.badDescent = false; + _flags.badDescent = false; } // Calculate pitch demand _update_pitch(); - // log to AP_Logger - // @LoggerMessage: TECS - // @Vehicles: Plane - // @Description: Information about the Total Energy Control System - // @URL: http://ardupilot.org/plane/docs/tecs-total-energy-control-system-for-speed-height-tuning-guide.html - // @Field: TimeUS: Time since system startup - // @Field: h: height estimate (UP) currently in use by TECS - // @Field: dh: current climb rate ("delta-height") - // @Field: hdem: height TECS is currently trying to achieve - // @Field: dhdem: climb rate TECS is currently trying to achieve - // @Field: spdem: True AirSpeed TECS is currently trying to achieve - // @Field: sp: current estimated True AirSpeed - // @Field: dsp: x-axis acceleration estimate ("delta-speed") - // @Field: ith: throttle integrator value - // @Field: iph: Specific Energy Balance integrator value - // @Field: th: throttle output - // @Field: ph: pitch output - // @Field: dspdem: demanded acceleration output ("delta-speed demand") - // @Field: w: current TECS prioritization of height vs speed (0==100% height,2==100% speed, 1==50%height+50%speed - // @Field: f: flags - // @FieldBits: f: Underspeed,UnachievableDescent,AutoLanding,ReachedTakeoffSpd - AP::logger().WriteStreaming( - "TECS", - "TimeUS,h,dh,hdem,dhdem,spdem,sp,dsp,ith,iph,th,ph,dspdem,w,f", - "smnmnnnn----o--", - "F0000000----0--", - "QfffffffffffffB", - now, - (double)_height, - (double)_climb_rate, - (double)_hgt_dem_adj, - (double)_hgt_rate_dem, - (double)_TAS_dem_adj, - (double)_TAS_state, - (double)_vel_dot, - (double)_integTHR_state, - (double)_integSEB_state, - (double)_throttle_dem, - (double)_pitch_dem, - (double)_TAS_rate_dem, - (double)logging.SKE_weighting, - _flags_byte); - // @LoggerMessage: TEC2 - // @Vehicles: Plane - // @Description: Additional Information about the Total Energy Control System - // @URL: http://ardupilot.org/plane/docs/tecs-total-energy-control-system-for-speed-height-tuning-guide.html - // @Field: TimeUS: Time since system startup - // @Field: pmax: maximum allowed pitch from parameter - // @Field: pmin: minimum allowed pitch from parameter - // @Field: KErr: difference between estimated kinetic energy and desired kinetic energy - // @Field: PErr: difference between estimated potential energy and desired potential energy - // @Field: EDelta: current error in speed/balance weighting - // @Field: LF: aerodynamic load factor - // @Field: hdem1: demanded height input - // @Field: hdem2: rate-limited height demand - AP::logger().WriteStreaming("TEC2", "TimeUS,pmax,pmin,KErr,PErr,EDelta,LF,hdem1,hdem2", - "s------mm", - "F--------", - "Qffffffff", - now, - (double)degrees(_PITCHmaxf), - (double)degrees(_PITCHminf), - (double)logging.SKE_error, - (double)logging.SPE_error, - (double)logging.SEB_delta, - (double)load_factor, - (double)hgt_dem_cm*0.01, - (double)_hgt_dem); + if (AP::logger().should_log(_log_bitmask)){ + // log to AP_Logger + // @LoggerMessage: TECS + // @Vehicles: Plane + // @Description: Information about the Total Energy Control System + // @URL: http://ardupilot.org/plane/docs/tecs-total-energy-control-system-for-speed-height-tuning-guide.html + // @Field: TimeUS: Time since system startup + // @Field: h: height estimate (UP) currently in use by TECS + // @Field: dh: current climb rate ("delta-height") + // @Field: hdem: height TECS is currently trying to achieve + // @Field: dhdem: climb rate TECS is currently trying to achieve + // @Field: spdem: True AirSpeed TECS is currently trying to achieve + // @Field: sp: current estimated True AirSpeed + // @Field: dsp: x-axis acceleration estimate ("delta-speed") + // @Field: ith: throttle integrator value + // @Field: iph: Specific Energy Balance integrator value + // @Field: th: throttle output + // @Field: ph: pitch output + // @Field: dspdem: demanded acceleration output ("delta-speed demand") + // @Field: w: current TECS prioritization of height vs speed (0==100% height,2==100% speed, 1==50%height+50%speed + // @Field: f: flags + // @FieldBits: f: Underspeed,UnachievableDescent,AutoLanding,ReachedTakeoffSpd + AP::logger().WriteStreaming( + "TECS", + "TimeUS,h,dh,hdem,dhdem,spdem,sp,dsp,ith,iph,th,ph,dspdem,w,f", + "smnmnnnn----o--", + "F0000000----0--", + "QfffffffffffffB", + now, + (double)_height, + (double)_climb_rate, + (double)_hgt_dem_adj, + (double)_hgt_rate_dem, + (double)_TAS_dem_adj, + (double)_TAS_state, + (double)_vel_dot, + (double)_integTHR_state, + (double)_integSEB_state, + (double)_throttle_dem, + (double)_pitch_dem, + (double)_TAS_rate_dem, + (double)logging.SKE_weighting, + _flags_byte); + // @LoggerMessage: TEC2 + // @Vehicles: Plane + // @Description: Additional Information about the Total Energy Control System + // @URL: http://ardupilot.org/plane/docs/tecs-total-energy-control-system-for-speed-height-tuning-guide.html + // @Field: TimeUS: Time since system startup + // @Field: pmax: maximum allowed pitch from parameter + // @Field: pmin: minimum allowed pitch from parameter + // @Field: KErr: difference between estimated kinetic energy and desired kinetic energy + // @Field: PErr: difference between estimated potential energy and desired potential energy + // @Field: EDelta: current error in speed/balance weighting + // @Field: LF: aerodynamic load factor + // @Field: hdem1: demanded height input + // @Field: hdem2: rate-limited height demand + AP::logger().WriteStreaming("TEC2", "TimeUS,pmax,pmin,KErr,PErr,EDelta,LF,hdem1,hdem2", + "s------mm", + "F--------", + "Qffffffff", + now, + (double)degrees(_PITCHmaxf), + (double)degrees(_PITCHminf), + (double)logging.SKE_error, + (double)logging.SPE_error, + (double)logging.SEB_delta, + (double)load_factor, + (double)hgt_dem_cm*0.01, + (double)_hgt_dem); + } } diff --git a/libraries/AP_TECS/AP_TECS.h b/libraries/AP_TECS/AP_TECS.h index e47122c9d02..7b624922315 100644 --- a/libraries/AP_TECS/AP_TECS.h +++ b/libraries/AP_TECS/AP_TECS.h @@ -21,14 +21,16 @@ #include #include #include +#include class AP_Landing; class AP_TECS { public: - AP_TECS(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms, const AP_Landing &landing) + AP_TECS(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms, const AP_Landing &landing, const uint32_t log_bitmask) : _ahrs(ahrs) , aparm(parms) , _landing(landing) + , _log_bitmask(log_bitmask) { AP_Param::setup_object_defaults(this, var_info); } @@ -160,7 +162,10 @@ class AP_TECS { // reference to const AP_Landing to access it's params const AP_Landing &_landing; - + + // Logging bitmask + const uint32_t _log_bitmask; + // TECS tuning parameters AP_Float _hgtCompFiltOmega; AP_Float _spdCompFiltOmega; diff --git a/libraries/AP_Terrain/AP_Terrain.cpp b/libraries/AP_Terrain/AP_Terrain.cpp index 3f2cf781666..2c50a825ebb 100644 --- a/libraries/AP_Terrain/AP_Terrain.cpp +++ b/libraries/AP_Terrain/AP_Terrain.cpp @@ -67,6 +67,14 @@ const AP_Param::GroupInfo AP_Terrain::var_info[] = { // @Range: 0.05 50000 // @User: Advanced AP_GROUPINFO("MARGIN", 3, AP_Terrain, margin, 0.05), + + // @Param: OFS_MAX + // @DisplayName: Terrain reference offset maximum + // @Description: The maximum adjustment of terrain altitude based on the assumption that the vehicle is on the ground when it is armed. When the vehicle is armed the location of the vehicle is recorded, and when terrain data is available for that location a height adjustment for terrain data is calculated that aligns the terrain height at that location with the altitude recorded at arming. This height adjustment is applied to all terrain data. This parameter clamps the amount of adjustment. A value of zero disables the use of terrain height adjustment. + // @Units: m + // @Range: 0 50 + // @User: Advanced + AP_GROUPINFO("OFS_MAX", 4, AP_Terrain, offset_max, 15), AP_GROUPEND }; @@ -107,9 +115,8 @@ bool AP_Terrain::height_amsl(const Location &loc, float &height, bool corrected) if (loc.lat == home_loc.lat && loc.lng == home_loc.lng) { height = home_height; - // apply correction which assumes home altitude is at terrain altitude - if (corrected) { - height += (ahrs.get_home().alt * 0.01f) - home_height; + if (corrected && have_reference_offset) { + height += reference_offset; } return true; } @@ -159,13 +166,13 @@ bool AP_Terrain::height_amsl(const Location &loc, float &height, bool corrected) // remember home altitude as a special case home_height = height; home_loc = loc; + have_home_height = true; } - // apply correction which assumes home altitude is at terrain altitude - if (corrected) { - height += (ahrs.get_home().alt * 0.01f) - home_height; + if (corrected && have_reference_offset) { + height += reference_offset; } - + return true; } @@ -186,7 +193,7 @@ bool AP_Terrain::height_terrain_difference_home(float &terrain_difference, bool const AP_AHRS &ahrs = AP::ahrs(); float height_home, height_loc; - if (!height_amsl(ahrs.get_home(), height_home, false)) { + if (!height_amsl(ahrs.get_home(), height_home)) { // we don't know the height of home return false; } @@ -197,7 +204,7 @@ bool AP_Terrain::height_terrain_difference_home(float &terrain_difference, bool return false; } - if (!height_amsl(loc, height_loc, false)) { + if (!height_amsl(loc, height_loc)) { if (!extrapolate || !have_current_loc_height) { // we don't know the height of the given location return false; @@ -283,7 +290,7 @@ float AP_Terrain::lookahead(float bearing, float distance, float climb_ratio) return 0; } float base_height; - if (!height_amsl(loc, base_height, false)) { + if (!height_amsl(loc, base_height)) { // we don't know our current terrain height return 0; } @@ -297,7 +304,7 @@ float AP_Terrain::lookahead(float bearing, float distance, float climb_ratio) climb += climb_ratio * grid_spacing; distance -= grid_spacing; float height; - if (height_amsl(loc, height, false)) { + if (height_amsl(loc, height)) { float rise = (height - base_height) - climb; if (rise > lookahead_estimate) { lookahead_estimate = rise; @@ -324,12 +331,12 @@ void AP_Terrain::update(void) // try to ensure the home location is populated float height; - height_amsl(ahrs.get_home(), height, false); + height_amsl(ahrs.get_home(), height); // update the cached current location height Location loc; bool pos_valid = ahrs.get_location(loc); - bool terrain_valid = pos_valid && height_amsl(loc, height, false); + bool terrain_valid = pos_valid && height_amsl(loc, height); if (pos_valid && terrain_valid) { last_current_loc_height = height; have_current_loc_height = true; @@ -341,6 +348,13 @@ void AP_Terrain::update(void) // check for pending rally data update_rally_data(); + // update tiles surrounding our current location: + if (pos_valid) { + have_surrounding_tiles = update_surrounding_tiles(loc); + } else { + have_surrounding_tiles = false; + } + // update capabilities and status if (allocate()) { if (!pos_valid) { @@ -355,7 +369,41 @@ void AP_Terrain::update(void) } else { system_status = TerrainStatusDisabled; } +} +bool AP_Terrain::update_surrounding_tiles(const Location &loc) +{ + // also request a larger set of up to 9 grids + bool ret = true; + for (int8_t x=-1; x<=1; x++) { + for (int8_t y=-1; y<=1; y++) { + Location loc2 = loc; + loc2.offset(x*TERRAIN_GRID_BLOCK_SIZE_X*0.7f*grid_spacing, + y*TERRAIN_GRID_BLOCK_SIZE_Y*0.7f*grid_spacing); + float height; + if (!height_amsl(loc2, height)) { + ret = false; + } + } + } + return ret; +} + +bool AP_Terrain::pre_arm_checks(char *failure_msg, uint8_t failure_msg_len) const +{ + // check no outstanding requests for data: + uint16_t terr_pending, terr_loaded; + get_statistics(terr_pending, terr_loaded); + if (terr_pending != 0 || + !have_current_loc_height || + !have_home_height || + next_mission_index != 0 || + next_rally_index != 0) { + hal.util->snprintf(failure_msg, failure_msg_len, "waiting for terrain data"); + return false; + } + + return true; } void AP_Terrain::log_terrain_data() @@ -372,7 +420,7 @@ void AP_Terrain::log_terrain_data() float current_height = 0; uint16_t pending, loaded; - height_amsl(loc, terrain_height, false); + height_amsl(loc, terrain_height); height_above_terrain(current_height, true); get_statistics(pending, loaded); @@ -386,7 +434,8 @@ void AP_Terrain::log_terrain_data() terrain_height : terrain_height, current_height : current_height, pending : pending, - loaded : loaded + loaded : loaded, + reference_offset : have_reference_offset?reference_offset:0, }; AP::logger().WriteBlock(&pkt, sizeof(pkt)); } @@ -413,6 +462,78 @@ bool AP_Terrain::allocate(void) return true; } +/* + setup a reference location for terrain adjustment. This should + be called when the vehicle is definately on the ground +*/ +void AP_Terrain::set_reference_location(void) +{ + const auto &ahrs = AP::ahrs(); + + // check we have absolute position + nav_filter_status status; + if (!ahrs.get_filter_status(status) || + !status.flags.vert_pos || + !status.flags.horiz_pos_abs || + !status.flags.attitude) { + return; + } + + // check we have a small 3D velocity + Vector3f vel; + if (!ahrs.get_velocity_NED(vel) || + vel.length() > 3) { + return; + } + + have_reference_offset = false; + have_reference_loc = ahrs.get_location(reference_loc); + + update_reference_offset(); +} + +/* + get the offset between terrain height and reference alt at the + reference location + */ +void AP_Terrain::update_reference_offset(void) +{ + // TERR_OFS_MAX of zero means no adjustment + if (!is_positive(offset_max)) { + have_reference_offset = false; + return; + } + + // allow for change to TERRAIN_OFS_MAX while flying + if (have_reference_offset) { + reference_offset = constrain_float(reference_offset, -offset_max, offset_max); + return; + } + + if (!have_reference_loc) { + // no reference available yet + return; + } + + // calculate adjustment + float height; + if (!height_amsl(reference_loc, height)) { + return; + } + int32_t alt_cm; + if (!reference_loc.get_alt_cm(Location::AltFrame::ABSOLUTE, alt_cm)) { + return; + } + float adjustment = alt_cm*0.01 - height; + reference_offset = constrain_float(adjustment, -offset_max, offset_max); + if (fabsf(adjustment) > offset_max.get()+0.5) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Terrain: clamping offset %.0f to %.0f", + adjustment, reference_offset); + } + have_reference_offset = true; +} + + namespace AP { AP_Terrain *terrain() diff --git a/libraries/AP_Terrain/AP_Terrain.h b/libraries/AP_Terrain/AP_Terrain.h index aeac19c4bc8..2ef374a94a7 100644 --- a/libraries/AP_Terrain/AP_Terrain.h +++ b/libraries/AP_Terrain/AP_Terrain.h @@ -15,7 +15,7 @@ #pragma once #include -#include +#include #include #include #include @@ -102,11 +102,13 @@ class AP_Terrain { void update(void); bool enabled() const { return enable; } - void set_enabled(bool _enable) { enable = _enable; } + void set_enabled(bool _enable) { enable.set(_enable); } // return status enum for health reporting enum TerrainStatus status(void) const { return system_status; } + bool pre_arm_checks(char *failure_msg, uint8_t failure_msg_len) const; + // send any pending terrain request message bool send_cache_request(mavlink_channel_t chan); void send_request(mavlink_channel_t chan); @@ -121,12 +123,8 @@ class AP_Terrain { find the terrain height in meters above sea level for a location return false if not available - - if corrected is true then terrain alt is adjusted so that - the terrain altitude matches the home altitude at the home location - (i.e. we assume home is at the terrain altitude) */ - bool height_amsl(const Location &loc, float &height, bool corrected); + bool height_amsl(const Location &loc, float &height, bool corrected = true); /* find difference between home terrain height and the terrain @@ -193,6 +191,12 @@ class AP_Terrain { */ bool init_failed() const { return memory_alloc_failed; } + /* + setup a reference location for terrain adjustment. This should + be called when the vehicle is definately on the ground + */ + void set_reference_location(void); + private: // allocate the terrain subsystem data bool allocate(void); @@ -338,6 +342,9 @@ class AP_Terrain { void write_block(void); void read_block(void); + // check for missing data in squares surrounding loc: + bool update_surrounding_tiles(const Location &loc); + /* check for missing mission terrain data */ @@ -348,12 +355,18 @@ class AP_Terrain { */ void update_rally_data(void); + /* + calculate reference offset if needed + */ + void update_reference_offset(void); + // parameters AP_Int8 enable; AP_Float margin; AP_Int16 grid_spacing; // meters between grid points AP_Int16 options; // option bits + AP_Float offset_max; enum class Options { DisableDownload = (1U<<0), @@ -399,6 +412,16 @@ class AP_Terrain { // cache the home altitude, as it is needed so often float home_height; Location home_loc; + bool have_home_height; + + // reference position for terrain adjustment, set at arming + bool have_reference_loc; + Location reference_loc; + + // calculated reference offset + bool have_reference_offset; + float reference_offset; + // cache the last terrain height (AMSL) of the AHRS current // location. This is used for extrapolation when terrain data is @@ -406,6 +429,10 @@ class AP_Terrain { bool have_current_loc_height; float last_current_loc_height; + // true if we have all of the data for the squares around the + // current location: + bool have_surrounding_tiles; + // next mission command to check uint16_t next_mission_index; diff --git a/libraries/AP_Terrain/TerrainGCS.cpp b/libraries/AP_Terrain/TerrainGCS.cpp index 17621f1a72d..340b2a7a5b3 100644 --- a/libraries/AP_Terrain/TerrainGCS.cpp +++ b/libraries/AP_Terrain/TerrainGCS.cpp @@ -139,21 +139,10 @@ void AP_Terrain::send_request(mavlink_channel_t chan) return; } - // also request a larger set of up to 9 grids - for (int8_t x=-1; x<=1; x++) { - for (int8_t y=-1; y<=1; y++) { - Location loc2 = loc; - loc2.offset(x*TERRAIN_GRID_BLOCK_SIZE_X*0.7f*grid_spacing, - y*TERRAIN_GRID_BLOCK_SIZE_Y*0.7f*grid_spacing); - struct grid_info info2; - calculate_grid_info(loc2, info2); - if (request_missing(chan, info2)) { - return; - } - } - } - - // check cache blocks that may have been setup by a TERRAIN_CHECK + // check cache blocks that may have been setup by a TERRAIN_CHECK, + // mission items, rally items, squares surrounding our current + // location, favourite holiday destination, scripting, height + // reference location, .... if (send_cache_request(chan)) { return; } @@ -228,8 +217,8 @@ void AP_Terrain::send_terrain_report(mavlink_channel_t chan, const Location &loc Location current_loc; const AP_AHRS &ahrs = AP::ahrs(); if (ahrs.get_location(current_loc) && - height_amsl(ahrs.get_home(), home_terrain_height, false) && - height_amsl(loc, terrain_height, false)) { + height_amsl(ahrs.get_home(), home_terrain_height) && + height_amsl(loc, terrain_height)) { // non-zero spacing indicates we have data spacing = grid_spacing; } else if (extrapolate && have_current_loc_height) { @@ -238,7 +227,7 @@ void AP_Terrain::send_terrain_report(mavlink_channel_t chan, const Location &loc terrain_height = last_current_loc_height; } else { // report terrain height if we can, but can't give current_height - height_amsl(loc, terrain_height, false); + height_amsl(loc, terrain_height); } uint16_t pending, loaded; get_statistics(pending, loaded); diff --git a/libraries/AP_Terrain/TerrainIO.cpp b/libraries/AP_Terrain/TerrainIO.cpp index 65098d81d8a..950230b235d 100644 --- a/libraries/AP_Terrain/TerrainIO.cpp +++ b/libraries/AP_Terrain/TerrainIO.cpp @@ -351,6 +351,8 @@ void AP_Terrain::io_timer(void) return; } + update_reference_offset(); + switch (disk_io_state) { case DiskIoIdle: case DiskIoDoneRead: diff --git a/libraries/AP_Terrain/TerrainMission.cpp b/libraries/AP_Terrain/TerrainMission.cpp index ab6b8b79cea..381bc6bc55e 100644 --- a/libraries/AP_Terrain/TerrainMission.cpp +++ b/libraries/AP_Terrain/TerrainMission.cpp @@ -35,7 +35,7 @@ extern const AP_HAL::HAL& hal; */ void AP_Terrain::update_mission_data(void) { -#if HAL_MISSION_ENABLED +#if AP_MISSION_ENABLED const AP_Mission *mission = AP::mission(); if (mission == nullptr) { return; @@ -95,7 +95,7 @@ void AP_Terrain::update_mission_data(void) // we have a mission command to check float height; - if (!height_amsl(cmd.content.location, height, false)) { + if (!height_amsl(cmd.content.location, height)) { // if we can't get data for a mission item then return and // check again next time return; @@ -112,7 +112,7 @@ void AP_Terrain::update_mission_data(void) next_mission_pos = 0; } } -#endif // HAL_MISSION_ENABLED +#endif // AP_MISSION_ENABLED } /* @@ -157,7 +157,7 @@ void AP_Terrain::update_rally_data(void) loc.lat = rp.lat; loc.lng = rp.lng; float height; - if (!height_amsl(loc, height, false)) { + if (!height_amsl(loc, height)) { // if we can't get data for a rally item then return and // check again next time return; diff --git a/libraries/AP_Torqeedo/AP_Torqeedo.cpp b/libraries/AP_Torqeedo/AP_Torqeedo.cpp index 19da31067a4..84b0856595e 100644 --- a/libraries/AP_Torqeedo/AP_Torqeedo.cpp +++ b/libraries/AP_Torqeedo/AP_Torqeedo.cpp @@ -283,7 +283,7 @@ bool AP_Torqeedo::pre_arm_checks(char *failure_msg, uint8_t failure_msg_len) return true; } -// returns a human-readable string corresponding the the passed-in +// returns a human-readable string corresponding the passed-in // master error code (see page 93 of https://media.torqeedo.com/downloads/manuals/torqeedo-Travel-manual-DE-EN.pdf) // If no conversion is available then nullptr is returned const char * AP_Torqeedo::map_master_error_code_to_string(uint8_t code) const @@ -1031,7 +1031,7 @@ int16_t AP_Torqeedo::calc_motor_speed_limited(int16_t desired_motor_speed) } // calculate dt since last update - float dt = (now_ms - _motor_speed_limited_ms) / 1000.0f; + float dt = (now_ms - _motor_speed_limited_ms) * 0.001f; if (dt > 1.0) { // after a long delay limit motor output to zero to avoid sudden starts lower_limit = 0; diff --git a/libraries/AP_Torqeedo/AP_Torqeedo.h b/libraries/AP_Torqeedo/AP_Torqeedo.h index 2fa21ddf04b..e17de5f5fe6 100644 --- a/libraries/AP_Torqeedo/AP_Torqeedo.h +++ b/libraries/AP_Torqeedo/AP_Torqeedo.h @@ -360,7 +360,7 @@ class AP_Torqeedo : public AP_ESC_Telem_Backend { MotorStatus _motor_status_prev; // backup of motor status static AP_Torqeedo *_singleton; - // returns a human-readable string corresponding the the passed-in + // returns a human-readable string corresponding the passed-in // master error code (see page 93 of https://media.torqeedo.com/downloads/manuals/torqeedo-Travel-manual-DE-EN.pdf) // If no conversion is available then nullptr is returned const char *map_master_error_code_to_string(uint8_t code) const; diff --git a/libraries/AP_ToshibaCAN/AP_ToshibaCAN.cpp b/libraries/AP_ToshibaCAN/AP_ToshibaCAN.cpp deleted file mode 100644 index c31111c1bc5..00000000000 --- a/libraries/AP_ToshibaCAN/AP_ToshibaCAN.cpp +++ /dev/null @@ -1,497 +0,0 @@ -/* - This program is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - This program is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with this program. If not, see . - */ - -#include - -#if HAL_MAX_CAN_PROTOCOL_DRIVERS - -#include -#include -#include -#include -#include -#include -#include -#include "AP_ToshibaCAN.h" -#include -#include - -extern const AP_HAL::HAL& hal; - -#if HAL_CANMANAGER_ENABLED -#define debug_can(level_debug, fmt, args...) do { AP::can().log_text(level_debug, "ToshibaCAN", fmt, ##args); } while (0) -#else -#define debug_can(level_debug, fmt, args...) -#endif - -// stupid compiler is not able to optimise this under gnu++11 -// move this back when moving to gnu++17 -const uint16_t AP_ToshibaCAN::TOSHIBACAN_SEND_TIMEOUT_US = 500; - -AP_ToshibaCAN::AP_ToshibaCAN() -{ - debug_can(AP_CANManager::LOG_INFO, "ToshibaCAN: constructed\n\r"); - (void)COMMAND_STOP; - (void)MOTOR_DATA5; -} - -AP_ToshibaCAN *AP_ToshibaCAN::get_tcan(uint8_t driver_index) -{ - if (driver_index >= AP::can().get_num_drivers() || - AP::can().get_driver_type(driver_index) != AP_CANManager::Driver_Type_ToshibaCAN) { - return nullptr; - } - return static_cast(AP::can().get_driver(driver_index)); -} - - -bool AP_ToshibaCAN::add_interface(AP_HAL::CANIface* can_iface) { - if (_can_iface != nullptr) { - debug_can(AP_CANManager::LOG_ERROR, "ToshibaCAN: Multiple Interface not supported\n\r"); - return false; - } - - _can_iface = can_iface; - - if (_can_iface == nullptr) { - debug_can(AP_CANManager::LOG_ERROR, "ToshibaCAN: CAN driver not found\n\r"); - return false; - } - - if (!_can_iface->is_initialized()) { - debug_can(AP_CANManager::LOG_ERROR, "ToshibaCAN: Driver not initialized\n\r"); - return false; - } - - if (!_can_iface->set_event_handle(&_event_handle)) { - debug_can(AP_CANManager::LOG_ERROR, "ToshibaCAN: Cannot add event handle\n\r"); - return false; - } - return true; -} - - -// initialise ToshibaCAN bus -void AP_ToshibaCAN::init(uint8_t driver_index, bool enable_filters) -{ - _driver_index = driver_index; - - debug_can(AP_CANManager::LOG_DEBUG, "ToshibaCAN: starting init\n\r"); - - if (_initialized) { - debug_can(AP_CANManager::LOG_ERROR, "ToshibaCAN: already initialized\n\r"); - return; - } - - if (_can_iface == nullptr) { - debug_can(AP_CANManager::LOG_ERROR, "ToshibaCAN: Interface not found\n\r"); - return; - } - - // start calls to loop in separate thread - if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_ToshibaCAN::loop, void), _thread_name, 4096, AP_HAL::Scheduler::PRIORITY_MAIN, 1)) { - debug_can(AP_CANManager::LOG_ERROR, "ToshibaCAN: couldn't create thread\n\r"); - return; - } - - _initialized = true; - - debug_can(AP_CANManager::LOG_DEBUG, "ToshibaCAN: init done\n\r"); - - return; -} - -// loop to send output to ESCs in background thread -void AP_ToshibaCAN::loop() -{ - uint64_t timeout = 0; - const uint32_t timeout_us = MIN(AP::scheduler().get_loop_period_us(), TOSHIBACAN_SEND_TIMEOUT_US); - - while (true) { - if (!_initialized) { - // if not initialised wait 2ms - debug_can(AP_CANManager::LOG_DEBUG, "ToshibaCAN: not initialized\n\r"); - hal.scheduler->delay_microseconds(2000); - continue; - } - - // check for updates - if (update_count == update_count_sent) { - hal.scheduler->delay_microseconds(50); - continue; - } - - // prepare commands and frames - if (send_stage == 0) { - motor_lock_cmd_t unlock_cmd = {}; - motor_rotation_cmd_t mot_rot_cmd1; - motor_rotation_cmd_t mot_rot_cmd2; - motor_rotation_cmd_t mot_rot_cmd3; - { - // take semaphore to read scaled motor outputs - WITH_SEMAPHORE(_rc_out_sem); - - // prepare command to lock or unlock motors - unlock_cmd.motor1 = (_scaled_output[0] == 0) ? 2 : 1; - unlock_cmd.motor2 = (_scaled_output[1] == 0) ? 2 : 1; - unlock_cmd.motor3 = (_scaled_output[2] == 0) ? 2 : 1; - unlock_cmd.motor4 = (_scaled_output[3] == 0) ? 2 : 1; - unlock_cmd.motor5 = (_scaled_output[4] == 0) ? 2 : 1; - unlock_cmd.motor6 = (_scaled_output[5] == 0) ? 2 : 1; - unlock_cmd.motor7 = (_scaled_output[6] == 0) ? 2 : 1; - unlock_cmd.motor8 = (_scaled_output[7] == 0) ? 2 : 1; - unlock_cmd.motor9 = (_scaled_output[8] == 0) ? 2 : 1; - unlock_cmd.motor10 = (_scaled_output[9] == 0) ? 2 : 1; - unlock_cmd.motor11 = (_scaled_output[10] == 0) ? 2 : 1; - unlock_cmd.motor12 = (_scaled_output[11] == 0) ? 2 : 1; - - // prepare command to spin motors in bank1 - mot_rot_cmd1.motor1 = htobe16(_scaled_output[0]); - mot_rot_cmd1.motor2 = htobe16(_scaled_output[1]); - mot_rot_cmd1.motor3 = htobe16(_scaled_output[2]); - mot_rot_cmd1.motor4 = htobe16(_scaled_output[3]); - - // prepare message to spin motors in bank2 - mot_rot_cmd2.motor1 = htobe16(_scaled_output[4]); - mot_rot_cmd2.motor2 = htobe16(_scaled_output[5]); - mot_rot_cmd2.motor3 = htobe16(_scaled_output[6]); - mot_rot_cmd2.motor4 = htobe16(_scaled_output[7]); - - // prepare message to spin motors in bank3 - mot_rot_cmd3.motor1 = htobe16(_scaled_output[8]); - mot_rot_cmd3.motor2 = htobe16(_scaled_output[9]); - mot_rot_cmd3.motor3 = htobe16(_scaled_output[10]); - mot_rot_cmd3.motor4 = htobe16(_scaled_output[11]); - - // copy update time - update_count_buffered = update_count; - } - unlock_frame = {(uint8_t)COMMAND_LOCK, unlock_cmd.data, sizeof(unlock_cmd.data)}; - mot_rot_frame1 = {((uint8_t)COMMAND_MOTOR1 & AP_HAL::CANFrame::MaskStdID), mot_rot_cmd1.data, sizeof(mot_rot_cmd1.data)}; - mot_rot_frame2 = {((uint8_t)COMMAND_MOTOR2 & AP_HAL::CANFrame::MaskStdID), mot_rot_cmd2.data, sizeof(mot_rot_cmd2.data)}; - mot_rot_frame3 = {((uint8_t)COMMAND_MOTOR3 & AP_HAL::CANFrame::MaskStdID), mot_rot_cmd3.data, sizeof(mot_rot_cmd3.data)}; - - // advance to next stage - send_stage++; - } - - // send unlock command - if (send_stage == 1) { - timeout = AP_HAL::native_micros64() + timeout_us; - if (!write_frame(unlock_frame, timeout)) { - continue; - } - send_stage++; - } - - // send output to motor bank3 - if (send_stage == 2) { - timeout = AP_HAL::native_micros64() + timeout_us; - if (!write_frame(mot_rot_frame3, timeout)) { - continue; - } - send_stage++; - } - - // send output to motor bank2 - if (send_stage == 3) { - timeout = AP_HAL::native_micros64() + timeout_us; - if (!write_frame(mot_rot_frame2, timeout)) { - continue; - } - send_stage++; - } - - // send output to motor bank1 - if (send_stage == 4) { - timeout = AP_HAL::native_micros64() + timeout_us; - if (!write_frame(mot_rot_frame1, timeout)) { - continue; - } - send_stage++; - } - - // check if we should request update from ESCs - if (send_stage == 5) { - uint32_t now_ms = AP_HAL::native_millis(); - uint32_t diff_ms = now_ms - _telemetry_req_ms; - - // check if 100ms has passed since last update request - if (diff_ms >= TOSHIBA_CAN_ESC_UPDATE_MS) { - // set _telem_req_ms to time we ideally should have requested update - if (diff_ms >= 2 * TOSHIBA_CAN_ESC_UPDATE_MS) { - _telemetry_req_ms = now_ms; - } else { - _telemetry_req_ms += TOSHIBA_CAN_ESC_UPDATE_MS; - } - - // prepare command to request data1 (rpm and voltage) from all ESCs - motor_request_data_cmd_t request_data_cmd = get_motor_request_data_cmd(1); - AP_HAL::CANFrame request_data_frame; - request_data_frame = {(uint8_t)COMMAND_REQUEST_DATA, request_data_cmd.data, sizeof(request_data_cmd.data)}; - - // send request data command - timeout = AP_HAL::native_micros64() + timeout_us; - if (!write_frame(request_data_frame, timeout)) { - continue; - } - - // increment count to request temperature and usage - _telemetry_temp_req_counter++; - _telemetry_usage_req_counter++; - } - - send_stage++; - } - - // check if we should request temperature from ESCs - if (send_stage == 6) { - if (_telemetry_temp_req_counter > 10) { - _telemetry_temp_req_counter = 0; - - // prepare command to request data2 (temperature) from all ESCs - motor_request_data_cmd_t request_data_cmd = get_motor_request_data_cmd(2); - AP_HAL::CANFrame request_data_frame; - request_data_frame = {(uint8_t)COMMAND_REQUEST_DATA, request_data_cmd.data, sizeof(request_data_cmd.data)}; - - // send request data command - timeout = AP_HAL::native_micros64() + timeout_us; - if (!write_frame(request_data_frame, timeout)) { - continue; - } - } - - send_stage++; - } - - // check if we should request usage from ESCs - if (send_stage == 7) { - if (_telemetry_usage_req_counter > 100) { - _telemetry_usage_req_counter = 0; - - // prepare command to request data2 (temperature) from all ESCs - motor_request_data_cmd_t request_data_cmd = get_motor_request_data_cmd(3); - AP_HAL::CANFrame request_data_frame; - request_data_frame = {(uint8_t)COMMAND_REQUEST_DATA, request_data_cmd.data, sizeof(request_data_cmd.data)}; - - // send request data command - timeout = AP_HAL::native_micros64() + timeout_us; - if (!write_frame(request_data_frame, timeout)) { - continue; - } - } - send_stage++; - } - - // check for replies from ESCs - if (send_stage == 8) { - AP_HAL::CANFrame recv_frame; - while (read_frame(recv_frame, timeout)) { -#if HAL_WITH_ESC_TELEM - // decode rpm and voltage data - if ((recv_frame.id >= MOTOR_DATA1) && (recv_frame.id <= MOTOR_DATA1 + TOSHIBACAN_MAX_NUM_ESCS)) { - // copy contents to our structure - motor_reply_data1_t reply_data; - memcpy(reply_data.data, recv_frame.data, sizeof(reply_data.data)); - // store response in telemetry array - const uint8_t esc_id = recv_frame.id - MOTOR_DATA1; - if (esc_id < TOSHIBACAN_MAX_NUM_ESCS) { - update_rpm(esc_id, (int16_t)be16toh(reply_data.rpm)); - - // update total current - const uint32_t now_ms = AP_HAL::native_millis(); - const uint32_t diff_ms = now_ms - _telemetry[esc_id].last_update_ms; - TelemetryData t {}; - t.voltage = float(be16toh(reply_data.voltage_mv)) * 0.001f; // millivolts to volts - t.current = MAX((int16_t)be16toh(reply_data.current_ma), 0) * (4.0f * 0.001f); // milli-amps to amps - if (diff_ms <= 1000) { - // convert centi-amps milliseconds to mAh - _telemetry[esc_id].current_tot_mah += t.current * diff_ms * amp_ms_to_mah; - } - t.consumption_mah = _telemetry[esc_id].current_tot_mah; - update_telem_data(esc_id, t, - AP_ESC_Telem_Backend::TelemetryType::CURRENT - | AP_ESC_Telem_Backend::TelemetryType::VOLTAGE - | AP_ESC_Telem_Backend::TelemetryType::CONSUMPTION); - - _telemetry[esc_id].last_update_ms = now_ms; - _esc_present_bitmask_recent |= ((uint32_t)1 << esc_id); - } - } - - // decode temperature data - if ((recv_frame.id >= MOTOR_DATA2) && (recv_frame.id <= MOTOR_DATA2 + TOSHIBACAN_MAX_NUM_ESCS)) { - // motor data2 data format is 8 bytes (64 bits) - // 10 bits: U temperature - // 10 bits: V temperature - // 10 bits: W temperature - // 10 bits: motor temperature - // remaining 24 bits: reserved - const uint16_t u_temp = ((uint16_t)recv_frame.data[0] << 2) | ((uint16_t)recv_frame.data[1] >> 6); - const uint16_t v_temp = (((uint16_t)recv_frame.data[1] & (uint16_t)0x3F) << 4) | (((uint16_t)recv_frame.data[2] & (uint16_t)0xF0) >> 4); - const uint16_t w_temp = (((uint16_t)recv_frame.data[2] & (uint16_t)0x0F) << 6) | (((uint16_t)recv_frame.data[3] & (uint16_t)0xFC) >> 2); - const uint16_t motor_temp = (((uint16_t)recv_frame.data[3] & (uint16_t)0x03) << 8) | ((uint16_t)recv_frame.data[4]); - const uint16_t temp_max = MAX(u_temp, MAX(v_temp, w_temp)); - - // store response in telemetry array - uint8_t esc_id = recv_frame.id - MOTOR_DATA2; - if (esc_id < TOSHIBACAN_MAX_NUM_ESCS) { - const int16_t esc_temp_deg = temp_max < 100 ? 0 : temp_max / 5 - 20; - const int16_t motor_temp_deg = motor_temp < 100 ? 0 : motor_temp / 5 - 20; - _esc_present_bitmask_recent |= ((uint32_t)1 << esc_id); - - TelemetryData t { - .temperature_cdeg = int16_t(esc_temp_deg * 100) - }; - t.motor_temp_cdeg = int16_t(motor_temp_deg * 100); - update_telem_data(esc_id, t, AP_ESC_Telem_Backend::TelemetryType::MOTOR_TEMPERATURE | - AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE); - } - } - - // decode cumulative usage data - if ((recv_frame.id >= MOTOR_DATA3) && (recv_frame.id <= MOTOR_DATA3 + TOSHIBACAN_MAX_NUM_ESCS)) { - // motor data3 data format is 8 bytes (64 bits) - // 3 bytes: usage in seconds - // 2 bytes: number of times rotors started and stopped - // 3 bytes: reserved - const uint32_t usage_sec = ((uint32_t)recv_frame.data[0] << 16) | ((uint32_t)recv_frame.data[1] << 8) | (uint32_t)recv_frame.data[2]; - - // store response in telemetry array - uint8_t esc_id = recv_frame.id - MOTOR_DATA3; - if (esc_id < TOSHIBACAN_MAX_NUM_ESCS) { - _esc_present_bitmask_recent |= ((uint32_t)1 << esc_id); - - TelemetryData t {}; - t.usage_s = usage_sec; - update_telem_data(esc_id, t, AP_ESC_Telem_Backend::TelemetryType::USAGE); - } - } -#endif // HAL_WITH_ESC_TELEM - } - - // update bitmask of escs that replied - update_esc_present_bitmask(); - } - - // success! - send_stage = 0; - - // record success so we don't send this frame again - update_count_sent = update_count_buffered; - } -} - -// write frame on CAN bus -bool AP_ToshibaCAN::write_frame(AP_HAL::CANFrame &out_frame, uint64_t timeout) -{ - // wait for space in buffer to send command - - bool read_select = false; - bool write_select = true; - bool ret; - do { - ret = _can_iface->select(read_select, write_select, &out_frame, timeout); - if (!ret || !write_select) { - // delay if no space is available to send - hal.scheduler->delay_microseconds(50); - } - } while (!ret || !write_select); - - // send frame and return success - return (_can_iface->send(out_frame, timeout, AP_HAL::CANIface::AbortOnError) == 1); -} - -// read frame on CAN bus, returns true on success -bool AP_ToshibaCAN::read_frame(AP_HAL::CANFrame &recv_frame, uint64_t timeout) -{ - // wait for space in buffer to read - bool read_select = true; - bool write_select = false; - int ret = _can_iface->select(read_select, write_select, nullptr, timeout); - if (!ret || !read_select) { - // return false if no data is available to read - return false; - } - uint64_t time; - AP_HAL::CANIface::CanIOFlags flags {}; - - // read frame and return success - return (_can_iface->receive(recv_frame, time, flags) == 1); -} - -// update esc_present_bitmask -void AP_ToshibaCAN::update_esc_present_bitmask() -{ - // recently detected escs are immediately considered present - _esc_present_bitmask |= _esc_present_bitmask_recent; - - // escs that don't respond disappear in 1 to 2 seconds - // set the _esc_present_bitmask to the "recent" bitmask and - // clear the "recent" bitmask every second - uint32_t now_ms = AP_HAL::native_millis(); - if (now_ms - _esc_present_update_ms > 1000) { - _esc_present_bitmask = _esc_present_bitmask_recent; - _esc_present_bitmask_recent = 0; - _esc_present_update_ms = now_ms; - } -} - -// called from SRV_Channels -void AP_ToshibaCAN::update() -{ - // take semaphore and update outputs - { - WITH_SEMAPHORE(_rc_out_sem); - const bool armed = hal.util->get_soft_armed(); - for (uint8_t i = 0; i < MIN(TOSHIBACAN_MAX_NUM_ESCS, 16); i++) { - const SRV_Channel *c = SRV_Channels::srv_channel(i); - if (!armed || (c == nullptr)) { - _scaled_output[i] = 0; - } else { - const uint16_t pwm_out = c->get_output_pwm(); - if (pwm_out <= 1000) { - _scaled_output[i] = 0; - } else if (pwm_out >= 2000) { - _scaled_output[i] = TOSHIBACAN_OUTPUT_MAX; - } else { - _scaled_output[i] = TOSHIBACAN_OUTPUT_MIN + (pwm_out - 1000) * 0.001f * (TOSHIBACAN_OUTPUT_MAX - TOSHIBACAN_OUTPUT_MIN); - } - } - } - update_count++; - } -} - -// helper function to create motor_request_data_cmd_t -AP_ToshibaCAN::motor_request_data_cmd_t AP_ToshibaCAN::get_motor_request_data_cmd(uint8_t request_id) const -{ - motor_request_data_cmd_t req_data_cmd = {}; - req_data_cmd.motor1 = request_id; - req_data_cmd.motor2 = request_id; - req_data_cmd.motor3 = request_id; - req_data_cmd.motor4 = request_id; - req_data_cmd.motor5 = request_id; - req_data_cmd.motor6 = request_id; - req_data_cmd.motor7 = request_id; - req_data_cmd.motor8 = request_id; - req_data_cmd.motor9 = request_id; - req_data_cmd.motor10 = request_id; - req_data_cmd.motor11 = request_id; - req_data_cmd.motor12 = request_id; - return req_data_cmd; -} - -#endif // HAL_NUM_CAN_IFACES diff --git a/libraries/AP_ToshibaCAN/AP_ToshibaCAN.h b/libraries/AP_ToshibaCAN/AP_ToshibaCAN.h deleted file mode 100644 index c638631c204..00000000000 --- a/libraries/AP_ToshibaCAN/AP_ToshibaCAN.h +++ /dev/null @@ -1,184 +0,0 @@ -/* - This program is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - This program is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with this program. If not, see . - */ - -#pragma once - -#include -#include -#include - -#define TOSHIBACAN_MAX_NUM_ESCS 12 - -class CANTester; - -class AP_ToshibaCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { - friend class CANTester; -public: - AP_ToshibaCAN(); - ~AP_ToshibaCAN(); - - /* Do not allow copies */ - AP_ToshibaCAN(const AP_ToshibaCAN &other) = delete; - AP_ToshibaCAN &operator=(const AP_ToshibaCAN&) = delete; - - // Return ToshibaCAN from @driver_index or nullptr if it's not ready or doesn't exist - static AP_ToshibaCAN *get_tcan(uint8_t driver_index); - - // initialise ToshibaCAN bus - void init(uint8_t driver_index, bool enable_filters) override; - bool add_interface(AP_HAL::CANIface* can_iface) override; - - // called from SRV_Channels - void update(); - - // return a bitmask of escs that are "present" which means they are responding to requests. Bitmask matches RC outputs - uint16_t get_present_mask() const { return _esc_present_bitmask; } - -private: - - // data format for messages from flight controller - static constexpr uint8_t COMMAND_STOP = 0x0; - static constexpr uint8_t COMMAND_LOCK = 0x10; - static constexpr uint8_t COMMAND_REQUEST_DATA = 0x20; - static constexpr uint8_t COMMAND_MOTOR3 = 0x3B; - static constexpr uint8_t COMMAND_MOTOR2 = 0x3D; - static constexpr uint8_t COMMAND_MOTOR1 = 0x3F; - - // data format for messages from ESC - static constexpr uint8_t MOTOR_DATA1 = 0x40; - static constexpr uint8_t MOTOR_DATA2 = 0x50; - static constexpr uint8_t MOTOR_DATA3 = 0x60; - static constexpr uint8_t MOTOR_DATA5 = 0x80; - - // processing definitions - static constexpr uint16_t TOSHIBACAN_OUTPUT_MIN = 6300; - static constexpr uint16_t TOSHIBACAN_OUTPUT_MAX = 32000; - static const uint16_t TOSHIBACAN_SEND_TIMEOUT_US; - static constexpr uint8_t CAN_IFACE_INDEX = 0; - - // telemetry definitions - static constexpr uint32_t TOSHIBA_CAN_ESC_UPDATE_MS = 100; - - // loop to send output to ESCs in background thread - void loop(); - - // write frame on CAN bus, returns true on success - bool write_frame(AP_HAL::CANFrame &out_frame, uint64_t timeout); - - // read frame on CAN bus, returns true on success - bool read_frame(AP_HAL::CANFrame &recv_frame, uint64_t timeout); - - // update esc_present_bitmask - void update_esc_present_bitmask(); - - bool _initialized; - char _thread_name[9]; - uint8_t _driver_index; - AP_HAL::CANIface* _can_iface; - HAL_EventHandle _event_handle; - // PWM output - HAL_Semaphore _rc_out_sem; - uint16_t _scaled_output[TOSHIBACAN_MAX_NUM_ESCS]; - uint16_t update_count; // counter increments each time main thread updates outputs - uint16_t update_count_buffered; // counter when outputs copied to buffer before before sending to ESCs - uint16_t update_count_sent; // counter of outputs successfully sent - uint8_t send_stage; // stage of sending algorithm (each stage sends one frame to ESCs) - - struct telemetry_info_t { - uint32_t last_update_ms; // system time telemetry was last update (used to calc total current) - float current_tot_mah; // total current in mAh - } _telemetry[TOSHIBACAN_MAX_NUM_ESCS]; - uint32_t _telemetry_req_ms; // system time (in milliseconds) to request data from escs (updated at 10hz) - uint8_t _telemetry_temp_req_counter; // counter used to trigger temp data requests from ESCs (10x slower than other telem data) - uint8_t _telemetry_usage_req_counter; // counter used to trigger usage data requests from ESCs (100x slower than other telem data) - const float amp_ms_to_mah = 1.0f / 3600.0f; // for converting amp milliseconds to mAh - - // variables for updating bitmask of responsive escs - uint16_t _esc_present_bitmask; // bitmask of which escs seem to be present - uint16_t _esc_present_bitmask_recent; // bitmask of escs that have responded in the last second - uint32_t _esc_present_update_ms; // system time _esc_present_bitmask was last updated - - // structure for sending motor lock command to ESC - union motor_lock_cmd_t { - struct PACKED { - uint8_t motor2:4; - uint8_t motor1:4; - uint8_t motor4:4; - uint8_t motor3:4; - uint8_t motor6:4; - uint8_t motor5:4; - uint8_t motor8:4; - uint8_t motor7:4; - uint8_t motor10:4; - uint8_t motor9:4; - uint8_t motor12:4; - uint8_t motor11:4; - }; - uint8_t data[6]; - }; - - // structure for sending turn rate command to ESC - union motor_rotation_cmd_t { - struct PACKED { - uint16_t motor4; - uint16_t motor3; - uint16_t motor2; - uint16_t motor1; - }; - uint8_t data[8]; - }; - - // structure for requesting data from ESC - union motor_request_data_cmd_t { - struct PACKED { - uint8_t motor2:4; - uint8_t motor1:4; - uint8_t motor4:4; - uint8_t motor3:4; - uint8_t motor6:4; - uint8_t motor5:4; - uint8_t motor8:4; - uint8_t motor7:4; - uint8_t motor10:4; - uint8_t motor9:4; - uint8_t motor12:4; - uint8_t motor11:4; - }; - uint8_t data[6]; - }; - - // helper function to create motor_request_data_cmd_t - motor_request_data_cmd_t get_motor_request_data_cmd(uint8_t request_id) const; - - // structure for replies from ESC of data1 (rpm and voltage) - union motor_reply_data1_t { - struct PACKED { - uint8_t rxng:1; // RX No Good. "1" if ESC encountered error receiving a message since MOTOR_DATA1 was last sent - uint8_t stepout:1; // "1" if a "step out" has occured since MOTOR_DATA1 was last sent - uint8_t state:6; - int16_t rpm; - uint16_t current_ma; // current in milliamps - uint16_t voltage_mv; // voltage in millivolts - uint8_t position_est_error; - }; - uint8_t data[8]; - }; - - // frames to be sent - AP_HAL::CANFrame unlock_frame; - AP_HAL::CANFrame mot_rot_frame1; - AP_HAL::CANFrame mot_rot_frame2; - AP_HAL::CANFrame mot_rot_frame3; -}; diff --git a/libraries/AP_Tuning/AP_Tuning.cpp b/libraries/AP_Tuning/AP_Tuning.cpp index 83df2e5203a..0fcc4e63f4e 100644 --- a/libraries/AP_Tuning/AP_Tuning.cpp +++ b/libraries/AP_Tuning/AP_Tuning.cpp @@ -1,7 +1,9 @@ #include "AP_Tuning.h" + #include #include #include +#include extern const AP_HAL::HAL& hal; diff --git a/libraries/AP_UAVCAN/AP_UAVCAN.cpp b/libraries/AP_UAVCAN/AP_UAVCAN.cpp index 3dba5e0060f..baeabe95574 100644 --- a/libraries/AP_UAVCAN/AP_UAVCAN.cpp +++ b/libraries/AP_UAVCAN/AP_UAVCAN.cpp @@ -48,6 +48,7 @@ #include #include #include +#include #include #include #include @@ -57,11 +58,29 @@ #include #include "AP_UAVCAN_DNA_Server.h" #include +#include +#include +#include "AP_UAVCAN_pool.h" #define LED_DELAY_US 50000 extern const AP_HAL::HAL& hal; +// setup default pool size +#ifndef UAVCAN_NODE_POOL_SIZE +#if HAL_CANFD_SUPPORTED +#define UAVCAN_NODE_POOL_SIZE 16384 +#else +#define UAVCAN_NODE_POOL_SIZE 8192 +#endif +#endif + +#if HAL_CANFD_SUPPORTED +#define UAVCAN_STACK_SIZE 8192 +#else +#define UAVCAN_STACK_SIZE 4096 +#endif + #define debug_uavcan(level_debug, fmt, args...) do { AP::can().log_text(level_debug, "UAVCAN", fmt, ##args); } while (0) // Translation of all messages from UAVCAN structures into AP structures is done @@ -79,16 +98,17 @@ const AP_Param::GroupInfo AP_UAVCAN::var_info[] = { AP_GROUPINFO("NODE", 1, AP_UAVCAN, _uavcan_node, 10), // @Param: SRV_BM - // @DisplayName: RC Out channels to be transmitted as servo over UAVCAN + // @DisplayName: Output channels to be transmitted as servo over UAVCAN // @Description: Bitmask with one set for channel to be transmitted as a servo command over UAVCAN - // @Bitmask: 0: Servo 1, 1: Servo 2, 2: Servo 3, 3: Servo 4, 4: Servo 5, 5: Servo 6, 6: Servo 7, 7: Servo 8, 8: Servo 9, 9: Servo 10, 10: Servo 11, 11: Servo 12, 12: Servo 13, 13: Servo 14, 14: Servo 15 + // @Bitmask: 0: Servo 1, 1: Servo 2, 2: Servo 3, 3: Servo 4, 4: Servo 5, 5: Servo 6, 6: Servo 7, 7: Servo 8, 8: Servo 9, 9: Servo 10, 10: Servo 11, 11: Servo 12, 12: Servo 13, 13: Servo 14, 14: Servo 15, 15: Servo 16, 16: Servo 17, 17: Servo 18, 18: Servo 19, 19: Servo 20, 20: Servo 21, 21: Servo 22, 22: Servo 23, 23: Servo 24, 24: Servo 25, 25: Servo 26, 26: Servo 27, 27: Servo 28, 28: Servo 29, 29: Servo 30, 30: Servo 31, 31: Servo 32 + // @User: Advanced AP_GROUPINFO("SRV_BM", 2, AP_UAVCAN, _servo_bm, 0), // @Param: ESC_BM - // @DisplayName: RC Out channels to be transmitted as ESC over UAVCAN + // @DisplayName: Output channels to be transmitted as ESC over UAVCAN // @Description: Bitmask with one set for channel to be transmitted as a ESC command over UAVCAN - // @Bitmask: 0: ESC 1, 1: ESC 2, 2: ESC 3, 3: ESC 4, 4: ESC 5, 5: ESC 6, 6: ESC 7, 7: ESC 8, 8: ESC 9, 9: ESC 10, 10: ESC 11, 11: ESC 12, 12: ESC 13, 13: ESC 14, 14: ESC 15, 15: ESC 16 + // @Bitmask: 0: ESC 1, 1: ESC 2, 2: ESC 3, 3: ESC 4, 4: ESC 5, 5: ESC 6, 6: ESC 7, 7: ESC 8, 8: ESC 9, 9: ESC 10, 10: ESC 11, 11: ESC 12, 12: ESC 13, 13: ESC 14, 14: ESC 15, 15: ESC 16, 16: ESC 17, 17: ESC 18, 18: ESC 19, 19: ESC 20, 20: ESC 21, 21: ESC 22, 22: ESC 23, 23: ESC 24, 24: ESC 25, 25: ESC 26, 26: ESC 27, 27: ESC 28, 28: ESC 29, 29: ESC 30, 30: ESC 31, 31: ESC 32 // @User: Advanced AP_GROUPINFO("ESC_BM", 3, AP_UAVCAN, _esc_bm, 0), @@ -103,7 +123,7 @@ const AP_Param::GroupInfo AP_UAVCAN::var_info[] = { // @Param: OPTION // @DisplayName: UAVCAN options // @Description: Option flags - // @Bitmask: 0:ClearDNADatabase,1:IgnoreDNANodeConflicts + // @Bitmask: 0:ClearDNADatabase,1:IgnoreDNANodeConflicts,2:EnableCanfd,3:IgnoreDNANodeUnhealthy // @User: Advanced AP_GROUPINFO("OPTION", 5, AP_UAVCAN, _options, 0), @@ -115,6 +135,20 @@ const AP_Param::GroupInfo AP_UAVCAN::var_info[] = { // @User: Advanced AP_GROUPINFO("NTF_RT", 6, AP_UAVCAN, _notify_state_hz, 20), + // @Param: ESC_OF + // @DisplayName: ESC Output channels offset + // @Description: Offset for ESC numbering in DroneCAN ESC RawCommand messages. This allows for more efficient packing of ESC command messages. If your ESCs are on servo functions 5 to 8 and you set this parameter to 4 then the ESC RawCommand will be sent with the first 4 slots filled. This can be used for more efficint usage of CAN bandwidth + // @Range: 0 18 + // @User: Advanced + AP_GROUPINFO("ESC_OF", 7, AP_UAVCAN, _esc_offset, 0), + + // @Param: POOL + // @DisplayName: CAN pool size + // @Description: Amount of memory in bytes to allocate for the DroneCAN memory pool. More memory is needed for higher CAN bus loads + // @Range: 1024 16384 + // @User: Advanced + AP_GROUPINFO("POOL", 8, AP_UAVCAN, _pool_size, UAVCAN_NODE_POOL_SIZE), + AP_GROUPEND }; @@ -164,9 +198,7 @@ static uavcan::Subscriber *esc_stat UC_REGISTRY_BINDER(DebugCb, uavcan::protocol::debug::LogMessage); static uavcan::Subscriber *debug_listener[HAL_MAX_CAN_PROTOCOL_DRIVERS]; - -AP_UAVCAN::AP_UAVCAN() : - _node_allocator() +AP_UAVCAN::AP_UAVCAN() { AP_Param::setup_object_defaults(this, var_info); @@ -225,7 +257,14 @@ void AP_UAVCAN::init(uint8_t driver_index, bool enable_filters) return; } - _node = new uavcan::Node<0>(*_iface_mgr, uavcan::SystemClock::instance(), _node_allocator); + _allocator = new AP_PoolAllocator(_pool_size); + + if (_allocator == nullptr || !_allocator->init()) { + debug_uavcan(AP_CANManager::LOG_ERROR, "UAVCAN: couldn't allocate node pool\n"); + return; + } + + _node = new uavcan::Node<0>(*_iface_mgr, uavcan::SystemClock::instance(), *_allocator); if (_node == nullptr) { debug_uavcan(AP_CANManager::LOG_ERROR, "UAVCAN: couldn't allocate node\n\r"); @@ -271,14 +310,27 @@ void AP_UAVCAN::init(uint8_t driver_index, bool enable_filters) } _node->setHardwareVersion(hw_version); } + +#if UAVCAN_SUPPORT_CANFD + if (option_is_set(Options::CANFD_ENABLED)) { + _node->enableCanFd(); + } +#endif + int start_res = _node->start(); if (start_res < 0) { debug_uavcan(AP_CANManager::LOG_ERROR, "UAVCAN: node start problem, error %d\n\r", start_res); return; } + _dna_server = new AP_UAVCAN_DNA_Server(this, StorageAccess(StorageManager::StorageCANDNA)); + if (_dna_server == nullptr) { + debug_uavcan(AP_CANManager::LOG_ERROR, "UAVCAN: couldn't allocate DNA server\n\r"); + return; + } + //Start Servers - if (!AP::uavcan_dna_server().init(this)) { + if (!_dna_server->init()) { debug_uavcan(AP_CANManager::LOG_ERROR, "UAVCAN: Failed to start DNA Server\n\r"); return; } @@ -287,13 +339,22 @@ void AP_UAVCAN::init(uint8_t driver_index, bool enable_filters) AP_UAVCAN_DNA_Server::subscribe_msgs(this); AP_GPS_UAVCAN::subscribe_msgs(this); AP_Compass_UAVCAN::subscribe_msgs(this); +#if AP_BARO_UAVCAN_ENABLED AP_Baro_UAVCAN::subscribe_msgs(this); +#endif AP_BattMonitor_UAVCAN::subscribe_msgs(this); +#if AP_AIRSPEED_UAVCAN_ENABLED AP_Airspeed_UAVCAN::subscribe_msgs(this); +#endif #if AP_OPTICALFLOW_HEREFLOW_ENABLED AP_OpticalFlow_HereFlow::subscribe_msgs(this); #endif +#if AP_RANGEFINDER_UAVCAN_ENABLED AP_RangeFinder_UAVCAN::subscribe_msgs(this); +#endif +#if HAL_EFI_ENABLED + AP_EFI_DroneCAN::subscribe_msgs(this); +#endif act_out_array[driver_index] = new uavcan::Publisher(*_node); act_out_array[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(2)); @@ -369,7 +430,7 @@ void AP_UAVCAN::init(uint8_t driver_index, bool enable_filters) snprintf(_thread_name, sizeof(_thread_name), "uavcan_%u", driver_index); - if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_UAVCAN::loop, void), _thread_name, 4096, AP_HAL::Scheduler::PRIORITY_CAN, 0)) { + if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_UAVCAN::loop, void), _thread_name, UAVCAN_STACK_SIZE, AP_HAL::Scheduler::PRIORITY_CAN, 0)) { _node->setModeOfflineAndPublish(); debug_uavcan(AP_CANManager::LOG_ERROR, "UAVCAN: couldn't create thread\n\r"); return; @@ -429,7 +490,10 @@ void AP_UAVCAN::loop(void) notify_state_send(); send_parameter_request(); send_parameter_save_request(); - AP::uavcan_dna_server().verify_nodes(this); + _dna_server->verify_nodes(); +#if AP_OPENDRONEID_ENABLED + AP::opendroneid().dronecan_send(this); +#endif } } @@ -464,11 +528,13 @@ void AP_UAVCAN::SRV_send_actuator(void) if (_SRV_conf[starting_servo].servo_pending && ((((uint32_t) 1) << starting_servo) & _servo_bm)) { cmd.actuator_id = starting_servo + 1; - // TODO: other types - cmd.command_type = uavcan::equipment::actuator::Command::COMMAND_TYPE_UNITLESS; - - // TODO: failsafe, safety - cmd.command_value = constrain_float(((float) _SRV_conf[starting_servo].pulse - 1000.0) / 500.0 - 1.0, -1.0, 1.0); + if (option_is_set(Options::USE_ACTUATOR_PWM)) { + cmd.command_type = uavcan::equipment::actuator::Command::COMMAND_TYPE_PWM; + cmd.command_value = _SRV_conf[starting_servo].pulse; + } else { + cmd.command_type = uavcan::equipment::actuator::Command::COMMAND_TYPE_UNITLESS; + cmd.command_value = constrain_float(((float) _SRV_conf[starting_servo].pulse - 1000.0) / 500.0 - 1.0, -1.0, 1.0); + } msg.commands.push_back(cmd); @@ -496,8 +562,11 @@ void AP_UAVCAN::SRV_send_esc(void) WITH_SEMAPHORE(SRV_sem); + // esc offset allows for efficient packing of higher ESC numbers in RawCommand + const uint8_t esc_offset = constrain_int16(_esc_offset.get(), 0, UAVCAN_SRV_NUMBER); + // find out how many esc we have enabled and if they are active at all - for (uint8_t i = 0; i < UAVCAN_SRV_NUMBER; i++) { + for (uint8_t i = esc_offset; i < UAVCAN_SRV_NUMBER; i++) { if ((((uint32_t) 1) << i) & _esc_bm) { max_esc_num = i + 1; if (_SRV_conf[i].esc_pending) { @@ -510,7 +579,7 @@ void AP_UAVCAN::SRV_send_esc(void) if (active_esc_num > 0) { k = 0; - for (uint8_t i = 0; i < max_esc_num && k < 20; i++) { + for (uint8_t i = esc_offset; i < max_esc_num && k < 20; i++) { if ((((uint32_t) 1) << i) & _esc_bm) { // TODO: ESC negative scaling for reverse thrust and reverse rotation float scaled = cmd_max * (hal.rcout->scale_esc_to_unity(_SRV_conf[i].pulse) + 1.0) / 2.0; @@ -533,9 +602,9 @@ void AP_UAVCAN::SRV_push_servos() { WITH_SEMAPHORE(SRV_sem); - for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) { + for (uint8_t i = 0; i < UAVCAN_SRV_NUMBER; i++) { // Check if this channels has any function assigned - if (SRV_Channels::channel_function(i)) { + if (SRV_Channels::channel_function(i) >= SRV_Channel::k_none) { _SRV_conf[i].pulse = SRV_Channels::srv_channel(i)->get_output_pwm(); _SRV_conf[i].esc_pending = true; _SRV_conf[i].servo_pending = true; @@ -915,7 +984,8 @@ void AP_UAVCAN::handle_actuator_status(AP_UAVCAN* ap_uavcan, uint8_t node_id, co void AP_UAVCAN::handle_ESC_status(AP_UAVCAN* ap_uavcan, uint8_t node_id, const ESCStatusCb &cb) { #if HAL_WITH_ESC_TELEM - const uint8_t esc_index = cb.msg->esc_index; + const uint8_t esc_offset = constrain_int16(ap_uavcan->_esc_offset.get(), 0, UAVCAN_SRV_NUMBER); + const uint8_t esc_index = cb.msg->esc_index + esc_offset; if (!is_esc_data_index_valid(esc_index)) { return; @@ -1140,4 +1210,11 @@ bool AP_UAVCAN::check_and_reset_option(Options option) return ret; } +// handle prearm check +bool AP_UAVCAN::prearm_check(char* fail_msg, uint8_t fail_msg_len) const +{ + // forward this to DNA_Server + return _dna_server->prearm_check(fail_msg, fail_msg_len); +} + #endif // HAL_NUM_CAN_IFACES diff --git a/libraries/AP_UAVCAN/AP_UAVCAN.h b/libraries/AP_UAVCAN/AP_UAVCAN.h index 5fed1a4cc91..9085a76c5a9 100644 --- a/libraries/AP_UAVCAN/AP_UAVCAN.h +++ b/libraries/AP_UAVCAN/AP_UAVCAN.h @@ -21,28 +21,19 @@ #if HAL_ENABLE_LIBUAVCAN_DRIVERS #include -#include "AP_UAVCAN_DNA_Server.h" #include "AP_UAVCAN_IfaceMgr.h" #include "AP_UAVCAN_Clock.h" -#include +#include #include #include #include #include #include -#include +#include -#ifndef UAVCAN_NODE_POOL_SIZE -#define UAVCAN_NODE_POOL_SIZE 8192 -#endif - -#ifndef UAVCAN_NODE_POOL_BLOCK_SIZE -#define UAVCAN_NODE_POOL_BLOCK_SIZE 64 -#endif - #ifndef UAVCAN_SRV_NUMBER -#define UAVCAN_SRV_NUMBER 18 +#define UAVCAN_SRV_NUMBER NUM_SERVO_CHANNELS #endif #define AP_UAVCAN_SW_VERS_MAJOR 1 @@ -61,6 +52,8 @@ class ESCStatusCb; class DebugCb; class ParamGetSetCb; class ParamExecuteOpcodeCb; +class AP_PoolAllocator; +class AP_UAVCAN_DNA_Server; #if defined(__GNUC__) && (__GNUC__ > 8) #define DISABLE_W_CAST_FUNCTION_TYPE_PUSH \ @@ -105,6 +98,7 @@ class ParamExecuteOpcodeCb; } class AP_UAVCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { + friend class AP_UAVCAN_DNA_Server; public: AP_UAVCAN(); ~AP_UAVCAN(); @@ -113,10 +107,11 @@ class AP_UAVCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { // Return uavcan from @driver_index or nullptr if it's not ready or doesn't exist static AP_UAVCAN *get_uavcan(uint8_t driver_index); + bool prearm_check(char* fail_msg, uint8_t fail_msg_len) const; void init(uint8_t driver_index, bool enable_filters) override; bool add_interface(AP_HAL::CANIface* can_iface) override; - + uavcan::Node<0>* get_node() { return _node; } uint8_t get_driver_index() const { return _driver_index; } @@ -206,6 +201,9 @@ class AP_UAVCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { enum class Options : uint16_t { DNA_CLEAR_DATABASE = (1U<<0), DNA_IGNORE_DUPLICATE_NODE = (1U<<1), + CANFD_ENABLED = (1U<<2), + DNA_IGNORE_UNHEALTHY_NODE = (1U<<3), + USE_ACTUATOR_PWM = (1U<<4), }; // check if a option is set @@ -217,11 +215,11 @@ class AP_UAVCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { // 0. return true if it was set bool check_and_reset_option(Options option); -private: // This will be needed to implement if UAVCAN is used with multithreading // Such cases will be firmware update, etc. class RaiiSynchronizer {}; +private: void loop(void); ///// SRV output ///// @@ -262,15 +260,18 @@ class AP_UAVCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { HAL_Semaphore _param_save_sem; uint8_t param_save_request_node_id; - uavcan::PoolAllocator _node_allocator; - // UAVCAN parameters AP_Int8 _uavcan_node; AP_Int32 _servo_bm; AP_Int32 _esc_bm; + AP_Int8 _esc_offset; AP_Int16 _servo_rate_hz; AP_Int16 _options; AP_Int16 _notify_state_hz; + AP_Int16 _pool_size; + + AP_PoolAllocator *_allocator; + AP_UAVCAN_DNA_Server *_dna_server; uavcan::Node<0> *_node; diff --git a/libraries/AP_UAVCAN/AP_UAVCAN_DNA_Server.cpp b/libraries/AP_UAVCAN/AP_UAVCAN_DNA_Server.cpp index ed4052cd7e2..0e1b50cd035 100644 --- a/libraries/AP_UAVCAN/AP_UAVCAN_DNA_Server.cpp +++ b/libraries/AP_UAVCAN/AP_UAVCAN_DNA_Server.cpp @@ -40,15 +40,17 @@ extern const AP_HAL::HAL& hal; //Callback Object Definitions UC_REGISTRY_BINDER(AllocationCb, uavcan::protocol::dynamic_node_id::Allocation); UC_REGISTRY_BINDER(NodeStatusCb, uavcan::protocol::NodeStatus); +UC_CLIENT_CALL_REGISTRY_BINDER(GetNodeInfoCb, uavcan::protocol::GetNodeInfo); -static void trampoline_handleNodeInfo(const uavcan::ServiceCallResult& resp); -static void trampoline_handleAllocation(AP_UAVCAN* ap_uavcan, uint8_t node_id, const AllocationCb &cb); -static void trampoline_handleNodeStatus(AP_UAVCAN* ap_uavcan, uint8_t node_id, const NodeStatusCb &cb); - -static uavcan::ServiceClient* getNodeInfo_client[HAL_MAX_CAN_PROTOCOL_DRIVERS]; +static uavcan::ServiceClient* getNodeInfo_client[HAL_MAX_CAN_PROTOCOL_DRIVERS]; static uavcan::Publisher* allocation_pub[HAL_MAX_CAN_PROTOCOL_DRIVERS]; +AP_UAVCAN_DNA_Server::AP_UAVCAN_DNA_Server(AP_UAVCAN *ap_uavcan, StorageAccess _storage) : + _ap_uavcan(ap_uavcan), + storage(_storage) +{} + /* Subscribe to all the messages we are going to handle for Server registry and Node allocation. */ void AP_UAVCAN_DNA_Server::subscribe_msgs(AP_UAVCAN* ap_uavcan) @@ -107,6 +109,7 @@ bool AP_UAVCAN_DNA_Server::readNodeData(NodeData &data, uint8_t node_id) if (node_id > MAX_NODE_ID) { return false; } + WITH_SEMAPHORE(storage_sem); if (!storage.read_block(&data, (node_id * sizeof(struct NodeData)) + NODEDATA_MAGIC_LEN, sizeof(struct NodeData))) { //This will fall through to Prearm Check server_state = STORAGE_FAILURE; @@ -121,6 +124,7 @@ bool AP_UAVCAN_DNA_Server::writeNodeData(const NodeData &data, uint8_t node_id) if (node_id > MAX_NODE_ID) { return false; } + WITH_SEMAPHORE(storage_sem); if (!storage.write_block((node_id * sizeof(struct NodeData)) + NODEDATA_MAGIC_LEN, &data, sizeof(struct NodeData))) { server_state = STORAGE_FAILURE; @@ -251,23 +255,16 @@ bool AP_UAVCAN_DNA_Server::isValidNodeDataAvailable(uint8_t node_id) Also resets the Server Record in case there is a mismatch between specified node id and unique id against the existing Server Record. */ -bool AP_UAVCAN_DNA_Server::init(AP_UAVCAN *ap_uavcan) +bool AP_UAVCAN_DNA_Server::init() { - if (ap_uavcan == nullptr) { - return false; - } - - WITH_SEMAPHORE(sem); - - _ap_uavcan = ap_uavcan; - //Read the details from ap_uavcan - uavcan::Node<0>* _node = ap_uavcan->get_node(); + uavcan::Node<0>* _node = _ap_uavcan->get_node(); uint8_t node_id = _node->getNodeID().get(); - uint8_t driver_index = ap_uavcan->get_driver_index(); uint8_t own_unique_id[16] = {0}; uint8_t own_unique_id_len = 16; + driver_index = _ap_uavcan->get_driver_index(); + //copy unique id from node to uint8_t array uavcan::copy(_node->getHardwareVersion().unique_id.begin(), _node->getHardwareVersion().unique_id.end(), @@ -276,7 +273,7 @@ bool AP_UAVCAN_DNA_Server::init(AP_UAVCAN *ap_uavcan) server_state = HEALTHY; //Setup publisher for this driver index - allocation_pub[driver_index] = new uavcan::Publisher(*_node); + allocation_pub[driver_index] = new uavcan::Publisher(*_node, true); if (allocation_pub[driver_index] == nullptr) { AP_BoardConfig::allocation_error("AP_UAVCAN_DNA: allocation_pub[%d]", driver_index); } @@ -287,18 +284,13 @@ bool AP_UAVCAN_DNA_Server::init(AP_UAVCAN *ap_uavcan) } allocation_pub[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(uavcan::protocol::dynamic_node_id::Allocation::FOLLOWUP_TIMEOUT_MS)); + //Setup GetNodeInfo Client - getNodeInfo_client[driver_index] = new uavcan::ServiceClient(*_node); + getNodeInfo_client[driver_index] = new uavcan::ServiceClient(*_node, GetNodeInfoCb(_ap_uavcan, &trampoline_handleNodeInfo)); if (getNodeInfo_client[driver_index] == nullptr) { AP_BoardConfig::allocation_error("AP_UAVCAN_DNA: getNodeInfo_client[%d]", driver_index); } - res = getNodeInfo_client[driver_index]->init(); - if (res < 0) { - return false; - } - - getNodeInfo_client[driver_index]->setCallback(trampoline_handleNodeInfo); /* Go through our records and look for valid NodeData, to initialise occupation mask */ @@ -310,12 +302,15 @@ bool AP_UAVCAN_DNA_Server::init(AP_UAVCAN *ap_uavcan) // Check if the magic is present uint16_t magic; - storage.read_block(&magic, 0, NODEDATA_MAGIC_LEN); + { + WITH_SEMAPHORE(storage_sem); + storage.read_block(&magic, 0, NODEDATA_MAGIC_LEN); + } if (magic != NODEDATA_MAGIC) { //Its not there a reset should write it in the Storage reset(); } - if (ap_uavcan->check_and_reset_option(AP_UAVCAN::Options::DNA_CLEAR_DATABASE)) { + if (_ap_uavcan->check_and_reset_option(AP_UAVCAN::Options::DNA_CLEAR_DATABASE)) { GCS_SEND_TEXT(MAV_SEVERITY_INFO, "UC DNA database reset"); reset(); } @@ -354,6 +349,7 @@ bool AP_UAVCAN_DNA_Server::init(AP_UAVCAN *ap_uavcan) if any duplicates are on the bus carrying our Node ID */ addToSeenNodeMask(node_id); setVerificationMask(node_id); + node_healthy_mask.set(node_id); self_node_id[driver_index] = node_id; return true; } @@ -370,6 +366,7 @@ void AP_UAVCAN_DNA_Server::reset() for (uint8_t i = 0; i <= MAX_NODE_ID; i++) { writeNodeData(node_data, i); } + WITH_SEMAPHORE(storage_sem); //Ensure we mark magic at the end uint16_t magic = NODEDATA_MAGIC; storage.write_block(0, &magic, NODEDATA_MAGIC_LEN); @@ -423,10 +420,8 @@ void AP_UAVCAN_DNA_Server::addToSeenNodeMask(uint8_t node_id) than once per 5 second. We continually verify the nodes in our seen list, So that we can raise issue if there are duplicates on the bus. */ -void AP_UAVCAN_DNA_Server::verify_nodes(AP_UAVCAN *ap_uavcan) +void AP_UAVCAN_DNA_Server::verify_nodes() { - WITH_SEMAPHORE(sem); - uint32_t now = uavcan::SystemClock::instance().getMonotonic().toMSec(); if ((now - last_verification_request) < 5000) { return; @@ -440,11 +435,10 @@ void AP_UAVCAN_DNA_Server::verify_nodes(AP_UAVCAN *ap_uavcan) //Check if we got acknowledgement from previous request //except for requests using our own node_id - for (uint8_t i = 0; i < HAL_MAX_CAN_PROTOCOL_DRIVERS; i++) { - if (curr_verifying_node == self_node_id[i]) { - nodeInfo_resp_rcvd = true; - } + if (curr_verifying_node == self_node_id[driver_index]) { + nodeInfo_resp_rcvd = true; } + if (!nodeInfo_resp_rcvd) { /* Also notify GCS about this Reason for this could be either the node was disconnected @@ -466,12 +460,10 @@ void AP_UAVCAN_DNA_Server::verify_nodes(AP_UAVCAN *ap_uavcan) break; } } - for (uint8_t i = 0; i < HAL_MAX_CAN_PROTOCOL_DRIVERS; i++) { - if (getNodeInfo_client[i] != nullptr && isNodeIDOccupied(curr_verifying_node)) { - uavcan::protocol::GetNodeInfo::Request request; - getNodeInfo_client[i]->call(curr_verifying_node, request); - nodeInfo_resp_rcvd = false; - } + if (getNodeInfo_client[driver_index] != nullptr && isNodeIDOccupied(curr_verifying_node)) { + uavcan::protocol::GetNodeInfo::Request request; + getNodeInfo_client[driver_index]->call(curr_verifying_node, request); + nodeInfo_resp_rcvd = false; } } @@ -483,14 +475,24 @@ void AP_UAVCAN_DNA_Server::handleNodeStatus(uint8_t node_id, const NodeStatusCb if (node_id > MAX_NODE_ID) { return; } - WITH_SEMAPHORE(sem); + if ((cb.msg->health != uavcan::protocol::NodeStatus::HEALTH_OK || + cb.msg->mode != uavcan::protocol::NodeStatus::MODE_OPERATIONAL) && + !_ap_uavcan->option_is_set(AP_UAVCAN::Options::DNA_IGNORE_UNHEALTHY_NODE)) { + //if node is not healthy or operational, clear resp health mask, and set fault_node_id + fault_node_id = node_id; + server_state = NODE_STATUS_UNHEALTHY; + node_healthy_mask.clear(node_id); + } else { + node_healthy_mask.set(node_id); + if (node_healthy_mask == verified_mask) { + server_state = HEALTHY; + } + } if (!isNodeIDVerified(node_id)) { //immediately begin verification of the node_id - for (uint8_t i = 0; i < HAL_MAX_CAN_PROTOCOL_DRIVERS; i++) { - if (getNodeInfo_client[i] != nullptr) { - uavcan::protocol::GetNodeInfo::Request request; - getNodeInfo_client[i]->call(node_id, request); - } + if (getNodeInfo_client[driver_index] != nullptr) { + uavcan::protocol::GetNodeInfo::Request request; + getNodeInfo_client[driver_index]->call(node_id, request); } } //Add node to seen list if not seen before @@ -498,13 +500,13 @@ void AP_UAVCAN_DNA_Server::handleNodeStatus(uint8_t node_id, const NodeStatusCb } //Trampoline call for handleNodeStatus member method -void trampoline_handleNodeStatus(AP_UAVCAN* ap_uavcan, uint8_t node_id, const NodeStatusCb &cb) +void AP_UAVCAN_DNA_Server::trampoline_handleNodeStatus(AP_UAVCAN* ap_uavcan, uint8_t node_id, const NodeStatusCb &cb) { if (ap_uavcan == nullptr) { return; } - AP::uavcan_dna_server().handleNodeStatus(node_id, cb); + ap_uavcan->_dna_server->handleNodeStatus(node_id, cb); } @@ -518,8 +520,6 @@ void AP_UAVCAN_DNA_Server::handleNodeInfo(uint8_t node_id, uint8_t unique_id[], if (node_id > MAX_NODE_ID) { return; } - WITH_SEMAPHORE(sem); - /* if we haven't logged this node then log it now */ @@ -581,23 +581,19 @@ void AP_UAVCAN_DNA_Server::handleNodeInfo(uint8_t node_id, uint8_t unique_id[], } //Trampoline call for handleNodeInfo member call -void trampoline_handleNodeInfo(const uavcan::ServiceCallResult& resp) +void AP_UAVCAN_DNA_Server::trampoline_handleNodeInfo(AP_UAVCAN* ap_uavcan, uint8_t node_id, const GetNodeInfoCb& resp) { - uint8_t node_id, unique_id[16] = {0}; + uint8_t unique_id[16] = {0}; char name[50] = {0}; - node_id = resp.getResponse().getSrcNodeID().get(); - //copy the unique id from message to uint8_t array - auto &r = resp.getResponse(); + auto &r = resp.rsp->getResponse(); uavcan::copy(r.hardware_version.unique_id.begin(), r.hardware_version.unique_id.end(), unique_id); strncpy_noterm(name, r.name.c_str(), sizeof(name)-1); - auto &dna_server = AP::uavcan_dna_server(); - - dna_server.handleNodeInfo(node_id, unique_id, name, + ap_uavcan->_dna_server->handleNodeInfo(node_id, unique_id, name, r.software_version.major, r.software_version.minor, r.software_version.vcs_commit); @@ -605,32 +601,17 @@ void trampoline_handleNodeInfo(const uavcan::ServiceCallResultisAnonymousTransfer()) { //Ignore Allocation messages that are not DNA requests return; } uint32_t now = uavcan::SystemClock::instance().getMonotonic().toMSec(); - if (driver_index == current_driver_index) { - last_activity_ms = now; - } else if ((now - last_activity_ms) > 500) { - /* prepare for requests on another driver if we didn't had any activity on - current driver for more than 500ms */ - current_driver_index = driver_index; - last_activity_ms = now; - rcvd_unique_id_offset = 0; - memset(rcvd_unique_id, 0, sizeof(rcvd_unique_id)); - } else { - /* we ignore the requests from other drivers, - while busy handling the current one */ - return; - } if (rcvd_unique_id_offset == 0 || (now - last_alloc_msg_ms) > 500) { @@ -703,12 +684,12 @@ void AP_UAVCAN_DNA_Server::handleAllocation(uint8_t driver_index, uint8_t node_i } //Trampoline Call for handleAllocation member call -void trampoline_handleAllocation(AP_UAVCAN* ap_uavcan, uint8_t node_id, const AllocationCb &cb) +void AP_UAVCAN_DNA_Server::trampoline_handleAllocation(AP_UAVCAN* ap_uavcan, uint8_t node_id, const AllocationCb &cb) { if (ap_uavcan == nullptr) { return; } - AP::uavcan_dna_server().handleAllocation(ap_uavcan->get_driver_index(), node_id, cb); + ap_uavcan->_dna_server->handleAllocation(node_id, cb); } //report the server state, along with failure message if any @@ -733,18 +714,17 @@ bool AP_UAVCAN_DNA_Server::prearm_check(char* fail_msg, uint8_t fail_msg_len) co snprintf(fail_msg, fail_msg_len, "Failed to add Node %d!", fault_node_id); return false; } + case NODE_STATUS_UNHEALTHY: { + if (_ap_uavcan->option_is_set(AP_UAVCAN::Options::DNA_IGNORE_UNHEALTHY_NODE)) { + // ignore error + return true; + } + snprintf(fail_msg, fail_msg_len, "Node %d unhealthy!", fault_node_id); + return false; + } } // should never get; compiler should enforce all server_states are covered return false; } -namespace AP -{ -AP_UAVCAN_DNA_Server& uavcan_dna_server() -{ - // clang gets confused with only one pair of braces so we add one more pair - static AP_UAVCAN_DNA_Server _server((StorageAccess(StorageManager::StorageCANDNA))); - return _server; -} -} #endif //HAL_NUM_CAN_IFACES diff --git a/libraries/AP_UAVCAN/AP_UAVCAN_DNA_Server.h b/libraries/AP_UAVCAN/AP_UAVCAN_DNA_Server.h index 1c1d9684ac8..3a6d6ae14f6 100644 --- a/libraries/AP_UAVCAN/AP_UAVCAN_DNA_Server.h +++ b/libraries/AP_UAVCAN/AP_UAVCAN_DNA_Server.h @@ -1,5 +1,6 @@ #pragma once -#include +#include +#include #if HAL_ENABLE_LIBUAVCAN_DRIVERS #include @@ -11,6 +12,7 @@ class AllocationCb; class NodeStatusCb; class NodeInfoCb; +class GetNodeInfoCb; class AP_UAVCAN; class AP_UAVCAN_DNA_Server @@ -23,6 +25,7 @@ class AP_UAVCAN_DNA_Server }; enum ServerState { + NODE_STATUS_UNHEALTHY = -5, STORAGE_FAILURE = -3, DUPLICATE_NODES = -2, FAILED_TO_ADD_NODE = -1, @@ -38,6 +41,7 @@ class AP_UAVCAN_DNA_Server Bitmask<128> verified_mask; Bitmask<128> node_seen_mask; Bitmask<128> logged; + Bitmask<128> node_healthy_mask; uint8_t last_logging_count; @@ -50,8 +54,6 @@ class AP_UAVCAN_DNA_Server //Allocation params uint8_t rcvd_unique_id[16]; uint8_t rcvd_unique_id_offset; - uint8_t current_driver_index; - uint32_t last_activity_ms; uint32_t last_alloc_msg_ms; //Methods to handle and report Node IDs seen on the bus @@ -87,18 +89,25 @@ class AP_UAVCAN_DNA_Server //Look in the storage and check if there's a valid Server Record there bool isValidNodeDataAvailable(uint8_t node_id); - HAL_Semaphore sem; + static void trampoline_handleNodeInfo(AP_UAVCAN* ap_uavcan, uint8_t node_id, const GetNodeInfoCb& resp); + static void trampoline_handleAllocation(AP_UAVCAN* ap_uavcan, uint8_t node_id, const AllocationCb &cb); + static void trampoline_handleNodeStatus(AP_UAVCAN* ap_uavcan, uint8_t node_id, const NodeStatusCb &cb); + + + HAL_Semaphore storage_sem; AP_UAVCAN *_ap_uavcan; + uint8_t driver_index; public: - AP_UAVCAN_DNA_Server(StorageAccess _storage) : storage(_storage) {} + AP_UAVCAN_DNA_Server(AP_UAVCAN *ap_uavcan, StorageAccess _storage); + // Do not allow copies AP_UAVCAN_DNA_Server(const AP_UAVCAN_DNA_Server &other) = delete; AP_UAVCAN_DNA_Server &operator=(const AP_UAVCAN_DNA_Server&) = delete; //Initialises publisher and Server Record for specified uavcan driver - bool init(AP_UAVCAN *ap_uavcan); + bool init(); //Reset the Server Record void reset(); @@ -117,16 +126,12 @@ class AP_UAVCAN_DNA_Server bool prearm_check(char* fail_msg, uint8_t fail_msg_len) const; //Callbacks - void handleAllocation(uint8_t driver_index, uint8_t node_id, const AllocationCb &cb); + void handleAllocation(uint8_t node_id, const AllocationCb &cb); void handleNodeStatus(uint8_t node_id, const NodeStatusCb &cb); void handleNodeInfo(uint8_t node_id, uint8_t unique_id[], char name[], uint8_t major, uint8_t minor, uint32_t vcs_commit); //Run through the list of seen node ids for verification - void verify_nodes(AP_UAVCAN *ap_uavcan); + void verify_nodes(); }; -namespace AP -{ -AP_UAVCAN_DNA_Server& uavcan_dna_server(); -} #endif diff --git a/libraries/AP_UAVCAN/AP_UAVCAN_IfaceMgr.cpp b/libraries/AP_UAVCAN/AP_UAVCAN_IfaceMgr.cpp index ee10e5e6a2c..bfa04b40843 100644 --- a/libraries/AP_UAVCAN/AP_UAVCAN_IfaceMgr.cpp +++ b/libraries/AP_UAVCAN/AP_UAVCAN_IfaceMgr.cpp @@ -48,7 +48,7 @@ int16_t CanIface::send(const CanFrame& frame, MonotonicTime tx_deadline, CanIOFl if (can_iface_ == UAVCAN_NULLPTR) { return -1; } - return can_iface_->send(AP_HAL::CANFrame(frame.id, frame.data, frame.dlc), tx_deadline.toUSec(), flags); + return can_iface_->send(AP_HAL::CANFrame(frame.id, frame.data, AP_HAL::CANFrame::dlcToDataLength(frame.dlc), frame.isCanFDFrame()), tx_deadline.toUSec(), flags); } /** @@ -83,7 +83,7 @@ int16_t CanIface::receive(CanFrame& out_frame, MonotonicTime& out_ts_monotonic, if (ret < 0) { return ret; } - out_frame = CanFrame(frame.id, (const uint8_t*)frame.data, frame.dlc); + out_frame = CanFrame(frame.id, (const uint8_t*)frame.data, AP_HAL::CANFrame::dlcToDataLength(frame.dlc), frame.canfd); out_flags = flags; if (rx_timestamp != 0) { out_ts_utc = uavcan::UtcTime::fromUSec(SystemClock::instance().getAdjustUsec() + rx_timestamp); @@ -185,7 +185,7 @@ CanSelectMasks CanIfaceMgr::makeSelectMasks(const CanSelectMasks in_mask, const msk.write |= (write ? 1 : 0) << i; } } else { - AP_HAL::CANFrame frame {pending_tx[i]->id, pending_tx[i]->data, pending_tx[i]->dlc}; + AP_HAL::CANFrame frame {pending_tx[i]->id, pending_tx[i]->data, AP_HAL::CANFrame::dlcToDataLength(pending_tx[i]->dlc)}; if (iface->can_iface_->select(read, write, &frame, 0)) { msk.read |= (read ? 1 : 0) << i; msk.write |= (write ? 1 : 0) << i; diff --git a/libraries/AP_UAVCAN/AP_UAVCAN_pool.cpp b/libraries/AP_UAVCAN/AP_UAVCAN_pool.cpp new file mode 100644 index 00000000000..2f68ab955cc --- /dev/null +++ b/libraries/AP_UAVCAN/AP_UAVCAN_pool.cpp @@ -0,0 +1,89 @@ +/* + * This file is free software: you can redistribute it and/or modify it + * under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program. If not, see . + * + */ +/* + based on dynamic_memory.hpp which is: + Copyright (C) 2014 Pavel Kirienko + */ + +#include + +#if HAL_ENABLE_LIBUAVCAN_DRIVERS + +#include "AP_UAVCAN.h" +#include "AP_UAVCAN_pool.h" + +AP_PoolAllocator::AP_PoolAllocator(uint16_t _pool_size) : + num_blocks(_pool_size / UAVCAN_NODE_POOL_BLOCK_SIZE) +{ +} + +bool AP_PoolAllocator::init(void) +{ + WITH_SEMAPHORE(sem); + pool_nodes = (Node *)calloc(num_blocks, UAVCAN_NODE_POOL_BLOCK_SIZE); + if (pool_nodes == nullptr) { + return false; + } + for (uint16_t i=0; i<(num_blocks-1); i++) { + pool_nodes[i].next = &pool_nodes[i+1]; + } + free_list = &pool_nodes[0]; + return true; +} + +void* AP_PoolAllocator::allocate(std::size_t size) +{ + WITH_SEMAPHORE(sem); + if (free_list == nullptr || size > UAVCAN_NODE_POOL_BLOCK_SIZE) { + return nullptr; + } + Node *ret = free_list; + const uint32_t blk = ret - pool_nodes; + if (blk >= num_blocks) { + INTERNAL_ERROR(AP_InternalError::error_t::mem_guard); + return nullptr; + } + free_list = free_list->next; + + used++; + if (used > max_used) { + max_used = used; + } + + return ret; +} + +void AP_PoolAllocator::deallocate(const void* ptr) +{ + if (ptr == nullptr) { + return; + } + WITH_SEMAPHORE(sem); + + Node *p = reinterpret_cast(const_cast(ptr)); + const uint32_t blk = p - pool_nodes; + if (blk >= num_blocks) { + INTERNAL_ERROR(AP_InternalError::error_t::mem_guard); + return; + } + p->next = free_list; + free_list = p; + + used--; +} + +#endif // HAL_ENABLE_LIBUAVCAN_DRIVERS + diff --git a/libraries/AP_UAVCAN/AP_UAVCAN_pool.h b/libraries/AP_UAVCAN/AP_UAVCAN_pool.h new file mode 100644 index 00000000000..2549526bb79 --- /dev/null +++ b/libraries/AP_UAVCAN/AP_UAVCAN_pool.h @@ -0,0 +1,60 @@ +/* + * This file is free software: you can redistribute it and/or modify it + * under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program. If not, see . + * + */ +/* + based on dynamic_memory.hpp which is: + Copyright (C) 2014 Pavel Kirienko + */ + +#pragma once + +#include "AP_UAVCAN.h" + +#ifndef UAVCAN_NODE_POOL_BLOCK_SIZE +#if HAL_CANFD_SUPPORTED +#define UAVCAN_NODE_POOL_BLOCK_SIZE 128 +#else +#define UAVCAN_NODE_POOL_BLOCK_SIZE 64 +#endif +#endif + +class AP_PoolAllocator : public uavcan::IPoolAllocator +{ +public: + AP_PoolAllocator(uint16_t _pool_size); + + bool init(void); + void *allocate(std::size_t size) override; + void deallocate(const void* ptr) override; + + uint16_t getBlockCapacity() const override { + return num_blocks; + } + +private: + const uint16_t num_blocks; + + union Node { + uint8_t data[UAVCAN_NODE_POOL_BLOCK_SIZE]; + Node* next; + }; + + Node *free_list; + Node *pool_nodes; + HAL_Semaphore sem; + + uint16_t used; + uint16_t max_used; +}; diff --git a/libraries/AP_Vehicle/AP_Vehicle.cpp b/libraries/AP_Vehicle/AP_Vehicle.cpp index 338081b6c9b..807f8255972 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.cpp +++ b/libraries/AP_Vehicle/AP_Vehicle.cpp @@ -4,10 +4,17 @@ #include #include #include +#include #include #include +#include +#include +#include +#include +#include #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS #include +#include #endif #define SCHED_TASK(func, rate_hz, max_time_micros, prio) SCHED_TASK_CLASS(AP_Vehicle, &vehicle, func, rate_hz, max_time_micros, prio) @@ -73,6 +80,33 @@ const AP_Param::GroupInfo AP_Vehicle::var_info[] = { AP_SUBGROUPINFO(airspeed, "ARSPD", 10, AP_Vehicle, AP_Airspeed), #endif + // @Group: CUST_ROT + // @Path: ../AP_CustomRotations/AP_CustomRotations.cpp + AP_SUBGROUPINFO(custom_rotations, "CUST_ROT", 11, AP_Vehicle, AP_CustomRotations), + +#if HAL_WITH_ESC_TELEM + // @Group: ESC_TLM + // @Path: ../AP_ESC_Telem/AP_ESC_Telem.cpp + AP_SUBGROUPINFO(esc_telem, "ESC_TLM", 12, AP_Vehicle, AP_ESC_Telem), +#endif + +#if AP_AIS_ENABLED + // @Group: AIS_ + // @Path: ../AP_AIS/AP_AIS.cpp + AP_SUBGROUPINFO(ais, "AIS_", 13, AP_Vehicle, AP_AIS), +#endif + +#if AP_FENCE_ENABLED + // @Group: FENCE_ + // @Path: ../AC_Fence/AC_Fence.cpp + AP_SUBGROUPINFO(fence, "FENCE_", 14, AP_Vehicle, AC_Fence), +#endif + +#if AP_OPENDRONEID_ENABLED + // @Group: DID_ + // @Path: ../AP_OpenDroneID/AP_OpenDroneID.cpp + AP_SUBGROUPINFO(opendroneid, "DID_", 15, AP_Vehicle, AP_OpenDroneID), +#endif AP_GROUPEND }; @@ -94,11 +128,15 @@ void AP_Vehicle::setup() // initialise serial port serial_manager.init_console(); - hal.console->printf("\n\nInit %s" + DEV_PRINTF("\n\nInit %s" "\n\nFree RAM: %u\n", AP::fwversion().fw_string, (unsigned)hal.util->available_memory()); +#if AP_CHECK_FIRMWARE_ENABLED + check_firmware_print(); +#endif + load_parameters(); #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS @@ -189,6 +227,10 @@ void AP_Vehicle::setup() smartaudio.init(); #endif +#if AP_TRAMP_ENABLED + tramp.init(); +#endif + #if AP_PARAM_KEY_DUMP AP_Param::show_all(hal.console, true); #endif @@ -199,11 +241,25 @@ void AP_Vehicle::setup() generator.init(); #endif +#if AP_OPENDRONEID_ENABLED + opendroneid.init(); +#endif + // init EFI monitoring #if HAL_EFI_ENABLED efi.init(); #endif +#if AP_AIS_ENABLED + ais.init(); +#endif + +#if AP_FENCE_ENABLED + fence.init(); +#endif + + custom_rotations.init(); + gcs().send_text(MAV_SEVERITY_INFO, "ArduPilot Ready"); } @@ -237,16 +293,6 @@ void AP_Vehicle::loop() } } -/* - fast loop callback for all vehicles. This will get called at the end of any vehicle-specific fast loop. - */ -void AP_Vehicle::fast_loop() -{ -#if HAL_GYROFFT_ENABLED - gyro_fft.sample_gyros(); -#endif -} - /* scheduler table - all regular tasks apart from the fast_loop() should be listed here. @@ -274,9 +320,15 @@ SCHED_TASK_CLASS arguments: */ const AP_Scheduler::Task AP_Vehicle::scheduler_tasks[] = { +#if HAL_GYROFFT_ENABLED + FAST_TASK_CLASS(AP_GyroFFT, &vehicle.gyro_fft, sample_gyros), +#endif #if AP_AIRSPEED_ENABLED SCHED_TASK_CLASS(AP_Airspeed, &vehicle.airspeed, update, 10, 100, 41), // NOTE: the priority number here should be right before Plane's calc_airspeed_errors #endif +#if COMPASS_CAL_ENABLED + SCHED_TASK_CLASS(Compass, &vehicle.compass, cal_update, 100, 200, 75), +#endif #if HAL_RUNCAM_ENABLED SCHED_TASK_CLASS(AP_RunCam, &vehicle.runcam, update, 50, 50, 200), #endif @@ -286,20 +338,38 @@ const AP_Scheduler::Task AP_Vehicle::scheduler_tasks[] = { #endif SCHED_TASK(update_dynamic_notch_at_specified_rate, LOOP_RATE, 200, 215), SCHED_TASK_CLASS(AP_VideoTX, &vehicle.vtx, update, 2, 100, 220), +#if AP_TRAMP_ENABLED + SCHED_TASK_CLASS(AP_Tramp, &vehicle.tramp, update, 50, 50, 225), +#endif SCHED_TASK(send_watchdog_reset_statustext, 0.1, 20, 225), #if HAL_WITH_ESC_TELEM - SCHED_TASK_CLASS(AP_ESC_Telem, &vehicle.esc_telem, update, 10, 50, 230), + SCHED_TASK_CLASS(AP_ESC_Telem, &vehicle.esc_telem, update, 100, 50, 230), #endif #if HAL_GENERATOR_ENABLED SCHED_TASK_CLASS(AP_Generator, &vehicle.generator, update, 10, 50, 235), #endif +#if AP_OPENDRONEID_ENABLED + SCHED_TASK_CLASS(AP_OpenDroneID, &vehicle.opendroneid, update, 10, 50, 236), +#endif #if OSD_ENABLED SCHED_TASK(publish_osd_info, 1, 10, 240), #endif - SCHED_TASK(accel_cal_update, 10, 100, 245), +#if HAL_INS_ACCELCAL_ENABLED + SCHED_TASK(accel_cal_update, 10, 100, 245), +#endif +#if AP_FENCE_ENABLED + SCHED_TASK_CLASS(AC_Fence, &vehicle.fence, update, 10, 100, 248), +#endif +#if AP_AIS_ENABLED + SCHED_TASK_CLASS(AP_AIS, &vehicle.ais, update, 5, 100, 249), +#endif #if HAL_EFI_ENABLED - SCHED_TASK_CLASS(AP_EFI, &vehicle.efi, update, 10, 200, 250), + SCHED_TASK_CLASS(AP_EFI, &vehicle.efi, update, 50, 200, 250), #endif +#if HAL_INS_ACCELCAL_ENABLED + SCHED_TASK(one_Hz_update, 1, 100, 252), +#endif + SCHED_TASK(update_arming, 1, 50, 253), }; void AP_Vehicle::get_common_scheduler_tasks(const AP_Scheduler::Task*& tasks, uint8_t& num_tasks) @@ -385,20 +455,130 @@ bool AP_Vehicle::is_crashed() const return AP::arming().last_disarm_method() == AP_Arming::Method::CRASH; } -// run notch update at either loop rate or 200Hz -void AP_Vehicle::update_dynamic_notch_at_specified_rate() +// update the harmonic notch filter for throttle based notch +void AP_Vehicle::update_throttle_notch(AP_InertialSensor::HarmonicNotch ¬ch) +{ +#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI||APM_BUILD_TYPE(APM_BUILD_Rover) + const float ref_freq = notch.params.center_freq_hz(); + const float ref = notch.params.reference(); + const float min_ratio = notch.params.freq_min_ratio(); + +#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI + const AP_Motors* motors = AP::motors(); + const float motors_throttle = motors != nullptr ? MAX(0,motors->get_throttle_out()) : 0; +#else // APM_BUILD_Rover + const AP_MotorsUGV *motors = AP::motors_ugv(); + const float motors_throttle = motors != nullptr ? abs(motors->get_throttle() / 100.0f) : 0; +#endif + + float throttle_freq = ref_freq * MAX(min_ratio, sqrtf(motors_throttle / ref)); + + notch.update_freq_hz(throttle_freq); +#endif +} + +// update the harmonic notch filter center frequency dynamically +void AP_Vehicle::update_dynamic_notch(AP_InertialSensor::HarmonicNotch ¬ch) { - if (ins.has_harmonic_option(HarmonicNotchFilterParams::Options::LoopRateUpdate)) { - update_dynamic_notch(); +#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI||APM_BUILD_TYPE(APM_BUILD_Rover) + if (!notch.params.enabled()) { + return; + } + const float ref_freq = notch.params.center_freq_hz(); + const float ref = notch.params.reference(); + if (is_zero(ref)) { + notch.update_freq_hz(ref_freq); return; } - // decimated update at 200Hz - const uint32_t now = AP_HAL::millis(); +#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI + const AP_Motors* motors = AP::motors(); + if (motors != nullptr && motors->get_spool_state() == AP_Motors::SpoolState::SHUT_DOWN) { + notch.set_inactive(true); + } else { + notch.set_inactive(false); + } +#else // APM_BUILD_Rover: keep notch active + notch.set_inactive(false); +#endif + + switch (notch.params.tracking_mode()) { + case HarmonicNotchDynamicMode::UpdateThrottle: // throttle based tracking + // set the harmonic notch filter frequency approximately scaled on motor rpm implied by throttle + update_throttle_notch(notch); + break; + + case HarmonicNotchDynamicMode::UpdateRPM: // rpm sensor based tracking + case HarmonicNotchDynamicMode::UpdateRPM2: { + const auto *rpm_sensor = AP::rpm(); + uint8_t sensor = (notch.params.tracking_mode()==HarmonicNotchDynamicMode::UpdateRPM?0:1); + float rpm; + if (rpm_sensor != nullptr && rpm_sensor->get_rpm(sensor, rpm)) { + // set the harmonic notch filter frequency from the main rotor rpm + notch.update_freq_hz(MAX(ref_freq, rpm * ref * (1.0/60))); + } else { + notch.update_freq_hz(ref_freq); + } + break; + } +#if HAL_WITH_ESC_TELEM + case HarmonicNotchDynamicMode::UpdateBLHeli: // BLHeli based tracking + // set the harmonic notch filter frequency scaled on measured frequency + if (notch.params.hasOption(HarmonicNotchFilterParams::Options::DynamicHarmonic)) { + float notches[INS_MAX_NOTCHES]; + // ESC telemetry will return 0 for missing data, but only after 1s + const uint8_t num_notches = AP::esc_telem().get_motor_frequencies_hz(INS_MAX_NOTCHES, notches); + for (uint8_t i = 0; i < num_notches; i++) { + if (!is_zero(notches[i])) { + notches[i] = MAX(ref_freq, notches[i]); + } + } + if (num_notches > 0) { + notch.update_frequencies_hz(num_notches, notches); + } else { // throttle fallback + update_throttle_notch(notch); + } + } else { + notch.update_freq_hz(MAX(ref_freq, AP::esc_telem().get_average_motor_frequency_hz() * ref)); + } + break; +#endif +#if HAL_GYROFFT_ENABLED + case HarmonicNotchDynamicMode::UpdateGyroFFT: // FFT based tracking + // set the harmonic notch filter frequency scaled on measured frequency + if (notch.params.hasOption(HarmonicNotchFilterParams::Options::DynamicHarmonic)) { + float notches[INS_MAX_NOTCHES]; + const uint8_t peaks = gyro_fft.get_weighted_noise_center_frequencies_hz(notch.num_dynamic_notches, notches); + + notch.update_frequencies_hz(peaks, notches); + } else { + notch.update_freq_hz(gyro_fft.get_weighted_noise_center_freq_hz()); + } + break; +#endif + case HarmonicNotchDynamicMode::Fixed: // static + default: + notch.update_freq_hz(ref_freq); + break; + } +#endif // APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI||APM_BUILD_TYPE(APM_BUILD_Rover) +} - if (now - _last_notch_update_ms > 5) { - _last_notch_update_ms = now; - update_dynamic_notch(); +// run notch update at either loop rate or 200Hz +void AP_Vehicle::update_dynamic_notch_at_specified_rate() +{ + for (auto ¬ch : ins.harmonic_notches) { + if (notch.params.hasOption(HarmonicNotchFilterParams::Options::LoopRateUpdate)) { + update_dynamic_notch(notch); + } else { + // decimated update at 200Hz + const uint32_t now = AP_HAL::millis(); + const uint8_t i = ¬ch - &ins.harmonic_notches[0]; + if (now - _last_notch_update_ms[i] > 5) { + _last_notch_update_ms[i] = now; + update_dynamic_notch(notch); + } + } } } @@ -467,6 +647,7 @@ void AP_Vehicle::publish_osd_info() nav_info.wp_number = mission->get_current_nav_index(); osd->set_nav_info(nav_info); } +#endif void AP_Vehicle::get_osd_roll_pitch_rad(float &roll, float &pitch) const { @@ -474,7 +655,7 @@ void AP_Vehicle::get_osd_roll_pitch_rad(float &roll, float &pitch) const pitch = ahrs.pitch; } -#endif +#if HAL_INS_ACCELCAL_ENABLED #ifndef HAL_CAL_ALWAYS_REBOOT // allow for forced reboot after accelcal @@ -486,7 +667,6 @@ void AP_Vehicle::get_osd_roll_pitch_rad(float &roll, float &pitch) const */ void AP_Vehicle::accel_cal_update() { -#if HAL_INS_ENABLED if (hal.util->get_soft_armed()) { return; } @@ -504,7 +684,43 @@ void AP_Vehicle::accel_cal_update() hal.scheduler->reboot(false); } #endif -#endif // HAL_INS_ENABLED +} +#endif // HAL_INS_ACCELCAL_ENABLED + +// call the arming library's update function +void AP_Vehicle::update_arming() +{ + AP::arming().update(); +} + +/* + one Hz checks common to all vehicles + */ +void AP_Vehicle::one_Hz_update(void) +{ + one_Hz_counter++; + + /* + every 10s check if using a 2M firmware on a 1M board + */ + if (one_Hz_counter % 10U == 0) { +#if defined(BOARD_CHECK_F427_USE_1M) && (BOARD_FLASH_SIZE>1024) + if (!hal.util->get_soft_armed() && check_limit_flash_1M()) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, BOARD_CHECK_F427_USE_1M); + } +#endif + } + + /* + every 30s check if using a 1M firmware on a 2M board + */ + if (one_Hz_counter % 30U == 0) { +#if defined(BOARD_CHECK_F427_USE_1M) && (BOARD_FLASH_SIZE<=1024) + if (!hal.util->get_soft_armed() && !check_limit_flash_1M()) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, BOARD_CHECK_F427_USE_2M); + } +#endif + } } AP_Vehicle *AP_Vehicle::_singleton = nullptr; @@ -522,3 +738,4 @@ AP_Vehicle *vehicle() } }; + diff --git a/libraries/AP_Vehicle/AP_Vehicle.h b/libraries/AP_Vehicle/AP_Vehicle.h index a93746e2320..eb74e07f192 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.h +++ b/libraries/AP_Vehicle/AP_Vehicle.h @@ -21,14 +21,16 @@ #include "ModeReason.h" // reasons can't be defined in this header due to circular loops +#include +#include #include #include // board configuration library #include #include +#include #include #include #include -#include #include // Notify library #include #include @@ -38,6 +40,7 @@ #include // Serial manager library #include #include +#include #include #include #include @@ -47,9 +50,12 @@ #include #include #include -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#include #include -#endif +#include +#include +#include +#include class AP_Vehicle : public AP_HAL::HAL::Callbacks { @@ -208,6 +214,7 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks { // get target location (for use by scripting) virtual bool get_target_location(Location& target_loc) { return false; } + virtual bool update_target_location(const Location &old_loc, const Location &new_loc) { return false; } // circle mode controls (only used by scripting with Copter) virtual bool get_circle_radius(float &radius_m) { return false; } @@ -219,10 +226,18 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks { // set turn rate in deg/sec and speed in meters/sec (for use by scripting with Rover) virtual bool set_desired_turn_rate_and_speed(float turn_rate, float speed) { return false; } + // set auto mode speed in meters/sec (for use by scripting with Copter/Rover) + virtual bool set_desired_speed(float speed) { return false; } + // support for NAV_SCRIPT_TIME mission command virtual bool nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2) { return false; } virtual void nav_script_time_done(uint16_t id) {} + // allow for VTOL velocity matching of a target + virtual bool set_velocity_match(const Vector2f &velocity) { return false; } + + // returns true if the EKF failsafe has triggered + virtual bool has_ekf_failsafed() const { return false; } // control outputs enumeration enum class ControlOutput { @@ -243,9 +258,6 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks { #endif // AP_SCRIPTING_ENABLED - // update the harmonic notch - virtual void update_dynamic_notch() {}; - // zeroing the RC outputs can prevent unwanted motor movement: virtual bool should_zero_rc_outputs_on_reboot() const { return false; } @@ -280,10 +292,13 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks { */ virtual bool get_pan_tilt_norm(float &pan_norm, float &tilt_norm) const { return false; } -#if OSD_ENABLED // Returns roll and pitch for OSD Horizon, Plane overrides to correct for VTOL view and fixed wing TRIM_PITCH_CD virtual void get_osd_roll_pitch_rad(float &roll, float &pitch) const; -#endif + + /* + get the target earth-frame angular velocities in rad/s (Z-axis component used by some gimbals) + */ + virtual bool get_rate_ef_targets(Vector3f& rate_ef_targets) const { return false; } protected: @@ -300,8 +315,7 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks { #endif // main loop scheduler - AP_Scheduler scheduler{FUNCTOR_BIND_MEMBER(&AP_Vehicle::fast_loop, void)}; - virtual void fast_loop(); + AP_Scheduler scheduler; // IMU variables // Integration time; time last loop took to run @@ -350,6 +364,10 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks { AP_ESC_Telem esc_telem; #endif +#if AP_OPENDRONEID_ENABLED + AP_OpenDroneID opendroneid; +#endif + #if HAL_MSP_ENABLED AP_MSP msp; #endif @@ -366,6 +384,10 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks { AP_SmartAudio smartaudio; #endif +#if AP_TRAMP_ENABLED + AP_Tramp tramp; +#endif + #if HAL_EFI_ENABLED // EFI Engine Monitor AP_EFI efi; @@ -375,6 +397,15 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks { AP_Airspeed airspeed; #endif +#if AP_AIS_ENABLED + // Automatic Identification System - for tracking sea-going vehicles + AP_AIS ais; +#endif + +#if AP_FENCE_ENABLED + AC_Fence fence; +#endif + static const struct AP_Param::GroupInfo var_info[]; static const struct AP_Scheduler::Task scheduler_tasks[]; @@ -382,12 +413,17 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks { void publish_osd_info(); #endif +#if HAL_INS_ACCELCAL_ENABLED // update accel calibration void accel_cal_update(); +#endif + + // call the arming library's update function + void update_arming(); ModeReason control_mode_reason = ModeReason::UNKNOWN; -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#if AP_SIM_ENABLED SITL::SIM sitl; #endif @@ -400,18 +436,31 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks { // statustext: void send_watchdog_reset_statustext(); + // update the harmonic notch for throttle based notch + void update_throttle_notch(AP_InertialSensor::HarmonicNotch ¬ch); + + // update the harmonic notch + void update_dynamic_notch(AP_InertialSensor::HarmonicNotch ¬ch); + // run notch update at either loop rate or 200Hz void update_dynamic_notch_at_specified_rate(); + // decimation for 1Hz update + uint8_t one_Hz_counter; + void one_Hz_update(); + bool likely_flying; // true if vehicle is probably flying uint32_t _last_flying_ms; // time when likely_flying last went true - uint32_t _last_notch_update_ms; // last time update_dynamic_notch() was run + uint32_t _last_notch_update_ms[HAL_INS_NUM_HARMONIC_NOTCH_FILTERS]; // last time update_dynamic_notch() was run static AP_Vehicle *_singleton; bool done_safety_init; + uint32_t _last_internal_errors; // backup of AP_InternalError::internal_errors bitmask + + AP_CustomRotations custom_rotations; }; namespace AP { diff --git a/libraries/AP_Vehicle/ModeReason.h b/libraries/AP_Vehicle/ModeReason.h index c0e431ec84c..905b2697d70 100644 --- a/libraries/AP_Vehicle/ModeReason.h +++ b/libraries/AP_Vehicle/ModeReason.h @@ -66,4 +66,6 @@ enum class ModeReason : uint8_t { LOITER_ALT_REACHED_QLAND = 46, LOITER_ALT_IN_VTOL = 47, RADIO_FAILSAFE_RECOVERY = 48, + QLAND_INSTEAD_OF_RTL = 49, + DEADRECKON_FAILSAFE = 50, }; diff --git a/libraries/AP_VideoTX/AP_SmartAudio.cpp b/libraries/AP_VideoTX/AP_SmartAudio.cpp index bcb848c3335..846e4b1f79d 100644 --- a/libraries/AP_VideoTX/AP_SmartAudio.cpp +++ b/libraries/AP_VideoTX/AP_SmartAudio.cpp @@ -51,7 +51,7 @@ bool AP_SmartAudio::init() _port = AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_SmartAudio, 0); if (_port!=nullptr) { _port->configure_parity(0); - _port->set_stop_bits(2); + _port->set_stop_bits(AP::vtx().has_option(AP_VideoTX::VideoOptions::VTX_SA_ONE_STOP_BIT) ? 1 : 2); _port->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE); _port->set_options((_port->get_options() & ~AP_HAL::UARTDriver::OPTION_RXINV) | AP_HAL::UARTDriver::OPTION_HDPLEX | AP_HAL::UARTDriver::OPTION_PULLDOWN_TX | AP_HAL::UARTDriver::OPTION_PULLDOWN_RX); @@ -123,9 +123,13 @@ void AP_SmartAudio::loop() // and the initial response is 40ms long so we should wait at least 140ms before giving up if (now - _last_request_sent_ms < 200 && _is_waiting_response) { - // setup sheduler delay to 50 ms again after response processes + // setup scheduler delay to 50 ms again after response processes if (!read_response(_response_buffer)) { hal.scheduler->delay(10); + } else { + // successful response, wait another 100ms to give the VTX a chance to recover + // before sending another command. This is needed on the Atlatl v1. + hal.scheduler->delay(100); } } else if (_is_waiting_response) { // timeout @@ -134,13 +138,14 @@ void AP_SmartAudio::loop() _port->discard_input(); _inline_buffer_length = 0; _is_waiting_response = false; - } else { + debug("response timeout"); + } else if (_initialised) { if (AP::vtx().have_params_changed() ||_vtx_power_change_pending || _vtx_freq_change_pending || _vtx_options_change_pending) { update_vtx_params(); set_configuration_pending(true); vtx.set_configuration_finished(false); - // we've tried to udpate something, re-request the settings so that they + // we've tried to update something, re-request the settings so that they // are reflected correctly request_settings(); } else if (is_configuration_pending()) { @@ -176,22 +181,20 @@ void AP_SmartAudio::update_vtx_params() vtx.get_channel(), vtx.get_configured_channel(), vtx.get_band(), vtx.get_configured_band(), vtx.get_power_mw(), vtx.get_configured_power_mw(), - vtx.get_options(), vtx.get_configured_options()); + vtx.get_options() & 0xF, vtx.get_configured_options() & 0xF); uint8_t opts = vtx.get_configured_options(); - uint8_t pitModeRunning = (vtx.get_options() & uint8_t(AP_VideoTX::VideoOptions::VTX_PITMODE)); - uint8_t pitMode = opts & uint8_t(AP_VideoTX::VideoOptions::VTX_PITMODE); + uint8_t pitMode = vtx.get_configured_pitmode(); uint8_t mode; - // check if we are turning pitmode on or off, but only on SA 2.1 as older versions - // appear not to work properly - if (pitMode != pitModeRunning && _protocol_version >= SMARTAUDIO_SPEC_PROTOCOL_v21) { - if (pitModeRunning) { + // check if we are turning pitmode on or off, but only on SA 2.0+ + if (pitMode != vtx.get_pitmode() && _protocol_version >= SMARTAUDIO_SPEC_PROTOCOL_v2) { + if (vtx.get_pitmode()) { debug("Turning OFF pitmode"); // turn it off mode = 0x04 | ((opts & uint8_t(AP_VideoTX::VideoOptions::VTX_UNLOCKED)) << 2); } else { debug("Turning ON pitmode"); - // turn it on + // turn it on (in range pitmode flag) mode = 0x01 | ((opts & uint8_t(AP_VideoTX::VideoOptions::VTX_UNLOCKED)) << 2); } } else { @@ -218,7 +221,7 @@ void AP_SmartAudio::update_vtx_params() set_channel(vtx.get_configured_band() * VTX_MAX_CHANNELS + vtx.get_configured_channel()); } } else if (_vtx_power_change_pending) { - debug("update power"); + debug("update power (ver %u)", _protocol_version); switch (_protocol_version) { case SMARTAUDIO_SPEC_PROTOCOL_v21: set_power(vtx.get_configured_power_dbm() | 0x80); @@ -264,7 +267,7 @@ void AP_SmartAudio::send_request(const Frame& requestFrame, uint8_t size) _packets_sent++; #ifdef SA_DEBUG - print_bytes_to_hex_string("send_request():", request, size,0); + print_bytes_to_hex_string("send_request():", request, size); #endif } @@ -316,6 +319,10 @@ bool AP_SmartAudio::read_response(uint8_t *response_buffer) FrameHeader* header = (FrameHeader*)response_buffer; incoming_bytes_count -= response_header_size; + // implementations that ignore the CRC also appear to not account for it in the frame length + if (ignore_crc()) { + header->length++; + } _packet_size = header->length; } @@ -339,12 +346,12 @@ bool AP_SmartAudio::read_response(uint8_t *response_buffer) } #ifdef SA_DEBUG - print_bytes_to_hex_string("read_response():", response_buffer, incoming_bytes_count,(_inline_buffer_length-incoming_bytes_count)>=0?(_inline_buffer_length-incoming_bytes_count):0); + print_bytes_to_hex_string("read_response():", response_buffer, _inline_buffer_length); #endif - _is_waiting_response=false; + _is_waiting_response = false; bool correct_parse = parse_response_buffer(response_buffer); - response_buffer=nullptr; + response_buffer = nullptr; _inline_buffer_length=0; _packet_size = 0; _packets_rcvd++; @@ -357,6 +364,8 @@ bool AP_SmartAudio::read_response(uint8_t *response_buffer) void AP_SmartAudio::push_command_only_frame(uint8_t cmd_id) { Packet command; + // according to the spec the length should include the CRC, but no implementation appears to + // do this command.frame.header.init(cmd_id, 0); command.frame_size = SMARTAUDIO_COMMAND_FRAME_SIZE; command.frame.payload[0] = crc8_dvb_s2_update(0, &command.frame, SMARTAUDIO_COMMAND_FRAME_SIZE - 1); @@ -451,31 +460,32 @@ void AP_SmartAudio::unpack_frequency(AP_SmartAudio::Settings *settings, const ui } } +// SmartAudio v1/v2 void AP_SmartAudio::unpack_settings(Settings *settings, const SettingsResponseFrame *frame) { settings->channel = frame->channel % VTX_MAX_CHANNELS; settings->band = frame->channel / VTX_MAX_CHANNELS; settings->power = frame->power; settings->mode = frame->operationMode; + settings->num_power_levels = 0; unpack_frequency(settings, be16toh(frame->frequency)); } +// SmartAudio v2.1 void AP_SmartAudio::unpack_settings(Settings *settings, const SettingsExtendedResponseFrame *frame) { - settings->channel = frame->channel % VTX_MAX_CHANNELS; - settings->band = frame->channel / VTX_MAX_CHANNELS; - settings->power = frame->power; - settings->power_in_dbm=frame->power_dbm; - settings->mode = frame->operationMode; - unpack_frequency(settings, be16toh(frame->frequency)); + unpack_settings(settings, &frame->settings); + settings->power_in_dbm = frame->power_dbm; + settings->num_power_levels = frame->num_power_levels + 1; + memcpy(settings->power_levels, frame->power_levels, frame->num_power_levels + 1); } #ifdef SA_DEBUG -void AP_SmartAudio::print_bytes_to_hex_string(const char* msg, const uint8_t buf[], uint8_t len,uint8_t offset) +void AP_SmartAudio::print_bytes_to_hex_string(const char* msg, const uint8_t buf[], uint8_t len) { hal.console->printf("SA: %s ", msg); for (uint8_t i = 0; i < len; i++) { - hal.console->printf("0x%02X ", buf[i+offset]); + hal.console->printf("0x%02X ", buf[i]); } hal.console->printf("\n"); } @@ -485,11 +495,11 @@ void AP_SmartAudio::print_settings(const Settings* settings) { debug("SETTINGS: VER: %u, MD: '%c%c%c%c%c', CH: %u, PWR: %u, DBM: %u FREQ: %u, BND: %u", settings->version, - (settings->mode & 0x10) ? 'U' : 'L', - (settings->mode & 0x8) ? 'O' : ' ', - (settings->mode & 0x4) ? 'I' : ' ', - (settings->mode & 0x2) ? 'P' : ' ', - (settings->mode & 0x1) ? 'F' : 'C', + (settings->mode & 0x10) ? 'U' : 'L',// (L)ocked or (U)nlocked + (settings->mode & 0x8) ? 'O' : ' ', // (O)ut-range pitmode + (settings->mode & 0x4) ? 'I' : ' ', // (I)n-range pitmode + (settings->mode & 0x2) ? 'P' : ' ', // (P)itmode running + (settings->mode & 0x1) ? 'F' : 'C', // Set (F)requency or (C)hannel settings->channel, settings->power, settings->power_in_dbm, settings->frequency, settings->band); } @@ -501,10 +511,13 @@ void AP_SmartAudio::update_vtx_settings(const Settings& settings) vtx.set_frequency_mhz(settings.frequency); vtx.set_band(settings.band); vtx.set_channel(settings.channel); + // SA21 sends us a complete packet with the supported power levels if (settings.version == SMARTAUDIO_SPEC_PROTOCOL_v21) { vtx.set_power_dbm(settings.power_in_dbm); + // learn them all + vtx.update_all_power_dbm(settings.num_power_levels, settings.power_levels); } else { - vtx.set_power_level(settings.power); + vtx.set_power_level(settings.power, AP_VideoTX::PowerActive::Active); } // it seems like the spec is wrong, on a unify pro32 this setting is inverted _vtx_use_set_freq = !(settings.mode & 1); @@ -530,9 +543,10 @@ bool AP_SmartAudio::parse_response_buffer(const uint8_t *buffer) const uint8_t *startPtr = buffer + 2; const uint8_t *endPtr = buffer + headerPayloadLength; - if (crc8_dvb_s2_update(0x00, startPtr, headerPayloadLength-2)!=*(endPtr) + if ((crc8_dvb_s2_update(0x00, startPtr, headerPayloadLength-2)!=*(endPtr) && !ignore_crc()) || header->headerByte != SMARTAUDIO_HEADER_BYTE - || header->syncByte!=SMARTAUDIO_SYNC_BYTE) { + || header->syncByte != SMARTAUDIO_SYNC_BYTE) { + debug("parse_response_buffer() failed - invalid CRC or header"); return false; } // SEND TO GCS A MESSAGE TO UNDERSTAND WHATS HAPPENING @@ -590,20 +604,24 @@ bool AP_SmartAudio::parse_response_buffer(const uint8_t *buffer) const uint8_t power = resp->payload & 0xFF; switch (_protocol_version) { case SMARTAUDIO_SPEC_PROTOCOL_v21: + if (vtx.get_configured_power_dbm() != power) { + vtx.update_power_dbm(vtx.get_configured_power_dbm(), AP_VideoTX::PowerActive::Inactive); + } vtx.set_power_dbm(power); vtx.set_configured_power_mw(vtx.get_power_mw()); break; case SMARTAUDIO_SPEC_PROTOCOL_v2: + if (vtx.get_configured_power_level() != power) { + vtx.update_power_dbm(vtx.get_configured_power_dbm(), AP_VideoTX::PowerActive::Inactive); + } vtx.set_power_level(power); vtx.set_configured_power_mw(vtx.get_power_mw()); break; default: - switch(power) { - case 16: vtx.set_power_level(1); break; // 200mw - case 25: vtx.set_power_level(2); break; // 500mw - case 40: vtx.set_power_level(3); break; // 800mw - default: vtx.set_power_level(0); break; // 25mw + if (vtx.get_configured_power_dac() != power) { + vtx.update_power_dbm(vtx.get_configured_power_dbm(), AP_VideoTX::PowerActive::Inactive); } + vtx.set_power_dac(power); vtx.set_configured_power_mw(vtx.get_power_mw()); break; } diff --git a/libraries/AP_VideoTX/AP_SmartAudio.h b/libraries/AP_VideoTX/AP_SmartAudio.h index 9c9966932db..6306aa84794 100644 --- a/libraries/AP_VideoTX/AP_SmartAudio.h +++ b/libraries/AP_VideoTX/AP_SmartAudio.h @@ -66,7 +66,7 @@ #define SMARTAUDIO_BANDCHAN_TO_INDEX(band, channel) (band * VTX_MAX_CHANNELS + (channel)) -// #define SA_DEBUG +//#define SA_DEBUG class AP_SmartAudio { @@ -85,7 +85,8 @@ class AP_SmartAudio uint16_t frequency; uint8_t band; - uint8_t* power_levels; + uint8_t num_power_levels; + uint8_t power_levels[8]; uint8_t power_in_dbm; uint16_t pitmodeFrequency; @@ -136,14 +137,10 @@ class AP_SmartAudio } PACKED; struct SettingsExtendedResponseFrame { - FrameHeader header; - uint8_t channel; - uint8_t power; - uint8_t operationMode; - uint16_t frequency; - uint8_t power_dbm; - uint8_t power_levels_len; - uint8_t power_dbm_levels; // first in the list of dbm levels + SettingsResponseFrame settings; + uint8_t power_dbm; // current power + uint8_t num_power_levels; + uint8_t power_levels[8]; // first in the list of dbm levels //uint8_t crc; } PACKED; @@ -217,13 +214,15 @@ class AP_SmartAudio #ifdef SA_DEBUG // utility method for debugging. - void print_bytes_to_hex_string(const char* msg, const uint8_t buf[], uint8_t x,uint8_t offset); + void print_bytes_to_hex_string(const char* msg, const uint8_t buf[], uint8_t length); #endif void print_settings(const Settings* settings); void update_vtx_params(); void update_vtx_settings(const Settings& settings); + bool ignore_crc() const { return AP::vtx().has_option(AP_VideoTX::VideoOptions::VTX_SA_IGNORE_CRC); } + // looping over requests void loop(); // send a frame over the wire diff --git a/libraries/AP_VideoTX/AP_Tramp.cpp b/libraries/AP_VideoTX/AP_Tramp.cpp new file mode 100644 index 00000000000..59177274a1f --- /dev/null +++ b/libraries/AP_VideoTX/AP_Tramp.cpp @@ -0,0 +1,502 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + + Code by Andy Piper, ported from betaflight vtx_tramp +*/ + +#include "AP_Tramp.h" +#include +#include +#include + +#if AP_TRAMP_ENABLED + +#define AP_TRAMP_UART_BAUD 9600 +// request and response size is 16 bytes +#define AP_TRAMP_UART_BUFSIZE_RX 32 +#define AP_TRAMP_UART_BUFSIZE_TX 32 + +// Define periods between requests +#define TRAMP_MIN_REQUEST_PERIOD_US (200 * 1000) // 200ms +#define TRAMP_STATUS_REQUEST_PERIOD_US (1000 * 1000) // 1s + +//#define TRAMP_DEBUG +#ifdef TRAMP_DEBUG +# define debug(fmt, args...) do { hal.console->printf("TRAMP: " fmt "\n", ##args); } while (0) +#else +# define debug(fmt, args...) do {} while(0) +#endif + +extern const AP_HAL::HAL &hal; + +AP_Tramp::AP_Tramp() +{ + singleton = this; +} + +AP_Tramp *AP_Tramp::singleton; + +// Calculate tramp protocol checksum of provided buffer +uint8_t AP_Tramp::checksum(uint8_t *buf) +{ + uint8_t cksum = 0; + + for (int i = 1 ; i < TRAMP_BUF_SIZE - 2; i++) { + cksum += buf[i]; + } + + return cksum; +} + +// Send tramp protocol frame to device +void AP_Tramp::send_command(uint8_t cmd, uint16_t param) +{ + if (port == nullptr) { + return; + } + + memset(request_buffer, 0, ARRAY_SIZE(request_buffer)); + request_buffer[0] = 0x0F; + request_buffer[1] = cmd; + request_buffer[2] = param & 0xFF; + request_buffer[3] = (param >> 8) & 0xFF; + request_buffer[14] = checksum(request_buffer); + + port->write(request_buffer, TRAMP_BUF_SIZE); + port->flush(); + + debug("send command '%c': %u", cmd, param); +} + +// Process response and return code if valid else 0 +char AP_Tramp::handle_response(void) +{ + const uint8_t respCode = response_buffer[1]; + + switch (respCode) { + case 'r': { + const uint16_t min_freq = response_buffer[2]|(response_buffer[3] << 8); + // Check we're not reading the request (indicated by freq zero) + if (min_freq != 0) { + // Got response, update device limits + device_limits.rf_freq_min = min_freq; + device_limits.rf_freq_max = response_buffer[4]|(response_buffer[5] << 8); + device_limits.rf_power_max = response_buffer[6]|(response_buffer[7] << 8); + debug("device limits: min freq: %u, max freq: %u, max power %u", + unsigned(device_limits.rf_freq_min), unsigned(device_limits.rf_freq_max), unsigned(device_limits.rf_power_max)); + return 'r'; + } + break; + } + case 'v': { + const uint16_t freq = response_buffer[2]|(response_buffer[3] << 8); + // Check we're not reading the request (indicated by freq zero) + if (freq != 0) { + // Got response, update device status + const uint16_t power = response_buffer[4]|(response_buffer[5] << 8); + cur_control_mode = response_buffer[6]; // Currently only used for race lock + const bool pit_mode = response_buffer[7]; + cur_act_power = response_buffer[8]|(response_buffer[9] << 8); + + // update the vtx + AP_VideoTX& vtx = AP::vtx(); + bool update_pending = vtx.have_params_changed(); + vtx.set_frequency_mhz(freq); + + AP_VideoTX::VideoBand band; + uint8_t channel; + if (vtx.get_band_and_channel(freq, band, channel)) { + vtx.set_band(band); + vtx.set_channel(channel); + } + + vtx.set_power_mw(power); + if (pit_mode) { + vtx.set_options(vtx.get_options() | uint8_t(AP_VideoTX::VideoOptions::VTX_PITMODE)); + } else { + vtx.set_options(vtx.get_options() & ~uint8_t(AP_VideoTX::VideoOptions::VTX_PITMODE)); + } + + // make sure the configured values now reflect reality + // if they do then announce if there were changes + if (!vtx.set_defaults() && update_pending && !vtx.have_params_changed()) { + vtx.announce_vtx_settings(); + } + + debug("device config: freq: %u, power: %u, pitmode: %u", + unsigned(freq), unsigned(power), unsigned(pit_mode)); + + + return 'v'; + } + break; + } + case 's': { + const uint16_t temp = (int16_t)(response_buffer[6]|(response_buffer[7] << 8)); + // Check we're not reading the request (indicated by temp zero) + if (temp != 0) { + // Got response, update device status + cur_temp = temp; + return 's'; + } + break; + } + } + + // Likely reading a request, return zero to indicate not accepted + return 0; +} + +// Reset receiver state machine +void AP_Tramp::reset_receiver(void) +{ + receive_state = ReceiveState::S_WAIT_LEN; + receive_pos = 0; +} + +// returns completed response code or 0 +char AP_Tramp::receive_response() +{ + if (port == nullptr) { + return 0; + } + + // wait for complete packet + const uint16_t bytesNeeded = TRAMP_BUF_SIZE - receive_pos; + if (port->available() < bytesNeeded) { + return 0; + } + + // sanity check + if (bytesNeeded == 0) { + reset_receiver(); + return 0; + } + + for (uint16_t i = 0; i < bytesNeeded; i++) { + const int16_t b = port->read(); + if (b < 0) { + // uart claimed bytes available, but there were none + return 0; + } + const uint8_t c = uint8_t(b); + response_buffer[receive_pos++] = c; + + switch (receive_state) { + case ReceiveState::S_WAIT_LEN: { + if (c == 0x0F) { + // Found header byte, advance to wait for code + receive_state = ReceiveState::S_WAIT_CODE; + } else { + // Unexpected header, reset state machine + reset_receiver(); + } + break; + } + case ReceiveState::S_WAIT_CODE: { + if (c == 'r' || c == 'v' || c == 's') { + // Code is for response is one we're interested in, advance to data + receive_state = ReceiveState::S_DATA; + } else { + // Unexpected code, reset state machine + reset_receiver(); + } + break; + } + case ReceiveState::S_DATA: { + if (receive_pos == TRAMP_BUF_SIZE) { + // Buffer is full, calculate checksum + const uint8_t cksum = checksum(response_buffer); + + // Reset state machine ready for next response + reset_receiver(); + + if ((response_buffer[TRAMP_BUF_SIZE-2] == cksum) && (response_buffer[TRAMP_BUF_SIZE-1] == 0)) { + // Checksum is correct, process response + const char r = handle_response(); + + // Check response valid else keep on reading + if (r != 0) { + return r; + } + } + } + break; + } + default: + // Invalid state, reset state machine + reset_receiver(); + break; + } + } + + return 0; +} + +void AP_Tramp::send_query(uint8_t cmd) +{ + // Reset receive buffer and issue command + reset_receiver(); + send_command(cmd, 0); +} + +void AP_Tramp::set_status(TrampStatus _status) +{ + status = _status; +#ifdef TRAMP_DEBUG + switch (status) { + case TrampStatus::TRAMP_STATUS_OFFLINE: + debug("status: OFFLINE"); + break; + case TrampStatus::TRAMP_STATUS_INIT: + debug("status: INIT"); + break; + case TrampStatus::TRAMP_STATUS_ONLINE_MONITOR_FREQPWRPIT: + debug("status: ONLINE_MONITOR_FREQPWRPIT"); + break; + case TrampStatus::TRAMP_STATUS_ONLINE_MONITOR_TEMP: + debug("status: ONLINE_MONITOR_TEMP"); + break; + case TrampStatus::TRAMP_STATUS_ONLINE_CONFIG: + debug("status: ONLINE_CONFIG"); + break; + } +#endif +} + +void AP_Tramp::process_requests() +{ + if (port == nullptr) { + return; + } + + bool configUpdateRequired = false; + + // Read response from device + const char replyCode = receive_response(); + const uint32_t now = AP_HAL::micros(); + +#ifdef TRAMP_DEBUG + if (replyCode != 0) { + debug("receive response '%c'", replyCode); + } +#endif + + // Act on state + switch (status) { + case TrampStatus::TRAMP_STATUS_OFFLINE: { + // Offline, check for response + if (replyCode == 'r') { + // Device replied to reset? request, enter init + set_status(TrampStatus::TRAMP_STATUS_INIT); + } else if ((now - last_time_us) >= TRAMP_MIN_REQUEST_PERIOD_US) { + // Min request period exceeded, issue another reset? + send_query('r'); + + // Update last time + last_time_us = now; + } + break; + } + case TrampStatus::TRAMP_STATUS_INIT: { + // Initializing, check for response + if (replyCode == 'v') { + // Device replied to freq / power / pit query, enter online + set_status(TrampStatus::TRAMP_STATUS_ONLINE_MONITOR_FREQPWRPIT); + } else if ((now - last_time_us) >= TRAMP_MIN_REQUEST_PERIOD_US) { + // Min request period exceeded, issue another query + send_query('v'); + + // Update last time + last_time_us = now; + } + break; + } + case TrampStatus::TRAMP_STATUS_ONLINE_MONITOR_FREQPWRPIT: { + // Note after config a status update request is made, a new status + // request is made, this request is handled above and should prevent + // subsequent config updates if the config is now correct + if (retry_count > 0 && ((now - last_time_us) >= TRAMP_MIN_REQUEST_PERIOD_US)) { + AP_VideoTX& vtx = AP::vtx(); + // Config retries remain and min request period exceeded, check freq + if (!is_race_lock_enabled() && vtx.update_frequency()) { + // Freq can be and needs to be updated, issue request + send_command('F', vtx.get_configured_frequency_mhz()); + + // Set flag + configUpdateRequired = true; + } else if (!is_race_lock_enabled() && vtx.update_power()) { + // Power can be and needs to be updated, issue request + send_command('P', vtx.get_configured_power_mw()); + + // Set flag + configUpdateRequired = true; + } else if (vtx.update_options()) { + // Pit mode needs to be updated, issue request + send_command('I', vtx.has_option(AP_VideoTX::VideoOptions::VTX_PITMODE) ? 0 : 1); + + // Set flag + configUpdateRequired = true; + } + + if (configUpdateRequired) { + // Update required, decrement retry count + retry_count--; + + // Update last time + last_time_us = now; + + // Advance state + set_status(TrampStatus::TRAMP_STATUS_ONLINE_CONFIG); + } else { + // No update required, reset retry count + retry_count = 0; + } + } + + /* Was a config update made? */ + if (!configUpdateRequired) { + /* No, look to continue monitoring */ + if ((now - last_time_us) >= TRAMP_STATUS_REQUEST_PERIOD_US) { + // Request period exceeded, issue freq/power/pit query + send_query('v'); + + // Update last time + last_time_us = now; + } else if (replyCode == 'v') { + // Got reply, issue temp query + send_query('s'); + + // Wait for reply + set_status(TrampStatus::TRAMP_STATUS_ONLINE_MONITOR_TEMP); + + // Update last time + last_time_us = now; + } + } + + break; + } + case TrampStatus::TRAMP_STATUS_ONLINE_MONITOR_TEMP: { + // Check request time + if (replyCode == 's') { + // Got reply, return to request freq/power/pit + set_status(TrampStatus::TRAMP_STATUS_ONLINE_MONITOR_TEMP); + } else if ((now - last_time_us) >= TRAMP_MIN_REQUEST_PERIOD_US) { + // Timed out after min request period, return to request freq/power/pit query + set_status(TrampStatus::TRAMP_STATUS_ONLINE_MONITOR_FREQPWRPIT); + } + break; + } + case TrampStatus::TRAMP_STATUS_ONLINE_CONFIG: { + // Param should now be set, check time + if ((now - last_time_us) >= TRAMP_MIN_REQUEST_PERIOD_US) { + // Min request period exceeded, re-query + send_query('v'); + + // Advance state + set_status(TrampStatus::TRAMP_STATUS_ONLINE_MONITOR_FREQPWRPIT); + + // Update last time + last_time_us = now; + } + break; + } + default: + // Invalid state, reset + set_status(TrampStatus::TRAMP_STATUS_OFFLINE); + break; + } +} + +bool AP_Tramp::is_device_ready() +{ + return status >= TrampStatus::TRAMP_STATUS_ONLINE_MONITOR_FREQPWRPIT; +} + +void AP_Tramp::set_frequency(uint16_t freq) +{ + uint8_t freqValid; + + // Check frequency valid + if (device_limits.rf_freq_min != 0 && device_limits.rf_freq_max != 0) { + freqValid = (freq >= device_limits.rf_freq_min && freq <= device_limits.rf_freq_max); + } else { + freqValid = (freq >= VTX_TRAMP_MIN_FREQUENCY_MHZ && freq <= VTX_TRAMP_MAX_FREQUENCY_MHZ); + } + + // Is frequency valid? + if (freqValid) { + // Requested freq changed, reset retry count + retry_count = VTX_TRAMP_MAX_RETRIES; + } else { + debug("requested frequency %u is invalid", freq); + // not valid reset to default + AP::vtx().set_configured_frequency_mhz(AP::vtx().get_frequency_mhz()); + } +} + +void AP_Tramp::update() +{ + if (port == nullptr) { + return; + } + + AP_VideoTX& vtx = AP::vtx(); + + if (vtx.have_params_changed() && retry_count == 0) { + // check changes in the order they will be processed + if (vtx.update_frequency() || vtx.update_band() || vtx.update_channel()) { + if (vtx.update_frequency()) { + vtx.update_configured_channel_and_band(); + } else { + vtx.update_configured_frequency(); + } + set_frequency(vtx.get_configured_frequency_mhz()); + } + else if (vtx.update_power()) { + retry_count = VTX_TRAMP_MAX_RETRIES; + } + else if (vtx.update_options()) { + retry_count = VTX_TRAMP_MAX_RETRIES; + } + } + + process_requests(); +} + +bool AP_Tramp::init(void) +{ + if (AP::vtx().get_enabled() == 0) { + debug("protocol is not active"); + return false; + } + + // init uart + port = AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_Tramp, 0); + if (port != nullptr) { + port->configure_parity(0); + port->set_stop_bits(1); + port->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE); + port->set_options((port->get_options() & ~AP_HAL::UARTDriver::OPTION_RXINV)); + + port->begin(AP_TRAMP_UART_BAUD, AP_TRAMP_UART_BUFSIZE_RX, AP_TRAMP_UART_BUFSIZE_TX); + debug("port opened"); + + return true; + } + return false; +} + +#endif // VTX_TRAMP diff --git a/libraries/AP_VideoTX/AP_Tramp.h b/libraries/AP_VideoTX/AP_Tramp.h new file mode 100644 index 00000000000..ee9ddb72455 --- /dev/null +++ b/libraries/AP_VideoTX/AP_Tramp.h @@ -0,0 +1,142 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + + Code by Andy Piper, ported from betaflight vtx_tramp +*/ + +#pragma once + +#include +#include + +#ifndef AP_TRAMP_ENABLED +#define AP_TRAMP_ENABLED OSD_ENABLED && BOARD_FLASH_SIZE>1024 && !HAL_MINIMIZE_FEATURES +#endif + +#if AP_TRAMP_ENABLED + +#include +#include +#include +#include "AP_VideoTX.h" + +#define VTX_TRAMP_POWER_COUNT 5 + +#define VTX_TRAMP_MIN_FREQUENCY_MHZ 5000 //min freq in MHz +#define VTX_TRAMP_MAX_FREQUENCY_MHZ 5999 //max freq in MHz +// Maximum number of requests sent to try a config change +// Some VTX fail to respond to every request (like Matek FCHUB-VTX) so +// we sometimes need multiple retries to get the VTX to respond. +#define VTX_TRAMP_MAX_RETRIES (20) +// Race lock - settings can't be changed +#define TRAMP_CONTROL_RACE_LOCK (0x01) + +class AP_Tramp +{ +public: + AP_Tramp(); + ~AP_Tramp() {} + + /* Do not allow copies */ + AP_Tramp(const AP_Tramp &other) = delete; + AP_Tramp &operator=(const AP_Tramp&) = delete; + + static AP_Tramp *get_singleton(void) { + return singleton; + } + + bool init(void); + void update(); + + uint16_t get_current_actual_power(); + uint16_t get_current_temp(); + +private: + uint8_t checksum(uint8_t *buf); + // Check if race lock is enabled + bool is_race_lock_enabled(void) { + return cur_control_mode & TRAMP_CONTROL_RACE_LOCK; + } + void send_command(uint8_t cmd, uint16_t param); + char handle_response(); + void reset_receiver(); + char receive_response(); + void send_query(uint8_t cmd); + void process_requests(); + bool is_device_ready(); + void set_frequency(uint16_t freq); + void set_power(uint16_t power); + void set_pit_mode(uint8_t onoff); + + // serial interface + AP_HAL::UARTDriver *port; // UART used to send data to Tramp VTX + + //Pointer to singleton + static AP_Tramp* singleton; + + const static uint16_t TRAMP_BUF_SIZE = 16; + + // Serial transmit and receive buffers + uint8_t request_buffer[TRAMP_BUF_SIZE]; + uint8_t response_buffer[TRAMP_BUF_SIZE]; + + // Module state machine + enum class TrampStatus { + // Offline - device hasn't responded yet + TRAMP_STATUS_OFFLINE = 0, + // Init - fetching current settings from device + TRAMP_STATUS_INIT, + // Online - device is ready and being monitored - freq/power/pitmode + TRAMP_STATUS_ONLINE_MONITOR_FREQPWRPIT, + // Online - device is ready and being monitored - temperature + TRAMP_STATUS_ONLINE_MONITOR_TEMP, + // Online - device is ready and config has just been updated + TRAMP_STATUS_ONLINE_CONFIG + }; + + TrampStatus status = TrampStatus::TRAMP_STATUS_OFFLINE; + + void set_status(TrampStatus stat); + + // Device limits, read from device during init + struct { + uint32_t rf_freq_min; + uint32_t rf_freq_max; + uint32_t rf_power_max; + } device_limits; + + uint16_t cur_act_power; // Actual power + int16_t cur_temp; + uint8_t cur_control_mode; + + // Retry count + uint8_t retry_count = VTX_TRAMP_MAX_RETRIES; + + // Receive state machine + enum class ReceiveState { + S_WAIT_LEN = 0, // Waiting for a packet len + S_WAIT_CODE, // Waiting for a response code + S_DATA, // Waiting for rest of the packet. + }; + + ReceiveState receive_state = ReceiveState::S_WAIT_LEN; + + // Receive buffer index + int16_t receive_pos; + + // Last action time + uint32_t last_time_us; +}; + +#endif diff --git a/libraries/AP_VideoTX/AP_VideoTX.cpp b/libraries/AP_VideoTX/AP_VideoTX.cpp index dd2370af7ca..33db1951505 100644 --- a/libraries/AP_VideoTX/AP_VideoTX.cpp +++ b/libraries/AP_VideoTX/AP_VideoTX.cpp @@ -17,6 +17,8 @@ #include #include +#include + extern const AP_HAL::HAL& hal; AP_VideoTX *AP_VideoTX::singleton; @@ -59,9 +61,9 @@ const AP_Param::GroupInfo AP_VideoTX::var_info[] = { // @Param: OPTIONS // @DisplayName: Video Transmitter Options - // @Description: Video Transmitter Options. Pitmode puts the VTX in a low power state. Unlocked enables certain restricted frequencies and power levels. Do not enable the Unlocked option unless you have appropriate permissions in your jurisdiction to transmit at high power levels. + // @Description: Video Transmitter Options. Pitmode puts the VTX in a low power state. Unlocked enables certain restricted frequencies and power levels. Do not enable the Unlocked option unless you have appropriate permissions in your jurisdiction to transmit at high power levels. One stop-bit may be required for VTXs that erroneously mimic iNav behaviour. // @User: Advanced - // @Bitmask: 0:Pitmode,1:Pitmode until armed,2:Pitmode when disarmed,3:Unlocked,4:Add leading zero byte to requests + // @Bitmask: 0:Pitmode,1:Pitmode until armed,2:Pitmode when disarmed,3:Unlocked,4:Add leading zero byte to requests,5:Use 1 stop-bit in SmartAudio,6:Ignore CRC in SmartAudio,7:Ignore status updates in CRSF and blindly set VTX options AP_GROUPINFO("OPTIONS", 6, AP_VideoTX, _options, 0), // @Param: MAX_POWER @@ -73,6 +75,13 @@ const AP_Param::GroupInfo AP_VideoTX::var_info[] = { AP_GROUPEND }; +//#define VTX_DEBUG +#ifdef VTX_DEBUG +# define debug(fmt, args...) hal.console->printf("VTX: " fmt "\n", ##args) +#else +# define debug(fmt, args...) do {} while(0) +#endif + extern const AP_HAL::HAL& hal; const char * AP_VideoTX::band_names[] = {"A","B","E","F","R","L"}; @@ -87,6 +96,23 @@ const uint16_t AP_VideoTX::VIDEO_CHANNELS[AP_VideoTX::MAX_BANDS][VTX_MAX_CHANNEL { 5621, 5584, 5547, 5510, 5473, 5436, 5399, 5362} /* LO Race */ }; +// mapping of power level to milliwatt to dbm +// valid power levels from SmartAudio spec, the adjacent levels might be the actual values +// so these are marked as level + 0x10 and will be switched if a dbm message proves it +AP_VideoTX::PowerLevel AP_VideoTX::_power_levels[VTX_MAX_POWER_LEVELS] = { + // level, mw, dbm, dac + { 0xFF, 0, 0, 0 }, // only in SA 2.1 + { 0, 25, 14, 7 }, + { 0x11, 100, 20, 0xFF }, // only in SA 2.1 + { 1, 200, 23, 16 }, + { 0x12, 400, 26, 0xFF }, // only in SA 2.1 + { 2, 500, 27, 25 }, + //{ 0x13, 600, 28, 0xFF }, + { 3, 800, 29, 40 }, + { 0x13, 1000, 30, 0xFF }, // only in SA 2.1 + { 0xFF, 0, 0, 0XFF, PowerActive::Inactive } // slot reserved for a custom power level +}; + AP_VideoTX::AP_VideoTX() { if (singleton) { @@ -109,7 +135,23 @@ bool AP_VideoTX::init(void) return false; } - _current_power = _power_mw; + // PARAMETER_CONVERSION - Added: Sept-2022 + _options.convert_parameter_width(AP_PARAM_INT16); + + // find the index into the power table + for (uint8_t i = 0; i < VTX_MAX_POWER_LEVELS; i++) { + if (_power_mw <= _power_levels[i].mw) { + if (_power_mw != _power_levels[i].mw) { + if (i > 0) { + _current_power = i - 1; + } + _power_mw.set_and_save(get_power_mw()); + } else { + _current_power = i; + } + break; + } + } _current_band = _band; _current_channel = _channel; _current_frequency = _frequency_mhz; @@ -135,91 +177,158 @@ bool AP_VideoTX::get_band_and_channel(uint16_t freq, VideoBand& band, uint8_t& c } // set the current power -void AP_VideoTX::set_configured_power_mw(uint16_t power) { +void AP_VideoTX::set_configured_power_mw(uint16_t power) +{ _power_mw.set_and_save_ifchanged(power); } +uint8_t AP_VideoTX::find_current_power() const +{ + for (uint8_t i = 0; i < VTX_MAX_POWER_LEVELS; i++) { + if (_power_mw == _power_levels[i].mw) { + return i; + } + } + return 0; +} + // set the power in dbm, rounding appropriately -void AP_VideoTX::set_power_dbm(uint8_t power) { - switch (power) { - case 14: - _current_power = 25; - break; - case 20: - _current_power = 100; - break; - case 23: - _current_power = 200; - break; - case 26: - _current_power = 400; - break; - case 27: - _current_power = 500; - break; - case 29: - _current_power = 800; - break; - default: - _current_power = uint16_t(roundf(powf(10, power / 10.0f))); - break; +void AP_VideoTX::set_power_dbm(uint8_t power, PowerActive active) +{ + if (power == _power_levels[_current_power].dbm + && _power_levels[_current_power].active == active) { + return; } + + for (uint8_t i = 0; i < VTX_MAX_POWER_LEVELS; i++) { + if (power == _power_levels[i].dbm) { + _current_power = i; + _power_levels[i].active = active; + debug("learned power %ddbm", power); + // now unlearn the "other" power level since we have no other way of guessing + // the supported levels + if ((_power_levels[i].level & 0xF0) == 0x10) { + _power_levels[i].level = _power_levels[i].level & 0xF; + } + if (i > 0 && _power_levels[i-1].level == _power_levels[i].level) { + debug("invalidated power %dwm, level %d is now %dmw", _power_levels[i-1].mw, _power_levels[i].level, _power_levels[i].mw); + _power_levels[i-1].level = 0xFF; + _power_levels[i-1].active = PowerActive::Inactive; + } else if (i < VTX_MAX_POWER_LEVELS-1 && _power_levels[i+1].level == _power_levels[i].level) { + debug("invalidated power %dwm, level %d is now %dmw", _power_levels[i+1].mw, _power_levels[i].level, _power_levels[i].mw); + _power_levels[i+1].level = 0xFF; + _power_levels[i+1].active = PowerActive::Inactive; + } + return; + } + } + // learn the non-standard power + _current_power = update_power_dbm(power, active); } -// get the power in dbm, rounding appropriately -uint8_t AP_VideoTX::get_configured_power_dbm() const { - switch (_power_mw.get()) { - case 25: return 14; - case 100: return 20; - case 200: return 23; - case 400: return 26; - case 500: return 27; - case 800: return 29; - default: - return uint8_t(roundf(10.0f * log10f(_power_mw))); +// add an active power setting in dbm +uint8_t AP_VideoTX::update_power_dbm(uint8_t power, PowerActive active) +{ + for (uint8_t i = 0; i < VTX_MAX_POWER_LEVELS; i++) { + if (power == _power_levels[i].dbm) { + if (_power_levels[i].active != active) { + _power_levels[i].active = active; + debug("%s power %ddbm", active == PowerActive::Active ? "learned" : "invalidated", power); + } + return i; + } } + // handed a non-standard value, use the last slot + _power_levels[VTX_MAX_POWER_LEVELS-1].dbm = power; + _power_levels[VTX_MAX_POWER_LEVELS-1].level = 255; + _power_levels[VTX_MAX_POWER_LEVELS-1].dac = 255; + _power_levels[VTX_MAX_POWER_LEVELS-1].mw = uint16_t(roundf(powf(10, power / 10.0f))); + _power_levels[VTX_MAX_POWER_LEVELS-1].active = active; + debug("non-standard power %ddbm -> %dmw", power, _power_levels[VTX_MAX_POWER_LEVELS-1].mw); + return VTX_MAX_POWER_LEVELS-1; } -// get the power "level" -uint8_t AP_VideoTX::get_configured_power_level() const { - if (_power_mw < 26) { - return 0; - } else if (_power_mw < 201) { - return 1; - } else if (_power_mw < 501) { - return 2; - } else { // 800 - return 3; +// add all active power setting in dbm +void AP_VideoTX::update_all_power_dbm(uint8_t nlevels, const uint8_t power[]) +{ + for (uint8_t i = 0; i < nlevels; i++) { + update_power_dbm(power[i], PowerActive::Active); + } + // invalidate the remaining ones + for (uint8_t i = 0; i < VTX_MAX_POWER_LEVELS; i++) { + if (_power_levels[i].active == PowerActive::Unknown) { + _power_levels[i].active = PowerActive::Inactive; + } + } +} + +// set the power in mw +void AP_VideoTX::set_power_mw(uint16_t power) +{ + for (uint8_t i = 0; i < VTX_MAX_POWER_LEVELS; i++) { + if (power == _power_levels[i].mw) { + _current_power = i; + break; + } } } // set the power "level" -void AP_VideoTX::set_power_level(uint8_t level) { - switch (level) { - case 1: - _current_power = 200; - break; - case 2: - _current_power = 500; - break; - case 3: - _current_power = 800; - break; - case 0: - default: - _current_power = 25; - break; +void AP_VideoTX::set_power_level(uint8_t level, PowerActive active) +{ + if (level == _power_levels[_current_power].level + && _power_levels[_current_power].active == active) { + return; + } + + for (uint8_t i = 0; i < VTX_MAX_POWER_LEVELS; i++) { + if (level == _power_levels[i].level) { + _current_power = i; + _power_levels[i].active = active; + debug("learned power level %d: %dmw", level, get_power_mw()); + break; + } + } +} + +// set the power dac +void AP_VideoTX::set_power_dac(uint16_t power, PowerActive active) +{ + if (power == _power_levels[_current_power].dac + && _power_levels[_current_power].active == active) { + return; + } + + for (uint8_t i = 0; i < VTX_MAX_POWER_LEVELS; i++) { + if (power == _power_levels[i].dac) { + _current_power = i; + _power_levels[i].active = active; + debug("learned power %dmw", get_power_mw()); + } } } // set the current channel -void AP_VideoTX::set_enabled(bool enabled) { +void AP_VideoTX::set_enabled(bool enabled) +{ _current_enabled = enabled; - if (!_enabled.configured_in_storage()) { + if (!_enabled.configured()) { _enabled.set_and_save(enabled); } } +void AP_VideoTX::set_power_is_current() +{ + set_power_dbm(get_configured_power_dbm()); +} + +void AP_VideoTX::set_freq_is_current() +{ + _current_frequency = _frequency_mhz; + _current_band = _band; + _current_channel = _channel; +} + // periodic update void AP_VideoTX::update(void) { @@ -233,10 +342,19 @@ void AP_VideoTX::update(void) // manipulate pitmode if pitmode-on-disarm or power-on-arm is set if (has_option(VideoOptions::VTX_PITMODE_ON_DISARM) || has_option(VideoOptions::VTX_PITMODE_UNTIL_ARM)) { if (hal.util->get_soft_armed() && has_option(VideoOptions::VTX_PITMODE)) { - _options &= ~uint8_t(VideoOptions::VTX_PITMODE); + _options.set(_options & ~uint8_t(VideoOptions::VTX_PITMODE)); } else if (!hal.util->get_soft_armed() && !has_option(VideoOptions::VTX_PITMODE) && has_option(VideoOptions::VTX_PITMODE_ON_DISARM)) { - _options |= uint8_t(VideoOptions::VTX_PITMODE); + _options.set(_options | uint8_t(VideoOptions::VTX_PITMODE)); + } + } + // check that the requested power is actually allowed + // reset if not + if (_power_mw != get_power_mw()) { + if (_power_levels[find_current_power()].active == PowerActive::Inactive) { + // reset to something we know works + debug("power reset to %dmw from %dmw", get_power_mw(), _power_mw.get()); + _power_mw.set_and_save(get_power_mw()); } } } @@ -252,6 +370,12 @@ bool AP_VideoTX::update_options() const return true; } +#if HAL_CRSF_TELEM_ENABLED + // using CRSF so unlock is not an option + if (AP::crsf_telem() != nullptr) { + return false; + } +#endif // check unlock only if ((_options & uint8_t(VideoOptions::VTX_UNLOCKED)) != 0 && (_current_options & uint8_t(VideoOptions::VTX_UNLOCKED)) == 0) { @@ -262,6 +386,21 @@ bool AP_VideoTX::update_options() const return false; } +bool AP_VideoTX::update_power() const { + if (!_defaults_set || _power_mw == get_power_mw() || get_pitmode()) { + return false; + } + // check that the requested power is actually allowed + for (uint8_t i = 0; i < VTX_MAX_POWER_LEVELS; i++) { + if (_power_mw == _power_levels[i].mw + && _power_levels[i].active != PowerActive::Inactive) { + return true; + } + } + // asked for something unsupported - only SA2.1 allows this and will have already provided a list + return false; +} + bool AP_VideoTX::have_params_changed() const { return _enabled @@ -299,7 +438,7 @@ bool AP_VideoTX::set_defaults() return false; } - // check that our current view of freqency matches band/channel + // check that our current view of frequency matches band/channel // if not then force one to be correct uint16_t calced_freq = get_frequency_mhz(_current_band, _current_channel); if (_current_frequency != calced_freq) { @@ -324,10 +463,10 @@ bool AP_VideoTX::set_defaults() _channel.set_and_save(_current_channel); } if (!_band.configured()) { - _frequency_mhz.set_and_save(_current_band); + _band.set_and_save(_current_band); } if (!_power_mw.configured()) { - _power_mw.set_and_save(_current_power); + _power_mw.set_and_save(get_power_mw()); } if (!_frequency_mhz.configured()) { _frequency_mhz.set_and_save(_current_frequency); @@ -364,96 +503,25 @@ void AP_VideoTX::change_power(int8_t position) if (position < 0 || position > 5) { return; } - - uint16_t power = 0; - // 0 or 25 - if (_max_power_mw < 100) { - switch (position) { - case 3: - case 4: - case 5: - power = 25; - break; - default: - power = 0; - break; - } - } - // 0, 25 or 100 - else if (_max_power_mw < 200) { - switch (position) { - case 0: - power = 0; - break; - case 5: - power = 100; - break; - default: - power = 25; - break; + // first find out how many possible levels there are + uint8_t num_active_levels = 0; + for (uint8_t i = 0; i < VTX_MAX_POWER_LEVELS; i++) { + if (_power_levels[i].active != PowerActive::Inactive) { + num_active_levels++; } } - // 0, 25, 100 or 200 - else if (_max_power_mw < 500) { - switch (position) { - case 1: - case 2: - power = 25; - break; - case 3: - case 4: - power = 100; - break; - case 5: - power = 200; - break; - default: - power = 0; - break; - } - } - // 0, 25, 100, 200 or 500 - else if (_max_power_mw < 800) { - switch (position) { - case 1: - case 2: - power = 25; - break; - case 3: - power = 100; - break; - case 4: - power = 200; - break; - case 5: - power = 500; - break; - default: - power = 0; - break; + // iterate through to find the level + uint16_t level = constrain_int16(roundf((num_active_levels * (position + 1)/ 6.0f) - 1), 0, num_active_levels - 1); + debug("looking for pos %d power level %d from %d", position, level, num_active_levels); + uint16_t power = 0; + for (uint8_t i = 0, j = 0; i < num_active_levels; i++, j++) { + while (j < VTX_MAX_POWER_LEVELS-1 && _power_levels[j].active == PowerActive::Inactive) { + j++; } - } - // full range - else { - switch (position) { - case 1: - power = 25; - break; - case 2: - power = 100; - break; - case 3: - power = 200; - break; - case 4: - power = 500; - break; - case 5: - power = _max_power_mw; // some VTX's support 1000mw - break; - default: - power = 0; - break; + if (i == level) { + power = _power_levels[j].mw; + debug("selected power %dmw", power); + break; } } diff --git a/libraries/AP_VideoTX/AP_VideoTX.h b/libraries/AP_VideoTX/AP_VideoTX.h index c69210c209e..ff392fd7b57 100644 --- a/libraries/AP_VideoTX/AP_VideoTX.h +++ b/libraries/AP_VideoTX/AP_VideoTX.h @@ -14,11 +14,10 @@ */ #pragma once -#include #include -#include #define VTX_MAX_CHANNELS 8 +#define VTX_MAX_POWER_LEVELS 9 class AP_VideoTX { public: @@ -46,6 +45,9 @@ class AP_VideoTX { VTX_PITMODE_ON_DISARM = (1 << 2), VTX_UNLOCKED = (1 << 3), VTX_PULLDOWN = (1 << 4), + VTX_SA_ONE_STOP_BIT = (1 << 5), + VTX_SA_IGNORE_CRC = (1 << 6), + VTX_CRSF_IGNORE_STAT = (1 << 7), }; static const char *band_names[]; @@ -60,6 +62,22 @@ class AP_VideoTX { MAX_BANDS }; + enum class PowerActive { + Unknown, + Active, + Inactive + }; + + struct PowerLevel { + uint8_t level; + uint16_t mw; + uint8_t dbm; + uint8_t dac; // SmartAudio v1 dac value + PowerActive active; + }; + + static PowerLevel _power_levels[VTX_MAX_POWER_LEVELS]; + static const uint16_t VIDEO_CHANNELS[MAX_BANDS][VTX_MAX_CHANNELS]; static uint16_t get_frequency_mhz(uint8_t band, uint8_t channel) { return VIDEO_CHANNELS[band][channel]; } @@ -72,15 +90,31 @@ class AP_VideoTX { bool update_frequency() const { return _defaults_set && _frequency_mhz != _current_frequency; } void update_configured_frequency(); // get / set power level - void set_power_mw(uint16_t power) { _current_power = power; } - void set_power_level(uint8_t level); - void set_power_dbm(uint8_t power); + void set_power_mw(uint16_t power); + void set_power_level(uint8_t level, PowerActive active=PowerActive::Active); + void set_power_dbm(uint8_t power, PowerActive active=PowerActive::Active); + void set_power_dac(uint16_t power, PowerActive active=PowerActive::Active); + // add a new dbm setting to those supported + uint8_t update_power_dbm(uint8_t power, PowerActive active=PowerActive::Active); + void update_all_power_dbm(uint8_t nlevels, const uint8_t levels[]); void set_configured_power_mw(uint16_t power); uint16_t get_configured_power_mw() const { return _power_mw; } - uint16_t get_power_mw() const { return _current_power; } - uint8_t get_configured_power_dbm() const; - uint8_t get_configured_power_level() const; - bool update_power() const { return _defaults_set && _power_mw != _current_power; } + uint16_t get_power_mw() const { return _power_levels[_current_power].mw; } + + // get the power in dbm, rounding appropriately + uint8_t get_configured_power_dbm() const { + return _power_levels[find_current_power()].dbm; + } + // get the power "level" + uint8_t get_configured_power_level() const { + return _power_levels[find_current_power()].level & 0xF; + } + // get the power "dac" + uint8_t get_configured_power_dac() const { + return _power_levels[find_current_power()].dac; + } + + bool update_power() const; // change the video power based on switch input void change_power(int8_t position); // get / set the frequency band @@ -97,11 +131,13 @@ class AP_VideoTX { bool update_channel() const { return _defaults_set && _channel != _current_channel; } void update_configured_channel_and_band(); // get / set vtx option - void set_options(uint8_t options) { _current_options = options; } - void set_configured_options(uint8_t options) { _options.set_and_save_ifchanged(options); } - uint8_t get_configured_options() const { return _options; } - uint8_t get_options() const { return _current_options; } - bool has_option(VideoOptions option) const { return _options.get() & uint8_t(option); } + void set_options(uint16_t options) { _current_options = options; } + void set_configured_options(uint16_t options) { _options.set_and_save_ifchanged(options); } + uint16_t get_configured_options() const { return _options; } + uint16_t get_options() const { return _current_options; } + bool has_option(VideoOptions option) const { return _options.get() & uint16_t(option); } + bool get_configured_pitmode() const { return _options.get() & uint8_t(AP_VideoTX::VideoOptions::VTX_PITMODE); } + bool get_pitmode() const { return _current_options & uint8_t(AP_VideoTX::VideoOptions::VTX_PITMODE); } bool update_options() const; // get / set whether the vtx is enabled void set_enabled(bool enabled); @@ -114,6 +150,10 @@ class AP_VideoTX { bool set_defaults(); // display the current VTX settings in the GCS void announce_vtx_settings() const; + // force the current values to reflect the configured values + void set_power_is_current(); + void set_freq_is_current(); + void set_options_are_current() { _current_options = _options; } void set_configuration_finished(bool configuration_finished) { _configuration_finished = configuration_finished; } bool is_configuration_finished() { return _configuration_finished; } @@ -121,6 +161,7 @@ class AP_VideoTX { static AP_VideoTX *singleton; private: + uint8_t find_current_power() const; // channel frequency AP_Int16 _frequency_mhz; uint16_t _current_frequency; @@ -139,8 +180,8 @@ class AP_VideoTX { uint8_t _current_channel; // vtx options - AP_Int8 _options; - uint8_t _current_options; + AP_Int16 _options; + uint16_t _current_options; AP_Int8 _enabled; bool _current_enabled; @@ -148,7 +189,7 @@ class AP_VideoTX { bool _initialized; // when defaults have been configured bool _defaults_set; - // true when configuration have been applied succesfully to the VTX + // true when configuration have been applied successfully to the VTX bool _configuration_finished; }; diff --git a/libraries/AP_VisualOdom/AP_VisualOdom.h b/libraries/AP_VisualOdom/AP_VisualOdom.h index dc47faeb4ec..e13bb562f14 100644 --- a/libraries/AP_VisualOdom/AP_VisualOdom.h +++ b/libraries/AP_VisualOdom/AP_VisualOdom.h @@ -14,12 +14,7 @@ */ #pragma once -#include -#include - -#ifndef HAL_VISUALODOM_ENABLED -#define HAL_VISUALODOM_ENABLED (!HAL_MINIMIZE_FEATURES && BOARD_FLASH_SIZE > 1024) -#endif +#include "AP_VisualOdom_config.h" #if HAL_VISUALODOM_ENABLED diff --git a/libraries/AP_VisualOdom/AP_VisualOdom_Backend.cpp b/libraries/AP_VisualOdom/AP_VisualOdom_Backend.cpp index a09b15230da..3a01cb7a839 100644 --- a/libraries/AP_VisualOdom/AP_VisualOdom_Backend.cpp +++ b/libraries/AP_VisualOdom/AP_VisualOdom_Backend.cpp @@ -56,7 +56,7 @@ void AP_VisualOdom_Backend::handle_vision_position_delta_msg(const mavlink_messa _last_update_ms = now_ms; // send to EKF - const float time_delta_sec = packet.time_delta_usec / 1000000.0f; + const float time_delta_sec = packet.time_delta_usec * 1.0E-6; AP::ahrs().writeBodyFrameOdom(packet.confidence, position_delta, angle_delta, diff --git a/libraries/AP_VisualOdom/AP_VisualOdom_config.h b/libraries/AP_VisualOdom/AP_VisualOdom_config.h new file mode 100644 index 00000000000..e38580cd3ba --- /dev/null +++ b/libraries/AP_VisualOdom/AP_VisualOdom_config.h @@ -0,0 +1,7 @@ +#pragma once + +#include + +#ifndef HAL_VISUALODOM_ENABLED +#define HAL_VISUALODOM_ENABLED (!HAL_MINIMIZE_FEATURES && BOARD_FLASH_SIZE > 1024) +#endif diff --git a/libraries/AP_VisualOdom/LogStructure.h b/libraries/AP_VisualOdom/LogStructure.h index 51b92ccf4f5..cb15e181c4b 100644 --- a/libraries/AP_VisualOdom/LogStructure.h +++ b/libraries/AP_VisualOdom/LogStructure.h @@ -1,6 +1,7 @@ #pragma once #include +#include "AP_VisualOdom_config.h" #define LOG_IDS_FROM_VISUALODOM \ LOG_VISUALODOM_MSG, \ @@ -87,6 +88,7 @@ struct PACKED log_VisualVelocity { uint8_t ignored; }; +#if HAL_VISUALODOM_ENABLED #define LOG_STRUCTURE_FROM_VISUALODOM \ { LOG_VISUALODOM_MSG, sizeof(log_VisualOdom), \ "VISO", "Qffffffff", "TimeUS,dt,AngDX,AngDY,AngDZ,PosDX,PosDY,PosDZ,conf", "ssrrrmmm-", "FF000000-" }, \ @@ -94,4 +96,6 @@ struct PACKED log_VisualVelocity { "VISP", "QQIffffffffBB", "TimeUS,RTimeUS,CTimeMS,PX,PY,PZ,Roll,Pitch,Yaw,PErr,AErr,Rst,Ign", "sssmmmddhmd--", "FFC00000000--" }, \ { LOG_VISUALVEL_MSG, sizeof(log_VisualVelocity), \ "VISV", "QQIffffBB", "TimeUS,RTimeUS,CTimeMS,VX,VY,VZ,VErr,Rst,Ign", "sssnnnn--", "FFC0000--" }, - +#else +#define LOG_STRUCTURE_FROM_VISUALODOM +#endif diff --git a/libraries/AP_Volz_Protocol/AP_Volz_Protocol.cpp b/libraries/AP_Volz_Protocol/AP_Volz_Protocol.cpp index 5fb5b6c69a9..fdd788b4297 100644 --- a/libraries/AP_Volz_Protocol/AP_Volz_Protocol.cpp +++ b/libraries/AP_Volz_Protocol/AP_Volz_Protocol.cpp @@ -4,18 +4,22 @@ * Created on: Oct 31, 2017 * Author: guy */ +#include "AP_Volz_Protocol.h" + +#if AP_VOLZ_ENABLED + #include + +#include #include -#include "AP_Volz_Protocol.h" -#if NUM_SERVO_CHANNELS extern const AP_HAL::HAL& hal; const AP_Param::GroupInfo AP_Volz_Protocol::var_info[] = { // @Param: MASK // @DisplayName: Channel Bitmask // @Description: Enable of volz servo protocol to specific channels - // @Bitmask: 0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16 + // @Bitmask: 0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16,16:Channel17,17:Channel18,18:Channel19,19:Channel20,20:Channel21,21:Channel22,22:Channel23,23:Channel24,24:Channel25,25:Channel26,26:Channel27,28:Channel29,29:Channel30,30:Channel31,31:Channel32 // @User: Standard AP_GROUPINFO("MASK", 1, AP_Volz_Protocol, bitmask, 0), @@ -62,7 +66,7 @@ void AP_Volz_Protocol::update() uint8_t i; uint16_t value; - // loop for all 16 channels + // loop for all channels for (i=0; i + +#ifndef AP_VOLZ_ENABLED +#define AP_VOLZ_ENABLED (!HAL_MINIMIZE_FEATURES && BOARD_FLASH_SIZE > 1024) +#endif + +#if AP_VOLZ_ENABLED + #include -#include #include -//#include - #define VOLZ_SCALE_VALUE (uint16_t)(VOLZ_EXTENDED_POSITION_MAX - VOLZ_EXTENDED_POSITION_MIN) // Extended Position Data Format defines 100 as 0x0F80, which results in 1920 steps for +100 deg and 1920 steps for -100 degs meaning if you take movement a scaled between -1 ... 1 and multiply by 1920 you get the travel from center #define VOLZ_SET_EXTENDED_POSITION_CMD 0xDC #define VOLZ_SET_EXTENDED_POSITION_RSP 0x2C @@ -56,8 +61,7 @@ class AP_Volz_Protocol { AP_Volz_Protocol(); /* Do not allow copies */ - AP_Volz_Protocol(const AP_Volz_Protocol &other) = delete; - AP_Volz_Protocol &operator=(const AP_Volz_Protocol&) = delete; + CLASS_NO_COPY(AP_Volz_Protocol); static const struct AP_Param::GroupInfo var_info[]; @@ -77,3 +81,5 @@ class AP_Volz_Protocol { AP_Int32 bitmask; bool initialised; }; + +#endif // AP_VOLZ_PROTOCOL diff --git a/libraries/AP_WheelEncoder/AP_WheelEncoder.h b/libraries/AP_WheelEncoder/AP_WheelEncoder.h index ad8a97c5f90..aefebffbc13 100644 --- a/libraries/AP_WheelEncoder/AP_WheelEncoder.h +++ b/libraries/AP_WheelEncoder/AP_WheelEncoder.h @@ -15,7 +15,6 @@ #pragma once #include -#include #include #include diff --git a/libraries/AP_WheelEncoder/AP_WheelRateControl.cpp b/libraries/AP_WheelEncoder/AP_WheelRateControl.cpp index fe2fce23357..ff8739eb45f 100644 --- a/libraries/AP_WheelEncoder/AP_WheelRateControl.cpp +++ b/libraries/AP_WheelEncoder/AP_WheelRateControl.cpp @@ -189,9 +189,6 @@ float AP_WheelRateControl::get_rate_controlled_throttle(uint8_t instance, float // determine which PID instance to use AC_PID& rate_pid = (instance == 0) ? _rate_pid0 : _rate_pid1; - // set PID's dt - rate_pid.set_dt(dt); - // check for timeout uint32_t now = AP_HAL::millis(); if (now - _last_update_ms > AP_WHEEL_RATE_CONTROL_TIMEOUT_MS) { @@ -203,13 +200,13 @@ float AP_WheelRateControl::get_rate_controlled_throttle(uint8_t instance, float _last_update_ms = now; // convert desired rate as a percentage to radians/sec - float desired_rate = desired_rate_pct / 100.0f * get_rate_max_rads(); + float desired_rate = desired_rate_pct * 0.01f * get_rate_max_rads(); - // get actual rate from wheeel encoder + // get actual rate from wheel encoder float actual_rate = _wheel_encoder.get_rate(instance); // constrain and set limit flags - float output = rate_pid.update_all(desired_rate, actual_rate, (_limit[instance].lower || _limit[instance].upper)); + float output = rate_pid.update_all(desired_rate, actual_rate, dt, (_limit[instance].lower || _limit[instance].upper)); output += rate_pid.get_ff(); // set limits for next iteration diff --git a/libraries/AP_WheelEncoder/WheelEncoder_Backend.cpp b/libraries/AP_WheelEncoder/WheelEncoder_Backend.cpp index 35a20c62c09..4742dcfa1f2 100644 --- a/libraries/AP_WheelEncoder/WheelEncoder_Backend.cpp +++ b/libraries/AP_WheelEncoder/WheelEncoder_Backend.cpp @@ -14,7 +14,6 @@ */ #include -#include #include "AP_WheelEncoder.h" #include "WheelEncoder_Backend.h" diff --git a/libraries/AP_WheelEncoder/WheelEncoder_Backend.h b/libraries/AP_WheelEncoder/WheelEncoder_Backend.h index 77fff6a3ea2..382c911ff76 100644 --- a/libraries/AP_WheelEncoder/WheelEncoder_Backend.h +++ b/libraries/AP_WheelEncoder/WheelEncoder_Backend.h @@ -15,7 +15,6 @@ #pragma once #include -#include #include "AP_WheelEncoder.h" class AP_WheelEncoder_Backend diff --git a/libraries/AP_WheelEncoder/WheelEncoder_Quadrature.cpp b/libraries/AP_WheelEncoder/WheelEncoder_Quadrature.cpp index 09c248342e8..518bd26fd7b 100644 --- a/libraries/AP_WheelEncoder/WheelEncoder_Quadrature.cpp +++ b/libraries/AP_WheelEncoder/WheelEncoder_Quadrature.cpp @@ -138,5 +138,5 @@ void AP_WheelEncoder_Quadrature::irq_handler(uint8_t pin, update_phase_and_error_count(); // record update time - irq_state.last_reading_ms = timestamp; + irq_state.last_reading_ms = timestamp * 1e-3f; } diff --git a/libraries/AP_Winch/AP_Winch.h b/libraries/AP_Winch/AP_Winch.h index 0e03f7d0a71..81cbca5f73f 100644 --- a/libraries/AP_Winch/AP_Winch.h +++ b/libraries/AP_Winch/AP_Winch.h @@ -59,7 +59,7 @@ class AP_Winch { float get_rate_max() const { return MAX(config.rate_max, 0.0f); } // send status to ground station - void send_status(const GCS_MAVLINK &channel); + void send_status(const class GCS_MAVLINK &channel); // write log void write_log(); diff --git a/libraries/AP_Winch/AP_Winch_Backend.cpp b/libraries/AP_Winch/AP_Winch_Backend.cpp index 9a01999ff41..61e395de018 100644 --- a/libraries/AP_Winch/AP_Winch_Backend.cpp +++ b/libraries/AP_Winch/AP_Winch_Backend.cpp @@ -1,5 +1,7 @@ #include + #include +#include // setup rc input and output void AP_Winch_Backend::init() diff --git a/libraries/AP_Winch/AP_Winch_Daiwa.cpp b/libraries/AP_Winch/AP_Winch_Daiwa.cpp index d660d15e384..99f1921578e 100644 --- a/libraries/AP_Winch/AP_Winch_Daiwa.cpp +++ b/libraries/AP_Winch/AP_Winch_Daiwa.cpp @@ -1,4 +1,6 @@ #include + +#include #include extern const AP_HAL::HAL& hal; @@ -184,7 +186,7 @@ void AP_Winch_Daiwa::read_data_from_winch() void AP_Winch_Daiwa::control_winch() { const uint32_t now_ms = AP_HAL::millis(); - float dt = (now_ms - control_update_ms) / 1000.0f; + float dt = (now_ms - control_update_ms) * 0.001f; if (dt > 1.0f) { dt = 0.0f; } diff --git a/libraries/AP_Winch/AP_Winch_PWM.cpp b/libraries/AP_Winch/AP_Winch_PWM.cpp index f7782559265..afd7d770095 100644 --- a/libraries/AP_Winch/AP_Winch_PWM.cpp +++ b/libraries/AP_Winch/AP_Winch_PWM.cpp @@ -1,4 +1,6 @@ #include "AP_Winch_PWM.h" + +#include #include extern const AP_HAL::HAL& hal; @@ -32,7 +34,7 @@ void AP_Winch_PWM::update() void AP_Winch_PWM::control_winch() { const uint32_t now_ms = AP_HAL::millis(); - float dt = (now_ms - control_update_ms) / 1000.0f; + float dt = (now_ms - control_update_ms) * 0.001f; if (dt > 1.0f) { dt = 0.0f; } diff --git a/libraries/AP_WindVane/AP_WindVane.cpp b/libraries/AP_WindVane/AP_WindVane.cpp index dba378495cc..8b5bfa10bf2 100644 --- a/libraries/AP_WindVane/AP_WindVane.cpp +++ b/libraries/AP_WindVane/AP_WindVane.cpp @@ -23,7 +23,12 @@ #include "AP_WindVane_SITL.h" #include "AP_WindVane_NMEA.h" +#include +#include #include +#include + +extern const AP_HAL::HAL& hal; const AP_Param::GroupInfo AP_WindVane::var_info[] = { @@ -369,12 +374,16 @@ void AP_WindVane::update() } +void AP_WindVane::record_home_heading() +{ + _home_heading = AP::ahrs().yaw; +} // to start direction calibration from mavlink or other bool AP_WindVane::start_direction_calibration() { if (enabled() && (_calibration == 0)) { - _calibration = 1; + _calibration.set(1); return true; } return false; @@ -384,7 +393,7 @@ bool AP_WindVane::start_direction_calibration() bool AP_WindVane::start_speed_calibration() { if (enabled() && (_calibration == 0)) { - _calibration = 2; + _calibration.set(2); return true; } return false; diff --git a/libraries/AP_WindVane/AP_WindVane.h b/libraries/AP_WindVane/AP_WindVane.h index c4cbfaae129..ebc9adb4768 100644 --- a/libraries/AP_WindVane/AP_WindVane.h +++ b/libraries/AP_WindVane/AP_WindVane.h @@ -15,8 +15,8 @@ #pragma once #include -#include -#include +#include +#include #ifndef WINDVANE_DEFAULT_PIN #define WINDVANE_DEFAULT_PIN -1 // default wind vane sensor analog pin @@ -58,7 +58,7 @@ class AP_WindVane bool wind_speed_enabled() const; // Initialize the Wind Vane object and prepare it for use - void init(const AP_SerialManager& serial_manager); + void init(const class AP_SerialManager& serial_manager); // update wind vane void update(); @@ -88,7 +88,7 @@ class AP_WindVane Sailboat_Tack get_current_tack() const { return _current_tack; } // record home heading for use as wind direction if no sensor is fitted - void record_home_heading() { _home_heading = AP::ahrs().yaw; } + void record_home_heading(); // start calibration routine bool start_direction_calibration(); diff --git a/libraries/AP_WindVane/AP_WindVane_Analog.cpp b/libraries/AP_WindVane/AP_WindVane_Analog.cpp index ecf38c5dad8..cee49bdd1ef 100644 --- a/libraries/AP_WindVane/AP_WindVane_Analog.cpp +++ b/libraries/AP_WindVane/AP_WindVane_Analog.cpp @@ -15,8 +15,17 @@ #include "AP_WindVane_Analog.h" +#include +#include + +extern const AP_HAL::HAL& hal; + #define WINDVANE_CALIBRATION_VOLT_DIFF_MIN 1.0f // calibration routine's min voltage difference required for success +#include + +extern const AP_HAL::HAL& hal; + // constructor AP_WindVane_Analog::AP_WindVane_Analog(AP_WindVane &frontend) : AP_WindVane_Backend(frontend) diff --git a/libraries/AP_WindVane/AP_WindVane_Analog.h b/libraries/AP_WindVane/AP_WindVane_Analog.h index eed943835c3..017266b0be9 100644 --- a/libraries/AP_WindVane/AP_WindVane_Analog.h +++ b/libraries/AP_WindVane/AP_WindVane_Analog.h @@ -16,11 +16,6 @@ #include "AP_WindVane_Backend.h" -#include -#include - -extern const AP_HAL::HAL& hal; - class AP_WindVane_Analog : public AP_WindVane_Backend { public: @@ -33,7 +28,7 @@ class AP_WindVane_Analog : public AP_WindVane_Backend private: // pin for reading analog voltage - AP_HAL::AnalogSource *_dir_analog_source; + class AP_HAL::AnalogSource *_dir_analog_source; float _current_analog_voltage; uint32_t _cal_start_ms = 0; diff --git a/libraries/AP_WindVane/AP_WindVane_Backend.cpp b/libraries/AP_WindVane/AP_WindVane_Backend.cpp index 02e041a2526..39f9ac9ed79 100644 --- a/libraries/AP_WindVane/AP_WindVane_Backend.cpp +++ b/libraries/AP_WindVane/AP_WindVane_Backend.cpp @@ -16,6 +16,8 @@ #include "AP_WindVane.h" #include "AP_WindVane_Backend.h" +#include + // base class constructor. AP_WindVane_Backend::AP_WindVane_Backend(AP_WindVane &frontend) : _frontend(frontend) diff --git a/libraries/AP_WindVane/AP_WindVane_Backend.h b/libraries/AP_WindVane/AP_WindVane_Backend.h index c2319acfba7..e347de49723 100644 --- a/libraries/AP_WindVane/AP_WindVane_Backend.h +++ b/libraries/AP_WindVane/AP_WindVane_Backend.h @@ -16,9 +16,6 @@ #include "AP_WindVane.h" -#include -#include - class AP_WindVane_Backend { public: diff --git a/libraries/AP_WindVane/AP_WindVane_Home.cpp b/libraries/AP_WindVane/AP_WindVane_Home.cpp index 64ed706402b..042d4ca0c18 100644 --- a/libraries/AP_WindVane/AP_WindVane_Home.cpp +++ b/libraries/AP_WindVane/AP_WindVane_Home.cpp @@ -15,6 +15,8 @@ #include "AP_WindVane_Home.h" +#include + void AP_WindVane_Home::update_direction() { float direction_apparent_ef = _frontend._home_heading; diff --git a/libraries/AP_WindVane/AP_WindVane_ModernDevice.cpp b/libraries/AP_WindVane/AP_WindVane_ModernDevice.cpp index 402f3b9f079..9daacb6c86b 100644 --- a/libraries/AP_WindVane/AP_WindVane_ModernDevice.cpp +++ b/libraries/AP_WindVane/AP_WindVane_ModernDevice.cpp @@ -17,6 +17,11 @@ // read wind speed from Modern Device rev p wind sensor // https://moderndevice.com/news/calibrating-rev-p-wind-sensor-new-regression/ +#include +#include + +extern const AP_HAL::HAL& hal; + // constructor AP_WindVane_ModernDevice::AP_WindVane_ModernDevice(AP_WindVane &frontend) : AP_WindVane_Backend(frontend) diff --git a/libraries/AP_WindVane/AP_WindVane_ModernDevice.h b/libraries/AP_WindVane/AP_WindVane_ModernDevice.h index 66b2e8c5c20..1d327088816 100644 --- a/libraries/AP_WindVane/AP_WindVane_ModernDevice.h +++ b/libraries/AP_WindVane/AP_WindVane_ModernDevice.h @@ -16,11 +16,6 @@ #include "AP_WindVane_Backend.h" -#include -#include - -extern const AP_HAL::HAL& hal; - class AP_WindVane_ModernDevice : public AP_WindVane_Backend { public: diff --git a/libraries/AP_WindVane/AP_WindVane_SITL.cpp b/libraries/AP_WindVane/AP_WindVane_SITL.cpp index 936ad2c63e2..c853185b97f 100644 --- a/libraries/AP_WindVane/AP_WindVane_SITL.cpp +++ b/libraries/AP_WindVane/AP_WindVane_SITL.cpp @@ -17,6 +17,9 @@ #if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#include +#include + void AP_WindVane_SITL::update_direction() { if (_frontend._direction_type == _frontend.WindVaneType::WINDVANE_SITL_TRUE) { diff --git a/libraries/AR_Motors/AP_MotorsUGV.cpp b/libraries/AR_Motors/AP_MotorsUGV.cpp index 4ae276adc7b..a74af181760 100644 --- a/libraries/AR_Motors/AP_MotorsUGV.cpp +++ b/libraries/AR_Motors/AP_MotorsUGV.cpp @@ -454,16 +454,6 @@ bool AP_MotorsUGV::output_test_pwm(motor_test_order motor_seq, float pwm) // returns true if checks pass, false if they fail. report should be true to send text messages to GCS bool AP_MotorsUGV::pre_arm_check(bool report) const { - // check if both regular and skid steering functions have been defined - if (SRV_Channels::function_assigned(SRV_Channel::k_throttleLeft) && - SRV_Channels::function_assigned(SRV_Channel::k_throttleRight) && - SRV_Channels::function_assigned(SRV_Channel::k_throttle) && - SRV_Channels::function_assigned(SRV_Channel::k_steering)) { - if (report) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: regular AND skid steering configured"); - } - return false; - } // check if only one of skid-steering output has been configured if (SRV_Channels::function_assigned(SRV_Channel::k_throttleLeft) != SRV_Channels::function_assigned(SRV_Channel::k_throttleRight)) { if (report) { @@ -494,9 +484,9 @@ bool AP_MotorsUGV::pre_arm_check(bool report) const // sanity check parameters void AP_MotorsUGV::sanity_check_parameters() { - _throttle_min = constrain_int16(_throttle_min, 0, 20); - _throttle_max = constrain_int16(_throttle_max, 30, 100); - _vector_angle_max = constrain_float(_vector_angle_max, 0.0f, 90.0f); + _throttle_min.set(constrain_int16(_throttle_min, 0, 20)); + _throttle_max.set(constrain_int16(_throttle_max, 30, 100)); + _vector_angle_max.set(constrain_float(_vector_angle_max, 0.0f, 90.0f)); } // setup pwm output type @@ -504,6 +494,8 @@ void AP_MotorsUGV::setup_pwm_type() { _motor_mask = 0; + hal.rcout->set_dshot_esc_type(SRV_Channels::get_dshot_esc_type()); + // work out mask of channels assigned to motors _motor_mask |= SRV_Channels::get_output_channel_mask(SRV_Channel::k_throttle); _motor_mask |= SRV_Channels::get_output_channel_mask(SRV_Channel::k_throttleLeft); @@ -634,7 +626,7 @@ void AP_MotorsUGV::output_regular(bool armed, float ground_speed, float steering // normalise desired steering and throttle to ease calculations float steering_norm = steering / 4500.0f; - const float throttle_norm = throttle / 100.0f; + const float throttle_norm = throttle * 0.01f; // steering can never be more than throttle * tan(_vector_angle_max) const float vector_angle_max_rad = radians(constrain_float(_vector_angle_max, 0.0f, 90.0f)); @@ -739,7 +731,7 @@ void AP_MotorsUGV::output_skid_steering(bool armed, float steering, float thrott // skid steering mixer float steering_scaled = steering / 4500.0f; // steering scaled -1 to +1 - float throttle_scaled = throttle / 100.0f; // throttle scaled -1 to +1 + float throttle_scaled = throttle * 0.01f; // throttle scaled -1 to +1 // apply constraints steering_scaled = constrain_float(steering_scaled, -1.0f, 1.0f); @@ -800,9 +792,9 @@ void AP_MotorsUGV::output_omni(bool armed, float steering, float throttle, float steering = constrain_float(steering, -4500.0f, 4500.0f); // scale throttle, steering and lateral inputs to -1 to 1 - const float scaled_throttle = throttle / 100.0f; + const float scaled_throttle = throttle * 0.01f; const float scaled_steering = steering / 4500.0f; - const float scaled_lateral = lateral / 100.0f; + const float scaled_lateral = lateral * 0.01f; float thr_str_ltr_out[AP_MOTORS_NUM_MOTORS_MAX]; float thr_str_ltr_max = 1; @@ -956,9 +948,9 @@ float AP_MotorsUGV::get_scaled_throttle(float throttle) const // scale using throttle_min if (_throttle_min > 0) { if (is_negative(throttle)) { - throttle = -_throttle_min + (throttle * ((100.0f - _throttle_min) / 100.0f)); + throttle = -_throttle_min + (throttle * ((100.0f - _throttle_min) * 0.01f)); } else { - throttle = _throttle_min + (throttle * ((100.0f - _throttle_min) / 100.0f)); + throttle = _throttle_min + (throttle * ((100.0f - _throttle_min) * 0.01f)); } } @@ -969,7 +961,7 @@ float AP_MotorsUGV::get_scaled_throttle(float throttle) const // calculate scaler const float sign = (throttle < 0.0f) ? -1.0f : 1.0f; - const float throttle_pct = constrain_float(throttle, -100.0f, 100.0f) / 100.0f; + const float throttle_pct = constrain_float(throttle, -100.0f, 100.0f) * 0.01f; return 100.0f * sign * ((_thrust_curve_expo - 1.0f) + safe_sqrt((1.0f - _thrust_curve_expo) * (1.0f - _thrust_curve_expo) + 4.0f * _thrust_curve_expo * fabsf(throttle_pct))) / (2.0f * _thrust_curve_expo); } diff --git a/libraries/AR_Motors/AP_MotorsUGV.h b/libraries/AR_Motors/AP_MotorsUGV.h index 35c11546448..667c9fe9ff7 100644 --- a/libraries/AR_Motors/AP_MotorsUGV.h +++ b/libraries/AR_Motors/AP_MotorsUGV.h @@ -3,6 +3,7 @@ #include #include #include +#include class AP_MotorsUGV { public: @@ -106,7 +107,7 @@ class AP_MotorsUGV { bool pre_arm_check(bool report) const; // return the motor mask - uint16_t get_motor_mask() const { return _motor_mask; } + uint32_t get_motor_mask() const { return _motor_mask; } // returns true if the configured PWM type is digital and should have fixed endpoints bool is_digital_pwm_type() const; @@ -215,7 +216,7 @@ class AP_MotorsUGV { float _mainsail; // requested mainsail input as a value from 0 to 100 float _wingsail; // requested wing sail input as a value in the range +- 100 float _mast_rotation; // requested mast rotation input as a value in the range +- 100 - uint16_t _motor_mask; // mask of motors configured with pwm_type + uint32_t _motor_mask; // mask of motors configured with pwm_type frame_type _frame_type; // frame type requested at initialisation // omni variables diff --git a/libraries/AR_WPNav/AR_PivotTurn.cpp b/libraries/AR_WPNav/AR_PivotTurn.cpp new file mode 100644 index 00000000000..cc82d9bb826 --- /dev/null +++ b/libraries/AR_WPNav/AR_PivotTurn.cpp @@ -0,0 +1,152 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +#include +#include +#include +#include "AR_PivotTurn.h" + +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#include +#endif + +extern const AP_HAL::HAL& hal; + +#define AR_PIVOT_TIMEOUT_MS 100 // pivot controller timesout and reset target if not called within this many milliseconds +#define AR_PIVOT_ANGLE_DEFAULT 60 // default PIVOT_ANGLE parameter value +#define AR_PIVOT_ANGLE_ACCURACY 5 // vehicle will pivot to within this many degrees of destination +#define AR_PIVOT_RATE_DEFAULT 60 // default PIVOT_RATE parameter value +#define AR_PIVOT_DELAY_DEFAULT 0 // default PIVOT_DELAY parameter value + +const AP_Param::GroupInfo AR_PivotTurn::var_info[] = { + + // @Param: ANGLE + // @DisplayName: Pivot Angle + // @Description: Pivot when the difference between the vehicle's heading and its target heading is more than this many degrees. Set to zero to disable pivot turns. This parameter should be greater than 5 degrees for pivot turns to work. + // @Units: deg + // @Range: 0 360 + // @Increment: 1 + // @User: Standard + AP_GROUPINFO("ANGLE", 1, AR_PivotTurn, _angle, AR_PIVOT_ANGLE_DEFAULT), + + // @Param: RATE + // @DisplayName: Pivot Turn Rate + // @Description: Turn rate during pivot turns + // @Units: deg/s + // @Range: 0 360 + // @Increment: 1 + // @User: Standard + AP_GROUPINFO("RATE", 2, AR_PivotTurn, _rate_max, AR_PIVOT_RATE_DEFAULT), + + // @Param: DELAY + // @DisplayName: Pivot Delay + // @Description: Vehicle waits this many seconds after completing a pivot turn before proceeding + // @Units: s + // @Range: 0 60 + // @Increment: 0.1 + // @User: Standard + AP_GROUPINFO("DELAY", 3, AR_PivotTurn, _delay, AR_PIVOT_DELAY_DEFAULT), + + AP_GROUPEND +}; + +AR_PivotTurn::AR_PivotTurn(AR_AttitudeControl& atc) : + _atc(atc) +{ + AP_Param::setup_object_defaults(this, var_info); +} + +// enable or disable pivot controller +void AR_PivotTurn::enable(bool enable_pivot) +{ + _enabled = enable_pivot; + if (!_enabled) { + _active = false; + } +} + +// true if update has been called recently +bool AR_PivotTurn::active() const +{ + return _enabled && _active; +} + +// checks if pivot turns should be activated or deactivated +// force_active should be true if the caller wishes to trigger the start of a pivot turn regardless of the heading error +void AR_PivotTurn::check_activation(float desired_heading_deg, bool force_active) +{ + // check cases where we clearly cannot use pivot steering + if (!_enabled || (_angle <= AR_PIVOT_ANGLE_ACCURACY)) { + _active = false; + return; + } + + // calc yaw error in degrees + const float yaw_error = fabsf(wrap_180(desired_heading_deg - (AP::ahrs().yaw_sensor * 0.01f))); + + // if error is larger than _pivot_angle start pivot steering + if (yaw_error > _angle || force_active) { + _active = true; + _delay_start_ms = 0; + return; + } + + uint32_t now_ms = AP_HAL::millis(); + + // if within 5 degrees of the target heading, set start time of pivot steering + if (_active && (yaw_error < AR_PIVOT_ANGLE_ACCURACY) && (_delay_start_ms == 0)) { + _delay_start_ms = now_ms; + } + + // exit pivot steering after the time set by pivot_delay has elapsed + if ((_delay_start_ms > 0) && + (now_ms - _delay_start_ms) >= get_delay_duration_ms()) { + _active = false; + _delay_start_ms = 0; + } +} + +// check if pivot turn would be activated given an expected change in yaw in degrees +// note this does not actually active the pivot turn. To activate use the check_activation method +bool AR_PivotTurn::would_activate(float yaw_change_deg) const +{ + // check cases where we clearly cannot use pivot steering + if (!_enabled || (_angle <= AR_PIVOT_ANGLE_ACCURACY)) { + return false; + } + + // return true if yaw change is larger than _pivot_angle + return fabsf(wrap_180(yaw_change_deg)) > _angle; +} + +// get turn rate (in rad/sec) +// desired heading should be the heading towards the next waypoint in degrees +// dt should be the time since the last call in seconds +float AR_PivotTurn::get_turn_rate_rads(float desired_heading_deg, float dt) +{ + // handle pivot turns + const float desired_turn_rate_rads = _atc.get_turn_rate_from_heading(radians(desired_heading_deg), radians(_rate_max)); + + // update flag so that it can be cleared + check_activation(desired_heading_deg); + + return desired_turn_rate_rads; +} + +// return post-turn delay duration in milliseconds +uint32_t AR_PivotTurn::get_delay_duration_ms() const +{ + return constrain_float(_delay.get(), 0.0f, 60.0f) * 1000; +} diff --git a/libraries/AR_WPNav/AR_PivotTurn.h b/libraries/AR_WPNav/AR_PivotTurn.h new file mode 100644 index 00000000000..035a4d28eeb --- /dev/null +++ b/libraries/AR_WPNav/AR_PivotTurn.h @@ -0,0 +1,70 @@ +#pragma once + +#include +#include + +/* + * Pivot Turn controller for skid-steering rovers and boats + * + * How-to-Use: + * 1. call "enable(true)" once for skid-steering vehicles to enable this controller + * 2. before vehicle starts towards a waypoint call "check_activation" and provide the earth-frame heading to the waypoint + * this may change the controller's internal state to "active" + * 3. on each main loop iteration call "active()" to see if this controller thinks it is controllering the vehicle + * 4. call "get_turn_rate_rads()" to retrieve the desired turn rate towards the next waypoint + * 5. pass above turn rate into the rate controller, set speed controller's speed to zero + * 6. this controller's "active" state will change to false once it has completed the pivot turn + */ + +class AR_PivotTurn { +public: + + // constructor + AR_PivotTurn(AR_AttitudeControl& atc); + + // enable or disable pivot controller + void enable(bool enable_pivot); + + // true if this controller is controlling vehicle + bool active() const; + + // checks if pivot turns should be activated or deactivated + // force_active should be true if the caller wishes to trigger the start of a pivot turn regardless of the heading error + void check_activation(float desired_heading_deg, bool force_active = false); + + // check if pivot turn would be activated given an expected change in yaw in degrees + // note this does not actually active the pivot turn. To activate use the check_activation method + bool would_activate(float yaw_change_deg) const WARN_IF_UNUSED; + + // forcibly deactivate this controller + void deactivate() { _active = false; }; + + // get turn rate (in rad/sec) + // desired heading should be the heading towards the next waypoint in degrees + // dt should be the time since the last call in seconds + float get_turn_rate_rads(float desired_heading_deg, float dt); + + // accessors for parameter values + float get_rate_max() const { return _rate_max; } + + // parameter var table + static const struct AP_Param::GroupInfo var_info[]; + +private: + + // return post-turn delay duration in milliseconds + uint32_t get_delay_duration_ms() const; + + // parameters + AP_Int16 _angle; // minimum angle error (in degrees) that leads to pivot turn + AP_Int16 _rate_max; // maximum turn rate (in degrees) during pivot turn + AP_Float _delay; // waiting time (in seconds) after pivot turn completes + + // references + AR_AttitudeControl& _atc; // rover attitude control library + + // local variables + bool _enabled; // true if vehicle can pivot + bool _active; // true if vehicle is currently pivoting + uint32_t _delay_start_ms; // system time when post-turn delay started +}; diff --git a/libraries/AR_WPNav/AR_WPNav.cpp b/libraries/AR_WPNav/AR_WPNav.cpp index 1e550ca023d..8372180efd8 100644 --- a/libraries/AR_WPNav/AR_WPNav.cpp +++ b/libraries/AR_WPNav/AR_WPNav.cpp @@ -13,19 +13,26 @@ along with this program. If not, see . */ +#include #include #include #include "AR_WPNav.h" +#include + +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#include +#endif extern const AP_HAL::HAL& hal; #define AR_WPNAV_TIMEOUT_MS 100 #define AR_WPNAV_SPEED_DEFAULT 2.0f +#define AR_WPNAV_SPEED_MIN 0.05f // minimum speed between waypoints in m/s +#define AR_WPNAV_SPEED_UPDATE_MIN_MS 500 // max speed cannot be updated more than once in this many milliseconds #define AR_WPNAV_RADIUS_DEFAULT 2.0f -#define AR_WPNAV_OVERSHOOT_DEFAULT 2.0f -#define AR_WPNAV_PIVOT_ANGLE_DEFAULT 60 -#define AR_WPNAV_PIVOT_ANGLE_ACCURACY 5 // vehicle will pivot to within this many degrees of destination -#define AR_WPNAV_PIVOT_RATE_DEFAULT 90 +#define AR_WPNAV_OVERSPEED_RATIO_MAX 5.0f // if _overspeed_enabled the vehicle may travel as quickly as 5x WP_SPEED +#define AR_WPNAV_SNAP_MAX 15.0f // scurve snap (change in jerk) in m/s/s/s/s +#define AR_WPNAV_ACCEL_MAX 20.0 // acceleration used when user has specified no acceleration limit const AP_Param::GroupInfo AR_WPNav::var_info[] = { @@ -47,61 +54,88 @@ const AP_Param::GroupInfo AR_WPNav::var_info[] = { // @User: Standard AP_GROUPINFO("RADIUS", 2, AR_WPNav, _radius, AR_WPNAV_RADIUS_DEFAULT), - // @Param: OVERSHOOT - // @DisplayName: Waypoint overshoot maximum - // @Description: Waypoint overshoot maximum in meters. The vehicle will attempt to stay within this many meters of the track as it completes one waypoint and moves to the next. - // @Units: m - // @Range: 0 10 - // @Increment: 0.1 - // @User: Standard - AP_GROUPINFO("OVERSHOOT", 3, AR_WPNav, _overshoot, AR_WPNAV_OVERSHOOT_DEFAULT), - - // @Param: PIVOT_ANGLE - // @DisplayName: Waypoint Pivot Angle - // @Description: Pivot when the difference between the vehicle's heading and its target heading is more than this many degrees. Set to zero to disable pivot turns. Note: This parameter should be greater than 10 degrees for pivot turns to work. - // @Units: deg - // @Range: 0 360 - // @Increment: 1 - // @User: Standard - AP_GROUPINFO("PIVOT_ANGLE", 4, AR_WPNav, _pivot_angle, AR_WPNAV_PIVOT_ANGLE_DEFAULT), - - // @Param: PIVOT_RATE - // @DisplayName: Waypoint Pivot Turn Rate - // @Description: Turn rate during pivot turns - // @Units: deg/s - // @Range: 0 360 - // @Increment: 1 - // @User: Standard - AP_GROUPINFO("PIVOT_RATE", 5, AR_WPNav, _pivot_rate, AR_WPNAV_PIVOT_RATE_DEFAULT), + // 3 was OVERSHOOT - // @Param: SPEED_MIN - // @DisplayName: Waypoint speed minimum - // @Description: Vehicle will not slow below this speed for corners. Should be set to boat's plane speed. Does not apply to pivot turns. - // @Units: m/s + // 4 was PIVOT_ANGLE + // 5 was PIVOT_RATE + // 6 was SPEED_MIN + // 7 was PIVOT_DELAY + + // @Group: PIVOT_ + // @Path: AR_PivotTurn.cpp + AP_SUBGROUPINFO(_pivot, "PIVOT_", 8, AR_WPNav, AR_PivotTurn), + + // @Param: ACCEL + // @DisplayName: Waypoint acceleration + // @Description: Waypoint acceleration. If zero then ATC_ACCEL_MAX is used + // @Units: m/s/s // @Range: 0 100 // @Increment: 0.1 // @User: Standard - AP_GROUPINFO("SPEED_MIN", 6, AR_WPNav, _speed_min, 0), + AP_GROUPINFO("ACCEL", 9, AR_WPNav, _accel_max, 0), - // @Param: PIVOT_DELAY - // @DisplayName: Delay after pivot turn - // @Description: Waiting time after pivot turn - // @Units: s - // @Range: 0 60 + // @Param: JERK + // @DisplayName: Waypoint jerk + // @Description: Waypoint jerk (change in acceleration). If zero then jerk is same as acceleration + // @Units: m/s/s/s + // @Range: 0 100 // @Increment: 0.1 // @User: Standard - AP_GROUPINFO("PIVOT_DELAY", 7, AR_WPNav, _pivot_delay, 0), + AP_GROUPINFO("JERK", 10, AR_WPNav, _jerk_max, 0), AP_GROUPEND }; -AR_WPNav::AR_WPNav(AR_AttitudeControl& atc, AP_Navigation& nav_controller) : +AR_WPNav::AR_WPNav(AR_AttitudeControl& atc, AR_PosControl &pos_control) : _atc(atc), - _nav_controller(nav_controller) + _pos_control(pos_control), + _pivot(atc) { AP_Param::setup_object_defaults(this, var_info); } +// initialise waypoint controller. speed_max should be set to the maximum speed in m/s (or left at zero to use the default speed) +void AR_WPNav::init(float speed_max) +{ + // determine max speed, acceleration and jerk + if (is_positive(speed_max)) { + _base_speed_max = speed_max; + } else { + _base_speed_max = _speed_max; + } + _base_speed_max = MAX(AR_WPNAV_SPEED_MIN, _base_speed_max); + float atc_accel_max = MIN(_atc.get_accel_max(), _atc.get_decel_max()); + if (!is_positive(atc_accel_max)) { + // accel_max of zero means no limit so use maximum acceleration + atc_accel_max = AR_WPNAV_ACCEL_MAX; + } + const float accel_max = is_positive(_accel_max) ? MIN(_accel_max, atc_accel_max) : atc_accel_max; + const float jerk_max = is_positive(_jerk_max) ? _jerk_max : accel_max; + + // initialise position controller + _pos_control.set_limits(_base_speed_max, accel_max, _atc.get_turn_lat_accel_max(), jerk_max); + + _scurve_prev_leg.init(); + _scurve_this_leg.init(); + _scurve_next_leg.init(); + _track_scalar_dt = 1.0f; + + // init some flags + _reached_destination = false; + _fast_waypoint = false; + + // ensure pivot turns are deactivated + _pivot.deactivate(); + _pivot_at_next_wp = false; + + // initialise origin and destination to stopping point + _orig_and_dest_valid = false; + set_origin_and_destination_to_stopping_point(); + + // initialise nudge speed to zero + set_nudge_speed_max(0); +} + // update navigation void AR_WPNav::update(float dt) { @@ -110,7 +144,9 @@ void AR_WPNav::update(float dt) float speed; if (!hal.util->get_soft_armed() || !_orig_and_dest_valid || !AP::ahrs().get_location(current_loc) || !_atc.get_forward_speed(speed)) { _desired_speed_limited = _atc.get_desired_speed_accel_limited(0.0f, dt); + _desired_lat_accel = 0.0f; _desired_turn_rate_rads = 0.0f; + _cross_track_error = 0; return; } @@ -120,118 +156,143 @@ void AR_WPNav::update(float dt) } _last_update_ms = AP_HAL::millis(); - // run path planning around obstacles - bool stop_vehicle = false; - - // true if OA has been recently active; - bool _oa_was_active = _oa_active; - - AP_OAPathPlanner *oa = AP_OAPathPlanner::get_singleton(); - if (oa != nullptr) { - AP_OAPathPlanner::OAPathPlannerUsed path_planner_used; - const AP_OAPathPlanner::OA_RetState oa_retstate = oa->mission_avoidance(current_loc, _origin, _destination, _oa_origin, _oa_destination, path_planner_used); - switch (oa_retstate) { - case AP_OAPathPlanner::OA_NOT_REQUIRED: - _oa_active = false; - break; - case AP_OAPathPlanner::OA_PROCESSING: - case AP_OAPathPlanner::OA_ERROR: - // during processing or in case of error, slow vehicle to a stop - stop_vehicle = true; - _oa_active = false; - break; - case AP_OAPathPlanner::OA_SUCCESS: - _oa_active = true; - break; - } - } - if (!_oa_active) { - _oa_origin = _origin; - _oa_destination = _destination; - } - update_distance_and_bearing_to_destination(); - // if object avoidance is active check if vehicle should pivot towards destination - if (_oa_active) { - update_pivot_active_flag(); - } + // handle change in max speed + update_speed_max(); - // check if vehicle is in recovering state after switching off OA - if (!_oa_active && _oa_was_active) { - if (oa->get_options() & AP_OAPathPlanner::OA_OPTION_WP_RESET) { - //reset wp origin to vehicles current location - _origin = current_loc; + // advance target along path unless vehicle is pivoting + if (!_pivot.active()) { + switch (_nav_control_type) { + case NavControllerType::NAV_SCURVE: + advance_wp_target_along_track(current_loc, dt); + break; + case NavControllerType::NAV_PSC_INPUT_SHAPING: + update_psc_input_shaping(dt); + break; } } - // check if vehicle has reached the destination - const bool near_wp = _distance_to_destination <= _radius; - const bool past_wp = !_oa_active && current_loc.past_interval_finish_line(_origin, _destination); - if (!_reached_destination && (near_wp || past_wp)) { - _reached_destination = true; - } + // update_steering_and_speed + update_steering_and_speed(current_loc, dt); +} - // handle stopping vehicle if avoidance has failed - if (stop_vehicle) { - // decelerate to speed to zero and set turn rate to zero - _desired_speed_limited = _atc.get_desired_speed_accel_limited(0.0f, dt); - _desired_lat_accel = 0.0f; - _desired_turn_rate_rads = 0.0f; - return; +// set maximum speed in m/s. returns true on success +// this should not be called at more than 3hz or else SCurve path planning may not advance properly +bool AR_WPNav::set_speed_max(float speed_max) +{ + // range check target speed + if (speed_max < AR_WPNAV_SPEED_MIN) { + return false; } - // calculate the required turn of the wheels - update_steering(current_loc, speed); + _base_speed_max = speed_max; + return true; +} - // calculate desired speed - update_desired_speed(dt); +// set speed nudge in m/s. this will have no effect unless nudge_speed_max > speed_max +// nudge_speed_max should always be positive regardless of whether the vehicle is travelling forward or reversing +void AR_WPNav::set_nudge_speed_max(float nudge_speed_max) +{ + _nudge_speed_max = nudge_speed_max; } -// set desired location -bool AR_WPNav::set_desired_location(const struct Location& destination, float next_leg_bearing_cd) +// set desired location and (optionally) next_destination +// next_destination should be provided if known to allow smooth cornering +bool AR_WPNav::set_desired_location(const struct Location& destination, Location next_destination) { - // set origin to last destination if waypoint controller active - if (is_active() && _orig_and_dest_valid && _reached_destination) { - _origin = _destination; - } else { - // otherwise use reasonable stopping point - if (!get_stopping_location(_origin)) { + // re-initialise if inactive, previous destination has been interrupted or different controller was used + if (!is_active() || !_reached_destination || (_nav_control_type != NavControllerType::NAV_SCURVE)) { + if (!set_origin_and_destination_to_stopping_point()) { return false; } + // clear scurves + _scurve_prev_leg.init(); + _scurve_this_leg.init(); + _scurve_next_leg.init(); } + // shift this leg to previous leg + _scurve_prev_leg = _scurve_this_leg; + // initialise some variables - _oa_origin = _origin; - _oa_destination = _destination = destination; + _origin = _destination; + _destination = destination; _orig_and_dest_valid = true; _reached_destination = false; + update_distance_and_bearing_to_destination(); - // determine if we should pivot immediately - update_pivot_active_flag(); - - // set final desired speed and whether vehicle should pivot - _desired_speed_final = 0.0f; - if (!is_equal(next_leg_bearing_cd, AR_WPNAV_HEADING_UNKNOWN)) { - const float curr_leg_bearing_cd = _origin.get_bearing_to(_destination); - const float turn_angle_cd = wrap_180_cd(next_leg_bearing_cd - curr_leg_bearing_cd); - if (fabsf(turn_angle_cd) < 10.0f) { - // if turning less than 0.1 degrees vehicle can continue at full speed - // we use 0.1 degrees instead of zero to avoid divide by zero in calcs below - _desired_speed_final = _desired_speed; - } else if (use_pivot_steering_at_next_WP(turn_angle_cd)) { - // pivoting so we will stop - _desired_speed_final = 0.0f; - } else { - // calculate maximum speed that keeps overshoot within bounds - const float radius_m = fabsf(_overshoot / (cosf(radians(turn_angle_cd * 0.01f)) - 1.0f)); - _desired_speed_final = MIN(_desired_speed, safe_sqrt(_atc.get_turn_lat_accel_max() * radius_m)); - // ensure speed does not fall below minimum - apply_speed_min(_desired_speed_final); + // check if vehicle should pivot if vehicle stopped at previous waypoint + // or journey to previous waypoint was interrupted or navigation has just started + if (!_fast_waypoint) { + _pivot.deactivate(); + _pivot.check_activation((_reversed ? wrap_360_cd(oa_wp_bearing_cd() + 18000) : oa_wp_bearing_cd()) * 0.01, _pivot_at_next_wp); + } + + // convert origin and destination to offset from EKF origin + Vector2f origin_NE; + Vector2f destination_NE; + if (!_origin.get_vector_xy_from_origin_NE(origin_NE) || + !_destination.get_vector_xy_from_origin_NE(destination_NE)) { + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + return false; + } + origin_NE *= 0.01f; + destination_NE *= 0.01f; + + // calculate track to destination + if (_fast_waypoint && !_scurve_next_leg.finished()) { + // skip recalculating this leg by simply shifting next leg + _scurve_this_leg = _scurve_next_leg; + } else { + _scurve_this_leg.calculate_track(Vector3f{origin_NE.x, origin_NE.y, 0.0f}, // origin + Vector3f{destination_NE.x, destination_NE.y, 0.0f}, // destination + _pos_control.get_speed_max(), + _pos_control.get_speed_max(), // speed up (not used) + _pos_control.get_speed_max(), // speed down (not used) + _pos_control.get_accel_max(), // forward back acceleration + _pos_control.get_accel_max(), // vertical accel (not used) + AR_WPNAV_SNAP_MAX, // snap + _pos_control.get_jerk_max()); + } + + // handle next destination + _scurve_next_leg.init(); + _fast_waypoint = false; + _pivot_at_next_wp = false; + if (next_destination.initialised()) { + // check if vehicle should pivot at next waypoint + const float next_wp_yaw_change = get_corner_angle(_origin, destination, next_destination); + _pivot_at_next_wp = _pivot.would_activate(next_wp_yaw_change); + if (!_pivot_at_next_wp) { + // convert next_destination to offset from EKF origin + Vector2f next_destination_NE; + if (!next_destination.get_vector_xy_from_origin_NE(next_destination_NE)) { + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + return false; + } + next_destination_NE *= 0.01f; + _scurve_next_leg.calculate_track(Vector3f{destination_NE.x, destination_NE.y, 0.0f}, + Vector3f{next_destination_NE.x, next_destination_NE.y, 0.0f}, + _pos_control.get_speed_max(), + _pos_control.get_speed_max(), // speed up (not used) + _pos_control.get_speed_max(), // speed down (not used) + _pos_control.get_accel_max(), // forward back acceleration + _pos_control.get_accel_max(), // vertical accel (not used) + AR_WPNAV_SNAP_MAX, // snap + _pos_control.get_jerk_max()); + + // next destination provided so fast waypoint + _fast_waypoint = true; } } + // scurves used for navigation to destination + _nav_control_type = NavControllerType::NAV_SCURVE; + + update_distance_and_bearing_to_destination(); + return true; } @@ -246,7 +307,7 @@ bool AR_WPNav::set_desired_location_to_stopping_location() } // set desired location as offset from the EKF origin, return true on success -bool AR_WPNav::set_desired_location_NED(const Vector3f& destination, float next_leg_bearing_cd) +bool AR_WPNav::set_desired_location_NED(const Vector3f& destination) { // initialise destination to ekf origin Location destination_ned; @@ -256,7 +317,50 @@ bool AR_WPNav::set_desired_location_NED(const Vector3f& destination, float next_ // apply offset destination_ned.offset(destination.x, destination.y); - return set_desired_location(destination_ned, next_leg_bearing_cd); + return set_desired_location(destination_ned); +} + +bool AR_WPNav::set_desired_location_NED(const Vector3f &destination, const Vector3f &next_destination) +{ + // initialise destination to ekf origin + Location dest_loc, next_dest_loc; + if (!AP::ahrs().get_origin(dest_loc)) { + return false; + } + next_dest_loc = dest_loc; + + // apply offsets + dest_loc.offset(destination.x, destination.y); + next_dest_loc.offset(next_destination.x, next_destination.y); + return set_desired_location(dest_loc, next_dest_loc); +} + +// set desired location but expect the destination to be updated again in the near future +// position controller input shaping will be used for navigation instead of scurves +// Note: object avoidance is not supported if this method is used +bool AR_WPNav::set_desired_location_expect_fast_update(const Location &destination) +{ + // initialise if not active + if (!is_active() || (_nav_control_type != NavControllerType::NAV_PSC_INPUT_SHAPING)) { + if (!set_origin_and_destination_to_stopping_point()) { + return false; + } + } + + // initialise some variables + _origin = _destination; + _destination = destination; + _orig_and_dest_valid = true; + _reached_destination = false; + + update_distance_and_bearing_to_destination(); + + // check if vehicle should pivot + _pivot.check_activation((_reversed ? wrap_360_cd(oa_wp_bearing_cd() + 18000) : oa_wp_bearing_cd()) * 0.01); + + // position controller input shaping used for navigation to destination + _nav_control_type = NavControllerType::NAV_PSC_INPUT_SHAPING; + return true; } // calculate vehicle stopping point using current location, velocity and maximum acceleration @@ -288,61 +392,98 @@ bool AR_WPNav::get_stopping_location(Location& stopping_loc) return true; } -// returns true if vehicle should pivot turn at next waypoint -bool AR_WPNav::use_pivot_steering_at_next_WP(float yaw_error_cd) const +// true if update has been called recently +bool AR_WPNav::is_active() const { - // check cases where we clearly cannot use pivot steering - if (!_pivot_possible || _pivot_angle <= AR_WPNAV_PIVOT_ANGLE_ACCURACY) { - return false; - } - - // if error is larger than _pivot_angle then use pivot steering at next WP - if (fabsf(yaw_error_cd) * 0.01f > _pivot_angle) { - return true; - } - - return false; + return ((AP_HAL::millis() - _last_update_ms) < AR_WPNAV_TIMEOUT_MS); } -// updates _pivot_active flag based on heading error to destination -// relies on update_distance_and_bearing_to_destination having been called first -// to update _oa_wp_bearing and _reversed variables -void AR_WPNav::update_pivot_active_flag() +// move target location along track from origin to destination using SCurves navigation +void AR_WPNav::advance_wp_target_along_track(const Location ¤t_loc, float dt) { - // check cases where we clearly cannot use pivot steering - if (!_pivot_possible || (_pivot_angle <= AR_WPNAV_PIVOT_ANGLE_ACCURACY)) { - _pivot_active = false; + // exit immediately if no current location, destination or disarmed + Vector2f curr_pos_NE; + Vector3f curr_vel_NED; + if (!AP::ahrs().get_relative_position_NE_origin(curr_pos_NE) || !AP::ahrs().get_velocity_NED(curr_vel_NED)) { return; } - // calc yaw error - const float yaw_cd = _reversed ? wrap_360_cd(_oa_wp_bearing_cd + 18000) : _oa_wp_bearing_cd; - const float yaw_error = fabsf(wrap_180_cd(yaw_cd - AP::ahrs().yaw_sensor)) * 0.01f; - - // if error is larger than _pivot_angle start pivot steering - if (yaw_error > _pivot_angle) { - _pivot_active = true; + // exit immediately if we can't convert waypoint origin to offset from ekf origin + Vector2f origin_NE; + if (!_origin.get_vector_xy_from_origin_NE(origin_NE)) { return; } - - uint32_t now = AP_HAL::millis(); - - // if within 5 degrees of the target heading, set start time of pivot steering - if (_pivot_active && yaw_error < AR_WPNAV_PIVOT_ANGLE_ACCURACY && _pivot_start_ms == 0) { - _pivot_start_ms = now; + // convert from cm to meters + origin_NE *= 0.01f; + + // use _track_scalar_dt to slow down S-Curve time to prevent target moving too far in front of vehicle + Vector2f curr_target_vel = _pos_control.get_desired_velocity(); + float track_scaler_dt = 1.0f; + if (is_positive(curr_target_vel.length())) { + Vector2f track_direction = curr_target_vel.normalized(); + const float track_error = _pos_control.get_pos_error().tofloat().dot(track_direction); + float track_velocity = curr_vel_NED.xy().dot(track_direction); + // set time scaler to be consistent with the achievable vehicle speed with a 5% buffer for short term variation. + const float time_scaler_dt_max = _overspeed_enabled ? AR_WPNAV_OVERSPEED_RATIO_MAX : 1.0f; + track_scaler_dt = constrain_float(0.05f + (track_velocity - _pos_control.get_pos_p().kP() * track_error) / curr_target_vel.length(), 0.1f, time_scaler_dt_max); } - - // exit pivot steering after the time set by pivot_delay has elapsed - if (_pivot_start_ms > 0 && now - _pivot_start_ms >= constrain_float(_pivot_delay.get(), 0.0f, 60.0f) * 1000.0f) { - _pivot_active = false; - _pivot_start_ms = 0; + // change s-curve time speed with a time constant of maximum acceleration / maximum jerk + float track_scaler_tc = 1.0f; + if (is_positive(_pos_control.get_jerk_max())) { + track_scaler_tc = _pos_control.get_accel_max() / _pos_control.get_jerk_max(); + } + _track_scalar_dt += (track_scaler_dt - _track_scalar_dt) * (dt / track_scaler_tc); + + // target position, velocity and acceleration from straight line or spline calculators + Vector3f target_pos_3d_ftype{origin_NE.x, origin_NE.y, 0.0f}; + Vector3f target_vel, target_accel; + + // update target position, velocity and acceleration + const float wp_radius = MAX(_radius, _turn_radius); + bool s_finished = _scurve_this_leg.advance_target_along_track(_scurve_prev_leg, _scurve_next_leg, wp_radius, _pos_control.get_lat_accel_max(), _fast_waypoint, _track_scalar_dt * dt, target_pos_3d_ftype, target_vel, target_accel); + + // pass new target to the position controller + init_pos_control_if_necessary(); + Vector2p target_pos_ptype{target_pos_3d_ftype.x, target_pos_3d_ftype.y}; + _pos_control.set_pos_vel_accel_target(target_pos_ptype, target_vel.xy(), target_accel.xy()); + + // check if we've reached the waypoint + if (!_reached_destination && s_finished) { + // "fast" waypoints are complete once the intermediate point reaches the destination + if (_fast_waypoint) { + _reached_destination = true; + } else { + // regular waypoints also require the vehicle to be within the waypoint radius or past the "finish line" + const bool near_wp = current_loc.get_distance(_destination) <= _radius; + const bool past_wp = current_loc.past_interval_finish_line(_origin, _destination); + _reached_destination = near_wp || past_wp; + } } } -// true if update has been called recently -bool AR_WPNav::is_active() const +// update psc input shaping navigation controller +void AR_WPNav::update_psc_input_shaping(float dt) { - return ((AP_HAL::millis() - _last_update_ms) < AR_WPNAV_TIMEOUT_MS); + // convert destination location to offset from EKF origin (in meters) + Vector2f pos_target_cm; + if (!_destination.get_vector_xy_from_origin_NE(pos_target_cm)) { + return; + } + + // initialise position controller if not called recently + init_pos_control_if_necessary(); + + // convert to meters and update target + const Vector2p pos_target = pos_target_cm.topostype() * 0.01; + _pos_control.input_pos_target(pos_target, dt); + + // update reached_destination + if (!_reached_destination) { + // calculate position difference between destination and position controller input shaped target + Vector2p pos_target_diff = pos_target - _pos_control.get_pos_target(); + // vehicle has reached destination when the target is within 1cm of the destination and vehicle is within waypoint radius + _reached_destination = (pos_target_diff.length_squared() < sq(0.01)) && (_pos_control.get_pos_error().length_squared() < sq(_radius)); + } } // update distance from vehicle's current position to destination @@ -353,145 +494,133 @@ void AR_WPNav::update_distance_and_bearing_to_destination() if (!_orig_and_dest_valid || !AP::ahrs().get_location(current_loc)) { _distance_to_destination = 0.0f; _wp_bearing_cd = 0.0f; - - // update OA adjusted values - _oa_distance_to_destination = 0.0f; - _oa_wp_bearing_cd = 0.0f; return; } _distance_to_destination = current_loc.get_distance(_destination); _wp_bearing_cd = current_loc.get_bearing_to(_destination); - - // update OA adjusted values - if (_oa_active) { - _oa_distance_to_destination = current_loc.get_distance(_oa_destination); - _oa_wp_bearing_cd = current_loc.get_bearing_to(_oa_destination); - } else { - _oa_distance_to_destination = _distance_to_destination; - _oa_wp_bearing_cd = _wp_bearing_cd; - } } -// calculate steering output to drive along line from origin to destination waypoint -// relies on update_distance_and_bearing_to_destination being called first so _wp_bearing_cd has been updated -void AR_WPNav::update_steering(const Location& current_loc, float current_speed) +// calculate steering and speed to drive along line from origin to destination waypoint +void AR_WPNav::update_steering_and_speed(const Location ¤t_loc, float dt) { - // calculate desired turn rate and update desired heading - if (_pivot_active) { - _cross_track_error = calc_crosstrack_error(current_loc); - _desired_heading_cd = _reversed ? wrap_360_cd(_oa_wp_bearing_cd + 18000) : _oa_wp_bearing_cd;; - _desired_lat_accel = 0.0f; - _desired_turn_rate_rads = _atc.get_turn_rate_from_heading(radians(_desired_heading_cd * 0.01f), radians(_pivot_rate)); - - // update flag so that it can be cleared - update_pivot_active_flag(); - } else { - // run L1 controller - _nav_controller.set_reverse(_reversed); - _nav_controller.update_waypoint(_reached_destination ? current_loc : _oa_origin, _oa_destination, _radius); - - // retrieve lateral acceleration, heading back towards line and crosstrack error - _desired_lat_accel = constrain_float(_nav_controller.lateral_acceleration(), -_atc.get_turn_lat_accel_max(), _atc.get_turn_lat_accel_max()); - _desired_heading_cd = wrap_360_cd(_nav_controller.nav_bearing_cd()); - if (_reversed) { - _desired_lat_accel *= -1.0f; - _desired_heading_cd = wrap_360_cd(_desired_heading_cd + 18000); - } - _cross_track_error = _nav_controller.crosstrack_error(); - _desired_turn_rate_rads = _atc.get_turn_rate_from_lat_accel(_desired_lat_accel, current_speed); - } -} + _cross_track_error = calc_crosstrack_error(current_loc); -// calculated desired speed(in m/s) based on yaw error and lateral acceleration and/or distance to a waypoint -// relies on update_distance_and_bearing_to_destination and update_steering being run so these internal members -// have been updated: _oa_wp_bearing_cd, _cross_track_error, _oa_distance_to_destination -void AR_WPNav::update_desired_speed(float dt) -{ - // reduce speed to zero during pivot turns - if (_pivot_active) { + // handle pivot turns + if (_pivot.active()) { // decelerate to zero _desired_speed_limited = _atc.get_desired_speed_accel_limited(0.0f, dt); + _desired_heading_cd = _reversed ? wrap_360_cd(oa_wp_bearing_cd() + 18000) : oa_wp_bearing_cd(); + _desired_turn_rate_rads = is_zero(_desired_speed_limited) ? _pivot.get_turn_rate_rads(_desired_heading_cd * 0.01, dt) : 0; + _desired_lat_accel = 0.0f; return; } - // accelerate desired speed towards max - float des_speed_lim = _atc.get_desired_speed_accel_limited(_reversed ? -_desired_speed : _desired_speed, dt); - - // reduce speed to limit overshoot from line between origin and destination - // calculate number of degrees vehicle must turn to face waypoint - float ahrs_yaw_sensor = AP::ahrs().yaw_sensor; - const float heading_cd = is_negative(des_speed_lim) ? wrap_180_cd(ahrs_yaw_sensor + 18000) : ahrs_yaw_sensor; - const float wp_yaw_diff_cd = wrap_180_cd(_oa_wp_bearing_cd - heading_cd); - const float turn_angle_rad = fabsf(radians(wp_yaw_diff_cd * 0.01f)); - - // calculate distance from vehicle to line + wp_overshoot - const float line_yaw_diff = wrap_180_cd(_oa_origin.get_bearing_to(_oa_destination) - heading_cd); - const float dist_from_line = fabsf(_cross_track_error); - const bool heading_away = is_positive(line_yaw_diff) == is_positive(_cross_track_error); - const float wp_overshoot_adj = heading_away ? -dist_from_line : dist_from_line; - - // calculate radius of circle that touches vehicle's current position and heading and target position and heading - float radius_m = 999.0f; - const float radius_calc_denom = fabsf(1.0f - cosf(turn_angle_rad)); - if (!is_zero(radius_calc_denom)) { - radius_m = MAX(0.0f, _overshoot + wp_overshoot_adj) / radius_calc_denom; - } - - // calculate and limit speed to allow vehicle to stay on circle - // ensure limit does not force speed below minimum - float overshoot_speed_max = safe_sqrt(_atc.get_turn_lat_accel_max() * MAX(_turn_radius, radius_m)); - apply_speed_min(overshoot_speed_max); - des_speed_lim = constrain_float(des_speed_lim, -overshoot_speed_max, overshoot_speed_max); - - // limit speed based on distance to waypoint and max acceleration/deceleration - if (is_positive(_oa_distance_to_destination) && is_positive(_atc.get_decel_max())) { - const float dist_speed_max = safe_sqrt(2.0f * _oa_distance_to_destination * _atc.get_decel_max() + sq(_desired_speed_final)); - des_speed_lim = constrain_float(des_speed_lim, -dist_speed_max, dist_speed_max); - } - - _desired_speed_limited = des_speed_lim; + _pos_control.set_reversed(_reversed); + _pos_control.update(dt); + _desired_speed_limited = _pos_control.get_desired_speed(); + _desired_turn_rate_rads = _pos_control.get_desired_turn_rate_rads(); + _desired_lat_accel = _pos_control.get_desired_lat_accel(); } // settor to allow vehicle code to provide turn related param values to this library (should be updated regularly) void AR_WPNav::set_turn_params(float turn_radius, bool pivot_possible) { - _turn_radius = turn_radius; - _pivot_possible = pivot_possible; -} - -// adjust speed to ensure it does not fall below value held in SPEED_MIN -// desired_speed should always be positive (or zero) -void AR_WPNav::apply_speed_min(float &desired_speed) const -{ - if (!is_positive(_speed_min) || (_speed_min > _speed_max)) { - return; - } - - // ensure speed does not fall below minimum - desired_speed = MAX(desired_speed, _speed_min); + _turn_radius = pivot_possible ? 0.0 : turn_radius; + _pivot.enable(pivot_possible); } -// calculate the crosstrack error (does not rely on L1 controller) +// calculate the crosstrack error float AR_WPNav::calc_crosstrack_error(const Location& current_loc) const { if (!_orig_and_dest_valid) { return 0.0f; } + // get object avoidance adjusted origin and destination + const Location &orig = get_oa_origin(); + const Location &dest = get_oa_destination(); + // calculate the NE position of destination relative to origin - Vector2f dest_from_origin = _oa_origin.get_distance_NE(_oa_destination); + Vector2f dest_from_origin = orig.get_distance_NE(dest); - // return distance to origin if length of track is very small + // return distance to destination if length of track is very small if (dest_from_origin.length() < 1.0e-6f) { - return current_loc.get_distance_NE(_oa_destination).length(); + return current_loc.get_distance_NE(dest).length(); } // convert to a vector indicating direction only dest_from_origin.normalize(); // calculate the NE position of the vehicle relative to origin - const Vector2f veh_from_origin = _oa_origin.get_distance_NE(current_loc); + const Vector2f veh_from_origin = orig.get_distance_NE(current_loc); // calculate distance to target track, for reporting return veh_from_origin % dest_from_origin; } + +// calculate yaw change at next waypoint in degrees +// returns zero if the angle cannot be calculated because some points are on top of others +float AR_WPNav::get_corner_angle(const Location& loc1, const Location& loc2, const Location& loc3) const +{ + // sanity check + if (!loc1.initialised() || !loc2.initialised() || !loc3.initialised()) { + return 0; + } + const float loc1_to_loc2_deg = loc1.get_bearing_to(loc2) * 0.01; + const float loc2_to_loc3_deg = loc2.get_bearing_to(loc3) * 0.01; + const float diff_yaw_deg = wrap_180(loc2_to_loc3_deg - loc1_to_loc2_deg); + return diff_yaw_deg; +} + +// helper function to initialise position controller if it hasn't been called recently +// this should be called before updating the position controller with new targets but after the EKF has a good position estimate +void AR_WPNav::init_pos_control_if_necessary() +{ + // initialise position controller if not called recently + if (!_pos_control.is_active()) { + if (!_pos_control.init()) { + // this should never fail because we should always have a valid position estimate at this point + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + return; + } + } +} + +// set origin and destination to stopping point +bool AR_WPNav::set_origin_and_destination_to_stopping_point() +{ + // initialise origin and destination to stopping point + Location stopping_loc; + if (!get_stopping_location(stopping_loc)) { + return false; + } + _origin = _destination = stopping_loc; + _orig_and_dest_valid = true; + return true; +} + +// check for changes in _base_speed_max or _nudge_speed_max +// updates position controller limits and recalculate scurve path if required +void AR_WPNav::update_speed_max() +{ + const float speed_max = MAX(_base_speed_max, _nudge_speed_max); + + // ignore calls that do not change the speed + if (is_equal(speed_max, _pos_control.get_speed_max())) { + return; + } + + // protect against rapid updates + const uint32_t now_ms = AP_HAL::millis(); + if (now_ms - _last_speed_update_ms < AR_WPNAV_SPEED_UPDATE_MIN_MS) { + return; + } + _last_speed_update_ms = now_ms; + + // update position controller max speed + _pos_control.set_limits(speed_max, _pos_control.get_accel_max(), _pos_control.get_lat_accel_max(), _pos_control.get_jerk_max()); + + // change track speed + _scurve_this_leg.set_speed_max(_pos_control.get_speed_max(), _pos_control.get_speed_max(), _pos_control.get_speed_max()); + _scurve_next_leg.set_speed_max(_pos_control.get_speed_max(), _pos_control.get_speed_max(), _pos_control.get_speed_max()); +} diff --git a/libraries/AR_WPNav/AR_WPNav.h b/libraries/AR_WPNav/AR_WPNav.h index 4e64fadc55d..1bfb2864aaf 100644 --- a/libraries/AR_WPNav/AR_WPNav.h +++ b/libraries/AR_WPNav/AR_WPNav.h @@ -1,29 +1,32 @@ #pragma once #include +#include #include -#include +#include #include - -const float AR_WPNAV_HEADING_UNKNOWN = 99999.0f; // used to indicate to set_desired_location method that next leg's heading is unknown +#include "AR_PivotTurn.h" class AR_WPNav { public: // constructor - AR_WPNav(AR_AttitudeControl& atc, AP_Navigation& nav_controller); + AR_WPNav(AR_AttitudeControl& atc, AR_PosControl &pos_control); - // update navigation - void update(float dt); + // initialise waypoint controller. speed_max should be set to the maximum speed in m/s (or left at zero to use the default speed) + void init(float speed_max = 0); - // return desired speed - float get_desired_speed() const { return _desired_speed; } + // update navigation + virtual void update(float dt); - // set desired speed in m/s - void set_desired_speed(float speed) { _desired_speed = MAX(speed, 0.0f); } + // get or set maximum speed in m/s + // if set_speed_max is called in rapid succession changes in speed may be delayed by up to 0.5sec + float get_speed_max() const { return _base_speed_max; } + bool set_speed_max(float speed_max); - // restore desired speed to default from parameter value - void set_desired_speed_to_default() { _desired_speed = _speed_max; } + // set speed nudge in m/s. this will have no effect unless nudge_speed_max > speed_max + // nudge_speed_max should always be positive regardless of whether the vehicle is travelling forward or reversing + void set_nudge_speed_max(float nudge_speed_max); // execute the mission in reverse (i.e. drive backwards to destination) bool get_reversed() const { return _reversed; } @@ -36,18 +39,24 @@ class AR_WPNav { // get desired lateral acceleration (for reporting purposes only because will be zero during pivot turns) float get_lat_accel() const { return _desired_lat_accel; } - // set desired location - // next_leg_bearing_cd should be heading to the following waypoint (used to slow the vehicle in order to make the turn) - bool set_desired_location(const struct Location& destination, float next_leg_bearing_cd = AR_WPNAV_HEADING_UNKNOWN) WARN_IF_UNUSED; + // set desired location and (optionally) next_destination + // next_destination should be provided if known to allow smooth cornering + virtual bool set_desired_location(const Location &destination, Location next_destination = Location()) WARN_IF_UNUSED; // set desired location to a reasonable stopping point, return true on success bool set_desired_location_to_stopping_location() WARN_IF_UNUSED; // set desired location as offset from the EKF origin, return true on success - bool set_desired_location_NED(const Vector3f& destination, float next_leg_bearing_cd = AR_WPNAV_HEADING_UNKNOWN) WARN_IF_UNUSED; + bool set_desired_location_NED(const Vector3f& destination) WARN_IF_UNUSED; + bool set_desired_location_NED(const Vector3f &destination, const Vector3f &next_destination) WARN_IF_UNUSED; + + // set desired location but expect the destination to be updated again in the near future + // position controller input shaping will be used for navigation instead of scurves + // Note: object avoidance is not supported if this method is used + bool set_desired_location_expect_fast_update(const Location &destination) WARN_IF_UNUSED; // true if vehicle has reached desired location. defaults to true because this is normally used by missions and we do not want the mission to become stuck - bool reached_destination() const { return _reached_destination; } + virtual bool reached_destination() const { return _reached_destination; } // return distance (in meters) to destination float get_distance_to_destination() const { return _distance_to_destination; } @@ -56,96 +65,123 @@ class AR_WPNav { bool is_destination_valid() const { return _orig_and_dest_valid; } // get current destination. Note: this is not guaranteed to be valid (i.e. _orig_and_dest_valid is not checked) - const Location &get_destination() { return _destination; } - - // get object avoidance adjusted destination. Note: this is not guaranteed to be valid (i.e. _orig_and_dest_valid is not checked) - const Location &get_oa_destination() { return _oa_destination; } + const Location &get_destination() const { return _destination; } // return heading (in centi-degrees) and cross track error (in meters) for reporting to ground station (NAV_CONTROLLER_OUTPUT message) float wp_bearing_cd() const { return _wp_bearing_cd; } float nav_bearing_cd() const { return _desired_heading_cd; } float crosstrack_error() const { return _cross_track_error; } + // get object avoidance adjusted origin. Note: this is not guaranteed to be valid (i.e. _orig_and_dest_valid is not checked) + virtual const Location &get_oa_origin() const { return _origin; } + + // get object avoidance adjusted destination. Note: this is not guaranteed to be valid (i.e. _orig_and_dest_valid is not checked) + virtual const Location &get_oa_destination() const { return get_destination(); } + // return the heading (in centi-degrees) to the next waypoint accounting for OA, (used by sailboats) - float oa_wp_bearing_cd() const { return _oa_wp_bearing_cd; } + virtual float oa_wp_bearing_cd() const { return wp_bearing_cd(); } // settor to allow vehicle code to provide turn related param values to this library (should be updated regularly) void set_turn_params(float turn_radius, bool pivot_possible); + // enable speeding up position target to catch-up with vehicles travelling faster than WP_SPEED + // designed to support sailboats that do not have precise speed control + // only supported when using SCurves and not when using position controller input shaping + void enable_overspeed(bool enable) { _overspeed_enabled = enable; } + // accessors for parameter values float get_default_speed() const { return _speed_max; } + float get_default_accel() const { return _accel_max; } + float get_default_jerk() const { return _jerk_max; } float get_radius() const { return _radius; } - float get_pivot_rate() const { return _pivot_rate; } + float get_pivot_rate() const { return _pivot.get_rate_max(); } // calculate stopping location using current position and attitude controller provided maximum deceleration // returns true on success, false on failure bool get_stopping_location(Location& stopping_loc) WARN_IF_UNUSED; + // is_fast_waypoint returns true if vehicle will not stop at destination (e.g. set_desired_location provided a next_destination) + bool is_fast_waypoint() const { return _fast_waypoint; } + // parameter var table static const struct AP_Param::GroupInfo var_info[]; -private: +protected: // true if update has been called recently bool is_active() const; + // move target location along track from origin to destination using SCurves navigation + void advance_wp_target_along_track(const Location ¤t_loc, float dt); + + // update psc input shaping navigation controller + void update_psc_input_shaping(float dt); + // update distance and bearing from vehicle's current position to destination void update_distance_and_bearing_to_destination(); - // calculate steering output to drive along line from origin to destination waypoint - // relies on update_distance_and_bearing_to_destination being called first - void update_steering(const Location& current_loc, float current_speed); + // calculate steering and speed to drive along line from origin to destination waypoint + void update_steering_and_speed(const Location ¤t_loc, float dt); - // calculated desired speed(in m/s) based on yaw error and lateral acceleration and/or distance to a waypoint - // relies on update_distance_and_bearing_to_destination and update_steering being run so these internal members - // have been updated: _wp_bearing_cd, _cross_track_error, _distance_to_destination - void update_desired_speed(float dt); + // calculate the crosstrack error (does not rely on L1 controller) + float calc_crosstrack_error(const Location& current_loc) const; - // returns true if vehicle should pivot turn at next waypoint - bool use_pivot_steering_at_next_WP(float yaw_error_cd) const; + // calculate yaw change at next waypoint in degrees + // returns zero if the angle cannot be calculated because some points are on top of others + float get_corner_angle(const Location& loc1, const Location& loc2, const Location& loc3) const; - // updates _pivot_active flag based on heading error to destination - // relies on update_distance_and_bearing_to_destination having been called first - // to update _oa_wp_bearing and _reversed variables - void update_pivot_active_flag(); + // helper function to initialise position controller if it hasn't been called recently + // this should be called before updating the position controller with new targets but after the EKF has a good position estimate + void init_pos_control_if_necessary(); - // adjust speed to ensure it does not fall below value held in SPEED_MIN - // desired_speed should always be positive (or zero) - void apply_speed_min(float &desired_speed) const; + // set origin and destination to stopping point + bool set_origin_and_destination_to_stopping_point(); - // calculate the crosstrack error (does not rely on L1 controller) - float calc_crosstrack_error(const Location& current_loc) const; + // check for changes in _base_speed_max or _nudge_speed_max + // updates position controller limits and recalculate scurve path if required + void update_speed_max(); // parameters AP_Float _speed_max; // target speed between waypoints in m/s - AP_Float _speed_min; // target speed minimum in m/s. Vehicle will not slow below this speed for corners AP_Float _radius; // distance in meters from a waypoint when we consider the waypoint has been reached - AP_Float _overshoot; // maximum horizontal overshoot in meters - AP_Int16 _pivot_angle; // angle error that leads to pivot turn - AP_Int16 _pivot_rate; // desired turn rate during pivot turns in deg/sec - AP_Float _pivot_delay; // waiting time after pivot turn + AR_PivotTurn _pivot; // pivot turn controller + AP_Float _accel_max; // max acceleration. If zero then attitude controller's specified max accel is used + AP_Float _jerk_max; // max jerk (change in acceleration). If zero then value is same as accel_max // references AR_AttitudeControl& _atc; // rover attitude control library - AP_Navigation& _nav_controller; // navigation controller (aka L1 controller) + AR_PosControl &_pos_control; // rover position control library + + // scurve + SCurve _scurve_prev_leg; // previous scurve trajectory used to blend with current scurve trajectory + SCurve _scurve_this_leg; // current scurve trajectory + SCurve _scurve_next_leg; // next scurve trajectory used to blend with current scurve trajectory + bool _fast_waypoint; // true if vehicle will stop at the next waypoint + bool _pivot_at_next_wp; // true if vehicle should pivot at next waypoint + bool _overspeed_enabled; // if true scurve's position target will speedup to catch vehicles travelling faster than WP_SPEED + float _track_scalar_dt; // time scaler to ensure scurve target doesn't get too far ahead of vehicle // variables held in vehicle code (for now) float _turn_radius; // vehicle turn radius in meters - bool _pivot_possible; // true if vehicle can pivot - bool _pivot_active; // true if vehicle is currently pivoting // variables for navigation uint32_t _last_update_ms; // system time of last call to update - uint32_t _pivot_start_ms; // system time when pivot turn started Location _origin; // origin Location (vehicle will travel from the origin to the destination) Location _destination; // destination Location when in Guided_WP bool _orig_and_dest_valid; // true if the origin and destination have been set bool _reversed; // execute the mission by backing up - float _desired_speed_final; // desired speed in m/s when we reach the destination + enum class NavControllerType { + NAV_SCURVE = 0, // scurves used for navigation + NAV_PSC_INPUT_SHAPING // position controller input shaping used for navigation + } _nav_control_type; // navigation controller that should be used to travel from _origin to _destination + + // speed_max handling + float _base_speed_max; // speed max (in m/s) derived from parameters or passed into init + float _nudge_speed_max; // "nudge" speed max (in m/s) normally from the pilot. has no effect if less than _base_speed_max. always positive. + uint32_t _last_speed_update_ms; // system time that speed_max was last update. used to ensure speed_max is not update too quickly // main outputs from navigation library - float _desired_speed; // desired speed in m/s - float _desired_speed_limited; // desired speed (above) but accel/decel limited and reduced to keep vehicle within _overshoot of line + float _desired_speed_limited; // desired speed (above) but accel/decel limited float _desired_turn_rate_rads; // desired turn-rate in rad/sec (negative is counter clockwise, positive is clockwise) float _desired_lat_accel; // desired lateral acceleration (for reporting only) float _desired_heading_cd; // desired heading (back towards line between origin and destination) @@ -155,11 +191,4 @@ class AR_WPNav { // variables for reporting float _distance_to_destination; // distance from vehicle to final destination in meters bool _reached_destination; // true once the vehicle has reached the destination - - // object avoidance variables - bool _oa_active; // true if we should use alternative destination to avoid obstacles - Location _oa_origin; // intermediate origin during avoidance - Location _oa_destination; // intermediate destination during avoidance - float _oa_distance_to_destination; // OA (object avoidance) distance from vehicle to _oa_destination in meters - float _oa_wp_bearing_cd; // OA adjusted heading to _oa_destination in centi-degrees }; diff --git a/libraries/AR_WPNav/AR_WPNav_OA.cpp b/libraries/AR_WPNav/AR_WPNav_OA.cpp new file mode 100644 index 00000000000..97e7b77c587 --- /dev/null +++ b/libraries/AR_WPNav/AR_WPNav_OA.cpp @@ -0,0 +1,205 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +#include +#include +#include +#include "AR_WPNav_OA.h" +#include + +extern const AP_HAL::HAL& hal; + +// update navigation +void AR_WPNav_OA::update(float dt) +{ + // exit immediately if no current location, origin or destination + Location current_loc; + float speed; + if (!hal.util->get_soft_armed() || !is_destination_valid() || !AP::ahrs().get_location(current_loc) || !_atc.get_forward_speed(speed)) { + _desired_speed_limited = _atc.get_desired_speed_accel_limited(0.0f, dt); + _desired_lat_accel = 0.0f; + _desired_turn_rate_rads = 0.0f; + _oa_active = false; + return; + } + + // run path planning around obstacles + bool stop_vehicle = false; + + // backup _origin and _destination when not doing oa + if (!_oa_active) { + _origin_oabak = _origin; + _destination_oabak = _destination; + } + + AP_OAPathPlanner *oa = AP_OAPathPlanner::get_singleton(); + if (oa != nullptr) { + Location oa_origin_new, oa_destination_new; + AP_OAPathPlanner::OAPathPlannerUsed path_planner_used; + const AP_OAPathPlanner::OA_RetState oa_retstate = oa->mission_avoidance(current_loc, _origin_oabak, _destination_oabak, oa_origin_new, oa_destination_new, path_planner_used); + switch (oa_retstate) { + + case AP_OAPathPlanner::OA_NOT_REQUIRED: + if (_oa_active) { + // object avoidance has become inactive so reset target to original destination + if (!AR_WPNav::set_desired_location(_destination_oabak)) { + // this should never happen because we should have an EKF origin and the destination must be valid + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + stop_vehicle = true; + } + _oa_active = false; + // ToDo: handle "if (oa->get_options() & AP_OAPathPlanner::OA_OPTION_WP_RESET)" + } + break; + + case AP_OAPathPlanner::OA_PROCESSING: + case AP_OAPathPlanner::OA_ERROR: + // during processing or in case of error, slow vehicle to a stop + stop_vehicle = true; + _oa_active = false; + break; + + case AP_OAPathPlanner::OA_SUCCESS: + // handling of returned destination depends upon path planner used + switch (path_planner_used) { + + case AP_OAPathPlanner::OAPathPlannerUsed::None: + case AP_OAPathPlanner::OAPathPlannerUsed::BendyRulerVertical: + // this should never happen. this means the path planner has returned success but has returned an invalid planner + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + _oa_active = false; + stop_vehicle = true; + return; + + case AP_OAPathPlanner::OAPathPlannerUsed::Dijkstras: + // Dijkstra's. Action is only needed if path planner has just became active or the target destination's lat or lon has changed + if (!_oa_active || !oa_destination_new.same_latlon_as(_oa_destination)) { + if (AR_WPNav::set_desired_location(oa_destination_new)) { + // if new target set successfully, update oa state and destination + _oa_active = true; + _oa_origin = oa_origin_new; + _oa_destination = oa_destination_new; + } else { + // this should never happen + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + stop_vehicle = true; + } + } + break; + + case AP_OAPathPlanner::OAPathPlannerUsed::BendyRulerHorizontal: { + // BendyRuler. Action is only needed if path planner has just became active or the target destination's lat or lon has changed + if (!_oa_active || !oa_destination_new.same_latlon_as(_oa_destination)) { + if (AR_WPNav::set_desired_location_expect_fast_update(oa_destination_new)) { + // if new target set successfully, update oa state and destination + _oa_active = true; + _oa_origin = oa_origin_new; + _oa_destination = oa_destination_new; + } else { + // this should never happen + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + stop_vehicle = true; + } + } + } + break; + + } // switch (path_planner_used) { + } // switch (oa_retstate) { + } // if (oa != nullptr) { + + update_oa_distance_and_bearing_to_destination(); + + // handle stopping vehicle if avoidance has failed + if (stop_vehicle) { + // decelerate to speed to zero and set turn rate to zero + _desired_speed_limited = _atc.get_desired_speed_accel_limited(0.0f, dt); + _desired_lat_accel = 0.0f; + _desired_turn_rate_rads = 0.0f; + return; + } + + // call parent update + AR_WPNav::update(dt); +} + +// set desired location and (optionally) next_destination +// next_destination should be provided if known to allow smooth cornering +bool AR_WPNav_OA::set_desired_location(const struct Location& destination, Location next_destination) +{ + const bool ret = AR_WPNav::set_desired_location(destination, next_destination); + + if (ret) { + // disable object avoidance, it will be re-enabled (if necessary) on next update + _oa_active = false; + } + + return ret; +} + +// true if vehicle has reached desired location. defaults to true because this is normally used by missions and we do not want the mission to become stuck +bool AR_WPNav_OA::reached_destination() const +{ + // object avoidance should always be deactivated before reaching final destination + if (_oa_active) { + return false; + } + + return AR_WPNav::reached_destination(); +} + +// get object avoidance adjusted origin. Note: this is not guaranteed to be valid (i.e. _orig_and_dest_valid is not checked) +const Location &AR_WPNav_OA::get_oa_origin() const +{ + if (_oa_active) { + return _oa_origin; + } + + return _origin; +} + +// get object avoidance adjusted destination. Note: this is not guaranteed to be valid (i.e. _orig_and_dest_valid is not checked) +const Location &AR_WPNav_OA::get_oa_destination() const +{ + if (_oa_active) { + return _oa_destination; + } + + return AR_WPNav::get_oa_destination(); +} + +// return the heading (in centi-degrees) to the next waypoint accounting for OA, (used by sailboats) +float AR_WPNav_OA::oa_wp_bearing_cd() const +{ + if (_oa_active) { + return _oa_wp_bearing_cd; + } + + return AR_WPNav::oa_wp_bearing_cd(); +} + +// update distance from vehicle's current position to destination +void AR_WPNav_OA::update_oa_distance_and_bearing_to_destination() +{ + // update OA adjusted values + Location current_loc; + if (_oa_active && AP::ahrs().get_location(current_loc)) { + _oa_distance_to_destination = current_loc.get_distance(_oa_destination); + _oa_wp_bearing_cd = current_loc.get_bearing_to(_oa_destination); + } else { + _oa_distance_to_destination = AR_WPNav::get_distance_to_destination(); + _oa_wp_bearing_cd = AR_WPNav::wp_bearing_cd(); + } +} diff --git a/libraries/AR_WPNav/AR_WPNav_OA.h b/libraries/AR_WPNav/AR_WPNav_OA.h new file mode 100644 index 00000000000..195ed3028f2 --- /dev/null +++ b/libraries/AR_WPNav/AR_WPNav_OA.h @@ -0,0 +1,43 @@ +#pragma once + +#include "AR_WPNav.h" + +class AR_WPNav_OA : public AR_WPNav { +public: + + // re-use parent's constructor + using AR_WPNav::AR_WPNav; + + // update navigation + void update(float dt) override; + + // set desired location and (optionally) next_destination + // next_destination should be provided if known to allow smooth cornering + bool set_desired_location(const Location &destination, Location next_destination = Location()) override WARN_IF_UNUSED; + + // true if vehicle has reached desired location. defaults to true because this is normally used by missions and we do not want the mission to become stuck + bool reached_destination() const override; + + // get object avoidance adjusted origin. Note: this is not guaranteed to be valid (i.e. _orig_and_dest_valid is not checked) + const Location &get_oa_origin() const override; + + // get object avoidance adjusted destination. Note: this is not guaranteed to be valid (i.e. _orig_and_dest_valid is not checked) + const Location &get_oa_destination() const override; + + // return the heading (in centi-degrees) to the next waypoint accounting for OA, (used by sailboats) + float oa_wp_bearing_cd() const override; + +private: + + // update distance and bearing from vehicle's current position to destination + void update_oa_distance_and_bearing_to_destination(); + + // object avoidance variables + bool _oa_active; // true if we should use alternative destination to avoid obstacles + Location _origin_oabak; // backup of _origin so it can be restored when oa completes + Location _destination_oabak; // backup of _desitnation so it can be restored when oa completes + Location _oa_origin; // intermediate origin during avoidance + Location _oa_destination; // intermediate destination during avoidance + float _oa_distance_to_destination; // OA (object avoidance) distance from vehicle to _oa_destination in meters + float _oa_wp_bearing_cd; // OA adjusted heading to _oa_destination in centi-degrees +}; diff --git a/libraries/Filter/Butter.h b/libraries/Filter/Butter.h index 02eb2e064d7..36ac1f420ec 100644 --- a/libraries/Filter/Butter.h +++ b/libraries/Filter/Butter.h @@ -1,7 +1,5 @@ #pragma once -#include - template class Butter2 { diff --git a/libraries/Filter/HarmonicNotchFilter.cpp b/libraries/Filter/HarmonicNotchFilter.cpp index b2c4e97b4bc..9bf70e04b17 100644 --- a/libraries/Filter/HarmonicNotchFilter.cpp +++ b/libraries/Filter/HarmonicNotchFilter.cpp @@ -60,7 +60,7 @@ const AP_Param::GroupInfo HarmonicNotchFilterParams::var_info[] = { // @Param: HMNCS // @DisplayName: Harmonic Notch Filter harmonics - // @Description: Bitmask of harmonic frequencies to apply Harmonic Notch Filter to. This option takes effect on the next reboot. A maximum of 3 harmonics can be used at any one time. + // @Description: Bitmask of harmonic frequencies to apply Harmonic Notch Filter to. This option takes effect on the next reboot. A value of 0 disables this filter. The first harmonic refers to the base frequency. // @Bitmask: 0:1st harmonic,1:2nd harmonic,2:3rd harmonic,3:4th hamronic,4:5th harmonic,5:6th harmonic,6:7th harmonic,7:8th harmonic // @User: Advanced // @RebootRequired: True @@ -78,18 +78,25 @@ const AP_Param::GroupInfo HarmonicNotchFilterParams::var_info[] = { // @DisplayName: Harmonic Notch Filter dynamic frequency tracking mode // @Description: Harmonic Notch Filter dynamic frequency tracking mode. Dynamic updates can be throttle, RPM sensor, ESC telemetry or dynamic FFT based. Throttle-based updates should only be used with multicopters. // @Range: 0 4 - // @Values: 0:Disabled,1:Throttle,2:RPM Sensor,3:ESC Telemetry,4:Dynamic FFT + // @Values: 0:Disabled,1:Throttle,2:RPM Sensor,3:ESC Telemetry,4:Dynamic FFT,5:Second RPM Sensor // @User: Advanced - AP_GROUPINFO("MODE", 7, HarmonicNotchFilterParams, _tracking_mode, 1), + AP_GROUPINFO("MODE", 7, HarmonicNotchFilterParams, _tracking_mode, int8_t(HarmonicNotchDynamicMode::UpdateThrottle)), // @Param: OPTS // @DisplayName: Harmonic Notch Filter options - // @Description: Harmonic Notch Filter options. Double-notches can provide deeper attenuation across a wider bandwidth than single notches and are suitable for larger aircraft. Dynamic harmonics attaches a harmonic notch to each detected noise frequency instead of simply being multiples of the base frequency, in the case of FFT it will attach notches to each of three detected noise peaks, in the case of ESC it will attach notches to each of four motor RPM values. Loop rate update changes the notch center frequency at the scheduler loop rate rather than at the default of 200Hz. - // @Bitmask: 0:Double notch,1:Dynamic harmonic,2:Update at loop rate + // @Description: Harmonic Notch Filter options. Triple and double-notches can provide deeper attenuation across a wider bandwidth with reduced latency than single notches and are suitable for larger aircraft. Dynamic harmonics attaches a harmonic notch to each detected noise frequency instead of simply being multiples of the base frequency, in the case of FFT it will attach notches to each of three detected noise peaks, in the case of ESC it will attach notches to each of four motor RPM values. Loop rate update changes the notch center frequency at the scheduler loop rate rather than at the default of 200Hz. If both double and triple notches are specified only double notches will take effect. + // @Bitmask: 0:Double notch,1:Dynamic harmonic,2:Update at loop rate,3:EnableOnAllIMUs,4:Triple notch // @User: Advanced // @RebootRequired: True AP_GROUPINFO("OPTS", 8, HarmonicNotchFilterParams, _options, 0), + // @Param: FM_RAT + // @DisplayName: Throttle notch min freqency ratio + // @Description: The minimum ratio below the configured frequency to take throttle based notch filters when flying at a throttle level below the reference throttle. Note that lower frequency notch filters will have more phase lag. If you want throttle based notch filtering to be effective at a throttle up to 30% below the configured notch frequency then set this parameter to 0.7. The default of 1.0 means the notch will not go below the frequency in the FREQ parameter. + // @Range: 0.1 1.0 + // @User: Advanced + AP_GROUPINFO("FM_RAT", 9, HarmonicNotchFilterParams, _freq_min_ratio, 1.0), + AP_GROUPEND }; @@ -124,14 +131,9 @@ void HarmonicNotchFilter::init(float sample_freq_hz, float center_freq_hz, fl // Calculate spread required to achieve an equivalent single notch using two notches with Bandwidth/2 _notch_spread = bandwidth_hz / (32 * center_freq_hz); - if (_double_notch) { - // position the individual notches so that the attenuation is no worse than a single notch - // calculate attenuation and quality from the shaping constraints - NotchFilter::calculate_A_and_Q(center_freq_hz, bandwidth_hz * 0.5, attenuation_dB, _A, _Q); - } else { - // calculate attenuation and quality from the shaping constraints - NotchFilter::calculate_A_and_Q(center_freq_hz, bandwidth_hz, attenuation_dB, _A, _Q); - } + // position the individual notches so that the attenuation is no worse than a single notch + // calculate attenuation and quality from the shaping constraints + NotchFilter::calculate_A_and_Q(center_freq_hz, bandwidth_hz / _composite_notches, attenuation_dB, _A, _Q); _initialised = true; update(center_freq_hz); @@ -141,11 +143,11 @@ void HarmonicNotchFilter::init(float sample_freq_hz, float center_freq_hz, fl allocate a collection of, at most HNF_MAX_FILTERS, notch filters to be managed by this harmonic notch filter */ template -void HarmonicNotchFilter::allocate_filters(uint8_t num_notches, uint8_t harmonics, bool double_notch) +void HarmonicNotchFilter::allocate_filters(uint8_t num_notches, uint8_t harmonics, uint8_t composite_notches) { - _double_notch = double_notch; + _composite_notches = MIN(composite_notches, 3); _num_harmonics = __builtin_popcount(harmonics); - _num_filters = _num_harmonics * num_notches * (double_notch ? 2 : 1); + _num_filters = _num_harmonics * num_notches * _composite_notches; _harmonics = harmonics; if (_num_filters > 0) { @@ -157,6 +159,37 @@ void HarmonicNotchFilter::allocate_filters(uint8_t num_notches, uint8_t harmo } } +/* + expand the number of filters at runtime, allowing for RPM sources such as lua scripts + */ +template +void HarmonicNotchFilter::expand_filter_count(uint8_t num_notches) +{ + uint8_t num_filters = _num_harmonics * num_notches * _composite_notches; + if (num_filters <= _num_filters) { + // enough already + return; + } + if (_alloc_has_failed) { + // we've failed to allocate before, don't try again + return; + } + /* + note that we rely on the semaphore in + AP_InertialSensor_Backend.cpp to make this thread safe + */ + auto filters = new NotchFilter[num_filters]; + if (filters == nullptr) { + _alloc_has_failed = true; + return; + } + memcpy(filters, _filters, sizeof(filters[0])*_num_filters); + auto _old_filters = _filters; + _filters = filters; + _num_filters = num_filters; + delete[] _old_filters; +} + /* update the underlying filters' center frequency using the current attenuation and quality this function is cheaper than init() because A & Q do not need to be recalculated @@ -177,12 +210,13 @@ void HarmonicNotchFilter::update(float center_freq_hz) for (uint8_t i = 0; i < HNF_MAX_HARMONICS && _num_enabled_filters < _num_filters; i++) { if ((1U< 1) { float notch_center_double; // only enable the filter if its center frequency is below the nyquist frequency notch_center_double = notch_center * (1.0 - _notch_spread); @@ -213,6 +247,11 @@ void HarmonicNotchFilter::update(uint8_t num_centers, const float center_freq // adjust the frequencies to be in the allowable range const float nyquist_limit = _sample_freq_hz * 0.48f; + if (num_centers > _num_filters) { + // alloc realloc of filters + expand_filter_count(num_centers); + } + _num_enabled_filters = 0; // update all of the filters using the new center frequencies and existing A & Q @@ -226,12 +265,13 @@ void HarmonicNotchFilter::update(uint8_t num_centers, const float center_freq } const float notch_center = constrain_float(center_freq_hz[center_n] * (harmonic_n+1), 1.0f, nyquist_limit); - if (!_double_notch) { + if (_composite_notches != 2) { // only enable the filter if its center frequency is below the nyquist frequency if (notch_center < nyquist_limit) { _filters[_num_enabled_filters++].init_with_A_and_Q(_sample_freq_hz, notch_center, _A, _Q); } - } else { + } + if (_composite_notches > 1) { float notch_center_double; // only enable the filter if its center frequency is below the nyquist frequency notch_center_double = notch_center * (1.0 - _notch_spread); @@ -287,7 +327,22 @@ HarmonicNotchFilterParams::HarmonicNotchFilterParams(void) AP_Param::setup_object_defaults(this, var_info); } +/* + save changed parameters + */ +void HarmonicNotchFilterParams::save_params() +{ + _enable.save(); + _center_freq_hz.save(); + _bandwidth_hz.save(); + _attenuation_dB.save(); + _harmonics.save(); + _reference.save(); +} + /* instantiate template classes */ template class HarmonicNotchFilter; +template class HarmonicNotchFilter; + diff --git a/libraries/Filter/HarmonicNotchFilter.h b/libraries/Filter/HarmonicNotchFilter.h index 4cfd18e48fd..6188a192d35 100644 --- a/libraries/Filter/HarmonicNotchFilter.h +++ b/libraries/Filter/HarmonicNotchFilter.h @@ -30,7 +30,9 @@ class HarmonicNotchFilter { public: ~HarmonicNotchFilter(); // allocate a bank of notch filters for this harmonic notch filter - void allocate_filters(uint8_t num_notches, uint8_t harmonics, bool double_notch); + void allocate_filters(uint8_t num_notches, uint8_t harmonics, uint8_t composite_notches); + // expand filter bank with new filters + void expand_filter_count(uint8_t num_notches); // initialize the underlying filters using the provided filter parameters void init(float sample_freq_hz, float center_freq_hz, float bandwidth_hz, float attenuation_dB); // update the underlying filters' center frequencies using center_freq_hz as the fundamental @@ -55,8 +57,8 @@ class HarmonicNotchFilter { float _Q; // a bitmask of the harmonics to use uint8_t _harmonics; - // whether to use double-notches - bool _double_notch; + // number of notches that make up a composite notch + uint8_t _composite_notches; // number of allocated filters uint8_t _num_filters; // pre-calculated number of harmonics @@ -64,6 +66,9 @@ class HarmonicNotchFilter { // number of enabled filters uint8_t _num_enabled_filters; bool _initialised; + + // have we failed to expand filters? + bool _alloc_has_failed; }; // Harmonic notch update mode @@ -73,6 +78,7 @@ enum class HarmonicNotchDynamicMode { UpdateRPM = 2, UpdateBLHeli = 3, UpdateGyroFFT = 4, + UpdateRPM2 = 5, }; /* @@ -83,24 +89,37 @@ class HarmonicNotchFilterParams : public NotchFilterParams { enum class Options { DoubleNotch = 1<<0, DynamicHarmonic = 1<<1, - LoopRateUpdate = 2<<1, + LoopRateUpdate = 1<<2, + EnableOnAllIMUs = 1<<3, + TripleNotch = 1<<4, }; HarmonicNotchFilterParams(void); // set the fundamental center frequency of the harmonic notch void set_center_freq_hz(float center_freq) { _center_freq_hz.set(center_freq); } + // set the bandwidth of the harmonic notch + void set_bandwidth_hz(float bandwidth_hz) { _bandwidth_hz.set(bandwidth_hz); } // harmonics enabled on the harmonic notch uint8_t harmonics(void) const { return _harmonics; } // has the user set the harmonics value void set_default_harmonics(uint8_t hmncs) { _harmonics.set_default(hmncs); } // reference value of the harmonic notch float reference(void) const { return _reference; } + void set_reference(float ref) { _reference.set(ref); } // notch options bool hasOption(Options option) const { return _options & uint16_t(option); } // notch dynamic tracking mode HarmonicNotchDynamicMode tracking_mode(void) const { return HarmonicNotchDynamicMode(_tracking_mode.get()); } static const struct AP_Param::GroupInfo var_info[]; + // return minimum frequency ratio for throttle notch + float freq_min_ratio(void) const { + return _freq_min_ratio; + } + + // save parameters + void save_params(); + private: // configured notch harmonics AP_Int8 _harmonics; @@ -110,6 +129,9 @@ class HarmonicNotchFilterParams : public NotchFilterParams { AP_Int8 _tracking_mode; // notch options AP_Int16 _options; + + // minimum frequency ratio for throttle based notches + AP_Float _freq_min_ratio; }; typedef HarmonicNotchFilter HarmonicNotchFilterVector3f; diff --git a/libraries/Filter/LowPassFilter.cpp b/libraries/Filter/LowPassFilter.cpp index c19322c7595..e4f741b9343 100644 --- a/libraries/Filter/LowPassFilter.cpp +++ b/libraries/Filter/LowPassFilter.cpp @@ -9,6 +9,7 @@ #pragma GCC optimize("O2") #endif #include "LowPassFilter.h" +#include //////////////////////////////////////////////////////////////////////////////////////////// // DigitalLPF @@ -23,10 +24,18 @@ DigitalLPF::DigitalLPF() { // add a new raw value to the filter, retrieve the filtered result template T DigitalLPF::apply(const T &sample, float cutoff_freq, float dt) { - if (cutoff_freq <= 0.0f || dt <= 0.0f) { + if (is_negative(cutoff_freq) || is_negative(dt)) { + INTERNAL_ERROR(AP_InternalError::error_t::invalid_arg_or_result); _output = sample; return _output; } + if (is_zero(cutoff_freq)) { + _output = sample; + return _output; + } + if (is_zero(dt)) { + return _output; + } float rc = 1.0f/(M_2PI*cutoff_freq); alpha = constrain_float(dt/(dt+rc), 0.0f, 1.0f); _output += (sample - _output) * alpha; diff --git a/libraries/Filter/ModeFilter.cpp b/libraries/Filter/ModeFilter.cpp index 473f4cd21e1..8d21c461e8d 100644 --- a/libraries/Filter/ModeFilter.cpp +++ b/libraries/Filter/ModeFilter.cpp @@ -85,7 +85,7 @@ void ModeFilter::isort(T new_sample, bool drop_high) i = 0; // if the element is lower than our new sample, push it down one position - while ( FilterWithBuffer::samples[i+1] < new_sample && i < FilterWithBuffer::sample_index-1 ) { + while ( i < FilterWithBuffer::sample_index-1 && FilterWithBuffer::samples[i+1] < new_sample ) { FilterWithBuffer::samples[i] = FilterWithBuffer::samples[i+1]; i++; } diff --git a/libraries/Filter/NotchFilter.cpp b/libraries/Filter/NotchFilter.cpp index fb586d17db5..db9e2e234b7 100644 --- a/libraries/Filter/NotchFilter.cpp +++ b/libraries/Filter/NotchFilter.cpp @@ -20,6 +20,10 @@ #include "NotchFilter.h" +const static float NOTCH_MAX_SLEW = 0.05f; +const static float NOTCH_MAX_SLEW_LOWER = 1.0f - NOTCH_MAX_SLEW; +const static float NOTCH_MAX_SLEW_UPPER = 1.0f / NOTCH_MAX_SLEW_LOWER; + /* calculate the attenuation and quality factors of the filter */ @@ -43,6 +47,7 @@ void NotchFilter::init(float sample_freq_hz, float center_freq_hz, float band // check center frequency is in the allowable range if ((center_freq_hz > 0.5 * bandwidth_hz) && (center_freq_hz < 0.5 * sample_freq_hz)) { float A, Q; + initialised = false; // force center frequency change calculate_A_and_Q(center_freq_hz, bandwidth_hz, attenuation_dB, A, Q); init_with_A_and_Q(sample_freq_hz, center_freq_hz, A, Q); } else { @@ -53,8 +58,21 @@ void NotchFilter::init(float sample_freq_hz, float center_freq_hz, float band template void NotchFilter::init_with_A_and_Q(float sample_freq_hz, float center_freq_hz, float A, float Q) { - if ((center_freq_hz > 0.0) && (center_freq_hz < 0.5 * sample_freq_hz) && (Q > 0.0)) { - float omega = 2.0 * M_PI * center_freq_hz / sample_freq_hz; + // don't update if no updates required + if (initialised && is_equal(center_freq_hz, _center_freq_hz) && is_equal(sample_freq_hz, _sample_freq_hz)) { + return; + } + + float new_center_freq = center_freq_hz; + + // constrain the new center frequency by a percentage of the old frequency + if (initialised && !need_reset && !is_zero(_center_freq_hz)) { + new_center_freq = constrain_float(new_center_freq, _center_freq_hz * NOTCH_MAX_SLEW_LOWER, + _center_freq_hz * NOTCH_MAX_SLEW_UPPER); + } + + if ((new_center_freq > 0.0) && (new_center_freq < 0.5 * sample_freq_hz) && (Q > 0.0)) { + float omega = 2.0 * M_PI * new_center_freq / sample_freq_hz; float alpha = sinf(omega) / (2 * Q); b0 = 1.0 + alpha*sq(A); b1 = -2.0 * cosf(omega); @@ -62,8 +80,11 @@ void NotchFilter::init_with_A_and_Q(float sample_freq_hz, float center_freq_h a0_inv = 1.0/(1.0 + alpha); a1 = b1; a2 = 1.0 - alpha; + _center_freq_hz = new_center_freq; + _sample_freq_hz = sample_freq_hz; initialised = true; } else { + // leave center_freq_hz at last value initialised = false; } } @@ -74,14 +95,15 @@ void NotchFilter::init_with_A_and_Q(float sample_freq_hz, float center_freq_h template T NotchFilter::apply(const T &sample) { - if (!initialised) { + if (!initialised || need_reset) { // if we have not been initialised when return the input // sample as output and update delayed samples - ntchsig2 = ntchsig1; - ntchsig1 = ntchsig; - ntchsig = sample; - signal2 = signal1; signal1 = sample; + signal2 = sample; + ntchsig = sample; + ntchsig1 = sample; + ntchsig2 = sample; + need_reset = false; return sample; } ntchsig2 = ntchsig1; @@ -96,58 +118,10 @@ T NotchFilter::apply(const T &sample) template void NotchFilter::reset() { - ntchsig2 = ntchsig1 = T(); - signal2 = signal1 = T(); + need_reset = true; } -// table of user settable parameters -const AP_Param::GroupInfo NotchFilterParams::var_info[] = { - - // @Param: ENABLE - // @DisplayName: Enable - // @Description: Enable notch filter - // @Values: 0:Disabled,1:Enabled - // @User: Advanced - AP_GROUPINFO_FLAGS("ENABLE", 1, NotchFilterParams, _enable, 0, AP_PARAM_FLAG_ENABLE), - - // Slots 2 and 3 are reserved - they were integer versions of FREQ and BW which have since been converted to float - - // @Param: ATT - // @DisplayName: Attenuation - // @Description: Notch attenuation in dB - // @Range: 5 30 - // @Units: dB - // @User: Advanced - AP_GROUPINFO("ATT", 4, NotchFilterParams, _attenuation_dB, 15), - - // @Param: FREQ - // @DisplayName: Frequency - // @Description: Notch center frequency in Hz - // @Range: 10 400 - // @Units: Hz - // @User: Advanced - AP_GROUPINFO("FREQ", 5, NotchFilterParams, _center_freq_hz, 80), - - // @Param: BW - // @DisplayName: Bandwidth - // @Description: Notch bandwidth in Hz - // @Range: 5 100 - // @Units: Hz - // @User: Advanced - AP_GROUPINFO("BW", 6, NotchFilterParams, _bandwidth_hz, 20), - - AP_GROUPEND -}; - /* - a notch filter with enable and filter parameters - constructor - */ -NotchFilterParams::NotchFilterParams(void) -{ - AP_Param::setup_object_defaults(this, var_info); -} - -/* instantiate template classes */ template class NotchFilter; diff --git a/libraries/Filter/NotchFilter.h b/libraries/Filter/NotchFilter.h index 290210a630b..53bacc8e741 100644 --- a/libraries/Filter/NotchFilter.h +++ b/libraries/Filter/NotchFilter.h @@ -40,8 +40,9 @@ class NotchFilter { private: - bool initialised; + bool initialised, need_reset; float b0, b1, b2, a1, a2, a0_inv; + float _center_freq_hz, _sample_freq_hz; T ntchsig, ntchsig1, ntchsig2, signal2, signal1; }; @@ -50,13 +51,11 @@ class NotchFilter { */ class NotchFilterParams { public: - NotchFilterParams(void); - static const struct AP_Param::GroupInfo var_info[]; - float center_freq_hz(void) const { return _center_freq_hz; } float bandwidth_hz(void) const { return _bandwidth_hz; } float attenuation_dB(void) const { return _attenuation_dB; } uint8_t enabled(void) const { return _enable; } + void enable() { _enable.set(true); } protected: AP_Int8 _enable; diff --git a/libraries/Filter/SlewLimiter.cpp b/libraries/Filter/SlewLimiter.cpp index d2e06775979..0f95760258d 100644 --- a/libraries/Filter/SlewLimiter.cpp +++ b/libraries/Filter/SlewLimiter.cpp @@ -40,6 +40,10 @@ SlewLimiter::SlewLimiter(const float &_slew_rate_max, const float &_slew_rate_ta */ float SlewLimiter::modifier(float sample, float dt) { + if (!is_positive(dt)) { + return 1.0; + } + if (slew_rate_max <= 0) { _output_slew_rate = 0.0; return 1.0; @@ -103,7 +107,7 @@ float SlewLimiter::modifier(float sample, float dt) const float raw_slew_rate = 0.5f*(_max_pos_slew_rate + _max_neg_slew_rate); - // Apply a further reduction when the oldest exceedance event falls outside the window rewuired for the + // Apply a further reduction when the oldest exceedance event falls outside the window required for the // specified number of exceedance events. This prevents spikes due to control mode changed, etc causing // unwanted gain reduction and is only applied to the slew rate used for gain reduction float modifier_input = raw_slew_rate; @@ -113,7 +117,7 @@ float SlewLimiter::modifier(float sample, float dt) } // Apply a filter to increases in slew rate only to reduce the effect of gusts and large controller - // setpoint changeschanges + // setpoint changes const float attack_alpha = fminf(2.0f * decay_alpha, 1.0f); _modifier_slew_rate = (1.0f - attack_alpha) * _modifier_slew_rate + attack_alpha * modifier_input; diff --git a/libraries/Filter/tests/plot_harmonics.gnu b/libraries/Filter/tests/plot_harmonics.gnu new file mode 100755 index 00000000000..a534c4994d4 --- /dev/null +++ b/libraries/Filter/tests/plot_harmonics.gnu @@ -0,0 +1,11 @@ +#!/usr/bin/gnuplot -persist +set y2tics 0,10 +set ytics nomirror +set style data linespoints +set key autotitle +set datafile separator "," +set key autotitle columnhead +set xlabel "Freq(Hz)" +set ylabel "Attenuation" +#set ylabel2 "PhaseLag(deg)" +plot "harmonicnotch_test.csv" using 1:2 axis x1y1, "harmonicnotch_test.csv" using 1:3 axis x1y2 diff --git a/libraries/Filter/tests/test_notchfilter.cpp b/libraries/Filter/tests/test_notchfilter.cpp new file mode 100644 index 00000000000..4cc0c0dbf6c --- /dev/null +++ b/libraries/Filter/tests/test_notchfilter.cpp @@ -0,0 +1,159 @@ +#include + +#include +#include +#include + +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); + +/* + test if a reset of a notch filter results in no glitch in the following samples + with constant input + */ +TEST(NotchFilterTest, ResetTest) +{ + NotchFilter filter; + filter.init(1000, 60, 33, 41); + const float const_sample = -0.512; + filter.reset(); + for (uint32_t i=0; i<100; i++) { + float v = filter.apply(const_sample); + EXPECT_FLOAT_EQ(v, const_sample); + } +} + +/* + test with a sine input + */ +TEST(NotchFilterTest, SineTest) +{ + NotchFilter filter; + const float test_freq = 47; + const float attenuation_dB = 43; + const float rate_hz = 2000; + const double dt = 1.0 / rate_hz; + const uint32_t period_samples = rate_hz / test_freq; + const uint32_t periods = 1000; + const float test_amplitude = 0.7; + const float expected_ratio = powf(10, (attenuation_dB/2)/10.0); + double integral1_in = 0; + double integral1_out = 0; + double integral2_in = 0; + double integral2_out = 0; + filter.init(rate_hz, test_freq, test_freq*0.5, attenuation_dB); + filter.reset(); + for (uint32_t i=0; i= 2*period_samples) { + integral1_in += sample * dt; + integral2_in += fabsf(sample) * dt; + integral1_out += v * dt; + integral2_out += fabsf(v) * dt; + } + } + + // we expect both absolute integrals to be zero + EXPECT_LE(fabsf(integral1_in), 0.01); + EXPECT_LE(fabsf(integral1_out), 0.01); + + // we expect the output abs integral to be smaller than input + // integral by the attenuation + const float ratio1 = integral2_in / integral2_out; + ::printf("ratio1=%f expected_ratio=%f\n", ratio1, expected_ratio); + const float err_pct = 100 * fabsf(ratio1 - expected_ratio) / ratio1; + EXPECT_LE(err_pct, 1); +} + +/* + test attentuation versus frequency + This is a way to get a graph of the attenuation and phase lag for a complex filter setup + */ +TEST(NotchFilterTest, HarmonicNotchTest) +{ + const uint8_t num_test_freq = 150; + const uint8_t harmonics = 15; + const uint8_t num_harmonics = __builtin_popcount(harmonics); + const float base_freq = 46; + const float bandwidth = base_freq/2; + const float attenuation_dB = 60; + // number of identical filters chained together, simulating + // usage of per-motor notch filtering + const uint8_t chained_filters = 8; + const uint16_t rate_hz = 2000; + const uint32_t samples = 50000; + const float test_amplitude = 0.7; + const double dt = 1.0 / rate_hz; + + bool double_notch = true; + HarmonicNotchFilter filters[num_test_freq][chained_filters] {}; + struct { + double in; + double out; + double last_in; + double last_out; + uint32_t last_crossing; + uint32_t total_lag_samples; + uint32_t lag_count; + float get_lag_degrees(const float freq) const { + const float lag_avg = total_lag_samples/float(lag_count); + return (360.0 * lag_avg * freq) / rate_hz; + } + } integrals[num_test_freq] {}; + + for (uint8_t i=0; i= s/10) { + integrals[i].in += fabsf(sample) * dt; + integrals[i].out += fabsf(v) * dt; + } + if (sample >= 0 && integrals[i].last_in < 0) { + integrals[i].last_crossing = s; + } + if (v >= 0 && integrals[i].last_out < 0 && integrals[i].last_crossing != 0) { + integrals[i].total_lag_samples += s - integrals[i].last_crossing; + integrals[i].lag_count++; + } + integrals[i].last_in = sample; + integrals[i].last_out = v; + } + } + const char *csv_file = "harmonicnotch_test.csv"; + FILE *f = fopen(csv_file, "w"); + fprintf(f, "Freq(Hz),Ratio,Lag(deg)\n"); + for (uint8_t i=0; i #include #include +#include #include #include +#include +#include + +#include "MissionItemProtocol_Waypoints.h" +#include "MissionItemProtocol_Rally.h" +#include "MissionItemProtocol_Fence.h" extern const AP_HAL::HAL& hal; @@ -31,7 +38,9 @@ void GCS::get_sensor_status_flags(uint32_t &present, MissionItemProtocol_Waypoints *GCS::_missionitemprotocol_waypoints; MissionItemProtocol_Rally *GCS::_missionitemprotocol_rally; +#if AP_FENCE_ENABLED MissionItemProtocol_Fence *GCS::_missionitemprotocol_fence; +#endif const MAV_MISSION_TYPE GCS_MAVLINK::supported_mission_types[] = { MAV_MISSION_TYPE_MISSION, @@ -113,6 +122,17 @@ void GCS::send_named_float(const char *name, float value) const (const char *)&packet); } +#if HAL_HIGH_LATENCY2_ENABLED +void GCS::enable_high_latency_connections(bool enabled) +{ + for (uint8_t i=0; isys_status_enabled()) { @@ -330,7 +350,7 @@ bool GCS::out_of_time() const return true; } -void gcs_out_of_space_to_send_count(mavlink_channel_t chan) +void gcs_out_of_space_to_send(mavlink_channel_t chan) { gcs().chan(chan)->out_of_space_to_send(); } diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index bdbf31acc00..8b3708b8f4d 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -17,21 +17,18 @@ #include #include #include "MAVLink_routing.h" -#include -#include #include #include #include #include -#include #include #include -#include #include +#include +#include +#include +#include -#include "MissionItemProtocol_Waypoints.h" -#include "MissionItemProtocol_Rally.h" -#include "MissionItemProtocol_Fence.h" #include "ap_message.h" #define GCS_DEBUG_SEND_MESSAGE_TIMINGS 0 @@ -46,7 +43,7 @@ // macros used to determine if a message will fit in the space available. -void gcs_out_of_space_to_send_count(mavlink_channel_t chan); +void gcs_out_of_space_to_send(mavlink_channel_t chan); // important note: despite the names, these messages do NOT check to // see if the payload will fit in the buffer. They check to see if @@ -63,14 +60,14 @@ void gcs_out_of_space_to_send_count(mavlink_channel_t chan); // anywhere in the code to determine if the mavlink message with ID id // can currently fit in the output of _chan. Note the use of the "," // operator here to increment a counter. -#define HAVE_PAYLOAD_SPACE(_chan, id) (comm_get_txspace(_chan) >= PAYLOAD_SIZE(_chan, id) ? true : (gcs_out_of_space_to_send_count(_chan), false)) +#define HAVE_PAYLOAD_SPACE(_chan, id) (comm_get_txspace(_chan) >= PAYLOAD_SIZE(_chan, id) ? true : (gcs_out_of_space_to_send(_chan), false)) // CHECK_PAYLOAD_SIZE - macro which may only be used within a // GCS_MAVLink object's methods. It inserts code which will // immediately return false from the current function if there is no // room to fit the mavlink message with id id on the current object's // output -#define CHECK_PAYLOAD_SIZE(id) if (txspace() < unsigned(packet_overhead()+MAVLINK_MSG_ID_ ## id ## _LEN)) { gcs_out_of_space_to_send_count(chan); return false; } +#define CHECK_PAYLOAD_SIZE(id) if (txspace() < unsigned(packet_overhead()+MAVLINK_MSG_ID_ ## id ## _LEN)) { gcs_out_of_space_to_send(chan); return false; } // CHECK_PAYLOAD_SIZE2 - macro which inserts code which will // immediately return false from the current function if there is no @@ -79,6 +76,12 @@ void gcs_out_of_space_to_send_count(mavlink_channel_t chan); // scope. #define CHECK_PAYLOAD_SIZE2(id) if (!HAVE_PAYLOAD_SPACE(chan, id)) return false +// CHECK_PAYLOAD_SIZE2_VOID - macro which inserts code which will +// immediately return from the current (void) function if there is no +// room to fit the mavlink message with id id on the mavlink output +// channel "chan". +#define CHECK_PAYLOAD_SIZE2_VOID(chan, id) if (!HAVE_PAYLOAD_SPACE(chan, id)) return + // convenience macros for defining which ap_message ids are in which streams: #define MAV_STREAM_ENTRY(stream_name) \ { \ @@ -174,6 +177,7 @@ class GCS_MAVLINK void send_mission_ack(const mavlink_message_t &msg, MAV_MISSION_TYPE mission_type, MAV_MISSION_RESULT result) const { + CHECK_PAYLOAD_SIZE2_VOID(chan, MISSION_ACK); mavlink_msg_mission_ack_send(chan, msg.sysid, msg.compid, @@ -303,9 +307,8 @@ class GCS_MAVLINK void send_local_position() const; void send_vfr_hud(); void send_vibration() const; - void send_mount_status() const; + void send_gimbal_device_attitude_status() const; void send_named_float(const char *name, float value) const; - void send_gimbal_report() const; void send_home_position() const; void send_gps_global_origin() const; virtual void send_attitude_target() {}; @@ -326,6 +329,7 @@ class GCS_MAVLINK void send_high_latency2() const; #endif // HAL_HIGH_LATENCY2_ENABLED void send_uavionix_adsb_out_status() const; + void send_autopilot_state_for_gimbal_device() const; // lock a channel, preventing use by MAVLink void lock(bool _lock) { @@ -358,6 +362,11 @@ class GCS_MAVLINK // return true if channel is private bool is_private(void) const { return is_private(chan); } +#if HAL_HIGH_LATENCY2_ENABLED + // return true if the link should be sending. Will return false if is a high latency link AND is not active + bool should_send() { return is_high_latency_link ? high_latency_link_enabled : true; } +#endif + /* send a MAVLink message to all components with this vehicle's system id This is a no-op if no routes to components have been learned @@ -375,6 +384,15 @@ class GCS_MAVLINK */ static bool find_by_mavtype(uint8_t mav_type, uint8_t &sysid, uint8_t &compid, mavlink_channel_t &channel) { return routing.find_by_mavtype(mav_type, sysid, compid, channel); } + /* + search for the first vehicle or component in the routing table with given mav_type and component id and retrieve its sysid and channel + returns true if a match is found + */ + static bool find_by_mavtype_and_compid(uint8_t mav_type, uint8_t compid, uint8_t &sysid, mavlink_channel_t &channel) { return routing.find_by_mavtype_and_compid(mav_type, compid, sysid, channel); } + // same as above, but returns a pointer to the GCS_MAVLINK object + // corresponding to the channel + static GCS_MAVLINK *find_by_mavtype_and_compid(uint8_t mav_type, uint8_t compid, uint8_t &sysid); + // update signing timestamp on GPS lock static void update_signing_timestamp(uint64_t timestamp_usec); @@ -477,7 +495,9 @@ class GCS_MAVLINK void handle_common_rally_message(const mavlink_message_t &msg); void handle_rally_fetch_point(const mavlink_message_t &msg); void handle_rally_point(const mavlink_message_t &msg) const; +#if HAL_MOUNT_ENABLED virtual void handle_mount_message(const mavlink_message_t &msg); +#endif void handle_fence_message(const mavlink_message_t &msg); void handle_param_value(const mavlink_message_t &msg); void handle_radio_status(const mavlink_message_t &msg, bool log_radio); @@ -606,12 +626,18 @@ class GCS_MAVLINK virtual uint8_t high_latency_wind_speed() const { return 0; } virtual uint8_t high_latency_wind_direction() const { return 0; } int8_t high_latency_air_temperature() const; -#endif // HAL_HIGH_LATENCY2_ENABLED + MAV_RESULT handle_control_high_latency(const mavlink_command_long_t &packet); + + // true if this is a high latency link + bool is_high_latency_link; + bool high_latency_link_enabled; +#endif // HAL_HIGH_LATENCY2_ENABLED + static constexpr const float magic_force_arm_value = 2989.0f; static constexpr const float magic_force_disarm_value = 21196.0f; - void manual_override(RC_Channel *c, int16_t value_in, uint16_t offset, float scaler, const uint32_t tnow, bool reversed = false); + void manual_override(class RC_Channel *c, int16_t value_in, uint16_t offset, float scaler, const uint32_t tnow, bool reversed = false); uint8_t receiver_rssi() const; @@ -632,6 +658,8 @@ class GCS_MAVLINK private: + const AP_SerialManager::UARTState *uartstate; + // last time we got a non-zero RSSI from RADIO_STATUS static struct LastRadioStatus { uint32_t remrssi_ms; @@ -641,6 +669,8 @@ class GCS_MAVLINK void log_mavlink_stats(); + uint32_t last_accel_cal_ms; // used to rate limit accel cals for bad links + MAV_RESULT _set_mode_common(const MAV_MODE base_mode, const uint32_t custom_mode); // send a (textual) message to the GCS that a received message has @@ -689,9 +719,10 @@ class GCS_MAVLINK const ap_message id; uint16_t interval_ms; uint16_t last_sent_ms; // from AP_HAL::millis16() - } deferred_message[2] = { + } deferred_message[3] = { { MSG_HEARTBEAT, }, { MSG_NEXT_PARAM, }, + { MSG_HIGH_LATENCY2, }, }; // returns index of id in deferred_message[] or -1 if not present int8_t get_deferred_message_index(const ap_message id) const; @@ -862,7 +893,6 @@ class GCS_MAVLINK struct ftp_state { ObjectBuffer *requests; - ObjectBuffer *replies; // session specific info, currently only support a single session over all links int fd = -1; @@ -879,7 +909,7 @@ class GCS_MAVLINK bool ftp_init(void); void handle_file_transfer_protocol(const mavlink_message_t &msg); - void send_ftp_replies(void); + bool send_ftp_reply(const pending_ftp &reply); void ftp_worker(void); void ftp_push_replies(pending_ftp &reply); @@ -1051,10 +1081,12 @@ class GCS ap_var_type param_type, float param_value); - static MissionItemProtocol_Waypoints *_missionitemprotocol_waypoints; - static MissionItemProtocol_Rally *_missionitemprotocol_rally; - static MissionItemProtocol_Fence *_missionitemprotocol_fence; - MissionItemProtocol *get_prot_for_mission_type(const MAV_MISSION_TYPE mission_type) const; + static class MissionItemProtocol_Waypoints *_missionitemprotocol_waypoints; + static class MissionItemProtocol_Rally *_missionitemprotocol_rally; +#if AP_FENCE_ENABLED + static class MissionItemProtocol_Fence *_missionitemprotocol_fence; +#endif + class MissionItemProtocol *get_prot_for_mission_type(const MAV_MISSION_TYPE mission_type) const; void try_send_queued_message_for_type(MAV_MISSION_TYPE type) const; void update_send(); @@ -1075,9 +1107,9 @@ class GCS bool out_of_time() const; // frsky backend - AP_Frsky_Telem *frsky; + class AP_Frsky_Telem *frsky; -#if !HAL_MINIMIZE_FEATURES +#if AP_LTM_TELEM_ENABLED // LTM backend AP_LTM_Telem ltm_telemetry; #endif @@ -1108,6 +1140,10 @@ class GCS uint8_t get_channel_from_port_number(uint8_t port_num); +#if HAL_HIGH_LATENCY2_ENABLED + void enable_high_latency_connections(bool enabled); +#endif // HAL_HIGH_LATENCY2_ENABLED + protected: virtual uint8_t sysid_this_mav() const = 0; diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 1decefa92b0..dbaa4dd4996 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -18,6 +18,7 @@ #include #include +#include #include #include #include @@ -44,11 +45,20 @@ #include #include #include +#include #include #include #include +#include #include #include +#include +#include +#include + +#include "MissionItemProtocol_Waypoints.h" +#include "MissionItemProtocol_Rally.h" +#include "MissionItemProtocol_Fence.h" #include @@ -70,7 +80,6 @@ #if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_ArduSub) #include #endif - #include #include #include #endif @@ -105,22 +114,25 @@ GCS_MAVLINK::GCS_MAVLINK(GCS_MAVLINK_Parameters ¶meters, bool GCS_MAVLINK::init(uint8_t instance) { - // search for serial port - const AP_SerialManager& serial_manager = AP::serialmanager(); - - const AP_SerialManager::SerialProtocol protocol = AP_SerialManager::SerialProtocol_MAVLink; - // get associated mavlink channel - if (!serial_manager.get_mavlink_channel(protocol, instance, chan)) { - // return immediately in unlikely case mavlink channel cannot be found + chan = (mavlink_channel_t)(MAVLINK_COMM_0 + instance); + if (!valid_channel(chan)) { return false; } - // and init the gcs instance - if (!valid_channel(chan)) { + + // find instance of MAVLink protocol; the protocol_match method in + // AP_SerialManager means this will match MAVLink2 and MAVLinkHL, + // too: + uartstate = AP::serialmanager().find_protocol_instance(AP_SerialManager::SerialProtocol_MAVLink, instance); + if (uartstate == nullptr) { return false; } - if (!serial_manager.should_forward_mavlink_telemetry(protocol, instance)) { + // and init the gcs instance + + // whether this port is considered "private" is stored on the uart + // rather than in our own parameters: + if (uartstate->option_enabled(AP_HAL::UARTDriver::OPTION_MAVLINK_NO_FORWARD)) { set_channel_private(chan); } @@ -146,24 +158,30 @@ bool GCS_MAVLINK::init(uint8_t instance) _port->set_flow_control(old_flow_control); // now change back to desired baudrate - _port->begin(serial_manager.find_baudrate(protocol, instance)); + _port->begin(uartstate->baudrate()); mavlink_comm_port[chan] = _port; - AP_SerialManager::SerialProtocol mavlink_protocol = serial_manager.get_mavlink_protocol(chan); + const auto mavlink_protocol = uartstate->get_protocol(); mavlink_status_t *status = mavlink_get_channel_status(chan); if (status == nullptr) { return false; } - if (mavlink_protocol == AP_SerialManager::SerialProtocol_MAVLink2) { + if (mavlink_protocol == AP_SerialManager::SerialProtocol_MAVLink2 || + mavlink_protocol == AP_SerialManager::SerialProtocol_MAVLinkHL) { // load signing key load_signing_key(); - } else if (status) { + } else { // user has asked to only send MAVLink1 status->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1; } - + +#if HAL_HIGH_LATENCY2_ENABLED + if (mavlink_protocol == AP_SerialManager::SerialProtocol_MAVLinkHL) { + is_high_latency_link = true; + } +#endif return true; } @@ -226,36 +244,75 @@ void GCS_MAVLINK::send_battery_status(const uint8_t instance) const bool got_temperature = battery.get_temperature(temp, instance); // prepare arrays of individual cell voltages - uint16_t cell_volts[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN]; - uint16_t cell_volts_ext[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_EXT_LEN]; + uint16_t cell_mvolts[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN]; + uint16_t cell_mvolts_ext[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_EXT_LEN]; + const uint16_t max_cell_mV = 0xFFFEU; + const uint16_t invalid_cell_mV = 0xFFFFU; + if (battery.has_cell_voltages(instance)) { const AP_BattMonitor::cells& batt_cells = battery.get_cell_voltages(instance); + static_assert(sizeof(cell_mvolts) <= sizeof(batt_cells.cells), "cell array length not large enough"); + // copy the first 10 cells - memcpy(cell_volts, batt_cells.cells, sizeof(cell_volts)); + memcpy(cell_mvolts, batt_cells.cells, sizeof(cell_mvolts)); // 11 ... 14 use a second cell_volts_ext array for (uint8_t i = 0; i < MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_EXT_LEN; i++) { if (MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN+i < uint8_t(ARRAY_SIZE(batt_cells.cells))) { - cell_volts_ext[i] = batt_cells.cells[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN+i]; + cell_mvolts_ext[i] = batt_cells.cells[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN+i]; } else { - cell_volts_ext[i] = 0; + cell_mvolts_ext[i] = 0; + } + } + /* + now adjust voltages to cope with two things: + 1) we may be reporting sag corrected voltage + 2) the battery may have more cells than can be reported by the backend, so the actual voltage may be higher than the sum + */ + const float voltage_mV = battery.gcs_voltage(instance) * 1e3f; + float voltage_mV_sum = 0; + uint8_t non_zero_cell_count = 0; + for (uint8_t i=0; i 0 && cell_mvolts[i] != invalid_cell_mV) { + non_zero_cell_count++; + voltage_mV_sum += cell_mvolts[i]; + } + } + for (uint8_t i=0; i 0 && cell_mvolts_ext[i] != invalid_cell_mV) { + non_zero_cell_count++; + voltage_mV_sum += cell_mvolts_ext[i]; + } + } + if (voltage_mV > voltage_mV_sum && non_zero_cell_count > 0) { + // distribute the extra voltage over the non-zero cells + uint32_t extra_mV = (voltage_mV - voltage_mV_sum) / non_zero_cell_count; + for (uint8_t i=0; i 0 && cell_mvolts[i] != invalid_cell_mV) { + cell_mvolts[i] = MIN(cell_mvolts[i] + extra_mV, max_cell_mV); + } + } + for (uint8_t i=0; i 0 && cell_mvolts_ext[i] != invalid_cell_mV) { + cell_mvolts_ext[i] = MIN(cell_mvolts_ext[i] + extra_mV, max_cell_mV); + } } } } else { // for battery monitors that cannot provide voltages for individual cells the battery's total voltage is put into the first cell // if the total voltage cannot fit into a single field, the remainder into subsequent fields. // the GCS can then recover the pack voltage by summing all non ignored cell values an we can report a pack up to 655.34 V - float voltage = battery.voltage(instance) * 1e3f; + float voltage_mV = battery.gcs_voltage(instance) * 1e3f; for (uint8_t i = 0; i < MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN; i++) { - if (voltage < 0.001f) { + if (voltage_mV < 0.001f) { // too small to send to the GCS, set it to the no cell value - cell_volts[i] = UINT16_MAX; + cell_mvolts[i] = UINT16_MAX; } else { - cell_volts[i] = MIN(voltage, 65534.0f); // Can't send more then UINT16_MAX - 1 in a cell - voltage -= 65534.0f; + cell_mvolts[i] = MIN(voltage_mV, max_cell_mV); // Can't send more then UINT16_MAX - 1 in a cell + voltage_mV -= max_cell_mV; } } for (uint8_t i = 0; i < MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_EXT_LEN; i++) { - cell_volts_ext[i] = 0; + cell_mvolts_ext[i] = 0; } } @@ -285,14 +342,14 @@ void GCS_MAVLINK::send_battery_status(const uint8_t instance) const MAV_BATTERY_FUNCTION_UNKNOWN, // function MAV_BATTERY_TYPE_UNKNOWN, // type got_temperature ? ((int16_t) (temp * 100)) : INT16_MAX, // temperature. INT16_MAX if unknown - cell_volts, // cell voltages + cell_mvolts, // cell voltages current, // current in centiampere consumed_mah, // total consumed current in milliampere.hour consumed_wh, // consumed energy in hJ (hecto-Joules) percentage, time_remaining, // time remaining, seconds battery.get_mavlink_charge_state(instance), // battery charge state - cell_volts_ext, // Cell 11..14 voltages + cell_mvolts_ext, // Cell 11..14 voltages 0, // battery mode battery.get_mavlink_fault_bitmask(instance)); // fault_bitmask #else @@ -394,7 +451,9 @@ void GCS_MAVLINK::send_distance_sensor() } } +#if HAL_PROXIMITY_ENABLED send_proximity(); +#endif } void GCS_MAVLINK::send_rangefinder() const @@ -413,9 +472,9 @@ void GCS_MAVLINK::send_rangefinder() const s->voltage_mv() * 0.001f); } +#if HAL_PROXIMITY_ENABLED void GCS_MAVLINK::send_proximity() { -#if HAL_PROXIMITY_ENABLED AP_Proximity *proximity = AP_Proximity::get_singleton(); if (proximity == nullptr) { return; // this is wrong, but pretend we sent data and don't requeue @@ -427,7 +486,7 @@ void GCS_MAVLINK::send_proximity() // send horizontal distances if (proximity->get_status() == AP_Proximity::Status::Good) { - AP_Proximity::Proximity_Distance_Array dist_array; + Proximity_Distance_Array dist_array; if (proximity->get_horizontal_distances(dist_array)) { for (uint8_t i = 0; i < PROXIMITY_MAX_DIRECTION; i++) { if (!HAVE_PAYLOAD_SPACE(chan, DISTANCE_SENSOR)) { @@ -473,8 +532,8 @@ void GCS_MAVLINK::send_proximity() 0, // Measurement covariance in centimeters, 0 for unknown / invalid readings 0, 0, nullptr, 0); } -#endif // HAL_PROXIMITY_ENABLED } +#endif // HAL_PROXIMITY_ENABLED // report AHRS2 state void GCS_MAVLINK::send_ahrs2() @@ -502,8 +561,10 @@ MissionItemProtocol *GCS::get_prot_for_mission_type(const MAV_MISSION_TYPE missi return _missionitemprotocol_waypoints; case MAV_MISSION_TYPE_RALLY: return _missionitemprotocol_rally; +#if AP_FENCE_ENABLED case MAV_MISSION_TYPE_FENCE: return _missionitemprotocol_fence; +#endif default: return nullptr; } @@ -658,20 +719,21 @@ void GCS_MAVLINK::handle_mission_write_partial_list(const mavlink_message_t &msg use_prot->handle_mission_write_partial_list(*this, msg, packet); } +#if HAL_MOUNT_ENABLED /* pass mavlink messages to the AP_Mount singleton */ void GCS_MAVLINK::handle_mount_message(const mavlink_message_t &msg) { -#if HAL_MOUNT_ENABLED AP_Mount *mount = AP::mount(); if (mount == nullptr) { return; } mount->handle_message(chan, msg); -#endif } +#endif + /* pass parameter value messages through to mount library */ @@ -796,7 +858,7 @@ void GCS_MAVLINK::handle_mission_item(const mavlink_message_t &msg) // add home alt if needed handle_change_alt_request(cmd); - // verify we recevied the command + // verify we received the command result = MAV_MISSION_ACCEPTED; } send_mission_ack(msg, MAV_MISSION_TYPE_MISSION, result); @@ -840,7 +902,9 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c { MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, MSG_ORIGIN}, { MAVLINK_MSG_ID_SYS_STATUS, MSG_SYS_STATUS}, { MAVLINK_MSG_ID_POWER_STATUS, MSG_POWER_STATUS}, +#if HAL_WITH_MCU_MONITORING { MAVLINK_MSG_ID_MCU_STATUS, MSG_MCU_STATUS}, +#endif { MAVLINK_MSG_ID_MEMINFO, MSG_MEMINFO}, { MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, MSG_NAV_CONTROLLER_OUTPUT}, { MAVLINK_MSG_ID_MISSION_CURRENT, MSG_CURRENT_WAYPOINT}, @@ -857,15 +921,19 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c { MAVLINK_MSG_ID_SCALED_PRESSURE3, MSG_SCALED_PRESSURE3}, { MAVLINK_MSG_ID_GPS_RAW_INT, MSG_GPS_RAW}, { MAVLINK_MSG_ID_GPS_RTK, MSG_GPS_RTK}, +#if GPS_MAX_RECEIVERS > 1 { MAVLINK_MSG_ID_GPS2_RAW, MSG_GPS2_RAW}, { MAVLINK_MSG_ID_GPS2_RTK, MSG_GPS2_RTK}, +#endif { MAVLINK_MSG_ID_SYSTEM_TIME, MSG_SYSTEM_TIME}, { MAVLINK_MSG_ID_RC_CHANNELS_SCALED, MSG_SERVO_OUT}, { MAVLINK_MSG_ID_PARAM_VALUE, MSG_NEXT_PARAM}, { MAVLINK_MSG_ID_FENCE_STATUS, MSG_FENCE_STATUS}, { MAVLINK_MSG_ID_AHRS, MSG_AHRS}, +#if AP_SIM_ENABLED { MAVLINK_MSG_ID_SIMSTATE, MSG_SIMSTATE}, { MAVLINK_MSG_ID_SIM_STATE, MSG_SIM_STATE}, +#endif { MAVLINK_MSG_ID_AHRS2, MSG_AHRS2}, { MAVLINK_MSG_ID_HWSTATUS, MSG_HWSTATUS}, { MAVLINK_MSG_ID_WIND, MSG_WIND}, @@ -875,9 +943,13 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c { MAVLINK_MSG_ID_TERRAIN_REQUEST, MSG_TERRAIN}, { MAVLINK_MSG_ID_BATTERY2, MSG_BATTERY2}, { MAVLINK_MSG_ID_CAMERA_FEEDBACK, MSG_CAMERA_FEEDBACK}, - { MAVLINK_MSG_ID_MOUNT_STATUS, MSG_MOUNT_STATUS}, +#if HAL_MOUNT_ENABLED + { MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS, MSG_GIMBAL_DEVICE_ATTITUDE_STATUS}, + { MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE, MSG_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE}, +#endif +#if AP_OPTICALFLOW_ENABLED { MAVLINK_MSG_ID_OPTICAL_FLOW, MSG_OPTICAL_FLOW}, - { MAVLINK_MSG_ID_GIMBAL_REPORT, MSG_GIMBAL_REPORT}, +#endif { MAVLINK_MSG_ID_MAG_CAL_PROGRESS, MSG_MAG_CAL_PROGRESS}, { MAVLINK_MSG_ID_MAG_CAL_REPORT, MSG_MAG_CAL_REPORT}, { MAVLINK_MSG_ID_EKF_STATUS_REPORT, MSG_EKF_STATUS_REPORT}, @@ -895,14 +967,28 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c { MAVLINK_MSG_ID_DEEPSTALL, MSG_LANDING}, { MAVLINK_MSG_ID_EXTENDED_SYS_STATE, MSG_EXTENDED_SYS_STATE}, { MAVLINK_MSG_ID_AUTOPILOT_VERSION, MSG_AUTOPILOT_VERSION}, +#if HAL_EFI_ENABLED { MAVLINK_MSG_ID_EFI_STATUS, MSG_EFI_STATUS}, +#endif +#if HAL_GENERATOR_ENABLED { MAVLINK_MSG_ID_GENERATOR_STATUS, MSG_GENERATOR_STATUS}, +#endif { MAVLINK_MSG_ID_WINCH_STATUS, MSG_WINCH_STATUS}, +#if HAL_WITH_ESC_TELEM { MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4, MSG_ESC_TELEMETRY}, +#endif +#if APM_BUILD_TYPE(APM_BUILD_Rover) { MAVLINK_MSG_ID_WATER_DEPTH, MSG_WATER_DEPTH}, +#endif +#if HAL_HIGH_LATENCY2_ENABLED { MAVLINK_MSG_ID_HIGH_LATENCY2, MSG_HIGH_LATENCY2}, +#endif +#if AP_AIS_ENABLED { MAVLINK_MSG_ID_AIS_VESSEL, MSG_AIS_VESSEL}, +#endif +#if HAL_ADSB_ENABLED { MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS, MSG_UAVIONIX_ADSB_OUT_STATUS}, +#endif }; for (uint8_t i=0; iget_protocol(); if (!(status.flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) && (status.flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && - AP::serialmanager().get_mavlink_protocol(chan) == AP_SerialManager::SerialProtocol_MAVLink2) { + (mavlink_protocol == AP_SerialManager::SerialProtocol_MAVLink2 || + mavlink_protocol == AP_SerialManager::SerialProtocol_MAVLinkHL)) { // if we receive any MAVLink2 packets on a connection // currently sending MAVLink1 then switch to sending // MAVLink2 @@ -1434,7 +1522,10 @@ void GCS_MAVLINK::packetReceived(const mavlink_status_t &status, return; } if (msg.msgid == MAVLINK_MSG_ID_GLOBAL_POSITION_INT) { +#if HAL_MOUNT_ENABLED + // allow mounts to see the location of other vehicles handle_mount_message(msg); +#endif } if (!accept_packet(status, msg)) { // e.g. enforce-sysid says we shouldn't look at this packet @@ -2104,7 +2195,7 @@ void GCS::send_message(enum ap_message id) void GCS::update_send() { update_send_has_been_called = true; -#ifndef HAL_BUILD_AP_PERIPH +#if !defined(HAL_BUILD_AP_PERIPH) && AP_FENCE_ENABLED if (!initialised_missionitemprotocol_objects) { initialised_missionitemprotocol_objects = true; // once-only initialisation of MissionItemProtocol objects: @@ -2226,7 +2317,7 @@ void GCS::setup_uarts() frsky = nullptr; } } -#if !HAL_MINIMIZE_FEATURES +#if AP_LTM_TELEM_ENABLED ltm_telemetry.init(); #endif @@ -2322,7 +2413,7 @@ MAV_RESULT GCS_MAVLINK::_set_mode_common(const MAV_MODE _base_mode, const uint32 */ void GCS_MAVLINK::send_opticalflow() { - const OpticalFlow *optflow = AP::opticalflow(); + const AP_OpticalFlow *optflow = AP::opticalflow(); // exit immediately if no optical flow sensor or not healthy if (optflow == nullptr || @@ -2701,22 +2792,47 @@ bool GCS_MAVLINK::telemetry_delayed() const */ void GCS_MAVLINK::send_servo_output_raw() { - uint16_t values[16] {}; - hal.rcout->read(values, 16); + const uint32_t enabled_mask = ~SRV_Channels::get_output_channel_mask(SRV_Channel::k_GPIO); + if (enabled_mask == 0) { + return; + } - for (uint8_t i=0; i<16; i++) { +#if NUM_SERVO_CHANNELS >= 17 + static const uint8_t max_channels = 32; +#else + static const uint8_t max_channels = 16; +#endif + + uint16_t values[max_channels] {}; + hal.rcout->read(values, max_channels); + for (uint8_t i=0; i= 17 + if ((enabled_mask & 0xFFFF0000) != 0) { + mavlink_msg_servo_output_raw_send( + chan, + AP_HAL::micros(), + 1, // port + values[16], values[17], values[18], values[19], + values[20], values[21], values[22], values[23], + values[24], values[25], values[26], values[27], + values[28], values[29], values[30], values[31]); + } +#endif } @@ -2847,6 +2963,18 @@ MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_long_t &pa INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); return MAV_RESULT_ACCEPTED; } +#if HAL_ENABLE_DFU_BOOT + if (is_equal(packet.param4, 99.0f)) { +#if AP_SIGNED_FIRMWARE + send_text(MAV_SEVERITY_ERROR, "Refusing DFU for secure firmware"); + return MAV_RESULT_FAILED; +#else + send_text(MAV_SEVERITY_WARNING, "Entering DFU mode"); + hal.util->boot_to_dfu(); + return MAV_RESULT_ACCEPTED; +#endif + } +#endif } if (hal.util->get_soft_armed()) { @@ -2859,6 +2987,19 @@ MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_long_t &pa return MAV_RESULT_UNSUPPORTED; } +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL + { // autotest relies in receiving the ACK for the reboot. Ensure + // there is space for it: + const uint32_t tstart_ms = AP_HAL::millis(); + while (AP_HAL::millis() - tstart_ms < 1000) { + if (HAVE_PAYLOAD_SPACE(chan, COMMAND_ACK)) { + break; + } + hal.scheduler->delay(10); + } + } +#endif + // send ack before we reboot mavlink_msg_command_ack_send(chan, packet.command, MAV_RESULT_ACCEPTED, 0, 0, 0, 0); @@ -3235,11 +3376,13 @@ void GCS_MAVLINK::handle_odometry(const mavlink_message_t &msg) posErr = cbrtf(sq(m.pose_covariance[0])+sq(m.pose_covariance[6])+sq(m.pose_covariance[11])); angErr = cbrtf(sq(m.pose_covariance[15])+sq(m.pose_covariance[18])+sq(m.pose_covariance[20])); } - + const uint32_t timestamp_ms = correct_offboard_timestamp_usec_to_ms(m.time_usec, PAYLOAD_SIZE(chan, ODOMETRY)); visual_odom->handle_vision_position_estimate(m.time_usec, timestamp_ms, m.x, m.y, m.z, q, posErr, angErr, m.reset_counter); - const Vector3f vel{m.vx, m.vy, m.vz}; + // convert velocity vector from FRD to NED frame + Vector3f vel{m.vx, m.vy, m.vz}; + vel = q * vel; visual_odom->handle_vision_speed_estimate(m.time_usec, timestamp_ms, vel, m.reset_counter); #endif } @@ -3313,10 +3456,13 @@ void GCS_MAVLINK::handle_vision_speed_estimate(const mavlink_message_t &msg) void GCS_MAVLINK::handle_command_ack(const mavlink_message_t &msg) { -#if HAL_INS_ENABLED +#if HAL_INS_ACCELCAL_ENABLED + mavlink_command_ack_t packet; + mavlink_msg_command_ack_decode(&msg, &packet); + AP_AccelCal *accelcal = AP::ins().get_acal(); if (accelcal != nullptr) { - accelcal->handleMessage(msg); + accelcal->handle_command_ack(packet); } #endif } @@ -3377,7 +3523,7 @@ void GCS_MAVLINK::handle_rc_channels_override(const mavlink_message_t &msg) #if AP_OPTICALFLOW_ENABLED void GCS_MAVLINK::handle_optical_flow(const mavlink_message_t &msg) { - OpticalFlow *optflow = AP::opticalflow(); + AP_OpticalFlow *optflow = AP::opticalflow(); if (optflow == nullptr) { return; } @@ -3585,9 +3731,21 @@ void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg) handle_fence_message(msg); break; +#if HAL_MOUNT_ENABLED + case MAVLINK_MSG_ID_MOUNT_CONFIGURE: // deprecated. Use MAV_CMD_DO_MOUNT_CONFIGURE + send_received_message_deprecation_warning("MOUNT_CONFIGURE"); + handle_mount_message(msg); + break; + case MAVLINK_MSG_ID_MOUNT_CONTROL: // deprecated. Use MAV_CMD_DO_MOUNT_CONTROL + send_received_message_deprecation_warning("MOUNT_CONTROL"); + handle_mount_message(msg); + break; case MAVLINK_MSG_ID_GIMBAL_REPORT: + case MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION: + case MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS: handle_mount_message(msg); break; +#endif case MAVLINK_MSG_ID_PARAM_VALUE: handle_param_value(msg); @@ -3613,22 +3771,17 @@ void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg) AP_Notify::handle_led_control(msg); break; - case MAVLINK_MSG_ID_MOUNT_CONFIGURE: // deprecated. Use MAV_CMD_DO_MOUNT_CONFIGURE - case MAVLINK_MSG_ID_MOUNT_CONTROL: // deprecated. Use MAV_CMD_DO_MOUNT_CONTROL - handle_mount_message(msg); - break; - case MAVLINK_MSG_ID_PLAY_TUNE: // send message to Notify AP_Notify::handle_play_tune(msg); break; +#if HAL_RALLY_ENABLED case MAVLINK_MSG_ID_RALLY_POINT: case MAVLINK_MSG_ID_RALLY_FETCH_POINT: -#if HAL_RALLY_ENABLED handle_common_rally_message(msg); -#endif break; +#endif case MAVLINK_MSG_ID_REQUEST_DATA_STREAM: // only pass if override is not selected @@ -3717,6 +3870,7 @@ void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg) break; case MAVLINK_MSG_ID_CAN_FRAME: + case MAVLINK_MSG_ID_CANFD_FRAME: handle_can_frame(msg); break; @@ -3725,6 +3879,24 @@ void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg) AP::can().handle_can_filter_modify(msg); #endif break; + +#if AP_OPENDRONEID_ENABLED + case MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS: + case MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID: + case MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID: + case MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID: + case MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM: + case MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_UPDATE: + AP::opendroneid().handle_msg(chan, msg); + break; +#endif + +#if AP_SIGNED_FIRMWARE + case MAVLINK_MSG_ID_SECURE_COMMAND: + case MAVLINK_MSG_ID_SECURE_COMMAND_REPLY: + AP_CheckFirmware::handle_msg(chan, msg); + break; +#endif } } @@ -3811,7 +3983,7 @@ void GCS_MAVLINK::send_banner() } // send system ID if we can - char sysid[40]; + char sysid[50]; if (hal.util->get_system_id(sysid)) { send_text(MAV_SEVERITY_INFO, "%s", sysid); } @@ -3833,27 +4005,25 @@ void GCS_MAVLINK::send_banner() } +#if AP_SIM_ENABLED void GCS_MAVLINK::send_simstate() const { -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL SITL::SIM *sitl = AP::sitl(); if (sitl == nullptr) { return; } sitl->simstate_send(get_chan()); -#endif } void GCS_MAVLINK::send_sim_state() const { -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL SITL::SIM *sitl = AP::sitl(); if (sitl == nullptr) { return; } sitl->sim_state_send(get_chan()); -#endif } +#endif MAV_RESULT GCS_MAVLINK::handle_command_flash_bootloader(const mavlink_command_long_t &packet) { @@ -3867,6 +4037,11 @@ MAV_RESULT GCS_MAVLINK::handle_command_flash_bootloader(const mavlink_command_lo case AP_HAL::Util::FlashBootloader::NO_CHANGE: // consider NO_CHANGE as success (so as not to display error to user) return MAV_RESULT_ACCEPTED; +#if AP_SIGNED_FIRMWARE + case AP_HAL::Util::FlashBootloader::NOT_SIGNED: + gcs().send_text(MAV_SEVERITY_ERROR, "Bootloader not signed"); + break; +#endif default: break; } @@ -3942,7 +4117,7 @@ MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration(const mavlink_comm rc().calibrating(is_positive(packet.param4)); -#if HAL_INS_ENABLED +#if HAL_INS_ACCELCAL_ENABLED if (is_equal(packet.param5,1.0f)) { // start with gyro calibration if (!calibrate_gyros()) { @@ -3953,22 +4128,38 @@ MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration(const mavlink_comm AP::ins().get_acal()->start(this); return MAV_RESULT_ACCEPTED; } +#endif +#if HAL_INS_ENABLED + const uint32_t now = AP_HAL::millis(); if (is_equal(packet.param5,2.0f)) { + // reject any time we've done a calibration recently + if ((now - last_accel_cal_ms) < 5000) { + return MAV_RESULT_TEMPORARILY_REJECTED; + } + if (!calibrate_gyros()) { + last_accel_cal_ms = AP_HAL::millis(); return MAV_RESULT_FAILED; } Vector3f trim_rad = AP::ahrs().get_trim(); if (!AP::ins().calibrate_trim(trim_rad)) { + last_accel_cal_ms = AP_HAL::millis(); return MAV_RESULT_FAILED; } // reset ahrs's trim to suggested values from calibration routine AP::ahrs().set_trim(trim_rad); + last_accel_cal_ms = AP_HAL::millis(); return MAV_RESULT_ACCEPTED; } if (is_equal(packet.param5,4.0f)) { + if ((now - last_accel_cal_ms) < 5000) { + return MAV_RESULT_TEMPORARILY_REJECTED; + } + // simple accel calibration + last_accel_cal_ms = AP_HAL::millis(); return AP::ins().simple_accel_cal(); } @@ -4044,7 +4235,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_preflight_can(const mavlink_command_long_ } case AP_CANManager::Driver_Type_CANTester: { // To be replaced with macro saying if KDECAN library is included -#if (APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_ArduSub)) && (HAL_MAX_CAN_PROTOCOL_DRIVERS > 1 && !HAL_MINIMIZE_FEATURES) +#if (APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_ArduSub)) && (HAL_MAX_CAN_PROTOCOL_DRIVERS > 1 && !HAL_MINIMIZE_FEATURES && HAL_ENABLE_CANTESTER) CANTester *cantester = CANTester::get_cantester(i); if (cantester != nullptr) { @@ -4236,18 +4427,16 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_sprayer(const mavlink_command_long_t & } #endif +#if HAL_INS_ACCELCAL_ENABLED MAV_RESULT GCS_MAVLINK::handle_command_accelcal_vehicle_pos(const mavlink_command_long_t &packet) { -#if HAL_INS_ENABLED if (AP::ins().get_acal() == nullptr || !AP::ins().get_acal()->gcs_vehicle_position(packet.param1)) { return MAV_RESULT_FAILED; } return MAV_RESULT_ACCEPTED; -#else - return MAV_RESULT_UNSUPPORTED; -#endif } +#endif // HAL_INS_ACCELCAL_ENABLED MAV_RESULT GCS_MAVLINK::handle_command_mount(const mavlink_command_long_t &packet) { @@ -4322,9 +4511,11 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t switch (packet.command) { +#if HAL_INS_ACCELCAL_ENABLED case MAV_CMD_ACCELCAL_VEHICLE_POS: result = handle_command_accelcal_vehicle_pos(packet); break; +#endif case MAV_CMD_DO_SET_MODE: result = handle_command_do_set_mode(packet); @@ -4346,6 +4537,12 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t result = handle_preflight_reboot(packet); break; +#if HAL_HIGH_LATENCY2_ENABLED + case MAV_CMD_CONTROL_HIGH_LATENCY: + result = handle_control_high_latency(packet); + break; +#endif // HAL_HIGH_LATENCY2_ENABLED + case MAV_CMD_DO_START_MAG_CAL: case MAV_CMD_DO_ACCEPT_MAG_CAL: case MAV_CMD_DO_CANCEL_MAG_CAL: { @@ -4375,6 +4572,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t case MAV_CMD_DO_MOUNT_CONFIGURE: case MAV_CMD_DO_MOUNT_CONTROL: + case MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW: result = handle_command_mount(packet); break; @@ -4894,7 +5092,7 @@ void GCS_MAVLINK::send_sys_status() control_sensors_health, static_cast(AP::scheduler().load_average() * 1000), #if !defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_BATTERY) - battery.voltage() * 1000, // mV + battery.gcs_voltage() * 1000, // mV battery_current, // in 10mA units battery_remaining, // in % #else @@ -4986,27 +5184,16 @@ void GCS_MAVLINK::send_global_position_int() ahrs.yaw_sensor); // compass heading in 1/100 degree } -void GCS_MAVLINK::send_gimbal_report() const -{ #if HAL_MOUNT_ENABLED - AP_Mount *mount = AP::mount(); - if (mount == nullptr) { - return; - } - mount->send_gimbal_report(chan); -#endif -} - -void GCS_MAVLINK::send_mount_status() const +void GCS_MAVLINK::send_gimbal_device_attitude_status() const { -#if HAL_MOUNT_ENABLED AP_Mount *mount = AP::mount(); if (mount == nullptr) { return; } - mount->send_mount_status(chan); -#endif + mount->send_gimbal_device_attitude_status(chan); } +#endif void GCS_MAVLINK::send_set_position_target_global_int(uint8_t target_system, uint8_t target_component, const Location& loc) { @@ -5036,20 +5223,20 @@ void GCS_MAVLINK::send_set_position_target_global_int(uint8_t target_system, uin 0,0); // yaw, yaw_rate } +#if HAL_GENERATOR_ENABLED void GCS_MAVLINK::send_generator_status() const { -#if HAL_GENERATOR_ENABLED AP_Generator *generator = AP::generator(); if (generator == nullptr) { return; } generator->send_generator_status(*this); -#endif } +#endif +#if APM_BUILD_TYPE(APM_BUILD_Rover) void GCS_MAVLINK::send_water_depth() const { -#if APM_BUILD_TYPE(APM_BUILD_Rover) if (!HAVE_PAYLOAD_SPACE(chan, WATER_DEPTH)) { return; } @@ -5095,17 +5282,63 @@ void GCS_MAVLINK::send_water_depth() const temp_C); // temperature in degC } -#endif } +#endif +#if HAL_ADSB_ENABLED void GCS_MAVLINK::send_uavionix_adsb_out_status() const { -#if HAL_ADSB_ENABLED AP_ADSB *adsb = AP::ADSB(); if (adsb != nullptr) { adsb->send_adsb_out_status(chan); } +} #endif + +void GCS_MAVLINK::send_autopilot_state_for_gimbal_device() const +{ + // get attitude + const AP_AHRS &ahrs = AP::ahrs(); + Quaternion quat; + if (!ahrs.get_quaternion(quat)) { + return; + } + const float repr_offseq_q[] = {quat.q1, quat.q2, quat.q3, quat.q4}; + + // get velocity + Vector3f vel; + if (!ahrs.get_velocity_NED(vel)) { + vel.zero(); + } + + // get vehicle earth-frame rotation rate targets + Vector3f rate_ef_targets; + const AP_Vehicle *vehicle = AP::vehicle(); + if (vehicle != nullptr) { + vehicle->get_rate_ef_targets(rate_ef_targets); + } + + // get estimator flags + uint16_t est_status_flags = 0; + nav_filter_status nav_filt_status; + if (ahrs.get_filter_status(nav_filt_status)) { + est_status_flags = (uint16_t)(nav_filt_status.value & 0xFFFF); + } + + mavlink_msg_autopilot_state_for_gimbal_device_send( + chan, + mavlink_system.sysid, // target system (this autopilot's gimbal) + 0, // target component (anything) + AP_HAL::micros(), // time boot us + repr_offseq_q, // attitude as quaternion + 0, // attitude estimated delay in micros + vel.x, // x speed in NED (m/s) + vel.y, // y speed in NED (m/s) + vel.z, // z speed in NED (m/s) + 0, // velocity estimated delay in micros + rate_ef_targets.z, // feed forward angular velocity z + est_status_flags, // estimator status + 0); // landed_state (see MAV_LANDED_STATE) } void GCS_MAVLINK::send_received_message_deprecation_warning(const char * message) @@ -5147,11 +5380,6 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) queued_param_send(); break; - case MSG_GIMBAL_REPORT: - CHECK_PAYLOAD_SIZE(GIMBAL_REPORT); - send_gimbal_report(); - break; - case MSG_HEARTBEAT: CHECK_PAYLOAD_SIZE(HEARTBEAT); last_heartbeat_time = AP_HAL::millis(); @@ -5211,7 +5439,7 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) case MSG_EKF_STATUS_REPORT: CHECK_PAYLOAD_SIZE(EKF_STATUS_REPORT); - AP::ahrs().send_ekf_status_report(chan); + AP::ahrs().send_ekf_status_report(*this); break; case MSG_MEMINFO: @@ -5263,18 +5491,27 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) #endif break; case MSG_GPS2_RTK: +#if GPS_MAX_RECEIVERS > 1 CHECK_PAYLOAD_SIZE(GPS2_RTK); AP::gps().send_mavlink_gps_rtk(chan, 1); +#endif break; - case MSG_LOCAL_POSITION: CHECK_PAYLOAD_SIZE(LOCAL_POSITION_NED); send_local_position(); break; - case MSG_MOUNT_STATUS: - CHECK_PAYLOAD_SIZE(MOUNT_STATUS); - send_mount_status(); + case MSG_GIMBAL_DEVICE_ATTITUDE_STATUS: +#if HAL_MOUNT_ENABLED + CHECK_PAYLOAD_SIZE(GIMBAL_DEVICE_ATTITUDE_STATUS); + send_gimbal_device_attitude_status(); +#endif + break; + case MSG_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE: +#if HAL_MOUNT_ENABLED + CHECK_PAYLOAD_SIZE(AUTOPILOT_STATE_FOR_GIMBAL_DEVICE); + send_autopilot_state_for_gimbal_device(); +#endif break; case MSG_OPTICAL_FLOW: @@ -5310,7 +5547,7 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) send_mcu_status(); #endif break; - + case MSG_RC_CHANNELS: CHECK_PAYLOAD_SIZE(RC_CHANNELS); send_rc_channels(); @@ -5362,13 +5599,17 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) break; case MSG_SIMSTATE: +#if AP_SIM_ENABLED CHECK_PAYLOAD_SIZE(SIMSTATE); send_simstate(); +#endif break; case MSG_SIM_STATE: +#if AP_SIM_ENABLED CHECK_PAYLOAD_SIZE(SIM_STATE); send_sim_state(); +#endif break; case MSG_SYS_STATUS: @@ -5412,8 +5653,10 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) break; case MSG_GENERATOR_STATUS: +#if HAL_GENERATOR_ENABLED CHECK_PAYLOAD_SIZE(GENERATOR_STATUS); send_generator_status(); +#endif break; case MSG_AUTOPILOT_VERSION: @@ -5444,9 +5687,12 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) break; case MSG_WATER_DEPTH: +#if APM_BUILD_TYPE(APM_BUILD_Rover) CHECK_PAYLOAD_SIZE(WATER_DEPTH); send_water_depth(); +#endif break; + case MSG_HIGH_LATENCY2: #if HAL_HIGH_LATENCY2_ENABLED CHECK_PAYLOAD_SIZE(HIGH_LATENCY2); @@ -5454,10 +5700,22 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) #endif // HAL_HIGH_LATENCY2_ENABLED break; + case MSG_AIS_VESSEL: { +#if AP_AIS_ENABLED + AP_AIS *ais = AP_AIS::get_singleton(); + if (ais) { + ais->send(chan); + } +#endif + break; + } + case MSG_UAVIONIX_ADSB_OUT_STATUS: +#if HAL_ADSB_ENABLED CHECK_PAYLOAD_SIZE(UAVIONIX_ADSB_OUT_STATUS); send_uavionix_adsb_out_status(); +#endif break; default: @@ -5687,7 +5945,15 @@ void GCS_MAVLINK::initialise_message_intervals_from_streamrates() for (uint8_t i=0; all_stream_entries[i].ap_message_ids != nullptr; i++) { initialise_message_intervals_for_stream(all_stream_entries[i].stream_id); } +#if HAL_HIGH_LATENCY2_ENABLED + if (!is_high_latency_link) { + set_mavlink_message_id_interval(MAVLINK_MSG_ID_HEARTBEAT, 1000); + } else { + set_mavlink_message_id_interval(MAVLINK_MSG_ID_HIGH_LATENCY2, 5000); + } +#else set_mavlink_message_id_interval(MAVLINK_MSG_ID_HEARTBEAT, 1000); +#endif } bool GCS_MAVLINK::get_default_interval_for_ap_message(const ap_message id, uint16_t &interval) const @@ -5698,6 +5964,12 @@ bool GCS_MAVLINK::get_default_interval_for_ap_message(const ap_message id, uint1 return true; } + if (id == MSG_HIGH_LATENCY2) { + // handle HL2 requests as a special case because HL2 is not "streamed" + interval = 5000; + return true; + } + #if HAL_MAVLINK_INTERVALS_FROM_FILES_ENABLED // a user can specify default rates in files, which are read close // to vehicle startup @@ -5786,6 +6058,11 @@ bool GCS_MAVLINK::accept_packet(const mavlink_status_t &status, */ void GCS::update_passthru(void) { +#if APM_BUILD_TYPE(APM_BUILD_UNKNOWN) + // examples don't have AP::serialmanager + return; +#endif + WITH_SEMAPHORE(_passthru.sem); uint32_t now = AP_HAL::millis(); uint32_t baud1, baud2; @@ -5932,8 +6209,8 @@ uint64_t GCS_MAVLINK::capabilities() const uint64_t ret = MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT | MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION; - AP_SerialManager::SerialProtocol mavlink_protocol = AP::serialmanager().get_mavlink_protocol(chan); - if (mavlink_protocol == AP_SerialManager::SerialProtocol_MAVLink2) { + const auto mavlink_protocol = uartstate->get_protocol(); + if (mavlink_protocol == AP_SerialManager::SerialProtocol_MAVLink2 || mavlink_protocol == AP_SerialManager::SerialProtocol_MAVLinkHL) { ret |= MAV_PROTOCOL_CAPABILITY_MAVLINK2; } @@ -5949,9 +6226,11 @@ uint64_t GCS_MAVLINK::capabilities() const } #endif +#if AP_FENCE_ENABLED if (AP::fence()) { ret |= MAV_PROTOCOL_CAPABILITY_MISSION_FENCE; } +#endif if (!AP_BoardConfig::ftp_disabled()){ //if ftp disable board option is not set ret |= MAV_PROTOCOL_CAPABILITY_FTP; @@ -6095,4 +6374,29 @@ int8_t GCS_MAVLINK::high_latency_air_temperature() const return INT8_MIN; } + +/* + handle a MAV_CMD_CONTROL_HIGH_LATENCY command + + Enable or disable any marked (via SERIALn_PROTOCOL) high latency connections + */ +MAV_RESULT GCS_MAVLINK::handle_control_high_latency(const mavlink_command_long_t &packet) +{ + // high latency mode is enabled if param1=1 or disabled if param1=0 + if (is_equal(packet.param1, 0.0f)) { + gcs().enable_high_latency_connections(false); + } else if (is_equal(packet.param1, 1.0f)) { + gcs().enable_high_latency_connections(true); + } else { + return MAV_RESULT_FAILED; + } + + // send to all other mavlink components with same sysid + mavlink_command_long_t hl_msg{}; + hl_msg.command = MAV_CMD_CONTROL_HIGH_LATENCY; + hl_msg.param1 = packet.param1; + GCS_MAVLINK::send_to_components(MAVLINK_MSG_ID_COMMAND_LONG, (char*)&hl_msg, sizeof(hl_msg)); + + return MAV_RESULT_ACCEPTED; +} #endif // HAL_HIGH_LATENCY2_ENABLED diff --git a/libraries/GCS_MAVLink/GCS_DeviceOp.cpp b/libraries/GCS_MAVLink/GCS_DeviceOp.cpp index 2d93f687987..b7418ad78c6 100644 --- a/libraries/GCS_MAVLink/GCS_DeviceOp.cpp +++ b/libraries/GCS_MAVLink/GCS_DeviceOp.cpp @@ -48,6 +48,10 @@ void GCS_MAVLINK::handle_device_op_read(const mavlink_message_t &msg) retcode = 2; goto fail; } + if (packet.count > sizeof(data)) { + retcode = 5; + goto fail; + } if (!dev->get_semaphore()->take(10)) { retcode = 3; goto fail; diff --git a/libraries/GCS_MAVLink/GCS_Dummy.cpp b/libraries/GCS_MAVLink/GCS_Dummy.cpp index 09360e538cd..135318e3137 100644 --- a/libraries/GCS_MAVLink/GCS_Dummy.cpp +++ b/libraries/GCS_MAVLink/GCS_Dummy.cpp @@ -13,9 +13,9 @@ const struct GCS_MAVLINK::stream_entries GCS_MAVLINK::all_stream_entries[] {}; void GCS_Dummy::send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list, uint8_t dest_bitmask) { #if !APM_BUILD_TYPE(APM_BUILD_Replay) - hal.console->printf("TOGCS: "); + DEV_PRINTF("TOGCS: "); hal.console->vprintf(fmt, arg_list); - hal.console->printf("\n"); + DEV_PRINTF("\n"); #else ::printf("TOGCS: "); ::vprintf(fmt, arg_list); diff --git a/libraries/GCS_MAVLink/GCS_FTP.cpp b/libraries/GCS_MAVLink/GCS_FTP.cpp index 3c3b7506edb..e86fafdd84d 100644 --- a/libraries/GCS_MAVLink/GCS_FTP.cpp +++ b/libraries/GCS_MAVLink/GCS_FTP.cpp @@ -44,11 +44,7 @@ bool GCS_MAVLINK::ftp_init(void) { } ftp.requests = new ObjectBuffer(5); - if (ftp.requests == nullptr) { - goto failed; - } - ftp.replies = new ObjectBuffer(30); - if (ftp.replies == nullptr) { + if (ftp.requests == nullptr || ftp.requests->get_size() == 0) { goto failed; } @@ -62,8 +58,6 @@ bool GCS_MAVLINK::ftp_init(void) { failed: delete ftp.requests; ftp.requests = nullptr; - delete ftp.replies; - ftp.replies = nullptr; gcs().send_text(MAV_SEVERITY_WARNING, "failed to initialize MAVFTP"); return false; @@ -96,50 +90,38 @@ void GCS_MAVLINK::handle_file_transfer_protocol(const mavlink_message_t &msg) { } } -void GCS_MAVLINK::send_ftp_replies(void) +bool GCS_MAVLINK::send_ftp_reply(const pending_ftp &reply) { /* provide same banner we would give with old param download */ - if (ftp.need_banner_send_mask & (1U<is_empty()) { - return; + WITH_SEMAPHORE(comm_chan_lock(reply.chan)); + if (!HAVE_PAYLOAD_SPACE(chan, FILE_TRANSFER_PROTOCOL)) { + return false; } - - for (uint8_t i = 0; i < 20; i++) { - if (!HAVE_PAYLOAD_SPACE(chan, FILE_TRANSFER_PROTOCOL)) { - return; - } - if ((i > 0) && comm_get_txspace(chan) < (2 * (packet_overhead() + MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN))) { - // if this isn't the first packet we have to leave deadspace for the next message - return; - } - - struct pending_ftp reply; - uint8_t payload[251] = {}; - if (ftp.replies->peek(reply) && (reply.chan == chan)) { - put_le16_ptr(payload, reply.seq_number); - payload[2] = reply.session; - payload[3] = static_cast(reply.opcode); - payload[4] = reply.size; - payload[5] = static_cast(reply.req_opcode); - payload[6] = reply.burst_complete ? 1 : 0; - put_le32_ptr(&payload[8], reply.offset); - memcpy(&payload[12], reply.data, sizeof(reply.data)); - mavlink_msg_file_transfer_protocol_send( - reply.chan, - 0, reply.sysid, reply.compid, - payload); - ftp.replies->pop(); - ftp.last_send_ms = AP_HAL::millis(); - } else { - return; - } + uint8_t payload[251] = {}; + put_le16_ptr(payload, reply.seq_number); + payload[2] = reply.session; + payload[3] = static_cast(reply.opcode); + payload[4] = reply.size; + payload[5] = static_cast(reply.req_opcode); + payload[6] = reply.burst_complete ? 1 : 0; + put_le32_ptr(&payload[8], reply.offset); + memcpy(&payload[12], reply.data, sizeof(reply.data)); + mavlink_msg_file_transfer_protocol_send( + reply.chan, + 0, reply.sysid, reply.compid, + payload); + if (reply.req_opcode == FTP_OP::TerminateSession) { + ftp.last_send_ms = 0; + } else { + ftp.last_send_ms = AP_HAL::millis(); } + return true; } void GCS_MAVLINK::ftp_error(struct pending_ftp &response, FTP_ERROR error) { @@ -168,7 +150,7 @@ void GCS_MAVLINK::ftp_error(struct pending_ftp &response, FTP_ERROR error) { // send our response back out to the system void GCS_MAVLINK::ftp_push_replies(pending_ftp &reply) { - while (!ftp.replies->push(reply)) { // we must fit the response, keep shoving it in + while (!send_ftp_reply(reply)) { hal.scheduler->delay(2); } } @@ -181,7 +163,7 @@ void GCS_MAVLINK::ftp_worker(void) { while (true) { bool skip_push_reply = false; - while (!ftp.requests->pop(request)) { + while (ftp.requests == nullptr || !ftp.requests->pop(request)) { // nothing to handle, delay ourselves a bit then check again. Ideally we'd use conditional waits here hal.scheduler->delay(2); } @@ -505,7 +487,27 @@ void GCS_MAVLINK::ftp_worker(void) { break; } - const uint32_t transfer_size = 100; + /* + calculate a burst delay so that FTP burst + transfer doesn't use more than 1/3 of + available bandwidth on links that don't have + flow control. This reduces the chance of + lost packets a lot, which results in overall + faster transfers + */ + uint32_t burst_delay_ms = 0; + if (valid_channel(request.chan)) { + auto *port = mavlink_comm_port[request.chan]; + if (port != nullptr && port->get_flow_control() != AP_HAL::UARTDriver::FLOW_CONTROL_ENABLE) { + const uint32_t bw = port->bw_in_kilobytes_per_second(); + const uint16_t pkt_size = PAYLOAD_SIZE(request.chan, FILE_TRANSFER_PROTOCOL) - (sizeof(reply.data) - max_read); + burst_delay_ms = 3 * pkt_size / bw; + } + } + + + // this transfer size is enough for a full parameter file with max parameters + const uint32_t transfer_size = 500; for (uint32_t i = 0; (i < transfer_size); i++) { // fill the buffer const ssize_t read_bytes = AP::FS().read(ftp.fd, reply.data, MIN(sizeof(reply.data), max_read)); @@ -538,6 +540,8 @@ void GCS_MAVLINK::ftp_worker(void) { // prep the reply to be used again reply.seq_number++; + + hal.scheduler->delay(burst_delay_ms); } if (reply.opcode != FTP_OP::Nack) { @@ -567,7 +571,7 @@ void GCS_MAVLINK::ftp_worker(void) { // calculates how much string length is needed to fit this in a list response int GCS_MAVLINK::gen_dir_entry(char *dest, size_t space, const char *path, const struct dirent * entry) { - const bool is_file = entry->d_type == DT_REG; + const bool is_file = entry->d_type == DT_REG || entry->d_type == DT_LNK; if (space < 3) { return -1; @@ -579,7 +583,12 @@ int GCS_MAVLINK::gen_dir_entry(char *dest, size_t space, const char *path, const } if (is_file) { - const size_t full_path_len = strlen(path) + strnlen(entry->d_name, 256); // FIXME: Really should do better then just hardcoding 256 +#ifdef MAX_NAME_LEN + const uint8_t max_name_len = MIN(unsigned(MAX_NAME_LEN), 255U); +#else + const uint8_t max_name_len = 255U; +#endif + const size_t full_path_len = strlen(path) + strnlen(entry->d_name, max_name_len); char full_path[full_path_len + 2]; hal.util->snprintf(full_path, sizeof(full_path), "%s/%s", path, entry->d_name); struct stat st; diff --git a/libraries/GCS_MAVLink/GCS_Fence.cpp b/libraries/GCS_MAVLink/GCS_Fence.cpp index b6bffdad07a..c99b99ece4f 100644 --- a/libraries/GCS_MAVLink/GCS_Fence.cpp +++ b/libraries/GCS_MAVLink/GCS_Fence.cpp @@ -6,6 +6,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_fence_enable(const mavlink_command_long_t &packet) { +#if AP_FENCE_ENABLED AC_Fence *fence = AP::fence(); if (fence == nullptr) { return MAV_RESULT_UNSUPPORTED; @@ -29,10 +30,14 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_fence_enable(const mavlink_command_lon default: return MAV_RESULT_FAILED; } +#else + return MAV_RESULT_UNSUPPORTED; +#endif // AP_FENCE_ENABLED } void GCS_MAVLINK::handle_fence_message(const mavlink_message_t &msg) { +#if AP_FENCE_ENABLED AC_Fence *fence = AP::fence(); if (fence == nullptr) { return; @@ -49,11 +54,13 @@ void GCS_MAVLINK::handle_fence_message(const mavlink_message_t &msg) #endif break; } +#endif // AP_FENCE_ENABLED } // fence_send_mavlink_status - send fence status to ground station void GCS_MAVLINK::send_fence_status() const { +#if AP_FENCE_ENABLED const AC_Fence *fence = AP::fence(); if (fence == nullptr) { return; @@ -95,4 +102,5 @@ void GCS_MAVLINK::send_fence_status() const mavlink_breach_type, fence->get_breach_time(), breach_mitigation); +#endif // AP_FENCE_ENABLED } diff --git a/libraries/GCS_MAVLink/GCS_MAVLink.cpp b/libraries/GCS_MAVLink/GCS_MAVLink.cpp index 0005207df09..23a6f77cbe4 100644 --- a/libraries/GCS_MAVLink/GCS_MAVLink.cpp +++ b/libraries/GCS_MAVLink/GCS_MAVLink.cpp @@ -48,6 +48,14 @@ mavlink_system_t mavlink_system = {7,1}; // routing table MAVLink_routing GCS_MAVLINK::routing; +GCS_MAVLINK *GCS_MAVLINK::find_by_mavtype_and_compid(uint8_t mav_type, uint8_t compid, uint8_t &sysid) { + mavlink_channel_t channel; + if (!routing.find_by_mavtype_and_compid(mav_type, compid, sysid, channel)) { + return nullptr; + } + return gcs().chan(channel); +} + // set a channel as private. Private channels get sent heartbeats, but // don't get broadcast packets or forwarded packets void GCS_MAVLINK::set_channel_private(mavlink_channel_t _chan) @@ -94,6 +102,13 @@ void comm_send_buffer(mavlink_channel_t chan, const uint8_t *buf, uint8_t len) if (!valid_channel(chan) || mavlink_comm_port[chan] == nullptr || chan_discard[chan]) { return; } +#if HAL_HIGH_LATENCY2_ENABLED + // if it's a disabled high latency channel, don't send + GCS_MAVLINK *link = gcs().chan(chan); + if (!link->should_send()) { + return; + } +#endif if (gcs_alternative_active[chan]) { // an alternative protocol is active return; @@ -120,7 +135,7 @@ void comm_send_lock(mavlink_channel_t chan_m, uint16_t size) chan_locks[chan].take_blocking(); if (mavlink_comm_port[chan]->txspace() < size) { chan_discard[chan] = true; - gcs_out_of_space_to_send_count(chan_m); + gcs_out_of_space_to_send(chan_m); } } diff --git a/libraries/GCS_MAVLink/GCS_Signing.cpp b/libraries/GCS_MAVLink/GCS_Signing.cpp index f078aca8a23..93aaef90dbc 100644 --- a/libraries/GCS_MAVLink/GCS_Signing.cpp +++ b/libraries/GCS_MAVLink/GCS_Signing.cpp @@ -134,7 +134,7 @@ void GCS_MAVLINK::load_signing_key(void) } mavlink_status_t *status = mavlink_get_channel_status(chan); if (status == nullptr) { - hal.console->printf("Failed to load signing key - no status"); + DEV_PRINTF("Failed to load signing key - no status"); return; } memcpy(signing.secret_key, key.secret_key, 32); diff --git a/libraries/GCS_MAVLink/MAVLink_routing.cpp b/libraries/GCS_MAVLink/MAVLink_routing.cpp index 54d922f81e8..c2679c20247 100644 --- a/libraries/GCS_MAVLink/MAVLink_routing.cpp +++ b/libraries/GCS_MAVLink/MAVLink_routing.cpp @@ -97,12 +97,8 @@ bool MAVLink_routing::check_and_forward(mavlink_channel_t in_channel, const mavl return true; } - // don't ever forward data from a private channel - if ((GCS_MAVLINK::is_private(in_channel))) { - return true; - } - - // learn new routes + // learn new routes including private channels + // so that find_mav_type works for all channels learn_route(in_channel, msg); if (msg.msgid == MAVLINK_MSG_ID_RADIO || @@ -110,10 +106,14 @@ bool MAVLink_routing::check_and_forward(mavlink_channel_t in_channel, const mavl // don't forward RADIO packets return true; } - + + const bool from_private_channel = GCS_MAVLINK::is_private(in_channel); + if (msg.msgid == MAVLINK_MSG_ID_HEARTBEAT) { // heartbeat needs special handling - handle_heartbeat(in_channel, msg); + if (!from_private_channel) { + handle_heartbeat(in_channel, msg); + } return true; } @@ -134,6 +134,11 @@ bool MAVLink_routing::check_and_forward(mavlink_channel_t in_channel, const mavl (target_component == mavlink_system.compid)); bool process_locally = match_system && match_component; + // don't ever forward data from a private channel + if (from_private_channel) { + return process_locally; + } + if (process_locally && !broadcast_system && !broadcast_component) { // nothing more to do - it can only be for us return true; @@ -261,6 +266,22 @@ bool MAVLink_routing::find_by_mavtype(uint8_t mavtype, uint8_t &sysid, uint8_t & return false; } +/* + search for the first vehicle or component in the routing table with given mav_type and component id and retrieve its sysid and channel + returns true if a match is found + */ +bool MAVLink_routing::find_by_mavtype_and_compid(uint8_t mavtype, uint8_t compid, uint8_t &sysid, mavlink_channel_t &channel) const +{ + for (uint8_t i=0; i #include #include "GCS_MAVLink.h" @@ -44,6 +43,12 @@ class MAVLink_routing */ bool find_by_mavtype(uint8_t mavtype, uint8_t &sysid, uint8_t &compid, mavlink_channel_t &channel); + /* + search for the first vehicle or component in the routing table with given mav_type and component id and retrieve its sysid and channel + returns true if a match is found + */ + bool find_by_mavtype_and_compid(uint8_t mavtype, uint8_t compid, uint8_t &sysid, mavlink_channel_t &channel) const; + private: // a simple linear routing table. We don't expect to have a lot of // routes, so a scalable structure isn't worthwhile yet. diff --git a/libraries/GCS_MAVLink/MissionItemProtocol.cpp b/libraries/GCS_MAVLink/MissionItemProtocol.cpp index 5792adc9f16..b90cc3b1661 100644 --- a/libraries/GCS_MAVLink/MissionItemProtocol.cpp +++ b/libraries/GCS_MAVLink/MissionItemProtocol.cpp @@ -111,6 +111,7 @@ void MissionItemProtocol::handle_mission_request_list( // reply with number of commands in the mission. The GCS will // then request each command separately + CHECK_PAYLOAD_SIZE2_VOID(_link.get_chan(), MISSION_COUNT); mavlink_msg_mission_count_send(_link.get_chan(), msg.sysid, msg.compid, @@ -148,6 +149,7 @@ void MissionItemProtocol::handle_mission_request_int(const GCS_MAVLINK &_link, return; } + CHECK_PAYLOAD_SIZE2_VOID(_link.get_chan(), MISSION_ITEM_INT); _link.send_message(MAVLINK_MSG_ID_MISSION_ITEM_INT, (const char*)&ret_packet); } @@ -186,6 +188,7 @@ void MissionItemProtocol::handle_mission_request(const GCS_MAVLINK &_link, return; } + CHECK_PAYLOAD_SIZE2_VOID(_link.get_chan(), MISSION_ITEM_INT); _link.send_message(MAVLINK_MSG_ID_MISSION_ITEM, (const char*)&ret_packet); } @@ -293,6 +296,7 @@ void MissionItemProtocol::send_mission_ack(const GCS_MAVLINK &_link, const mavlink_message_t &msg, MAV_MISSION_RESULT result) const { + CHECK_PAYLOAD_SIZE2_VOID(_link.get_chan(), MISSION_ACK); mavlink_msg_mission_ack_send(_link.get_chan(), msg.sysid, msg.compid, @@ -316,6 +320,7 @@ void MissionItemProtocol::queued_request_send() INTERNAL_ERROR(AP_InternalError::error_t::gcs_bad_missionprotocol_link); return; } + CHECK_PAYLOAD_SIZE2_VOID(link->get_chan(), MISSION_REQUEST); mavlink_msg_mission_request_send( link->get_chan(), dest_sysid, @@ -340,11 +345,14 @@ void MissionItemProtocol::update() if (tnow - timelast_receive_ms > upload_timeout_ms) { receiving = false; timeout(); - mavlink_msg_mission_ack_send(link->get_chan(), - dest_sysid, - dest_compid, - MAV_MISSION_OPERATION_CANCELLED, - mission_type()); + const mavlink_channel_t chan = link->get_chan(); + if (HAVE_PAYLOAD_SPACE(chan, MISSION_ACK)) { + mavlink_msg_mission_ack_send(chan, + dest_sysid, + dest_compid, + MAV_MISSION_OPERATION_CANCELLED, + mission_type()); + } link = nullptr; free_upload_resources(); return; diff --git a/libraries/GCS_MAVLink/MissionItemProtocol_Fence.cpp b/libraries/GCS_MAVLink/MissionItemProtocol_Fence.cpp index ea72bdc3bfc..5c308ea5dbf 100644 --- a/libraries/GCS_MAVLink/MissionItemProtocol_Fence.cpp +++ b/libraries/GCS_MAVLink/MissionItemProtocol_Fence.cpp @@ -1,6 +1,10 @@ #include "MissionItemProtocol_Fence.h" #include +#include +#include + +#if AP_FENCE_ENABLED /* public function to format mission item as mavlink_mission_item_int_t @@ -226,7 +230,7 @@ MAV_MISSION_RESULT MissionItemProtocol_Fence::allocate_receive_resources(const u MAV_MISSION_RESULT MissionItemProtocol_Fence::allocate_update_resources() { const uint16_t _item_count = _fence.polyfence().num_stored_items(); - _updated_mask = new uint8_t[(_item_count+7/8)]; + _updated_mask = new uint8_t[(_item_count+7)/8]; if (_updated_mask == nullptr) { return MAV_MISSION_ERROR; } @@ -239,3 +243,5 @@ MAV_MISSION_RESULT MissionItemProtocol_Fence::allocate_update_resources() _new_items_count = _item_count; return MAV_MISSION_ACCEPTED; } + +#endif // AP_FENCE_ENABLED diff --git a/libraries/GCS_MAVLink/MissionItemProtocol_Waypoints.cpp b/libraries/GCS_MAVLink/MissionItemProtocol_Waypoints.cpp index e707a1e2863..6878ae92bb0 100644 --- a/libraries/GCS_MAVLink/MissionItemProtocol_Waypoints.cpp +++ b/libraries/GCS_MAVLink/MissionItemProtocol_Waypoints.cpp @@ -65,11 +65,14 @@ MAV_MISSION_RESULT MissionItemProtocol_Waypoints::get_item(const GCS_MAVLINK &_l if (packet.seq != 0 && // always allow HOME to be read packet.seq >= mission.num_commands()) { // try to educate the GCS on the actual size of the mission: - mavlink_msg_mission_count_send(_link.get_chan(), - msg.sysid, - msg.compid, - mission.num_commands(), - MAV_MISSION_TYPE_MISSION); + const mavlink_channel_t chan = _link.get_chan(); + if (HAVE_PAYLOAD_SPACE(chan, MISSION_COUNT)) { + mavlink_msg_mission_count_send(chan, + msg.sysid, + msg.compid, + mission.num_commands(), + MAV_MISSION_TYPE_MISSION); + } return MAV_MISSION_ERROR; } diff --git a/libraries/GCS_MAVLink/ap_message.h b/libraries/GCS_MAVLink/ap_message.h index 7e314fe69ed..532c476273a 100644 --- a/libraries/GCS_MAVLink/ap_message.h +++ b/libraries/GCS_MAVLink/ap_message.h @@ -49,9 +49,8 @@ enum ap_message : uint8_t { MSG_TERRAIN, MSG_BATTERY2, MSG_CAMERA_FEEDBACK, - MSG_MOUNT_STATUS, + MSG_GIMBAL_DEVICE_ATTITUDE_STATUS, MSG_OPTICAL_FLOW, - MSG_GIMBAL_REPORT, MSG_MAG_CAL_PROGRESS, MSG_MAG_CAL_REPORT, MSG_EKF_STATUS_REPORT, @@ -82,5 +81,7 @@ enum ap_message : uint8_t { MSG_MCU_STATUS, MSG_UAVIONIX_ADSB_OUT_STATUS, MSG_ATTITUDE_TARGET, + MSG_HYGROMETER, + MSG_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE, MSG_LAST // MSG_LAST must be the last entry in this enum }; diff --git a/libraries/PID/PID.cpp b/libraries/PID/PID.cpp index 141afcd05f8..71079cdbe85 100644 --- a/libraries/PID/PID.cpp +++ b/libraries/PID/PID.cpp @@ -52,7 +52,7 @@ float PID::get_pid(float error, float scaler) } _last_t = tnow; - delta_time = (float)dt / 1000.0f; + delta_time = (float)dt * 0.001f; // Compute proportional component _pid_info.P = error * _kp; diff --git a/libraries/PID/PID.h b/libraries/PID/PID.h index 38b6f404454..0cb13b1257c 100644 --- a/libraries/PID/PID.h +++ b/libraries/PID/PID.h @@ -4,7 +4,7 @@ #include #include -#include +#include // for AP_PIDInfo #include #include @@ -19,10 +19,10 @@ class PID { const int16_t & initial_imax = 0) { AP_Param::setup_object_defaults(this, var_info); - _kp = initial_p; - _ki = initial_i; - _kd = initial_d; - _imax = initial_imax; + _kp.set_and_default(initial_p); + _ki.set_and_default(initial_i); + _kd.set_and_default(initial_d); + _imax.set_and_default(initial_imax); // set _last_derivative as invalid when we startup _last_derivative = NAN; @@ -63,7 +63,7 @@ class PID { const float i, const float d, const int16_t imaxval) { - _kp = p; _ki = i; _kd = d; _imax = imaxval; + _kp.set(p); _ki.set(i); _kd.set(d); _imax.set(imaxval); } float kP() const { @@ -98,7 +98,7 @@ class PID { static const struct AP_Param::GroupInfo var_info[]; - const AP_Logger::PID_Info& get_pid_info(void) const { return _pid_info; } + const AP_PIDInfo& get_pid_info(void) const { return _pid_info; } private: AP_Float _kp; @@ -113,7 +113,7 @@ class PID { float _get_pid(float error, uint16_t dt, float scaler); - AP_Logger::PID_Info _pid_info {}; + AP_PIDInfo _pid_info {}; /// Low pass filter cut frequency for derivative calculation. /// diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index 5b8b471a22d..f5bdd6254d0 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -36,6 +36,7 @@ extern const AP_HAL::HAL& hal; #include #include #include +#include #include #include #include @@ -97,10 +98,10 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = { // @Param: OPTION // @DisplayName: RC input option // @Description: Function assigned to this RC channel - // @Values{Copter}: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 37:Throw, 38:ADSB Avoidance En, 39:PrecLoiter, 40:Proximity Avoidance, 41:ArmDisarm (4.1 and lower), 42:SmartRTL, 43:InvertedFlight, 46:RC Override Enable, 47:User Function 1, 48:User Function 2, 49:User Function 3, 52:Acro, 55:Guided, 56:Loiter, 57:Follow, 58:Clear Waypoints, 60:ZigZag, 61:ZigZag SaveWP, 62:Compass Learn, 65:GPS Disable, 66:Relay5 On/Off, 67:Relay6 On/Off, 68:Stabilize, 69:PosHold, 70:AltHold, 71:FlowHold, 72:Circle, 73:Drift, 75:SurfaceTrackingUpDown, 76:Standby Mode, 78:RunCam Control, 79:RunCam OSD Control, 80:VisOdom Align, 81:Disarm, 83:ZigZag Auto, 84:Air Mode, 85:Generator, 90:EKF Pos Source, 94:VTX Power, 99:AUTO RTL, 100:KillIMU1, 101:KillIMU2, 102:Camera Mode Toggle, 105:GPS Disable Yaw, 151:Turtle, 152:simple heading reset, 153:ArmDisarm (4.2 and higher), 154:ArmDisarm with AirMode (4.2 and higher), 158:Optflow Calibration, 159:Force Flying, 161:Turbine Start(heli), 300:Scripting1, 301:Scripting2, 302:Scripting3, 303:Scripting4, 304:Scripting5, 305:Scripting6, 306:Scripting7, 307:Scripting8 - // @Values{Rover}: 0:Do Nothing, 4:RTL, 5:Save Trim (4.1 and lower), 7:Save WP, 9:Camera Trigger, 11:Fence, 16:Auto, 19:Gripper, 24:Auto Mission Reset, 27:Retract Mount, 28:Relay On/Off, 30:Lost Rover Sound, 31:Motor Emergency Stop, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 40:Proximity Avoidance, 41:ArmDisarm (4.1 and lower), 42:SmartRTL, 46:RC Override Enable, 50:LearnCruise, 51:Manual, 52:Acro, 53:Steering, 54:Hold, 55:Guided, 56:Loiter, 57:Follow, 58:Clear Waypoints, 59:Simple Mode, 62:Compass Learn, 63:Sailboat Tack, 65:GPS Disable, 66:Relay5 On/Off, 67:Relay6 On/Off, 74:Sailboat motoring 3pos, 78:RunCam Control, 79:RunCam OSD Control, 80:Viso Align, 81:Disarm, 90:EKF Pos Source, 94:VTX Power, 97:Windvane home heading direction offset, 100:KillIMU1, 101:KillIMU2, 102:Camera Mode Toggle, 105:GPS Disable Yaw, 106:Disable Airspeed Use, 153:ArmDisarm (4.2 and higher), 155: set steering trim to current servo and RC, 156:Torqeedo Clear Err, 201:Roll, 202:Pitch, 207:MainSail, 208:Flap, 211:Walking Height, 300:Scripting1, 301:Scripting2, 302:Scripting3, 303:Scripting4, 304:Scripting5, 305:Scripting6, 306:Scripting7, 307:Scripting8 - // @Values{Plane}: 0:Do Nothing, 4:ModeRTL, 9:Camera Trigger, 11:Fence, 16:ModeAuto, 22:Parachute Release, 24:Auto Mission Reset, 27:Retract Mount, 28:Relay On/Off, 29:Landing Gear, 30:Lost Plane Sound, 31:Motor Emergency Stop, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 38:ADSB Avoidance En, 41:ArmDisarm (4.1 and lower), 43:InvertedFlight, 46:RC Override Enable, 51:ModeManual, 52: ModeACRO, 55:ModeGuided, 56:ModeLoiter, 58:Clear Waypoints, 62:Compass Learn, 64:Reverse Throttle, 65:GPS Disable, 66:Relay5 On/Off, 67:Relay6 On/Off, 72:ModeCircle, 77:ModeTakeoff, 78:RunCam Control, 79:RunCam OSD Control, 81:Disarm, 82:QAssist 3pos, 84:Air Mode, 85:Generator, 86: Non Auto Terrain Follow Disable, 87:Crow Select, 88:Soaring Enable, 89:Landing Flare, 90:EKF Pos Source, 91:Airspeed Ratio Calibration, 92:FBWA, 94:VTX Power, 95:FBWA taildragger takeoff mode, 96:trigger re-reading of mode switch, 98: ModeTraining, 100:KillIMU1, 101:KillIMU2, 102:Camera Mode Toggle, 105:GPS Disable Yaw, 106:Disable Airspeed Use, 107: EnableFixedWingAutotune, 108: ModeQRTL, 150: CRUISE, 153:ArmDisarm (4.2 and higher), 154:ArmDisarm with Quadplane AirMode (4.2 and higher), 155: set roll pitch and yaw trim to current servo and RC, 157: Force FS Action to FBWA, 158:Optflow Calibration, 160:Weathervane Enable, 208:Flap, 209: Forward Throttle, 300:Scripting1, 301:Scripting2, 302:Scripting3, 303:Scripting4, 304:Scripting5, 305:Scripting6, 306:Scripting7, 307:Scripting8 - // @Values{Blimp}: 0:Do Nothing, 18:Land, 46:RC Override Enable, 65:GPS Disable, 81:Disarm, 90:EKF Pos Source, 100:KillIMU1, 101:KillIMU2, 153:ArmDisarm + // @Values{Copter}: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount1, 28:Relay On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 37:Throw, 38:ADSB Avoidance En, 39:PrecLoiter, 40:Proximity Avoidance, 41:ArmDisarm (4.1 and lower), 42:SmartRTL, 43:InvertedFlight, 44:Winch Enable, 46:RC Override Enable, 47:User Function 1, 48:User Function 2, 49:User Function 3, 52:Acro, 55:Guided, 56:Loiter, 57:Follow, 58:Clear Waypoints, 60:ZigZag, 61:ZigZag SaveWP, 62:Compass Learn, 65:GPS Disable, 66:Relay5 On/Off, 67:Relay6 On/Off, 68:Stabilize, 69:PosHold, 70:AltHold, 71:FlowHold, 72:Circle, 73:Drift, 75:SurfaceTrackingUpDown, 76:Standby Mode, 78:RunCam Control, 79:RunCam OSD Control, 80:VisOdom Align, 81:Disarm, 83:ZigZag Auto, 84:Air Mode, 85:Generator, 90:EKF Pos Source, 94:VTX Power, 99:AUTO RTL, 100:KillIMU1, 101:KillIMU2, 102:Camera Mode Toggle, 105:GPS Disable Yaw, 151:Turtle, 152:simple heading reset, 153:ArmDisarm (4.2 and higher), 154:ArmDisarm with AirMode (4.2 and higher), 158:Optflow Calibration, 159:Force Flying, 161:Turbine Start(heli), 162:FFT Tune, 163:Mount Lock, 164:Pause Stream Logging, 165:Arm/Emergency Motor Stop, 166:Camera Record Video, 167:Camera Zoom, 168:Camera Manual Focus, 169:Camera Auto Focus, 212:Mount1 Roll, 213:Mount1 Pitch, 214:Mount1 Yaw, 215:Mount2 Roll, 216:Mount2 Pitch, 217:Mount2 Yaw, 300:Scripting1, 301:Scripting2, 302:Scripting3, 303:Scripting4, 304:Scripting5, 305:Scripting6, 306:Scripting7, 307:Scripting8 + // @Values{Rover}: 0:Do Nothing, 4:RTL, 5:Save Trim (4.1 and lower), 7:Save WP, 9:Camera Trigger, 11:Fence, 16:Auto, 19:Gripper, 24:Auto Mission Reset, 27:Retract Mount1, 28:Relay On/Off, 30:Lost Rover Sound, 31:Motor Emergency Stop, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 40:Proximity Avoidance, 41:ArmDisarm (4.1 and lower), 42:SmartRTL, 46:RC Override Enable, 50:LearnCruise, 51:Manual, 52:Acro, 53:Steering, 54:Hold, 55:Guided, 56:Loiter, 57:Follow, 58:Clear Waypoints, 59:Simple Mode, 62:Compass Learn, 63:Sailboat Tack, 65:GPS Disable, 66:Relay5 On/Off, 67:Relay6 On/Off, 74:Sailboat motoring 3pos, 78:RunCam Control, 79:RunCam OSD Control, 80:Viso Align, 81:Disarm, 90:EKF Pos Source, 94:VTX Power, 97:Windvane home heading direction offset, 100:KillIMU1, 101:KillIMU2, 102:Camera Mode Toggle, 105:GPS Disable Yaw, 106:Disable Airspeed Use, 153:ArmDisarm (4.2 and higher), 155: set steering trim to current servo and RC, 156:Torqeedo Clear Err, 162:FFT Tune, 163:Mount Lock, 164:Pause Stream Logging, 165:Arm/Emergency Motor Stop, 166:Camera Record Video, 167:Camera Zoom, 168:Camera Manual Focus, 169:Camera Auto Focus, 201:Roll, 202:Pitch, 207:MainSail, 208:Flap, 211:Walking Height, 212:Mount1 Roll, 213:Mount1 Pitch, 214:Mount1 Yaw, 215:Mount2 Roll, 216:Mount2 Pitch, 217:Mount2 Yaw, 300:Scripting1, 301:Scripting2, 302:Scripting3, 303:Scripting4, 304:Scripting5, 305:Scripting6, 306:Scripting7, 307:Scripting8 + // @Values{Plane}: 0:Do Nothing, 4:ModeRTL, 9:Camera Trigger, 11:Fence, 16:ModeAuto, 22:Parachute Release, 24:Auto Mission Reset, 27:Retract Mount1, 28:Relay On/Off, 29:Landing Gear, 30:Lost Plane Sound, 31:Motor Emergency Stop, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 38:ADSB Avoidance En, 41:ArmDisarm (4.1 and lower), 43:InvertedFlight, 46:RC Override Enable, 51:ModeManual, 52: ModeACRO, 55:ModeGuided, 56:ModeLoiter, 58:Clear Waypoints, 62:Compass Learn, 64:Reverse Throttle, 65:GPS Disable, 66:Relay5 On/Off, 67:Relay6 On/Off, 72:ModeCircle, 77:ModeTakeoff, 78:RunCam Control, 79:RunCam OSD Control, 81:Disarm, 82:QAssist 3pos, 84:Air Mode, 85:Generator, 86: Non Auto Terrain Follow Disable, 87:Crow Select, 88:Soaring Enable, 89:Landing Flare, 90:EKF Pos Source, 91:Airspeed Ratio Calibration, 92:FBWA, 94:VTX Power, 95:FBWA taildragger takeoff mode, 96:trigger re-reading of mode switch, 98: ModeTraining, 100:KillIMU1, 101:KillIMU2, 102:Camera Mode Toggle, 105:GPS Disable Yaw, 106:Disable Airspeed Use, 107: EnableFixedWingAutotune, 108: ModeQRTL, 150: CRUISE, 153:ArmDisarm (4.2 and higher), 154:ArmDisarm with Quadplane AirMode (4.2 and higher), 155: set roll pitch and yaw trim to current servo and RC, 157: Force FS Action to FBWA, 158:Optflow Calibration, 160:Weathervane Enable, 162:FFT Tune, 163:Mount Lock, 164:Pause Stream Logging, 165:Arm/Emergency Motor Stop, 166:Camera Record Video, 167:Camera Zoom, 168:Camera Manual Focus, 169:Camera Auto Focus, 208:Flap, 209: Forward Throttle, 210: Airbrakes, 212:Mount1 Roll, 213:Mount1 Pitch, 214:Mount1 Yaw, 215:Mount2 Roll, 216:Mount2 Pitch, 217:Mount2 Yaw, 300:Scripting1, 301:Scripting2, 302:Scripting3, 303:Scripting4, 304:Scripting5, 305:Scripting6, 306:Scripting7, 307:Scripting8 + // @Values{Blimp}: 0:Do Nothing, 18:Land, 46:RC Override Enable, 65:GPS Disable, 81:Disarm, 90:EKF Pos Source, 100:KillIMU1, 101:KillIMU2, 153:ArmDisarm, 164:Pause Stream Logging, 166:Camera Record Video, 167:Camera Zoom, 168:Camera Manual Focus, 169:Camera Auto Focus // @User: Standard AP_GROUPINFO_FRAME("OPTION", 6, RC_Channel, option, 0, AP_PARAM_FRAME_COPTER|AP_PARAM_FRAME_ROVER|AP_PARAM_FRAME_PLANE|AP_PARAM_FRAME_BLIMP), @@ -332,7 +333,7 @@ bool RC_Channel::in_trim_dz() const /* return trues if input is within deadzone of min */ -bool RC_Channel::within_min_dz() const +bool RC_Channel::in_min_dz() const { return radio_in < radio_min + dead_zone; } @@ -395,7 +396,7 @@ float RC_Channel::stick_mixing(const float servo_in) } // -// support for auxillary switches: +// support for auxiliary switches: // void RC_Channel::reset_mode_switch() @@ -462,7 +463,7 @@ bool RC_Channel::debounce_completed(int8_t position) } // -// support for auxillary switches: +// support for auxiliary switches: // // init_aux_switch_function - initialize aux functions @@ -502,6 +503,12 @@ void RC_Channel::init_aux_function(const aux_func_t ch_option, const AuxSwitchPo case AUX_FUNC::VTX_POWER: case AUX_FUNC::OPTFLOW_CAL: case AUX_FUNC::TURBINE_START: + case AUX_FUNC::MOUNT1_ROLL: + case AUX_FUNC::MOUNT1_PITCH: + case AUX_FUNC::MOUNT1_YAW: + case AUX_FUNC::MOUNT2_ROLL: + case AUX_FUNC::MOUNT2_PITCH: + case AUX_FUNC::MOUNT2_YAW: break; case AUX_FUNC::AVOID_ADSB: case AUX_FUNC::AVOID_PROXIMITY: @@ -518,9 +525,17 @@ void RC_Channel::init_aux_function(const aux_func_t ch_option, const AuxSwitchPo case AUX_FUNC::RUNCAM_OSD_CONTROL: case AUX_FUNC::SPRAYER: case AUX_FUNC::DISABLE_AIRSPEED_USE: + case AUX_FUNC::FFT_NOTCH_TUNE: #if HAL_MOUNT_ENABLED - case AUX_FUNC::RETRACT_MOUNT: + case AUX_FUNC::RETRACT_MOUNT1: + case AUX_FUNC::MOUNT_LOCK: #endif + case AUX_FUNC::LOG_PAUSE: + case AUX_FUNC::ARM_EMERGENCY_STOP: + case AUX_FUNC::CAMERA_REC_VIDEO: + case AUX_FUNC::CAMERA_ZOOM: + case AUX_FUNC::CAMERA_MANUAL_FOCUS: + case AUX_FUNC::CAMERA_AUTO_FOCUS: run_aux_function(ch_option, ch_flag, AuxFuncTriggerSource::INIT); break; default: @@ -546,7 +561,7 @@ const RC_Channel::LookupTable RC_Channel::lookuptable[] = { { AUX_FUNC::PARACHUTE_RELEASE,"ParachuteRelease"}, { AUX_FUNC::PARACHUTE_3POS,"Parachute3Position"}, { AUX_FUNC::MISSION_RESET,"MissionReset"}, - { AUX_FUNC::RETRACT_MOUNT,"RetractMount"}, + { AUX_FUNC::RETRACT_MOUNT1,"RetractMount1"}, { AUX_FUNC::RELAY,"Relay1"}, { AUX_FUNC::MOTOR_ESTOP,"MotorEStop"}, { AUX_FUNC::MOTOR_INTERLOCK,"MotorInterlock"}, @@ -570,6 +585,7 @@ const RC_Channel::LookupTable RC_Channel::lookuptable[] = { { AUX_FUNC::RUNCAM_CONTROL,"RunCamControl"}, { AUX_FUNC::RUNCAM_OSD_CONTROL,"RunCamOSDControl"}, { AUX_FUNC::VISODOM_ALIGN,"VisOdomAlign"}, + { AUX_FUNC::AIRMODE, "AirMode"}, { AUX_FUNC::EKF_POS_SOURCE,"EKFPosSource"}, { AUX_FUNC::CAM_MODE_TOGGLE,"CamModeToggle"}, { AUX_FUNC::GENERATOR,"Generator"}, @@ -578,12 +594,19 @@ const RC_Channel::LookupTable RC_Channel::lookuptable[] = { { AUX_FUNC::EMERGENCY_LANDING_EN, "Emergency Landing"}, { AUX_FUNC::WEATHER_VANE_ENABLE, "Weathervane"}, { AUX_FUNC::TURBINE_START, "Turbine Start"}, + { AUX_FUNC::FFT_NOTCH_TUNE, "FFT Notch Tuning"}, + { AUX_FUNC::MOUNT_LOCK, "MountLock"}, + { AUX_FUNC::LOG_PAUSE, "Pause Stream Logging"}, + { AUX_FUNC::CAMERA_REC_VIDEO, "Camera Record Video"}, + { AUX_FUNC::CAMERA_ZOOM, "Camera Zoom"}, + { AUX_FUNC::CAMERA_MANUAL_FOCUS, "Camera Manual Focus"}, + { AUX_FUNC::CAMERA_AUTO_FOCUS, "Camera Auto Focus"}, }; /* lookup the announcement for switch change */ const char *RC_Channel::string_for_aux_function(AUX_FUNC function) const { - for (const struct LookupTable entry : lookuptable) { + for (const struct LookupTable &entry : lookuptable) { if (entry.option == function) { return entry.announcement; } @@ -726,6 +749,71 @@ void RC_Channel::do_aux_function_camera_trigger(const AuxSwitchPos ch_flag) } } +bool RC_Channel::do_aux_function_record_video(const AuxSwitchPos ch_flag) +{ + AP_Camera *camera = AP::camera(); + if (camera == nullptr) { + return false; + } + return camera->record_video(ch_flag == AuxSwitchPos::HIGH); +} + +bool RC_Channel::do_aux_function_camera_zoom(const AuxSwitchPos ch_flag) +{ + AP_Camera *camera = AP::camera(); + if (camera == nullptr) { + return false; + } + int8_t zoom_step = 0; // zoom out = -1, hold = 0, zoom in = 1 + switch (ch_flag) { + case AuxSwitchPos::HIGH: + zoom_step = 1; // zoom in + break; + case AuxSwitchPos::MIDDLE: + zoom_step = 0; // zoom hold + break; + case AuxSwitchPos::LOW: + zoom_step = -1; // zoom out + break; + } + return camera->set_zoom_step(zoom_step); +} + +bool RC_Channel::do_aux_function_camera_manual_focus(const AuxSwitchPos ch_flag) +{ + AP_Camera *camera = AP::camera(); + if (camera == nullptr) { + return false; + } + int8_t focus_step = 0; // focus in = -1, focus hold = 0, focus out = 1 + switch (ch_flag) { + case AuxSwitchPos::HIGH: + // wide shot, focus out + focus_step = 1; + break; + case AuxSwitchPos::MIDDLE: + focus_step = 0; + break; + case AuxSwitchPos::LOW: + // close shot, focus in + focus_step = -1; + break; + } + return camera->set_manual_focus_step(focus_step); +} + +bool RC_Channel::do_aux_function_camera_auto_focus(const AuxSwitchPos ch_flag) +{ + AP_Camera *camera = AP::camera(); + if (camera == nullptr) { + return false; + } + if (ch_flag == AuxSwitchPos::HIGH) { + return camera->set_auto_focus(); + } + return false; +} + void RC_Channel::do_aux_function_runcam_control(const AuxSwitchPos ch_flag) { #if HAL_RUNCAM_ENABLED @@ -771,12 +859,14 @@ void RC_Channel::do_aux_function_runcam_osd_control(const AuxSwitchPos ch_flag) // enable or disable the fence void RC_Channel::do_aux_function_fence(const AuxSwitchPos ch_flag) { +#if AP_FENCE_ENABLED AC_Fence *fence = AP::fence(); if (fence == nullptr) { return; } fence->enable(ch_flag == AuxSwitchPos::HIGH); +#endif } void RC_Channel::do_aux_function_clear_wp(const AuxSwitchPos ch_flag) @@ -899,8 +989,31 @@ void RC_Channel::do_aux_function_mission_reset(const AuxSwitchPos ch_flag) mission->reset(); } +void RC_Channel::do_aux_function_fft_notch_tune(const AuxSwitchPos ch_flag) +{ +#if HAL_GYROFFT_ENABLED + AP_GyroFFT *fft = AP::fft(); + if (fft == nullptr) { + return; + } + + switch (ch_flag) { + case AuxSwitchPos::HIGH: + fft->start_notch_tune(); + break; + case AuxSwitchPos::MIDDLE: + case AuxSwitchPos::LOW: + fft->stop_notch_tune(); + break; + } +#endif +} + bool RC_Channel::run_aux_function(aux_func_t ch_option, AuxSwitchPos pos, AuxFuncTriggerSource source) { +#if AP_SCRIPTING_ENABLED + rc().set_aux_cached(ch_option, pos); +#endif const bool ret = do_aux_function(ch_option, pos); // @LoggerMessage: AUXF @@ -908,7 +1021,7 @@ bool RC_Channel::run_aux_function(aux_func_t ch_option, AuxSwitchPos pos, AuxFun // @Field: TimeUS: Time since system startup // @Field: function: ID of triggered function // @Field: pos: switch position when function triggered - // @Field: source: source of auxillary function invocation + // @Field: source: source of auxiliary function invocation // @Field: result: true if function was successful AP::logger().Write( "AUXF", @@ -987,6 +1100,13 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos do_aux_function_avoid_adsb(ch_flag); break; +#if 0 + // feature disabled for 4.3.4 due to https://github.com/ArduPilot/ardupilot/pull/22686 + case AUX_FUNC::FFT_NOTCH_TUNE: + do_aux_function_fft_notch_tune(ch_flag); + break; +#endif + #if HAL_GENERATOR_ENABLED case AUX_FUNC::GENERATOR: do_aux_function_generator(ch_flag); @@ -1069,12 +1189,6 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos switch (ch_flag) { case AuxSwitchPos::HIGH: { SRV_Channels::set_emergency_stop(true); - - // log E-stop - AP_Logger *logger = AP_Logger::get_singleton(); - if (logger && logger->logging_enabled()) { - logger->Write_Event(LogEvent::MOTORS_EMERGENCY_STOPPED); - } break; } case AuxSwitchPos::MIDDLE: @@ -1082,12 +1196,6 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos break; case AuxSwitchPos::LOW: { SRV_Channels::set_emergency_stop(false); - - // log E-stop cleared - AP_Logger *logger = AP_Logger::get_singleton(); - if (logger && logger->logging_enabled()) { - logger->Write_Event(LogEvent::MOTORS_EMERGENCY_STOP_CLEARED); - } break; } } @@ -1123,7 +1231,7 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos case AUX_FUNC::OPTFLOW_CAL: { #if AP_OPTICALFLOW_ENABLED - OpticalFlow *optflow = AP::opticalflow(); + AP_OpticalFlow *optflow = AP::opticalflow(); if (optflow == nullptr) { gcs().send_text(MAV_SEVERITY_CRITICAL, "OptFlow Cal: failed sensor not enabled"); break; @@ -1166,8 +1274,19 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos } break; } + case AUX_FUNC::CAMERA_REC_VIDEO: + return do_aux_function_record_video(ch_flag); - case AUX_FUNC::RETRACT_MOUNT: { + case AUX_FUNC::CAMERA_ZOOM: + return do_aux_function_camera_zoom(ch_flag); + + case AUX_FUNC::CAMERA_MANUAL_FOCUS: + return do_aux_function_camera_manual_focus(ch_flag); + + case AUX_FUNC::CAMERA_AUTO_FOCUS: + return do_aux_function_camera_auto_focus(ch_flag); + + case AUX_FUNC::RETRACT_MOUNT1: { #if HAL_MOUNT_ENABLED AP_Mount *mount = AP::mount(); if (mount == nullptr) { @@ -1175,19 +1294,65 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos } switch (ch_flag) { case AuxSwitchPos::HIGH: - mount->set_mode(MAV_MOUNT_MODE_RETRACT); + mount->set_mode(0,MAV_MOUNT_MODE_RETRACT); break; case AuxSwitchPos::MIDDLE: // nothing break; case AuxSwitchPos::LOW: - mount->set_mode_to_default(); + mount->set_mode_to_default(0); break; } #endif break; } + case AUX_FUNC::MOUNT_LOCK: { +#if HAL_MOUNT_ENABLED + AP_Mount *mount = AP::mount(); + if (mount == nullptr) { + break; + } + mount->set_yaw_lock(ch_flag == AuxSwitchPos::HIGH); +#endif + break; + } + + case AUX_FUNC::LOG_PAUSE: { + AP_Logger *logger = AP_Logger::get_singleton(); + switch (ch_flag) { + case AuxSwitchPos::LOW: + logger->log_pause(false); + break; + case AuxSwitchPos::MIDDLE: + // nothing + break; + case AuxSwitchPos::HIGH: + logger->log_pause(true); + break; + } + break; + } + + case AUX_FUNC::ARM_EMERGENCY_STOP: { + switch (ch_flag) { + case AuxSwitchPos::HIGH: + // request arm, disable emergency motor stop + SRV_Channels::set_emergency_stop(false); + AP::arming().arm(AP_Arming::Method::AUXSWITCH, true); + break; + case AuxSwitchPos::MIDDLE: + // disable emergency motor stop + SRV_Channels::set_emergency_stop(false); + break; + case AuxSwitchPos::LOW: + // enable emergency motor stop + SRV_Channels::set_emergency_stop(true); + break; + } + break; + } + case AUX_FUNC::EKF_LANE_SWITCH: // used to test emergency lane switch AP::ahrs().check_lane_switch(); @@ -1211,6 +1376,13 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos break; } + // do nothing for these functions + case AUX_FUNC::MOUNT1_ROLL: + case AUX_FUNC::MOUNT1_PITCH: + case AUX_FUNC::MOUNT1_YAW: + case AUX_FUNC::MOUNT2_ROLL: + case AUX_FUNC::MOUNT2_PITCH: + case AUX_FUNC::MOUNT2_YAW: case AUX_FUNC::SCRIPTING_1: case AUX_FUNC::SCRIPTING_2: case AUX_FUNC::SCRIPTING_3: diff --git a/libraries/RC_Channel/RC_Channel.h b/libraries/RC_Channel/RC_Channel.h index 0c2df648aaf..56d54108688 100644 --- a/libraries/RC_Channel/RC_Channel.h +++ b/libraries/RC_Channel/RC_Channel.h @@ -5,6 +5,7 @@ #include #include #include +#include #define NUM_RC_CHANNELS 16 @@ -53,7 +54,7 @@ class RC_Channel { float norm_input_ignore_trim() const; // returns true if input is within deadzone of min - bool within_min_dz() const; + bool in_min_dz() const; uint8_t percent_input() const; @@ -88,8 +89,8 @@ class RC_Channel { // set and save trim if changed void set_and_save_radio_trim(int16_t val) { radio_trim.set_and_save_ifchanged(val);} - // check if any of the trim/min/max param are configured in storage, this would indicate that the user has done a calibration at somepoint - bool configured_in_storage() { return radio_min.configured_in_storage() || radio_max.configured_in_storage() || radio_trim.configured_in_storage(); } + // check if any of the trim/min/max param are configured, this would indicate that the user has done a calibration at somepoint + bool configured() { return radio_min.configured() || radio_max.configured() || radio_trim.configured(); } ControlType get_type(void) const { return type_in; } @@ -124,7 +125,7 @@ class RC_Channel { MISSION_RESET = 24, // Reset auto mission to start from first command ATTCON_FEEDFWD = 25, // enable/disable the roll and pitch rate feed forward ATTCON_ACCEL_LIM = 26, // enable/disable the roll, pitch and yaw accel limiting - RETRACT_MOUNT = 27, // Retract Mount + RETRACT_MOUNT1 = 27, // Retract Mount1 RELAY = 28, // Relay pin on/off (only supports first relay) LANDING_GEAR = 29, // Landing gear controller LOST_VEHICLE_SOUND = 30, // Play lost vehicle sound @@ -209,13 +210,14 @@ class RC_Channel { DISABLE_AIRSPEED_USE = 106, // equivalent to AIRSPEED_USE 0 FW_AUTOTUNE = 107, // fixed wing auto tune QRTL = 108, // QRTL mode + CUSTOM_CONTROLLER = 109, // if you add something here, make sure to update the documentation of the parameter in RC_Channel.cpp! // also, if you add an option >255, you will need to fix duplicate_options_exist // options 150-199 continue user rc switch options CRUISE = 150, // CRUISE mode TURTLE = 151, // Turtle mode - flip over after crash - SIMPLE_HEADING_RESET = 152, // reset simple mode refernce heading to current + SIMPLE_HEADING_RESET = 152, // reset simple mode reference heading to current ARMDISARM = 153, // arm or disarm vehicle ARMDISARM_AIRMODE = 154, // arm or disarm vehicle enabling airmode TRIM_TO_CURRENT_SERVO_RC = 155, // trim to current servo and RC @@ -224,7 +226,15 @@ class RC_Channel { OPTFLOW_CAL = 158, // optical flow calibration FORCEFLYING = 159, // enable or disable land detection for GPS based manual modes preventing land detection and maintainting set_throttle_mix_max WEATHER_VANE_ENABLE = 160, // enable/disable weathervaning - TURBINE_START = 161, // initialize turbine start sequence + TURBINE_START = 161, // initialize turbine start sequence + FFT_NOTCH_TUNE = 162, // FFT notch tuning function + MOUNT_LOCK = 163, // Mount yaw lock vs follow + LOG_PAUSE = 164, // Pauses logging if under logging rate control + ARM_EMERGENCY_STOP = 165, // ARM on high, MOTOR_ESTOP on low + CAMERA_REC_VIDEO = 166, // start recording on high, stop recording on low + CAMERA_ZOOM = 167, // camera zoom high = zoom in, middle = hold, low = zoom out + CAMERA_MANUAL_FOCUS = 168,// camera manual focus. high = long shot, middle = stop focus, low = close shot + CAMERA_AUTO_FOCUS = 169, // camera auto focus // inputs from 200 will eventually used to replace RCMAP ROLL = 201, // roll input @@ -236,6 +246,15 @@ class RC_Channel { FWD_THR = 209, // VTOL manual forward throttle AIRBRAKE = 210, // manual airbrake control WALKING_HEIGHT = 211, // walking robot height input + MOUNT1_ROLL = 212, // mount1 roll input + MOUNT1_PITCH = 213, // mount1 pitch input + MOUNT1_YAW = 214, // mount1 yaw input + MOUNT2_ROLL = 215, // mount2 roll input + MOUNT2_PITCH = 216, // mount3 pitch input + MOUNT2_YAW = 217, // mount4 yaw input + + // inputs 248-249 are reserved for the Skybrush fork at + // https://github.com/skybrush-io/ardupilot // inputs for the use of onboard lua scripting SCRIPTING_1 = 300, @@ -246,10 +265,13 @@ class RC_Channel { SCRIPTING_6 = 305, SCRIPTING_7 = 306, SCRIPTING_8 = 307, + + // this must be higher than any aux function above + AUX_FUNCTION_MAX = 308, }; typedef enum AUX_FUNC aux_func_t; - // auxillary switch handling (n.b.: we store this as 2-bits!): + // auxiliary switch handling (n.b.: we store this as 2-bits!): enum class AuxSwitchPos : uint8_t { LOW, // indicates auxiliary switch is in the low position (pwm <1200) MIDDLE, // indicates auxiliary switch is in the middle position (pwm >1200, <1800) @@ -274,7 +296,7 @@ class RC_Channel { const char *string_for_aux_function(AUX_FUNC function) const; #endif // pwm value under which we consider that Radio value is invalid - static const uint16_t RC_MIN_LIMIT_PWM = 900; + static const uint16_t RC_MIN_LIMIT_PWM = 800; // pwm value above which we consider that Radio value is invalid static const uint16_t RC_MAX_LIMIT_PWM = 2200; @@ -304,6 +326,10 @@ class RC_Channel { void do_aux_function_avoid_adsb(const AuxSwitchPos ch_flag); void do_aux_function_avoid_proximity(const AuxSwitchPos ch_flag); void do_aux_function_camera_trigger(const AuxSwitchPos ch_flag); + bool do_aux_function_record_video(const AuxSwitchPos ch_flag); + bool do_aux_function_camera_zoom(const AuxSwitchPos ch_flag); + bool do_aux_function_camera_manual_focus(const AuxSwitchPos ch_flag); + bool do_aux_function_camera_auto_focus(const AuxSwitchPos ch_flag); void do_aux_function_runcam_control(const AuxSwitchPos ch_flag); void do_aux_function_runcam_osd_control(const AuxSwitchPos ch_flag); void do_aux_function_fence(const AuxSwitchPos ch_flag); @@ -315,6 +341,7 @@ class RC_Channel { void do_aux_function_relay(uint8_t relay, bool val); void do_aux_function_sprayer(const AuxSwitchPos ch_flag); void do_aux_function_generator(const AuxSwitchPos ch_flag); + void do_aux_function_fft_notch_tune(const AuxSwitchPos ch_flag); typedef int8_t modeswitch_pos_t; virtual void mode_switch_changed(modeswitch_pos_t new_pos) { @@ -513,6 +540,10 @@ class RC_Channels { return get_singleton() != nullptr && (_options & uint32_t(Option::USE_CRSF_LQ_AS_RSSI)) != 0; } + bool use_420kbaud_for_elrs(void) const { + return get_singleton() != nullptr && (_options & uint32_t(Option::ELRS_420KBAUD)) != 0; + } + // returns true if overrides should time out. If true is returned // then returned_timeout_ms will contain the timeout in // milliseconds, with 0 meaning overrides are disabled. @@ -546,7 +577,7 @@ class RC_Channels { uint32_t last_input_ms() const { return last_update_ms; }; // method for other parts of the system (e.g. Button and mavlink) - // to trigger auxillary functions + // to trigger auxiliary functions bool run_aux_function(RC_Channel::AUX_FUNC ch_option, RC_Channel::AuxSwitchPos pos, RC_Channel::AuxFuncTriggerSource source) { return rc_channel(0)->run_aux_function(ch_option, pos, source); } @@ -562,6 +593,11 @@ class RC_Channels { void calibrating(bool b) { gcs_is_calibrating = b; } bool calibrating() { return gcs_is_calibrating; } +#if AP_SCRIPTING_ENABLED + // get last aux cached value for scripting. Returns false if never set, otherwise 0,1,2 + bool get_aux_cached(RC_Channel::aux_func_t aux_fn, uint8_t &pos); +#endif + protected: enum class Option { @@ -577,6 +613,7 @@ class RC_Channels { SUPPRESS_CRSF_MESSAGE = (1U << 9), // suppress CRSF mode/rate message for ELRS systems MULTI_RECEIVER_SUPPORT = (1U << 10), // allow multiple receivers USE_CRSF_LQ_AS_RSSI = (1U << 11), // returns CRSF link quality as RSSI value, instead of RSSI + ELRS_420KBAUD = (1U << 13), // use 420kbaud for ELRS protocol }; void new_override_received() { @@ -603,6 +640,15 @@ class RC_Channels { // true if GCS is performing a RC calibration bool gcs_is_calibrating; + +#if AP_SCRIPTING_ENABLED + // bitmask of last aux function value, 2 bits per function + // value 0 means never set, otherwise level+1 + HAL_Semaphore aux_cache_sem; + Bitmask aux_cached; + + void set_aux_cached(RC_Channel::aux_func_t aux_fn, RC_Channel::AuxSwitchPos pos); +#endif }; RC_Channels &rc(); diff --git a/libraries/RC_Channel/RC_Channels.cpp b/libraries/RC_Channel/RC_Channels.cpp index 4a202339109..21915176b1f 100644 --- a/libraries/RC_Channel/RC_Channels.cpp +++ b/libraries/RC_Channel/RC_Channels.cpp @@ -148,7 +148,7 @@ bool RC_Channels::receiver_bind(const int dsmMode) } -// support for auxillary switches: +// support for auxiliary switches: // read_aux_switches - checks aux switch positions and invokes configured actions void RC_Channels::read_aux_all() { @@ -260,6 +260,45 @@ uint32_t RC_Channels::enabled_protocols() const return uint32_t(_protocols.get()); } +#if AP_SCRIPTING_ENABLED +/* + implement aux function cache for scripting + */ + +/* + get last aux cached value for scripting. Returns false if never set, otherwise 0,1,2 +*/ +bool RC_Channels::get_aux_cached(RC_Channel::aux_func_t aux_fn, uint8_t &pos) +{ + const uint16_t aux_idx = uint16_t(aux_fn); + if (aux_idx >= unsigned(RC_Channel::AUX_FUNC::AUX_FUNCTION_MAX)) { + return false; + } + WITH_SEMAPHORE(aux_cache_sem); + uint8_t v = aux_cached.get(aux_idx*2) | (aux_cached.get(aux_idx*2+1)<<1); + if (v == 0) { + // never been set + return false; + } + pos = v-1; + return true; +} + +/* + set cached value of an aux function + */ +void RC_Channels::set_aux_cached(RC_Channel::aux_func_t aux_fn, RC_Channel::AuxSwitchPos pos) +{ + const uint16_t aux_idx = uint16_t(aux_fn); + if (aux_idx < unsigned(RC_Channel::AUX_FUNC::AUX_FUNCTION_MAX)) { + WITH_SEMAPHORE(aux_cache_sem); + uint8_t v = unsigned(pos)+1; + aux_cached.setonoff(aux_idx*2, v&1); + aux_cached.setonoff(aux_idx*2+1, v>>1); + } +} +#endif // AP_SCRIPTING_ENABLED + // singleton instance RC_Channels *RC_Channels::_singleton; diff --git a/libraries/RC_Channel/RC_Channels_VarInfo.h b/libraries/RC_Channel/RC_Channels_VarInfo.h index 302cf9a8dc4..9e3eb7c0d6e 100644 --- a/libraries/RC_Channel/RC_Channels_VarInfo.h +++ b/libraries/RC_Channel/RC_Channels_VarInfo.h @@ -89,7 +89,7 @@ const AP_Param::GroupInfo RC_Channels::var_info[] = { // @DisplayName: RC options // @Description: RC input options // @User: Advanced - // @Bitmask: 0:Ignore RC Receiver, 1:Ignore MAVLink Overrides, 2:Ignore Receiver Failsafe bit but allow other RC failsafes if setup, 3:FPort Pad, 4:Log RC input bytes, 5:Arming check throttle for 0 input, 6:Skip the arming check for neutral Roll/Pitch/Yaw sticks, 7:Allow Switch reverse, 8:Use passthrough for CRSF telemetry, 9:Suppress CRSF mode/rate message for ELRS systems,10:Enable multiple receiver support, 11:CRSF RSSI shows Link Quality + // @Bitmask: 0:Ignore RC Receiver, 1:Ignore MAVLink Overrides, 2:Ignore Receiver Failsafe bit but allow other RC failsafes if setup, 3:FPort Pad, 4:Log RC input bytes, 5:Arming check throttle for 0 input, 6:Skip the arming check for neutral Roll/Pitch/Yaw sticks, 7:Allow Switch reverse, 8:Use passthrough for CRSF telemetry, 9:Suppress CRSF mode/rate message for ELRS systems,10:Enable multiple receiver support, 11:Use Link Quality for RSSI with CRSF, 13: Use 420kbaud for ELRS protocol AP_GROUPINFO("_OPTIONS", 33, RC_CHANNELS_SUBCLASS, _options, (uint32_t)RC_Channels::Option::ARMING_CHECK_THROTTLE), // @Param: _PROTOCOLS diff --git a/libraries/SITL/SIM_Aircraft.cpp b/libraries/SITL/SIM_Aircraft.cpp index 2f8464448a5..0434abd3c5c 100644 --- a/libraries/SITL/SIM_Aircraft.cpp +++ b/libraries/SITL/SIM_Aircraft.cpp @@ -16,13 +16,14 @@ parent class for aircraft simulators */ +#define ALLOW_DOUBLE_MATH_FUNCTIONS + #include "SIM_Aircraft.h" #include #include #include - #if defined(__CYGWIN__) || defined(__CYGWIN64__) #include #include @@ -39,6 +40,8 @@ using namespace SITL; +extern const AP_HAL::HAL& hal; + /* parent class for all simulator types */ @@ -280,7 +283,13 @@ void Aircraft::sync_frame_time(void) } if (sleep_debt_us > min_sleep_time) { // sleep if we have built up a debt of min_sleep_tim +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL usleep(sleep_debt_us); +#elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS + hal.scheduler->delay_microseconds(sleep_debt_us); +#else + // ?? +#endif sleep_debt_us -= (get_wall_time_us() - now); } last_wall_time_us = get_wall_time_us(); @@ -381,9 +390,8 @@ void Aircraft::fill_fdm(struct sitl_fdm &fdm) fdm.velocity_air_bf = velocity_air_bf; fdm.battery_voltage = battery_voltage; fdm.battery_current = battery_current; - fdm.num_motors = num_motors; - fdm.vtol_motor_start = vtol_motor_start; - memcpy(fdm.rpm, rpm, num_motors * sizeof(float)); + fdm.motor_mask = motor_mask | sitl->vibe_motor_mask; + memcpy(fdm.rpm, rpm, sizeof(fdm.rpm)); fdm.rcin_chan_count = rcin_chan_count; fdm.range = rangefinder_range(); memcpy(fdm.rcin, rcin, rcin_chan_count * sizeof(float)); @@ -399,6 +407,8 @@ void Aircraft::fill_fdm(struct sitl_fdm &fdm) fdm.wind_vane_apparent.direction = wind_vane_apparent.direction; fdm.wind_vane_apparent.speed = wind_vane_apparent.speed; + fdm.wind_ef = wind_ef; + if (is_smoothed) { fdm.xAccel = smoothing.accel_body.x; fdm.yAccel = smoothing.accel_body.y; @@ -418,26 +428,9 @@ void Aircraft::fill_fdm(struct sitl_fdm &fdm) if (ahrs_orientation != nullptr) { enum Rotation imu_rotation = (enum Rotation)ahrs_orientation->get(); if (imu_rotation != last_imu_rotation) { - // Surprisingly, Matrix3::from_rotation(ROTATION_CUSTOM) is the identity matrix - // so we must deal with that here - if (imu_rotation == ROTATION_CUSTOM) { - if ((custom_roll == nullptr) || (custom_pitch == nullptr) || (custom_yaw == nullptr)) { - enum ap_var_type ptype; - custom_roll = (AP_Float *)AP_Param::find("AHRS_CUSTOM_ROLL", &ptype); - custom_pitch = (AP_Float *)AP_Param::find("AHRS_CUSTOM_PIT", &ptype); - custom_yaw = (AP_Float *)AP_Param::find("AHRS_CUSTOM_YAW", &ptype); - } - if ((custom_roll != nullptr) && (custom_pitch != nullptr) && (custom_yaw != nullptr)) { - sitl->ahrs_rotation.from_euler(radians(*custom_roll), radians(*custom_pitch), radians(*custom_yaw)); - sitl->ahrs_rotation_inv = sitl->ahrs_rotation.transposed(); - } else { - AP_HAL::panic("could not find one or more of parameters AHRS_CUSTOM_ROLL/PITCH/YAW"); - } - } else { - sitl->ahrs_rotation.from_rotation(imu_rotation); - sitl->ahrs_rotation_inv = sitl->ahrs_rotation.transposed(); - last_imu_rotation = imu_rotation; - } + sitl->ahrs_rotation.from_rotation(imu_rotation); + sitl->ahrs_rotation_inv = sitl->ahrs_rotation.transposed(); + last_imu_rotation = imu_rotation; } if (imu_rotation != ROTATION_NONE) { Matrix3f m = dcm; @@ -453,7 +446,7 @@ void Aircraft::fill_fdm(struct sitl_fdm &fdm) // in the first call here, if a speedup option is specified, overwrite it if (is_equal(last_speedup, -1.0f) && !is_equal(get_speedup(), 1.0f)) { - sitl->speedup = get_speedup(); + sitl->speedup.set(get_speedup()); } if (!is_equal(last_speedup, float(sitl->speedup)) && sitl->speedup > 0) { @@ -491,11 +484,19 @@ void Aircraft::fill_fdm(struct sitl_fdm &fdm) // is bouncing off: float Aircraft::perpendicular_distance_to_rangefinder_surface() const { - return sitl->height_agl; + switch ((Rotation)sitl->sonar_rot.get()) { + case Rotation::ROTATION_PITCH_270: + return sitl->height_agl; + case ROTATION_NONE ... ROTATION_YAW_315: + return sitl->measure_distance_at_angle_bf(location, sitl->sonar_rot.get()*45); + default: + AP_BoardConfig::config_error("Bad simulated sonar rotation"); + } } float Aircraft::rangefinder_range() const { + float roll = sitl->state.rollDeg; float pitch = sitl->state.pitchDeg; @@ -532,6 +533,7 @@ float Aircraft::rangefinder_range() const // sensor position offset in body frame const Vector3f relPosSensorBF = sitl->rngfnd_pos_offset; + // n.b. the following code is assuming rotation-pitch-270: // adjust altitude for position of the sensor on the vehicle if position offset is non-zero if (!relPosSensorBF.is_zero()) { // get a rotation matrix following DCM conventions (body to earth) @@ -553,6 +555,7 @@ float Aircraft::rangefinder_range() const } +// potentially replace this with a call to AP_HAL::Util::get_hw_rtc uint64_t Aircraft::get_wall_time_us() const { #if defined(__CYGWIN__) || defined(__CYGWIN64__) @@ -566,10 +569,12 @@ uint64_t Aircraft::get_wall_time_us() const last_ret_us += (uint64_t)((now - tPrev)*1000UL); tPrev = now; return last_ret_us; -#else +#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL struct timespec ts; clock_gettime(CLOCK_MONOTONIC, &ts); return uint64_t(ts.tv_sec * 1000000ULL + ts.tv_nsec / 1000ULL); +#else + return AP_HAL::micros64(); #endif } @@ -946,6 +951,13 @@ void Aircraft::update_external_payload(const struct sitl_input &input) external_payload_mass += sprayer->payload_mass(); } + { + const float range = rangefinder_range(); + for (uint8_t i=0; iupdate(*this); @@ -976,7 +988,7 @@ void Aircraft::update_external_payload(const struct sitl_input &input) if (precland && precland->is_enabled()) { precland->update(get_location(), get_position_relhome()); if (precland->_over_precland_base) { - local_ground_level += precland->_origin_height; + local_ground_level += precland->_device_height; } } @@ -1018,7 +1030,7 @@ void Aircraft::add_shove_forces(Vector3f &rot_accel, Vector3f &body_accel) body_accel.z += sitl->shove.z; } else { sitl->shove.start_ms = 0; - sitl->shove.t = 0; + sitl->shove.t.set(0); } } @@ -1107,7 +1119,7 @@ void Aircraft::add_twist_forces(Vector3f &rot_accel) rot_accel.z += sitl->twist.z; } else { sitl->twist.start_ms = 0; - sitl->twist.t = 0; + sitl->twist.t.set(0); } } diff --git a/libraries/SITL/SIM_Aircraft.h b/libraries/SITL/SIM_Aircraft.h index 1c2c0ca00f8..ca057d0453f 100644 --- a/libraries/SITL/SIM_Aircraft.h +++ b/libraries/SITL/SIM_Aircraft.h @@ -18,6 +18,8 @@ #pragma once +#if AP_SIM_ENABLED + #include #include "SITL.h" @@ -89,16 +91,6 @@ class Aircraft { // get frame rate of model in Hz float get_rate_hz(void) const { return rate_hz; } - // get number of motors for model - uint16_t get_num_motors() const { - return num_motors; - } - - // get motor offset for model - virtual uint16_t get_motors_offset() const { - return 0; - } - const Vector3f &get_gyro(void) const { return gyro; } @@ -187,9 +179,8 @@ class Aircraft { // battery model Battery battery; - uint8_t num_motors = 1; - uint8_t vtol_motor_start; - float rpm[12]; + uint32_t motor_mask; + float rpm[32]; uint8_t rcin_chan_count; float rcin[12]; @@ -343,3 +334,5 @@ class Aircraft { }; } // namespace SITL + +#endif // AP_SIM_ENABLED diff --git a/libraries/SITL/SIM_BalanceBot.cpp b/libraries/SITL/SIM_BalanceBot.cpp index 384be77f672..f3b11d0c903 100644 --- a/libraries/SITL/SIM_BalanceBot.cpp +++ b/libraries/SITL/SIM_BalanceBot.cpp @@ -16,6 +16,8 @@ Balance Bot simulator class */ +#define ALLOW_DOUBLE_MATH_FUNCTIONS + #include "SIM_BalanceBot.h" #include diff --git a/libraries/SITL/SIM_BattMonitor_SMBus.cpp b/libraries/SITL/SIM_BattMonitor_SMBus.cpp index 418318f6725..2f9fe08df5c 100644 --- a/libraries/SITL/SIM_BattMonitor_SMBus.cpp +++ b/libraries/SITL/SIM_BattMonitor_SMBus.cpp @@ -11,46 +11,67 @@ SITL::SIM_BattMonitor_SMBus::SIM_BattMonitor_SMBus() : add_register("Remaining Capacity", SMBusBattDevReg::REMAINING_CAPACITY, SITL::I2CRegisters::RegMode::RDONLY); add_register("Full Charge Capacity", SMBusBattDevReg::FULL_CHARGE_CAPACITY, SITL::I2CRegisters::RegMode::RDONLY); add_register("Cycle_Count", SMBusBattDevReg::CYCLE_COUNT, SITL::I2CRegisters::RegMode::RDONLY); + add_register("Design Charge Capacity", SMBusBattDevReg::DESIGN_CAPACITY, SITL::I2CRegisters::RegMode::RDONLY); + add_register("Design Maximum Voltage", SMBusBattDevReg::DESIGN_VOLTAGE, SITL::I2CRegisters::RegMode::RDONLY); add_register("Specification Info", SMBusBattDevReg::SPECIFICATION_INFO, SITL::I2CRegisters::RegMode::RDONLY); + add_register("Manufacture Date", SMBusBattDevReg::MANUFACTURE_DATE, SITL::I2CRegisters::RegMode::RDONLY); add_register("Serial", SMBusBattDevReg::SERIAL, SITL::I2CRegisters::RegMode::RDONLY); add_block("Manufacture Name", SMBusBattDevReg::MANUFACTURE_NAME, SITL::I2CRegisters::RegMode::RDONLY); add_block("Device Name", SMBusBattDevReg::DEVICE_NAME, SITL::I2CRegisters::RegMode::RDONLY); + add_block("Device Chemistry", SMBusBattDevReg::DEVICE_CHEMISTRY, SITL::I2CRegisters::RegMode::RDONLY); add_register("Manufacture Data", SMBusBattDevReg::MANUFACTURE_DATA, SITL::I2CRegisters::RegMode::RDONLY); set_register(SMBusBattDevReg::TEMP, (int16_t)((C_TO_KELVIN(15))*10)); - // see update for voltage - // see update for current - // TODO: remaining capacity - // TODO: full capacity - set_register(SMBusBattDevReg::CYCLE_COUNT, (uint16_t(39U))); - - // Set SPECIFICATION_INFO - union { - struct { - uint8_t revision : 4; - uint8_t version: 4; - uint8_t vscale: 4; - uint8_t ipscale: 4; - } fields; - uint16_t word; - } specinfo; - - specinfo.fields.revision = 0b0001; // version 1 -// specinfo.fields.version = 0b0011; // 1.1 with PEC; TODO! - specinfo.fields.version = 0b0001; // 1.0 - specinfo.fields.vscale = 0b0000; // unknown... - specinfo.fields.ipscale = 0b0000; // unknown... - set_register(SMBusBattDevReg::SPECIFICATION_INFO, specinfo.word); - - set_register(SMBusBattDevReg::SERIAL, (uint16_t)12345); - - const char *manufacturer_name = "ArduPilot"; - set_block(SMBusBattDevReg::MANUFACTURE_NAME, manufacturer_name); - - const char *device_name = "SITLBatMon_V0.99"; - set_block(SMBusBattDevReg::DEVICE_NAME, device_name); - - // TODO: manufacturer data + // see update for voltage + // see update for current + + set_register(SMBusBattDevReg::DESIGN_VOLTAGE, (uint16_t(50400U))); // (mV) Design maximum voltage + + // TODO: remaining capacity connect to sim capacity add to update method below? + // TODO: Battery mode bit set to mAh vs 10 mWh + set_register(SMBusBattDevReg::REMAINING_CAPACITY, (uint16_t(42042U))); // (mAh) Remaining Capacity + + // TODO: full capacity fill via SIM parameter + set_register(SMBusBattDevReg::FULL_CHARGE_CAPACITY, (uint16_t(45000U))); // (mAh) Full charge capacity + set_register(SMBusBattDevReg::DESIGN_CAPACITY, (uint16_t(52500U))); // (mAh) Design capacity + + set_register(SMBusBattDevReg::CYCLE_COUNT, (uint16_t(42U))); + + // Set SPECIFICATION_INFO + union { + struct { + uint8_t revision : 4; + uint8_t version: 4; + uint8_t vscale: 4; + uint8_t ipscale: 4; + } fields; + uint16_t word; + } specinfo; + + // TODO: compute PEC for relevant monitors + specinfo.fields.revision = 0b0001; // version 1 +// specinfo.fields.version = 0b0011; // 1.1 with PEC; TODO! + specinfo.fields.version = 0b0001; // 1.0 + specinfo.fields.vscale = 0b0000; // unknown... + specinfo.fields.ipscale = 0b0000; // unknown... + set_register(SMBusBattDevReg::SPECIFICATION_INFO, specinfo.word); + + set_register(SMBusBattDevReg::SERIAL, (uint16_t)12345); + + const char *manufacturer_name = "ArduPilot"; + set_block(SMBusBattDevReg::MANUFACTURE_NAME, manufacturer_name); + + const char *device_name = "SITLBatMon_V0.99"; + set_block(SMBusBattDevReg::DEVICE_NAME, device_name); + + const char *device_chemistry = "LION"; + set_block(SMBusBattDevReg::DEVICE_CHEMISTRY, device_chemistry); + + // Set Manufacture date to 2021 APR 24th + const uint16_t manufacturer_date = ((2021 - 1980) << 9) + (04 << 5) + 24; + set_register(SMBusBattDevReg::MANUFACTURE_DATE, manufacturer_date); + + // TODO: manufacturer data } void SITL::SIM_BattMonitor_SMBus::update(const class Aircraft &aircraft) diff --git a/libraries/SITL/SIM_BattMonitor_SMBus.h b/libraries/SITL/SIM_BattMonitor_SMBus.h index b622b4f91d5..2b8267d6951 100644 --- a/libraries/SITL/SIM_BattMonitor_SMBus.h +++ b/libraries/SITL/SIM_BattMonitor_SMBus.h @@ -10,12 +10,16 @@ class SMBusBattDevReg : public SMBusRegEnum { static const uint8_t VOLTAGE = 0x09; // Voltage static const uint8_t CURRENT = 0x0A; // Current static const uint8_t REMAINING_CAPACITY = 0x0F; // Remaining Capacity - static const uint8_t FULL_CHARGE_CAPACITY = 0x10; // Full Charge Capacity + static const uint8_t FULL_CHARGE_CAPACITY = 0x10; // Full Charge Capacity (accounting for battery degradation) static const uint8_t CYCLE_COUNT = 0x17; // Cycle Count + static const uint8_t DESIGN_CAPACITY = 0x18; // Design capacity (capacity when newly manufactured) + static const uint8_t DESIGN_VOLTAGE = 0x19; // Design voltage static const uint8_t SPECIFICATION_INFO = 0x1A; // Specification Info + static const uint8_t MANUFACTURE_DATE = 0x1B; // Manufacture date static const uint8_t SERIAL = 0x1C; // Serial Number static const uint8_t MANUFACTURE_NAME = 0x20; // Manufacture Name static const uint8_t DEVICE_NAME = 0x21; // Device Name + static const uint8_t DEVICE_CHEMISTRY = 0x22; // Battery chemistry type static const uint8_t MANUFACTURE_DATA = 0x23; // Manufacture Data }; diff --git a/libraries/SITL/SIM_BattMonitor_SMBus_Generic.cpp b/libraries/SITL/SIM_BattMonitor_SMBus_Generic.cpp index d6d542e4e1f..d7e322417bb 100644 --- a/libraries/SITL/SIM_BattMonitor_SMBus_Generic.cpp +++ b/libraries/SITL/SIM_BattMonitor_SMBus_Generic.cpp @@ -3,6 +3,10 @@ SITL::SIM_BattMonitor_SMBus_Generic::SIM_BattMonitor_SMBus_Generic() : SIM_BattMonitor_SMBus() { + + const char *manufacturer_name = "sitl_smbus_generic"; + set_block(SMBusBattDevReg::MANUFACTURE_NAME, manufacturer_name); + } void SITL::SIM_BattMonitor_SMBus_Generic::init() diff --git a/libraries/SITL/SIM_BattMonitor_SMBus_Generic.h b/libraries/SITL/SIM_BattMonitor_SMBus_Generic.h index 5260568a15d..4a99458207c 100644 --- a/libraries/SITL/SIM_BattMonitor_SMBus_Generic.h +++ b/libraries/SITL/SIM_BattMonitor_SMBus_Generic.h @@ -30,7 +30,7 @@ class SIM_BattMonitor_SMBus_Generic : public SIM_BattMonitor_SMBus void init() override; void update(const class Aircraft &aircraft) override; - virtual uint8_t cellcount() const = 0; + virtual uint8_t cellcount() const { return 12; } virtual uint8_t connected_cells() const { return 3; } }; diff --git a/libraries/SITL/SIM_BattMonitor_SMBus_Maxell.cpp b/libraries/SITL/SIM_BattMonitor_SMBus_Maxell.cpp index f71579100cc..eaf1c1b19fb 100644 --- a/libraries/SITL/SIM_BattMonitor_SMBus_Maxell.cpp +++ b/libraries/SITL/SIM_BattMonitor_SMBus_Maxell.cpp @@ -3,5 +3,15 @@ SITL::Maxell::Maxell() : SIM_BattMonitor_SMBus_Generic() { + // TO DO set maxell batteries PEC version to V1 + + // Note Maxell batteries do not support PEC and ArduPilot checks for this by + // checking that the manufacturer name matches "Hitachi maxell" + const char *manufacturer_name = "Hitachi maxell"; + set_block(SMBusBattDevReg::MANUFACTURE_NAME, manufacturer_name); + + const char *device_name = "SITL_maxell"; + set_block(SMBusBattDevReg::DEVICE_NAME, device_name); + set_register(SMBusBattGenericDevReg::SERIAL, (uint16_t)37); } diff --git a/libraries/SITL/SIM_BattMonitor_SMBus_Rotoye.cpp b/libraries/SITL/SIM_BattMonitor_SMBus_Rotoye.cpp index 8a5cac07a13..adadfda70ea 100644 --- a/libraries/SITL/SIM_BattMonitor_SMBus_Rotoye.cpp +++ b/libraries/SITL/SIM_BattMonitor_SMBus_Rotoye.cpp @@ -7,6 +7,14 @@ SITL::Rotoye::Rotoye() : add_register("External Temperature", SMBusBattRotoyeDevReg::TEMP_EXT, SITL::I2CRegisters::RegMode::RDONLY); set_register(SMBusBattRotoyeDevReg::SERIAL, (uint16_t)39); + + const char *manufacturer_name = "Rotoye"; + set_block(SMBusBattDevReg::MANUFACTURE_NAME, manufacturer_name); + + const char *device_name = "SITL_BatMon v4.03"; + set_block(SMBusBattDevReg::DEVICE_NAME, device_name); + + set_register(SMBusBattGenericDevReg::SERIAL, (uint16_t) 278); } void SITL::Rotoye::update(const class Aircraft &aircraft) diff --git a/libraries/SITL/SIM_Blimp.cpp b/libraries/SITL/SIM_Blimp.cpp index ea129152b97..73e41d0eae1 100644 --- a/libraries/SITL/SIM_Blimp.cpp +++ b/libraries/SITL/SIM_Blimp.cpp @@ -16,6 +16,8 @@ Blimp simulator class */ +#define ALLOW_DOUBLE_MATH_FUNCTIONS + #include "SIM_Blimp.h" #include diff --git a/libraries/SITL/SIM_Buzzer.cpp b/libraries/SITL/SIM_Buzzer.cpp index 39f0cbd3e41..0cd15450521 100644 --- a/libraries/SITL/SIM_Buzzer.cpp +++ b/libraries/SITL/SIM_Buzzer.cpp @@ -40,6 +40,8 @@ namespace BuzzerSynth { using namespace SITL; +#ifdef WITH_SITL_TONEALARM + // table of user settable parameters const AP_Param::GroupInfo Buzzer::var_info[] = { @@ -60,8 +62,6 @@ const AP_Param::GroupInfo Buzzer::var_info[] = { AP_GROUPEND }; -#ifdef WITH_SITL_TONEALARM - static sf::SoundBuffer xsoundBuffer; static sf::Sound xdemoSound; @@ -126,6 +126,8 @@ void Buzzer::update(const struct sitl_input &input) using namespace SITL; +const AP_Param::GroupInfo Buzzer::var_info[] = { AP_GROUPEND }; + Buzzer::Buzzer() { }; void Buzzer::update(const struct sitl_input &input) {} diff --git a/libraries/SITL/SIM_Buzzer.h b/libraries/SITL/SIM_Buzzer.h index 74c23094720..4153cc18050 100644 --- a/libraries/SITL/SIM_Buzzer.h +++ b/libraries/SITL/SIM_Buzzer.h @@ -40,11 +40,13 @@ class Buzzer { AP_Int8 _enable; // enable buzzer sim AP_Int8 _pin; +#ifdef WITH_SITL_TONEALARM bool was_on; uint32_t on_time; bool prep_done; +#endif }; } diff --git a/libraries/SITL/SIM_EFI_MegaSquirt.h b/libraries/SITL/SIM_EFI_MegaSquirt.h index d32707874df..f957a296c75 100644 --- a/libraries/SITL/SIM_EFI_MegaSquirt.h +++ b/libraries/SITL/SIM_EFI_MegaSquirt.h @@ -44,8 +44,6 @@ class EFI_MegaSquirt : public SerialDevice { private: void send_table(); - uint32_t time_send_ms; - struct PACKED { uint16_t size; uint8_t command; diff --git a/libraries/SITL/SIM_FlightAxis.cpp b/libraries/SITL/SIM_FlightAxis.cpp index 5e34d91fe63..0355b2ede9f 100644 --- a/libraries/SITL/SIM_FlightAxis.cpp +++ b/libraries/SITL/SIM_FlightAxis.cpp @@ -109,7 +109,6 @@ FlightAxis::FlightAxis(const char *frame_str) : Aircraft(frame_str) { use_time_sync = false; - num_motors = 2; rate_hz = 250 / target_speedup; heli_demix = strstr(frame_str, "helidemix") != nullptr; rev4_servos = strstr(frame_str, "rev4") != nullptr; @@ -489,12 +488,12 @@ void FlightAxis::update(const struct sitl_input &input) can't get that from m_airspeed_MPS, so instead we calculate it from wind vector and ground speed */ - Vector3f m_wind_ef(-state.m_windY_MPS,-state.m_windX_MPS,-state.m_windZ_MPS); - Vector3f airspeed_3d_ef = m_wind_ef + velocity_ef; + wind_ef = Vector3f(state.m_windY_MPS,state.m_windX_MPS,state.m_windZ_MPS); + Vector3f airspeed_3d_ef = velocity_ef - wind_ef; Vector3f airspeed3d = dcm.mul_transpose(airspeed_3d_ef); if (last_imu_rotation != ROTATION_NONE) { - airspeed3d = airspeed3d * sitl->ahrs_rotation_inv; + airspeed3d = sitl->ahrs_rotation * airspeed3d; } airspeed_pitot = MAX(airspeed3d.x,0); diff --git a/libraries/SITL/SIM_Frame.cpp b/libraries/SITL/SIM_Frame.cpp index 45b736fb978..ea7c96ba767 100644 --- a/libraries/SITL/SIM_Frame.cpp +++ b/libraries/SITL/SIM_Frame.cpp @@ -23,7 +23,7 @@ #include #include -#include "picojson.h" + using namespace SITL; @@ -322,6 +322,7 @@ float Frame::get_air_density(float alt_amsl) const return air_pressure / (ISA_GAS_CONSTANT * (C_TO_KELVIN(model.refTempC))); } +#if USE_PICOJSON /* load frame specific parameters from a json file if available */ @@ -375,11 +376,19 @@ void Frame::load_frame_params(const char *model_json) exit(1); } - struct { + enum class VarType { + FLOAT, + VECTOR3F, + }; + + struct json_search { const char *label; - float &v; - } vars[] = { -#define FRAME_VAR(s) { #s, model.s } + void *ptr; + VarType t; + }; + + json_search vars[] = { +#define FRAME_VAR(s) { #s, &model.s, VarType::FLOAT } FRAME_VAR(mass), FRAME_VAR(diagonal_size), FRAME_VAR(refSpd), @@ -401,8 +410,9 @@ void Frame::load_frame_params(const char *model_json) FRAME_VAR(slew_max), FRAME_VAR(disc_area), FRAME_VAR(mdrag_coef), + {"moment_inertia", &model.moment_of_inertia, VarType::VECTOR3F}, + FRAME_VAR(num_motors), }; - static_assert(sizeof(model) == sizeof(float)*ARRAY_SIZE(vars), "incorrect model vars"); for (uint8_t i=0; i()) { - AP_HAL::panic("Bad json type for %s: %s", vars[i].label, v.to_str().c_str()); + if (vars[i].t == VarType::FLOAT) { + parse_float(v, vars[i].label, *((float *)vars[i].ptr)); + + } else if (vars[i].t == VarType::VECTOR3F) { + parse_vector3(v, vars[i].label, *(Vector3f *)vars[i].ptr); + + } + } + + json_search per_motor_vars[] = { + {"position", &model.motor_pos, VarType::VECTOR3F}, + {"vector", &model.motor_thrust_vec, VarType::VECTOR3F}, + {"yaw", &model.yaw_factor, VarType::FLOAT}, + }; + char label_name[20]; + for (uint8_t i=0; i()) { + // use default value + continue; + } + if (vars[i].t == VarType::FLOAT) { + parse_float(v, label_name, *(((float *)per_motor_vars[i].ptr) + j)); + + } else if (per_motor_vars[i].t == VarType::VECTOR3F) { + parse_vector3(v, label_name, *(((Vector3f *)per_motor_vars[i].ptr) + j)); + } } - vars[i].v = v.get(); } ::printf("Loaded model params from %s\n", model_json); } +void Frame::parse_float(picojson::value val, const char* label, float ¶m) { + if (!val.is()) { + AP_HAL::panic("Bad json type for %s: %s", label, val.to_str().c_str()); + } + param = val.get(); +} + +void Frame::parse_vector3(picojson::value val, const char* label, Vector3f ¶m) { + if (!val.is() || !val.contains(2) || val.contains(3)) { + AP_HAL::panic("Bad json type for %s: %s", label, val.to_str().c_str()); + } + for (uint8_t j=0; j<3; j++) { + parse_float(val.get(j), label, param[j]); + } +} + +#endif + /* initialise the frame */ +#if AP_SIM_ENABLED void Frame::init(const char *frame_str, Battery *_battery) { model = default_model; battery = _battery; +#if USE_PICOJSON const char *colon = strchr(frame_str, ':'); size_t slen = strlen(frame_str); if (colon != nullptr && slen > 5 && strcmp(&frame_str[slen-5], ".json") == 0) { load_frame_params(colon+1); } +#endif mass = model.mass; const float drag_force = model.mass * GRAVITY_MSS * tanf(radians(model.refAngle)); @@ -446,10 +503,10 @@ void Frame::init(const char *frame_str, Battery *_battery) if (momentum_drag > drag_force) { model.mdrag_coef *= drag_force / momentum_drag; areaCd = 0.0; - ::printf("Suggested EK3_BCOEF_* = 0, EK3_MCOEF = %.3f\n", (momentum_drag / (model.mass * airspeed_bf)) * sqrtf(1.225f / ref_air_density)); + ::printf("Suggested EK3_DRAG_BCOEF_* = 0, EK3_DRAG_MCOEF = %.3f\n", (momentum_drag / (model.mass * airspeed_bf)) * sqrtf(1.225f / ref_air_density)); } else { areaCd = (drag_force - momentum_drag) / (0.5f * ref_air_density * sq(model.refSpd)); - ::printf("Suggested EK3_BCOEF_* = %.3f, EK3_MCOEF = %.3f\n", model.mass / areaCd, (momentum_drag / (model.mass * airspeed_bf)) * sqrtf(1.225f / ref_air_density)); + ::printf("Suggested EK3_DRAG_BCOEF_* = %.3f, EK3_DRAG_MCOEF = %.3f\n", model.mass / areaCd, (momentum_drag / (model.mass * airspeed_bf)) * sqrtf(1.225f / ref_air_density)); } terminal_rotation_rate = model.refRotRate; @@ -458,39 +515,32 @@ void Frame::init(const char *frame_str, Battery *_battery) float hover_power = model.refCurrent * model.refVoltage; float hover_velocity_out = 2 * hover_power / hover_thrust; float effective_disc_area = hover_thrust / (0.5 * ref_air_density * sq(hover_velocity_out)); - velocity_max = hover_velocity_out / sqrtf(model.hoverThrOut); - thrust_max = 0.5 * ref_air_density * effective_disc_area * sq(velocity_max); - effective_prop_area = effective_disc_area / num_motors; + float velocity_max = hover_velocity_out / sqrtf(model.hoverThrOut); + float effective_prop_area = effective_disc_area / num_motors; + float true_prop_area = model.disc_area / num_motors; // power_factor is ratio of power consumed per newton of thrust float power_factor = hover_power / hover_thrust; battery->setup(model.battCapacityAh, model.refBatRes, model.maxVoltage); + if (uint8_t(model.num_motors) != num_motors) { + ::printf("Warning model expected %u motors and got %u\n", uint8_t(model.num_motors), num_motors); + } + for (uint8_t i=0; iget_voltage()); - ::printf("pwm[%u] cmd=%.3f thrust=%.3f hovthst=%.3f\n", - pwm, motors[0].pwm_to_command(pwm), -thrust.z*num_motors, hover_thrust); - } - motors[0].set_slew_max(model.slew_max); + if (is_zero(model.moment_of_inertia.x) || is_zero(model.moment_of_inertia.y) || is_zero(model.moment_of_inertia.z)) { + // if no inertia provided, assume 50% of mass on ring around center + model.moment_of_inertia.x = model.mass * 0.25 * sq(model.diagonal_size*0.5); + model.moment_of_inertia.y = model.moment_of_inertia.x; + model.moment_of_inertia.z = model.mass * 0.5 * sq(model.diagonal_size*0.5); } -#endif // setup reasonable defaults for battery AP_Param::set_default_by_name("SIM_BATT_VOLTAGE", model.maxVoltage); @@ -523,30 +573,33 @@ void Frame::calculate_forces(const Aircraft &aircraft, bool use_drag) { Vector3f thrust; // newtons + Vector3f torque; const float air_density = get_air_density(aircraft.get_location().alt*0.01); + const Vector3f gyro = aircraft.get_gyro(); Vector3f vel_air_bf = aircraft.get_dcm().transposed() * aircraft.get_velocity_air_ef(); float current = 0; for (uint8_t i=0; iget_voltage()); + Vector3f mtorque, mthrust; + motors[i].calculate_forces(input, motor_offset, mtorque, mthrust, vel_air_bf, gyro, air_density, battery->get_voltage(), use_drag); current += motors[i].get_current(); - rot_accel += mraccel; + torque += mtorque; thrust += mthrust; // simulate motor rpm if (!is_zero(AP::sitl()->vibe_motor)) { - rpm[i] = motors[i].get_command() * AP::sitl()->vibe_motor * 60.0f; + rpm[motor_offset+i] = motors[i].get_command() * AP::sitl()->vibe_motor * 60.0f; } } - body_accel = thrust/aircraft.gross_mass(); + // calculate total rotational acceleration + rot_accel.x = torque.x / model.moment_of_inertia.x; + rot_accel.y = torque.y / model.moment_of_inertia.y; + rot_accel.z = torque.z / model.moment_of_inertia.z; if (terminal_rotation_rate > 0) { // rotational air resistance - const Vector3f &gyro = aircraft.get_gyro(); rot_accel.x -= gyro.x * radians(400.0) / terminal_rotation_rate; rot_accel.y -= gyro.y * radians(400.0) / terminal_rotation_rate; rot_accel.z -= gyro.z * radians(400.0) / terminal_rotation_rate; @@ -555,41 +608,25 @@ void Frame::calculate_forces(const Aircraft &aircraft, if (use_drag) { // use the model params to calculate drag Vector3f drag_bf; - drag_bf.x = areaCd * 0.5f * air_density * sq(vel_air_bf.x) + - model.mdrag_coef * fabsf(vel_air_bf.x) * sqrtf(fabsf(thrust.z) * air_density * model.disc_area); - if (is_positive(vel_air_bf.x)) { + drag_bf.x = areaCd * 0.5f * air_density * sq(vel_air_bf.x); + if (is_negative(vel_air_bf.x)) { drag_bf.x = -drag_bf.x; } - drag_bf.y = areaCd * 0.5f * air_density * sq(vel_air_bf.y) + - model.mdrag_coef * fabsf(vel_air_bf.y) * sqrtf(fabsf(thrust.z) * air_density * model.disc_area); - if (is_positive(vel_air_bf.y)) { + drag_bf.y = areaCd * 0.5f * air_density * sq(vel_air_bf.y); + if (is_negative(vel_air_bf.y)) { drag_bf.y = -drag_bf.y; } - // The application of momentum drag to the Z axis is a 'hack' to compensate for incorrect modelling - // of the variation of thust with vel_air_bf.z in SIM_Motor.cpp. If nmot applied, the vehicle will - // climb at an unrealistic rate during operation in STABILIZE. TODO replace prop and motor model in - // the Motor class with one based on DC motor, mometum disc and blade elemnt theory. - drag_bf.z = areaCd * 0.5f * air_density * sq(vel_air_bf.z) + - model.mdrag_coef * fabsf(vel_air_bf.z) * sqrtf(fabsf(thrust.z) * air_density * model.disc_area); - if (is_positive(vel_air_bf.z)) { + drag_bf.z = areaCd * 0.5f * air_density * sq(vel_air_bf.z); + if (is_negative(vel_air_bf.z)) { drag_bf.z = -drag_bf.z; } - body_accel += drag_bf / mass; + thrust -= drag_bf; } - // add some noise - const float gyro_noise = radians(0.1); - const float accel_noise = 0.3; - const float noise_scale = thrust.length() / thrust_max; - rot_accel += Vector3f(aircraft.rand_normal(0, 1), - aircraft.rand_normal(0, 1), - aircraft.rand_normal(0, 1)) * gyro_noise * noise_scale; - body_accel += Vector3f(aircraft.rand_normal(0, 1), - aircraft.rand_normal(0, 1), - aircraft.rand_normal(0, 1)) * accel_noise * noise_scale; + body_accel = thrust/aircraft.gross_mass(); } @@ -607,3 +644,4 @@ void Frame::current_and_voltage(float &voltage, float ¤t) current += motors[i].get_current(); } } +#endif // AP_SIM_ENABLED diff --git a/libraries/SITL/SIM_Frame.h b/libraries/SITL/SIM_Frame.h index e0c11e5816d..156caed26a6 100644 --- a/libraries/SITL/SIM_Frame.h +++ b/libraries/SITL/SIM_Frame.h @@ -21,6 +21,14 @@ #include "SIM_Aircraft.h" #include "SIM_Motor.h" +#ifndef USE_PICOJSON +#define USE_PICOJSON (CONFIG_HAL_BOARD == HAL_BOARD_SITL) +#endif + +#if USE_PICOJSON +#include "picojson.h" +#endif + namespace SITL { /* @@ -39,7 +47,7 @@ class Frame { num_motors(_num_motors), motors(_motors) {} - +#if AP_SIM_ENABLED // find a frame by name static Frame *find_frame(const char *name); @@ -51,7 +59,8 @@ class Frame { const struct sitl_input &input, Vector3f &rot_accel, Vector3f &body_accel, float* rpm, bool use_drag=true); - +#endif // AP_SIM_ENABLED + float terminal_velocity; float terminal_rotation_rate; uint8_t motor_offset; @@ -127,24 +136,43 @@ class Frame { // momentum drag coefficient float mdrag_coef = 0.2; + // if zero value will be estimated from mass + Vector3f moment_of_inertia; + + // if zero will no be used + Vector3f motor_pos[12]; + Vector3f motor_thrust_vec[12]; + float yaw_factor[12] = {0}; + + // number of motors + float num_motors = 4; + } default_model; +protected: +#if USE_PICOJSON + // load frame parameters from a json model file + void load_frame_params(const char *model_json); +#endif + + // get air density in kg/m^3 + float get_air_density(float alt_amsl) const; + struct Model model; +private: // exposed area times coefficient of drag float areaCd; float mass; - float velocity_max; - float thrust_max; - float effective_prop_area; - Battery *battery; float last_param_voltage; +#if AP_SIM_ENABLED + Battery *battery; +#endif - // get air density in kg/m^3 - float get_air_density(float alt_amsl) const; - - // load frame parameters from a json model file - void load_frame_params(const char *model_json); - + // json parsing helpers +#if USE_PICOJSON + void parse_float(picojson::value val, const char* label, float ¶m); + void parse_vector3(picojson::value val, const char* label, Vector3f ¶m); +#endif }; } diff --git a/libraries/SITL/SIM_GPS.cpp b/libraries/SITL/SIM_GPS.cpp index 4a2479e153f..d3713ab56c1 100644 --- a/libraries/SITL/SIM_GPS.cpp +++ b/libraries/SITL/SIM_GPS.cpp @@ -10,6 +10,10 @@ #if HAL_SIM_GPS_ENABLED +#include + +#define ALLOW_DOUBLE_MATH_FUNCTIONS + #include #include #include @@ -994,39 +998,57 @@ uint32_t GPS::CalculateBlockCRC32(uint32_t length, uint8_t *buffer, uint32_t crc } /* - temporary method to use file as GPS data + read file data logged from AP_GPS_DEBUG_LOGGING_ENABLED */ #if AP_SIM_GPS_FILE_ENABLED void GPS::update_file() { - static int fd = -1; - static int fd2 = -1; - int temp_fd; - if (instance == 0) { - if (fd == -1) { - fd = open("/tmp/gps.dat", O_RDONLY|O_CLOEXEC); - } - temp_fd = fd; - } else { - if (fd2 == -1) { - fd2 = open("/tmp/gps2.dat", O_RDONLY|O_CLOEXEC); - } - temp_fd = fd2; - } - - if (temp_fd == -1) { + static int fd[2] = {-1,-1}; + static uint32_t base_time[2]; + const uint16_t lognum = 9; + if (instance > 1) { return; } - char buf[200]; - ssize_t ret = ::read(temp_fd, buf, sizeof(buf)); - if (ret > 0) { - ::printf("wrote gps %u bytes\n", (unsigned)ret); - write_to_autopilot((const char *)buf, ret); + if (fd[instance] == -1) { + char fname[] = "gpsN_NNN.log"; + hal.util->snprintf(fname, 13, "gps%u_%03u.log", instance+1, lognum); + fd[instance] = open(fname, O_RDONLY|O_CLOEXEC); + if (fd[instance] == -1) { + return; + } } - if (ret == 0) { - ::printf("gps rewind\n"); - lseek(temp_fd, 0, SEEK_SET); + const uint32_t magic = 0x7fe53b04; + struct { + uint32_t magic; + uint32_t time_ms; + uint32_t n; + } header; + uint8_t *buf = nullptr; + while (true) { + if (::read(fd[instance], (void *)&header, sizeof(header)) != sizeof(header) || + header.magic != magic) { + goto rewind_file; + } + if (header.time_ms+base_time[instance] > AP_HAL::millis()) { + // not ready for this data yet + ::lseek(fd[instance], -sizeof(header), SEEK_CUR); + return; + } + buf = new uint8_t[header.n]; + if (buf != nullptr && ::read(fd[instance], buf, header.n) == ssize_t(header.n)) { + write_to_autopilot((const char *)buf, header.n); + delete[] buf; + buf = nullptr; + continue; + } + goto rewind_file; } + +rewind_file: + ::printf("GPS[%u] rewind\n", unsigned(instance)); + base_time[instance] = AP_HAL::millis(); + ::lseek(fd[instance], 0, SEEK_SET); + delete[] buf; } #endif // AP_SIM_GPS_FILE_ENABLED diff --git a/libraries/SITL/SIM_GPS.h b/libraries/SITL/SIM_GPS.h index 1244f573389..dd2fa3d0f3e 100644 --- a/libraries/SITL/SIM_GPS.h +++ b/libraries/SITL/SIM_GPS.h @@ -26,7 +26,7 @@ param set SERIAL5_PROTOCOL 5 #include #ifndef HAL_SIM_GPS_ENABLED -#define HAL_SIM_GPS_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL && !defined(HAL_BUILD_AP_PERIPH)) +#define HAL_SIM_GPS_ENABLED (AP_SIM_ENABLED && !defined(HAL_BUILD_AP_PERIPH)) #endif #if HAL_SIM_GPS_ENABLED diff --git a/libraries/SITL/SIM_Gazebo.cpp b/libraries/SITL/SIM_Gazebo.cpp index bf32962b1ba..52c1cc09b30 100644 --- a/libraries/SITL/SIM_Gazebo.cpp +++ b/libraries/SITL/SIM_Gazebo.cpp @@ -23,10 +23,6 @@ #include #include -#include - -extern const AP_HAL::HAL& hal; - namespace SITL { Gazebo::Gazebo(const char *frame_str) : diff --git a/libraries/SITL/SIM_Helicopter.h b/libraries/SITL/SIM_Helicopter.h index a2d757385ea..5845ae27709 100644 --- a/libraries/SITL/SIM_Helicopter.h +++ b/libraries/SITL/SIM_Helicopter.h @@ -62,7 +62,6 @@ class Helicopter : public Aircraft { float hover_throttle = 0.5f; float terminal_velocity = 80; float hover_lean = 3.2f; - float yaw_zero = 0.1f; float rotor_rot_accel = radians(20); float roll_rate_max = radians(1400); float pitch_rate_max = radians(1400); @@ -70,10 +69,8 @@ class Helicopter : public Aircraft { float rsc_setpoint = 0.8f; float izz = 0.2f; float tr_dist = 0.85f; - float tr_accel_max = 50.0f; //rad/s/s float cyclic_scalar = 7.2; // converts swashplate servo ouputs to cyclic blade pitch float thrust_scale; - float tail_thrust_scale; Vector2f _tpp_angle; float torque_scale; float torque_mpog; diff --git a/libraries/SITL/SIM_I2C.cpp b/libraries/SITL/SIM_I2C.cpp index 334c496a477..ac4c1860225 100644 --- a/libraries/SITL/SIM_I2C.cpp +++ b/libraries/SITL/SIM_I2C.cpp @@ -56,6 +56,7 @@ static MaxSonarI2CXL maxsonari2cxl; static MaxSonarI2CXL maxsonari2cxl_2; static Maxell maxell; static Rotoye rotoye; +static SIM_BattMonitor_SMBus_Generic smbus_generic; static Airspeed_DLVR airspeed_dlvr; static TSYS01 tsys01; static MCP9600 mcp9600; @@ -80,8 +81,9 @@ struct i2c_device_at_address { { 1, 0x40, ignored }, // KellerLD { 1, 0x76, ms5525 }, // MS5525: ARSPD_TYPE = 4 { 1, 0x77, tsys01 }, - { 1, 0x0B, rotoye }, // Rotoye: BATTx_MONITOR 19 - { 2, 0x0B, maxell }, // Maxell: BATTx_MONITOR 16 + { 1, 0x0B, rotoye }, // Rotoye: BATTx_MONITOR 19, BATTx_I2C_ADDR 13 + { 2, 0x0B, maxell }, // Maxell: BATTx_MONITOR 16, BATTx_I2C_ADDR 13 + { 3, 0x0B, smbus_generic}, // BATTx_MONITOR 7, BATTx_I2C_ADDR 13 { 2, 0x28, airspeed_dlvr }, // ARSPD_TYPE = 7 5inch H2O sensor { 2, 0x77, ms5611 }, // MS5611: BARO_PROBE_EXT = 2 }; diff --git a/libraries/SITL/SIM_ICEngine.cpp b/libraries/SITL/SIM_ICEngine.cpp index 2978c9542d4..113a569aba1 100644 --- a/libraries/SITL/SIM_ICEngine.cpp +++ b/libraries/SITL/SIM_ICEngine.cpp @@ -30,6 +30,9 @@ float ICEngine::update(const struct sitl_input &input) bool have_choke = choke_servo>=0; bool have_starter = starter_servo>=0; float throttle_demand = (input.servos[throttle_servo]-1000) * 0.001f; + if (throttle_reversed) { + throttle_demand = 1 - throttle_demand; + } state.ignition = have_ignition?input.servos[ignition_servo]>1700:true; state.choke = have_choke?input.servos[choke_servo]>1700:false; diff --git a/libraries/SITL/SIM_ICEngine.h b/libraries/SITL/SIM_ICEngine.h index 10423913e02..bac065a31e4 100644 --- a/libraries/SITL/SIM_ICEngine.h +++ b/libraries/SITL/SIM_ICEngine.h @@ -30,12 +30,13 @@ class ICEngine { const int8_t starter_servo; const float slew_rate; // percent-per-second - ICEngine(uint8_t _throttle, int8_t _choke, int8_t _ignition, int8_t _starter, float _slew_rate) : + ICEngine(uint8_t _throttle, int8_t _choke, int8_t _ignition, int8_t _starter, float _slew_rate, bool _throttle_reversed) : throttle_servo(_throttle), choke_servo(_choke), ignition_servo(_ignition), starter_servo(_starter), - slew_rate(_slew_rate) + slew_rate(_slew_rate), + throttle_reversed(_throttle_reversed) {} // update motor state @@ -54,5 +55,6 @@ class ICEngine { uint8_t value; } state, last_state; bool overheat:1; + bool throttle_reversed; }; } diff --git a/libraries/SITL/SIM_IntelligentEnergy24.cpp b/libraries/SITL/SIM_IntelligentEnergy24.cpp index 2d694d8e831..6776c4f3bd6 100644 --- a/libraries/SITL/SIM_IntelligentEnergy24.cpp +++ b/libraries/SITL/SIM_IntelligentEnergy24.cpp @@ -102,8 +102,8 @@ void IntelligentEnergy24::update_send() int32_t battery_pwr = battery_voltage * amps; // Watts // These are non-physical values - const int32_t pwr_out = battery_pwr*1.4f; - const uint32_t spm_pwr = battery_pwr*0.3f; + const int32_t pwr_out = float_to_int32(battery_pwr*1.4f); + const uint32_t spm_pwr = float_to_uint32(battery_pwr*0.3f); uint32_t state = set_state; if (set_state == -1) { diff --git a/libraries/SITL/SIM_JSBSim.cpp b/libraries/SITL/SIM_JSBSim.cpp index ca1128143d5..0b77e298402 100644 --- a/libraries/SITL/SIM_JSBSim.cpp +++ b/libraries/SITL/SIM_JSBSim.cpp @@ -64,7 +64,6 @@ JSBSim::JSBSim(const char *frame_str) : } control_port = 5505 + instance*10; fdm_port = 5504 + instance*10; - num_motors = 2; printf("JSBSim backend started: control_port=%u fdm_port=%u\n", control_port, fdm_port); diff --git a/libraries/SITL/SIM_JSON.cpp b/libraries/SITL/SIM_JSON.cpp index be64d053ed9..0d37e7529ad 100644 --- a/libraries/SITL/SIM_JSON.cpp +++ b/libraries/SITL/SIM_JSON.cpp @@ -255,7 +255,7 @@ void JSON::recv_fdm(const struct sitl_input &input) const uint32_t received_bitmask = parse_sensors((const char *)(p1+1)); if (received_bitmask == 0) { - // did not receve one of the mandatory fields + // did not receive one of the mandatory fields printf("Did not contain all mandatory fields\n"); return; } diff --git a/libraries/SITL/SIM_JSON_Master.cpp b/libraries/SITL/SIM_JSON_Master.cpp index e96ce1a1bc9..3eb6f622a39 100644 --- a/libraries/SITL/SIM_JSON_Master.cpp +++ b/libraries/SITL/SIM_JSON_Master.cpp @@ -13,7 +13,7 @@ along with this program. If not, see . */ /* - Send and receve JSON backend data to alow a second AP instance to ride along + Send and receive JSON backend data to alow a second AP instance to ride along */ #include "SIM_JSON_Master.h" @@ -159,7 +159,7 @@ void JSON_Master::receive(struct sitl_input &input) if (list->instance == master_instance) { // Use the servo outs from this instance - memcpy(input.servos,buffer.pwm,sizeof(input.servos)); + memcpy(input.servos,buffer.pwm,sizeof(buffer.pwm)); } } } diff --git a/libraries/SITL/SIM_JSON_Master.h b/libraries/SITL/SIM_JSON_Master.h index 36c4d827b2e..9a568f6ed14 100644 --- a/libraries/SITL/SIM_JSON_Master.h +++ b/libraries/SITL/SIM_JSON_Master.h @@ -13,7 +13,7 @@ along with this program. If not, see . */ /* - Send and receve JSON backend data to alow a second AP instance to ride along + Send and receive JSON backend data to alow a second AP instance to ride along */ #pragma once diff --git a/libraries/SITL/SIM_MS5525.cpp b/libraries/SITL/SIM_MS5525.cpp index 2dd4cb46fb7..24e2000d52c 100644 --- a/libraries/SITL/SIM_MS5525.cpp +++ b/libraries/SITL/SIM_MS5525.cpp @@ -73,5 +73,6 @@ void MS5525::get_pressure_temperature_readings(float &P_Pa, float &Temp_C) // To Do: Add a sensor board temperature offset parameter Temp_C = (KELVIN_TO_C(SSL_AIR_TEMPERATURE * theta)) + 25.0; - P_Pa = AP::sitl()->state.airspeed_raw_pressure[0]; + const uint8_t instance = 0; // TODO: work out which sensor this is + P_Pa = AP::sitl()->state.airspeed_raw_pressure[instance] + AP::sitl()->airspeed[instance].offset; } diff --git a/libraries/SITL/SIM_MS5611.cpp b/libraries/SITL/SIM_MS5611.cpp index a1957df17da..d269272598b 100644 --- a/libraries/SITL/SIM_MS5611.cpp +++ b/libraries/SITL/SIM_MS5611.cpp @@ -1,3 +1,5 @@ +#define ALLOW_DOUBLE_MATH_FUNCTIONS + #include "SIM_MS5611.h" #include diff --git a/libraries/SITL/SIM_MS5XXX.h b/libraries/SITL/SIM_MS5XXX.h index 345722b2ba1..532fcdc1190 100644 --- a/libraries/SITL/SIM_MS5XXX.h +++ b/libraries/SITL/SIM_MS5XXX.h @@ -23,10 +23,6 @@ class MS5XXX : public I2CDevice // float pressure; // float temperature; - // time we last updated the measurements (simulated internal - // workings of sensor) - uint32_t last_update_ms; - void reset(); enum class Command : uint8_t { diff --git a/libraries/SITL/SIM_Motor.cpp b/libraries/SITL/SIM_Motor.cpp index fd025ad5348..e145d0d8239 100644 --- a/libraries/SITL/SIM_Motor.cpp +++ b/libraries/SITL/SIM_Motor.cpp @@ -24,16 +24,14 @@ using namespace SITL; // calculate rotational accel and thrust for a motor void Motor::calculate_forces(const struct sitl_input &input, uint8_t motor_offset, - Vector3f &rot_accel, + Vector3f &torque, Vector3f &thrust, const Vector3f &velocity_air_bf, + const Vector3f &gyro, float air_density, - float velocity_max, - float effective_prop_area, - float voltage) + float voltage, + bool use_drag) { - // fudge factors - const float yaw_scale = radians(40); const float pwm = input.servos[motor_offset+servo]; float command = pwm_to_command(pwm); @@ -41,7 +39,7 @@ void Motor::calculate_forces(const struct sitl_input &input, if (voltage_scale < 0.1) { // battery is dead - rot_accel.zero(); + torque.zero(); thrust.zero(); current = 0; return; @@ -57,21 +55,24 @@ void Motor::calculate_forces(const struct sitl_input &input, last_calc_us = now_us; last_command = command; - // the yaw torque of the motor - Vector3f rotor_torque(0, 0, yaw_factor * command * yaw_scale * voltage_scale); + // velocity of motor through air + Vector3f motor_vel = velocity_air_bf; + + // add velocity of motor about center due to vehicle rotation + motor_vel += -(position % gyro); - // calculate velocity into prop, clipping at zero, assumes zero roll/pitch - float velocity_in = MAX(0, -velocity_air_bf.z); + // calculate velocity into prop, clipping at zero + float velocity_in = MAX(0, -motor_vel.projected(thrust_vector).z); // get thrust for untilted motor - float motor_thrust = calc_thrust(command, air_density, effective_prop_area, velocity_in, velocity_max * voltage_scale); + float motor_thrust = calc_thrust(command, air_density, velocity_in, voltage_scale); - // thrust in NED - thrust = {0, 0, -motor_thrust}; + // the yaw torque of the motor + const float yaw_scale = 0.05 * diagonal_size * motor_thrust; + Vector3f rotor_torque = thrust_vector * yaw_factor * command * yaw_scale * -1.0; - // define the arm position relative to center of mass - Vector3f arm(cosf(radians(angle)), sinf(radians(angle)), 0); - arm *= diagonal_size; + // thrust in bodyframe NED + thrust = thrust_vector * motor_thrust; // work out roll and pitch of motor relative to it pointing straight up float roll = 0, pitch = 0; @@ -98,7 +99,7 @@ void Motor::calculate_forces(const struct sitl_input &input, last_change_usec = now; // calculate torque in newton-meters - Vector3f torque = (arm % thrust) + rotor_torque; + torque = (position % thrust) + rotor_torque; // possibly rotate the thrust vector and the rotor torque if (!is_zero(roll) || !is_zero(pitch)) { @@ -108,10 +109,20 @@ void Motor::calculate_forces(const struct sitl_input &input, torque = rotation * torque; } - // calculate total rotational acceleration - rot_accel.x = torque.x / moment_of_inertia.x; - rot_accel.y = torque.y / moment_of_inertia.y; - rot_accel.z = torque.z / moment_of_inertia.z; + if (use_drag) { + // calculate momentum drag per motor + const float momentum_drag_factor = momentum_drag_coefficient * sqrtf(air_density * true_prop_area); + Vector3f momentum_drag; + momentum_drag.x = momentum_drag_factor * motor_vel.x * (sqrtf(fabsf(thrust.y)) + sqrtf(fabsf(thrust.z))); + momentum_drag.y = momentum_drag_factor * motor_vel.y * (sqrtf(fabsf(thrust.x)) + sqrtf(fabsf(thrust.z))); + // The application of momentum drag to the Z axis is a 'hack' to compensate for incorrect modelling + // of the variation of thust with inflow velocity. If not applied, the vehicle will + // climb at an unrealistic rate during operation in STABILIZE. TODO replace prop and motor model in + // with one based on DC motor, momentum disc and blade element theory. + momentum_drag.z = momentum_drag_factor * motor_vel.z * (sqrtf(fabsf(thrust.x)) + sqrtf(fabsf(thrust.y)) + sqrtf(fabsf(thrust.z))); + + thrust -= momentum_drag; + } // calculate current float power = power_factor * fabsf(motor_thrust); @@ -153,7 +164,9 @@ float Motor::get_current(void) const // setup PWM ranges for this motor void Motor::setup_params(uint16_t _pwm_min, uint16_t _pwm_max, float _spin_min, float _spin_max, float _expo, float _slew_max, - float _vehicle_mass, float _diagonal_size, float _power_factor, float _voltage_max) + float _diagonal_size, float _power_factor, float _voltage_max, float _effective_prop_area, + float _velocity_max, Vector3f _position, Vector3f _thrust_vector, float _yaw_factor, + float _true_prop_area, float _momentum_drag_coefficient) { mot_pwm_min = _pwm_min; mot_pwm_max = _pwm_max; @@ -161,15 +174,28 @@ void Motor::setup_params(uint16_t _pwm_min, uint16_t _pwm_max, float _spin_min, mot_spin_max = _spin_max; mot_expo = _expo; slew_max = _slew_max; - vehicle_mass = _vehicle_mass; - diagonal_size = _diagonal_size; power_factor = _power_factor; voltage_max = _voltage_max; + effective_prop_area = _effective_prop_area; + max_outflow_velocity = _velocity_max; + true_prop_area = _true_prop_area; + momentum_drag_coefficient = _momentum_drag_coefficient; + diagonal_size = _diagonal_size; + + if (!_position.is_zero()) { + position = _position; + } else { + position.x = cosf(radians(angle)) * _diagonal_size; + position.y = sinf(radians(angle)) * _diagonal_size; + position.z = 0; + } - // assume 50% of mass on ring around center - moment_of_inertia.x = vehicle_mass * 0.25 * sq(diagonal_size*0.5); - moment_of_inertia.y = moment_of_inertia.x; - moment_of_inertia.z = vehicle_mass * 0.5 * sq(diagonal_size*0.5); + if (!_thrust_vector.is_zero()) { + thrust_vector = _thrust_vector; + } + if (!is_zero(_yaw_factor)) { + yaw_factor = _yaw_factor; + } } /* @@ -186,14 +212,14 @@ float Motor::pwm_to_command(float pwm) const /* calculate thrust given a command value */ -float Motor::calc_thrust(float command, float air_density, float effective_prop_area, float velocity_in, float velocity_max) const +float Motor::calc_thrust(float command, float air_density, float velocity_in, float voltage_scale) const { - float velocity_out = velocity_max * sqrtf((1-mot_expo)*command + mot_expo*sq(command)); + float velocity_out = voltage_scale * max_outflow_velocity * sqrtf((1-mot_expo)*command + mot_expo*sq(command)); float ret = 0.5 * air_density * effective_prop_area * (sq(velocity_out) - sq(velocity_in)); #if 0 if (command > 0) { ::printf("air_density=%f effective_prop_area=%f velocity_in=%f velocity_max=%f\n", - air_density, effective_prop_area, velocity_in, velocity_max); + air_density, effective_prop_area, velocity_in, voltage_scale * max_outflow_velocity); ::printf("calc_thrust %.3f %.3f\n", command, ret); } #endif diff --git a/libraries/SITL/SIM_Motor.h b/libraries/SITL/SIM_Motor.h index abbaf0c2e61..39745b6843a 100644 --- a/libraries/SITL/SIM_Motor.h +++ b/libraries/SITL/SIM_Motor.h @@ -18,7 +18,8 @@ #pragma once -#include "SIM_Aircraft.h" +#include +#include namespace SITL { @@ -49,7 +50,15 @@ class Motor { angle(_angle), // angle in degrees from front yaw_factor(_yaw_factor), // positive is clockwise display_order(_display_order) // order for clockwise display - {} + { + position.x = cosf(radians(angle)); + position.y = sinf(radians(angle)); + position.z = 0; + + thrust_vector.x = 0; + thrust_vector.y = 0; + thrust_vector.z = -1; + } /* alternative constructor for tiltable motors @@ -67,17 +76,25 @@ class Motor { pitch_servo(_pitch_servo), pitch_min(_pitch_min), pitch_max(_pitch_max) - {} + { + position.x = cosf(radians(angle)); + position.y = sinf(radians(angle)); + position.z = 0; + + thrust_vector.x = 0; + thrust_vector.y = 0; + thrust_vector.z = -1; + } void calculate_forces(const struct sitl_input &input, uint8_t motor_offset, - Vector3f &rot_accel, // rad/sec - Vector3f &body_thrust, // Z is down + Vector3f &torque, // Newton meters + Vector3f &thrust, // Z is down, Newtons const Vector3f &velocity_air_bf, + const Vector3f &gyro, // rad/sec float air_density, - float velocity_max, - float effective_prop_area, - float voltage); + float voltage, + bool use_drag); uint16_t update_servo(uint16_t demand, uint64_t time_usec, float &last_value) const; @@ -89,7 +106,9 @@ class Motor { // setup motor key parameters void setup_params(uint16_t _pwm_min, uint16_t _pwm_max, float _spin_min, float _spin_max, float _expo, float _slew_max, - float _vehicle_mass, float _diagonal_size, float _power_factor, float _voltage_max); + float _diagonal_size, float _power_factor, float _voltage_max, float _effective_prop_area, + float _velocity_max, Vector3f _position, Vector3f _thrust_vector, float _yaw_factor, + float _true_prop_area, float _momentum_drag_coefficient); // override slew limit void set_slew_max(float _slew_max) { @@ -101,7 +120,7 @@ class Motor { } // calculate thrust of motor - float calc_thrust(float command, float air_density, float effective_prop_area, float velocity_in, float velocity_max) const; + float calc_thrust(float command, float air_density, float velocity_in, float voltage_scale) const; private: float mot_pwm_min; @@ -110,15 +129,20 @@ class Motor { float mot_spin_max; float mot_expo; float slew_max; - float vehicle_mass; - float diagonal_size; float current; float power_factor; float voltage_max; - Vector3f moment_of_inertia; + float effective_prop_area; + float max_outflow_velocity; + float true_prop_area; + float momentum_drag_coefficient; + float diagonal_size; float last_command; uint64_t last_calc_us; + + Vector3f position; + Vector3f thrust_vector; }; } diff --git a/libraries/SITL/SIM_Multicopter.cpp b/libraries/SITL/SIM_Multicopter.cpp index e271849587e..a834cc6f856 100644 --- a/libraries/SITL/SIM_Multicopter.cpp +++ b/libraries/SITL/SIM_Multicopter.cpp @@ -36,7 +36,6 @@ MultiCopter::MultiCopter(const char *frame_str) : mass = frame->get_mass(); frame_height = 0.1; - num_motors = frame->num_motors; ground_behavior = GROUND_BEHAVIOR_NO_MOVEMENT; lock_step_scheduled = true; } @@ -44,6 +43,7 @@ MultiCopter::MultiCopter(const char *frame_str) : // calculate rotational and linear accelerations void MultiCopter::calculate_forces(const struct sitl_input &input, Vector3f &rot_accel, Vector3f &body_accel) { + motor_mask |= ((1U<num_motors)-1U) << frame->motor_offset; frame->calculate_forces(*this, input, rot_accel, body_accel, rpm); add_shove_forces(rot_accel, body_accel); diff --git a/libraries/SITL/SIM_Multicopter.h b/libraries/SITL/SIM_Multicopter.h index bac5b6a80ad..fa9a869358a 100644 --- a/libraries/SITL/SIM_Multicopter.h +++ b/libraries/SITL/SIM_Multicopter.h @@ -34,11 +34,6 @@ class MultiCopter : public Aircraft { /* update model by one time step */ void update(const struct sitl_input &input) override; - // get motor offset for model - virtual uint16_t get_motors_offset() const override { - return frame->motor_offset; - } - /* static object creator */ static Aircraft *create(const char *frame_str) { return new MultiCopter(frame_str); diff --git a/libraries/SITL/SIM_PS_LightWare_SF45B.h b/libraries/SITL/SIM_PS_LightWare_SF45B.h index 99a5ab9ceba..68ec7961e35 100644 --- a/libraries/SITL/SIM_PS_LightWare_SF45B.h +++ b/libraries/SITL/SIM_PS_LightWare_SF45B.h @@ -18,7 +18,7 @@ ./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:sf45b --speedup=1 -l 51.8752066,14.6487840,54.15,0 param set SERIAL5_PROTOCOL 11 # proximity -param set PRX_TYPE 8 # s45b +param set PRX1_TYPE 8 # s45b reboot arm throttle diff --git a/libraries/SITL/SIM_PS_RPLidarA2.h b/libraries/SITL/SIM_PS_RPLidarA2.h index 2c1912b8eba..558a33590a9 100644 --- a/libraries/SITL/SIM_PS_RPLidarA2.h +++ b/libraries/SITL/SIM_PS_RPLidarA2.h @@ -18,7 +18,7 @@ ./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:rplidara2 --speedup=1 -l 51.8752066,14.6487840,54.15,0 --map param set SERIAL5_PROTOCOL 11 -param set PRX_TYPE 5 +param set PRX1_TYPE 5 reboot arm throttle diff --git a/libraries/SITL/SIM_PS_TeraRangerTower.h b/libraries/SITL/SIM_PS_TeraRangerTower.h index b124a5ebcb4..8d4dc7c9b51 100644 --- a/libraries/SITL/SIM_PS_TeraRangerTower.h +++ b/libraries/SITL/SIM_PS_TeraRangerTower.h @@ -18,7 +18,7 @@ ./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:terarangertower --speedup=1 -l 51.8752066,14.6487840,54.15,0 param set SERIAL5_PROTOCOL 11 -param set PRX_TYPE 3 # terarangertower +param set PRX1_TYPE 3 # terarangertower reboot arm throttle diff --git a/libraries/SITL/SIM_Plane.cpp b/libraries/SITL/SIM_Plane.cpp index c529f33814d..9ee8e073b9f 100644 --- a/libraries/SITL/SIM_Plane.cpp +++ b/libraries/SITL/SIM_Plane.cpp @@ -17,6 +17,8 @@ just enough to be able to debug control logic for new frame types */ +#define ALLOW_DOUBLE_MATH_FUNCTIONS + #include "SIM_Plane.h" #include @@ -34,7 +36,6 @@ Plane::Plane(const char *frame_str) : */ thrust_scale = (mass * GRAVITY_MSS) / hover_throttle; frame_height = 0.1f; - num_motors = 1; ground_behavior = GROUND_BEHAVIOR_FWD_ONLY; lock_step_scheduled = true; @@ -352,7 +353,8 @@ void Plane::calculate_forces(const struct sitl_input &input, Vector3f &rot_accel } // simulate engine RPM - rpm[0] = thrust * 7000; + motor_mask |= (1U<<2); + rpm[2] = thrust * 7000; // scale thrust to newtons thrust *= thrust_scale; diff --git a/libraries/SITL/SIM_Plane.h b/libraries/SITL/SIM_Plane.h index bfd0862e8e6..37d42e20e69 100644 --- a/libraries/SITL/SIM_Plane.h +++ b/libraries/SITL/SIM_Plane.h @@ -115,7 +115,8 @@ class Plane : public Aircraft { choke_servo, ignition_servo, starter_servo, - slewrate + slewrate, + true }; float liftCoeff(float alpha) const; diff --git a/libraries/SITL/SIM_Precland.cpp b/libraries/SITL/SIM_Precland.cpp index bdec2865f25..8406d1696c2 100644 --- a/libraries/SITL/SIM_Precland.cpp +++ b/libraries/SITL/SIM_Precland.cpp @@ -32,31 +32,31 @@ const AP_Param::GroupInfo SIM_Precland::var_info[] = { AP_GROUPINFO("ENABLE", 0, SIM_Precland, _enable, 0), // @Param: LAT - // @DisplayName: Precland device origin's latitude - // @Description: Precland device origin's latitude + // @DisplayName: Precland device center's latitude + // @Description: Precland device center's latitude // @Units: deg // @Increment: 0.000001 // @Range: -90 90 // @User: Advanced - AP_GROUPINFO("LAT", 1, SIM_Precland, _origin_lat, 0), + AP_GROUPINFO("LAT", 1, SIM_Precland, _device_lat, 0), // @Param: LON - // @DisplayName: Precland device origin's longitude - // @Description: Precland device origin's longitude + // @DisplayName: Precland device center's longitude + // @Description: Precland device center's longitude // @Units: deg // @Increment: 0.000001 // @Range: -180 180 // @User: Advanced - AP_GROUPINFO("LON", 2, SIM_Precland, _origin_lon, 0), + AP_GROUPINFO("LON", 2, SIM_Precland, _device_lon, 0), // @Param: HEIGHT - // @DisplayName: Precland device origin's height above sealevel - // @Description: Precland device origin's height above sealevel assume a 2x2m square as station base + // @DisplayName: Precland device center's height above sealevel + // @Description: Precland device center's height above sealevel assume a 2x2m square as station base // @Units: cm // @Increment: 1 // @Range: 0 10000 // @User: Advanced - AP_GROUPINFO("HEIGHT", 3, SIM_Precland, _origin_height, 0), + AP_GROUPINFO("HEIGHT", 3, SIM_Precland, _device_height, 0), // @Param: YAW // @DisplayName: Precland device systems rotation from north @@ -98,6 +98,20 @@ const AP_Param::GroupInfo SIM_Precland::var_info[] = { // @User: Advanced AP_GROUPINFO("DIST_LMT", 8, SIM_Precland, _dist_limit, 10), + // @Param: ORIENT + // @DisplayName: Precland device orientation + // @Description: Precland device orientation vector + // @Values: 0:Front, 4:Back, 24:Up + // @User: Advanced + AP_GROUPINFO("ORIENT", 9, SIM_Precland, _orient, ROTATION_PITCH_90), + + // @Param: OPTIONS + // @DisplayName: SIM_Precland extra options + // @Description: SIM_Precland extra options + // @Bitmask: 0: Enable target distance + // @User: Advanced + AP_GROUPINFO("OPTIONS", 10, SIM_Precland, _options, 0), + AP_GROUPEND }; @@ -112,24 +126,40 @@ void SIM_Precland::update(const Location &loc, const Vector3d &position) return; } - const float distance_z = -position.z; - const float origin_height_m = _origin_height * 0.01f; - if (distance_z > _alt_limit + origin_height_m) { + const Location device_center(static_cast(_device_lat * 1.0e7f), + static_cast(_device_lon * 1.0e7f), + static_cast(_device_height), + Location::AltFrame::ABOVE_HOME); + Vector2f centerf; + if (!device_center.get_vector_xy_from_origin_NE(centerf)) { _healthy = false; return; } - - const Location origin_center(static_cast(_origin_lat * 1.0e7f), - static_cast(_origin_lon * 1.0e7f), - static_cast(_origin_height), - Location::AltFrame::ABOVE_HOME); - Vector2f center; - if (!origin_center.get_vector_xy_from_origin_NE(center)) { + centerf = centerf * 0.01f; // cm to m + Vector3d center(centerf.x, centerf.y, -_device_height); // convert to make the further vector operations easy + + // axis of cone or cylinder inside which the vehicle receives signals from simulated precland device + Vector3d axis{1, 0, 0}; + axis.rotate((Rotation)_orient.get()); // unit vector in direction of axis of cone or cylinder + Vector3d position_wrt_device = position - center; // position of vehicle with respect to preland device center + + // longitudinal distance of vehicle from the precland device + // this is the distance of vehicle from the plane which is passing through precland device center and perpendicular to axis of cone/cylinder + // this plane is the ground plane when the axis has PITCH_90 rotation + Vector3d projection_on_axis = position_wrt_device.projected(axis); + const float longitudinal_dist = projection_on_axis.length(); + + // lateral distance of vehicle from the precland device + // this is the perpendicular distance of vehicle from the axis of cone/cylinder + const float lateral_distance = safe_sqrt(MAX(0, position_wrt_device.length_squared() - longitudinal_dist*longitudinal_dist)); + + // sign of projection's dot product with axis tells if vehicle is in front of beacon + // return false if vehicle if vehicle is longitudinally too far away from precland device + // for PITCH_90 orientation, longitudinal distance = alt of vehicle - device_height (in m) + if (projection_on_axis.dot(axis) <= 0 || longitudinal_dist > _alt_limit) { _healthy = false; return; } - center = center * 0.01f; // cm to m - _over_precland_base = origin_center.get_distance(loc) <= 2.0f; const uint32_t now = AP_HAL::millis(); if (now - _last_update_ms < 1000.0f * (1.0f / _rate)) { @@ -139,15 +169,17 @@ void SIM_Precland::update(const Location &loc, const Vector3d &position) switch (_type) { case PRECLAND_TYPE_CONE: { - const float in_radius = distance_z * _dist_limit / (_alt_limit + origin_height_m); - if (norm(position.x - center.x, position.y - center.y) > in_radius) { + // lateral_limit is the limit of how far the vehicle can laterally be from precland_device + // in case of cone, this limit increases gradually as the vehicle moves longitudinally far away from precland device + const float lateral_limit = longitudinal_dist * _dist_limit / _alt_limit; + if (lateral_distance > lateral_limit) { _healthy = false; return; } break; } case PRECLAND_TYPE_SPHERE: { - if (norm(position.x - center.x, position.y - center.y, distance_z - _origin_height) > (_alt_limit + origin_height_m)) { + if (position_wrt_device.length() > _dist_limit) { _healthy = false; return; } @@ -155,21 +187,21 @@ void SIM_Precland::update(const Location &loc, const Vector3d &position) } default: case PRECLAND_TYPE_CYLINDER: { - if (norm(position.x - center.x, position.y - center.y) > _dist_limit) { + if (lateral_distance > _dist_limit) { _healthy = false; return; } break; } } - _target_pos = position - Vector3d(center.x, center.y, origin_height_m); + _target_pos = position_wrt_device; _healthy = true; } void SIM_Precland::set_default_location(float lat, float lon, int16_t yaw) { - if (is_zero(_origin_lat) && is_zero(_origin_lon)) { - _origin_lat = lat; - _origin_lon = lon; - _orient_yaw = yaw; + if (is_zero(_device_lat) && is_zero(_device_lon)) { + _device_lat.set(lat); + _device_lon.set(lon); + _orient_yaw.set(yaw); } } diff --git a/libraries/SITL/SIM_Precland.h b/libraries/SITL/SIM_Precland.h index 12ebd609eea..f779867e6f4 100644 --- a/libraries/SITL/SIM_Precland.h +++ b/libraries/SITL/SIM_Precland.h @@ -41,15 +41,22 @@ class SIM_Precland { void set_default_location(float lat, float lon, int16_t yaw); static const struct AP_Param::GroupInfo var_info[]; + // enum for SIM_PLD_OPTIONS parameter + enum class Option : uint8_t { + ENABLE_TARGET_DISTANCE = (1U << 0), + }; + AP_Int8 _enable; - AP_Float _origin_lat; - AP_Float _origin_lon; - AP_Float _origin_height; + AP_Float _device_lat; + AP_Float _device_lon; + AP_Float _device_height; AP_Int16 _orient_yaw; AP_Int8 _type; AP_Int32 _rate; AP_Float _alt_limit; AP_Float _dist_limit; + AP_Int8 _orient; + AP_Enum